38#include <geometric_shapes/shapes.h>
40#include <rclcpp/logger.hpp>
41#include <rclcpp/logging.hpp>
44#if (MOVEIT_FCL_VERSION >= FCL_VERSION_CHECK(0, 6, 0))
45#include <fcl/geometry/bvh/BVH_model.h>
46#include <fcl/geometry/octree/octree.h>
48#include <fcl/BVH/BVH_model.h>
49#include <fcl/shape/geometric_shapes.h>
50#include <fcl/octree.h>
99 bool always_allow_collision =
false;
109 always_allow_collision =
true;
112 RCLCPP_DEBUG(getLogger(),
113 "Collision between '%s' (type '%s') and '%s' (type '%s') is always allowed. "
114 "No contacts are computed.",
124 RCLCPP_DEBUG(getLogger(),
"Collision between '%s' and '%s' is conditionally allowed", cd1->
getID().c_str(),
125 cd2->
getID().c_str());
135 if (tl.find(cd1->
getID()) != tl.end())
137 always_allow_collision =
true;
140 RCLCPP_DEBUG(getLogger(),
"Robot link '%s' is allowed to touch attached object '%s'. No contacts are computed.",
148 if (tl.find(cd2->
getID()) != tl.end())
150 always_allow_collision =
true;
153 RCLCPP_DEBUG(getLogger(),
"Robot link '%s' is allowed to touch attached object '%s'. No contacts are computed.",
162 always_allow_collision =
true;
166 if (always_allow_collision)
171 RCLCPP_DEBUG(getLogger(),
"Actually checking collisions between %s and %s", cd1->
getID().c_str(),
172 cd2->
getID().c_str());
176 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)
203 bool enable_cost = cdata->
req_->
cost;
205 bool enable_contact =
true;
207 int num_contacts = fcl::collide(o1, o2,
209 num_max_cost_sources, enable_cost),
211 if (num_contacts > 0)
215 RCLCPP_INFO(getLogger(),
216 "Found %d contacts between '%s' and '%s'. "
217 "These contacts will be evaluated to check if they are accepted or not",
218 num_contacts, cd1->
getID().c_str(), cd2->
getID().c_str());
221 const std::pair<std::string, std::string>& pc = cd1->
getID() < cd2->
getID() ?
224 for (
int i = 0; i < num_contacts; ++i)
231 if (want_contact_count > 0)
233 --want_contact_count;
238 RCLCPP_INFO(getLogger(),
"Found unacceptable contact between '%s' and '%s'. Contact was stored.",
244 RCLCPP_INFO(getLogger(),
245 "Found unacceptable contact between '%s' (type '%s') and '%s' "
246 "(type '%s'). Contact was stored.",
251 if (want_contact_count == 0)
259 std::vector<fcl::CostSourced> cost_sources;
260 col_result.getCostSources(cost_sources);
263 for (
auto& cost_source : cost_sources)
274 if (want_contact_count > 0)
277 bool enable_cost = cdata->
req_->
cost;
279 bool enable_contact{
true };
286 if (num_contacts > 0)
288 int num_contacts_initial = num_contacts;
291 if (want_contact_count >=
static_cast<std::size_t
>(num_contacts))
293 want_contact_count -= num_contacts;
297 num_contacts = want_contact_count;
298 want_contact_count = 0;
303 RCLCPP_INFO(getLogger(),
304 "Found %d contacts between '%s' (type '%s') and '%s' (type '%s'), "
305 "which constitute a collision. %d contacts will be stored",
310 const std::pair<std::string, std::string>& pc = cd1->
getID() < cd2->
getID() ?
314 for (
int i = 0; i < num_contacts; ++i)
325 std::vector<fcl::CostSourced> cost_sources;
326 col_result.getCostSources(cost_sources);
329 for (
auto& cost_source : cost_sources)
340 bool enable_cost = cdata->
req_->
cost;
342 bool enable_contact =
false;
344 int num_contacts = fcl::collide(
346 if (num_contacts > 0)
351 RCLCPP_INFO(getLogger(),
352 "Found a contact between '%s' (type '%s') and '%s' (type '%s'), "
353 "which constitutes a collision. "
354 "Contact information is not stored.",
362 std::vector<fcl::CostSourced> cost_sources;
363 col_result.getCostSources(cost_sources);
366 for (
auto& cost_source : cost_sources)
385 RCLCPP_INFO(getLogger(),
386 "Collision checking is considered complete (collision was found and %u contacts are stored)",
397 RCLCPP_INFO(getLogger(),
398 "Collision checking is considered complete due to external callback. "
399 "%s was found. %u contacts are stored.",
414 using ShapeMap = std::map<ShapeKey, FCLGeometryConstPtr, std::owner_less<ShapeKey>>;
428 for (
auto it =
map_.begin(); it !=
map_.end();)
432 if (it->first.expired())
484 bool always_allow_collision =
false;
494 always_allow_collision =
true;
497 RCLCPP_DEBUG(getLogger(),
"Collision between '%s' and '%s' is always allowed. No distances are computed.",
508 if (tl.find(cd1->
getID()) != tl.end())
510 always_allow_collision =
true;
513 RCLCPP_DEBUG(getLogger(),
514 "Robot link '%s' is allowed to touch attached object '%s'. No distances are computed.",
522 if (tl.find(cd2->
getID()) != tl.end())
524 always_allow_collision =
true;
527 RCLCPP_DEBUG(getLogger(),
528 "Robot link '%s' is allowed to touch attached object '%s'. No distances are computed.",
534 if (always_allow_collision)
540 RCLCPP_DEBUG(getLogger(),
"Actually checking collisions between %s and %s", cd1->
getID().c_str(),
541 cd2->
getID().c_str());
546 const std::pair<const std::string&, const std::string&> pc =
547 cd1->
getID() < cd2->
getID() ? std::make_pair(std::cref(cd1->
getID()), std::cref(cd2->
getID())) :
548 std::make_pair(std::cref(cd2->
getID()), std::cref(cd1->
getID()));
550 DistanceMap::iterator it = cdata->
res->
distances.find(pc);
553 if (cdata->
req->
type == DistanceRequestType::GLOBAL)
560 if (cdata->
req->
type == DistanceRequestType::LIMITED)
568 else if (cdata->
req->
type == DistanceRequestType::SINGLE)
570 dist_threshold = it->second[0].distance;
575 fcl_result.min_distance = dist_threshold;
577 if ((o1->getObjectType() == fcl::OT_OCTREE &&
578 !std::static_pointer_cast<const fcl::OcTreed>(o1->collisionGeometry())->getRoot()) ||
579 (o2->getObjectType() == fcl::OT_OCTREE &&
580 !std::static_pointer_cast<const fcl::OcTreed>(o2->collisionGeometry())->getRoot()))
589 if (distance < dist_threshold)
594 dist_result.
distance = fcl_result.min_distance;
601#if (MOVEIT_FCL_VERSION >= FCL_VERSION_CHECK(0, 6, 0))
605 dist_result.
nearest_points[0] = Eigen::Map<const Eigen::Vector3d>(fcl_result.nearest_points[0].data.vs);
606 dist_result.
nearest_points[1] = Eigen::Map<const Eigen::Vector3d>(fcl_result.nearest_points[1].data.vs);
617 if (distance <= 0 && cdata->req->enable_signed_distance)
621 dist_result.
normal.setZero();
626 coll_req.enable_contact =
true;
627 coll_req.num_max_contacts = 200;
628 std::size_t contacts = fcl::collide(o1, o2, coll_req, coll_res);
633 for (std::size_t i = 0; i < contacts; ++i)
636 if (contact.penetration_depth > max_dist)
638 max_dist = contact.penetration_depth;
643 const fcl::Contactd& contact = coll_res.getContact(max_index);
644 dist_result.
distance = -contact.penetration_depth;
646#if (MOVEIT_FCL_VERSION >= FCL_VERSION_CHECK(0, 6, 0))
650 dist_result.
nearest_points[0] = Eigen::Map<const Eigen::Vector3d>(contact.pos.data.vs);
651 dist_result.
nearest_points[1] = Eigen::Map<const Eigen::Vector3d>(contact.pos.data.vs);
656#if (MOVEIT_FCL_VERSION >= FCL_VERSION_CHECK(0, 6, 0))
657 Eigen::Vector3d normal(contact.normal);
659 Eigen::Vector3d normal(contact.normal.data.vs);
663 if (contact.o1 == o1->collisionGeometry().get())
665 dist_result.
normal = normal;
669 dist_result.
normal = -normal;
685 if (cdata->
req->
type != DistanceRequestType::GLOBAL)
689 std::vector<DistanceResultsData> data;
691 data.push_back(dist_result);
696 if (cdata->
req->
type == DistanceRequestType::ALL)
698 it->second.push_back(dist_result);
700 else if (cdata->
req->
type == DistanceRequestType::SINGLE)
702 if (dist_result.
distance < it->second[0].distance)
703 it->second[0] = dist_result;
705 else if (cdata->
req->
type == DistanceRequestType::LIMITED)
708 it->second.push_back(dist_result);
725template <
typename BV,
typename T>
746template <
typename BV,
typename T>
749 using ShapeKey = shapes::ShapeConstWeakPtr;
750 using ShapeMap = std::map<ShapeKey, FCLGeometryConstPtr, std::owner_less<ShapeKey>>;
754 shapes::ShapeConstWeakPtr wptr(shape);
756 ShapeMap::const_iterator cache_it = cache.
map_.find(wptr);
757 if (cache_it != cache.
map_.end())
759 if (cache_it->second->collision_geometry_data_->ptr.raw == data)
764 return cache_it->second;
766 else if (cache_it->second.unique())
768 const_cast<FCLGeometry*
>(cache_it->second.get())->updateCollisionGeometryData(data, shape_index,
false);
773 return cache_it->second;
781 if (std::is_same<T, moveit::core::AttachedBody>::value)
784 FCLShapeCache& othercache = getShapeCache<BV, World::Object>();
787 auto cache_it = othercache.
map_.find(wptr);
788 if (cache_it != othercache.
map_.end())
790 if (cache_it->second.unique())
793 FCLGeometryConstPtr obj_cache = cache_it->second;
794 othercache.
map_.erase(cache_it);
796 const_cast<FCLGeometry*
>(obj_cache.get())->updateCollisionGeometryData(data, shape_index,
true);
804 cache.
map_[wptr] = obj_cache;
814 if (std::is_same<T, World::Object>::value)
817 FCLShapeCache& othercache = getShapeCache<BV, moveit::core::AttachedBody>();
820 auto cache_it = othercache.
map_.find(wptr);
821 if (cache_it != othercache.
map_.end())
823 if (cache_it->second.unique())
826 FCLGeometryConstPtr obj_cache = cache_it->second;
827 othercache.
map_.erase(cache_it);
830 const_cast<FCLGeometry*
>(obj_cache.get())->updateCollisionGeometryData(data, shape_index,
true);
839 cache.
map_[wptr] = obj_cache;
852 const shapes::Plane* p =
static_cast<const shapes::Plane*
>(shape.get());
858 const shapes::Sphere* s =
static_cast<const shapes::Sphere*
>(shape.get());
864 const shapes::Box* s =
static_cast<const shapes::Box*
>(shape.get());
865 const double* size = s->size;
866 cg_g =
new fcl::Boxd(size[0], size[1], size[2]);
869 case shapes::CYLINDER:
871 const shapes::Cylinder* s =
static_cast<const shapes::Cylinder*
>(shape.get());
877 const shapes::Cone* s =
static_cast<const shapes::Cone*
>(shape.get());
883 auto g =
new fcl::BVHModel<BV>();
884 const shapes::Mesh* mesh =
static_cast<const shapes::Mesh*
>(shape.get());
885 if (mesh->vertex_count > 0 && mesh->triangle_count > 0)
887 std::vector<fcl::Triangle> tri_indices(mesh->triangle_count);
888 for (
unsigned int i = 0; i < mesh->triangle_count; ++i)
891 fcl::Triangle(mesh->triangles[3 * i], mesh->triangles[3 * i + 1], mesh->triangles[3 * i + 2]);
894 std::vector<fcl::Vector3d> points(mesh->vertex_count);
895 for (
unsigned int i = 0; i < mesh->vertex_count; ++i)
896 points[i] =
fcl::Vector3d(mesh->vertices[3 * i], mesh->vertices[3 * i + 1], mesh->vertices[3 * i + 2]);
899 g->addSubModel(points, tri_indices);
907 const shapes::OcTree* g =
static_cast<const shapes::OcTree*
>(shape.get());
912 RCLCPP_ERROR(getLogger(),
"This shape type (%d) is not supported using FCL yet",
static_cast<int>(shape->type));
918 cg_g->computeLocalAABB();
919 FCLGeometryConstPtr res = std::make_shared<const FCLGeometry>(cg_g, data, shape_index);
920 cache.
map_[wptr] = res;
924 return FCLGeometryConstPtr();
930 return createCollisionGeometry<fcl::OBBRSSd, moveit::core::LinkModel>(shape, link, shape_index);
936 return createCollisionGeometry<fcl::OBBRSSd, moveit::core::AttachedBody>(shape, ab, shape_index);
941 return createCollisionGeometry<fcl::OBBRSSd, World::Object>(shape, obj, 0);
946template <
typename BV,
typename T>
948 const T* data,
int shape_index)
950 if (fabs(scale - 1.0) <= std::numeric_limits<double>::epsilon() &&
951 fabs(padding) <= std::numeric_limits<double>::epsilon())
953 return createCollisionGeometry<BV, T>(shape, data, shape_index);
957 shapes::ShapePtr scaled_shape(shape->clone());
958 scaled_shape->scaleAndPadd(scale, padding);
959 return createCollisionGeometry<BV, T>(scaled_shape, data, shape_index);
966 return createCollisionGeometry<fcl::OBBRSSd, moveit::core::LinkModel>(shape, scale, padding, link, shape_index);
972 return createCollisionGeometry<fcl::OBBRSSd, moveit::core::AttachedBody>(shape, scale, padding, ab, shape_index);
978 return createCollisionGeometry<fcl::OBBRSSd, World::Object>(shape, scale, padding, obj, 0);
983 FCLShapeCache& cache1 = getShapeCache<fcl::OBBRSSd, World::Object>();
987 FCLShapeCache& cache2 = getShapeCache<fcl::OBBRSSd, moveit::core::AttachedBody>();
1010 if (!collision_objects.empty())
1011 manager->registerObjects(collision_objects);
1017 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 LinkModel * getAttachedLink() const
Get the model of the link this body is attached to.
const std::set< std::string > & getTouchLinks() const
Get the links that the attached body is allowed to touch.
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.
rclcpp::Logger getLogger()
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.
FCLShapeCache & getShapeCache()
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 ...
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...
fcl::CollisionObject CollisionObjectd
fcl::DistanceResult DistanceResultd
fcl::BroadPhaseCollisionManager BroadPhaseCollisionManagerd
fcl::DistanceRequest DistanceRequestd
fcl::CollisionGeometry CollisionGeometryd
fcl::CollisionResult CollisionResultd
fcl::CollisionRequest CollisionRequestd
rclcpp::Logger getLogger(const std::string &name)
Creates a namespaced logger.
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.
BodyType body_types[2]
The object body type.
EIGEN_MAKE_ALIGNED_OPERATOR_NEW Eigen::Vector3d nearest_points[2]
The nearest points.
std::string link_names[2]
The object link names.
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.