36 #include <rclcpp/logger.hpp>
37 #include <rclcpp/logging.hpp>
46 BulletCastBVHManagerPtr manager = std::make_shared<BulletCastBVHManager>();
48 for (
const std::pair<const std::string, collision_detection_bullet::CollisionObjectWrapperPtr>& cow :
link2cow_)
50 CollisionObjectWrapperPtr new_cow = cow.second->clone();
52 assert(new_cow->getCollisionShape());
53 assert(new_cow->getCollisionShape()->getShapeType() != CUSTOM_CONVEX_SHAPE_TYPE);
55 new_cow->setWorldTransform(cow.second->getWorldTransform());
57 manager->addCollisionObject(new_cow);
60 manager->setActiveCollisionObjects(
active_);
67 const Eigen::Isometry3d& pose2)
74 CollisionObjectWrapperPtr& cow = it->second;
75 assert(cow->m_collisionFilterGroup == btBroadphaseProxy::KinematicFilter);
80 cow->setWorldTransform(tf1);
86 if (btBroadphaseProxy::isConvex(cow->getCollisionShape()->getShapeType()))
88 static_cast<CastHullShape*
>(cow->getCollisionShape())->updateCastTransform(tf1.inverseTimes(tf2));
90 else if (btBroadphaseProxy::isCompound(cow->getCollisionShape()->getShapeType()))
92 btCompoundShape* compound =
static_cast<btCompoundShape*
>(cow->getCollisionShape());
94 for (
int i = 0; i < compound->getNumChildShapes(); ++i)
96 if (btBroadphaseProxy::isConvex(compound->getChildShape(i)->getShapeType()))
98 const btTransform& local_tf = compound->getChildTransform(i);
100 btTransform delta_tf = (tf1 * local_tf).inverseTimes(tf2 * local_tf);
101 static_cast<CastHullShape*
>(compound->getChildShape(i))->updateCastTransform(delta_tf);
102 compound->updateChildTransform(i, local_tf,
false);
104 else if (btBroadphaseProxy::isCompound(compound->getChildShape(i)->getShapeType()))
106 btCompoundShape* second_compound =
static_cast<btCompoundShape*
>(compound->getChildShape(i));
108 for (
int j = 0; j < second_compound->getNumChildShapes(); ++j)
110 assert(!btBroadphaseProxy::isCompound(second_compound->getChildShape(j)->getShapeType()));
111 const btTransform& local_tf = second_compound->getChildTransform(j);
113 btTransform delta_tf = (tf1 * local_tf).inverseTimes(tf2 * local_tf);
114 static_cast<CastHullShape*
>(second_compound->getChildShape(j))->updateCastTransform(delta_tf);
115 second_compound->updateChildTransform(j, local_tf,
false);
117 second_compound->recalculateLocalAabb();
120 compound->recalculateLocalAabb();
124 RCLCPP_ERROR_STREAM(
getLogger(),
"I can only continuous collision check convex shapes and "
125 "compound shapes made of convex shapes");
126 throw std::runtime_error(
127 "I can only continuous collision check convex shapes and compound shapes made of convex shapes");
142 btOverlappingPairCache* pair_cache =
broadphase_->getOverlappingPairCache();
144 RCLCPP_DEBUG_STREAM(
getLogger(),
"Number overlapping candidates " << pair_cache->getNumOverlappingPairs());
148 pair_cache->processAllOverlappingPairs(&collision_callback,
dispatcher_.get());
153 std::string
name = cow->getName();
154 if (cow->m_collisionFilterGroup == btBroadphaseProxy::KinematicFilter)
164 btVector3 aabb_min, aabb_max;
167 int type =
link2cow_[
name]->getCollisionShape()->getShapeType();
Definition of a structure for the allowed collision matrix. All elements in the collision world are r...
std::vector< std::string > active_
A list of the active collision links.
std::unique_ptr< btBroadphaseInterface > broadphase_
The bullet broadphase interface.
double contact_distance_
The contact distance threshold.
std::map< std::string, CollisionObjectWrapperPtr > link2cow_
A map of collision objects being managed.
btDispatcherInfo dispatch_info_
The bullet collision dispatcher configuration information.
std::unique_ptr< btCollisionDispatcher > dispatcher_
The bullet collision dispatcher used for getting object to object collision algorithm.
void setCastCollisionObjectsTransform(const std::string &name, const Eigen::Isometry3d &pose1, const Eigen::Isometry3d &pose2)
Set a single cast (moving) collision object's transforms.
void contactTest(collision_detection::CollisionResult &collisions, const collision_detection::CollisionRequest &req, const collision_detection::AllowedCollisionMatrix *acm, bool self) override
Perform a contact test for all objects.
BulletCastBVHManagerPtr clone() const
Clone the manager.
void addCollisionObject(const CollisionObjectWrapperPtr &cow) override
Add a tesseract collision object to the manager.
A callback function that is called as part of the broadphase collision checking.
btVector3 convertEigenToBt(const Eigen::Vector3d &v)
Converts eigen vector to bullet vector.
rclcpp::Logger getLogger()
CollisionObjectWrapperPtr makeCastCollisionObject(const CollisionObjectWrapperPtr &cow)
void updateBroadphaseAABB(const CollisionObjectWrapperPtr &cow, const std::unique_ptr< btBroadphaseInterface > &broadphase, const std::unique_ptr< btCollisionDispatcher > &dispatcher)
Update the Broadphase AABB for the input collision object.
Representation of a collision checking request.
Representation of a collision checking result.
Casted collision shape used for checking if an object is collision free between two discrete poses.