collision_env_distance_field.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2012, 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 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: E. Gil Jones */
36 
38 #include <ros/console.h>
39 #include <ros/assert.h>
40 #include <tf2_eigen/tf2_eigen.h>
45 #include <functional>
46 #include <memory>
47 #include <utility>
48 
49 namespace collision_detection
50 {
51 namespace
52 {
53 static const std::string NAME = "DISTANCE_FIELD";
54 const double EPSILON = 0.001f;
55 } // namespace
56 
58  const moveit::core::RobotModelConstPtr& robot_model,
59  const std::map<std::string, std::vector<CollisionSphere>>& link_body_decompositions, double size_x, double size_y,
60  double size_z, const Eigen::Vector3d& origin, bool use_signed_distance_field, double resolution,
61  double collision_tolerance, double max_propogation_distance, double /*padding*/, double /*scale*/)
62  : CollisionEnv(robot_model)
63 {
64  initialize(link_body_decompositions, Eigen::Vector3d(size_x, size_y, size_z), origin, use_signed_distance_field,
65  resolution, collision_tolerance, max_propogation_distance);
66 
67  setPadding(0.0);
68 
69  distance_field_cache_entry_world_ = generateDistanceFieldCacheEntryWorld();
70 
71  // request notifications about changes to world
72  observer_handle_ = getWorld()->addObserver(
73  [this](const World::ObjectConstPtr& object, World::Action action) { return notifyObjectChange(object, action); });
74 }
75 
77  const moveit::core::RobotModelConstPtr& robot_model, const WorldPtr& world,
78  const std::map<std::string, std::vector<CollisionSphere>>& link_body_decompositions, double size_x, double size_y,
79  double size_z, const Eigen::Vector3d& origin, bool use_signed_distance_field, double resolution,
80  double collision_tolerance, double max_propogation_distance, double padding, double scale)
81  : CollisionEnv(robot_model, world, padding, scale)
82 {
83  initialize(link_body_decompositions, Eigen::Vector3d(size_x, size_y, size_z), origin, use_signed_distance_field,
84  resolution, collision_tolerance, max_propogation_distance);
85 
86  distance_field_cache_entry_world_ = generateDistanceFieldCacheEntryWorld();
87 
88  // request notifications about changes to world
89  observer_handle_ = getWorld()->addObserver(
90  [this](const World::ObjectConstPtr& object, World::Action action) { return notifyObjectChange(object, action); });
91 
92  getWorld()->notifyObserverAllObjects(observer_handle_, World::CREATE);
93 }
94 
95 CollisionEnvDistanceField::CollisionEnvDistanceField(const CollisionEnvDistanceField& other, const WorldPtr& world)
96  : CollisionEnv(other, world)
97 {
98  size_ = other.size_;
99  origin_ = other.origin_;
100 
101  use_signed_distance_field_ = other.use_signed_distance_field_;
102  resolution_ = other.resolution_;
103  collision_tolerance_ = other.collision_tolerance_;
104  max_propogation_distance_ = other.max_propogation_distance_;
105  link_body_decomposition_vector_ = other.link_body_decomposition_vector_;
106  link_body_decomposition_index_map_ = other.link_body_decomposition_index_map_;
107  in_group_update_map_ = other.in_group_update_map_;
109  pregenerated_group_state_representation_map_ = other.pregenerated_group_state_representation_map_;
110  planning_scene_ = std::make_shared<planning_scene::PlanningScene>(robot_model_);
111 
112  // request notifications about changes to world
113  observer_handle_ = getWorld()->addObserver(
114  [this](const World::ObjectConstPtr& object, World::Action action) { return notifyObjectChange(object, action); });
115  getWorld()->notifyObserverAllObjects(observer_handle_, World::CREATE);
116 }
117 
119 {
120  getWorld()->removeObserver(observer_handle_);
121 }
122 
124  const std::map<std::string, std::vector<CollisionSphere>>& link_body_decompositions, const Eigen::Vector3d& size,
125  const Eigen::Vector3d& origin, bool use_signed_distance_field, double resolution, double collision_tolerance,
126  double max_propogation_distance)
127 {
128  size_ = size;
129  origin_ = origin;
130  use_signed_distance_field_ = use_signed_distance_field;
131  resolution_ = resolution;
132  collision_tolerance_ = collision_tolerance;
133  max_propogation_distance_ = max_propogation_distance;
134  addLinkBodyDecompositions(resolution_, link_body_decompositions);
136  planning_scene_ = std::make_shared<planning_scene::PlanningScene>(robot_model_);
137 
138  const std::vector<const moveit::core::JointModelGroup*>& jmg = robot_model_->getJointModelGroups();
139  for (const moveit::core::JointModelGroup* jm : jmg)
140  {
141  std::map<std::string, bool> updated_group_entry;
142  std::vector<std::string> links = jm->getUpdatedLinkModelsWithGeometryNames();
143  for (const std::string& link : links)
144  {
145  updated_group_entry[link] = true;
146  }
147  in_group_update_map_[jm->getName()] = updated_group_entry;
148  state.updateLinkTransforms();
149  DistanceFieldCacheEntryPtr dfce =
150  generateDistanceFieldCacheEntry(jm->getName(), state, &planning_scene_->getAllowedCollisionMatrix(), false);
152  }
153  // add special case for empty group name
154  std::map<std::string, bool> updated_group_entry;
155  std::vector<std::string> links = robot_model_->getLinkModelNamesWithCollisionGeometry();
156  for (const std::string& link : links)
157  {
158  updated_group_entry[link] = true;
159  }
160  in_group_update_map_[""] = updated_group_entry;
161 }
162 
164  const std::string& group_name, const moveit::core::RobotState& state,
165  const collision_detection::AllowedCollisionMatrix* acm, GroupStateRepresentationPtr& gsr,
166  bool generate_distance_field) const
167 {
168  DistanceFieldCacheEntryConstPtr dfce = getDistanceFieldCacheEntry(group_name, state, acm);
169  if (!dfce || (generate_distance_field && !dfce->distance_field_))
170  {
171  // ROS_DEBUG_STREAM_NAMED("collision_distance_field", "Generating new
172  // DistanceFieldCacheEntry for CollisionRobot");
173  DistanceFieldCacheEntryPtr new_dfce =
174  generateDistanceFieldCacheEntry(group_name, state, acm, generate_distance_field);
175  boost::mutex::scoped_lock slock(update_cache_lock_);
176  (const_cast<CollisionEnvDistanceField*>(this))->distance_field_cache_entry_ = new_dfce;
177  dfce = new_dfce;
178  }
179  getGroupStateRepresentation(dfce, state, gsr);
180 }
181 
184  const moveit::core::RobotState& state,
186  GroupStateRepresentationPtr& gsr) const
187 {
188  if (!gsr)
189  {
190  generateCollisionCheckingStructures(req.group_name, state, acm, gsr, true);
191  }
192  else
193  {
195  }
196  // ros::WallTime n = ros::WallTime::now();
197  bool done = getSelfCollisions(req, res, gsr);
198 
199  if (!done)
200  {
201  getIntraGroupCollisions(req, res, gsr);
202  ROS_DEBUG_COND(res.collision, "Intra Group Collision found");
203  }
204 }
205 
206 DistanceFieldCacheEntryConstPtr
207 CollisionEnvDistanceField::getDistanceFieldCacheEntry(const std::string& group_name,
208  const moveit::core::RobotState& state,
210 {
211  DistanceFieldCacheEntryConstPtr ret;
213  {
214  ROS_DEBUG_STREAM("No current Distance field cache entry");
215  return ret;
216  }
217  DistanceFieldCacheEntryConstPtr cur = distance_field_cache_entry_;
218  if (group_name != cur->group_name_)
219  {
220  ROS_DEBUG("No cache entry as group name changed from %s to %s", cur->group_name_.c_str(), group_name.c_str());
221  return ret;
222  }
223  else if (!compareCacheEntryToState(cur, state))
224  {
225  // Regenerating distance field as state has changed from last time
226  // ROS_DEBUG_STREAM_NAMED("collision_distance_field", "Regenerating distance field as
227  // state has changed from last time");
228  return ret;
229  }
230  else if (acm && !compareCacheEntryToAllowedCollisionMatrix(cur, *acm))
231  {
232  ROS_DEBUG("Regenerating distance field as some relevant part of the acm changed");
233  return ret;
234  }
235  return cur;
236 }
237 
240  const moveit::core::RobotState& state) const
241 {
242  GroupStateRepresentationPtr gsr;
243  checkSelfCollisionHelper(req, res, state, nullptr, gsr);
244 }
245 
248  const moveit::core::RobotState& state,
249  GroupStateRepresentationPtr& gsr) const
250 {
251  checkSelfCollisionHelper(req, res, state, nullptr, gsr);
252 }
253 
256  const moveit::core::RobotState& state,
258 {
259  GroupStateRepresentationPtr gsr;
260  checkSelfCollisionHelper(req, res, state, &acm, gsr);
261 }
262 
265  const moveit::core::RobotState& state,
267  GroupStateRepresentationPtr& gsr) const
268 {
269  if (gsr)
270  {
271  ROS_WARN("Shouldn't be calling this function with initialized gsr - ACM "
272  "will be ignored");
273  }
274  checkSelfCollisionHelper(req, res, state, &acm, gsr);
275 }
276 
279  GroupStateRepresentationPtr& gsr) const
280 {
281  for (unsigned int i = 0; i < gsr->dfce_->link_names_.size() + gsr->dfce_->attached_body_names_.size(); i++)
282  {
283  bool is_link = i < gsr->dfce_->link_names_.size();
284  if ((is_link && !gsr->dfce_->link_has_geometry_[i]) || !gsr->dfce_->self_collision_enabled_[i])
285  continue;
286  const std::vector<CollisionSphere>* collision_spheres_1;
287  const EigenSTL::vector_Vector3d* sphere_centers_1;
288 
289  if (is_link)
290  {
291  collision_spheres_1 = &(gsr->link_body_decompositions_[i]->getCollisionSpheres());
292  sphere_centers_1 = &(gsr->link_body_decompositions_[i]->getSphereCenters());
293  }
294  else
295  {
296  collision_spheres_1 =
297  &(gsr->attached_body_decompositions_[i - gsr->dfce_->link_names_.size()]->getCollisionSpheres());
298  sphere_centers_1 = &(gsr->attached_body_decompositions_[i - gsr->dfce_->link_names_.size()]->getSphereCenters());
299  }
300 
301  if (req.contacts)
302  {
303  std::vector<unsigned int> colls;
304  bool coll =
305  getCollisionSphereCollision(gsr->dfce_->distance_field_.get(), *collision_spheres_1, *sphere_centers_1,
307  std::min(req.max_contacts_per_pair, req.max_contacts - res.contact_count), colls);
308  if (coll)
309  {
310  res.collision = true;
311  for (unsigned int col : colls)
312  {
314  if (is_link)
315  {
316  con.pos = gsr->link_body_decompositions_[i]->getSphereCenters()[col];
318  con.body_name_1 = gsr->dfce_->link_names_[i];
319  }
320  else
321  {
322  con.pos = gsr->attached_body_decompositions_[i - gsr->dfce_->link_names_.size()]->getSphereCenters()[col];
324  con.body_name_1 = gsr->dfce_->attached_body_names_[i - gsr->dfce_->link_names_.size()];
325  }
326 
327  ROS_DEBUG_STREAM("Self collision detected for link " << con.body_name_1);
328 
330  con.body_name_2 = "self";
331  res.contact_count++;
332  res.contacts[std::pair<std::string, std::string>(con.body_name_1, con.body_name_2)].push_back(con);
333  gsr->gradients_[i].types[col] = SELF;
334  }
335  gsr->gradients_[i].collision = true;
336 
337  if (res.contact_count >= req.max_contacts)
338  {
339  return true;
340  }
341  }
342  }
343  else
344  {
345  bool coll = getCollisionSphereCollision(gsr->dfce_->distance_field_.get(), *collision_spheres_1,
346  *sphere_centers_1, max_propogation_distance_, collision_tolerance_);
347  if (coll)
348  {
349  ROS_DEBUG("Link %s in self collision", gsr->dfce_->link_names_[i].c_str());
350  res.collision = true;
351  return true;
352  }
353  }
354  }
355  return (res.contact_count >= req.max_contacts);
356 }
357 
358 bool CollisionEnvDistanceField::getSelfProximityGradients(GroupStateRepresentationPtr& gsr) const
359 {
360  bool in_collision = false;
361 
362  for (unsigned int i = 0; i < gsr->dfce_->link_names_.size(); i++)
363  {
364  const std::string& link_name = gsr->dfce_->link_names_[i];
365  bool is_link = i < gsr->dfce_->link_names_.size();
366  if ((is_link && !gsr->dfce_->link_has_geometry_[i]) || !gsr->dfce_->self_collision_enabled_[i])
367  {
368  continue;
369  }
370 
371  const std::vector<CollisionSphere>* collision_spheres_1;
372  const EigenSTL::vector_Vector3d* sphere_centers_1;
373  if (is_link)
374  {
375  collision_spheres_1 = &(gsr->link_body_decompositions_[i]->getCollisionSpheres());
376  sphere_centers_1 = &(gsr->link_body_decompositions_[i]->getSphereCenters());
377  }
378  else
379  {
380  collision_spheres_1 =
381  &(gsr->attached_body_decompositions_[i - gsr->dfce_->link_names_.size()]->getCollisionSpheres());
382  sphere_centers_1 = &(gsr->attached_body_decompositions_[i - gsr->dfce_->link_names_.size()]->getSphereCenters());
383  }
384 
385  // computing distance gradients by checking collisions against other mobile
386  // links as indicated by the AllowedCollisionMatrix
387  bool coll = false;
388  if (gsr->dfce_->acm_.getSize() > 0)
389  {
391  for (unsigned int j = 0; j < gsr->dfce_->link_names_.size(); j++)
392  {
393  // on self collisions skip
394  if (link_name == gsr->dfce_->link_names_[j])
395  {
396  continue;
397  }
398 
399  // on collision exceptions skip
400  if (gsr->dfce_->acm_.getEntry(link_name, gsr->dfce_->link_names_[j], col_type) &&
401  col_type != AllowedCollision::NEVER)
402  {
403  continue;
404  }
405 
406  if (gsr->link_distance_fields_[j])
407  {
408  coll = gsr->link_distance_fields_[j]->getCollisionSphereGradients(
409  *collision_spheres_1, *sphere_centers_1, gsr->gradients_[i], collision_detection::SELF,
411 
412  if (coll)
413  {
414  in_collision = true;
415  }
416  }
417  }
418  }
419 
420  coll = getCollisionSphereGradients(gsr->dfce_->distance_field_.get(), *collision_spheres_1, *sphere_centers_1,
421  gsr->gradients_[i], collision_detection::SELF, collision_tolerance_, false,
423 
424  if (coll)
425  {
426  in_collision = true;
427  }
428  }
429 
430  return in_collision;
431 }
432 
435  GroupStateRepresentationPtr& gsr) const
436 {
437  unsigned int num_links = gsr->dfce_->link_names_.size();
438  unsigned int num_attached_bodies = gsr->dfce_->attached_body_names_.size();
439 
440  for (unsigned int i = 0; i < num_links + num_attached_bodies; i++)
441  {
442  for (unsigned int j = i + 1; j < num_links + num_attached_bodies; j++)
443  {
444  if (i == j)
445  continue;
446  bool i_is_link = i < num_links;
447  bool j_is_link = j < num_links;
448 
449  if ((i_is_link && !gsr->dfce_->link_has_geometry_[i]) || (j_is_link && !gsr->dfce_->link_has_geometry_[j]))
450  continue;
451 
452  if (!gsr->dfce_->intra_group_collision_enabled_[i][j])
453  continue;
454 
455  if (i_is_link && j_is_link &&
456  !doBoundingSpheresIntersect(gsr->link_body_decompositions_[i], gsr->link_body_decompositions_[j]))
457  {
458  // ROS_DEBUG_STREAM("Bounding spheres for " <<
459  // gsr->dfce_->link_names_[i] << " and " << gsr->dfce_->link_names_[j]
460  //<< " don't intersect");
461  continue;
462  }
463  else if (!i_is_link || !j_is_link)
464  {
465  bool all_ok = true;
466  if (!i_is_link && j_is_link)
467  {
468  for (unsigned int k = 0; k < gsr->attached_body_decompositions_[i - num_links]->getSize(); k++)
469  {
471  gsr->link_body_decompositions_[j],
472  gsr->attached_body_decompositions_[i - num_links]->getPosedBodySphereDecomposition(k)))
473  {
474  all_ok = false;
475  break;
476  }
477  }
478  }
479  else if (i_is_link && !j_is_link)
480  {
481  for (unsigned int k = 0; k < gsr->attached_body_decompositions_[j - num_links]->getSize(); k++)
482  {
484  gsr->link_body_decompositions_[i],
485  gsr->attached_body_decompositions_[j - num_links]->getPosedBodySphereDecomposition(k)))
486  {
487  all_ok = false;
488  break;
489  }
490  }
491  }
492  else
493  {
494  for (unsigned int k = 0; k < gsr->attached_body_decompositions_[i - num_links]->getSize() && all_ok; k++)
495  {
496  for (unsigned int l = 0; l < gsr->attached_body_decompositions_[j - num_links]->getSize(); l++)
497  {
499  gsr->attached_body_decompositions_[i - num_links]->getPosedBodySphereDecomposition(k),
500  gsr->attached_body_decompositions_[j - num_links]->getPosedBodySphereDecomposition(l)))
501  {
502  all_ok = false;
503  break;
504  }
505  }
506  }
507  }
508  if (all_ok)
509  {
510  continue;
511  }
512  // std::cerr << "Bounding spheres for " << gsr->dfce_->link_names_[i] <<
513  // " and " << gsr->dfce_->link_names_[j]
514  // << " intersect" << std::endl;
515  }
516  int num_pair = -1;
517  std::string name_1;
518  std::string name_2;
519  if (i_is_link)
520  {
521  name_1 = gsr->dfce_->link_names_[i];
522  }
523  else
524  {
525  name_1 = gsr->dfce_->attached_body_names_[i - num_links];
526  }
527 
528  if (j_is_link)
529  {
530  name_2 = gsr->dfce_->link_names_[j];
531  }
532  else
533  {
534  name_2 = gsr->dfce_->attached_body_names_[j - num_links];
535  }
536  if (req.contacts)
537  {
538  collision_detection::CollisionResult::ContactMap::iterator it =
539  res.contacts.find(std::pair<std::string, std::string>(name_1, name_2));
540  if (it == res.contacts.end())
541  {
542  num_pair = 0;
543  }
544  else
545  {
546  num_pair = it->second.size();
547  }
548  }
549  const std::vector<CollisionSphere>* collision_spheres_1;
550  const std::vector<CollisionSphere>* collision_spheres_2;
551  const EigenSTL::vector_Vector3d* sphere_centers_1;
552  const EigenSTL::vector_Vector3d* sphere_centers_2;
553  if (i_is_link)
554  {
555  collision_spheres_1 = &(gsr->link_body_decompositions_[i]->getCollisionSpheres());
556  sphere_centers_1 = &(gsr->link_body_decompositions_[i]->getSphereCenters());
557  }
558  else
559  {
560  collision_spheres_1 = &(gsr->attached_body_decompositions_[i - num_links]->getCollisionSpheres());
561  sphere_centers_1 = &(gsr->attached_body_decompositions_[i - num_links]->getSphereCenters());
562  }
563  if (j_is_link)
564  {
565  collision_spheres_2 = &(gsr->link_body_decompositions_[j]->getCollisionSpheres());
566  sphere_centers_2 = &(gsr->link_body_decompositions_[j]->getSphereCenters());
567  }
568  else
569  {
570  collision_spheres_2 = &(gsr->attached_body_decompositions_[j - num_links]->getCollisionSpheres());
571  sphere_centers_2 = &(gsr->attached_body_decompositions_[j - num_links]->getSphereCenters());
572  }
573 
574  for (unsigned int k = 0; k < collision_spheres_1->size() && num_pair < (int)req.max_contacts_per_pair; k++)
575  {
576  for (unsigned int l = 0; l < collision_spheres_2->size() && num_pair < (int)req.max_contacts_per_pair; l++)
577  {
578  Eigen::Vector3d gradient = (*sphere_centers_1)[k] - (*sphere_centers_2)[l];
579  double dist = gradient.norm();
580  // std::cerr << "Dist is " << dist << " rad " <<
581  // (*collision_spheres_1)[k].radius_+(*collision_spheres_2)[l].radius_
582  // << std::endl;
583 
584  if (dist < (*collision_spheres_1)[k].radius_ + (*collision_spheres_2)[l].radius_)
585  {
586  // ROS_DEBUG("Intra-group contact between %s and %s, d =
587  // %f < r1 = %f + r2 = %f", name_1.c_str(),
588  // name_2.c_str(),
589  // dist ,(*collision_spheres_1)[k].radius_
590  // ,(*collision_spheres_2)[l].radius_);
591  // Eigen::Vector3d sc1 = (*sphere_centers_1)[k];
592  // Eigen::Vector3d sc2 = (*sphere_centers_2)[l];
593  // ROS_DEBUG("sphere center 1:[ %f, %f, %f ], sphere
594  // center 2: [%f, %f,%f ], lbdc size =
595  // %i",sc1[0],sc1[1],sc1[2],
596  // sc2[0],sc2[1],sc2[2],int(gsr->link_body_decompositions_.size()));
597  res.collision = true;
598 
599  if (req.contacts)
600  {
602  con.pos = gsr->link_body_decompositions_[i]->getSphereCenters()[k];
603  con.body_name_1 = name_1;
604  con.body_name_2 = name_2;
605  if (i_is_link)
606  {
608  }
609  else
610  {
612  }
613  if (j_is_link)
614  {
616  }
617  else
618  {
620  }
621  res.contact_count++;
622  res.contacts[std::pair<std::string, std::string>(con.body_name_1, con.body_name_2)].push_back(con);
623  num_pair++;
624  // std::cerr << "Pushing back intra " << con.body_name_1 << " and
625  // " << con.body_name_2 << std::endl;
626  gsr->gradients_[i].types[k] = INTRA;
627  gsr->gradients_[i].collision = true;
628  gsr->gradients_[j].types[l] = INTRA;
629  gsr->gradients_[j].collision = true;
630  // ROS_INFO_STREAM("Sphere 1 " << (*sphere_centers_1)[k]);
631  // ROS_INFO_STREAM("Sphere 2 " << (*sphere_centers_2)[l]);
632  // ROS_INFO_STREAM("Norm " << gradient.norm());
633  // ROS_INFO_STREAM("Dist is " << dist
634  // << " radius 1 " <<
635  // (*collision_spheres_1)[k].radius_
636  // << " radius 2 " <<
637  // (*collision_spheres_2)[l].radius_);
638  // ROS_INFO_STREAM("Gradient " << gradient);
639  // ROS_INFO_STREAM("Spheres intersect for " <<
640  // gsr->dfce_->link_names_[i] << " and " <<
641  // gsr->dfce_->link_names_[j]);
642  // std::cerr << "Spheres intersect for " <<
643  // gsr->dfce_->link_names_[i] << " and " <<
644  // gsr->dfce_->link_names_[j] << std::cerr;
645  if (res.contact_count >= req.max_contacts)
646  {
647  return true;
648  }
649  }
650  else
651  {
652  return true;
653  }
654  }
655  }
656  }
657  }
658  }
659  return false;
660 }
661 
662 bool CollisionEnvDistanceField::getIntraGroupProximityGradients(GroupStateRepresentationPtr& gsr) const
663 {
664  bool in_collision = false;
665  unsigned int num_links = gsr->dfce_->link_names_.size();
666  unsigned int num_attached_bodies = gsr->dfce_->attached_body_names_.size();
667  // TODO - deal with attached bodies
668  for (unsigned int i = 0; i < num_links + num_attached_bodies; i++)
669  {
670  for (unsigned int j = i + 1; j < num_links + num_attached_bodies; j++)
671  {
672  if (i == j)
673  continue;
674  bool i_is_link = i < num_links;
675  bool j_is_link = j < num_links;
676  if ((i_is_link && !gsr->dfce_->link_has_geometry_[i]) || (j_is_link && !gsr->dfce_->link_has_geometry_[j]))
677  continue;
678  if (!gsr->dfce_->intra_group_collision_enabled_[i][j])
679  continue;
680  const std::vector<CollisionSphere>* collision_spheres_1;
681  const std::vector<CollisionSphere>* collision_spheres_2;
682  const EigenSTL::vector_Vector3d* sphere_centers_1;
683  const EigenSTL::vector_Vector3d* sphere_centers_2;
684  if (i_is_link)
685  {
686  collision_spheres_1 = &(gsr->link_body_decompositions_[i]->getCollisionSpheres());
687  sphere_centers_1 = &(gsr->link_body_decompositions_[i]->getSphereCenters());
688  }
689  else
690  {
691  collision_spheres_1 = &(gsr->attached_body_decompositions_[i - num_links]->getCollisionSpheres());
692  sphere_centers_1 = &(gsr->attached_body_decompositions_[i - num_links]->getSphereCenters());
693  }
694  if (j_is_link)
695  {
696  collision_spheres_2 = &(gsr->link_body_decompositions_[j]->getCollisionSpheres());
697  sphere_centers_2 = &(gsr->link_body_decompositions_[j]->getSphereCenters());
698  }
699  else
700  {
701  collision_spheres_2 = &(gsr->attached_body_decompositions_[j - num_links]->getCollisionSpheres());
702  sphere_centers_2 = &(gsr->attached_body_decompositions_[j - num_links]->getSphereCenters());
703  }
704  for (unsigned int k = 0; k < collision_spheres_1->size(); k++)
705  {
706  for (unsigned int l = 0; l < collision_spheres_2->size(); l++)
707  {
708  Eigen::Vector3d gradient = (*sphere_centers_1)[k] - (*sphere_centers_2)[l];
709  double dist = gradient.norm();
710  if (dist < gsr->gradients_[i].distances[k])
711  {
712  gsr->gradients_[i].distances[k] = dist;
713  gsr->gradients_[i].gradients[k] = gradient;
714  gsr->gradients_[i].types[k] = INTRA;
715  }
716  if (dist < gsr->gradients_[j].distances[l])
717  {
718  gsr->gradients_[j].distances[l] = dist;
719  gsr->gradients_[j].gradients[l] = -gradient;
720  gsr->gradients_[j].types[l] = INTRA;
721  }
722  }
723  }
724  }
725  }
726  return in_collision;
727 }
729  const std::string& group_name, const moveit::core::RobotState& state,
730  const collision_detection::AllowedCollisionMatrix* acm, bool generate_distance_field) const
731 {
732  DistanceFieldCacheEntryPtr dfce(new DistanceFieldCacheEntry());
733 
734  dfce->group_name_ = group_name;
735 
736  if (group_name.empty())
737  dfce->link_names_ = robot_model_->getLinkModelNames();
738  else
739  dfce->link_names_ = robot_model_->getJointModelGroup(group_name)->getUpdatedLinkModelNames();
740 
741  dfce->state_ = std::make_shared<moveit::core::RobotState>(state);
742  if (acm)
743  {
744  dfce->acm_ = *acm;
745  }
746  else
747  {
748  ROS_WARN_STREAM("Allowed Collision Matrix is null, enabling all collisions "
749  "in the DistanceFieldCacheEntry");
750  }
751 
752  // generateAllowedCollisionInformation(dfce);
753  std::vector<const moveit::core::AttachedBody*> all_attached_bodies;
754  dfce->state_->getAttachedBodies(all_attached_bodies);
755  unsigned int att_count = 0;
756 
757  // may be bigger than necessary
758  std::vector<bool> all_true(dfce->link_names_.size() + all_attached_bodies.size(), true);
759  std::vector<bool> all_false(dfce->link_names_.size() + all_attached_bodies.size(), false);
760 
761  dfce->self_collision_enabled_.resize(dfce->link_names_.size() + all_attached_bodies.size(), true);
762  dfce->intra_group_collision_enabled_.resize(dfce->link_names_.size() + all_attached_bodies.size());
763 
764  for (unsigned int i = 0; i < dfce->link_names_.size(); i++)
765  {
766  std::string link_name = dfce->link_names_[i];
767  const moveit::core::LinkModel* link_state = dfce->state_->getLinkModel(link_name);
768 
769  auto pos = std::find(dfce->link_names_.begin(), dfce->link_names_.end(), link_name);
770  if (pos != dfce->link_names_.end())
771  {
772  dfce->link_state_indices_.push_back(pos - dfce->link_names_.begin());
773  }
774  else
775  {
776  ROS_DEBUG("No link state found for link '%s'", link_name.c_str());
777  continue;
778  }
779 
780  if (!link_state->getShapes().empty())
781  {
782  dfce->link_has_geometry_.push_back(true);
783  dfce->link_body_indices_.push_back(link_body_decomposition_index_map_.find(link_name)->second);
784 
785  if (acm)
786  {
788  if (acm->getEntry(link_name, link_name, t) && t == collision_detection::AllowedCollision::ALWAYS)
789  {
790  dfce->self_collision_enabled_[i] = false;
791  }
792 
793  dfce->intra_group_collision_enabled_[i] = all_true;
794  for (unsigned int j = i + 1; j < dfce->link_names_.size(); j++)
795  {
796  if (link_name == dfce->link_names_[j])
797  {
798  dfce->intra_group_collision_enabled_[i][j] = false;
799  continue;
800  }
801  if (acm->getEntry(link_name, dfce->link_names_[j], t) && t == collision_detection::AllowedCollision::ALWAYS)
802  {
803  dfce->intra_group_collision_enabled_[i][j] = false;
804  }
805  }
806 
807  std::vector<const moveit::core::AttachedBody*> link_attached_bodies;
808  state.getAttachedBodies(link_attached_bodies, link_state);
809  for (unsigned int j = 0; j < link_attached_bodies.size(); j++, att_count++)
810  {
811  dfce->attached_body_names_.push_back(link_attached_bodies[j]->getName());
812  dfce->attached_body_link_state_indices_.push_back(dfce->link_state_indices_[i]);
813 
814  if (acm->getEntry(link_name, link_attached_bodies[j]->getName(), t))
815  {
817  {
818  dfce->intra_group_collision_enabled_[i][att_count + dfce->link_names_.size()] = false;
819  }
820  }
821  // std::cerr << "Checking touch links for " << link_name << " and " <<
822  // attached_bodies[j]->getName()
823  // << " num " << attached_bodies[j]->getTouchLinks().size()
824  // << std::endl;
825  // touch links take priority
826  if (link_attached_bodies[j]->getTouchLinks().find(link_name) != link_attached_bodies[j]->getTouchLinks().end())
827  {
828  dfce->intra_group_collision_enabled_[i][att_count + dfce->link_names_.size()] = false;
829  // std::cerr << "Setting intra group for " << link_name << " and
830  // attached body " << link_attached_bodies[j]->getName() << " to
831  // false" << std::endl;
832  }
833  }
834  }
835  else
836  {
837  dfce->self_collision_enabled_[i] = true;
838  dfce->intra_group_collision_enabled_[i] = all_true;
839  }
840  }
841  else
842  {
843  dfce->link_has_geometry_.push_back(false);
844  dfce->link_body_indices_.push_back(0);
845  dfce->self_collision_enabled_[i] = false;
846  dfce->intra_group_collision_enabled_[i] = all_false;
847  }
848  }
849 
850  for (unsigned int i = 0; i < dfce->attached_body_names_.size(); i++)
851  {
852  dfce->intra_group_collision_enabled_[i + dfce->link_names_.size()] = all_true;
853  if (acm)
854  {
856  if (acm->getEntry(dfce->attached_body_names_[i], dfce->attached_body_names_[i], t) &&
858  {
859  dfce->self_collision_enabled_[i + dfce->link_names_.size()] = false;
860  }
861  for (unsigned int j = i + 1; j < dfce->attached_body_names_.size(); j++)
862  {
863  if (acm->getEntry(dfce->attached_body_names_[i], dfce->attached_body_names_[j], t) &&
865  {
866  dfce->intra_group_collision_enabled_[i + dfce->link_names_.size()][j + dfce->link_names_.size()] = false;
867  }
868  // TODO - allow for touch links to be attached bodies?
869  // else {
870  // std::cerr << "Setting not allowed for " << link_name << " and " <<
871  // dfce->link_names_[j] << std::endl;
872  //}
873  }
874  }
875  }
876 
877  std::map<std::string, GroupStateRepresentationPtr>::const_iterator it =
878  pregenerated_group_state_representation_map_.find(dfce->group_name_);
880  {
881  dfce->pregenerated_group_state_representation_ = it->second;
882  }
883 
884  std::map<std::string, bool> updated_map;
885  if (!dfce->link_names_.empty())
886  {
887  const std::vector<const moveit::core::JointModel*>& child_joint_models = [&]() {
888  if (dfce->group_name_.empty())
889  return dfce->state_->getRobotModel()->getActiveJointModels();
890  else
891  return dfce->state_->getJointModelGroup(dfce->group_name_)->getActiveJointModels();
892  }();
893 
894  for (const moveit::core::JointModel* child_joint_model : child_joint_models)
895  {
896  updated_map[child_joint_model->getName()] = true;
897  ROS_DEBUG_STREAM("Joint " << child_joint_model->getName() << " has been added to updated list");
898  }
899  }
900 
901  const std::vector<std::string>& state_variable_names = state.getVariableNames();
902  for (const std::string& state_variable_name : state_variable_names)
903  {
904  double val = state.getVariablePosition(state_variable_name);
905  dfce->state_values_.push_back(val);
906  if (updated_map.count(state_variable_name) == 0)
907  {
908  dfce->state_check_indices_.push_back(dfce->state_values_.size() - 1);
909  ROS_DEBUG_STREAM("Non-group joint " << state_variable_name << " will be checked for state changes");
910  }
911  }
912 
913  if (generate_distance_field)
914  {
915  if (dfce->distance_field_)
916  {
917  ROS_DEBUG_STREAM("CollisionRobot skipping distance field generation, "
918  "will use existing one");
919  }
920  else
921  {
922  std::vector<PosedBodyPointDecompositionPtr> non_group_link_decompositions;
923  std::vector<PosedBodyPointDecompositionVectorPtr> non_group_attached_body_decompositions;
924  const std::map<std::string, bool>& updated_group_map = in_group_update_map_.find(group_name)->second;
925  for (const moveit::core::LinkModel* link_model : robot_model_->getLinkModelsWithCollisionGeometry())
926  {
927  const std::string& link_name = link_model->getName();
928  const moveit::core::LinkModel* link_state = dfce->state_->getLinkModel(link_name);
929  if (updated_group_map.find(link_name) != updated_group_map.end())
930  {
931  continue;
932  }
933 
934  // populating array with link that are not part of the planning group
935  non_group_link_decompositions.push_back(getPosedLinkBodyPointDecomposition(link_state));
936  non_group_link_decompositions.back()->updatePose(dfce->state_->getFrameTransform(link_state->getName()));
937 
938  std::vector<const moveit::core::AttachedBody*> attached_bodies;
939  dfce->state_->getAttachedBodies(attached_bodies, link_state);
940  for (const moveit::core::AttachedBody* attached_body : attached_bodies)
941  {
942  non_group_attached_body_decompositions.push_back(
944  }
945  }
946  dfce->distance_field_ = std::make_shared<distance_field::PropagationDistanceField>(
947  size_.x(), size_.y(), size_.z(), resolution_, origin_.x() - 0.5 * size_.x(), origin_.y() - 0.5 * size_.y(),
949 
950  // ROS_INFO_STREAM("Creation took " <<
951  // (ros::WallTime::now()-before_create).toSec());
952  // TODO - deal with AllowedCollisionMatrix
953  // now we need to actually set the points
954  // TODO - deal with shifted robot
955  EigenSTL::vector_Vector3d all_points;
956  for (collision_detection::PosedBodyPointDecompositionPtr& non_group_link_decomposition :
957  non_group_link_decompositions)
958  {
959  all_points.insert(all_points.end(), non_group_link_decomposition->getCollisionPoints().begin(),
960  non_group_link_decomposition->getCollisionPoints().end());
961  }
962 
963  for (collision_detection::PosedBodyPointDecompositionVectorPtr& non_group_attached_body_decomposition :
964  non_group_attached_body_decompositions)
965  {
966  const EigenSTL::vector_Vector3d collision_points = non_group_attached_body_decomposition->getCollisionPoints();
967  all_points.insert(all_points.end(), collision_points.begin(), collision_points.end());
968  }
969 
970  dfce->distance_field_->addPointsToField(all_points);
971  ROS_DEBUG_STREAM("CollisionRobot distance field has been initialized with " << all_points.size() << " points.");
972  }
973  }
974  return dfce;
975 }
976 
978 {
979  const std::vector<const moveit::core::LinkModel*>& link_models = robot_model_->getLinkModelsWithCollisionGeometry();
980  for (const moveit::core::LinkModel* link_model : link_models)
981  {
982  if (link_model->getShapes().empty())
983  {
984  ROS_WARN("No collision geometry for link model %s though there should be", link_model->getName().c_str());
985  continue;
986  }
987 
988  ROS_DEBUG("Generating model for %s", link_model->getName().c_str());
989  BodyDecompositionConstPtr bd(new BodyDecomposition(link_model->getShapes(),
990  link_model->getCollisionOriginTransforms(), resolution,
991  getLinkPadding(link_model->getName())));
992  link_body_decomposition_vector_.push_back(bd);
993  link_body_decomposition_index_map_[link_model->getName()] = link_body_decomposition_vector_.size() - 1;
994  }
995 }
996 
998  visualization_msgs::MarkerArray& model_markers) const
999 {
1000  // creating colors
1001  std_msgs::ColorRGBA robot_color;
1002  robot_color.r = 0;
1003  robot_color.b = 0.8f;
1004  robot_color.g = 0;
1005  robot_color.a = 0.5;
1006 
1007  std_msgs::ColorRGBA world_links_color;
1008  world_links_color.r = 1;
1009  world_links_color.g = 1;
1010  world_links_color.b = 0;
1011  world_links_color.a = 0.5;
1012 
1013  // creating sphere marker
1014  visualization_msgs::Marker sphere_marker;
1015  sphere_marker.header.frame_id = robot_model_->getRootLinkName();
1016  sphere_marker.header.stamp = ros::Time(0);
1017  sphere_marker.ns = distance_field_cache_entry_->group_name_ + "_sphere_decomposition";
1018  sphere_marker.id = 0;
1019  sphere_marker.type = visualization_msgs::Marker::SPHERE;
1020  sphere_marker.action = visualization_msgs::Marker::ADD;
1021  sphere_marker.pose.orientation.x = 0;
1022  sphere_marker.pose.orientation.y = 0;
1023  sphere_marker.pose.orientation.z = 0;
1024  sphere_marker.pose.orientation.w = 1;
1025  sphere_marker.color = robot_color;
1026  sphere_marker.lifetime = ros::Duration(0);
1027 
1028  unsigned int id = 0;
1030  const std::vector<std::string>& group_link_names = joint_group->getUpdatedLinkModelNames();
1031 
1032  std::map<std::string, unsigned int>::const_iterator map_iter;
1033  for (map_iter = link_body_decomposition_index_map_.begin(); map_iter != link_body_decomposition_index_map_.end();
1034  map_iter++)
1035  {
1036  const std::string& link_name = map_iter->first;
1037  unsigned int link_index = map_iter->second;
1038 
1039  // selecting color
1040  if (std::find(group_link_names.begin(), group_link_names.end(), link_name) != group_link_names.end())
1041  {
1042  sphere_marker.color = robot_color;
1043  }
1044  else
1045  {
1046  sphere_marker.color = world_links_color;
1047  }
1048 
1049  collision_detection::PosedBodySphereDecompositionPtr sphere_representation(
1051  sphere_representation->updatePose(state.getGlobalLinkTransform(link_name));
1052  for (unsigned int j = 0; j < sphere_representation->getCollisionSpheres().size(); j++)
1053  {
1054  sphere_marker.pose.position = tf2::toMsg(sphere_representation->getSphereCenters()[j]);
1055  sphere_marker.scale.x = sphere_marker.scale.y = sphere_marker.scale.z =
1056  2 * sphere_representation->getCollisionSpheres()[j].radius_;
1057  sphere_marker.id = id;
1058  id++;
1059 
1060  model_markers.markers.push_back(sphere_marker);
1061  }
1062  }
1063 }
1064 
1066  double resolution, const std::map<std::string, std::vector<CollisionSphere>>& link_spheres)
1067 {
1068  ROS_ASSERT_MSG(robot_model_, "RobotModelPtr is invalid");
1069  const std::vector<const moveit::core::LinkModel*>& link_models = robot_model_->getLinkModelsWithCollisionGeometry();
1070 
1071  for (const moveit::core::LinkModel* link_model : link_models)
1072  {
1073  if (link_model->getShapes().empty())
1074  {
1075  ROS_WARN_STREAM("Skipping model generation for link " << link_model->getName()
1076  << " since it contains no geometries");
1077  continue;
1078  }
1079 
1080  BodyDecompositionPtr bd(new BodyDecomposition(link_model->getShapes(), link_model->getCollisionOriginTransforms(),
1081  resolution, getLinkPadding(link_model->getName())));
1082 
1083  ROS_DEBUG("Generated model for %s", link_model->getName().c_str());
1084 
1085  if (link_spheres.find(link_model->getName()) != link_spheres.end())
1086  {
1087  bd->replaceCollisionSpheres(link_spheres.find(link_model->getName())->second, Eigen::Isometry3d::Identity());
1088  }
1089  link_body_decomposition_vector_.push_back(bd);
1090  link_body_decomposition_index_map_[link_model->getName()] = link_body_decomposition_vector_.size() - 1;
1091  }
1092  ROS_DEBUG_STREAM(__FUNCTION__ << " Finished ");
1093 }
1094 
1095 PosedBodySphereDecompositionPtr
1097  unsigned int ind) const
1098 {
1099  PosedBodySphereDecompositionPtr ret;
1100  ret = std::make_shared<PosedBodySphereDecomposition>(link_body_decomposition_vector_.at(ind));
1101  return ret;
1102 }
1103 
1104 PosedBodyPointDecompositionPtr
1106 {
1107  PosedBodyPointDecompositionPtr ret;
1108  std::map<std::string, unsigned int>::const_iterator it = link_body_decomposition_index_map_.find(ls->getName());
1109  if (it == link_body_decomposition_index_map_.end())
1110  {
1111  ROS_ERROR_NAMED("collision_distance_field", "No link body decomposition for link %s.", ls->getName().c_str());
1112  return ret;
1113  }
1114  ret = std::make_shared<PosedBodyPointDecomposition>(link_body_decomposition_vector_[it->second]);
1115  return ret;
1116 }
1117 
1119  GroupStateRepresentationPtr& gsr) const
1120 {
1121  for (unsigned int i = 0; i < gsr->dfce_->link_names_.size(); i++)
1122  {
1123  const moveit::core::LinkModel* ls = state.getLinkModel(gsr->dfce_->link_names_[i]);
1124  if (gsr->dfce_->link_has_geometry_[i])
1125  {
1126  gsr->link_body_decompositions_[i]->updatePose(state.getFrameTransform(ls->getName()));
1127  gsr->link_distance_fields_[i]->updatePose(state.getFrameTransform(ls->getName()));
1128  gsr->gradients_[i].closest_distance = DBL_MAX;
1129  gsr->gradients_[i].collision = false;
1130  gsr->gradients_[i].types.assign(gsr->link_body_decompositions_[i]->getCollisionSpheres().size(), NONE);
1131  gsr->gradients_[i].distances.assign(gsr->link_body_decompositions_[i]->getCollisionSpheres().size(), DBL_MAX);
1132  gsr->gradients_[i].gradients.assign(gsr->link_body_decompositions_[i]->getCollisionSpheres().size(),
1133  Eigen::Vector3d(0.0, 0.0, 0.0));
1134  gsr->gradients_[i].sphere_locations = gsr->link_body_decompositions_[i]->getSphereCenters();
1135  }
1136  }
1138  for (unsigned int i = 0; i < gsr->dfce_->attached_body_names_.size(); i++)
1139  {
1140  const moveit::core::AttachedBody* att = state.getAttachedBody(gsr->dfce_->attached_body_names_[i]);
1141  if (!att)
1142  {
1143  ROS_WARN("Attached body discrepancy");
1144  continue;
1145  }
1146 
1147  // TODO: This logic for checking attached body count might be incorrect
1148  if (gsr->attached_body_decompositions_.size() != att->getShapes().size())
1149  {
1150  ROS_WARN("Attached body size discrepancy");
1151  continue;
1152  }
1153 
1154  for (unsigned int j = 0; j < att->getShapes().size(); j++)
1155  {
1156  gsr->attached_body_decompositions_[i]->updatePose(j, att->getGlobalCollisionBodyTransforms()[j]);
1157  }
1158 
1159  gsr->gradients_[i + gsr->dfce_->link_names_.size()].closest_distance = DBL_MAX;
1160  gsr->gradients_[i + gsr->dfce_->link_names_.size()].collision = false;
1161  gsr->gradients_[i + gsr->dfce_->link_names_.size()].types.assign(
1162  gsr->attached_body_decompositions_[i]->getCollisionSpheres().size(), NONE);
1163  gsr->gradients_[i + gsr->dfce_->link_names_.size()].distances.assign(
1164  gsr->attached_body_decompositions_[i]->getCollisionSpheres().size(), DBL_MAX);
1165  gsr->gradients_[i + gsr->dfce_->link_names_.size()].gradients.assign(
1166  gsr->attached_body_decompositions_[i]->getCollisionSpheres().size(), Eigen::Vector3d(0.0, 0.0, 0.0));
1167  gsr->gradients_[i + gsr->dfce_->link_names_.size()].sphere_locations =
1168  gsr->attached_body_decompositions_[i]->getSphereCenters();
1169  }
1170 }
1171 
1172 void CollisionEnvDistanceField::getGroupStateRepresentation(const DistanceFieldCacheEntryConstPtr& dfce,
1173  const moveit::core::RobotState& state,
1174  GroupStateRepresentationPtr& gsr) const
1175 {
1176  if (!dfce->pregenerated_group_state_representation_)
1177  {
1178  ROS_DEBUG_STREAM("Creating GroupStateRepresentation");
1179 
1180  // unsigned int count = 0;
1181  gsr = std::make_shared<GroupStateRepresentation>();
1182  gsr->dfce_ = dfce;
1183  gsr->gradients_.resize(dfce->link_names_.size() + dfce->attached_body_names_.size());
1184 
1185  Eigen::Vector3d link_size;
1186  Eigen::Vector3d link_origin;
1187  for (unsigned int i = 0; i < dfce->link_names_.size(); i++)
1188  {
1189  const moveit::core::LinkModel* ls = state.getLinkModel(dfce->link_names_[i]);
1190  if (dfce->link_has_geometry_[i])
1191  {
1192  // create link body geometric decomposition
1193  gsr->link_body_decompositions_.push_back(getPosedLinkBodySphereDecomposition(ls, dfce->link_body_indices_[i]));
1194 
1195  // create and fill link distance field
1196  PosedBodySphereDecompositionPtr& link_bd = gsr->link_body_decompositions_.back();
1197  double diameter = 2 * link_bd->getBoundingSphereRadius();
1198  link_size = Eigen::Vector3d(diameter, diameter, diameter);
1199  link_origin = link_bd->getBoundingSphereCenter() - 0.5 * link_size;
1200 
1201  ROS_DEBUG_STREAM("Creating PosedDistanceField for link "
1202  << dfce->link_names_[i] << " with size [" << link_size.x() << ", " << link_size.y() << ", "
1203  << link_size.z() << "] and origin " << link_origin.x() << ", " << link_origin.y() << ", "
1204  << link_origin.z());
1205 
1206  gsr->link_distance_fields_.push_back(std::make_shared<PosedDistanceField>(
1208  gsr->link_distance_fields_.back()->addPointsToField(link_bd->getCollisionPoints());
1209  ROS_DEBUG_STREAM("Created PosedDistanceField for link " << dfce->link_names_[i] << " with "
1210  << link_bd->getCollisionPoints().size() << " points");
1211 
1212  gsr->link_body_decompositions_.back()->updatePose(state.getFrameTransform(ls->getName()));
1213  gsr->link_distance_fields_.back()->updatePose(state.getFrameTransform(ls->getName()));
1214  gsr->gradients_[i].types.resize(gsr->link_body_decompositions_.back()->getCollisionSpheres().size(), NONE);
1215  gsr->gradients_[i].distances.resize(gsr->link_body_decompositions_.back()->getCollisionSpheres().size(),
1216  DBL_MAX);
1217  gsr->gradients_[i].gradients.resize(gsr->link_body_decompositions_.back()->getCollisionSpheres().size());
1218  gsr->gradients_[i].sphere_radii = gsr->link_body_decompositions_.back()->getSphereRadii();
1219  gsr->gradients_[i].joint_name = ls->getParentJointModel()->getName();
1220  }
1221  else
1222  {
1223  gsr->link_body_decompositions_.push_back(PosedBodySphereDecompositionPtr());
1224  gsr->link_distance_fields_.push_back(PosedDistanceFieldPtr());
1225  }
1226  }
1227  }
1228  else
1229  {
1230  gsr = std::make_shared<GroupStateRepresentation>(*(dfce->pregenerated_group_state_representation_));
1231  gsr->dfce_ = dfce;
1232  gsr->gradients_.resize(dfce->link_names_.size() + dfce->attached_body_names_.size());
1233  for (unsigned int i = 0; i < dfce->link_names_.size(); i++)
1234  {
1235  const moveit::core::LinkModel* ls = state.getLinkModel(dfce->link_names_[i]);
1236  if (dfce->link_has_geometry_[i])
1237  {
1238  gsr->link_body_decompositions_[i]->updatePose(state.getFrameTransform(ls->getName()));
1239  gsr->link_distance_fields_[i]->updatePose(state.getFrameTransform(ls->getName()));
1240  gsr->gradients_[i].sphere_locations = gsr->link_body_decompositions_[i]->getSphereCenters();
1241  }
1242  }
1243  }
1244 
1245  for (unsigned int i = 0; i < dfce->attached_body_names_.size(); i++)
1246  {
1247  int link_index = dfce->attached_body_link_state_indices_[i];
1248  const moveit::core::LinkModel* ls =
1249  state.getJointModelGroup(gsr->dfce_->group_name_)->getUpdatedLinkModels()[link_index];
1250  // const moveit::core::LinkModel* ls =
1251  // state.getLinkStateVector()[dfce->attached_body_link_state_indices_[i]];
1254  gsr->attached_body_decompositions_.push_back(
1255  getAttachedBodySphereDecomposition(state.getAttachedBody(dfce->attached_body_names_[i]), resolution_));
1256  gsr->gradients_[i + dfce->link_names_.size()].types.resize(
1257  gsr->attached_body_decompositions_.back()->getCollisionSpheres().size(), NONE);
1258  gsr->gradients_[i + dfce->link_names_.size()].distances.resize(
1259  gsr->attached_body_decompositions_.back()->getCollisionSpheres().size(), DBL_MAX);
1260  gsr->gradients_[i + dfce->link_names_.size()].gradients.resize(
1261  gsr->attached_body_decompositions_.back()->getCollisionSpheres().size());
1262  gsr->gradients_[i + dfce->link_names_.size()].sphere_locations =
1263  gsr->attached_body_decompositions_.back()->getSphereCenters();
1264  gsr->gradients_[i + dfce->link_names_.size()].sphere_radii =
1265  gsr->attached_body_decompositions_.back()->getSphereRadii();
1266  gsr->gradients_[i + dfce->link_names_.size()].joint_name = ls->getParentJointModel()->getName();
1267  }
1268 }
1269 
1270 bool CollisionEnvDistanceField::compareCacheEntryToState(const DistanceFieldCacheEntryConstPtr& dfce,
1271  const moveit::core::RobotState& state) const
1272 {
1273  std::vector<double> new_state_values(state.getVariableCount());
1274  for (unsigned int i = 0; i < new_state_values.size(); i++)
1275  {
1276  new_state_values[i] = state.getVariablePosition(i);
1277  }
1278 
1279  if (dfce->state_values_.size() != new_state_values.size())
1280  {
1281  ROS_ERROR("State value size mismatch");
1282  return false;
1283  }
1284 
1285  for (unsigned int i = 0; i < dfce->state_check_indices_.size(); i++)
1286  {
1287  double diff =
1288  fabs(dfce->state_values_[dfce->state_check_indices_[i]] - new_state_values[dfce->state_check_indices_[i]]);
1289  if (diff > EPSILON)
1290  {
1291  ROS_WARN_STREAM("State for Variable " << state.getVariableNames()[dfce->state_check_indices_[i]]
1292  << " has changed by " << diff << " radians");
1293  return false;
1294  }
1295  }
1296  std::vector<const moveit::core::AttachedBody*> attached_bodies_dfce;
1297  std::vector<const moveit::core::AttachedBody*> attached_bodies_state;
1298  dfce->state_->getAttachedBodies(attached_bodies_dfce);
1299  state.getAttachedBodies(attached_bodies_state);
1300  if (attached_bodies_dfce.size() != attached_bodies_state.size())
1301  {
1302  return false;
1303  }
1304  // TODO - figure all the things that can change
1305  for (unsigned int i = 0; i < attached_bodies_dfce.size(); i++)
1306  {
1307  if (attached_bodies_dfce[i]->getName() != attached_bodies_state[i]->getName())
1308  {
1309  return false;
1310  }
1311  if (attached_bodies_dfce[i]->getTouchLinks() != attached_bodies_state[i]->getTouchLinks())
1312  {
1313  return false;
1314  }
1315  if (attached_bodies_dfce[i]->getShapes().size() != attached_bodies_state[i]->getShapes().size())
1316  {
1317  return false;
1318  }
1319  for (unsigned int j = 0; j < attached_bodies_dfce[i]->getShapes().size(); j++)
1320  {
1321  if (attached_bodies_dfce[i]->getShapes()[j] != attached_bodies_state[i]->getShapes()[j])
1322  {
1323  return false;
1324  }
1325  }
1326  }
1327  return true;
1328 }
1329 
1331  const DistanceFieldCacheEntryConstPtr& dfce, const collision_detection::AllowedCollisionMatrix& acm) const
1332 {
1333  if (dfce->acm_.getSize() != acm.getSize())
1334  {
1335  ROS_DEBUG("Allowed collision matrix size mismatch");
1336  return false;
1337  }
1338  std::vector<const moveit::core::AttachedBody*> attached_bodies;
1339  dfce->state_->getAttachedBodies(attached_bodies);
1340  for (unsigned int i = 0; i < dfce->link_names_.size(); i++)
1341  {
1342  std::string link_name = dfce->link_names_[i];
1343  if (dfce->link_has_geometry_[i])
1344  {
1345  bool self_collision_enabled = true;
1347  if (acm.getEntry(link_name, link_name, t))
1348  {
1350  {
1351  self_collision_enabled = false;
1352  }
1353  }
1354  if (self_collision_enabled != dfce->self_collision_enabled_[i])
1355  {
1356  // ROS_INFO_STREAM("Self collision for " << link_name << " went from "
1357  // << dfce->self_collision_enabled_[i] << " to " <<
1358  // self_collision_enabled);
1359  return false;
1360  }
1361  for (unsigned int j = i; j < dfce->link_names_.size(); j++)
1362  {
1363  if (i == j)
1364  continue;
1365  if (dfce->link_has_geometry_[j])
1366  {
1367  bool intra_collision_enabled = true;
1368  if (acm.getEntry(link_name, dfce->link_names_[j], t))
1369  {
1371  {
1372  intra_collision_enabled = false;
1373  }
1374  }
1375  if (dfce->intra_group_collision_enabled_[i][j] != intra_collision_enabled)
1376  {
1377  // std::cerr << "Intra collision for " << dfce->link_names_[i] << "
1378  // " << dfce->link_names_[j]
1379  // << " went from " <<
1380  // dfce->intra_group_collision_enabled_[i][j] << " to " <<
1381  // intra_collision_enabled << std::endl;
1382  return false;
1383  }
1384  }
1385  }
1386  }
1387  }
1388  return true;
1389 }
1390 
1391 // void
1392 // CollisionEnvDistanceField::generateAllowedCollisionInformation(CollisionEnvDistanceField::DistanceFieldCacheEntryPtr&
1393 // dfce)
1394 // {
1395 // for(unsigned int i = 0; i < dfce.link_names_.size(); i++) {
1396 // for(unsigned int j = 0; j <
1397 // if(dfce->acm.find
1398 // }
1399 // }
1400 
1401 void CollisionEnvDistanceField::checkCollision(const CollisionRequest& req, CollisionResult& res,
1402  const moveit::core::RobotState& state) const
1403 {
1404  GroupStateRepresentationPtr gsr;
1405  checkCollision(req, res, state, gsr);
1406 }
1407 
1408 void CollisionEnvDistanceField::checkCollision(const CollisionRequest& req, CollisionResult& res,
1409  const moveit::core::RobotState& state,
1410  GroupStateRepresentationPtr& gsr) const
1411 {
1412  if (!gsr)
1413  {
1414  generateCollisionCheckingStructures(req.group_name, state, nullptr, gsr, true);
1415  }
1416  else
1417  {
1419  }
1420  bool done = getSelfCollisions(req, res, gsr);
1421  if (!done)
1422  {
1423  done = getIntraGroupCollisions(req, res, gsr);
1424  }
1425  if (!done)
1426  {
1427  getEnvironmentCollisions(req, res, distance_field_cache_entry_world_->distance_field_, gsr);
1428  }
1429 
1430  (const_cast<CollisionEnvDistanceField*>(this))->last_gsr_ = gsr;
1431 }
1432 
1434  const moveit::core::RobotState& state,
1435  const AllowedCollisionMatrix& acm) const
1436 {
1437  GroupStateRepresentationPtr gsr;
1438  checkCollision(req, res, state, acm, gsr);
1439 }
1442  const moveit::core::RobotState& state, const AllowedCollisionMatrix& acm,
1443  GroupStateRepresentationPtr& gsr) const
1444 {
1445  if (!gsr)
1446  {
1447  generateCollisionCheckingStructures(req.group_name, state, &acm, gsr, true);
1448  }
1449  else
1450  {
1452  }
1453  bool done = getSelfCollisions(req, res, gsr);
1454  if (!done)
1455  {
1456  done = getIntraGroupCollisions(req, res, gsr);
1457  }
1458  if (!done)
1459  {
1460  getEnvironmentCollisions(req, res, distance_field_cache_entry_world_->distance_field_, gsr);
1461  }
1462 
1463  (const_cast<CollisionEnvDistanceField*>(this))->last_gsr_ = gsr;
1464 }
1467  const moveit::core::RobotState& state) const
1468 {
1469  GroupStateRepresentationPtr gsr;
1470  checkRobotCollision(req, res, state, gsr);
1471 }
1472 
1474  const moveit::core::RobotState& state,
1475  GroupStateRepresentationPtr& gsr) const
1476 {
1477  distance_field::DistanceFieldConstPtr env_distance_field = distance_field_cache_entry_world_->distance_field_;
1478  if (!gsr)
1479  {
1480  generateCollisionCheckingStructures(req.group_name, state, nullptr, gsr, false);
1481  }
1482  else
1483  {
1485  }
1486  getEnvironmentCollisions(req, res, env_distance_field, gsr);
1487  (const_cast<CollisionEnvDistanceField*>(this))->last_gsr_ = gsr;
1488 
1489  // checkRobotCollisionHelper(req, res, robot, state, &acm);
1490 }
1491 
1493  const moveit::core::RobotState& state,
1494  const AllowedCollisionMatrix& acm) const
1495 {
1496  GroupStateRepresentationPtr gsr;
1497  checkRobotCollision(req, res, state, acm, gsr);
1499 
1501  const moveit::core::RobotState& state,
1502  const AllowedCollisionMatrix& acm,
1503  GroupStateRepresentationPtr& gsr) const
1504 {
1505  distance_field::DistanceFieldConstPtr env_distance_field = distance_field_cache_entry_world_->distance_field_;
1506 
1507  if (!gsr)
1508  {
1509  generateCollisionCheckingStructures(req.group_name, state, &acm, gsr, true);
1510  }
1511  else
1512  {
1514  }
1515  getEnvironmentCollisions(req, res, env_distance_field, gsr);
1516  (const_cast<CollisionEnvDistanceField*>(this))->last_gsr_ = gsr;
1517 
1518  // checkRobotCollisionHelper(req, res, robot, state, &acm);
1519 }
1520 
1521 void CollisionEnvDistanceField::checkRobotCollision(const CollisionRequest& /*req*/, CollisionResult& /*res*/,
1522  const moveit::core::RobotState& /*state1*/,
1523  const moveit::core::RobotState& /*state2*/,
1524  const AllowedCollisionMatrix& /*acm*/) const
1525 {
1526  ROS_ERROR_NAMED("collision_detection.distance", "Continuous collision checking not implemented");
1527 }
1528 
1530  const moveit::core::RobotState& /*state1*/,
1531  const moveit::core::RobotState& /*state2*/) const
1533  ROS_ERROR_NAMED("collision_detection.distance", "Continuous collision checking not implemented");
1534 }
1535 
1537  const moveit::core::RobotState& state,
1538  const AllowedCollisionMatrix* acm,
1539  GroupStateRepresentationPtr& gsr) const
1540 {
1541  distance_field::DistanceFieldConstPtr env_distance_field = distance_field_cache_entry_world_->distance_field_;
1542 
1543  if (!gsr)
1544  {
1545  generateCollisionCheckingStructures(req.group_name, state, acm, gsr, true);
1546  }
1547  else
1548  {
1550  }
1551 
1554  getEnvironmentProximityGradients(env_distance_field, gsr);
1555 
1556  (const_cast<CollisionEnvDistanceField*>(this))->last_gsr_ = gsr;
1557 }
1558 
1560  const moveit::core::RobotState& state,
1562  GroupStateRepresentationPtr& gsr) const
1563 {
1564  if (!gsr)
1565  {
1566  generateCollisionCheckingStructures(req.group_name, state, acm, gsr, true);
1567  }
1568  else
1569  {
1571  }
1572  getSelfCollisions(req, res, gsr);
1573  getIntraGroupCollisions(req, res, gsr);
1574  distance_field::DistanceFieldConstPtr env_distance_field = distance_field_cache_entry_world_->distance_field_;
1575  getEnvironmentCollisions(req, res, env_distance_field, gsr);
1576 
1577  (const_cast<CollisionEnvDistanceField*>(this))->last_gsr_ = gsr;
1578 }
1579 
1580 bool CollisionEnvDistanceField::getEnvironmentCollisions(const CollisionRequest& req, CollisionResult& res,
1581  const distance_field::DistanceFieldConstPtr& env_distance_field,
1582  GroupStateRepresentationPtr& gsr) const
1583 {
1584  for (unsigned int i = 0; i < gsr->dfce_->link_names_.size() + gsr->dfce_->attached_body_names_.size(); i++)
1585  {
1586  bool is_link = i < gsr->dfce_->link_names_.size();
1587  std::string link_name = i < gsr->dfce_->link_names_.size() ? gsr->dfce_->link_names_[i] : "attached";
1588  if (is_link && !gsr->dfce_->link_has_geometry_[i])
1589  {
1590  continue;
1591  }
1592 
1593  const std::vector<CollisionSphere>* collision_spheres_1;
1594  const EigenSTL::vector_Vector3d* sphere_centers_1;
1595 
1596  if (is_link)
1597  {
1598  collision_spheres_1 = &(gsr->link_body_decompositions_[i]->getCollisionSpheres());
1599  sphere_centers_1 = &(gsr->link_body_decompositions_[i]->getSphereCenters());
1600  }
1601  else
1602  {
1603  collision_spheres_1 =
1604  &(gsr->attached_body_decompositions_[i - gsr->dfce_->link_names_.size()]->getCollisionSpheres());
1605  sphere_centers_1 = &(gsr->attached_body_decompositions_[i - gsr->dfce_->link_names_.size()]->getSphereCenters());
1606  }
1607 
1608  if (req.contacts)
1609  {
1610  std::vector<unsigned int> colls;
1611  bool coll =
1612  getCollisionSphereCollision(env_distance_field.get(), *collision_spheres_1, *sphere_centers_1,
1614  std::min(req.max_contacts_per_pair, req.max_contacts - res.contact_count), colls);
1615  if (coll)
1616  {
1617  res.collision = true;
1618  for (unsigned int col : colls)
1619  {
1620  Contact con;
1621  if (is_link)
1622  {
1623  con.pos = gsr->link_body_decompositions_[i]->getSphereCenters()[col];
1625  con.body_name_1 = gsr->dfce_->link_names_[i];
1626  }
1627  else
1628  {
1629  con.pos = gsr->attached_body_decompositions_[i - gsr->dfce_->link_names_.size()]->getSphereCenters()[col];
1631  con.body_name_1 = gsr->dfce_->attached_body_names_[i - gsr->dfce_->link_names_.size()];
1632  }
1633 
1635  con.body_name_2 = "environment";
1636  res.contact_count++;
1637  res.contacts[std::pair<std::string, std::string>(con.body_name_1, con.body_name_2)].push_back(con);
1638  gsr->gradients_[i].types[col] = ENVIRONMENT;
1639  // ROS_DEBUG_STREAM("Link " << dfce->link_names_[i] << " sphere " <<
1640  // colls[j] << " in env collision");
1641  }
1642 
1643  gsr->gradients_[i].collision = true;
1644  if (res.contact_count >= req.max_contacts)
1645  {
1646  return true;
1647  }
1648  }
1649  }
1650  else
1651  {
1652  bool coll = getCollisionSphereCollision(env_distance_field.get(), *collision_spheres_1, *sphere_centers_1,
1654  if (coll)
1655  {
1656  res.collision = true;
1657  return true;
1658  }
1659  }
1660  }
1661  return (res.contact_count >= req.max_contacts);
1662 }
1663 
1665  const distance_field::DistanceFieldConstPtr& env_distance_field, GroupStateRepresentationPtr& gsr) const
1666 {
1667  bool in_collision = false;
1668  for (unsigned int i = 0; i < gsr->dfce_->link_names_.size(); i++)
1669  {
1670  bool is_link = i < gsr->dfce_->link_names_.size();
1671 
1672  if (is_link && !gsr->dfce_->link_has_geometry_[i])
1673  {
1674  continue;
1675  }
1676 
1677  const std::vector<CollisionSphere>* collision_spheres_1;
1678  const EigenSTL::vector_Vector3d* sphere_centers_1;
1679  if (is_link)
1680  {
1681  collision_spheres_1 = &(gsr->link_body_decompositions_[i]->getCollisionSpheres());
1682  sphere_centers_1 = &(gsr->link_body_decompositions_[i]->getSphereCenters());
1683  }
1684  else
1685  {
1686  collision_spheres_1 =
1687  &(gsr->attached_body_decompositions_[i - gsr->dfce_->link_names_.size()]->getCollisionSpheres());
1688  sphere_centers_1 = &(gsr->attached_body_decompositions_[i - gsr->dfce_->link_names_.size()]->getSphereCenters());
1689  }
1690 
1691  bool coll = getCollisionSphereGradients(env_distance_field.get(), *collision_spheres_1, *sphere_centers_1,
1692  gsr->gradients_[i], ENVIRONMENT, collision_tolerance_, false,
1693  max_propogation_distance_, false);
1694  if (coll)
1695  {
1696  in_collision = true;
1697  }
1698  }
1699  return in_collision;
1700 }
1701 
1702 void CollisionEnvDistanceField::setWorld(const WorldPtr& world)
1703 {
1704  if (world == getWorld())
1705  return;
1706 
1707  // turn off notifications about old world
1708  getWorld()->removeObserver(observer_handle_);
1709 
1710  // clear out objects from old world
1711  distance_field_cache_entry_world_->distance_field_->reset();
1712 
1713  CollisionEnv::setWorld(world);
1714 
1715  // request notifications about changes to new world
1716  observer_handle_ = getWorld()->addObserver(
1717  [this](const World::ObjectConstPtr& object, World::Action action) { return notifyObjectChange(object, action); });
1718 
1719  // get notifications any objects already in the new world
1720  getWorld()->notifyObserverAllObjects(observer_handle_, World::CREATE);
1721 }
1722 
1723 void CollisionEnvDistanceField::notifyObjectChange(const ObjectConstPtr& obj, World::Action action)
1724 {
1726 
1727  EigenSTL::vector_Vector3d add_points;
1728  EigenSTL::vector_Vector3d subtract_points;
1729  updateDistanceObject(obj->id_, distance_field_cache_entry_world_, add_points, subtract_points);
1730 
1731  if (action == World::DESTROY)
1732  {
1733  distance_field_cache_entry_world_->distance_field_->removePointsFromField(subtract_points);
1734  }
1735  else if (action & (World::MOVE_SHAPE | World::REMOVE_SHAPE))
1736  {
1737  distance_field_cache_entry_world_->distance_field_->removePointsFromField(subtract_points);
1738  distance_field_cache_entry_world_->distance_field_->addPointsToField(add_points);
1739  }
1740  else
1741  {
1742  distance_field_cache_entry_world_->distance_field_->addPointsToField(add_points);
1743  }
1744 
1745  ROS_DEBUG_NAMED("collision_distance_field", "Modifying object %s took %lf s", obj->id_.c_str(),
1746  (ros::WallTime::now() - n).toSec());
1747 }
1748 
1749 void CollisionEnvDistanceField::updateDistanceObject(const std::string& id, DistanceFieldCacheEntryWorldPtr& dfce,
1750  EigenSTL::vector_Vector3d& add_points,
1751  EigenSTL::vector_Vector3d& subtract_points)
1752 {
1753  std::map<std::string, std::vector<PosedBodyPointDecompositionPtr>>::iterator cur_it =
1754  dfce->posed_body_point_decompositions_.find(id);
1755  if (cur_it != dfce->posed_body_point_decompositions_.end())
1756  {
1757  for (collision_detection::PosedBodyPointDecompositionPtr& posed_body_point_decomposition : cur_it->second)
1758  {
1759  subtract_points.insert(subtract_points.end(), posed_body_point_decomposition->getCollisionPoints().begin(),
1760  posed_body_point_decomposition->getCollisionPoints().end());
1761  }
1762  }
1763 
1764  World::ObjectConstPtr object = getWorld()->getObject(id);
1765  if (object)
1766  {
1767  ROS_DEBUG_STREAM("Updating/Adding Object '" << object->id_ << "' with " << object->shapes_.size()
1768  << " shape(s) to CollisionEnvDistanceField");
1769  std::vector<PosedBodyPointDecompositionPtr> shape_points;
1770  for (unsigned int i = 0; i < object->shapes_.size(); i++)
1771  {
1772  shapes::ShapeConstPtr shape = object->shapes_[i];
1773  if (shape->type == shapes::OCTREE)
1774  {
1775  const shapes::OcTree* octree_shape = static_cast<const shapes::OcTree*>(shape.get());
1776  std::shared_ptr<const octomap::OcTree> octree = octree_shape->octree;
1777 
1778  shape_points.push_back(std::make_shared<PosedBodyPointDecomposition>(octree));
1779  }
1780  else
1781  {
1782  BodyDecompositionConstPtr bd = getBodyDecompositionCacheEntry(shape, resolution_);
1783  shape_points.push_back(
1784  std::make_shared<PosedBodyPointDecomposition>(bd, getWorld()->getGlobalShapeTransform(id, i)));
1785  }
1786 
1787  add_points.insert(add_points.end(), shape_points.back()->getCollisionPoints().begin(),
1788  shape_points.back()->getCollisionPoints().end());
1789  }
1790 
1791  dfce->posed_body_point_decompositions_[id] = shape_points;
1792  }
1793  else
1794  {
1795  ROS_DEBUG_STREAM("Removing Object '" << id << "' from CollisionEnvDistanceField");
1796  dfce->posed_body_point_decompositions_.erase(id);
1797  }
1798 }
1799 
1800 CollisionEnvDistanceField::DistanceFieldCacheEntryWorldPtr
1802 {
1803  DistanceFieldCacheEntryWorldPtr dfce(new DistanceFieldCacheEntryWorld());
1804  dfce->distance_field_ = std::make_shared<distance_field::PropagationDistanceField>(
1805  size_.x(), size_.y(), size_.z(), resolution_, origin_.x() - 0.5 * size_.x(), origin_.y() - 0.5 * size_.y(),
1807 
1808  EigenSTL::vector_Vector3d add_points;
1809  EigenSTL::vector_Vector3d subtract_points;
1810  for (const std::pair<const std::string, ObjectPtr>& object : *getWorld())
1811  {
1812  updateDistanceObject(object.first, dfce, add_points, subtract_points);
1813  }
1814  dfce->distance_field_->addPointsToField(add_points);
1815  return dfce;
1816 }
1817 
1818 const std::string& CollisionDetectorAllocatorDistanceField::getName() const
1819 {
1820  return NAME;
1821 }
1822 
1823 } // namespace collision_detection
collision_detection::INTRA
@ INTRA
Definition: collision_distance_field_types.h:125
moveit::core::LinkModel
A link from the robot. Contains the constant transform applied to the link and its geometry.
Definition: link_model.h:71
moveit::core
Core components of MoveIt.
Definition: kinematics_base.h:83
collision_detection::CollisionEnvDistanceField::observer_handle_
World::ObserverHandle observer_handle_
Definition: collision_env_distance_field.h:337
collision_common_distance_field.h
collision_detection::Contact::body_type_1
BodyType body_type_1
The type of the first body involved in the contact.
Definition: include/moveit/collision_detection/collision_common.h:122
collision_detection::World::DESTROY
@ DESTROY
Definition: world.h:259
initialize
bool initialize(MeshCollisionTraversalNode< BV > &node, BVHModel< BV > &model1, Transform3< typename BV::S > &tf1, BVHModel< BV > &model2, Transform3< typename BV::S > &tf2, const CollisionRequest< typename BV::S > &request, CollisionResult< typename BV::S > &result, bool use_refit, bool refit_bottomup)
shapes::OcTree::octree
std::shared_ptr< const octomap::OcTree > octree
collision_detection::CollisionEnvDistanceField::~CollisionEnvDistanceField
~CollisionEnvDistanceField() override
Definition: collision_env_distance_field.cpp:150
moveit::core::RobotState::getVariableCount
std::size_t getVariableCount() const
Get the number of variables that make up this state.
Definition: robot_state.h:176
EPSILON
constexpr double EPSILON
Definition: test_kinematic_complex.cpp:49
moveit::core::JointModelGroup
Definition: joint_model_group.h:134
collision_detection::CollisionEnvDistanceField::updateGroupStateRepresentationState
void updateGroupStateRepresentationState(const moveit::core::RobotState &state, GroupStateRepresentationPtr &gsr) const
Definition: collision_env_distance_field.cpp:1150
collision_detection::BodyTypes::WORLD_OBJECT
@ WORLD_OBJECT
A body in the environment.
Definition: include/moveit/collision_detection/collision_common.h:97
collision_detection::CollisionEnvDistanceField::use_signed_distance_field_
bool use_signed_distance_field_
Definition: collision_env_distance_field.h:319
tf2_eigen.h
collision_detection::AllowedCollisionMatrix::getSize
std::size_t getSize() const
Get the size of the allowed collision matrix (number of specified entries)
Definition: collision_matrix.h:226
collision_detection::CollisionEnvDistanceField::getPosedLinkBodyPointDecomposition
PosedBodyPointDecompositionPtr getPosedLinkBodyPointDecomposition(const moveit::core::LinkModel *ls) const
Definition: collision_env_distance_field.cpp:1137
propagation_distance_field.h
collision_detection::CollisionEnvDistanceField::distance_field_cache_entry_
DistanceFieldCacheEntryPtr distance_field_cache_entry_
Definition: collision_env_distance_field.h:328
moveit::core::RobotState::getLinkModel
const LinkModel * getLinkModel(const std::string &link) const
Get the model of a particular link.
Definition: robot_state.h:188
getName
ROSCONSOLE_CONSOLE_IMPL_DECL std::string getName(void *handle)
collision_detection::CollisionEnvDistanceField::checkSelfCollisionHelper
void checkSelfCollisionHelper(const collision_detection::CollisionRequest &req, collision_detection::CollisionResult &res, const moveit::core::RobotState &state, const collision_detection::AllowedCollisionMatrix *acm, GroupStateRepresentationPtr &gsr) const
Definition: collision_env_distance_field.cpp:214
collision_detection::AllowedCollisionMatrix::getEntry
bool getEntry(const std::string &name1, const std::string &name2, AllowedCollision::Type &allowed_collision_type) const
Get the type of the allowed collision between two elements. Return true if the entry is included in t...
Definition: collision_matrix.cpp:145
moveit::core::JointModel::getName
const std::string & getName() const
Get the name of the joint.
Definition: joint_model.h:196
collision_detection::CollisionEnvDistanceField::generateDistanceFieldCacheEntry
DistanceFieldCacheEntryPtr generateDistanceFieldCacheEntry(const std::string &group_name, const moveit::core::RobotState &state, const collision_detection::AllowedCollisionMatrix *acm, bool generate_distance_field) const
Definition: collision_env_distance_field.cpp:760
ROS_DEBUG
#define ROS_DEBUG(...)
moveit::core::LinkModel::getParentJointModel
const JointModel * getParentJointModel() const
Get the joint model whose child this link is. There will always be a parent joint.
Definition: link_model.h:107
ROS_DEBUG_COND
#define ROS_DEBUG_COND(cond,...)
collision_detection::AllowedCollision::ALWAYS
@ ALWAYS
Collisions between a particular pair of bodies does not imply that the robot configuration is in coll...
Definition: collision_matrix.h:157
collision_detection::CollisionEnvDistanceField::getIntraGroupProximityGradients
bool getIntraGroupProximityGradients(GroupStateRepresentationPtr &gsr) const
Definition: collision_env_distance_field.cpp:694
collision_detection::SELF
@ SELF
Definition: collision_distance_field_types.h:124
moveit::core::RobotState::getAttachedBody
const AttachedBody * getAttachedBody(const std::string &name) const
Get the attached body named name. Return NULL if not found.
Definition: robot_state.cpp:1075
collision_detection::World::Action
Represents an action that occurred on an object in the world. Several bits may be set indicating seve...
Definition: world.h:268
ROS_ERROR_NAMED
#define ROS_ERROR_NAMED(name,...)
moveit::core::RobotState
Representation of a robot's state. This includes position, velocity, acceleration and effort.
Definition: robot_state.h:155
collision_env_distance_field.h
moveit::core::RobotState::getGlobalLinkTransform
const Eigen::Isometry3d & getGlobalLinkTransform(const std::string &link_name)
Get the link transform w.r.t. the root link (model frame) of the RobotModel. This is typically the ro...
Definition: robot_state.h:1394
collision_detection::CollisionEnvDistanceField::compareCacheEntryToState
bool compareCacheEntryToState(const DistanceFieldCacheEntryConstPtr &dfce, const moveit::core::RobotState &state) const
Definition: collision_env_distance_field.cpp:1302
collision_detection::CollisionEnvDistanceField::planning_scene_
planning_scene::PlanningScenePtr planning_scene_
Definition: collision_env_distance_field.h:332
collision_detection::Contact
Definition of a contact point.
Definition: include/moveit/collision_detection/collision_common.h:105
collision_detection::CollisionEnvDistanceField::checkCollision
void checkCollision(const CollisionRequest &req, CollisionResult &res, const moveit::core::RobotState &state) const override
Check whether the robot model is in collision with itself or the world at a particular state....
Definition: collision_env_distance_field.cpp:1433
ROS_DEBUG_STREAM
#define ROS_DEBUG_STREAM(args)
collision_detection::CollisionEnvDistanceField::pregenerated_group_state_representation_map_
std::map< std::string, GroupStateRepresentationPtr > pregenerated_group_state_representation_map_
Definition: collision_env_distance_field.h:330
obj
CollisionObject< S > * obj
collision_detection::CollisionRequest
Representation of a collision checking request.
Definition: include/moveit/collision_detection/collision_common.h:179
collision_detection::getAttachedBodyPointDecomposition
PosedBodyPointDecompositionVectorPtr getAttachedBodyPointDecomposition(const moveit::core::AttachedBody *att, double resolution)
Definition: collision_common_distance_field.cpp:149
robot_model.h
collision_detection::doBoundingSpheresIntersect
bool doBoundingSpheresIntersect(const PosedBodySphereDecompositionConstPtr &p1, const PosedBodySphereDecompositionConstPtr &p2)
Definition: collision_distance_field_types.cpp:410
moveit::core::RobotState::getVariableNames
const std::vector< std::string > & getVariableNames() const
Get the names of the variables that make up this state, in the order they are stored in memory.
Definition: robot_state.h:182
collision_detection::Contact::body_name_2
std::string body_name_2
The id of the second body involved in the contact.
Definition: include/moveit/collision_detection/collision_common.h:125
collision_detection::Contact::body_type_2
BodyType body_type_2
The type of the second body involved in the contact.
Definition: include/moveit/collision_detection/collision_common.h:128
collision_detection::CollisionEnvDistanceField::getEnvironmentCollisions
bool getEnvironmentCollisions(const CollisionRequest &req, CollisionResult &res, const distance_field::DistanceFieldConstPtr &env_distance_field, GroupStateRepresentationPtr &gsr) const
Definition: collision_env_distance_field.cpp:1612
moveit::core::AttachedBody
Object defining bodies that can be attached to robot links.
Definition: attached_body.h:121
collision_detection::Contact::body_name_1
std::string body_name_1
The id of the first body involved in the contact.
Definition: include/moveit/collision_detection/collision_common.h:119
collision_detection::CollisionEnvDistanceField::distance_field_cache_entry_world_
DistanceFieldCacheEntryWorldPtr distance_field_cache_entry_world_
Definition: collision_env_distance_field.h:335
collision_detection::CollisionEnvDistanceField::size_
Eigen::Vector3d size_
Definition: collision_env_distance_field.h:317
console.h
ROS_WARN_STREAM
#define ROS_WARN_STREAM(args)
collision_detection::AllowedCollisionMatrix
Definition of a structure for the allowed collision matrix.
Definition: collision_matrix.h:112
collision_detection::CollisionEnvDistanceField::update_cache_lock_
boost::mutex update_cache_lock_
Definition: collision_env_distance_field.h:327
collision_detection::NAME
static const std::string NAME
Definition: collision_env_fcl.cpp:81
collision_detection::CollisionEnvDistanceField::getSelfProximityGradients
bool getSelfProximityGradients(GroupStateRepresentationPtr &gsr) const
Definition: collision_env_distance_field.cpp:390
collision_detection::CollisionEnvDistanceField::collision_tolerance_
double collision_tolerance_
Definition: collision_env_distance_field.h:321
collision_detection::CollisionEnvDistanceField::compareCacheEntryToAllowedCollisionMatrix
bool compareCacheEntryToAllowedCollisionMatrix(const DistanceFieldCacheEntryConstPtr &dfce, const collision_detection::AllowedCollisionMatrix &acm) const
Definition: collision_env_distance_field.cpp:1362
collision_detection::CollisionEnv::setPadding
void setPadding(double padding)
Set the link padding (for every link)
Definition: collision_env.cpp:111
ROS_DEBUG_NAMED
#define ROS_DEBUG_NAMED(name,...)
collision_detection::CollisionResult
Representation of a collision checking result.
Definition: include/moveit/collision_detection/collision_common.h:382
collision_detection::AllowedCollision::Type
Type
Definition: collision_matrix.h:117
collision_detection::CollisionEnvDistanceField::in_group_update_map_
std::map< std::string, std::map< std::string, bool > > in_group_update_map_
Definition: collision_env_distance_field.h:329
ros::WallTime::now
static WallTime now()
collision_detection::getCollisionSphereGradients
bool getCollisionSphereGradients(const distance_field::DistanceField *distance_field, const std::vector< CollisionSphere > &sphere_list, const EigenSTL::vector_Vector3d &sphere_centers, GradientInfo &gradient, const CollisionType &type, double tolerance, bool subtract_radii, double maximum_value, bool stop_at_first_collision)
Definition: collision_distance_field_types.cpp:143
EigenSTL::vector_Vector3d
std::vector< Eigen::Vector3d, Eigen::aligned_allocator< Eigen::Vector3d > > vector_Vector3d
collision_detection::CollisionRequest::max_contacts
std::size_t max_contacts
Overall maximum number of contacts to compute.
Definition: include/moveit/collision_detection/collision_common.h:212
collision_detection::CollisionEnvDistanceField::link_body_decomposition_vector_
std::vector< BodyDecompositionConstPtr > link_body_decomposition_vector_
Definition: collision_env_distance_field.h:324
collision_detection::CollisionEnvDistanceField::setWorld
void setWorld(const WorldPtr &world) override
Definition: collision_env_distance_field.cpp:1734
collision_detection::CollisionEnvDistanceField::getPosedLinkBodySphereDecomposition
PosedBodySphereDecompositionPtr getPosedLinkBodySphereDecomposition(const moveit::core::LinkModel *ls, unsigned int ind) const
Definition: collision_env_distance_field.cpp:1128
collision_detection::CollisionEnvDistanceField
Definition: collision_env_distance_field.h:90
moveit::core::RobotState::getVariablePosition
double getVariablePosition(const std::string &variable) const
Get the position of a particular variable. An exception is thrown if the variable is not known.
Definition: robot_state.h:273
collision_detection::CollisionRequest::group_name
std::string group_name
The group name to check collisions for (optional; if empty, assume the complete robot)
Definition: include/moveit/collision_detection/collision_common.h:197
collision_detection::CollisionEnvDistanceField::getAllCollisions
void getAllCollisions(const CollisionRequest &req, CollisionResult &res, const moveit::core::RobotState &state, const AllowedCollisionMatrix *acm, GroupStateRepresentationPtr &gsr) const
Definition: collision_env_distance_field.cpp:1591
moveit::core::JointModelGroup::getUpdatedLinkModelNames
const std::vector< std::string > & getUpdatedLinkModelNames() const
Get the names of the links returned by getUpdatedLinkModels()
Definition: joint_model_group.h:311
collision_detection::getBodyDecompositionCacheEntry
BodyDecompositionConstPtr getBodyDecompositionCacheEntry(const shapes::ShapeConstPtr &shape, double resolution)
Definition: collision_common_distance_field.cpp:97
moveit::core::AttachedBody::getGlobalCollisionBodyTransforms
const EigenSTL::vector_Isometry3d & getGlobalCollisionBodyTransforms() const
Get the global transforms (in world frame) for the collision bodies. The returned transforms are guar...
Definition: attached_body.h:256
ROS_ERROR
#define ROS_ERROR(...)
collision_detection::CollisionEnvBullet::notifyObjectChange
void notifyObjectChange(const ObjectConstPtr &obj, World::Action action)
Callback function executed for each change to the world environment.
Definition: collision_env_bullet.cpp:349
ROS_ASSERT_MSG
#define ROS_ASSERT_MSG(cond,...)
collision_detection::NONE
@ NONE
Definition: collision_distance_field_types.h:123
ROS_WARN
#define ROS_WARN(...)
collision_detection::BodyTypes::ROBOT_ATTACHED
@ ROBOT_ATTACHED
A body attached to a robot link.
Definition: include/moveit/collision_detection/collision_common.h:94
collision_detection::CollisionEnvDistanceField::generateCollisionCheckingStructures
void generateCollisionCheckingStructures(const std::string &group_name, const moveit::core::RobotState &state, const collision_detection::AllowedCollisionMatrix *acm, GroupStateRepresentationPtr &gsr, bool generate_distance_field) const
Definition: collision_env_distance_field.cpp:195
moveit::core::RobotState::getAttachedBodies
void getAttachedBodies(std::vector< const AttachedBody * > &attached_bodies) const
Get all bodies attached to the model corresponding to this state.
Definition: robot_state.cpp:1113
collision_detection::CollisionEnvDistanceField::origin_
Eigen::Vector3d origin_
Definition: collision_env_distance_field.h:318
collision_detection::CollisionEnvDistanceField::getSelfCollisions
bool getSelfCollisions(const collision_detection::CollisionRequest &req, collision_detection::CollisionResult &res, GroupStateRepresentationPtr &gsr) const
Definition: collision_env_distance_field.cpp:309
collision_detection::ENVIRONMENT
@ ENVIRONMENT
Definition: collision_distance_field_types.h:126
ros::WallTime
collision_detection::BodyTypes::ROBOT_LINK
@ ROBOT_LINK
A link on the robot.
Definition: include/moveit/collision_detection/collision_common.h:91
shapes::OcTree
collision_detection::CollisionEnvDistanceField::link_body_decomposition_index_map_
std::map< std::string, unsigned int > link_body_decomposition_index_map_
Definition: collision_env_distance_field.h:325
shapes::OCTREE
OCTREE
collision_detection::CollisionDetectorAllocatorDistanceField::getName
const std::string & getName() const override
Definition: collision_env_distance_field.cpp:1850
collision_detection::CollisionResult::contacts
ContactMap contacts
A map returning the pairs of body ids in contact, plus their contact details.
Definition: include/moveit/collision_detection/collision_common.h:418
moveit::core::RobotState::updateLinkTransforms
void updateLinkTransforms()
Update the reference frame transforms for links. This call is needed before using the transforms of l...
Definition: robot_state.cpp:770
collision_detection::CollisionEnvDistanceField::getGroupStateRepresentation
void getGroupStateRepresentation(const DistanceFieldCacheEntryConstPtr &dfce, const moveit::core::RobotState &state, GroupStateRepresentationPtr &gsr) const
Definition: collision_env_distance_field.cpp:1204
collision_detector_allocator_distance_field.h
collision_detection::Contact::pos
EIGEN_MAKE_ALIGNED_OPERATOR_NEW Eigen::Vector3d pos
contact position
Definition: include/moveit/collision_detection/collision_common.h:110
collision_detection::getCollisionSphereCollision
bool getCollisionSphereCollision(const distance_field::DistanceField *distance_field, const std::vector< CollisionSphere > &sphere_list, const EigenSTL::vector_Vector3d &sphere_centers, double maximum_value, double tolerance)
Definition: collision_distance_field_types.cpp:206
moveit::core::RobotState::getFrameTransform
const Eigen::Isometry3d & getFrameTransform(const std::string &frame_id, bool *frame_found=nullptr)
Get the transformation matrix from the model frame (root of model) to the frame identified by frame_i...
Definition: robot_state.cpp:1191
collision_detection::CollisionEnvDistanceField::updateDistanceObject
void updateDistanceObject(const std::string &id, CollisionEnvDistanceField::DistanceFieldCacheEntryWorldPtr &dfce, EigenSTL::vector_Vector3d &add_points, EigenSTL::vector_Vector3d &subtract_points)
Definition: collision_env_distance_field.cpp:1781
ros::Time
collision_detection::World::MOVE_SHAPE
@ MOVE_SHAPE
Definition: world.h:260
collision_detection::CollisionEnvDistanceField::addLinkBodyDecompositions
void addLinkBodyDecompositions(double resolution)
Definition: collision_env_distance_field.cpp:1009
collision_detection::CollisionEnvDistanceField::notifyObjectChange
void notifyObjectChange(const ObjectConstPtr &obj, World::Action action)
Definition: collision_env_distance_field.cpp:1755
moveit::core::JointModelGroup::getUpdatedLinkModels
const std::vector< const LinkModel * > & getUpdatedLinkModels() const
Get the names of the links that are to be updated when the state of this group changes....
Definition: joint_model_group.h:299
collision_detection::CollisionEnvDistanceField::getDistanceFieldCacheEntry
DistanceFieldCacheEntryConstPtr getDistanceFieldCacheEntry(const std::string &group_name, const moveit::core::RobotState &state, const collision_detection::AllowedCollisionMatrix *acm) const
Definition: collision_env_distance_field.cpp:239
collision_detection::CollisionRequest::contacts
bool contacts
If true, compute contacts. Otherwise only a binary collision yes/no is reported.
Definition: include/moveit/collision_detection/collision_common.h:209
collision_detection::CollisionEnv::getLinkPadding
const std::map< std::string, double > & getLinkPadding() const
Get the link paddings as a map (from link names to padding value)
Definition: collision_env.cpp:179
collision_detection::CollisionEnvDistanceField::getCollisionGradients
void getCollisionGradients(const CollisionRequest &req, CollisionResult &res, const moveit::core::RobotState &state, const AllowedCollisionMatrix *acm, GroupStateRepresentationPtr &gsr) const
Definition: collision_env_distance_field.cpp:1568
moveit::core::AttachedBody::getShapes
const std::vector< shapes::ShapeConstPtr > & getShapes() const
Get the shapes that make up this attached body.
Definition: attached_body.h:168
collision_detection::CollisionEnvDistanceField::initialize
void initialize(const std::map< std::string, std::vector< CollisionSphere >> &link_body_decompositions, const Eigen::Vector3d &size, const Eigen::Vector3d &origin, bool use_signed_distance_field, double resolution, double collision_tolerance, double max_propogation_distance)
Definition: collision_env_distance_field.cpp:155
collision_detection::CollisionEnvDistanceField::CollisionEnvDistanceField
EIGEN_MAKE_ALIGNED_OPERATOR_NEW CollisionEnvDistanceField(const moveit::core::RobotModelConstPtr &robot_model, const std::map< std::string, std::vector< CollisionSphere >> &link_body_decompositions=std::map< std::string, std::vector< CollisionSphere >>(), double size_x=DEFAULT_SIZE_X, double size_y=DEFAULT_SIZE_Y, double size_z=DEFAULT_SIZE_Z, const Eigen::Vector3d &origin=Eigen::Vector3d(0, 0, 0), bool use_signed_distance_field=DEFAULT_USE_SIGNED_DISTANCE_FIELD, double resolution=DEFAULT_RESOLUTION, double collision_tolerance=DEFAULT_COLLISION_TOLERANCE, double max_propogation_distance=DEFAULT_MAX_PROPOGATION_DISTANCE, double padding=0.0, double scale=1.0)
Definition: collision_env_distance_field.cpp:89
tf2::toMsg
B toMsg(const A &a)
collision_detection::CollisionEnvDistanceField::getEnvironmentProximityGradients
bool getEnvironmentProximityGradients(const distance_field::DistanceFieldConstPtr &env_distance_field, GroupStateRepresentationPtr &gsr) const
Definition: collision_env_distance_field.cpp:1696
shapes::ShapeConstPtr
std::shared_ptr< const Shape > ShapeConstPtr
collision_detection::CollisionResult::collision
bool collision
True if collision was found, false otherwise.
Definition: include/moveit/collision_detection/collision_common.h:406
collision_detection::CollisionEnvDistanceField::checkRobotCollision
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...
Definition: collision_env_distance_field.cpp:1498
collision_detection::CollisionEnvDistanceField::getIntraGroupCollisions
bool getIntraGroupCollisions(const collision_detection::CollisionRequest &req, collision_detection::CollisionResult &res, GroupStateRepresentationPtr &gsr) const
Definition: collision_env_distance_field.cpp:465
collision_detection::PosedBodySphereDecomposition
Definition: collision_distance_field_types.h:325
collision_detection::CollisionEnvDistanceField::generateDistanceFieldCacheEntryWorld
DistanceFieldCacheEntryWorldPtr generateDistanceFieldCacheEntryWorld()
Definition: collision_env_distance_field.cpp:1833
collision_detection::CollisionEnv::setWorld
virtual void setWorld(const WorldPtr &world)
Definition: collision_env.cpp:282
moveit::core::LinkModel::getShapes
const std::vector< shapes::ShapeConstPtr > & getShapes() const
Get shape associated to the collision geometry for this link.
Definition: link_model.h:175
collision_detection::CollisionRequest::max_contacts_per_pair
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...
Definition: include/moveit/collision_detection/collision_common.h:216
moveit::core::LinkModel::getName
const std::string & getName() const
The name of this link.
Definition: link_model.h:80
collision_detection::World::CREATE
@ CREATE
Definition: world.h:258
moveit::core::RobotState::getJointModelGroup
const JointModelGroup * getJointModelGroup(const std::string &group) const
Get the model of a particular joint group.
Definition: robot_state.h:200
assert.h
collision_detection::CollisionEnvDistanceField::max_propogation_distance_
double max_propogation_distance_
Definition: collision_env_distance_field.h:322
collision_detection::CollisionResult::contact_count
std::size_t contact_count
Number of contacts returned.
Definition: include/moveit/collision_detection/collision_common.h:415
ros::Duration
collision_detection::CollisionEnv::robot_model_
moveit::core::RobotModelConstPtr robot_model_
The kinematic model corresponding to this collision model.
Definition: collision_env.h:342
collision_detection::getAttachedBodySphereDecomposition
PosedBodySphereDecompositionVectorPtr getAttachedBodySphereDecomposition(const moveit::core::AttachedBody *att, double resolution)
Definition: collision_common_distance_field.cpp:135
collision_detection::CollisionEnvDistanceField::resolution_
double resolution_
Definition: collision_env_distance_field.h:320
collision_detection::CollisionEnvDistanceField::checkSelfCollision
void checkSelfCollision(const collision_detection::CollisionRequest &req, collision_detection::CollisionResult &res, const moveit::core::RobotState &state) const override
Check for robot self collision. Any collision between any pair of links is checked for,...
Definition: collision_env_distance_field.cpp:270
t
geometry_msgs::TransformStamped t
collision_detection::CollisionEnvDistanceField::createCollisionModelMarker
void createCollisionModelMarker(const moveit::core::RobotState &state, visualization_msgs::MarkerArray &model_markers) const
Definition: collision_env_distance_field.cpp:1029
moveit::core::JointModel
A joint from the robot. Models the transform that this joint applies in the kinematic chain....
Definition: joint_model.h:173
collision_detection::AllowedCollision::NEVER
@ NEVER
Collisions between the pair of bodies is never ok, i.e., if two bodies are in contact in a particular...
Definition: collision_matrix.h:153
collision_detection::World::REMOVE_SHAPE
@ REMOVE_SHAPE
Definition: world.h:262
collision_detection::CollisionEnv::getWorld
const WorldPtr & getWorld()
Definition: collision_env.h:267
fcl::Vector3d
Vec3fX< details::Vec3Data< double > > Vector3d
Definition: fcl_compat.h:89
collision_detection::CollisionEnvBullet::observer_handle_
World::ObserverHandle observer_handle_
Definition: collision_env_bullet.h:210
collision_detection
Definition: collision_detector_allocator_allvalid.h:42


moveit_core
Author(s): Ioan Sucan , Sachin Chitta , Acorn Pooley
autogenerated on Sun Nov 3 2024 03:26:14