53 static const std::string
NAME =
"DISTANCE_FIELD";
58 const moveit::core::RobotModelConstPtr&
robot_model,
59 const std::map<std::string, std::vector<CollisionSphere>>& link_body_decompositions,
double size_x,
double size_y,
60 double size_z,
const Eigen::Vector3d& origin,
bool use_signed_distance_field,
double resolution,
61 double collision_tolerance,
double max_propogation_distance,
double ,
double )
65 resolution, collision_tolerance, max_propogation_distance);
69 distance_field_cache_entry_world_ = generateDistanceFieldCacheEntryWorld();
73 [
this](
const World::ObjectConstPtr&
object, World::Action action) {
return notifyObjectChange(
object, action); });
77 const moveit::core::RobotModelConstPtr&
robot_model,
const WorldPtr& world,
78 const std::map<std::string, std::vector<CollisionSphere>>& link_body_decompositions,
double size_x,
double size_y,
79 double size_z,
const Eigen::Vector3d& origin,
bool use_signed_distance_field,
double resolution,
80 double collision_tolerance,
double max_propogation_distance,
double padding,
double scale)
84 resolution, collision_tolerance, max_propogation_distance);
86 distance_field_cache_entry_world_ = generateDistanceFieldCacheEntryWorld();
96 : CollisionEnv(other, world)
124 const std::map<std::string, std::vector<CollisionSphere>>& link_body_decompositions,
const Eigen::Vector3d& size,
125 const Eigen::Vector3d& origin,
bool use_signed_distance_field,
double resolution,
double collision_tolerance,
126 double max_propogation_distance)
138 const std::vector<const moveit::core::JointModelGroup*>& jmg =
robot_model_->getJointModelGroups();
141 std::map<std::string, bool> updated_group_entry;
142 std::vector<std::string> links = jm->getUpdatedLinkModelsWithGeometryNames();
143 for (
const std::string& link : links)
145 updated_group_entry[link] =
true;
149 DistanceFieldCacheEntryPtr dfce =
154 std::map<std::string, bool> updated_group_entry;
155 std::vector<std::string> links =
robot_model_->getLinkModelNamesWithCollisionGeometry();
156 for (
const std::string& link : links)
158 updated_group_entry[link] =
true;
166 bool generate_distance_field)
const
169 if (!dfce || (generate_distance_field && !dfce->distance_field_))
173 DistanceFieldCacheEntryPtr new_dfce =
186 GroupStateRepresentationPtr& gsr)
const
206 DistanceFieldCacheEntryConstPtr
211 DistanceFieldCacheEntryConstPtr ret;
218 if (group_name != cur->group_name_)
220 ROS_DEBUG(
"No cache entry as group name changed from %s to %s", cur->group_name_.c_str(), group_name.c_str());
232 ROS_DEBUG(
"Regenerating distance field as some relevant part of the acm changed");
242 GroupStateRepresentationPtr gsr;
249 GroupStateRepresentationPtr& gsr)
const
259 GroupStateRepresentationPtr gsr;
267 GroupStateRepresentationPtr& gsr)
const
271 ROS_WARN(
"Shouldn't be calling this function with initialized gsr - ACM "
279 GroupStateRepresentationPtr& gsr)
const
281 for (
unsigned int i = 0; i < gsr->dfce_->link_names_.size() + gsr->dfce_->attached_body_names_.size(); i++)
283 bool is_link = i < gsr->dfce_->link_names_.size();
284 if ((is_link && !gsr->dfce_->link_has_geometry_[i]) || !gsr->dfce_->self_collision_enabled_[i])
286 const std::vector<CollisionSphere>* collision_spheres_1;
291 collision_spheres_1 = &(gsr->link_body_decompositions_[i]->getCollisionSpheres());
292 sphere_centers_1 = &(gsr->link_body_decompositions_[i]->getSphereCenters());
296 collision_spheres_1 =
297 &(gsr->attached_body_decompositions_[i - gsr->dfce_->link_names_.size()]->getCollisionSpheres());
298 sphere_centers_1 = &(gsr->attached_body_decompositions_[i - gsr->dfce_->link_names_.size()]->getSphereCenters());
303 std::vector<unsigned int> colls;
311 for (
unsigned int col : colls)
316 con.
pos = gsr->link_body_decompositions_[i]->getSphereCenters()[col];
322 con.
pos = gsr->attached_body_decompositions_[i - gsr->dfce_->link_names_.size()]->getSphereCenters()[col];
324 con.
body_name_1 = gsr->dfce_->attached_body_names_[i - gsr->dfce_->link_names_.size()];
333 gsr->gradients_[i].types[col] =
SELF;
335 gsr->gradients_[i].collision =
true;
349 ROS_DEBUG(
"Link %s in self collision", gsr->dfce_->link_names_[i].c_str());
360 bool in_collision =
false;
362 for (
unsigned int i = 0; i < gsr->dfce_->link_names_.size(); i++)
364 const std::string& link_name = gsr->dfce_->link_names_[i];
365 bool is_link = i < gsr->dfce_->link_names_.size();
366 if ((is_link && !gsr->dfce_->link_has_geometry_[i]) || !gsr->dfce_->self_collision_enabled_[i])
371 const std::vector<CollisionSphere>* collision_spheres_1;
375 collision_spheres_1 = &(gsr->link_body_decompositions_[i]->getCollisionSpheres());
376 sphere_centers_1 = &(gsr->link_body_decompositions_[i]->getSphereCenters());
380 collision_spheres_1 =
381 &(gsr->attached_body_decompositions_[i - gsr->dfce_->link_names_.size()]->getCollisionSpheres());
382 sphere_centers_1 = &(gsr->attached_body_decompositions_[i - gsr->dfce_->link_names_.size()]->getSphereCenters());
388 if (gsr->dfce_->acm_.getSize() > 0)
391 for (
unsigned int j = 0; j < gsr->dfce_->link_names_.size(); j++)
394 if (link_name == gsr->dfce_->link_names_[j])
400 if (gsr->dfce_->acm_.getEntry(link_name, gsr->dfce_->link_names_[j], col_type) &&
406 if (gsr->link_distance_fields_[j])
408 coll = gsr->link_distance_fields_[j]->getCollisionSphereGradients(
435 GroupStateRepresentationPtr& gsr)
const
437 unsigned int num_links = gsr->dfce_->link_names_.size();
438 unsigned int num_attached_bodies = gsr->dfce_->attached_body_names_.size();
440 for (
unsigned int i = 0; i < num_links + num_attached_bodies; i++)
442 for (
unsigned int j = i + 1; j < num_links + num_attached_bodies; j++)
446 bool i_is_link = i < num_links;
447 bool j_is_link = j < num_links;
449 if ((i_is_link && !gsr->dfce_->link_has_geometry_[i]) || (j_is_link && !gsr->dfce_->link_has_geometry_[j]))
452 if (!gsr->dfce_->intra_group_collision_enabled_[i][j])
455 if (i_is_link && j_is_link &&
463 else if (!i_is_link || !j_is_link)
466 if (!i_is_link && j_is_link)
468 for (
unsigned int k = 0; k < gsr->attached_body_decompositions_[i - num_links]->getSize(); k++)
471 gsr->link_body_decompositions_[j],
472 gsr->attached_body_decompositions_[i - num_links]->getPosedBodySphereDecomposition(k)))
479 else if (i_is_link && !j_is_link)
481 for (
unsigned int k = 0; k < gsr->attached_body_decompositions_[j - num_links]->getSize(); k++)
484 gsr->link_body_decompositions_[i],
485 gsr->attached_body_decompositions_[j - num_links]->getPosedBodySphereDecomposition(k)))
494 for (
unsigned int k = 0; k < gsr->attached_body_decompositions_[i - num_links]->getSize() && all_ok; k++)
496 for (
unsigned int l = 0; l < gsr->attached_body_decompositions_[j - num_links]->getSize(); l++)
499 gsr->attached_body_decompositions_[i - num_links]->getPosedBodySphereDecomposition(k),
500 gsr->attached_body_decompositions_[j - num_links]->getPosedBodySphereDecomposition(l)))
521 name_1 = gsr->dfce_->link_names_[i];
525 name_1 = gsr->dfce_->attached_body_names_[i - num_links];
530 name_2 = gsr->dfce_->link_names_[j];
534 name_2 = gsr->dfce_->attached_body_names_[j - num_links];
538 collision_detection::CollisionResult::ContactMap::iterator it =
539 res.
contacts.find(std::pair<std::string, std::string>(name_1, name_2));
546 num_pair = it->second.size();
549 const std::vector<CollisionSphere>* collision_spheres_1;
550 const std::vector<CollisionSphere>* collision_spheres_2;
555 collision_spheres_1 = &(gsr->link_body_decompositions_[i]->getCollisionSpheres());
556 sphere_centers_1 = &(gsr->link_body_decompositions_[i]->getSphereCenters());
560 collision_spheres_1 = &(gsr->attached_body_decompositions_[i - num_links]->getCollisionSpheres());
561 sphere_centers_1 = &(gsr->attached_body_decompositions_[i - num_links]->getSphereCenters());
565 collision_spheres_2 = &(gsr->link_body_decompositions_[j]->getCollisionSpheres());
566 sphere_centers_2 = &(gsr->link_body_decompositions_[j]->getSphereCenters());
570 collision_spheres_2 = &(gsr->attached_body_decompositions_[j - num_links]->getCollisionSpheres());
571 sphere_centers_2 = &(gsr->attached_body_decompositions_[j - num_links]->getSphereCenters());
574 for (
unsigned int k = 0; k < collision_spheres_1->size() && num_pair < (int)req.
max_contacts_per_pair; k++)
576 for (
unsigned int l = 0; l < collision_spheres_2->size() && num_pair < (int)req.
max_contacts_per_pair; l++)
578 Eigen::Vector3d gradient = (*sphere_centers_1)[k] - (*sphere_centers_2)[l];
579 double dist = gradient.norm();
584 if (dist < (*collision_spheres_1)[k].radius_ + (*collision_spheres_2)[l].radius_)
602 con.
pos = gsr->link_body_decompositions_[i]->getSphereCenters()[k];
626 gsr->gradients_[i].types[k] =
INTRA;
627 gsr->gradients_[i].collision =
true;
628 gsr->gradients_[j].types[l] =
INTRA;
629 gsr->gradients_[j].collision =
true;
664 bool in_collision =
false;
665 unsigned int num_links = gsr->dfce_->link_names_.size();
666 unsigned int num_attached_bodies = gsr->dfce_->attached_body_names_.size();
668 for (
unsigned int i = 0; i < num_links + num_attached_bodies; i++)
670 for (
unsigned int j = i + 1; j < num_links + num_attached_bodies; j++)
674 bool i_is_link = i < num_links;
675 bool j_is_link = j < num_links;
676 if ((i_is_link && !gsr->dfce_->link_has_geometry_[i]) || (j_is_link && !gsr->dfce_->link_has_geometry_[j]))
678 if (!gsr->dfce_->intra_group_collision_enabled_[i][j])
680 const std::vector<CollisionSphere>* collision_spheres_1;
681 const std::vector<CollisionSphere>* collision_spheres_2;
686 collision_spheres_1 = &(gsr->link_body_decompositions_[i]->getCollisionSpheres());
687 sphere_centers_1 = &(gsr->link_body_decompositions_[i]->getSphereCenters());
691 collision_spheres_1 = &(gsr->attached_body_decompositions_[i - num_links]->getCollisionSpheres());
692 sphere_centers_1 = &(gsr->attached_body_decompositions_[i - num_links]->getSphereCenters());
696 collision_spheres_2 = &(gsr->link_body_decompositions_[j]->getCollisionSpheres());
697 sphere_centers_2 = &(gsr->link_body_decompositions_[j]->getSphereCenters());
701 collision_spheres_2 = &(gsr->attached_body_decompositions_[j - num_links]->getCollisionSpheres());
702 sphere_centers_2 = &(gsr->attached_body_decompositions_[j - num_links]->getSphereCenters());
704 for (
unsigned int k = 0; k < collision_spheres_1->size(); k++)
706 for (
unsigned int l = 0; l < collision_spheres_2->size(); l++)
708 Eigen::Vector3d gradient = (*sphere_centers_1)[k] - (*sphere_centers_2)[l];
709 double dist = gradient.norm();
710 if (dist < gsr->gradients_[i].distances[k])
712 gsr->gradients_[i].distances[k] = dist;
713 gsr->gradients_[i].gradients[k] = gradient;
714 gsr->gradients_[i].types[k] =
INTRA;
716 if (dist < gsr->gradients_[j].distances[l])
718 gsr->gradients_[j].distances[l] = dist;
719 gsr->gradients_[j].gradients[l] = -gradient;
720 gsr->gradients_[j].types[l] =
INTRA;
732 DistanceFieldCacheEntryPtr dfce(
new DistanceFieldCacheEntry());
734 dfce->group_name_ = group_name;
736 if (group_name.empty())
739 dfce->link_names_ =
robot_model_->getJointModelGroup(group_name)->getUpdatedLinkModelNames();
741 dfce->state_ = std::make_shared<moveit::core::RobotState>(state);
748 ROS_WARN_STREAM(
"Allowed Collision Matrix is null, enabling all collisions "
749 "in the DistanceFieldCacheEntry");
753 std::vector<const moveit::core::AttachedBody*> all_attached_bodies;
754 dfce->state_->getAttachedBodies(all_attached_bodies);
755 unsigned int att_count = 0;
758 std::vector<bool> all_true(dfce->link_names_.size() + all_attached_bodies.size(),
true);
759 std::vector<bool> all_false(dfce->link_names_.size() + all_attached_bodies.size(),
false);
761 dfce->self_collision_enabled_.resize(dfce->link_names_.size() + all_attached_bodies.size(),
true);
762 dfce->intra_group_collision_enabled_.resize(dfce->link_names_.size() + all_attached_bodies.size());
764 for (
unsigned int i = 0; i < dfce->link_names_.size(); i++)
766 std::string link_name = dfce->link_names_[i];
769 auto pos = std::find(dfce->link_names_.begin(), dfce->link_names_.end(), link_name);
770 if (pos != dfce->link_names_.end())
772 dfce->link_state_indices_.push_back(pos - dfce->link_names_.begin());
776 ROS_DEBUG(
"No link state found for link '%s'", link_name.c_str());
782 dfce->link_has_geometry_.push_back(
true);
790 dfce->self_collision_enabled_[i] =
false;
793 dfce->intra_group_collision_enabled_[i] = all_true;
794 for (
unsigned int j = i + 1; j < dfce->link_names_.size(); j++)
796 if (link_name == dfce->link_names_[j])
798 dfce->intra_group_collision_enabled_[i][j] =
false;
803 dfce->intra_group_collision_enabled_[i][j] =
false;
807 std::vector<const moveit::core::AttachedBody*> link_attached_bodies;
809 for (
unsigned int j = 0; j < link_attached_bodies.size(); j++, att_count++)
811 dfce->attached_body_names_.push_back(link_attached_bodies[j]->
getName());
812 dfce->attached_body_link_state_indices_.push_back(dfce->link_state_indices_[i]);
814 if (acm->
getEntry(link_name, link_attached_bodies[j]->getName(),
t))
818 dfce->intra_group_collision_enabled_[i][att_count + dfce->link_names_.size()] =
false;
826 if (link_attached_bodies[j]->getTouchLinks().find(link_name) != link_attached_bodies[j]->getTouchLinks().end())
828 dfce->intra_group_collision_enabled_[i][att_count + dfce->link_names_.size()] =
false;
837 dfce->self_collision_enabled_[i] =
true;
838 dfce->intra_group_collision_enabled_[i] = all_true;
843 dfce->link_has_geometry_.push_back(
false);
844 dfce->link_body_indices_.push_back(0);
845 dfce->self_collision_enabled_[i] =
false;
846 dfce->intra_group_collision_enabled_[i] = all_false;
850 for (
unsigned int i = 0; i < dfce->attached_body_names_.size(); i++)
852 dfce->intra_group_collision_enabled_[i + dfce->link_names_.size()] = all_true;
856 if (acm->
getEntry(dfce->attached_body_names_[i], dfce->attached_body_names_[i], t) &&
859 dfce->self_collision_enabled_[i + dfce->link_names_.size()] =
false;
861 for (
unsigned int j = i + 1; j < dfce->attached_body_names_.size(); j++)
863 if (acm->
getEntry(dfce->attached_body_names_[i], dfce->attached_body_names_[j], t) &&
866 dfce->intra_group_collision_enabled_[i + dfce->link_names_.size()][j + dfce->link_names_.size()] =
false;
877 std::map<std::string, GroupStateRepresentationPtr>::const_iterator it =
881 dfce->pregenerated_group_state_representation_ = it->second;
884 std::map<std::string, bool> updated_map;
885 if (!dfce->link_names_.empty())
887 const std::vector<const moveit::core::JointModel*>& child_joint_models = [&]() {
888 if (dfce->group_name_.empty())
889 return dfce->state_->getRobotModel()->getActiveJointModels();
891 return dfce->state_->getJointModelGroup(dfce->group_name_)->getActiveJointModels();
896 updated_map[child_joint_model->getName()] =
true;
897 ROS_DEBUG_STREAM(
"Joint " << child_joint_model->getName() <<
" has been added to updated list");
901 const std::vector<std::string>& state_variable_names = state.
getVariableNames();
902 for (
const std::string& state_variable_name : state_variable_names)
905 dfce->state_values_.push_back(val);
906 if (updated_map.count(state_variable_name) == 0)
908 dfce->state_check_indices_.push_back(dfce->state_values_.size() - 1);
909 ROS_DEBUG_STREAM(
"Non-group joint " << state_variable_name <<
" will be checked for state changes");
913 if (generate_distance_field)
915 if (dfce->distance_field_)
918 "will use existing one");
922 std::vector<PosedBodyPointDecompositionPtr> non_group_link_decompositions;
923 std::vector<PosedBodyPointDecompositionVectorPtr> non_group_attached_body_decompositions;
924 const std::map<std::string, bool>& updated_group_map =
in_group_update_map_.find(group_name)->second;
927 const std::string& link_name = link_model->getName();
929 if (updated_group_map.find(link_name) != updated_group_map.end())
936 non_group_link_decompositions.back()->updatePose(dfce->state_->getFrameTransform(link_state->
getName()));
938 std::vector<const moveit::core::AttachedBody*> attached_bodies;
939 dfce->state_->getAttachedBodies(attached_bodies, link_state);
942 non_group_attached_body_decompositions.push_back(
946 dfce->distance_field_ = std::make_shared<distance_field::PropagationDistanceField>(
956 for (collision_detection::PosedBodyPointDecompositionPtr& non_group_link_decomposition :
957 non_group_link_decompositions)
959 all_points.insert(all_points.end(), non_group_link_decomposition->getCollisionPoints().begin(),
960 non_group_link_decomposition->getCollisionPoints().end());
963 for (collision_detection::PosedBodyPointDecompositionVectorPtr& non_group_attached_body_decomposition :
964 non_group_attached_body_decompositions)
967 all_points.insert(all_points.end(), collision_points.begin(), collision_points.end());
970 dfce->distance_field_->addPointsToField(all_points);
971 ROS_DEBUG_STREAM(
"CollisionRobot distance field has been initialized with " << all_points.size() <<
" points.");
979 const std::vector<const moveit::core::LinkModel*>& link_models =
robot_model_->getLinkModelsWithCollisionGeometry();
982 if (link_model->getShapes().empty())
984 ROS_WARN(
"No collision geometry for link model %s though there should be", link_model->getName().c_str());
988 ROS_DEBUG(
"Generating model for %s", link_model->getName().c_str());
989 BodyDecompositionConstPtr bd(
new BodyDecomposition(link_model->getShapes(),
990 link_model->getCollisionOriginTransforms(), resolution,
998 visualization_msgs::MarkerArray& model_markers)
const
1001 std_msgs::ColorRGBA robot_color;
1003 robot_color.b = 0.8f;
1005 robot_color.a = 0.5;
1007 std_msgs::ColorRGBA world_links_color;
1008 world_links_color.r = 1;
1009 world_links_color.g = 1;
1010 world_links_color.b = 0;
1011 world_links_color.a = 0.5;
1014 visualization_msgs::Marker sphere_marker;
1015 sphere_marker.header.frame_id =
robot_model_->getRootLinkName();
1016 sphere_marker.header.stamp =
ros::Time(0);
1018 sphere_marker.id = 0;
1019 sphere_marker.type = visualization_msgs::Marker::SPHERE;
1020 sphere_marker.action = visualization_msgs::Marker::ADD;
1021 sphere_marker.pose.orientation.x = 0;
1022 sphere_marker.pose.orientation.y = 0;
1023 sphere_marker.pose.orientation.z = 0;
1024 sphere_marker.pose.orientation.w = 1;
1025 sphere_marker.color = robot_color;
1028 unsigned int id = 0;
1032 std::map<std::string, unsigned int>::const_iterator map_iter;
1036 const std::string& link_name = map_iter->first;
1037 unsigned int link_index = map_iter->second;
1040 if (std::find(group_link_names.begin(), group_link_names.end(), link_name) != group_link_names.end())
1042 sphere_marker.color = robot_color;
1046 sphere_marker.color = world_links_color;
1049 collision_detection::PosedBodySphereDecompositionPtr sphere_representation(
1052 for (
unsigned int j = 0; j < sphere_representation->getCollisionSpheres().size(); j++)
1054 sphere_marker.pose.position =
tf2::toMsg(sphere_representation->getSphereCenters()[j]);
1055 sphere_marker.scale.x = sphere_marker.scale.y = sphere_marker.scale.z =
1056 2 * sphere_representation->getCollisionSpheres()[j].radius_;
1057 sphere_marker.id = id;
1060 model_markers.markers.push_back(sphere_marker);
1066 double resolution,
const std::map<std::string, std::vector<CollisionSphere>>& link_spheres)
1069 const std::vector<const moveit::core::LinkModel*>& link_models =
robot_model_->getLinkModelsWithCollisionGeometry();
1073 if (link_model->getShapes().empty())
1075 ROS_WARN_STREAM(
"Skipping model generation for link " << link_model->getName()
1076 <<
" since it contains no geometries");
1080 BodyDecompositionPtr bd(
new BodyDecomposition(link_model->getShapes(), link_model->getCollisionOriginTransforms(),
1083 ROS_DEBUG(
"Generated model for %s", link_model->getName().c_str());
1085 if (link_spheres.find(link_model->getName()) != link_spheres.end())
1087 bd->replaceCollisionSpheres(link_spheres.find(link_model->getName())->second, Eigen::Isometry3d::Identity());
1095 PosedBodySphereDecompositionPtr
1097 unsigned int ind)
const
1099 PosedBodySphereDecompositionPtr ret;
1104 PosedBodyPointDecompositionPtr
1107 PosedBodyPointDecompositionPtr ret;
1111 ROS_ERROR_NAMED(
"collision_distance_field",
"No link body decomposition for link %s.", ls->
getName().c_str());
1119 GroupStateRepresentationPtr& gsr)
const
1121 for (
unsigned int i = 0; i < gsr->dfce_->link_names_.size(); i++)
1124 if (gsr->dfce_->link_has_geometry_[i])
1128 gsr->gradients_[i].closest_distance = DBL_MAX;
1129 gsr->gradients_[i].collision =
false;
1130 gsr->gradients_[i].types.assign(gsr->link_body_decompositions_[i]->getCollisionSpheres().size(),
NONE);
1131 gsr->gradients_[i].distances.assign(gsr->link_body_decompositions_[i]->getCollisionSpheres().size(), DBL_MAX);
1132 gsr->gradients_[i].gradients.assign(gsr->link_body_decompositions_[i]->getCollisionSpheres().size(),
1134 gsr->gradients_[i].sphere_locations = gsr->link_body_decompositions_[i]->getSphereCenters();
1138 for (
unsigned int i = 0; i < gsr->dfce_->attached_body_names_.size(); i++)
1143 ROS_WARN(
"Attached body discrepancy");
1148 if (gsr->attached_body_decompositions_.size() != att->
getShapes().size())
1154 for (
unsigned int j = 0; j < att->
getShapes().size(); j++)
1159 gsr->gradients_[i + gsr->dfce_->link_names_.size()].closest_distance = DBL_MAX;
1160 gsr->gradients_[i + gsr->dfce_->link_names_.size()].collision =
false;
1161 gsr->gradients_[i + gsr->dfce_->link_names_.size()].types.assign(
1162 gsr->attached_body_decompositions_[i]->getCollisionSpheres().size(),
NONE);
1163 gsr->gradients_[i + gsr->dfce_->link_names_.size()].distances.assign(
1164 gsr->attached_body_decompositions_[i]->getCollisionSpheres().size(), DBL_MAX);
1165 gsr->gradients_[i + gsr->dfce_->link_names_.size()].gradients.assign(
1166 gsr->attached_body_decompositions_[i]->getCollisionSpheres().size(),
Eigen::Vector3d(0.0, 0.0, 0.0));
1167 gsr->gradients_[i + gsr->dfce_->link_names_.size()].sphere_locations =
1168 gsr->attached_body_decompositions_[i]->getSphereCenters();
1174 GroupStateRepresentationPtr& gsr)
const
1176 if (!dfce->pregenerated_group_state_representation_)
1181 gsr = std::make_shared<GroupStateRepresentation>();
1183 gsr->gradients_.resize(dfce->link_names_.size() + dfce->attached_body_names_.size());
1187 for (
unsigned int i = 0; i < dfce->link_names_.size(); i++)
1190 if (dfce->link_has_geometry_[i])
1196 PosedBodySphereDecompositionPtr& link_bd = gsr->link_body_decompositions_.back();
1197 double diameter = 2 * link_bd->getBoundingSphereRadius();
1199 link_origin = link_bd->getBoundingSphereCenter() - 0.5 * link_size;
1202 << dfce->link_names_[i] <<
" with size [" << link_size.x() <<
", " << link_size.y() <<
", "
1203 << link_size.z() <<
"] and origin " << link_origin.x() <<
", " << link_origin.y() <<
", "
1204 << link_origin.z());
1206 gsr->link_distance_fields_.push_back(std::make_shared<PosedDistanceField>(
1208 gsr->link_distance_fields_.back()->addPointsToField(link_bd->getCollisionPoints());
1209 ROS_DEBUG_STREAM(
"Created PosedDistanceField for link " << dfce->link_names_[i] <<
" with "
1210 << link_bd->getCollisionPoints().size() <<
" points");
1214 gsr->gradients_[i].types.resize(gsr->link_body_decompositions_.back()->getCollisionSpheres().size(),
NONE);
1215 gsr->gradients_[i].distances.resize(gsr->link_body_decompositions_.back()->getCollisionSpheres().size(),
1217 gsr->gradients_[i].gradients.resize(gsr->link_body_decompositions_.back()->getCollisionSpheres().size());
1218 gsr->gradients_[i].sphere_radii = gsr->link_body_decompositions_.back()->getSphereRadii();
1223 gsr->link_body_decompositions_.push_back(PosedBodySphereDecompositionPtr());
1224 gsr->link_distance_fields_.push_back(PosedDistanceFieldPtr());
1230 gsr = std::make_shared<GroupStateRepresentation>(*(dfce->pregenerated_group_state_representation_));
1232 gsr->gradients_.resize(dfce->link_names_.size() + dfce->attached_body_names_.size());
1233 for (
unsigned int i = 0; i < dfce->link_names_.size(); i++)
1236 if (dfce->link_has_geometry_[i])
1240 gsr->gradients_[i].sphere_locations = gsr->link_body_decompositions_[i]->getSphereCenters();
1245 for (
unsigned int i = 0; i < dfce->attached_body_names_.size(); i++)
1247 int link_index = dfce->attached_body_link_state_indices_[i];
1254 gsr->attached_body_decompositions_.push_back(
1256 gsr->gradients_[i + dfce->link_names_.size()].types.resize(
1257 gsr->attached_body_decompositions_.back()->getCollisionSpheres().size(),
NONE);
1258 gsr->gradients_[i + dfce->link_names_.size()].distances.resize(
1259 gsr->attached_body_decompositions_.back()->getCollisionSpheres().size(), DBL_MAX);
1260 gsr->gradients_[i + dfce->link_names_.size()].gradients.resize(
1261 gsr->attached_body_decompositions_.back()->getCollisionSpheres().size());
1262 gsr->gradients_[i + dfce->link_names_.size()].sphere_locations =
1263 gsr->attached_body_decompositions_.back()->getSphereCenters();
1264 gsr->gradients_[i + dfce->link_names_.size()].sphere_radii =
1265 gsr->attached_body_decompositions_.back()->getSphereRadii();
1274 for (
unsigned int i = 0; i < new_state_values.size(); i++)
1279 if (dfce->state_values_.size() != new_state_values.size())
1285 for (
unsigned int i = 0; i < dfce->state_check_indices_.size(); i++)
1288 fabs(dfce->state_values_[dfce->state_check_indices_[i]] - new_state_values[dfce->state_check_indices_[i]]);
1292 <<
" has changed by " << diff <<
" radians");
1296 std::vector<const moveit::core::AttachedBody*> attached_bodies_dfce;
1297 std::vector<const moveit::core::AttachedBody*> attached_bodies_state;
1298 dfce->state_->getAttachedBodies(attached_bodies_dfce);
1300 if (attached_bodies_dfce.size() != attached_bodies_state.size())
1305 for (
unsigned int i = 0; i < attached_bodies_dfce.size(); i++)
1307 if (attached_bodies_dfce[i]->
getName() != attached_bodies_state[i]->
getName())
1311 if (attached_bodies_dfce[i]->getTouchLinks() != attached_bodies_state[i]->getTouchLinks())
1315 if (attached_bodies_dfce[i]->getShapes().size() != attached_bodies_state[i]->getShapes().size())
1319 for (
unsigned int j = 0; j < attached_bodies_dfce[i]->getShapes().size(); j++)
1321 if (attached_bodies_dfce[i]->getShapes()[j] != attached_bodies_state[i]->getShapes()[j])
1333 if (dfce->acm_.getSize() != acm.
getSize())
1335 ROS_DEBUG(
"Allowed collision matrix size mismatch");
1338 std::vector<const moveit::core::AttachedBody*> attached_bodies;
1339 dfce->state_->getAttachedBodies(attached_bodies);
1340 for (
unsigned int i = 0; i < dfce->link_names_.size(); i++)
1342 std::string link_name = dfce->link_names_[i];
1343 if (dfce->link_has_geometry_[i])
1345 bool self_collision_enabled =
true;
1347 if (acm.
getEntry(link_name, link_name, t))
1351 self_collision_enabled =
false;
1354 if (self_collision_enabled != dfce->self_collision_enabled_[i])
1361 for (
unsigned int j = i; j < dfce->link_names_.size(); j++)
1365 if (dfce->link_has_geometry_[j])
1367 bool intra_collision_enabled =
true;
1368 if (acm.
getEntry(link_name, dfce->link_names_[j],
t))
1372 intra_collision_enabled =
false;
1375 if (dfce->intra_group_collision_enabled_[i][j] != intra_collision_enabled)
1404 GroupStateRepresentationPtr gsr;
1410 GroupStateRepresentationPtr& gsr)
const
1437 GroupStateRepresentationPtr gsr;
1443 GroupStateRepresentationPtr& gsr)
const
1469 GroupStateRepresentationPtr gsr;
1475 GroupStateRepresentationPtr& gsr)
const
1496 GroupStateRepresentationPtr gsr;
1503 GroupStateRepresentationPtr& gsr)
const
1526 ROS_ERROR_NAMED(
"collision_detection.distance",
"Continuous collision checking not implemented");
1533 ROS_ERROR_NAMED(
"collision_detection.distance",
"Continuous collision checking not implemented");
1539 GroupStateRepresentationPtr& gsr)
const
1562 GroupStateRepresentationPtr& gsr)
const
1581 const distance_field::DistanceFieldConstPtr& env_distance_field,
1582 GroupStateRepresentationPtr& gsr)
const
1584 for (
unsigned int i = 0; i < gsr->dfce_->link_names_.size() + gsr->dfce_->attached_body_names_.size(); i++)
1586 bool is_link = i < gsr->dfce_->link_names_.size();
1587 std::string link_name = i < gsr->dfce_->link_names_.size() ? gsr->dfce_->link_names_[i] :
"attached";
1588 if (is_link && !gsr->dfce_->link_has_geometry_[i])
1593 const std::vector<CollisionSphere>* collision_spheres_1;
1598 collision_spheres_1 = &(gsr->link_body_decompositions_[i]->getCollisionSpheres());
1599 sphere_centers_1 = &(gsr->link_body_decompositions_[i]->getSphereCenters());
1603 collision_spheres_1 =
1604 &(gsr->attached_body_decompositions_[i - gsr->dfce_->link_names_.size()]->getCollisionSpheres());
1605 sphere_centers_1 = &(gsr->attached_body_decompositions_[i - gsr->dfce_->link_names_.size()]->getSphereCenters());
1610 std::vector<unsigned int> colls;
1614 std::min(req.max_contacts_per_pair, req.max_contacts - res.contact_count), colls);
1617 res.collision =
true;
1618 for (
unsigned int col : colls)
1623 con.
pos = gsr->link_body_decompositions_[i]->getSphereCenters()[col];
1629 con.
pos = gsr->attached_body_decompositions_[i - gsr->dfce_->link_names_.size()]->getSphereCenters()[col];
1631 con.
body_name_1 = gsr->dfce_->attached_body_names_[i - gsr->dfce_->link_names_.size()];
1636 res.contact_count++;
1643 gsr->gradients_[i].collision =
true;
1644 if (res.contact_count >= req.max_contacts)
1656 res.collision =
true;
1661 return (res.contact_count >= req.max_contacts);
1665 const distance_field::DistanceFieldConstPtr& env_distance_field, GroupStateRepresentationPtr& gsr)
const
1667 bool in_collision =
false;
1668 for (
unsigned int i = 0; i < gsr->dfce_->link_names_.size(); i++)
1670 bool is_link = i < gsr->dfce_->link_names_.size();
1672 if (is_link && !gsr->dfce_->link_has_geometry_[i])
1677 const std::vector<CollisionSphere>* collision_spheres_1;
1681 collision_spheres_1 = &(gsr->link_body_decompositions_[i]->getCollisionSpheres());
1682 sphere_centers_1 = &(gsr->link_body_decompositions_[i]->getSphereCenters());
1686 collision_spheres_1 =
1687 &(gsr->attached_body_decompositions_[i - gsr->dfce_->link_names_.size()]->getCollisionSpheres());
1688 sphere_centers_1 = &(gsr->attached_body_decompositions_[i - gsr->dfce_->link_names_.size()]->getSphereCenters());
1696 in_collision =
true;
1699 return in_collision;
1717 [
this](
const World::ObjectConstPtr&
object, World::Action action) {
return notifyObjectChange(
object, action); });
1745 ROS_DEBUG_NAMED(
"collision_distance_field",
"Modifying object %s took %lf s",
obj->id_.c_str(),
1753 std::map<std::string, std::vector<PosedBodyPointDecompositionPtr>>::iterator cur_it =
1754 dfce->posed_body_point_decompositions_.find(
id);
1755 if (cur_it != dfce->posed_body_point_decompositions_.end())
1757 for (collision_detection::PosedBodyPointDecompositionPtr& posed_body_point_decomposition : cur_it->second)
1759 subtract_points.insert(subtract_points.end(), posed_body_point_decomposition->getCollisionPoints().begin(),
1760 posed_body_point_decomposition->getCollisionPoints().end());
1764 World::ObjectConstPtr
object =
getWorld()->getObject(
id);
1767 ROS_DEBUG_STREAM(
"Updating/Adding Object '" << object->id_ <<
"' with " << object->shapes_.size()
1768 <<
" shape(s) to CollisionEnvDistanceField");
1769 std::vector<PosedBodyPointDecompositionPtr> shape_points;
1770 for (
unsigned int i = 0; i <
object->shapes_.size(); i++)
1776 std::shared_ptr<const octomap::OcTree> octree = octree_shape->
octree;
1778 shape_points.push_back(std::make_shared<PosedBodyPointDecomposition>(octree));
1783 shape_points.push_back(
1784 std::make_shared<PosedBodyPointDecomposition>(bd,
getWorld()->getGlobalShapeTransform(
id, i)));
1787 add_points.insert(add_points.end(), shape_points.back()->getCollisionPoints().begin(),
1788 shape_points.back()->getCollisionPoints().end());
1791 dfce->posed_body_point_decompositions_[id] = shape_points;
1795 ROS_DEBUG_STREAM(
"Removing Object '" <<
id <<
"' from CollisionEnvDistanceField");
1796 dfce->posed_body_point_decompositions_.erase(
id);
1800 CollisionEnvDistanceField::DistanceFieldCacheEntryWorldPtr
1803 DistanceFieldCacheEntryWorldPtr dfce(
new DistanceFieldCacheEntryWorld());
1804 dfce->distance_field_ = std::make_shared<distance_field::PropagationDistanceField>(
1810 for (
const std::pair<const std::string, ObjectPtr>&
object : *
getWorld())
1814 dfce->distance_field_->addPointsToField(add_points);