42 #include <rclcpp/logger.hpp>
43 #include <rclcpp/logging.hpp>
45 #if (MOVEIT_FCL_VERSION >= FCL_VERSION_CHECK(0, 6, 0))
46 #include <fcl/broadphase/broadphase_dynamic_AABB_tree.h>
51 static const rclcpp::Logger LOGGER = rclcpp::get_logger(
"moveit_collision_detection_fcl.collision_env_fcl");
57 void checkFCLCapabilities(
const DistanceRequest& req)
59 #if MOVEIT_FCL_VERSION < FCL_VERSION_CHECK(0, 6, 0)
60 if (req.enable_nearest_points)
65 rclcpp::Clock steady_clock(RCL_STEADY_TIME);
66 RCLCPP_ERROR_THROTTLE(LOGGER, steady_clock, 2000,
67 "You requested a distance check with enable_nearest_points=true, "
68 "but the FCL version MoveIt was compiled against (%d.%d.%d) "
69 "is known to return bogus nearest points. Please update your FCL "
71 FCL_MAJOR_VERSION, FCL_MINOR_VERSION, FCL_PATCH_VERSION);
82 const std::vector<const moveit::core::LinkModel*>& links =
robot_model_->getLinkModelsWithCollisionGeometry();
87 for (
auto link : links)
88 for (std::size_t j = 0; j < link->getShapes().size(); ++j)
94 index = link->getFirstCollisionBodyTransformIndex() + j;
102 std::make_shared<const fcl::CollisionObjectd>(link_geometry->collision_geometry_));
105 RCLCPP_ERROR(LOGGER,
"Unable to construct collision geometry for link '%s'", link->getName().c_str());
108 manager_ = std::make_unique<fcl::DynamicAABBTreeCollisionManagerd>();
111 observer_handle_ =
getWorld()->addObserver(
119 const std::vector<const moveit::core::LinkModel*>& links =
robot_model_->getLinkModelsWithCollisionGeometry();
124 for (
auto link : links)
125 for (std::size_t j = 0; j < link->getShapes().size(); ++j)
131 index = link->getFirstCollisionBodyTransformIndex() + j;
138 robot_fcl_objs_[index] = std::make_shared<const fcl::CollisionObjectd>(g->collision_geometry_);
141 RCLCPP_ERROR(LOGGER,
"Unable to construct collision geometry for link '%s'", link->getName().c_str());
144 manager_ = std::make_unique<fcl::DynamicAABBTreeCollisionManagerd>();
147 observer_handle_ =
getWorld()->addObserver(
154 getWorld()->removeObserver(observer_handle_);
162 manager_ = std::make_unique<fcl::DynamicAABBTreeCollisionManagerd>();
166 fcl_obj.second.registerTo(
manager_.get());
170 observer_handle_ =
getWorld()->addObserver(
175 std::vector<FCLGeometryConstPtr>& geoms)
const
178 const size_t num_shapes =
shapes.size();
179 geoms.reserve(num_shapes);
180 for (std::size_t i = 0; i < num_shapes; ++i)
191 for (std::size_t i = 0; i < obj->
shapes_.size(); ++i)
212 robot_geoms_[i]->collision_geometry_data_->shape_index),
215 coll_obj->setTransform(fcl_tf);
216 coll_obj->computeAABB();
221 std::vector<const moveit::core::AttachedBody*> ab;
223 for (
auto& body : ab)
225 std::vector<FCLGeometryConstPtr> objs;
227 const EigenSTL::vector_Isometry3d& ab_t = body->getGlobalCollisionBodyTransforms();
228 for (std::size_t k = 0; k < objs.size(); ++k)
229 if (objs[k]->collision_geometry_)
233 std::make_shared<fcl::CollisionObjectd>(objs[k]->collision_geometry_, fcl_tf));
243 manager.
manager_ = std::make_unique<fcl::DynamicAABBTreeCollisionManagerd>();
304 RCLCPP_ERROR(LOGGER,
"Continuous collision not implemented");
312 RCLCPP_ERROR(LOGGER,
"Not implemented");
347 checkFCLCapabilities(req);
359 checkFCLCapabilities(req);
375 jt->second.unregisterFrom(
manager_.get());
387 jt->second.registerTo(
manager_.get());
410 getWorld()->removeObserver(observer_handle_);
420 observer_handle_ =
getWorld()->addObserver(
434 it->second.unregisterFrom(
manager_.get());
451 for (
const auto& link : links)
456 for (std::size_t j = 0; j < lmodel->
getShapes().size(); ++j)
464 robot_fcl_objs_[index] = std::make_shared<const fcl::CollisionObjectd>(g->collision_geometry_);
469 RCLCPP_ERROR(LOGGER,
"Updating padding or scaling for unknown link: '%s'", link.c_str());
Definition of a structure for the allowed collision matrix. All elements in the collision world are r...
static const std::string NAME
FCL implementation of the CollisionEnv.
std::vector< FCLCollisionObjectConstPtr > robot_fcl_objs_
Vector of shared pointers to the FCL collision objects which make up the robot.
void constructFCLObjectRobot(const moveit::core::RobotState &state, FCLObject &fcl_obj) const
Out of the current robot state and its attached bodies construct an FCLObject which can then be used ...
void checkSelfCollision(const CollisionRequest &req, CollisionResult &res, const moveit::core::RobotState &state) const override
Check for robot self collision. Any collision between any pair of links is checked for,...
void setWorld(const WorldPtr &world) override
std::unique_ptr< fcl::BroadPhaseCollisionManagerd > manager_
FCL collision manager which handles the collision checking process.
void distanceRobot(const DistanceRequest &req, DistanceResult &res, const moveit::core::RobotState &state) const override
Compute the distance between a robot and the world.
void checkRobotCollisionHelper(const CollisionRequest &req, CollisionResult &res, const moveit::core::RobotState &state, const AllowedCollisionMatrix *acm) const
Bundles the different checkRobotCollision functions into a single function.
void checkRobotCollision(const CollisionRequest &req, CollisionResult &res, const moveit::core::RobotState &state) const override
Check whether the robot model is in collision with the world. Any collisions between a robot link and...
void distanceSelf(const DistanceRequest &req, DistanceResult &res, const moveit::core::RobotState &state) const override
The distance to self-collision given the robot is at state state.
void updatedPaddingOrScaling(const std::vector< std::string > &links) override
Updates the FCL collision geometry and objects saved in the CollisionRobotFCL members to reflect a ne...
void allocSelfCollisionBroadPhase(const moveit::core::RobotState &state, FCLManager &manager) const
Prepares for the collision check through constructing an FCL collision object out of the current robo...
void updateFCLObject(const std::string &id)
Updates the specified object in \m fcl_objs_ and in the manager from new data available in the World.
void constructFCLObjectWorld(const World::Object *obj, FCLObject &fcl_obj) const
Construct an FCL collision object from MoveIt's World::Object.
~CollisionEnvFCL() override
void checkSelfCollisionHelper(const CollisionRequest &req, CollisionResult &res, const moveit::core::RobotState &state, const AllowedCollisionMatrix *acm) const
Bundles the different checkSelfCollision functions into a single function.
std::vector< FCLGeometryConstPtr > robot_geoms_
Vector of shared pointers to the FCL geometry for the objects in fcl_objs_.
std::map< std::string, FCLObject > fcl_objs_
void getAttachedBodyObjects(const moveit::core::AttachedBody *ab, std::vector< FCLGeometryConstPtr > &geoms) const
Converts all shapes which make up an attached body into a vector of FCLGeometryConstPtr.
Provides the interface to the individual collision checking libraries.
virtual void setWorld(const WorldPtr &world)
moveit::core::RobotModelConstPtr robot_model_
The kinematic model corresponding to this collision model.
const WorldPtr & getWorld()
const std::map< std::string, double > & getLinkScale() const
Get the link scaling as a map (from link names to scale value)
const std::map< std::string, double > & getLinkPadding() const
Get the link paddings as a map (from link names to padding value)
const moveit::core::RobotModelConstPtr & getRobotModel() const
The kinematic model corresponding to this collision model.
Represents an action that occurred on an object in the world. Several bits may be set indicating seve...
Object defining bodies that can be attached to robot links.
const std::string & getAttachedLinkName() const
Get the name of the link this body is attached to.
const std::vector< shapes::ShapeConstPtr > & getShapes() const
Get the shapes that make up this attached body.
A link from the robot. Contains the constant transform applied to the link and its geometry.
int getFirstCollisionBodyTransformIndex() const
const std::vector< shapes::ShapeConstPtr > & getShapes() const
Get shape associated to the collision geometry for this link.
const std::string & getName() const
The name of this link.
Representation of a robot's state. This includes position, velocity, acceleration and effort.
const Eigen::Isometry3d & getCollisionBodyTransform(const std::string &link_name, std::size_t index)
Get the link transform w.r.t. the root link (model frame) of the RobotModel. This is typically the ro...
void getAttachedBodies(std::vector< const AttachedBody * > &attached_bodies) const
Get all bodies attached to the model corresponding to this state.
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 ...
std::shared_ptr< fcl::CollisionObjectd > FCLCollisionObjectPtr
void transform2fcl(const Eigen::Isometry3d &b, fcl::Transform3d &f)
Transforms an Eigen Isometry3d to FCL coordinate transformation.
std::shared_ptr< const fcl::CollisionObjectd > FCLCollisionObjectConstPtr
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::Transform3f Transform3d
Data structure which is passed to the collision callback function of the collision manager.
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.
Representation of a collision checking request.
std::string group_name
The group name to check collisions for (optional; if empty, assume the complete robot)
bool detailed_distance
If true, return detailed distance information. Distance must be set to true as well.
bool distance
If true, compute proximity distance.
Representation of a collision checking result.
DistanceResult distance_result
Distance data for each link.
double distance
Closest distance between two bodies.
Data structure which is passed to the distance callback function of the collision manager.
bool done
Indicates if distance query is finished.
Representation of a distance-reporting request.
void enableGroup(const moveit::core::RobotModelConstPtr &robot_model)
Compute active_components_only_ based on req_.
std::string group_name
The group name.
const AllowedCollisionMatrix * acm
The allowed collision matrix used to filter checks.
Result of a distance request.
DistanceResultsData minimum_distance
ResultsData for the two objects with the minimum distance.
double distance
The distance between two objects. If two objects are in collision, distance <= 0.
Bundles an FCLObject and a broadphase FCL collision manager.
std::shared_ptr< fcl::BroadPhaseCollisionManagerd > manager_
A general high-level object which consists of multiple FCLCollisionObjects. It is the top level data ...
std::vector< FCLCollisionObjectPtr > collision_objects_
std::vector< FCLGeometryConstPtr > collision_geometry_
Geometry data corresponding to collision_objects_.
void registerTo(fcl::BroadPhaseCollisionManagerd *manager)
A representation of an object.
EigenSTL::vector_Isometry3d global_shape_poses_
The poses of the corresponding entries in shapes_, relative to the world frame.
std::vector< shapes::ShapeConstPtr > shapes_
All the shapes making up this object.