37 #include <boost/algorithm/string.hpp>
58 const std::string
LOGNAME =
"planning_scene";
67 bool canTransform(
const std::string& from_frame)
const override
72 bool isFixedFrame(
const std::string& frame)
const override
76 if (Transforms::isFixedFrame(frame))
84 const Eigen::Isometry3d&
getTransform(
const std::string& from_frame)
const override
115 const collision_detection::WorldPtr& world)
123 : world_(world), world_const_(world)
131 robot_model_ = createRobotModel(urdf_model, srdf_model);
154 acm_ = std::make_shared<collision_detection::AllowedCollisionMatrix>(*
getRobotModel()->getSRDF());
165 return moveit::core::RobotModelPtr();
175 if (!
parent_->getName().empty())
182 world_ = std::make_shared<collision_detection::World>(*
parent_->world_);
189 for (
const std::pair<const std::string, CollisionDetectorPtr>& it :
parent_->collision_)
191 const CollisionDetectorPtr& parent_detector = it.second;
193 detector = std::make_shared<CollisionDetector>();
194 detector->alloc_ = parent_detector->alloc_;
195 detector->parent_ = parent_detector;
197 detector->cenv_ = detector->alloc_->allocateEnv(parent_detector->cenv_,
world_);
198 detector->cenv_const_ = detector->cenv_;
200 detector->cenv_unpadded_ = detector->alloc_->allocateEnv(parent_detector->cenv_unpadded_,
world_);
201 detector->cenv_unpadded_const_ = detector->cenv_unpadded_;
208 PlanningScenePtr result = scene->diff();
209 result->decoupleParent();
210 result->setName(scene->getName());
216 return PlanningScenePtr(
new PlanningScene(shared_from_this()));
221 PlanningScenePtr result =
diff();
222 result->setPlanningSceneDiffMsg(msg);
228 cenv_->setLinkPadding(src.getCollisionEnv()->getLinkPadding());
229 cenv_->setLinkScale(src.getCollisionEnv()->getLinkScale());
234 for (std::pair<const std::string, CollisionDetectorPtr>& it :
collision_)
247 if (it != scene.parent_->collision_.end())
253 const std::string&
name = allocator->getName();
259 detector = std::make_shared<CollisionDetector>();
261 detector->alloc_ = allocator;
266 detector->findParent(*
this);
269 detector->cenv_const_ = detector->cenv_;
275 detector->cenv_unpadded_const_ = detector->cenv_unpadded_;
281 detector->cenv_unpadded_const_ = detector->cenv_unpadded_;
289 CollisionDetectorPtr p;
320 "Cannot setActiveCollisionDetector to '%s' -- it has been added to PlanningScene. "
321 "Keeping existing active collision detector '%s'",
331 for (
const std::pair<const std::string, CollisionDetectorPtr>& it :
collision_)
332 names.push_back(it.first);
335 const collision_detection::CollisionEnvConstPtr&
346 return it->second->getCollisionEnv();
349 const collision_detection::CollisionEnvConstPtr&
356 "Could not get CollisionRobotUnpadded named '%s'. "
357 "Returning active CollisionRobotUnpadded '%s' instead",
362 return it->second->getCollisionEnvUnpadded();
371 world_ = std::make_shared<collision_detection::World>(*
parent_->world_);
378 for (std::pair<const std::string, CollisionDetectorPtr>& it :
collision_)
380 if (!it.second->parent_)
381 it.second->findParent(*
this);
383 if (it.second->parent_)
385 it.second->cenv_unpadded_ = it.second->alloc_->allocateEnv(it.second->parent_->cenv_unpadded_,
world_);
386 it.second->cenv_unpadded_const_ = it.second->cenv_unpadded_;
388 it.second->cenv_ = it.second->alloc_->allocateEnv(it.second->parent_->cenv_,
world_);
389 it.second->cenv_const_ = it.second->cenv_;
393 it.second->copyPadding(*
parent_->active_collision_);
394 it.second->cenv_const_ = it.second->cenv_;
411 scene->getTransformsNonConst().setAllTransforms(
scene_transforms_->getAllTransforms());
417 std::vector<const moveit::core::AttachedBody*> attached_objs;
422 scene->setObjectType(attached_obj->getName(),
getObjectType(attached_obj->getName()));
424 scene->setObjectColor(attached_obj->getName(),
getObjectColor(attached_obj->getName()));
429 scene->getAllowedCollisionMatrixNonConst() = *
acm_;
431 collision_detection::CollisionEnvPtr active_cenv = scene->getCollisionEnvNonConst();
434 scene->propogateRobotPadding();
438 for (
const std::pair<const std::string, collision_detection::World::Action>& it : *
world_diff_)
442 scene->world_->removeObject(it.first);
443 scene->removeObjectColor(it.first);
444 scene->removeObjectType(it.first);
449 scene->world_->removeObject(
obj.id_);
450 scene->world_->addToObject(
obj.id_,
obj.pose_,
obj.shapes_,
obj.shape_poses_);
456 scene->world_->setSubframesOfObject(
obj.id_,
obj.subframe_poses_);
535 const std::string& group_name)
const
561 for (collision_detection::CollisionResult::ContactMap::const_iterator it = contacts.begin(); it != contacts.end();
614 acm_ = std::make_shared<collision_detection::AllowedCollisionMatrix>(
parent_->getAllowedCollisionMatrix());
641 scene_msg.name =
name_;
643 scene_msg.is_diff =
true;
648 scene_msg.fixed_frame_transforms.clear();
653 scene_msg.robot_state = moveit_msgs::RobotState();
654 scene_msg.robot_state.is_diff =
true;
657 acm_->getMessage(scene_msg.allowed_collision_matrix);
659 scene_msg.allowed_collision_matrix = moveit_msgs::AllowedCollisionMatrix();
664 scene_msg.object_colors.clear();
671 scene_msg.object_colors[i].id = it->first;
672 scene_msg.object_colors[i].color = it->second;
676 scene_msg.world.collision_objects.clear();
677 scene_msg.world.octomap = octomap_msgs::OctomapWithPose();
681 bool do_omap =
false;
682 for (
const std::pair<const std::string, collision_detection::World::Action>& it : *
world_diff_)
687 scene_msg.world.octomap.octomap.id =
"cleared";
694 if (!std::count_if(scene_msg.robot_state.attached_collision_objects.cbegin(),
695 scene_msg.robot_state.attached_collision_objects.cend(),
696 [&it](
const moveit_msgs::AttachedCollisionObject& aco) {
697 return aco.object.id == it.first &&
698 aco.object.operation == moveit_msgs::CollisionObject::ADD;
701 moveit_msgs::CollisionObject co;
704 co.operation = moveit_msgs::CollisionObject::REMOVE;
705 scene_msg.world.collision_objects.push_back(co);
710 scene_msg.world.collision_objects.emplace_back();
721 for (
const auto& collision_object : scene_msg.world.collision_objects)
723 if (
parent_ &&
parent_->getCurrentState().hasAttachedBody(collision_object.id))
725 moveit_msgs::AttachedCollisionObject aco;
726 aco.object.id = collision_object.id;
727 aco.object.operation = moveit_msgs::CollisionObject::REMOVE;
728 scene_msg.robot_state.attached_collision_objects.push_back(aco);
735 class ShapeVisitorAddToCollisionObject :
public boost::static_visitor<void>
738 ShapeVisitorAddToCollisionObject(moveit_msgs::CollisionObject* obj) :
boost::static_visitor<void>(),
obj_(
obj)
742 void setPoseMessage(
const geometry_msgs::Pose* pose)
747 void operator()(
const shape_msgs::Plane& shape_msg)
const
749 obj_->planes.push_back(shape_msg);
753 void operator()(
const shape_msgs::Mesh& shape_msg)
const
755 obj_->meshes.push_back(shape_msg);
759 void operator()(
const shape_msgs::SolidPrimitive& shape_msg)
const
761 obj_->primitives.push_back(shape_msg);
766 moveit_msgs::CollisionObject*
obj_;
767 const geometry_msgs::Pose*
pose_;
778 collision_obj.id = ns;
779 collision_obj.operation = moveit_msgs::CollisionObject::ADD;
780 ShapeVisitorAddToCollisionObject sv(&collision_obj);
781 for (std::size_t j = 0; j <
obj->shapes_.size(); ++j)
787 sv.setPoseMessage(&p);
788 boost::apply_visitor(sv, sm);
792 if (!collision_obj.primitives.empty() || !collision_obj.meshes.empty() || !collision_obj.planes.empty())
797 for (
const auto& frame_pair :
obj->subframe_poses_)
799 collision_obj.subframe_names.push_back(frame_pair.first);
800 geometry_msgs::Pose p;
802 collision_obj.subframe_poses.push_back(p);
810 collision_objs.clear();
811 const std::vector<std::string>& ids =
world_->getObjectIds();
812 for (
const std::string&
id : ids)
815 collision_objs.emplace_back();
821 const std::string& ns)
const
823 std::vector<moveit_msgs::AttachedCollisionObject> attached_collision_objs;
825 for (moveit_msgs::AttachedCollisionObject& it : attached_collision_objs)
827 if (it.object.id == ns)
829 attached_collision_obj = it;
837 std::vector<moveit_msgs::AttachedCollisionObject>& attached_collision_objs)
const
839 std::vector<const moveit::core::AttachedBody*> attached_bodies;
847 octomap.octomap = octomap_msgs::Octomap();
852 if (map->shapes_.size() == 1)
859 ROS_ERROR_NAMED(
LOGNAME,
"Unexpected number of shapes in octomap collision object. Not including '%s' object",
867 object_colors.clear();
872 object_colors.resize(cmap.size());
873 for (ObjectColorMap::const_iterator it = cmap.begin(); it != cmap.end(); ++it, ++i)
875 object_colors[i].id = it->first;
876 object_colors[i].color = it->second;
882 scene_msg.name =
name_;
883 scene_msg.is_diff =
false;
902 const moveit_msgs::PlanningSceneComponents& comp)
const
904 scene_msg.is_diff =
false;
905 if (comp.components & moveit_msgs::PlanningSceneComponents::SCENE_SETTINGS)
907 scene_msg.name =
name_;
911 if (comp.components & moveit_msgs::PlanningSceneComponents::TRANSFORMS)
914 if (comp.components & moveit_msgs::PlanningSceneComponents::ROBOT_STATE_ATTACHED_OBJECTS)
917 for (moveit_msgs::AttachedCollisionObject& attached_collision_object :
918 scene_msg.robot_state.attached_collision_objects)
922 attached_collision_object.object.type =
getObjectType(attached_collision_object.object.id);
926 else if (comp.components & moveit_msgs::PlanningSceneComponents::ROBOT_STATE)
931 if (comp.components & moveit_msgs::PlanningSceneComponents::ALLOWED_COLLISION_MATRIX)
934 if (comp.components & moveit_msgs::PlanningSceneComponents::LINK_PADDING_AND_SCALING)
940 if (comp.components & moveit_msgs::PlanningSceneComponents::OBJECT_COLORS)
944 if (comp.components & moveit_msgs::PlanningSceneComponents::WORLD_OBJECT_GEOMETRY)
946 else if (comp.components & moveit_msgs::PlanningSceneComponents::WORLD_OBJECT_NAMES)
948 const std::vector<std::string>& ids =
world_->getObjectIds();
949 scene_msg.world.collision_objects.clear();
950 scene_msg.world.collision_objects.reserve(ids.size());
951 for (
const std::string&
id : ids)
954 moveit_msgs::CollisionObject co;
958 scene_msg.world.collision_objects.push_back(co);
963 if (comp.components & moveit_msgs::PlanningSceneComponents::OCTOMAP)
969 out <<
name_ << std::endl;
970 const std::vector<std::string>& ids =
world_->getObjectIds();
971 for (
const std::string&
id : ids)
977 out <<
"* " <<
id << std::endl;
982 out <<
obj->shapes_.size() << std::endl;
983 for (std::size_t j = 0; j <
obj->shapes_.size(); ++j)
991 out << c.r <<
" " << c.g <<
" " << c.b <<
" " << c.a << std::endl;
994 out <<
"0 0 0 0" << std::endl;
998 out <<
obj->subframe_poses_.size() << std::endl;
999 for (
auto& pose_pair :
obj->subframe_poses_)
1001 out << pose_pair.first << std::endl;
1006 out <<
"." << std::endl;
1016 if (!in.good() || in.eof())
1022 std::getline(in,
name_);
1025 auto pos = in.tellg();
1029 std::getline(in, line);
1030 }
while (in.good() && !in.eof() && (line.empty() || line[0] !=
'*'));
1031 std::getline(in, line);
1032 boost::algorithm::trim(line);
1035 bool uses_new_scene_format = line.find(
' ') != std::string::npos;
1038 Eigen::Isometry3d pose;
1043 if (!in.good() || in.eof())
1050 std::string object_id;
1051 std::getline(in, object_id);
1052 if (!in.good() || in.eof())
1057 boost::algorithm::trim(object_id);
1066 Eigen::Isometry3d object_pose = offset * pose;
1069 unsigned int shape_count;
1072 world_->removeObject(object_id);
1073 for (std::size_t i = 0; i < shape_count && in.good() && !in.eof(); ++i)
1087 if (!(in >> r >> g >> b >> a))
1094 world_->addToObject(object_id, shape, pose);
1095 if (r > 0.0f || g > 0.0f || b > 0.0f || a > 0.0f)
1097 std_msgs::ColorRGBA color;
1108 world_->setObjectPose(object_id, object_pose);
1111 if (uses_new_scene_format)
1114 unsigned int subframe_count;
1115 in >> subframe_count;
1116 for (std::size_t i = 0; i < subframe_count && in.good() && !in.eof(); ++i)
1118 std::string subframe_name;
1119 in >> subframe_name;
1125 subframes[subframe_name] = pose;
1127 world_->setSubframesOfObject(object_id, subframes);
1130 else if (marker ==
".")
1145 double x,
y,
z, rx, ry, rz, rw;
1146 if (!(in >> x >> y >> z))
1151 if (!(in >> rx >> ry >> rz >> rw))
1156 pose = Eigen::Translation3d(x, y, z) * Eigen::Quaterniond(rw, rx, ry, rz);
1162 out << pose.translation().x() <<
" " << pose.translation().y() <<
" " << pose.translation().z() << std::endl;
1163 Eigen::Quaterniond
r(pose.linear());
1164 out <<
r.x() <<
" " <<
r.y() <<
" " <<
r.z() <<
" " <<
r.w() << std::endl;
1171 moveit_msgs::RobotState state_no_attached(state);
1172 state_no_attached.attached_collision_objects.clear();
1186 for (std::size_t i = 0; i < state.attached_collision_objects.size(); ++i)
1188 if (!state.is_diff && state.attached_collision_objects[i].object.operation != moveit_msgs::CollisionObject::ADD)
1191 "The specified RobotState is not marked as is_diff. "
1192 "The request to modify the object '%s' is not supported. Object is ignored.",
1193 state.attached_collision_objects[i].object.id.c_str());
1224 acm_ = std::make_shared<collision_detection::AllowedCollisionMatrix>(
parent_->getAllowedCollisionMatrix());
1226 for (std::pair<const std::string, CollisionDetectorPtr>& it :
collision_)
1228 it.second->parent_.reset();
1235 parent_->getKnownObjectColors(kc);
1241 parent_->getKnownObjectColors(kc);
1242 for (ObjectColorMap::const_iterator it = kc.begin(); it != kc.end(); ++it)
1244 (*object_colors_)[it->first] = it->second;
1250 parent_->getKnownObjectTypes(kc);
1256 parent_->getKnownObjectTypes(kc);
1257 for (ObjectTypeMap::const_iterator it = kc.begin(); it != kc.end(); ++it)
1259 (*object_types_)[it->first] = it->second;
1270 if (!scene_msg.name.empty())
1271 name_ = scene_msg.name;
1273 if (!scene_msg.robot_model_name.empty() && scene_msg.robot_model_name !=
getRobotModel()->
getName())
1279 if (!scene_msg.fixed_frame_transforms.empty())
1287 if (!scene_msg.robot_state.multi_dof_joint_state.joint_names.empty() ||
1288 !scene_msg.robot_state.joint_state.name.empty() || !scene_msg.robot_state.attached_collision_objects.empty())
1292 if (!scene_msg.allowed_collision_matrix.entry_names.empty())
1293 acm_ = std::make_shared<collision_detection::AllowedCollisionMatrix>(scene_msg.allowed_collision_matrix);
1295 if (!scene_msg.link_padding.empty() || !scene_msg.link_scale.empty())
1297 for (std::pair<const std::string, CollisionDetectorPtr>& it :
collision_)
1299 it.second->cenv_->setPadding(scene_msg.link_padding);
1300 it.second->cenv_->setScale(scene_msg.link_scale);
1305 for (
const moveit_msgs::ObjectColor& object_color : scene_msg.object_colors)
1309 for (
const moveit_msgs::CollisionObject& collision_object : scene_msg.world.collision_objects)
1313 if (!scene_msg.world.octomap.octomap.id.empty())
1321 assert(scene_msg.is_diff ==
false);
1323 name_ = scene_msg.name;
1325 if (!scene_msg.robot_model_name.empty() && scene_msg.robot_model_name !=
getRobotModel()->
getName())
1335 acm_ = std::make_shared<collision_detection::AllowedCollisionMatrix>(scene_msg.allowed_collision_matrix);
1336 for (std::pair<const std::string, CollisionDetectorPtr>& it :
collision_)
1338 it.second->cenv_->setPadding(scene_msg.link_padding);
1339 it.second->cenv_->setScale(scene_msg.link_scale);
1342 for (
const moveit_msgs::ObjectColor& object_color : scene_msg.object_colors)
1351 for (
const moveit_msgs::CollisionObject& collision_object : world.collision_objects)
1359 if (scene_msg.is_diff)
1367 std::shared_ptr<collision_detection::OccMapTree> om =
1368 std::make_shared<collision_detection::OccMapTree>(map.resolution);
1375 std::stringstream datastream;
1376 if (!map.data.empty())
1378 datastream.write((
const char*)&map.data[0], map.data.size());
1379 om->readData(datastream);
1390 if (map.data.empty())
1393 if (map.id !=
"OcTree")
1395 ROS_ERROR_NAMED(
LOGNAME,
"Received octomap is of type '%s' but type 'OcTree' is expected.", map.id.c_str());
1399 std::shared_ptr<collision_detection::OccMapTree> om =
createOctomap(map);
1400 if (!map.header.frame_id.empty())
1413 const std::vector<std::string>& object_ids =
world_->getObjectIds();
1414 for (
const std::string& object_id : object_ids)
1428 if (map.octomap.data.empty())
1431 if (map.octomap.id !=
"OcTree")
1433 ROS_ERROR_NAMED(
LOGNAME,
"Received octomap is of type '%s' but type 'OcTree' is expected.", map.octomap.id.c_str());
1437 std::shared_ptr<collision_detection::OccMapTree> om =
createOctomap(map.octomap);
1440 Eigen::Isometry3d p;
1451 if (map->shapes_.size() == 1)
1458 if (map->shape_poses_[0].isApprox(
t, std::numeric_limits<double>::epsilon() * 100.0))
1481 if (
object.
object.operation == moveit_msgs::CollisionObject::ADD && !
getRobotModel()->hasLinkModel(
object.link_name))
1483 ROS_ERROR_NAMED(
LOGNAME,
"Unable to attach a body to link '%s' (link not found)",
object.link_name.c_str());
1505 if (
object.
object.operation == moveit_msgs::CollisionObject::ADD ||
1506 object.
object.operation == moveit_msgs::CollisionObject::APPEND)
1512 Eigen::Isometry3d object_pose_in_link;
1513 std::vector<shapes::ShapeConstPtr>
shapes;
1521 if (
object.
object.operation == moveit_msgs::CollisionObject::ADD &&
object.
object.primitives.empty() &&
1522 object.object.meshes.empty() &&
object.object.planes.empty())
1527 object.link_name.c_str());
1528 object_pose_in_link =
robot_state_->getGlobalLinkTransform(link_model).inverse() * obj_in_world->pose_;
1529 shapes = obj_in_world->shapes_;
1530 shape_poses = obj_in_world->shape_poses_;
1531 subframe_poses = obj_in_world->subframe_poses_;
1536 "Attempting to attach object '%s' to link '%s' but no geometry specified "
1537 "and such an object does not exist in the collision world",
1538 object.
object.
id.c_str(),
object.link_name.c_str());
1544 Eigen::Isometry3d header_frame_to_object_pose;
1548 const Eigen::Isometry3d link_to_header_frame =
1549 robot_state_->getGlobalLinkTransform(link_model).inverse() * world_to_header_frame;
1550 object_pose_in_link = link_to_header_frame * header_frame_to_object_pose;
1552 Eigen::Isometry3d subframe_pose;
1553 for (std::size_t i = 0; i <
object.object.subframe_poses.size(); ++i)
1556 std::string
name =
object.object.subframe_names[i];
1557 subframe_poses[
name] = subframe_pose;
1564 object.link_name.c_str(),
object.object.id.c_str());
1568 if (!
object.
object.type.db.empty() || !
object.object.type.key.empty())
1572 if (obj_in_world &&
world_->removeObject(
object.object.id))
1574 if (
object.
object.operation == moveit_msgs::CollisionObject::ADD)
1576 object.
object.
id.c_str());
1579 "You tried to append geometry to an attached object "
1580 "that is actually a world object ('%s'). World geometry is ignored.",
1581 object.
object.
id.c_str());
1585 if (
object.
object.operation == moveit_msgs::CollisionObject::ADD ||
1590 "The robot state already had an object named '%s' attached to link '%s'. "
1591 "The object was replaced.",
1592 object.
object.
id.c_str(),
object.link_name.c_str());
1594 robot_state_->attachBody(
object.
object.
id, object_pose_in_link,
shapes, shape_poses,
object.touch_links,
1595 object.link_name,
object.detach_posture, subframe_poses);
1597 object.link_name.c_str());
1605 object_pose_in_link = ab->
getPose();
1610 trajectory_msgs::JointTrajectory detach_posture =
1611 object.detach_posture.joint_names.empty() ? ab->
getDetachPosture() :
object.detach_posture;
1614 touch_links.insert(std::make_move_iterator(
object.touch_links.begin()),
1615 std::make_move_iterator(
object.touch_links.end()));
1618 robot_state_->attachBody(
object.
object.
id, object_pose_in_link,
shapes, shape_poses, touch_links,
1619 object.link_name, detach_posture, subframe_poses);
1620 ROS_DEBUG_NAMED(
LOGNAME,
"Appended things to object '%s' attached to link '%s'",
object.
object.
id.c_str(),
1621 object.link_name.c_str());
1628 else if (
object.
object.operation == moveit_msgs::CollisionObject::REMOVE)
1631 std::vector<const moveit::core::AttachedBody*> attached_bodies;
1632 if (
object.
object.
id.empty())
1635 object.link_name.empty() ? nullptr :
getRobotModel()->getLinkModel(
object.link_name);
1637 robot_state_->getAttachedBodies(attached_bodies, link_model);
1649 <<
object.link_name <<
", but it is actually attached to "
1651 <<
". Leave the link_name empty or specify the correct link.");
1654 attached_bodies.push_back(body);
1661 const std::string&
name = attached_body->getName();
1662 if (
world_->hasObject(name))
1664 "The collision world already has an object with the same name as the body about to be detached. "
1665 "NOT adding the detached body '%s' to the collision world.",
1666 object.
object.
id.c_str());
1669 const Eigen::Isometry3d& pose = attached_body->getGlobalPose();
1670 world_->addToObject(name, pose, attached_body->getShapes(), attached_body->getShapePoses());
1671 world_->setSubframesOfObject(name, attached_body->getSubframes());
1673 name.c_str(),
object.link_name.c_str());
1678 if (!attached_bodies.empty() ||
object.object.id.empty())
1681 else if (
object.
object.operation == moveit_msgs::CollisionObject::MOVE)
1701 if (
object.operation == moveit_msgs::CollisionObject::ADD ||
object.operation == moveit_msgs::CollisionObject::APPEND)
1705 else if (
object.operation == moveit_msgs::CollisionObject::REMOVE)
1709 else if (
object.operation == moveit_msgs::CollisionObject::MOVE)
1720 Eigen::Translation3d translation(msg.position.x, msg.position.y, msg.position.z);
1721 Eigen::Quaterniond quaternion(msg.orientation.w, msg.orientation.x, msg.orientation.y, msg.orientation.z);
1722 if ((quaternion.x() == 0) && (quaternion.y() == 0) && (quaternion.z() == 0) && (quaternion.w() == 0))
1725 quaternion.setIdentity();
1729 quaternion.normalize();
1731 out = translation * quaternion;
1735 Eigen::Isometry3d& object_pose,
1736 std::vector<shapes::ShapeConstPtr>&
shapes,
1739 if (
object.primitives.size() <
object.primitive_poses.size())
1744 if (
object.meshes.size() <
object.mesh_poses.size())
1749 if (
object.planes.size() <
object.plane_poses.size())
1755 const int num_shapes =
object.primitives.size() +
object.meshes.size() +
object.planes.size();
1756 shapes.reserve(num_shapes);
1757 shape_poses.reserve(num_shapes);
1759 bool switch_object_pose_and_shape_pose =
false;
1763 switch_object_pose_and_shape_pose =
true;
1764 object_pose.setIdentity();
1770 &switch_object_pose_and_shape_pose](
shapes::Shape*
s,
const geometry_msgs::Pose& pose_msg) {
1773 Eigen::Isometry3d pose;
1775 if (!switch_object_pose_and_shape_pose)
1776 shape_poses.emplace_back(std::move(pose));
1779 shape_poses.emplace_back(std::move(object_pose));
1785 auto treat_shape_vectors = [&
append](
const auto& shape_vector,
1786 const auto& shape_poses_vector,
1787 const std::string& shape_type) {
1788 if (shape_vector.size() > shape_poses_vector.size())
1791 <<
" does not match number of poses "
1792 "in collision object message. Assuming identity.");
1793 for (std::size_t i = 0; i < shape_vector.size(); ++i)
1795 if (i >= shape_poses_vector.size())
1798 geometry_msgs::Pose identity;
1799 identity.orientation.w = 1.0;
1807 for (std::size_t i = 0; i < shape_vector.size(); ++i)
1811 treat_shape_vectors(
object.primitives,
object.primitive_poses, std::string(
"primitive_poses"));
1812 treat_shape_vectors(
object.meshes,
object.mesh_poses, std::string(
"meshes"));
1813 treat_shape_vectors(
object.planes,
object.plane_poses, std::string(
"planes"));
1825 if (
object.primitives.empty() &&
object.meshes.empty() &&
object.planes.empty())
1832 if (
object.operation == moveit_msgs::CollisionObject::ADD &&
world_->hasObject(
object.id))
1833 world_->removeObject(
object.
id);
1836 Eigen::Isometry3d header_to_pose_transform;
1837 std::vector<shapes::ShapeConstPtr>
shapes;
1841 const Eigen::Isometry3d object_frame_transform = world_to_object_header_transform * header_to_pose_transform;
1843 world_->addToObject(
object.
id, object_frame_transform,
shapes, shape_poses);
1845 if (!
object.type.key.empty() || !
object.type.db.empty())
1850 Eigen::Isometry3d subframe_pose;
1851 for (std::size_t i = 0; i <
object.subframe_poses.size(); ++i)
1854 std::string
name =
object.subframe_names[i];
1855 subframes[
name] = subframe_pose;
1857 world_->setSubframesOfObject(
object.
id, subframes);
1863 if (
object.
id.empty())
1869 if (!
world_->removeObject(
object.id))
1872 "Tried to remove world object '" <<
object.
id <<
"', but it does not exist in this scene.");
1884 if (
world_->hasObject(
object.id))
1887 if (!
object.primitives.empty() || !
object.meshes.empty() || !
object.planes.empty())
1888 ROS_WARN_NAMED(
LOGNAME,
"Move operation for object '%s' ignores the geometry specified in the message.",
1892 Eigen::Isometry3d header_to_pose_transform;
1896 const Eigen::Isometry3d object_frame_transform = world_to_object_header_transform * header_to_pose_transform;
1897 world_->setObjectPose(
object.
id, object_frame_transform);
1900 if (!
object.primitive_poses.empty() || !
object.mesh_poses.empty() || !
object.plane_poses.empty())
1902 auto world_object =
world_->getObject(
object.
id);
1904 std::size_t shape_size =
object.primitive_poses.size() +
object.mesh_poses.size() +
object.plane_poses.size();
1905 if (shape_size != world_object->shape_poses_.size())
1907 ROS_ERROR_NAMED(
LOGNAME,
"Move operation for object '%s' must have same number of geometry poses. Cannot move.",
1914 for (
const auto& shape_pose :
object.primitive_poses)
1916 shape_poses.emplace_back();
1919 for (
const auto& shape_pose :
object.mesh_poses)
1921 shape_poses.emplace_back();
1924 for (
const auto& shape_pose :
object.plane_poses)
1926 shape_poses.emplace_back();
1930 if (!
world_->moveShapesInObject(
object.id, shape_poses))
1932 ROS_ERROR_NAMED(
LOGNAME,
"Move operation for object '%s' internal world error. Cannot move.",
object.
id.c_str());
1958 const std::string& frame_id)
const
1960 if (!frame_id.empty() && frame_id[0] ==
'/')
1969 const Eigen::Isometry3d& t2 =
getWorld()->getTransform(frame_id, frame_found);
1982 if (!frame_id.empty() && frame_id[0] ==
'/')
1987 if (
getWorld()->knowsTransform(frame_id))
1998 return parent_->hasObjectType(object_id);
2006 ObjectTypeMap::const_iterator it =
object_types_->find(object_id);
2011 return parent_->getObjectType(object_id);
2012 static const object_recognition_msgs::ObjectType EMPTY;
2020 (*object_types_)[object_id] = type;
2033 parent_->getKnownObjectTypes(kc);
2036 kc[it->first] = it->second;
2045 return parent_->hasObjectColor(object_id);
2053 ObjectColorMap::const_iterator it =
object_colors_->find(object_id);
2058 return parent_->getObjectColor(object_id);
2059 static const std_msgs::ColorRGBA EMPTY;
2067 parent_->getKnownObjectColors(kc);
2070 kc[it->first] = it->second;
2075 if (object_id.empty())
2082 (*object_colors_)[object_id] = color;
2145 kinematic_constraints::KinematicConstraintSetPtr ks(
2170 static const moveit_msgs::Constraints EMP_CONSTRAINTS;
2176 static const moveit_msgs::Constraints EMP_CONSTRAINTS;
2181 const std::string& group,
bool verbose)
const
2189 const std::string& group,
bool verbose)
const
2210 const moveit_msgs::RobotTrajectory& trajectory,
const std::string& group,
bool verbose,
2211 std::vector<std::size_t>* invalid_index)
const
2213 static const moveit_msgs::Constraints EMP_CONSTRAINTS;
2214 static const std::vector<moveit_msgs::Constraints> EMP_CONSTRAINTS_VECTOR;
2215 return isPathValid(start_state, trajectory, EMP_CONSTRAINTS, EMP_CONSTRAINTS_VECTOR, group,
verbose, invalid_index);
2219 const moveit_msgs::RobotTrajectory& trajectory,
2220 const moveit_msgs::Constraints& path_constraints,
const std::string& group,
2221 bool verbose, std::vector<std::size_t>* invalid_index)
const
2223 static const std::vector<moveit_msgs::Constraints> EMP_CONSTRAINTS_VECTOR;
2224 return isPathValid(start_state, trajectory, path_constraints, EMP_CONSTRAINTS_VECTOR, group,
verbose, invalid_index);
2228 const moveit_msgs::RobotTrajectory& trajectory,
2229 const moveit_msgs::Constraints& path_constraints,
2230 const moveit_msgs::Constraints& goal_constraints,
const std::string& group,
2231 bool verbose, std::vector<std::size_t>* invalid_index)
const
2233 std::vector<moveit_msgs::Constraints> goal_constraints_vector(1, goal_constraints);
2234 return isPathValid(start_state, trajectory, path_constraints, goal_constraints_vector, group,
verbose, invalid_index);
2238 const moveit_msgs::RobotTrajectory& trajectory,
2239 const moveit_msgs::Constraints& path_constraints,
2240 const std::vector<moveit_msgs::Constraints>& goal_constraints,
const std::string& group,
2241 bool verbose, std::vector<std::size_t>* invalid_index)
const
2246 t.setRobotTrajectoryMsg(
start, trajectory);
2251 const moveit_msgs::Constraints& path_constraints,
2252 const std::vector<moveit_msgs::Constraints>& goal_constraints,
const std::string& group,
2253 bool verbose, std::vector<std::size_t>* invalid_index)
const
2257 invalid_index->clear();
2261 for (std::size_t i = 0; i < n_wp; ++i)
2265 bool this_state_valid =
true;
2267 this_state_valid =
false;
2269 this_state_valid =
false;
2271 this_state_valid =
false;
2273 if (!this_state_valid)
2276 invalid_index->push_back(i);
2283 if (i + 1 == n_wp && !goal_constraints.empty())
2286 for (
const moveit_msgs::Constraints& goal_constraint : goal_constraints)
2299 invalid_index->push_back(i);
2308 const moveit_msgs::Constraints& path_constraints,
2309 const moveit_msgs::Constraints& goal_constraints,
const std::string& group,
2310 bool verbose, std::vector<std::size_t>* invalid_index)
const
2312 std::vector<moveit_msgs::Constraints> goal_constraints_vector(1, goal_constraints);
2313 return isPathValid(trajectory, path_constraints, goal_constraints_vector, group, verbose, invalid_index);
2317 const moveit_msgs::Constraints& path_constraints,
const std::string& group,
2318 bool verbose, std::vector<std::size_t>* invalid_index)
const
2320 static const std::vector<moveit_msgs::Constraints> EMP_CONSTRAINTS_VECTOR;
2321 return isPathValid(trajectory, path_constraints, EMP_CONSTRAINTS_VECTOR, group, verbose, invalid_index);
2325 bool verbose, std::vector<std::size_t>* invalid_index)
const
2327 static const moveit_msgs::Constraints EMP_CONSTRAINTS;
2328 static const std::vector<moveit_msgs::Constraints> EMP_CONSTRAINTS_VECTOR;
2329 return isPathValid(trajectory, EMP_CONSTRAINTS, EMP_CONSTRAINTS_VECTOR, group, verbose, invalid_index);
2333 std::set<collision_detection::CostSource>& costs,
double overlap_fraction)
const
2335 getCostSources(trajectory, max_costs, std::string(), costs, overlap_fraction);
2339 const std::string& group_name, std::set<collision_detection::CostSource>& costs,
2340 double overlap_fraction)
const
2346 std::set<collision_detection::CostSource> cs;
2347 std::set<collision_detection::CostSource> cs_start;
2349 for (std::size_t i = 0; i < n_wp; ++i)
2358 if (cs.size() <= max_costs)
2364 for (std::set<collision_detection::CostSource>::iterator it = cs.begin(); i < max_costs; ++it, ++i)
2373 std::set<collision_detection::CostSource>& costs)
const
2379 const std::string& group_name,
2380 std::set<collision_detection::CostSource>& costs)
const
2393 const std::vector<std::string>& objects =
getWorld()->getObjectIds();
2394 std::vector<const moveit::core::AttachedBody*> attached_bodies;
2398 out <<
"-----------------------------------------\n";
2399 out <<
"PlanningScene Known Objects:\n";
2400 out <<
" - Collision World Objects:\n ";
2401 for (
const std::string&
object : objects)
2403 out <<
"\t- " <<
object <<
"\n";
2406 out <<
" - Attached Bodies:\n";
2409 out <<
"\t- " << attached_body->getName() <<
"\n";
2411 out <<
"-----------------------------------------\n";