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