41 #if (MOVEIT_FCL_VERSION >= FCL_VERSION_CHECK(0, 6, 0))
45 #include <fcl/BVH/BVH_model.h>
46 #include <fcl/shape/geometric_shapes.h>
47 #include <fcl/octree.h>
50 #include <boost/thread/mutex.hpp>
52 #include <type_traits>
58 CollisionData* cdata =
reinterpret_cast<CollisionData*
>(data);
61 const CollisionGeometryData* cd1 =
static_cast<const CollisionGeometryData*
>(o1->
collisionGeometry()->getUserData());
62 const CollisionGeometryData* cd2 =
static_cast<const CollisionGeometryData*
>(o2->
collisionGeometry()->getUserData());
65 if (cd1->sameObject(*cd2))
69 if (cdata->active_components_only_)
81 if ((!l1 || cdata->active_components_only_->find(l1) == cdata->active_components_only_->end()) &&
82 (!l2 || cdata->active_components_only_->find(l2) == cdata->active_components_only_->end()))
88 bool always_allow_collision =
false;
92 bool found = cdata->acm_->getAllowedCollision(cd1->getID(), cd2->getID(), type);
98 always_allow_collision =
true;
99 if (cdata->req_->verbose)
101 "Collision between '%s' (type '%s') and '%s' (type '%s') is always allowed. "
102 "No contacts are computed.",
103 cd1->getID().c_str(), cd1->getTypeString().c_str(), cd2->getID().c_str(),
104 cd2->getTypeString().c_str());
108 cdata->acm_->getAllowedCollision(cd1->getID(), cd2->getID(), dcf);
109 if (cdata->req_->verbose)
110 ROS_DEBUG_NAMED(
"collision_detection.fcl",
"Collision between '%s' and '%s' is conditionally allowed",
111 cd1->getID().c_str(), cd2->getID().c_str());
119 const std::set<std::string>& tl = cd2->ptr.ab->getTouchLinks();
120 if (tl.find(cd1->getID()) != tl.end())
122 always_allow_collision =
true;
123 if (cdata->req_->verbose)
125 "Robot link '%s' is allowed to touch attached object '%s'. No contacts are computed.",
126 cd1->getID().c_str(), cd2->getID().c_str());
131 const std::set<std::string>& tl = cd1->ptr.ab->getTouchLinks();
132 if (tl.find(cd2->getID()) != tl.end())
134 always_allow_collision =
true;
135 if (cdata->req_->verbose)
137 "Robot link '%s' is allowed to touch attached object '%s'. No contacts are computed.",
138 cd2->getID().c_str(), cd1->getID().c_str());
144 if (cd1->ptr.ab->getAttachedLink() == cd2->ptr.ab->getAttachedLink())
145 always_allow_collision =
true;
149 if (always_allow_collision)
152 if (cdata->req_->verbose)
153 ROS_DEBUG_NAMED(
"collision_detection.fcl",
"Actually checking collisions between %s and %s", cd1->getID().c_str(),
154 cd2->getID().c_str());
157 std::size_t want_contact_count = 0;
158 if (cdata->req_->contacts)
159 if (cdata->res_->contact_count < cdata->req_->max_contacts)
162 if (cd1->getID() < cd2->getID())
164 std::pair<std::string, std::string> cp(cd1->getID(), cd2->getID());
165 have = cdata->res_->contacts.find(cp) != cdata->res_->contacts.end() ? cdata->res_->contacts[cp].size() : 0;
169 std::pair<std::string, std::string> cp(cd2->getID(), cd1->getID());
170 have = cdata->res_->contacts.find(cp) != cdata->res_->contacts.end() ? cdata->res_->contacts[cp].size() : 0;
172 if (have < cdata->req_->max_contacts_per_pair)
174 std::min(cdata->req_->max_contacts_per_pair - have, cdata->req_->max_contacts - cdata->res_->contact_count);
180 bool enable_cost = cdata->req_->cost;
181 std::size_t num_max_cost_sources = cdata->req_->max_cost_sources;
186 num_max_cost_sources, enable_cost),
188 if (num_contacts > 0)
190 if (cdata->req_->verbose)
192 "Found %d contacts between '%s' and '%s'. "
193 "These contacts will be evaluated to check if they are accepted or not",
194 num_contacts, cd1->getID().c_str(), cd2->getID().c_str());
196 const std::pair<std::string, std::string>& pc = cd1->getID() < cd2->getID() ?
197 std::make_pair(cd1->getID(), cd2->getID()) :
198 std::make_pair(cd2->getID(), cd1->getID());
199 for (
int i = 0; i < num_contacts; ++i)
206 if (want_contact_count > 0)
208 --want_contact_count;
209 cdata->res_->contacts[pc].push_back(c);
210 cdata->res_->contact_count++;
211 if (cdata->req_->verbose)
213 "Found unacceptable contact between '%s' and '%s'. Contact was stored.",
214 cd1->getID().c_str(), cd2->getID().c_str());
216 else if (cdata->req_->verbose)
218 "Found unacceptable contact between '%s' (type '%s') and '%s' "
219 "(type '%s'). Contact was stored.",
220 cd1->getID().c_str(), cd1->getTypeString().c_str(), cd2->getID().c_str(),
221 cd2->getTypeString().c_str());
222 cdata->res_->collision =
true;
223 if (want_contact_count == 0)
231 std::vector<fcl::CostSourced> cost_sources;
235 for (
auto& cost_source : cost_sources)
238 cdata->res_->cost_sources.insert(cs);
239 while (cdata->res_->cost_sources.size() > cdata->req_->max_cost_sources)
240 cdata->res_->cost_sources.erase(--cdata->res_->cost_sources.end());
246 if (want_contact_count > 0)
249 bool enable_cost = cdata->req_->cost;
250 std::size_t num_max_cost_sources = cdata->req_->max_cost_sources;
258 if (num_contacts > 0)
260 int num_contacts_initial = num_contacts;
263 if (want_contact_count >= (std::size_t)num_contacts)
264 want_contact_count -= num_contacts;
267 num_contacts = want_contact_count;
268 want_contact_count = 0;
271 if (cdata->req_->verbose)
273 "Found %d contacts between '%s' (type '%s') and '%s' (type '%s'), "
274 "which constitute a collision. %d contacts will be stored",
275 num_contacts_initial, cd1->getID().c_str(), cd1->getTypeString().c_str(), cd2->getID().c_str(),
276 cd2->getTypeString().c_str(), num_contacts);
278 const std::pair<std::string, std::string>& pc = cd1->getID() < cd2->getID() ?
279 std::make_pair(cd1->getID(), cd2->getID()) :
280 std::make_pair(cd2->getID(), cd1->getID());
281 cdata->res_->collision =
true;
282 for (
int i = 0; i < num_contacts; ++i)
286 cdata->res_->contacts[pc].push_back(c);
287 cdata->res_->contact_count++;
293 std::vector<fcl::CostSourced> cost_sources;
297 for (
auto& cost_source : cost_sources)
300 cdata->res_->cost_sources.insert(cs);
301 while (cdata->res_->cost_sources.size() > cdata->req_->max_cost_sources)
302 cdata->res_->cost_sources.erase(--cdata->res_->cost_sources.end());
308 bool enable_cost = cdata->req_->cost;
309 std::size_t num_max_cost_sources = cdata->req_->max_cost_sources;
314 if (num_contacts > 0)
316 cdata->res_->collision =
true;
317 if (cdata->req_->verbose)
319 "Found a contact between '%s' (type '%s') and '%s' (type '%s'), "
320 "which constitutes a collision. "
321 "Contact information is not stored.",
322 cd1->getID().c_str(), cd1->getTypeString().c_str(), cd2->getID().c_str(),
323 cd2->getTypeString().c_str());
328 std::vector<fcl::CostSourced> cost_sources;
332 for (
auto& cost_source : cost_sources)
335 cdata->res_->cost_sources.insert(cs);
336 while (cdata->res_->cost_sources.size() > cdata->req_->max_cost_sources)
337 cdata->res_->cost_sources.erase(--cdata->res_->cost_sources.end());
343 if (cdata->res_->collision)
344 if (!cdata->req_->contacts || cdata->res_->contact_count >= cdata->req_->max_contacts)
346 if (!cdata->req_->cost)
348 if (cdata->req_->verbose)
350 "Collision checking is considered complete (collision was found and %u contacts are stored)",
351 (
unsigned int)cdata->res_->contact_count);
354 if (!cdata->done_ && cdata->req_->is_done)
356 cdata->done_ = cdata->req_->is_done(*cdata->res_);
357 if (cdata->done_ && cdata->req_->verbose)
359 "Collision checking is considered complete due to external callback. "
360 "%s was found. %u contacts are stored.",
361 cdata->res_->collision ?
"Collision" :
"No collision", (
unsigned int)cdata->res_->contact_count);
372 using ShapeKey = shapes::ShapeConstWeakPtr;
373 using ShapeMap = std::map<ShapeKey, FCLGeometryConstPtr, std::owner_less<ShapeKey>>;
387 for (
auto it =
map_.begin(); it !=
map_.end();)
391 if (it->first.expired())
443 bool always_allow_collision =
false;
453 always_allow_collision =
true;
456 "Collision between '%s' and '%s' is always allowed. No distances are computed.",
466 if (tl.find(cd1->
getID()) != tl.end())
468 always_allow_collision =
true;
471 "Robot link '%s' is allowed to touch attached object '%s'. No distances are computed.",
478 if (tl.find(cd2->
getID()) != tl.end())
480 always_allow_collision =
true;
483 "Robot link '%s' is allowed to touch attached object '%s'. No distances are computed.",
488 if (always_allow_collision)
493 ROS_DEBUG_NAMED(
"collision_detection.fcl",
"Actually checking collisions between %s and %s", cd1->
getID().c_str(),
494 cd2->
getID().c_str());
498 const std::pair<const std::string&, const std::string&> pc =
499 cd1->
getID() < cd2->
getID() ? std::make_pair(std::cref(cd1->
getID()), std::cref(cd2->
getID())) :
500 std::make_pair(
std::cref(cd2->getID()),
std::cref(cd1->getID()));
502 DistanceMap::iterator it = cdata->
res->
distances.find(pc);
522 dist_threshold = it->second[0].distance;
530 !std::static_pointer_cast<const fcl::OcTreed>(o1->
collisionGeometry())->getRoot()) ||
532 !std::static_pointer_cast<const fcl::OcTreed>(o2->
collisionGeometry())->getRoot()))
545 thread_local DistanceResultsData dist_result;
550 const CollisionGeometryData* res_cd1 =
static_cast<const CollisionGeometryData*
>(fcl_result.
o1->
getUserData());
551 const CollisionGeometryData* res_cd2 =
static_cast<const CollisionGeometryData*
>(fcl_result.
o2->
getUserData());
553 #if (MOVEIT_FCL_VERSION >= FCL_VERSION_CHECK(0, 6, 0))
557 dist_result.nearest_points[0] = Eigen::Map<const Eigen::Vector3d>(fcl_result.
nearest_points[0].data.vs);
558 dist_result.nearest_points[1] = Eigen::Map<const Eigen::Vector3d>(fcl_result.
nearest_points[1].data.vs);
560 dist_result.link_names[0] = res_cd1->getID();
561 dist_result.link_names[1] = res_cd2->getID();
562 dist_result.body_types[0] = res_cd1->type;
563 dist_result.body_types[1] = res_cd2->type;
566 dist_result.normal = (dist_result.nearest_points[1] - dist_result.nearest_points[0]).normalized();
569 if (distance <= 0 && cdata->req->enable_signed_distance)
571 dist_result.nearest_points[0].setZero();
572 dist_result.nearest_points[1].setZero();
573 dist_result.normal.setZero();
580 std::size_t contacts =
fcl::collide(o1, o2, coll_req, coll_res);
585 for (std::size_t i = 0; i < contacts; ++i)
595 const fcl::Contactd& contact = coll_res.getContact(max_index);
598 #if (MOVEIT_FCL_VERSION >= FCL_VERSION_CHECK(0, 6, 0))
599 dist_result.nearest_points[0] = contact.
pos;
600 dist_result.nearest_points[1] = contact.
pos;
602 dist_result.nearest_points[0] = Eigen::Map<const Eigen::Vector3d>(contact.
pos.data.vs);
603 dist_result.nearest_points[1] = Eigen::Map<const Eigen::Vector3d>(contact.
pos.data.vs);
608 #if (MOVEIT_FCL_VERSION >= FCL_VERSION_CHECK(0, 6, 0))
616 dist_result.normal = normal;
618 dist_result.normal = -normal;
628 if (dist_result.distance <= 0)
637 std::vector<DistanceResultsData> data;
639 data.push_back(dist_result);
646 it->second.push_back(dist_result);
650 if (dist_result.distance < it->second[0].distance)
651 it->second[0] = dist_result;
656 it->second.push_back(dist_result);
673 template <
typename BV,
typename T>
685 static thread_local FCLShapeCache cache;
694 template <
typename BV,
typename T>
697 using ShapeKey = shapes::ShapeConstWeakPtr;
698 using ShapeMap = std::map<ShapeKey, FCLGeometryConstPtr, std::owner_less<ShapeKey>>;
700 FCLShapeCache& cache = GetShapeCache<BV, T>();
702 shapes::ShapeConstWeakPtr wptr(shape);
704 ShapeMap::const_iterator cache_it = cache.map_.find(wptr);
705 if (cache_it != cache.map_.end())
707 if (cache_it->second->collision_geometry_data_->ptr.raw == data)
712 return cache_it->second;
714 else if (cache_it->second.unique())
716 const_cast<FCLGeometry*
>(cache_it->second.get())->updateCollisionGeometryData(data, shape_index,
false);
721 return cache_it->second;
729 if (std::is_same<T, moveit::core::AttachedBody>::value)
732 FCLShapeCache& othercache = GetShapeCache<BV, World::Object>();
735 auto cache_it = othercache.map_.find(wptr);
736 if (cache_it != othercache.map_.end())
738 if (cache_it->second.unique())
741 FCLGeometryConstPtr obj_cache = cache_it->second;
742 othercache.map_.erase(cache_it);
744 const_cast<FCLGeometry*
>(obj_cache.get())->updateCollisionGeometryData(data, shape_index,
true);
752 cache.map_[wptr] = obj_cache;
753 cache.bumpUseCount();
762 if (std::is_same<T, World::Object>::value)
765 FCLShapeCache& othercache = GetShapeCache<BV, moveit::core::AttachedBody>();
768 auto cache_it = othercache.map_.find(wptr);
769 if (cache_it != othercache.map_.end())
771 if (cache_it->second.unique())
774 FCLGeometryConstPtr obj_cache = cache_it->second;
775 othercache.map_.erase(cache_it);
778 const_cast<FCLGeometry*
>(obj_cache.get())->updateCollisionGeometryData(data, shape_index,
true);
787 cache.map_[wptr] = obj_cache;
788 cache.bumpUseCount();
813 const double* size =
s->size;
814 cg_g =
new fcl::Boxd(size[0], size[1], size[2]);
845 g->addSubModel(points, tri_indices);
858 ROS_ERROR_NAMED(
"collision_detection.fcl",
"This shape type (%d) is not supported using FCL yet",
866 FCLGeometryConstPtr res(
new FCLGeometry(cg_g, data, shape_index));
867 cache.map_[wptr] = res;
868 cache.bumpUseCount();
871 return FCLGeometryConstPtr();
877 return createCollisionGeometry<fcl::OBBRSSd, moveit::core::LinkModel>(shape, link, shape_index);
883 return createCollisionGeometry<fcl::OBBRSSd, moveit::core::AttachedBody>(shape, ab, shape_index);
888 return createCollisionGeometry<fcl::OBBRSSd, World::Object>(shape, obj, 0);
893 template <
typename BV,
typename T>
895 const T* data,
int shape_index)
897 if (fabs(scale - 1.0) <= std::numeric_limits<double>::epsilon() &&
898 fabs(padding) <= std::numeric_limits<double>::epsilon())
899 return createCollisionGeometry<BV, T>(shape, data, shape_index);
903 scaled_shape->scaleAndPadd(scale, padding);
904 return createCollisionGeometry<BV, T>(scaled_shape, data, shape_index);
911 return createCollisionGeometry<fcl::OBBRSSd, moveit::core::LinkModel>(shape, scale, padding, link, shape_index);
917 return createCollisionGeometry<fcl::OBBRSSd, moveit::core::AttachedBody>(shape, scale, padding, ab, shape_index);
921 const World::Object* obj)
923 return createCollisionGeometry<fcl::OBBRSSd, World::Object>(shape, scale, padding,
obj, 0);
928 FCLShapeCache& cache1 = GetShapeCache<fcl::OBBRSSd, World::Object>();
930 cache1.bumpUseCount(
true);
932 FCLShapeCache& cache2 = GetShapeCache<fcl::OBBRSSd, moveit::core::AttachedBody>();
934 cache2.bumpUseCount(
true);
951 if (!collision_objects.empty())