Go to the documentation of this file.
43 #if (MOVEIT_FCL_VERSION >= FCL_VERSION_CHECK(0, 6, 0))
49 static const std::string
NAME =
"FCL";
50 constexpr
char LOGNAME[] =
"collision_detection.fcl";
55 void checkFCLCapabilities(
const DistanceRequest& req)
57 #if MOVEIT_FCL_VERSION < FCL_VERSION_CHECK(0, 6, 0)
58 if (req.enable_nearest_points)
64 "You requested a distance check with enable_nearest_points=true, "
65 "but the FCL version MoveIt was compiled against (%d.%d.%d) "
66 "is known to return bogus nearest points. Please update your FCL "
68 FCL_MAJOR_VERSION, FCL_MINOR_VERSION, FCL_PATCH_VERSION);
77 : CollisionEnv(model, padding, scale)
79 const std::vector<const moveit::core::LinkModel*>& links =
robot_model_->getLinkModelsWithCollisionGeometry();
84 for (
auto link : links)
85 for (std::size_t j = 0; j < link->getShapes().size(); ++j)
91 index = link->getFirstCollisionBodyTransformIndex() + j;
92 robot_geoms_[
index] = link_geometry;
98 robot_fcl_objs_[
index] =
102 ROS_ERROR_NAMED(
LOGNAME,
"Unable to construct collision geometry for link '%s'", link->getName().c_str());
105 manager_ = std::make_unique<fcl::DynamicAABBTreeCollisionManagerd>();
114 : CollisionEnv(model, world, padding, scale)
116 const std::vector<const moveit::core::LinkModel*>& links =
robot_model_->getLinkModelsWithCollisionGeometry();
121 for (
auto link : links)
122 for (std::size_t j = 0; j < link->getShapes().size(); ++j)
128 index = link->getFirstCollisionBodyTransformIndex() + j;
138 ROS_ERROR_NAMED(
LOGNAME,
"Unable to construct collision geometry for link '%s'", link->getName().c_str());
141 manager_ = std::make_unique<fcl::DynamicAABBTreeCollisionManagerd>();
159 manager_ = std::make_unique<fcl::DynamicAABBTreeCollisionManagerd>();
163 fcl_obj.second.registerTo(
manager_.get());
168 [
this](
const World::ObjectConstPtr&
object, World::Action action) {
notifyObjectChange(
object, action); });
172 std::vector<FCLGeometryConstPtr>& geoms)
const
175 const size_t num_shapes =
shapes.size();
176 geoms.reserve(num_shapes);
177 for (std::size_t i = 0; i < num_shapes; ++i)
188 for (std::size_t i = 0; i <
obj->shapes_.size(); ++i)
209 robot_geoms_[i]->collision_geometry_data_->shape_index),
212 coll_obj->setTransform(fcl_tf);
213 coll_obj->computeAABB();
218 std::vector<const moveit::core::AttachedBody*> ab;
220 for (
auto& body : ab)
222 std::vector<FCLGeometryConstPtr> objs;
225 for (std::size_t k = 0; k < objs.size(); ++k)
226 if (objs[k]->collision_geometry_)
230 std::make_shared<fcl::CollisionObjectd>(objs[k]->collision_geometry_, fcl_tf));
240 manager.manager_ = std::make_unique<fcl::DynamicAABBTreeCollisionManagerd>();
243 manager.object_.registerTo(manager.manager_.get());
260 const AllowedCollisionMatrix* acm)
const
264 CollisionData cd(&req, &res, acm);
269 DistanceRequest dreq;
272 dreq.group_name = req.group_name;
277 if (req.detailed_distance)
279 res.distance_result = dres;
307 const AllowedCollisionMatrix& )
const
314 const AllowedCollisionMatrix* acm)
const
334 if (req.detailed_distance)
336 res.distance_result = dres;
344 checkFCLCapabilities(req);
356 checkFCLCapabilities(req);
372 jt->second.unregisterFrom(
manager_.get());
384 jt->second.registerTo(
manager_.get());
431 it->second.unregisterFrom(
manager_.get());
446 if (
obj->global_shape_poses_.size() != it->second.collision_objects_.size())
449 "Cannot move shapes, shape size mismatch between FCL object and world object: '%s'. Respectively "
451 obj->id_.c_str(), it->second.collision_objects_.size(), it->second.collision_objects_.size());
455 for (std::size_t i = 0; i < it->second.collision_objects_.size(); ++i)
457 it->second.collision_objects_[i]->setTransform(
transform2fcl(
obj->global_shape_poses_[i]));
460 it->second.collision_geometry_[i]->collision_geometry_->computeLocalAABB();
461 it->second.collision_objects_[i]->computeAABB();
466 it->second.unregisterFrom(
manager_.get());
467 it->second.registerTo(
manager_.get());
480 for (
const auto& link : links)
485 for (std::size_t j = 0; j < lmodel->
getShapes().size(); ++j)
A link from the robot. Contains the constant transform applied to the link and its geometry.
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.
World::ObserverHandle observer_handle_
std::shared_ptr< const fcl::CollisionObjectd > FCLCollisionObjectConstPtr
#define ROS_ERROR_THROTTLE_NAMED(period, name,...)
const moveit::core::RobotModelConstPtr & getRobotModel() const
The kinematic model corresponding to this collision model.
std::map< std::string, FCLObject > fcl_objs_
std::vector< Eigen::Isometry3d, Eigen::aligned_allocator< Eigen::Isometry3d > > vector_Isometry3d
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 updateFCLObject(const std::string &id)
Updates the specified object in fcl_objs_ and in the manager from new data available in the World.
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...
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.
std::shared_ptr< fcl::BroadPhaseCollisionManagerd > manager_
Transform3< double > Transform3d
Represents an action that occurred on an object in the world. Several bits may be set indicating seve...
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 ...
#define ROS_ERROR_NAMED(name,...)
Representation of a robot's state. This includes position, velocity, acceleration and effort.
std::vector< FCLCollisionObjectConstPtr > robot_fcl_objs_
Vector of shared pointers to the FCL collision objects which make up the robot.
CollisionObject< S > * obj
Representation of a collision checking request.
std::vector< FCLCollisionObjectPtr > collision_objects_
void cleanCollisionGeometryCache()
Increases the counter of the caches which can trigger the cleaning of expired entries from them.
Object defining bodies that can be attached to robot links.
Definition of a structure for the allowed collision matrix.
static const std::string NAME
void transform2fcl(const Eigen::Isometry3d &b, fcl::Transform3d &f)
Transforms an Eigen Isometry3d to FCL coordinate transformation.
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...
Representation of a collision checking result.
void constructFCLObjectWorld(const World::Object *obj, FCLObject &fcl_obj) const
Construct an FCL collision object from MoveIt's World::Object.
std::shared_ptr< fcl::CollisionObjectd > FCLCollisionObjectPtr
const AllowedCollisionMatrix * acm
The allowed collision matrix used to filter checks.
std::string group_name
The group name.
void getAttachedBodies(std::vector< const AttachedBody * > &attached_bodies) const
Get all bodies attached to the model corresponding to this state.
int getFirstCollisionBodyTransformIndex() const
A representation of an object.
Bundles an FCLObject and a broadphase FCL collision manager.
const std::map< std::string, double > & getLinkScale() const
Get the link scaling as a map (from link names to scale value)
DistanceResultsData minimum_distance
ResultsData for the two objects with the minimum distance.
FCLGeometryConstPtr createCollisionGeometry(const shapes::ShapeConstPtr &shape, const moveit::core::LinkModel *link, int shape_index)
Create new FCLGeometry object out of robot link model.
void setWorld(const WorldPtr &world) override
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 notifyObjectChange(const ObjectConstPtr &obj, World::Action action)
Result of a distance request.
const std::string & getAttachedLinkName() const
Get the name of the link this body is attached to.
std::vector< FCLGeometryConstPtr > robot_geoms_
Vector of shared pointers to the FCL geometry for the objects in fcl_objs_.
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...
World::ObserverHandle observer_handle_
const std::map< std::string, double > & getLinkPadding() const
Get the link paddings as a map (from link names to padding value)
const std::string & getName() const override
const std::vector< shapes::ShapeConstPtr > & getShapes() const
Get the shapes that make up this attached body.
A general high-level object which consists of multiple FCLCollisionObjects. It is the top level data ...
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 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 ...
Data structure which is passed to the distance callback function of the collision manager.
double distance
The distance between two objects. If two objects are in collision, distance <= 0.
std::vector< FCLGeometryConstPtr > collision_geometry_
Geometry data corresponding to collision_objects_.
virtual void setWorld(const WorldPtr &world)
const std::vector< shapes::ShapeConstPtr > & getShapes() const
Get shape associated to the collision geometry for this link.
~CollisionEnvFCL() override
const std::string & getName() const
The name of this link.
Data structure which is passed to the collision callback function of the collision manager.
Representation of a distance-reporting request.
void getAttachedBodyObjects(const moveit::core::AttachedBody *ab, std::vector< FCLGeometryConstPtr > &geoms) const
Converts all shapes which make up an atttached body into a vector of FCLGeometryConstPtr.
void enableGroup(const moveit::core::RobotModelConstPtr &robot_model)
Compute active_components_only_ based on req_.
void notifyObjectChange(const ObjectConstPtr &obj, World::Action action)
Callback function executed for each change to the world environment.
moveit::core::RobotModelConstPtr robot_model_
The kinematic model corresponding to this collision model.
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...
const WorldPtr & getWorld()
CollisionObject< double > CollisionObjectd
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,...
moveit_core
Author(s): Ioan Sucan
, Sachin Chitta , Acorn Pooley
autogenerated on Sun Nov 3 2024 03:26:14