collision_robot_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 Willow Garage 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 */
36 
38 
39 namespace collision_detection
40 {
41 CollisionRobotFCL::CollisionRobotFCL(const robot_model::RobotModelConstPtr& model, double padding, double scale)
42  : CollisionRobot(model, padding, scale)
43 {
44  const std::vector<const robot_model::LinkModel*>& links = robot_model_->getLinkModelsWithCollisionGeometry();
45  std::size_t index;
46  geoms_.resize(robot_model_->getLinkGeometryCount());
47  fcl_objs_.resize(robot_model_->getLinkGeometryCount());
48  // we keep the same order of objects as what RobotState *::getLinkState() returns
49  for (auto link : links)
50  for (std::size_t j = 0; j < link->getShapes().size(); ++j)
51  {
52  FCLGeometryConstPtr g = createCollisionGeometry(link->getShapes()[j], getLinkScale(link->getName()),
53  getLinkPadding(link->getName()), link, j);
54  if (g)
55  {
56  index = link->getFirstCollisionBodyTransformIndex() + j;
57  geoms_[index] = g;
58 
59  // Need to store the FCL object so the AABB does not get recreated every time.
60  // Every time this object is created, g->computeLocalAABB() is called which is
61  // very expensive and should only be calculated once. To update the AABB, use the
62  // collObj->setTransform and then call collObj->computeAABB() to transform the AABB.
63  fcl_objs_[index] = FCLCollisionObjectConstPtr(new fcl::CollisionObject(g->collision_geometry_));
64  }
65  else
66  ROS_ERROR_NAMED("collision_detection.fcl", "Unable to construct collision geometry for link '%s'",
67  link->getName().c_str());
68  }
69 }
70 
72 {
73  geoms_ = other.geoms_;
74  fcl_objs_ = other.fcl_objs_;
75 }
76 
78  std::vector<FCLGeometryConstPtr>& geoms) const
79 {
80  const std::vector<shapes::ShapeConstPtr>& shapes = ab->getShapes();
81  for (std::size_t i = 0; i < shapes.size(); ++i)
82  {
83  FCLGeometryConstPtr co = createCollisionGeometry(shapes[i], ab, i);
84  if (co)
85  geoms.push_back(co);
86  }
87 }
88 
90 {
91  fcl_obj.collision_objects_.reserve(geoms_.size());
92  fcl::Transform3f fcl_tf;
93 
94  for (std::size_t i = 0; i < geoms_.size(); ++i)
95  if (geoms_[i] && geoms_[i]->collision_geometry_)
96  {
97  transform2fcl(state.getCollisionBodyTransform(geoms_[i]->collision_geometry_data_->ptr.link,
98  geoms_[i]->collision_geometry_data_->shape_index),
99  fcl_tf);
100  auto collObj = new fcl::CollisionObject(*fcl_objs_[i]);
101  collObj->setTransform(fcl_tf);
102  collObj->computeAABB();
103  fcl_obj.collision_objects_.push_back(FCLCollisionObjectPtr(collObj));
104  }
105 
106  // TODO: Implement a method for caching fcl::CollisionObject's for robot_state::AttachedBody's
107  std::vector<const robot_state::AttachedBody*> ab;
108  state.getAttachedBodies(ab);
109  for (auto& body : ab)
110  {
111  std::vector<FCLGeometryConstPtr> objs;
112  getAttachedBodyObjects(body, objs);
113  const EigenSTL::vector_Affine3d& ab_t = body->getGlobalCollisionBodyTransforms();
114  for (std::size_t k = 0; k < objs.size(); ++k)
115  if (objs[k]->collision_geometry_)
116  {
117  transform2fcl(ab_t[k], fcl_tf);
118  fcl_obj.collision_objects_.push_back(
119  FCLCollisionObjectPtr(new fcl::CollisionObject(objs[k]->collision_geometry_, fcl_tf)));
120  // we copy the shared ptr to the CollisionGeometryData, as this is not stored by the class itself,
121  // and would be destroyed when objs goes out of scope.
122  fcl_obj.collision_geometry_.push_back(objs[k]);
123  }
124  }
125 }
126 
128 {
129  auto m = new fcl::DynamicAABBTreeCollisionManager();
130  // m->tree_init_level = 2;
131  manager.manager_.reset(m);
132  constructFCLObject(state, manager.object_);
133  manager.object_.registerTo(manager.manager_.get());
134  // manager.manager_->update();
135 }
136 
138  const robot_state::RobotState& state) const
139 {
140  checkSelfCollisionHelper(req, res, state, nullptr);
141 }
142 
144  const robot_state::RobotState& state,
145  const AllowedCollisionMatrix& acm) const
146 {
147  checkSelfCollisionHelper(req, res, state, &acm);
148 }
149 
151  const robot_state::RobotState& state1,
152  const robot_state::RobotState& state2) const
153 {
154  ROS_ERROR_NAMED("collision_detection.fcl", "FCL continuous collision checking not yet implemented");
155 }
156 
158  const robot_state::RobotState& state1, const robot_state::RobotState& state2,
159  const AllowedCollisionMatrix& acm) const
160 {
161  ROS_ERROR_NAMED("collision_detection.fcl", "FCL continuous collision checking not yet implemented");
162 }
163 
165  const robot_state::RobotState& state,
166  const AllowedCollisionMatrix* acm) const
167 {
168  FCLManager manager;
169  allocSelfCollisionBroadPhase(state, manager);
170  CollisionData cd(&req, &res, acm);
172  manager.manager_->collide(&cd, &collisionCallback);
173  if (req.distance)
174  {
175  DistanceRequest dreq;
176  DistanceResult dres;
177 
178  dreq.group_name = req.group_name;
179  dreq.acm = acm;
180  dreq.enableGroup(getRobotModel());
181  distanceSelf(dreq, dres, state);
183  }
184 }
185 
187  const robot_state::RobotState& state, const CollisionRobot& other_robot,
188  const robot_state::RobotState& other_state) const
189 {
190  checkOtherCollisionHelper(req, res, state, other_robot, other_state, nullptr);
191 }
192 
194  const robot_state::RobotState& state, const CollisionRobot& other_robot,
195  const robot_state::RobotState& other_state,
196  const AllowedCollisionMatrix& acm) const
197 {
198  checkOtherCollisionHelper(req, res, state, other_robot, other_state, &acm);
199 }
200 
202  const robot_state::RobotState& state1,
203  const robot_state::RobotState& state2, const CollisionRobot& other_robot,
204  const robot_state::RobotState& other_state1,
205  const robot_state::RobotState& other_state2) const
206 {
207  ROS_ERROR_NAMED("collision_detection.fcl", "FCL continuous collision checking not yet implemented");
208 }
209 
211  const robot_state::RobotState& state1,
212  const robot_state::RobotState& state2, const CollisionRobot& other_robot,
213  const robot_state::RobotState& other_state1,
214  const robot_state::RobotState& other_state2,
215  const AllowedCollisionMatrix& acm) const
216 {
217  ROS_ERROR_NAMED("collision_detection.fcl", "FCL continuous collision checking not yet implemented");
218 }
219 
221  const robot_state::RobotState& state,
222  const CollisionRobot& other_robot,
223  const robot_state::RobotState& other_state,
224  const AllowedCollisionMatrix* acm) const
225 {
226  FCLManager manager;
227  allocSelfCollisionBroadPhase(state, manager);
228 
229  const CollisionRobotFCL& fcl_rob = dynamic_cast<const CollisionRobotFCL&>(other_robot);
230  FCLObject other_fcl_obj;
231  fcl_rob.constructFCLObject(other_state, other_fcl_obj);
232 
233  CollisionData cd(&req, &res, acm);
235  for (std::size_t i = 0; !cd.done_ && i < other_fcl_obj.collision_objects_.size(); ++i)
236  manager.manager_->collide(other_fcl_obj.collision_objects_[i].get(), &cd, &collisionCallback);
237 
238  if (req.distance)
239  {
240  DistanceRequest dreq;
241  DistanceResult dres;
242 
243  dreq.group_name = req.group_name;
244  dreq.acm = acm;
245  dreq.enableGroup(getRobotModel());
246  distanceOther(dreq, dres, state, other_robot, other_state);
248  }
249 }
250 
251 void CollisionRobotFCL::updatedPaddingOrScaling(const std::vector<std::string>& links)
252 {
253  std::size_t index;
254  for (const auto& link : links)
255  {
256  const robot_model::LinkModel* lmodel = robot_model_->getLinkModel(link);
257  if (lmodel)
258  {
259  for (std::size_t j = 0; j < lmodel->getShapes().size(); ++j)
260  {
261  FCLGeometryConstPtr g = createCollisionGeometry(lmodel->getShapes()[j], getLinkScale(lmodel->getName()),
262  getLinkPadding(lmodel->getName()), lmodel, j);
263  if (g)
264  {
265  index = lmodel->getFirstCollisionBodyTransformIndex() + j;
266  geoms_[index] = g;
267  fcl_objs_[index] = FCLCollisionObjectConstPtr(new fcl::CollisionObject(g->collision_geometry_));
268  }
269  }
270  }
271  else
272  ROS_ERROR_NAMED("collision_detection.fcl", "Updating padding or scaling for unknown link: '%s'", link.c_str());
273  }
274 }
275 
277  const robot_state::RobotState& state) const
278 {
279  FCLManager manager;
280  allocSelfCollisionBroadPhase(state, manager);
281  DistanceData drd(&req, &res);
282 
283  manager.manager_->distance(&drd, &distanceCallback);
284 }
285 
287  const robot_state::RobotState& state, const CollisionRobot& other_robot,
288  const robot_state::RobotState& other_state) const
289 {
290  FCLManager manager;
291  allocSelfCollisionBroadPhase(state, manager);
292 
293  const CollisionRobotFCL& fcl_rob = dynamic_cast<const CollisionRobotFCL&>(other_robot);
294  FCLObject other_fcl_obj;
295  fcl_rob.constructFCLObject(other_state, other_fcl_obj);
296 
297  DistanceData drd(&req, &res);
298  for (std::size_t i = 0; !drd.done && i < other_fcl_obj.collision_objects_.size(); ++i)
299  manager.manager_->distance(other_fcl_obj.collision_objects_[i].get(), &drd, &distanceCallback);
300 }
301 
302 } // end of namespace collision_detection
const std::string & getName() const
The name of this link.
Definition: link_model.h:81
void getAttachedBodies(std::vector< const AttachedBody * > &attached_bodies) const
Get all bodies attached to the model corresponding to this state.
void constructFCLObject(const robot_state::RobotState &state, FCLObject &fcl_obj) const
bool done_
Flag indicating whether collision checking is complete.
std::vector< Eigen::Affine3d, Eigen::aligned_allocator< Eigen::Affine3d > > vector_Affine3d
FCLGeometryConstPtr createCollisionGeometry(const shapes::ShapeConstPtr &shape, const robot_model::LinkModel *link, int shape_index)
virtual void checkOtherCollision(const CollisionRequest &req, CollisionResult &res, const robot_state::RobotState &state, const CollisionRobot &other_robot, const robot_state::RobotState &other_state) const
Check for collision with a different robot (possibly a different kinematic model as well)...
const AllowedCollisionMatrix * acm
The allowed collision matrix used to filter checks.
bool collisionCallback(fcl::CollisionObject *o1, fcl::CollisionObject *o2, void *data)
DistanceResultsData minimum_distance
ResultsData for the two objects with the minimum distance.
CollisionRobotFCL(const robot_model::RobotModelConstPtr &kmodel, double padding=0.0, double scale=1.0)
const std::map< std::string, double > & getLinkPadding() const
Get the link paddings as a map (from link names to padding value)
void allocSelfCollisionBroadPhase(const robot_state::RobotState &state, FCLManager &manager) const
const robot_model::RobotModelConstPtr & getRobotModel() const
The kinematic model corresponding to this collision model.
std::vector< FCLGeometryConstPtr > geoms_
int getFirstCollisionBodyTransformIndex() const
Definition: link_model.h:97
Generic interface to collision detection.
void enableGroup(const robot_model::RobotModelConstPtr &kmodel)
Compute active_components_only_ based on req_.
robot_model::RobotModelConstPtr robot_model_
The kinematic model corresponding to this collision model.
std::shared_ptr< fcl::BroadPhaseCollisionManager > manager_
const std::vector< shapes::ShapeConstPtr > & getShapes() const
Get the shapes that make up this attached body.
Definition: attached_body.h:88
virtual void checkSelfCollision(const CollisionRequest &req, CollisionResult &res, const robot_state::RobotState &state) const
Check for self collision. Any collision between any pair of links is checked for, NO collisions are i...
unsigned int index
void checkSelfCollisionHelper(const CollisionRequest &req, CollisionResult &res, const robot_state::RobotState &state, const AllowedCollisionMatrix *acm) const
const Eigen::Affine3d & getCollisionBodyTransform(const LinkModel *link, std::size_t index)
Definition: robot_state.h:1384
Definition of a structure for the allowed collision matrix. All elements in the collision world are r...
void getAttachedBodyObjects(const robot_state::AttachedBody *ab, std::vector< FCLGeometryConstPtr > &geoms) const
This class represents a collision model of the robot and can be used for self collision checks (to ch...
std::string group_name
The group name to check collisions for (optional; if empty, assume the complete robot) ...
std::vector< FCLCollisionObjectConstPtr > fcl_objs_
const std::vector< shapes::ShapeConstPtr > & getShapes() const
Get shape associated to the collision geometry for this link.
Definition: link_model.h:174
double distance
The distance between two objects. If two objects are in collision, distance <= 0. ...
std::shared_ptr< const fcl::CollisionObject > FCLCollisionObjectConstPtr
const std::map< std::string, double > & getLinkScale() const
Get the link scaling as a map (from link names to scale value)
void enableGroup(const robot_model::RobotModelConstPtr &kmodel)
Compute active_components_only_ based on req_.
virtual void distanceSelf(const DistanceRequest &req, DistanceResult &res, const robot_state::RobotState &state) const override
The distance to self-collision given the robot is at state state.
void transform2fcl(const Eigen::Affine3d &b, fcl::Transform3f &f)
#define ROS_ERROR_NAMED(name,...)
Representation of a robot&#39;s state. This includes position, velocity, acceleration and effort...
Definition: robot_state.h:123
A link from the robot. Contains the constant transform applied to the link and its geometry...
Definition: link_model.h:72
virtual void updatedPaddingOrScaling(const std::vector< std::string > &links)
When the scale or padding is changed for a set of links by any of the functions in this class...
void checkOtherCollisionHelper(const CollisionRequest &req, CollisionResult &res, const robot_state::RobotState &state, const CollisionRobot &other_robot, const robot_state::RobotState &other_state, const AllowedCollisionMatrix *acm) const
bool distanceCallback(fcl::CollisionObject *o1, fcl::CollisionObject *o2, void *data, double &min_dist)
Object defining bodies that can be attached to robot links. This is useful when handling objects pick...
Definition: attached_body.h:56
std::shared_ptr< fcl::CollisionObject > FCLCollisionObjectPtr
void registerTo(fcl::BroadPhaseCollisionManager *manager)
virtual void distanceOther(const DistanceRequest &req, DistanceResult &res, const robot_state::RobotState &state, const CollisionRobot &other_robot, const robot_state::RobotState &other_state) const override
The distance to self-collision given the robot is at state state.


moveit_core
Author(s): Ioan Sucan , Sachin Chitta , Acorn Pooley
autogenerated on Wed Jul 10 2019 04:03:04