moveit2
The MoveIt Motion Planning Framework for ROS 2.
collision_env_fcl.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2011, Willow Garage, Inc.
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of the copyright holder nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *********************************************************************/
34 
35 /* Author: Ioan Sucan, Jens Petit */
36 
40 
42 #include <rclcpp/logger.hpp>
43 #include <rclcpp/logging.hpp>
44 
45 #if (MOVEIT_FCL_VERSION >= FCL_VERSION_CHECK(0, 6, 0))
46 #include <fcl/broadphase/broadphase_dynamic_AABB_tree.h>
47 #endif
48 
49 namespace collision_detection
50 {
51 static const rclcpp::Logger LOGGER = rclcpp::get_logger("moveit_collision_detection_fcl.collision_env_fcl");
52 const std::string CollisionDetectorAllocatorFCL::NAME("FCL");
53 
54 namespace
55 {
56 // Check whether this FCL version supports the requested computations
57 void checkFCLCapabilities(const DistanceRequest& req)
58 {
59 #if MOVEIT_FCL_VERSION < FCL_VERSION_CHECK(0, 6, 0)
60  if (req.enable_nearest_points)
61  {
62  // Known issues:
63  // https://github.com/flexible-collision-library/fcl/issues/171,
64  // https://github.com/flexible-collision-library/fcl/pull/288
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 "
70  "to at least 0.6.0.",
71  FCL_MAJOR_VERSION, FCL_MINOR_VERSION, FCL_PATCH_VERSION);
72  }
73 #else
74  (void)(req); // silent -Wunused-parameter
75 #endif
76 }
77 } // namespace
78 
79 CollisionEnvFCL::CollisionEnvFCL(const moveit::core::RobotModelConstPtr& model, double padding, double scale)
80  : CollisionEnv(model, padding, scale)
81 {
82  const std::vector<const moveit::core::LinkModel*>& links = robot_model_->getLinkModelsWithCollisionGeometry();
83  std::size_t index;
84  robot_geoms_.resize(robot_model_->getLinkGeometryCount());
85  robot_fcl_objs_.resize(robot_model_->getLinkGeometryCount());
86  // we keep the same order of objects as what RobotState *::getLinkState() returns
87  for (auto link : links)
88  for (std::size_t j = 0; j < link->getShapes().size(); ++j)
89  {
90  FCLGeometryConstPtr link_geometry = createCollisionGeometry(link->getShapes()[j], getLinkScale(link->getName()),
91  getLinkPadding(link->getName()), link, j);
92  if (link_geometry)
93  {
94  index = link->getFirstCollisionBodyTransformIndex() + j;
95  robot_geoms_[index] = link_geometry;
96 
97  // Need to store the FCL object so the AABB does not get recreated every time.
98  // Every time this object is created, g->computeLocalAABB() is called which is
99  // very expensive and should only be calculated once. To update the AABB, use the
100  // collObj->setTransform and then call collObj->computeAABB() to transform the AABB.
102  std::make_shared<const fcl::CollisionObjectd>(link_geometry->collision_geometry_));
103  }
104  else
105  RCLCPP_ERROR(LOGGER, "Unable to construct collision geometry for link '%s'", link->getName().c_str());
106  }
107 
108  manager_ = std::make_unique<fcl::DynamicAABBTreeCollisionManagerd>();
109 
110  // request notifications about changes to new world
111  observer_handle_ = getWorld()->addObserver(
112  [this](const World::ObjectConstPtr& object, World::Action action) { notifyObjectChange(object, action); });
113 }
114 
115 CollisionEnvFCL::CollisionEnvFCL(const moveit::core::RobotModelConstPtr& model, const WorldPtr& world, double padding,
116  double scale)
117  : CollisionEnv(model, world, padding, scale)
118 {
119  const std::vector<const moveit::core::LinkModel*>& links = robot_model_->getLinkModelsWithCollisionGeometry();
120  std::size_t index;
121  robot_geoms_.resize(robot_model_->getLinkGeometryCount());
122  robot_fcl_objs_.resize(robot_model_->getLinkGeometryCount());
123  // we keep the same order of objects as what RobotState *::getLinkState() returns
124  for (auto link : links)
125  for (std::size_t j = 0; j < link->getShapes().size(); ++j)
126  {
127  FCLGeometryConstPtr g = createCollisionGeometry(link->getShapes()[j], getLinkScale(link->getName()),
128  getLinkPadding(link->getName()), link, j);
129  if (g)
130  {
131  index = link->getFirstCollisionBodyTransformIndex() + j;
132  robot_geoms_[index] = g;
133 
134  // Need to store the FCL object so the AABB does not get recreated every time.
135  // Every time this object is created, g->computeLocalAABB() is called which is
136  // very expensive and should only be calculated once. To update the AABB, use the
137  // collObj->setTransform and then call collObj->computeAABB() to transform the AABB.
138  robot_fcl_objs_[index] = std::make_shared<const fcl::CollisionObjectd>(g->collision_geometry_);
139  }
140  else
141  RCLCPP_ERROR(LOGGER, "Unable to construct collision geometry for link '%s'", link->getName().c_str());
142  }
143 
144  manager_ = std::make_unique<fcl::DynamicAABBTreeCollisionManagerd>();
145 
146  // request notifications about changes to new world
147  observer_handle_ = getWorld()->addObserver(
148  [this](const World::ObjectConstPtr& object, World::Action action) { notifyObjectChange(object, action); });
149  getWorld()->notifyObserverAllObjects(observer_handle_, World::CREATE);
150 }
151 
153 {
154  getWorld()->removeObserver(observer_handle_);
155 }
156 
157 CollisionEnvFCL::CollisionEnvFCL(const CollisionEnvFCL& other, const WorldPtr& world) : CollisionEnv(other, world)
158 {
159  robot_geoms_ = other.robot_geoms_;
161 
162  manager_ = std::make_unique<fcl::DynamicAABBTreeCollisionManagerd>();
163 
164  fcl_objs_ = other.fcl_objs_;
165  for (auto& fcl_obj : fcl_objs_)
166  fcl_obj.second.registerTo(manager_.get());
167  // manager_->update();
168 
169  // request notifications about changes to new world
170  observer_handle_ = getWorld()->addObserver(
171  [this](const World::ObjectConstPtr& object, World::Action action) { notifyObjectChange(object, action); });
172 }
173 
175  std::vector<FCLGeometryConstPtr>& geoms) const
176 {
177  const std::vector<shapes::ShapeConstPtr>& shapes = ab->getShapes();
178  const size_t num_shapes = shapes.size();
179  geoms.reserve(num_shapes);
180  for (std::size_t i = 0; i < num_shapes; ++i)
181  {
182  FCLGeometryConstPtr co = createCollisionGeometry(shapes[i], getLinkScale(ab->getAttachedLinkName()),
183  getLinkPadding(ab->getAttachedLinkName()), ab, i);
184  if (co)
185  geoms.push_back(co);
186  }
187 }
188 
190 {
191  for (std::size_t i = 0; i < obj->shapes_.size(); ++i)
192  {
193  FCLGeometryConstPtr g = createCollisionGeometry(obj->shapes_[i], obj);
194  if (g)
195  {
196  auto co = new fcl::CollisionObjectd(g->collision_geometry_, transform2fcl(obj->global_shape_poses_[i]));
197  fcl_obj.collision_objects_.push_back(FCLCollisionObjectPtr(co));
198  fcl_obj.collision_geometry_.push_back(g);
199  }
200  }
201 }
202 
204 {
205  fcl_obj.collision_objects_.reserve(robot_geoms_.size());
206  fcl::Transform3d fcl_tf;
207 
208  for (std::size_t i = 0; i < robot_geoms_.size(); ++i)
209  if (robot_geoms_[i] && robot_geoms_[i]->collision_geometry_)
210  {
211  transform2fcl(state.getCollisionBodyTransform(robot_geoms_[i]->collision_geometry_data_->ptr.link,
212  robot_geoms_[i]->collision_geometry_data_->shape_index),
213  fcl_tf);
214  auto coll_obj = new fcl::CollisionObjectd(*robot_fcl_objs_[i]);
215  coll_obj->setTransform(fcl_tf);
216  coll_obj->computeAABB();
217  fcl_obj.collision_objects_.push_back(FCLCollisionObjectPtr(coll_obj));
218  }
219 
220  // TODO: Implement a method for caching fcl::CollisionObject's for moveit::core::AttachedBody's
221  std::vector<const moveit::core::AttachedBody*> ab;
222  state.getAttachedBodies(ab);
223  for (auto& body : ab)
224  {
225  std::vector<FCLGeometryConstPtr> objs;
226  getAttachedBodyObjects(body, 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_)
230  {
231  transform2fcl(ab_t[k], fcl_tf);
232  fcl_obj.collision_objects_.push_back(
233  std::make_shared<fcl::CollisionObjectd>(objs[k]->collision_geometry_, fcl_tf));
234  // we copy the shared ptr to the CollisionGeometryData, as this is not stored by the class itself,
235  // and would be destroyed when objs goes out of scope.
236  fcl_obj.collision_geometry_.push_back(objs[k]);
237  }
238  }
239 }
240 
242 {
243  manager.manager_ = std::make_unique<fcl::DynamicAABBTreeCollisionManagerd>();
244 
245  constructFCLObjectRobot(state, manager.object_);
246  manager.object_.registerTo(manager.manager_.get());
247 }
248 
250  const moveit::core::RobotState& state) const
251 {
252  checkSelfCollisionHelper(req, res, state, nullptr);
253 }
254 
256  const moveit::core::RobotState& state, const AllowedCollisionMatrix& acm) const
257 {
258  checkSelfCollisionHelper(req, res, state, &acm);
259 }
260 
262  const moveit::core::RobotState& state,
263  const AllowedCollisionMatrix* acm) const
264 {
265  FCLManager manager;
266  allocSelfCollisionBroadPhase(state, manager);
267  CollisionData cd(&req, &res, acm);
269  manager.manager_->collide(&cd, &collisionCallback);
270  if (req.distance)
271  {
272  DistanceRequest dreq;
273  DistanceResult dres;
274 
275  dreq.group_name = req.group_name;
276  dreq.acm = acm;
277  dreq.enableGroup(getRobotModel());
278  distanceSelf(dreq, dres, state);
280  if (req.detailed_distance)
281  {
282  res.distance_result = dres;
283  }
284  }
285 }
286 
288  const moveit::core::RobotState& state) const
289 {
290  checkRobotCollisionHelper(req, res, state, nullptr);
291 }
292 
294  const moveit::core::RobotState& state,
295  const AllowedCollisionMatrix& acm) const
296 {
297  checkRobotCollisionHelper(req, res, state, &acm);
298 }
299 
301  const moveit::core::RobotState& /*state1*/,
302  const moveit::core::RobotState& /*state2*/) const
303 {
304  RCLCPP_ERROR(LOGGER, "Continuous collision not implemented");
305 }
306 
308  const moveit::core::RobotState& /*state1*/,
309  const moveit::core::RobotState& /*state2*/,
310  const AllowedCollisionMatrix& /*acm*/) const
311 {
312  RCLCPP_ERROR(LOGGER, "Not implemented");
313 }
314 
316  const moveit::core::RobotState& state,
317  const AllowedCollisionMatrix* acm) const
318 {
319  FCLObject fcl_obj;
320  constructFCLObjectRobot(state, fcl_obj);
321 
322  CollisionData cd(&req, &res, acm);
324  for (std::size_t i = 0; !cd.done_ && i < fcl_obj.collision_objects_.size(); ++i)
325  manager_->collide(fcl_obj.collision_objects_[i].get(), &cd, &collisionCallback);
326 
327  if (req.distance)
328  {
329  DistanceRequest dreq;
330  DistanceResult dres;
331 
332  dreq.group_name = req.group_name;
333  dreq.acm = acm;
334  dreq.enableGroup(getRobotModel());
335  distanceRobot(dreq, dres, state);
337  if (req.detailed_distance)
338  {
339  res.distance_result = dres;
340  }
341  }
342 }
343 
345  const moveit::core::RobotState& state) const
346 {
347  checkFCLCapabilities(req);
348 
349  FCLManager manager;
350  allocSelfCollisionBroadPhase(state, manager);
351  DistanceData drd(&req, &res);
352 
353  manager.manager_->distance(&drd, &distanceCallback);
354 }
355 
357  const moveit::core::RobotState& state) const
358 {
359  checkFCLCapabilities(req);
360 
361  FCLObject fcl_obj;
362  constructFCLObjectRobot(state, fcl_obj);
363 
364  DistanceData drd(&req, &res);
365  for (std::size_t i = 0; !drd.done && i < fcl_obj.collision_objects_.size(); ++i)
366  manager_->distance(fcl_obj.collision_objects_[i].get(), &drd, &distanceCallback);
367 }
368 
369 void CollisionEnvFCL::updateFCLObject(const std::string& id)
370 {
371  // remove FCL objects that correspond to this object
372  auto jt = fcl_objs_.find(id);
373  if (jt != fcl_objs_.end())
374  {
375  jt->second.unregisterFrom(manager_.get());
376  jt->second.clear();
377  }
378 
379  // check to see if we have this object
380  auto it = getWorld()->find(id);
381  if (it != getWorld()->end())
382  {
383  // construct FCL objects that correspond to this object
384  if (jt != fcl_objs_.end())
385  {
386  constructFCLObjectWorld(it->second.get(), jt->second);
387  jt->second.registerTo(manager_.get());
388  }
389  else
390  {
391  constructFCLObjectWorld(it->second.get(), fcl_objs_[id]);
392  fcl_objs_[id].registerTo(manager_.get());
393  }
394  }
395  else
396  {
397  if (jt != fcl_objs_.end())
398  fcl_objs_.erase(jt);
399  }
400 
401  // manager_->update();
402 }
403 
404 void CollisionEnvFCL::setWorld(const WorldPtr& world)
405 {
406  if (world == getWorld())
407  return;
408 
409  // turn off notifications about old world
410  getWorld()->removeObserver(observer_handle_);
411 
412  // clear out objects from old world
413  manager_->clear();
414  fcl_objs_.clear();
416 
417  CollisionEnv::setWorld(world);
418 
419  // request notifications about changes to new world
420  observer_handle_ = getWorld()->addObserver(
421  [this](const World::ObjectConstPtr& object, World::Action action) { notifyObjectChange(object, action); });
422 
423  // get notifications any objects already in the new world
424  getWorld()->notifyObserverAllObjects(observer_handle_, World::CREATE);
425 }
426 
427 void CollisionEnvFCL::notifyObjectChange(const ObjectConstPtr& obj, World::Action action)
428 {
429  if (action == World::DESTROY)
430  {
431  auto it = fcl_objs_.find(obj->id_);
432  if (it != fcl_objs_.end())
433  {
434  it->second.unregisterFrom(manager_.get());
435  it->second.clear();
436  fcl_objs_.erase(it);
437  }
439  }
440  else
441  {
442  updateFCLObject(obj->id_);
445  }
446 }
447 
448 void CollisionEnvFCL::updatedPaddingOrScaling(const std::vector<std::string>& links)
449 {
450  std::size_t index;
451  for (const auto& link : links)
452  {
453  const moveit::core::LinkModel* lmodel = robot_model_->getLinkModel(link);
454  if (lmodel)
455  {
456  for (std::size_t j = 0; j < lmodel->getShapes().size(); ++j)
457  {
458  FCLGeometryConstPtr g = createCollisionGeometry(lmodel->getShapes()[j], getLinkScale(lmodel->getName()),
459  getLinkPadding(lmodel->getName()), lmodel, j);
460  if (g)
461  {
462  index = lmodel->getFirstCollisionBodyTransformIndex() + j;
463  robot_geoms_[index] = g;
464  robot_fcl_objs_[index] = std::make_shared<const fcl::CollisionObjectd>(g->collision_geometry_);
465  }
466  }
467  }
468  else
469  RCLCPP_ERROR(LOGGER, "Updating padding or scaling for unknown link: '%s'", link.c_str());
470  }
471 }
472 
473 } // end of namespace collision_detection
Definition of a structure for the allowed collision matrix. All elements in the collision world are r...
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.
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.
Definition: collision_env.h:52
virtual void setWorld(const WorldPtr &world)
moveit::core::RobotModelConstPtr robot_model_
The kinematic model corresponding to this collision model.
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...
Definition: world.h:265
Object defining bodies that can be attached to robot links.
Definition: attached_body.h:58
const std::string & getAttachedLinkName() const
Get the name of the link this body is attached to.
Definition: attached_body.h:92
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.
Definition: link_model.h:72
int getFirstCollisionBodyTransformIndex() const
Definition: link_model.h:97
const std::vector< shapes::ShapeConstPtr > & getShapes() const
Get shape associated to the collision geometry for this link.
Definition: link_model.h:176
const std::string & getName() const
The name of this link.
Definition: link_model.h:86
Representation of a robot's state. This includes position, velocity, acceleration and effort.
Definition: robot_state.h:90
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...
Definition: robot_state.h:1379
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
Definition: fcl_compat.h:50
fcl::Transform3f Transform3d
Definition: fcl_compat.h:54
Definition: world.h:49
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.
Definition: world.h:79
EigenSTL::vector_Isometry3d global_shape_poses_
The poses of the corresponding entries in shapes_, relative to the world frame.
Definition: world.h:106
std::vector< shapes::ShapeConstPtr > shapes_
All the shapes making up this object.
Definition: world.h:96