38 #include <geometric_shapes/shapes.h>
40 #include <rclcpp/logger.hpp>
41 #include <rclcpp/logging.hpp>
43 #if (MOVEIT_FCL_VERSION >= FCL_VERSION_CHECK(0, 6, 0))
44 #include <fcl/geometry/bvh/BVH_model.h>
45 #include <fcl/geometry/octree/octree.h>
47 #include <fcl/BVH/BVH_model.h>
48 #include <fcl/shape/geometric_shapes.h>
49 #include <fcl/octree.h>
53 #include <type_traits>
59 static const rclcpp::Logger LOGGER = rclcpp::get_logger(
"moveit_collision_detection_fcl.collision_common");
93 bool always_allow_collision =
false;
103 always_allow_collision =
true;
106 "Collision between '%s' (type '%s') and '%s' (type '%s') is always allowed. "
107 "No contacts are computed.",
115 RCLCPP_DEBUG(LOGGER,
"Collision between '%s' and '%s' is conditionally allowed", cd1->
getID().c_str(),
116 cd2->
getID().c_str());
125 if (tl.find(cd1->
getID()) != tl.end())
127 always_allow_collision =
true;
129 RCLCPP_DEBUG(LOGGER,
"Robot link '%s' is allowed to touch attached object '%s'. No contacts are computed.",
136 if (tl.find(cd2->
getID()) != tl.end())
138 always_allow_collision =
true;
140 RCLCPP_DEBUG(LOGGER,
"Robot link '%s' is allowed to touch attached object '%s'. No contacts are computed.",
151 always_allow_collision =
true;
157 if (tl1.find(cd2->
getID()) != tl1.end() || tl2.find(cd1->
getID()) != tl2.end())
159 always_allow_collision =
true;
162 if (always_allow_collision && cdata->
req_->
verbose)
164 RCLCPP_DEBUG(LOGGER,
"Attached object '%s' is allowed to touch attached object '%s'. No contacts are computed.",
170 if (always_allow_collision)
174 RCLCPP_DEBUG(LOGGER,
"Actually checking collisions between %s and %s", cd1->
getID().c_str(), cd2->
getID().c_str());
177 std::size_t want_contact_count = 0;
184 std::pair<std::string, std::string> cp(cd1->
getID(), cd2->
getID());
189 std::pair<std::string, std::string> cp(cd2->
getID(), cd1->
getID());
192 if (have < cdata->req_->max_contacts_per_pair)
200 bool enable_cost = cdata->
req_->
cost;
202 bool enable_contact =
true;
204 int num_contacts = fcl::collide(o1, o2,
206 num_max_cost_sources, enable_cost),
208 if (num_contacts > 0)
212 "Found %d contacts between '%s' and '%s'. "
213 "These contacts will be evaluated to check if they are accepted or not",
214 num_contacts, cd1->
getID().c_str(), cd2->
getID().c_str());
216 const std::pair<std::string, std::string>& pc = cd1->
getID() < cd2->
getID() ?
219 for (
int i = 0; i < num_contacts; ++i)
226 if (want_contact_count > 0)
228 --want_contact_count;
232 RCLCPP_INFO(LOGGER,
"Found unacceptable contact between '%s' and '%s'. Contact was stored.",
237 "Found unacceptable contact between '%s' (type '%s') and '%s' "
238 "(type '%s'). Contact was stored.",
242 if (want_contact_count == 0)
250 std::vector<fcl::CostSourced> cost_sources;
251 col_result.getCostSources(cost_sources);
254 for (
auto& cost_source : cost_sources)
265 if (want_contact_count > 0)
268 bool enable_cost = cdata->
req_->
cost;
270 bool enable_contact =
true;
277 if (num_contacts > 0)
279 int num_contacts_initial = num_contacts;
282 if (want_contact_count >= (std::size_t)num_contacts)
283 want_contact_count -= num_contacts;
286 num_contacts = want_contact_count;
287 want_contact_count = 0;
292 "Found %d contacts between '%s' (type '%s') and '%s' (type '%s'), "
293 "which constitute a collision. %d contacts will be stored",
297 const std::pair<std::string, std::string>& pc = cd1->
getID() < cd2->
getID() ?
301 for (
int i = 0; i < num_contacts; ++i)
312 std::vector<fcl::CostSourced> cost_sources;
313 col_result.getCostSources(cost_sources);
316 for (
auto& cost_source : cost_sources)
327 bool enable_cost = cdata->
req_->
cost;
329 bool enable_contact =
false;
331 int num_contacts = fcl::collide(
333 if (num_contacts > 0)
338 "Found a contact between '%s' (type '%s') and '%s' (type '%s'), "
339 "which constitutes a collision. "
340 "Contact information is not stored.",
347 std::vector<fcl::CostSourced> cost_sources;
348 col_result.getCostSources(cost_sources);
351 for (
auto& cost_source : cost_sources)
369 "Collision checking is considered complete (collision was found and %u contacts are stored)",
378 "Collision checking is considered complete due to external callback. "
379 "%s was found. %u contacts are stored.",
392 using ShapeMap = std::map<ShapeKey, FCLGeometryConstPtr, std::owner_less<ShapeKey>>;
406 for (
auto it =
map_.begin(); it !=
map_.end();)
410 if (it->first.expired())
462 bool always_allow_collision =
false;
472 always_allow_collision =
true;
474 RCLCPP_DEBUG(LOGGER,
"Collision between '%s' and '%s' is always allowed. No distances are computed.",
484 if (tl.find(cd1->
getID()) != tl.end())
486 always_allow_collision =
true;
488 RCLCPP_DEBUG(LOGGER,
"Robot link '%s' is allowed to touch attached object '%s'. No distances are computed.",
495 if (tl.find(cd2->
getID()) != tl.end())
497 always_allow_collision =
true;
499 RCLCPP_DEBUG(LOGGER,
"Robot link '%s' is allowed to touch attached object '%s'. No distances are computed.",
504 if (always_allow_collision)
509 RCLCPP_DEBUG(LOGGER,
"Actually checking collisions between %s and %s", cd1->
getID().c_str(), cd2->
getID().c_str());
513 const std::pair<const std::string&, const std::string&> pc =
514 cd1->
getID() < cd2->
getID() ? std::make_pair(std::cref(cd1->
getID()), std::cref(cd2->
getID())) :
515 std::make_pair(std::cref(cd2->
getID()), std::cref(cd1->
getID()));
517 DistanceMap::iterator it = cdata->
res->
distances.find(pc);
537 dist_threshold = it->second[0].distance;
542 fcl_result.min_distance = dist_threshold;
544 if ((o1->getObjectType() == fcl::OT_OCTREE &&
545 !std::static_pointer_cast<const fcl::OcTreed>(o1->collisionGeometry())->getRoot()) ||
546 (o2->getObjectType() == fcl::OT_OCTREE &&
547 !std::static_pointer_cast<const fcl::OcTreed>(o2->collisionGeometry())->getRoot()))
561 dist_result.
distance = fcl_result.min_distance;
568 #if (MOVEIT_FCL_VERSION >= FCL_VERSION_CHECK(0, 6, 0))
569 dist_result.nearest_points[0] = fcl_result.nearest_points[0];
570 dist_result.nearest_points[1] = fcl_result.nearest_points[1];
572 dist_result.nearest_points[0] = Eigen::Map<const Eigen::Vector3d>(fcl_result.nearest_points[0].data.vs);
573 dist_result.nearest_points[1] = Eigen::Map<const Eigen::Vector3d>(fcl_result.nearest_points[1].data.vs);
575 dist_result.link_names[0] = res_cd1->
getID();
576 dist_result.link_names[1] = res_cd2->
getID();
577 dist_result.body_types[0] = res_cd1->
type;
578 dist_result.body_types[1] = res_cd2->
type;
581 dist_result.normal = (dist_result.nearest_points[1] - dist_result.nearest_points[0]).normalized();
584 if (distance <= 0 && cdata->req->enable_signed_distance)
586 dist_result.nearest_points[0].setZero();
587 dist_result.nearest_points[1].setZero();
588 dist_result.normal.setZero();
593 coll_req.enable_contact =
true;
594 coll_req.num_max_contacts = 200;
595 std::size_t contacts = fcl::collide(o1, o2, coll_req, coll_res);
600 for (std::size_t i = 0; i < contacts; ++i)
603 if (contact.penetration_depth > max_dist)
605 max_dist = contact.penetration_depth;
610 const fcl::Contactd& contact = coll_res.getContact(max_index);
611 dist_result.distance = -contact.penetration_depth;
613 #if (MOVEIT_FCL_VERSION >= FCL_VERSION_CHECK(0, 6, 0))
614 dist_result.nearest_points[0] = contact.pos;
615 dist_result.nearest_points[1] = contact.pos;
617 dist_result.nearest_points[0] = Eigen::Map<const Eigen::Vector3d>(contact.pos.data.vs);
618 dist_result.nearest_points[1] = Eigen::Map<const Eigen::Vector3d>(contact.pos.data.vs);
623 #if (MOVEIT_FCL_VERSION >= FCL_VERSION_CHECK(0, 6, 0))
630 if (contact.o1 == o1->collisionGeometry().get())
631 dist_result.normal = normal;
633 dist_result.normal = -normal;
643 if (dist_result.distance <= 0)
652 std::vector<DistanceResultsData> data;
654 data.push_back(dist_result);
661 it->second.push_back(dist_result);
665 if (dist_result.distance < it->second[0].distance)
666 it->second[0] = dist_result;
671 it->second.push_back(dist_result);
688 template <
typename BV,
typename T>
709 template <
typename BV,
typename T>
712 using ShapeKey = shapes::ShapeConstWeakPtr;
713 using ShapeMap = std::map<ShapeKey, FCLGeometryConstPtr, std::owner_less<ShapeKey>>;
717 shapes::ShapeConstWeakPtr wptr(shape);
719 ShapeMap::const_iterator cache_it = cache.
map_.find(wptr);
720 if (cache_it != cache.
map_.end())
722 if (cache_it->second->collision_geometry_data_->ptr.raw == data)
727 return cache_it->second;
729 else if (cache_it->second.unique())
731 const_cast<FCLGeometry*
>(cache_it->second.get())->updateCollisionGeometryData(data, shape_index,
false);
736 return cache_it->second;
744 if (std::is_same<T, moveit::core::AttachedBody>::value)
747 FCLShapeCache& othercache = GetShapeCache<BV, World::Object>();
750 auto cache_it = othercache.
map_.find(wptr);
751 if (cache_it != othercache.
map_.end())
753 if (cache_it->second.unique())
756 FCLGeometryConstPtr obj_cache = cache_it->second;
757 othercache.
map_.erase(cache_it);
759 const_cast<FCLGeometry*
>(obj_cache.get())->updateCollisionGeometryData(data, shape_index,
true);
767 cache.
map_[wptr] = obj_cache;
777 if (std::is_same<T, World::Object>::value)
780 FCLShapeCache& othercache = GetShapeCache<BV, moveit::core::AttachedBody>();
783 auto cache_it = othercache.
map_.find(wptr);
784 if (cache_it != othercache.
map_.end())
786 if (cache_it->second.unique())
789 FCLGeometryConstPtr obj_cache = cache_it->second;
790 othercache.
map_.erase(cache_it);
793 const_cast<FCLGeometry*
>(obj_cache.get())->updateCollisionGeometryData(data, shape_index,
true);
802 cache.
map_[wptr] = obj_cache;
815 const shapes::Plane*
p =
static_cast<const shapes::Plane*
>(shape.get());
821 const shapes::Sphere* s =
static_cast<const shapes::Sphere*
>(shape.get());
827 const shapes::Box* s =
static_cast<const shapes::Box*
>(shape.get());
828 const double* size = s->size;
829 cg_g =
new fcl::Boxd(size[0], size[1], size[2]);
832 case shapes::CYLINDER:
834 const shapes::Cylinder* s =
static_cast<const shapes::Cylinder*
>(shape.get());
840 const shapes::Cone* s =
static_cast<const shapes::Cone*
>(shape.get());
846 auto g =
new fcl::BVHModel<BV>();
847 const shapes::Mesh* mesh =
static_cast<const shapes::Mesh*
>(shape.get());
848 if (mesh->vertex_count > 0 && mesh->triangle_count > 0)
850 std::vector<fcl::Triangle> tri_indices(mesh->triangle_count);
851 for (
unsigned int i = 0; i < mesh->triangle_count; ++i)
853 fcl::Triangle(mesh->triangles[3 * i], mesh->triangles[3 * i + 1], mesh->triangles[3 * i + 2]);
855 std::vector<fcl::Vector3d> points(mesh->vertex_count);
856 for (
unsigned int i = 0; i < mesh->vertex_count; ++i)
857 points[i] =
fcl::Vector3d(mesh->vertices[3 * i], mesh->vertices[3 * i + 1], mesh->vertices[3 * i + 2]);
860 g->addSubModel(points, tri_indices);
868 const shapes::OcTree* g =
static_cast<const shapes::OcTree*
>(shape.get());
873 RCLCPP_ERROR(LOGGER,
"This shape type (%d) is not supported using FCL yet",
static_cast<int>(shape->type));
879 cg_g->computeLocalAABB();
880 FCLGeometryConstPtr res = std::make_shared<const FCLGeometry>(cg_g, data, shape_index);
881 cache.
map_[wptr] = res;
885 return FCLGeometryConstPtr();
891 return createCollisionGeometry<fcl::OBBRSSd, moveit::core::LinkModel>(shape, link, shape_index);
897 return createCollisionGeometry<fcl::OBBRSSd, moveit::core::AttachedBody>(shape, ab, shape_index);
902 return createCollisionGeometry<fcl::OBBRSSd, World::Object>(shape, obj, 0);
907 template <
typename BV,
typename T>
909 const T* data,
int shape_index)
911 if (fabs(scale - 1.0) <= std::numeric_limits<double>::epsilon() &&
912 fabs(padding) <= std::numeric_limits<double>::epsilon())
913 return createCollisionGeometry<BV, T>(shape, data, shape_index);
916 shapes::ShapePtr scaled_shape(shape->clone());
917 scaled_shape->scaleAndPadd(scale, padding);
918 return createCollisionGeometry<BV, T>(scaled_shape, data, shape_index);
925 return createCollisionGeometry<fcl::OBBRSSd, moveit::core::LinkModel>(shape, scale, padding, link, shape_index);
931 return createCollisionGeometry<fcl::OBBRSSd, moveit::core::AttachedBody>(shape, scale, padding, ab, shape_index);
937 return createCollisionGeometry<fcl::OBBRSSd, World::Object>(shape, scale, padding, obj, 0);
942 FCLShapeCache& cache1 = GetShapeCache<fcl::OBBRSSd, World::Object>();
946 FCLShapeCache& cache2 = GetShapeCache<fcl::OBBRSSd, moveit::core::AttachedBody>();
965 if (!collision_objects.empty())
966 manager->registerObjects(collision_objects);
972 manager->unregisterObject(collision_object.get());
bool getAllowedCollision(const std::string &name1, const std::string &name2, DecideContactFn &fn) const
Get the allowed collision predicate between two elements. Return true if a predicate for entry is inc...
Object defining bodies that can be attached to robot links.
const std::set< std::string > & getTouchLinks() const
Get the links that the attached body is allowed to touch.
const LinkModel * getAttachedLink() const
Get the model of the link this body is attached to.
A link from the robot. Contains the constant transform applied to the link and its geometry.
@ CONDITIONAL
The collision is allowed depending on a predicate evaluated on the produced contact....
@ ALWAYS
Collisions between a particular pair of bodies does not imply that the robot configuration is in coll...
@ ROBOT_LINK
A link on the robot.
@ ROBOT_ATTACHED
A body attached to a robot link.
@ ALL
Find all the contacts for a given pair.
@ GLOBAL
Find the global minimum.
@ LIMITED
Find a limited(max_contacts_per_body) set of contacts for a given pair.
@ SINGLE
Find the global minimum for each pair.
void fcl2contact(const fcl::Contactd &fc, Contact &c)
Transforms an FCL contact into a MoveIt contact point.
FCLGeometryConstPtr createCollisionGeometry(const shapes::ShapeConstPtr &shape, const moveit::core::LinkModel *link, int shape_index)
Create new FCLGeometry object out of robot link model.
void cleanCollisionGeometryCache()
Increases the counter of the caches which can trigger the cleaning of expired entries from them.
bool collisionCallback(fcl::CollisionObjectd *o1, fcl::CollisionObjectd *o2, void *data)
Callback function used by the FCLManager used for each pair of collision objects to calculate object ...
FCLShapeCache & GetShapeCache()
std::function< bool(collision_detection::Contact &)> DecideContactFn
Signature of predicate that decides whether a contact is allowed or not (when AllowedCollision::Type ...
void fcl2costsource(const fcl::CostSourced &fcs, CostSource &cs)
Transforms the FCL internal representation to the MoveIt CostSource data structure.
bool distanceCallback(fcl::CollisionObjectd *o1, fcl::CollisionObjectd *o2, void *data, double &min_dist)
Callback function used by the FCLManager used for each pair of collision objects to calculate collisi...
Vec3fX< details::Vec3Data< double > > Vector3d
fcl::CollisionObject CollisionObjectd
fcl::DistanceResult DistanceResultd
fcl::BroadPhaseCollisionManager BroadPhaseCollisionManagerd
fcl::DistanceRequest DistanceRequestd
fcl::CollisionGeometry CollisionGeometryd
fcl::CollisionResult CollisionResultd
fcl::CollisionRequest CollisionRequestd
double distance(const urdf::Pose &transform)
Data structure which is passed to the collision callback function of the collision manager.
const std::set< const moveit::core::LinkModel * > * active_components_only_
If the collision request includes a group name, this set contains the pointers to the link models tha...
const AllowedCollisionMatrix * acm_
The user-specified collision matrix (may be nullptr).
void enableGroup(const moveit::core::RobotModelConstPtr &robot_model)
Compute active_components_only_ based on the joint group specified in req_.
bool done_
Flag indicating whether collision checking is complete.
CollisionResult * res_
The user-specified response location.
const CollisionRequest * req_
The collision request passed by the user.
Wrapper around world, link and attached objects' geometry data.
const moveit::core::LinkModel * link
bool sameObject(const CollisionGeometryData &other) const
Check if two CollisionGeometryData objects point to the same source object.
const std::string & getID() const
Returns the name which is saved in the member pointed to in ptr.
std::string getTypeString() const
Returns a string of the corresponding type.
const moveit::core::AttachedBody * ab
union collision_detection::CollisionGeometryData::@0 ptr
Points to the type of body which contains the geometry.
BodyType type
Indicates the body type of the object.
std::string group_name
The group name to check collisions for (optional; if empty, assume the complete robot)
bool verbose
Flag indicating whether information about detected collisions should be reported.
std::size_t max_cost_sources
When costs are computed, this value defines how many of the top cost sources should be returned.
bool contacts
If true, compute contacts. Otherwise only a binary collision yes/no is reported.
bool cost
If true, a collision cost is computed.
std::size_t max_contacts
Overall maximum number of contacts to compute.
std::function< bool(const CollisionResult &)> is_done
Function call that decides whether collision detection should stop.
std::size_t max_contacts_per_pair
Maximum number of contacts to compute per pair of bodies (multiple bodies may be in contact at differ...
std::set< CostSource > cost_sources
These are the individual cost sources when costs are computed.
bool collision
True if collision was found, false otherwise.
std::size_t contact_count
Number of contacts returned.
When collision costs are computed, this structure contains information about the partial cost incurre...
Data structure which is passed to the distance callback function of the collision manager.
DistanceResult * res
Distance query results information.
const DistanceRequest * req
Distance query request information.
bool done
Indicates if distance query is finished.
const std::set< const moveit::core::LinkModel * > * active_components_only
The set of active components to check.
bool verbose
Log debug information.
std::size_t max_contacts_per_body
Maximum number of contacts to store for bodies (multiple bodies may be within distance threshold)
double distance_threshold
bool enable_signed_distance
Indicate if a signed distance should be calculated in a collision.
const AllowedCollisionMatrix * acm
The allowed collision matrix used to filter checks.
bool enable_nearest_points
Indicate if nearest point information should be calculated.
DistanceMap distances
A map of distance data for each link in the req.active_components_only.
bool collision
Indicates if two objects were in collision.
DistanceResultsData minimum_distance
ResultsData for the two objects with the minimum distance.
Generic representation of the distance information for a pair of objects.
double distance
The distance between two objects. If two objects are in collision, distance <= 0.
Bundles the CollisionGeometryData and FCL collision geometry representation into a single class.
std::vector< FCLCollisionObjectPtr > collision_objects_
void unregisterFrom(fcl::BroadPhaseCollisionManagerd *manager)
std::vector< FCLGeometryConstPtr > collision_geometry_
Geometry data corresponding to collision_objects_.
void registerTo(fcl::BroadPhaseCollisionManagerd *manager)
Cache for an arbitrary type of shape. It is assigned during the execution of createCollisionGeometry(...
ShapeMap map_
Map of weak pointers to the FCLGeometry.
static const unsigned int MAX_CLEAN_COUNT
void bumpUseCount(bool force=false)
shapes::ShapeConstWeakPtr ShapeKey
unsigned int clean_count_
Counts cache usage and triggers clearing of cache when \m MAX_CLEAN_COUNT is exceeded.
std::map< ShapeKey, FCLGeometryConstPtr, std::owner_less< ShapeKey > > ShapeMap
A representation of an object.