42 #ifndef TESSERACT_COLLISION_FCL_UTILS_H
43 #define TESSERACT_COLLISION_FCL_UTILS_H
51 #include <console_bridge/console.h>
80 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
82 using Ptr = std::shared_ptr<CollisionObjectWrapper>;
83 using ConstPtr = std::shared_ptr<const CollisionObjectWrapper>;
106 [](
const Eigen::Isometry3d& t1,
const Eigen::Isometry3d& t2) { return t1.isApprox(t2); });
118 co->setTransform(pose *
shape_poses_[
static_cast<std::size_t
>(co->getShapeIndex())]);
136 std::shared_ptr<CollisionObjectWrapper>
clone()
const
138 auto clone_cow = std::make_shared<CollisionObjectWrapper>();
139 clone_cow->name_ =
name_;
149 assert(std::dynamic_pointer_cast<FCLCollisionObjectWrapper>(co) !=
nullptr);
151 std::make_shared<FCLCollisionObjectWrapper>(*std::static_pointer_cast<FCLCollisionObjectWrapper>(co));
152 collObj->setUserData(clone_cow.get());
153 collObj->setTransform(co->getTransform());
154 collObj->updateAABB();
155 clone_cow->collision_objects_.push_back(collObj);
156 clone_cow->collision_objects_raw_.push_back(collObj.get());
202 if (shapes.empty() || shape_poses.empty() || (shapes.size() != shape_poses.size()))
204 CONSOLE_BRIDGE_logDebug(
"ignoring link %s",
name.c_str());
208 auto new_cow = std::make_shared<COW>(
name, type_id, shapes, shape_poses);
210 new_cow->m_enabled = enabled;
211 CONSOLE_BRIDGE_logDebug(
"Created collision object for link %s", new_cow->getName().c_str());
224 const std::unique_ptr<fcl::BroadPhaseCollisionManagerd>& static_manager,
225 const std::unique_ptr<fcl::BroadPhaseCollisionManagerd>& dynamic_manager)
233 std::vector<CollisionObjectPtr>& objects = cow->getCollisionObjects();
235 for (
auto& co : objects)
236 dynamic_manager->unregisterObject(co.get());
238 for (
auto& co : objects)
239 static_manager->registerObject(co.get());
247 std::vector<CollisionObjectPtr>& objects = cow->getCollisionObjects();
249 for (
auto& co : objects)
250 static_manager->unregisterObject(co.get());
252 for (
auto& co : objects)
253 dynamic_manager->registerObject(co.get());
276 #endif // TESSERACT_COLLISION_FCL_UTILS_H