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>
55 rclcpp::get_logger(
"moveit_collision_distance_field.collision_robot_distance_field");
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 ,
double )
68 resolution, collision_tolerance, max_propogation_distance);
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)
87 resolution, collision_tolerance, max_propogation_distance);
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)
141 const std::vector<const moveit::core::JointModelGroup*>& jmg =
robot_model_->getJointModelGroups();
144 std::map<std::string, bool> updated_group_entry;
145 std::vector<std::string> links = jm->getUpdatedLinkModelsWithGeometryNames();
146 for (
const std::string& link : links)
148 updated_group_entry[link] =
true;
152 DistanceFieldCacheEntryPtr dfce =
161 bool generate_distance_field)
const
164 if (!dfce || (generate_distance_field && !dfce->distance_field_))
168 DistanceFieldCacheEntryPtr new_dfce =
181 GroupStateRepresentationPtr& gsr)
const
198 RCLCPP_DEBUG(
LOGGER,
"Intra Group Collision found");
202 DistanceFieldCacheEntryConstPtr
207 DistanceFieldCacheEntryConstPtr ret;
210 RCLCPP_DEBUG(
LOGGER,
" No current Distance field cache entry");
214 if (group_name != cur->group_name_)
216 RCLCPP_DEBUG(
LOGGER,
"No cache entry as group name changed from %s to %s", cur->group_name_.c_str(),
229 RCLCPP_DEBUG(
LOGGER,
"Regenerating distance field as some relevant part of the acm changed");
239 GroupStateRepresentationPtr gsr;
246 GroupStateRepresentationPtr& gsr)
const
256 GroupStateRepresentationPtr gsr;
264 GroupStateRepresentationPtr& gsr)
const
268 RCLCPP_WARN(
LOGGER,
"Shouldn't be calling this function with initialized gsr - ACM "
276 GroupStateRepresentationPtr& gsr)
const
278 for (
unsigned int i = 0; i < gsr->dfce_->link_names_.size() + gsr->dfce_->attached_body_names_.size(); ++i)
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])
283 const std::vector<CollisionSphere>* collision_spheres_1;
284 const EigenSTL::vector_Vector3d* sphere_centers_1;
288 collision_spheres_1 = &(gsr->link_body_decompositions_[i]->getCollisionSpheres());
289 sphere_centers_1 = &(gsr->link_body_decompositions_[i]->getSphereCenters());
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());
300 std::vector<unsigned int> colls;
308 for (
unsigned int col : colls)
313 con.
pos = gsr->link_body_decompositions_[i]->getSphereCenters()[col];
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()];
324 RCLCPP_DEBUG(
LOGGER,
"Self collision detected for link %s ", con.
body_name_1.c_str());
330 gsr->gradients_[i].types[col] =
SELF;
332 gsr->gradients_[i].collision =
true;
346 RCLCPP_DEBUG(
LOGGER,
"Link %s in self collision", gsr->dfce_->link_names_[i].c_str());
357 bool in_collision =
false;
359 for (
unsigned int i = 0; i < gsr->dfce_->link_names_.size(); ++i)
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])
368 const std::vector<CollisionSphere>* collision_spheres_1;
369 const EigenSTL::vector_Vector3d* sphere_centers_1;
372 collision_spheres_1 = &(gsr->link_body_decompositions_[i]->getCollisionSpheres());
373 sphere_centers_1 = &(gsr->link_body_decompositions_[i]->getSphereCenters());
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());
385 if (gsr->dfce_->acm_.getSize() > 0)
388 for (
unsigned int j = 0; j < gsr->dfce_->link_names_.size(); ++j)
391 if (link_name == gsr->dfce_->link_names_[j])
397 if (gsr->dfce_->acm_.getEntry(link_name, gsr->dfce_->link_names_[j], col_type) &&
403 if (gsr->link_distance_fields_[j])
405 coll = gsr->link_distance_fields_[j]->getCollisionSphereGradients(
432 GroupStateRepresentationPtr& gsr)
const
434 unsigned int num_links = gsr->dfce_->link_names_.size();
435 unsigned int num_attached_bodies = gsr->dfce_->attached_body_names_.size();
437 for (
unsigned int i = 0; i < num_links + num_attached_bodies; ++i)
439 for (
unsigned int j = i + 1; j < num_links + num_attached_bodies; ++j)
443 bool i_is_link = i < num_links;
444 bool j_is_link = j < num_links;
446 if ((i_is_link && !gsr->dfce_->link_has_geometry_[i]) || (j_is_link && !gsr->dfce_->link_has_geometry_[j]))
449 if (!gsr->dfce_->intra_group_collision_enabled_[i][j])
452 if (i_is_link && j_is_link &&
460 else if (!i_is_link || !j_is_link)
463 if (!i_is_link && j_is_link)
465 for (
unsigned int k = 0; k < gsr->attached_body_decompositions_[i - num_links]->getSize(); ++k)
468 gsr->link_body_decompositions_[j],
469 gsr->attached_body_decompositions_[i - num_links]->getPosedBodySphereDecomposition(k)))
476 else if (i_is_link && !j_is_link)
478 for (
unsigned int k = 0; k < gsr->attached_body_decompositions_[j - num_links]->getSize(); ++k)
481 gsr->link_body_decompositions_[i],
482 gsr->attached_body_decompositions_[j - num_links]->getPosedBodySphereDecomposition(k)))
491 for (
unsigned int k = 0; k < gsr->attached_body_decompositions_[i - num_links]->getSize() && all_ok; ++k)
493 for (
unsigned int l = 0; l < gsr->attached_body_decompositions_[j - num_links]->getSize(); ++l)
496 gsr->attached_body_decompositions_[i - num_links]->getPosedBodySphereDecomposition(k),
497 gsr->attached_body_decompositions_[j - num_links]->getPosedBodySphereDecomposition(l)))
518 name_1 = gsr->dfce_->link_names_[i];
522 name_1 = gsr->dfce_->attached_body_names_[i - num_links];
527 name_2 = gsr->dfce_->link_names_[j];
531 name_2 = gsr->dfce_->attached_body_names_[j - num_links];
535 collision_detection::CollisionResult::ContactMap::iterator it =
536 res.
contacts.find(std::pair<std::string, std::string>(name_1, name_2));
543 num_pair = it->second.size();
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;
552 collision_spheres_1 = &(gsr->link_body_decompositions_[i]->getCollisionSpheres());
553 sphere_centers_1 = &(gsr->link_body_decompositions_[i]->getSphereCenters());
557 collision_spheres_1 = &(gsr->attached_body_decompositions_[i - num_links]->getCollisionSpheres());
558 sphere_centers_1 = &(gsr->attached_body_decompositions_[i - num_links]->getSphereCenters());
562 collision_spheres_2 = &(gsr->link_body_decompositions_[j]->getCollisionSpheres());
563 sphere_centers_2 = &(gsr->link_body_decompositions_[j]->getSphereCenters());
567 collision_spheres_2 = &(gsr->attached_body_decompositions_[j - num_links]->getCollisionSpheres());
568 sphere_centers_2 = &(gsr->attached_body_decompositions_[j - num_links]->getSphereCenters());
571 for (
unsigned int k = 0;
574 for (
unsigned int l = 0;
577 Eigen::Vector3d gradient = (*sphere_centers_1)[k] - (*sphere_centers_2)[l];
578 double dist = gradient.norm();
583 if (dist < (*collision_spheres_1)[k].radius_ + (*collision_spheres_2)[l].radius_)
601 con.
pos = gsr->link_body_decompositions_[i]->getSphereCenters()[k];
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;
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();
650 for (
unsigned int i = 0; i < num_links + num_attached_bodies; ++i)
652 for (
unsigned int j = i + 1; j < num_links + num_attached_bodies; ++j)
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]))
660 if (!gsr->dfce_->intra_group_collision_enabled_[i][j])
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;
668 collision_spheres_1 = &(gsr->link_body_decompositions_[i]->getCollisionSpheres());
669 sphere_centers_1 = &(gsr->link_body_decompositions_[i]->getSphereCenters());
673 collision_spheres_1 = &(gsr->attached_body_decompositions_[i - num_links]->getCollisionSpheres());
674 sphere_centers_1 = &(gsr->attached_body_decompositions_[i - num_links]->getSphereCenters());
678 collision_spheres_2 = &(gsr->link_body_decompositions_[j]->getCollisionSpheres());
679 sphere_centers_2 = &(gsr->link_body_decompositions_[j]->getSphereCenters());
683 collision_spheres_2 = &(gsr->attached_body_decompositions_[j - num_links]->getCollisionSpheres());
684 sphere_centers_2 = &(gsr->attached_body_decompositions_[j - num_links]->getSphereCenters());
686 for (
unsigned int k = 0; k < collision_spheres_1->size(); ++k)
688 for (
unsigned int l = 0; l < collision_spheres_2->size(); ++l)
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])
694 gsr->gradients_[i].distances[k] = dist;
695 gsr->gradients_[i].gradients[k] = gradient;
696 gsr->gradients_[i].types[k] =
INTRA;
698 if (dist < gsr->gradients_[j].distances[l])
700 gsr->gradients_[j].distances[l] = dist;
701 gsr->gradients_[j].gradients[l] = -gradient;
702 gsr->gradients_[j].types[l] =
INTRA;
714 DistanceFieldCacheEntryPtr dfce = std::make_shared<DistanceFieldCacheEntry>();
716 if (
robot_model_->getJointModelGroup(group_name) ==
nullptr)
718 RCLCPP_WARN(
LOGGER,
"No group %s", group_name.c_str());
722 dfce->group_name_ = group_name;
723 dfce->state_ = std::make_shared<moveit::core::RobotState>(state);
730 RCLCPP_WARN(
LOGGER,
"Allowed Collision Matrix is null, enabling all collisions "
731 "in the DistanceFieldCacheEntry");
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;
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);
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());
748 for (
unsigned int i = 0; i < dfce->link_names_.size(); ++i)
750 std::string link_name = dfce->link_names_[i];
754 for (
unsigned int j = 0; j < lsv.size(); ++j)
756 if (lsv[j]->getName() == link_name)
758 dfce->link_state_indices_.push_back(j);
766 RCLCPP_DEBUG(
LOGGER,
"No link state found for link %s", dfce->link_names_[i].c_str());
772 dfce->link_has_geometry_.push_back(
true);
780 dfce->self_collision_enabled_[i] =
false;
783 dfce->intra_group_collision_enabled_[i] = all_true;
784 for (
unsigned int j = i + 1; j < dfce->link_names_.size(); ++j)
786 if (link_name == dfce->link_names_[j])
788 dfce->intra_group_collision_enabled_[i][j] =
false;
793 dfce->intra_group_collision_enabled_[i][j] =
false;
797 std::vector<const moveit::core::AttachedBody*> link_attached_bodies;
799 for (
unsigned int j = 0; j < link_attached_bodies.size(); ++j, ++att_count)
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]);
804 if (acm->
getEntry(link_name, link_attached_bodies[j]->getName(), t))
808 dfce->intra_group_collision_enabled_[i][att_count + dfce->link_names_.size()] =
false;
816 if (link_attached_bodies[j]->getTouchLinks().find(link_name) != link_attached_bodies[j]->getTouchLinks().end())
818 dfce->intra_group_collision_enabled_[i][att_count + dfce->link_names_.size()] =
false;
827 dfce->self_collision_enabled_[i] =
true;
828 dfce->intra_group_collision_enabled_[i] = all_true;
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;
840 for (
unsigned int i = 0; i < dfce->attached_body_names_.size(); ++i)
842 dfce->intra_group_collision_enabled_[i + dfce->link_names_.size()] = all_true;
846 if (acm->
getEntry(dfce->attached_body_names_[i], dfce->attached_body_names_[i], t) &&
849 dfce->self_collision_enabled_[i + dfce->link_names_.size()] =
false;
851 for (
unsigned int j = i + 1; j < dfce->attached_body_names_.size(); ++j)
853 if (acm->
getEntry(dfce->attached_body_names_[i], dfce->attached_body_names_[j], t) &&
856 dfce->intra_group_collision_enabled_[i + dfce->link_names_.size()][j + dfce->link_names_.size()] =
false;
867 std::map<std::string, GroupStateRepresentationPtr>::const_iterator it =
871 dfce->pregenerated_group_state_representation_ = it->second;
874 std::map<std::string, bool> updated_map;
875 if (!dfce->link_names_.empty())
877 const std::vector<const moveit::core::JointModel*>& child_joint_models =
878 dfce->state_->getJointModelGroup(dfce->group_name_)->getActiveJointModels();
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());
886 const std::vector<std::string>& state_variable_names = state.
getVariableNames();
887 for (
const std::string& state_variable_name : state_variable_names)
890 dfce->state_values_.push_back(val);
891 if (updated_map.count(state_variable_name) == 0)
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());
898 if (generate_distance_field)
900 if (dfce->distance_field_)
902 RCLCPP_DEBUG(
LOGGER,
"CollisionRobot skipping distance field generation, "
903 "will use existing one");
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;
912 const std::string& link_name = link_model->getName();
914 if (updated_group_map.find(link_name) != updated_group_map.end())
921 non_group_link_decompositions.back()->updatePose(dfce->state_->getFrameTransform(link_state->
getName()));
923 std::vector<const moveit::core::AttachedBody*> attached_bodies;
924 dfce->state_->getAttachedBodies(attached_bodies, link_state);
927 non_group_attached_body_decompositions.push_back(
931 dfce->distance_field_ = std::make_shared<distance_field::PropagationDistanceField>(
938 EigenSTL::vector_Vector3d all_points;
939 for (collision_detection::PosedBodyPointDecompositionPtr& non_group_link_decomposition :
940 non_group_link_decompositions)
942 all_points.insert(all_points.end(), non_group_link_decomposition->getCollisionPoints().begin(),
943 non_group_link_decomposition->getCollisionPoints().end());
946 for (collision_detection::PosedBodyPointDecompositionVectorPtr& non_group_attached_body_decomposition :
947 non_group_attached_body_decompositions)
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());
953 dfce->distance_field_->addPointsToField(all_points);
954 RCLCPP_DEBUG(
LOGGER,
"CollisionRobot distance field has been initialized with %zu points.", all_points.size());
962 const std::vector<const moveit::core::LinkModel*>& link_models =
robot_model_->getLinkModelsWithCollisionGeometry();
965 if (link_model->getShapes().empty())
967 RCLCPP_WARN(
LOGGER,
"No collision geometry for link model %s though there should be",
968 link_model->getName().c_str());
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(),
982 visualization_msgs::msg::MarkerArray& model_markers)
const
985 std_msgs::msg::ColorRGBA robot_color;
987 robot_color.b = 0.8f;
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;
998 visualization_msgs::msg::Marker sphere_marker;
999 sphere_marker.header.frame_id =
robot_model_->getRootLinkName();
1000 sphere_marker.header.stamp = rclcpp::Time(0);
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);
1012 unsigned int id = 0;
1016 std::map<std::string, unsigned int>::const_iterator map_iter;
1020 const std::string& link_name = map_iter->first;
1021 unsigned int link_index = map_iter->second;
1024 if (std::find(group_link_names.begin(), group_link_names.end(), link_name) != group_link_names.end())
1026 sphere_marker.color = robot_color;
1030 sphere_marker.color = world_links_color;
1033 collision_detection::PosedBodySphereDecompositionPtr sphere_representation(
1036 for (
unsigned int j = 0; j < sphere_representation->getCollisionSpheres().size(); ++j)
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;
1044 model_markers.markers.push_back(sphere_marker);
1050 double resolution,
const std::map<std::string, std::vector<CollisionSphere>>& link_spheres)
1053 const std::vector<const moveit::core::LinkModel*>& link_models =
robot_model_->getLinkModelsWithCollisionGeometry();
1057 if (link_model->getShapes().empty())
1059 RCLCPP_WARN(
LOGGER,
"Skipping model generation for link %s since it contains no geometries",
1060 link_model->getName().c_str());
1064 BodyDecompositionPtr bd =
1065 std::make_shared<BodyDecomposition>(link_model->getShapes(), link_model->getCollisionOriginTransforms(),
1068 RCLCPP_DEBUG(
LOGGER,
"Generated model for %s", link_model->getName().c_str());
1070 if (link_spheres.find(link_model->getName()) != link_spheres.end())
1072 bd->replaceCollisionSpheres(link_spheres.find(link_model->getName())->second, Eigen::Isometry3d::Identity());
1077 RCLCPP_DEBUG(
LOGGER,
" Finished ");
1080 PosedBodySphereDecompositionPtr
1082 unsigned int ind)
const
1084 PosedBodySphereDecompositionPtr ret;
1089 PosedBodyPointDecompositionPtr
1092 PosedBodyPointDecompositionPtr ret;
1096 RCLCPP_ERROR(
LOGGER,
"No link body decomposition for link %s.", ls->
getName().c_str());
1104 GroupStateRepresentationPtr& gsr)
const
1106 for (
unsigned int i = 0; i < gsr->dfce_->link_names_.size(); ++i)
1109 if (gsr->dfce_->link_has_geometry_[i])
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(),
1119 gsr->gradients_[i].sphere_locations = gsr->link_body_decompositions_[i]->getSphereCenters();
1123 for (
unsigned int i = 0; i < gsr->dfce_->attached_body_names_.size(); ++i)
1128 RCLCPP_WARN(
LOGGER,
"Attached body discrepancy");
1133 if (gsr->attached_body_decompositions_.size() != att->
getShapes().size())
1135 RCLCPP_WARN(
LOGGER,
"Attached body size discrepancy");
1139 for (
unsigned int j = 0; j < att->
getShapes().size(); ++j)
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();
1159 GroupStateRepresentationPtr& gsr)
const
1161 if (!dfce->pregenerated_group_state_representation_)
1163 RCLCPP_DEBUG(
LOGGER,
"Creating GroupStateRepresentation");
1166 gsr = std::make_shared<GroupStateRepresentation>();
1168 gsr->gradients_.resize(dfce->link_names_.size() + dfce->attached_body_names_.size());
1172 for (
unsigned int i = 0; i < dfce->link_names_.size(); ++i)
1175 if (dfce->link_has_geometry_[i])
1181 PosedBodySphereDecompositionPtr& link_bd = gsr->link_body_decompositions_.back();
1182 double diameter = 2 * link_bd->getBoundingSphereRadius();
1184 link_origin = link_bd->getBoundingSphereCenter() - 0.5 * link_size;
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());
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());
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(),
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();
1207 gsr->link_body_decompositions_.push_back(PosedBodySphereDecompositionPtr());
1208 gsr->link_distance_fields_.push_back(PosedDistanceFieldPtr());
1214 gsr = std::make_shared<GroupStateRepresentation>(*(dfce->pregenerated_group_state_representation_));
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)
1220 if (dfce->link_has_geometry_[i])
1224 gsr->gradients_[i].sphere_locations = gsr->link_body_decompositions_[i]->getSphereCenters();
1229 for (
unsigned int i = 0; i < dfce->attached_body_names_.size(); ++i)
1231 int link_index = dfce->attached_body_link_state_indices_[i];
1238 gsr->attached_body_decompositions_.push_back(
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();
1258 for (
unsigned int i = 0; i < new_state_values.size(); ++i)
1263 if (dfce->state_values_.size() != new_state_values.size())
1265 RCLCPP_ERROR(
LOGGER,
" State value size mismatch");
1269 for (
unsigned int i = 0; i < dfce->state_check_indices_.size(); ++i)
1272 fabs(dfce->state_values_[dfce->state_check_indices_[i]] - new_state_values[dfce->state_check_indices_[i]]);
1275 RCLCPP_WARN(
LOGGER,
"State for Variable %s has changed by %f radians",
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);
1284 if (attached_bodies_dfce.size() != attached_bodies_state.size())
1289 for (
unsigned int i = 0; i < attached_bodies_dfce.size(); ++i)
1291 if (attached_bodies_dfce[i]->getName() != attached_bodies_state[i]->getName())
1295 if (attached_bodies_dfce[i]->getTouchLinks() != attached_bodies_state[i]->getTouchLinks())
1299 if (attached_bodies_dfce[i]->getShapes().size() != attached_bodies_state[i]->getShapes().size())
1303 for (
unsigned int j = 0; j < attached_bodies_dfce[i]->getShapes().size(); ++j)
1305 if (attached_bodies_dfce[i]->getShapes()[j] != attached_bodies_state[i]->getShapes()[j])
1317 if (dfce->acm_.getSize() != acm.
getSize())
1319 RCLCPP_DEBUG(
LOGGER,
"Allowed collision matrix size mismatch");
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)
1326 std::string link_name = dfce->link_names_[i];
1327 if (dfce->link_has_geometry_[i])
1329 bool self_collision_enabled =
true;
1331 if (acm.
getEntry(link_name, link_name, t))
1335 self_collision_enabled =
false;
1338 if (self_collision_enabled != dfce->self_collision_enabled_[i])
1342 for (
unsigned int j = i; j < dfce->link_names_.size(); ++j)
1346 if (dfce->link_has_geometry_[j])
1348 bool intra_collision_enabled =
true;
1349 if (acm.
getEntry(link_name, dfce->link_names_[j], t))
1353 intra_collision_enabled =
false;
1356 if (dfce->intra_group_collision_enabled_[i][j] != intra_collision_enabled)
1385 GroupStateRepresentationPtr gsr;
1391 GroupStateRepresentationPtr& gsr)
const
1418 GroupStateRepresentationPtr gsr;
1424 GroupStateRepresentationPtr& gsr)
const
1450 GroupStateRepresentationPtr gsr;
1456 GroupStateRepresentationPtr& gsr)
const
1477 GroupStateRepresentationPtr gsr;
1484 GroupStateRepresentationPtr& gsr)
const
1507 RCLCPP_ERROR(
LOGGER,
"Continuous collision checking not implemented");
1514 RCLCPP_ERROR(
LOGGER,
"Continuous collision checking not implemented");
1520 GroupStateRepresentationPtr& gsr)
const
1543 GroupStateRepresentationPtr& gsr)
const
1562 const distance_field::DistanceFieldConstPtr& env_distance_field,
1563 GroupStateRepresentationPtr& gsr)
const
1565 for (
unsigned int i = 0; i < gsr->dfce_->link_names_.size() + gsr->dfce_->attached_body_names_.size(); ++i)
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])
1574 const std::vector<CollisionSphere>* collision_spheres_1;
1575 const EigenSTL::vector_Vector3d* sphere_centers_1;
1579 collision_spheres_1 = &(gsr->link_body_decompositions_[i]->getCollisionSpheres());
1580 sphere_centers_1 = &(gsr->link_body_decompositions_[i]->getSphereCenters());
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());
1591 std::vector<unsigned int> colls;
1599 for (
unsigned int col : colls)
1604 con.
pos = gsr->link_body_decompositions_[i]->getSphereCenters()[col];
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()];
1624 gsr->gradients_[i].collision =
true;
1646 const distance_field::DistanceFieldConstPtr& env_distance_field, GroupStateRepresentationPtr& gsr)
const
1648 bool in_collision =
false;
1649 for (
unsigned int i = 0; i < gsr->dfce_->link_names_.size(); ++i)
1651 bool is_link = i < gsr->dfce_->link_names_.size();
1653 if (is_link && !gsr->dfce_->link_has_geometry_[i])
1658 const std::vector<CollisionSphere>* collision_spheres_1;
1659 const EigenSTL::vector_Vector3d* sphere_centers_1;
1662 collision_spheres_1 = &(gsr->link_body_decompositions_[i]->getCollisionSpheres());
1663 sphere_centers_1 = &(gsr->link_body_decompositions_[i]->getSphereCenters());
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());
1677 in_collision =
true;
1680 return in_collision;
1706 rclcpp::Clock clock;
1707 rclcpp::Time start_time = clock.now();
1709 EigenSTL::vector_Vector3d add_points;
1710 EigenSTL::vector_Vector3d subtract_points;
1727 RCLCPP_DEBUG(
LOGGER,
"Modifying object %s took %lf s", obj->id_.c_str(), (clock.now() - start_time).seconds());
1731 EigenSTL::vector_Vector3d& add_points,
1732 EigenSTL::vector_Vector3d& subtract_points)
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())
1738 for (collision_detection::PosedBodyPointDecompositionPtr& posed_body_point_decomposition : cur_it->second)
1740 subtract_points.insert(subtract_points.end(), posed_body_point_decomposition->getCollisionPoints().begin(),
1741 posed_body_point_decomposition->getCollisionPoints().end());
1745 World::ObjectConstPtr
object =
getWorld()->getObject(
id);
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)
1753 shapes::ShapeConstPtr shape =
object->shapes_[i];
1754 if (shape->type == shapes::OCTREE)
1756 const shapes::OcTree* octree_shape =
static_cast<const shapes::OcTree*
>(shape.get());
1757 std::shared_ptr<const octomap::OcTree> octree = octree_shape->octree;
1759 shape_points.push_back(std::make_shared<PosedBodyPointDecomposition>(octree));
1764 shape_points.push_back(
1765 std::make_shared<PosedBodyPointDecomposition>(bd,
getWorld()->getGlobalShapeTransform(
id, i)));
1768 add_points.insert(add_points.end(), shape_points.back()->getCollisionPoints().begin(),
1769 shape_points.back()->getCollisionPoints().end());
1772 dfce->posed_body_point_decompositions_[id] = shape_points;
1776 RCLCPP_DEBUG(
LOGGER,
"Removing Object '%s' from CollisionEnvDistanceField",
id.c_str());
1777 dfce->posed_body_point_decompositions_.erase(
id);
1781 CollisionEnvDistanceField::DistanceFieldCacheEntryWorldPtr
1784 DistanceFieldCacheEntryWorldPtr dfce = std::make_shared<DistanceFieldCacheEntryWorld>();
1785 dfce->distance_field_ = std::make_shared<distance_field::PropagationDistanceField>(
1789 EigenSTL::vector_Vector3d add_points;
1790 EigenSTL::vector_Vector3d subtract_points;
1791 for (
const std::pair<const std::string, ObjectPtr>&
object : *
getWorld())
1795 dfce->distance_field_->addPointsToField(add_points);
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)
static const std::string NAME
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)
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
double collision_tolerance_
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
DistanceFieldCacheEntryPtr distance_field_cache_entry_
~CollisionEnvDistanceField() override
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 use_signed_distance_field_
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 setWorld(const WorldPtr &world) override
void updateDistanceObject(const std::string &id, CollisionEnvDistanceField::DistanceFieldCacheEntryWorldPtr &dfce, EigenSTL::vector_Vector3d &add_points, EigenSTL::vector_Vector3d &subtract_points)
static const rclcpp::Logger LOGGER
std::mutex update_cache_lock_
void getAllCollisions(const CollisionRequest &req, CollisionResult &res, const moveit::core::RobotState &state, const AllowedCollisionMatrix *acm, GroupStateRepresentationPtr &gsr) const
void addLinkBodyDecompositions(double resolution)
planning_scene::PlanningScenePtr planning_scene_
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
World::ObserverHandle observer_handle_
Provides the interface to the individual collision checking libraries.
virtual void setWorld(const WorldPtr &world)
moveit::core::RobotModelConstPtr robot_model_
The kinematic model corresponding to this collision model.
const WorldPtr & getWorld()
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...
Object defining bodies that can be attached to robot links.
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....
const std::string & getName() const
Get the name of the joint.
A link from the robot. Contains the constant transform applied to the link and its geometry.
const std::vector< shapes::ShapeConstPtr > & getShapes() const
Get shape associated to the collision geometry for this link.
const JointModel * getParentJointModel() const
Get the joint model whose child this link is. There will always be a parent joint.
const std::string & getName() const
The name of this link.
Representation of a robot's state. This includes position, velocity, acceleration and effort.
const LinkModel * getLinkModel(const std::string &link) const
Get the model of a particular link.
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...
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.
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.
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.
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.
@ 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
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.
bool collision
True if collision was found, false otherwise.
std::size_t contact_count
Number of contacts returned.