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);
445 scene->getAllowedCollisionMatrixNonConst().removeEntry(it.first);
450 scene->world_->removeObject(
obj.id_);
451 scene->world_->addToObject(
obj.id_,
obj.pose_,
obj.shapes_,
obj.shape_poses_);
457 scene->world_->setSubframesOfObject(
obj.id_,
obj.subframe_poses_);
536 const std::string& group_name)
const
562 for (collision_detection::CollisionResult::ContactMap::const_iterator it = contacts.begin(); it != contacts.end();
615 acm_ = std::make_shared<collision_detection::AllowedCollisionMatrix>(
parent_->getAllowedCollisionMatrix());
642 scene_msg.name =
name_;
644 scene_msg.is_diff =
true;
649 scene_msg.fixed_frame_transforms.clear();
654 scene_msg.robot_state = moveit_msgs::RobotState();
655 scene_msg.robot_state.is_diff =
true;
658 acm_->getMessage(scene_msg.allowed_collision_matrix);
660 scene_msg.allowed_collision_matrix = moveit_msgs::AllowedCollisionMatrix();
665 scene_msg.object_colors.clear();
672 scene_msg.object_colors[i].id = it->first;
673 scene_msg.object_colors[i].color = it->second;
677 scene_msg.world.collision_objects.clear();
678 scene_msg.world.octomap = octomap_msgs::OctomapWithPose();
682 bool do_omap =
false;
683 for (
const std::pair<const std::string, collision_detection::World::Action>& it : *
world_diff_)
688 scene_msg.world.octomap.octomap.id =
"cleared";
695 if (!std::count_if(scene_msg.robot_state.attached_collision_objects.cbegin(),
696 scene_msg.robot_state.attached_collision_objects.cend(),
697 [&it](
const moveit_msgs::AttachedCollisionObject& aco) {
698 return aco.object.id == it.first &&
699 aco.object.operation == moveit_msgs::CollisionObject::ADD;
702 moveit_msgs::CollisionObject co;
705 co.operation = moveit_msgs::CollisionObject::REMOVE;
706 scene_msg.world.collision_objects.push_back(co);
711 scene_msg.world.collision_objects.emplace_back();
722 for (
const auto& collision_object : scene_msg.world.collision_objects)
724 if (
parent_ &&
parent_->getCurrentState().hasAttachedBody(collision_object.id))
726 moveit_msgs::AttachedCollisionObject aco;
727 aco.object.id = collision_object.id;
728 aco.object.operation = moveit_msgs::CollisionObject::REMOVE;
729 scene_msg.robot_state.attached_collision_objects.push_back(aco);
736 class ShapeVisitorAddToCollisionObject :
public boost::static_visitor<void>
739 ShapeVisitorAddToCollisionObject(moveit_msgs::CollisionObject* obj) :
boost::static_visitor<void>(),
obj_(
obj)
743 void setPoseMessage(
const geometry_msgs::Pose* pose)
748 void operator()(
const shape_msgs::Plane& shape_msg)
const
750 obj_->planes.push_back(shape_msg);
754 void operator()(
const shape_msgs::Mesh& shape_msg)
const
756 obj_->meshes.push_back(shape_msg);
760 void operator()(
const shape_msgs::SolidPrimitive& shape_msg)
const
762 obj_->primitives.push_back(shape_msg);
767 moveit_msgs::CollisionObject*
obj_;
768 const geometry_msgs::Pose*
pose_;
779 collision_obj.id = ns;
780 collision_obj.operation = moveit_msgs::CollisionObject::ADD;
781 ShapeVisitorAddToCollisionObject sv(&collision_obj);
782 for (std::size_t j = 0; j <
obj->shapes_.size(); ++j)
788 sv.setPoseMessage(&p);
789 boost::apply_visitor(sv, sm);
793 if (!collision_obj.primitives.empty() || !collision_obj.meshes.empty() || !collision_obj.planes.empty())
798 for (
const auto& frame_pair :
obj->subframe_poses_)
800 collision_obj.subframe_names.push_back(frame_pair.first);
801 geometry_msgs::Pose p;
803 collision_obj.subframe_poses.push_back(p);
811 collision_objs.clear();
812 const std::vector<std::string>& ids =
world_->getObjectIds();
813 for (
const std::string&
id : ids)
816 collision_objs.emplace_back();
822 const std::string& ns)
const
824 std::vector<moveit_msgs::AttachedCollisionObject> attached_collision_objs;
826 for (moveit_msgs::AttachedCollisionObject& it : attached_collision_objs)
828 if (it.object.id == ns)
830 attached_collision_obj = it;
838 std::vector<moveit_msgs::AttachedCollisionObject>& attached_collision_objs)
const
840 std::vector<const moveit::core::AttachedBody*> attached_bodies;
848 octomap.octomap = octomap_msgs::Octomap();
853 if (map->shapes_.size() == 1)
860 ROS_ERROR_NAMED(
LOGNAME,
"Unexpected number of shapes in octomap collision object. Not including '%s' object",
868 object_colors.clear();
873 object_colors.resize(cmap.size());
874 for (ObjectColorMap::const_iterator it = cmap.begin(); it != cmap.end(); ++it, ++i)
876 object_colors[i].id = it->first;
877 object_colors[i].color = it->second;
883 scene_msg.name =
name_;
884 scene_msg.is_diff =
false;
903 const moveit_msgs::PlanningSceneComponents& comp)
const
905 scene_msg.is_diff =
false;
906 if (comp.components & moveit_msgs::PlanningSceneComponents::SCENE_SETTINGS)
908 scene_msg.name =
name_;
912 if (comp.components & moveit_msgs::PlanningSceneComponents::TRANSFORMS)
915 if (comp.components & moveit_msgs::PlanningSceneComponents::ROBOT_STATE_ATTACHED_OBJECTS)
918 for (moveit_msgs::AttachedCollisionObject& attached_collision_object :
919 scene_msg.robot_state.attached_collision_objects)
923 attached_collision_object.object.type =
getObjectType(attached_collision_object.object.id);
927 else if (comp.components & moveit_msgs::PlanningSceneComponents::ROBOT_STATE)
932 if (comp.components & moveit_msgs::PlanningSceneComponents::ALLOWED_COLLISION_MATRIX)
935 if (comp.components & moveit_msgs::PlanningSceneComponents::LINK_PADDING_AND_SCALING)
941 if (comp.components & moveit_msgs::PlanningSceneComponents::OBJECT_COLORS)
945 if (comp.components & moveit_msgs::PlanningSceneComponents::WORLD_OBJECT_GEOMETRY)
947 else if (comp.components & moveit_msgs::PlanningSceneComponents::WORLD_OBJECT_NAMES)
949 const std::vector<std::string>& ids =
world_->getObjectIds();
950 scene_msg.world.collision_objects.clear();
951 scene_msg.world.collision_objects.reserve(ids.size());
952 for (
const std::string&
id : ids)
955 moveit_msgs::CollisionObject co;
959 scene_msg.world.collision_objects.push_back(co);
964 if (comp.components & moveit_msgs::PlanningSceneComponents::OCTOMAP)
970 out <<
name_ << std::endl;
971 const std::vector<std::string>& ids =
world_->getObjectIds();
972 for (
const std::string&
id : ids)
978 out <<
"* " <<
id << std::endl;
983 out <<
obj->shapes_.size() << std::endl;
984 for (std::size_t j = 0; j <
obj->shapes_.size(); ++j)
992 out << c.r <<
" " << c.g <<
" " << c.b <<
" " << c.a << std::endl;
995 out <<
"0 0 0 0" << std::endl;
999 out <<
obj->subframe_poses_.size() << std::endl;
1000 for (
auto& pose_pair :
obj->subframe_poses_)
1002 out << pose_pair.first << std::endl;
1007 out <<
"." << std::endl;
1017 if (!in.good() || in.eof())
1023 std::getline(in,
name_);
1026 auto pos = in.tellg();
1030 std::getline(in, line);
1031 }
while (in.good() && !in.eof() && (line.empty() || line[0] !=
'*'));
1032 std::getline(in, line);
1033 boost::algorithm::trim(line);
1036 bool uses_new_scene_format = line.find(
' ') != std::string::npos;
1039 Eigen::Isometry3d pose;
1044 if (!in.good() || in.eof())
1051 std::string object_id;
1052 std::getline(in, object_id);
1053 if (!in.good() || in.eof())
1058 boost::algorithm::trim(object_id);
1067 Eigen::Isometry3d object_pose = offset * pose;
1070 unsigned int shape_count;
1073 world_->removeObject(object_id);
1074 for (std::size_t i = 0; i < shape_count && in.good() && !in.eof(); ++i)
1088 if (!(in >> r >> g >> b >> a))
1095 world_->addToObject(object_id, shape, pose);
1096 if (r > 0.0f || g > 0.0f || b > 0.0f || a > 0.0f)
1098 std_msgs::ColorRGBA color;
1109 world_->setObjectPose(object_id, object_pose);
1112 if (uses_new_scene_format)
1115 unsigned int subframe_count;
1116 in >> subframe_count;
1117 for (std::size_t i = 0; i < subframe_count && in.good() && !in.eof(); ++i)
1119 std::string subframe_name;
1120 in >> subframe_name;
1126 subframes[subframe_name] = pose;
1128 world_->setSubframesOfObject(object_id, subframes);
1131 else if (marker ==
".")
1146 double x,
y,
z, rx, ry, rz, rw;
1147 if (!(in >> x >> y >> z))
1152 if (!(in >> rx >> ry >> rz >> rw))
1157 pose = Eigen::Translation3d(x, y, z) * Eigen::Quaterniond(rw, rx, ry, rz);
1163 out << pose.translation().x() <<
" " << pose.translation().y() <<
" " << pose.translation().z() << std::endl;
1164 Eigen::Quaterniond
r(pose.linear());
1165 out <<
r.x() <<
" " <<
r.y() <<
" " <<
r.z() <<
" " <<
r.w() << std::endl;
1172 moveit_msgs::RobotState state_no_attached(state);
1173 state_no_attached.attached_collision_objects.clear();
1187 for (std::size_t i = 0; i < state.attached_collision_objects.size(); ++i)
1189 if (!state.is_diff && state.attached_collision_objects[i].object.operation != moveit_msgs::CollisionObject::ADD)
1192 "The specified RobotState is not marked as is_diff. "
1193 "The request to modify the object '%s' is not supported. Object is ignored.",
1194 state.attached_collision_objects[i].object.id.c_str());
1225 acm_ = std::make_shared<collision_detection::AllowedCollisionMatrix>(
parent_->getAllowedCollisionMatrix());
1227 for (std::pair<const std::string, CollisionDetectorPtr>& it :
collision_)
1229 it.second->parent_.reset();
1236 parent_->getKnownObjectColors(kc);
1242 parent_->getKnownObjectColors(kc);
1243 for (ObjectColorMap::const_iterator it = kc.begin(); it != kc.end(); ++it)
1245 (*object_colors_)[it->first] = it->second;
1251 parent_->getKnownObjectTypes(kc);
1257 parent_->getKnownObjectTypes(kc);
1258 for (ObjectTypeMap::const_iterator it = kc.begin(); it != kc.end(); ++it)
1260 (*object_types_)[it->first] = it->second;
1271 if (!scene_msg.name.empty())
1272 name_ = scene_msg.name;
1274 if (!scene_msg.robot_model_name.empty() && scene_msg.robot_model_name !=
getRobotModel()->
getName())
1280 if (!scene_msg.fixed_frame_transforms.empty())
1288 if (!scene_msg.robot_state.multi_dof_joint_state.joint_names.empty() ||
1289 !scene_msg.robot_state.joint_state.name.empty() || !scene_msg.robot_state.attached_collision_objects.empty())
1293 if (!scene_msg.allowed_collision_matrix.entry_names.empty())
1294 acm_ = std::make_shared<collision_detection::AllowedCollisionMatrix>(scene_msg.allowed_collision_matrix);
1296 if (!scene_msg.link_padding.empty() || !scene_msg.link_scale.empty())
1298 for (std::pair<const std::string, CollisionDetectorPtr>& it :
collision_)
1300 it.second->cenv_->setPadding(scene_msg.link_padding);
1301 it.second->cenv_->setScale(scene_msg.link_scale);
1306 for (
const moveit_msgs::ObjectColor& object_color : scene_msg.object_colors)
1310 for (
const moveit_msgs::CollisionObject& collision_object : scene_msg.world.collision_objects)
1314 if (!scene_msg.world.octomap.octomap.id.empty())
1322 assert(scene_msg.is_diff ==
false);
1324 name_ = scene_msg.name;
1326 if (!scene_msg.robot_model_name.empty() && scene_msg.robot_model_name !=
getRobotModel()->
getName())
1336 acm_ = std::make_shared<collision_detection::AllowedCollisionMatrix>(scene_msg.allowed_collision_matrix);
1337 for (std::pair<const std::string, CollisionDetectorPtr>& it :
collision_)
1339 it.second->cenv_->setPadding(scene_msg.link_padding);
1340 it.second->cenv_->setScale(scene_msg.link_scale);
1343 for (
const moveit_msgs::ObjectColor& object_color : scene_msg.object_colors)
1352 for (
const moveit_msgs::CollisionObject& collision_object : world.collision_objects)
1360 if (scene_msg.is_diff)
1368 std::shared_ptr<collision_detection::OccMapTree> om =
1369 std::make_shared<collision_detection::OccMapTree>(map.resolution);
1376 std::stringstream datastream;
1377 if (!map.data.empty())
1379 datastream.write((
const char*)&map.data[0], map.data.size());
1380 om->readData(datastream);
1391 if (map.data.empty())
1394 if (map.id !=
"OcTree")
1396 ROS_ERROR_NAMED(
LOGNAME,
"Received octomap is of type '%s' but type 'OcTree' is expected.", map.id.c_str());
1400 std::shared_ptr<collision_detection::OccMapTree> om =
createOctomap(map);
1401 if (!map.header.frame_id.empty())
1414 const std::vector<std::string>& object_ids =
world_->getObjectIds();
1415 for (
const std::string& object_id : object_ids)
1430 if (map.octomap.data.empty())
1433 if (map.octomap.id !=
"OcTree")
1435 ROS_ERROR_NAMED(
LOGNAME,
"Received octomap is of type '%s' but type 'OcTree' is expected.", map.octomap.id.c_str());
1439 std::shared_ptr<collision_detection::OccMapTree> om =
createOctomap(map.octomap);
1442 Eigen::Isometry3d p;
1453 if (map->shapes_.size() == 1)
1460 if (map->shape_poses_[0].isApprox(
t, std::numeric_limits<double>::epsilon() * 100.0))
1483 if (
object.
object.operation == moveit_msgs::CollisionObject::ADD && !
getRobotModel()->hasLinkModel(
object.link_name))
1485 ROS_ERROR_NAMED(
LOGNAME,
"Unable to attach a body to link '%s' (link not found)",
object.link_name.c_str());
1507 if (
object.
object.operation == moveit_msgs::CollisionObject::ADD ||
1508 object.
object.operation == moveit_msgs::CollisionObject::APPEND)
1514 Eigen::Isometry3d object_pose_in_link;
1515 std::vector<shapes::ShapeConstPtr>
shapes;
1523 if (
object.
object.operation == moveit_msgs::CollisionObject::ADD &&
object.
object.primitives.empty() &&
1524 object.object.meshes.empty() &&
object.object.planes.empty())
1529 object.link_name.c_str());
1530 object_pose_in_link =
robot_state_->getGlobalLinkTransform(link_model).inverse() * obj_in_world->pose_;
1531 shapes = obj_in_world->shapes_;
1532 shape_poses = obj_in_world->shape_poses_;
1533 subframe_poses = obj_in_world->subframe_poses_;
1538 "Attempting to attach object '%s' to link '%s' but no geometry specified "
1539 "and such an object does not exist in the collision world",
1540 object.
object.
id.c_str(),
object.link_name.c_str());
1546 Eigen::Isometry3d header_frame_to_object_pose;
1550 const Eigen::Isometry3d link_to_header_frame =
1551 robot_state_->getGlobalLinkTransform(link_model).inverse() * world_to_header_frame;
1552 object_pose_in_link = link_to_header_frame * header_frame_to_object_pose;
1554 Eigen::Isometry3d subframe_pose;
1555 for (std::size_t i = 0; i <
object.object.subframe_poses.size(); ++i)
1558 std::string
name =
object.object.subframe_names[i];
1559 subframe_poses[
name] = subframe_pose;
1566 object.link_name.c_str(),
object.object.id.c_str());
1570 if (!
object.
object.type.db.empty() || !
object.object.type.key.empty())
1574 if (obj_in_world &&
world_->removeObject(
object.object.id))
1576 if (
object.
object.operation == moveit_msgs::CollisionObject::ADD)
1578 object.
object.
id.c_str());
1581 "You tried to append geometry to an attached object "
1582 "that is actually a world object ('%s'). World geometry is ignored.",
1583 object.
object.
id.c_str());
1587 if (
object.
object.operation == moveit_msgs::CollisionObject::ADD ||
1592 "The robot state already had an object named '%s' attached to link '%s'. "
1593 "The object was replaced.",
1594 object.
object.
id.c_str(),
object.link_name.c_str());
1596 robot_state_->attachBody(
object.
object.
id, object_pose_in_link,
shapes, shape_poses,
object.touch_links,
1597 object.link_name,
object.detach_posture, subframe_poses);
1599 object.link_name.c_str());
1607 object_pose_in_link = ab->
getPose();
1612 trajectory_msgs::JointTrajectory detach_posture =
1613 object.detach_posture.joint_names.empty() ? ab->
getDetachPosture() :
object.detach_posture;
1616 touch_links.insert(std::make_move_iterator(
object.touch_links.begin()),
1617 std::make_move_iterator(
object.touch_links.end()));
1620 robot_state_->attachBody(
object.
object.
id, object_pose_in_link,
shapes, shape_poses, touch_links,
1621 object.link_name, detach_posture, subframe_poses);
1622 ROS_DEBUG_NAMED(
LOGNAME,
"Appended things to object '%s' attached to link '%s'",
object.
object.
id.c_str(),
1623 object.link_name.c_str());
1630 else if (
object.
object.operation == moveit_msgs::CollisionObject::REMOVE)
1633 std::vector<const moveit::core::AttachedBody*> attached_bodies;
1634 if (
object.
object.
id.empty())
1637 object.link_name.empty() ? nullptr :
getRobotModel()->getLinkModel(
object.link_name);
1639 robot_state_->getAttachedBodies(attached_bodies, link_model);
1651 <<
object.link_name <<
", but it is actually attached to "
1653 <<
". Leave the link_name empty or specify the correct link.");
1656 attached_bodies.push_back(body);
1663 const std::string&
name = attached_body->getName();
1664 if (
world_->hasObject(name))
1666 "The collision world already has an object with the same name as the body about to be detached. "
1667 "NOT adding the detached body '%s' to the collision world.",
1668 object.
object.
id.c_str());
1671 const Eigen::Isometry3d& pose = attached_body->getGlobalPose();
1672 world_->addToObject(name, pose, attached_body->getShapes(), attached_body->getShapePoses());
1673 world_->setSubframesOfObject(name, attached_body->getSubframes());
1675 name.c_str(),
object.link_name.c_str());
1680 if (!attached_bodies.empty() ||
object.object.id.empty())
1683 else if (
object.
object.operation == moveit_msgs::CollisionObject::MOVE)
1703 if (
object.operation == moveit_msgs::CollisionObject::ADD ||
object.operation == moveit_msgs::CollisionObject::APPEND)
1707 else if (
object.operation == moveit_msgs::CollisionObject::REMOVE)
1711 else if (
object.operation == moveit_msgs::CollisionObject::MOVE)
1722 Eigen::Translation3d translation(msg.position.x, msg.position.y, msg.position.z);
1723 Eigen::Quaterniond quaternion(msg.orientation.w, msg.orientation.x, msg.orientation.y, msg.orientation.z);
1724 if ((quaternion.x() == 0) && (quaternion.y() == 0) && (quaternion.z() == 0) && (quaternion.w() == 0))
1727 quaternion.setIdentity();
1731 quaternion.normalize();
1733 out = translation * quaternion;
1737 Eigen::Isometry3d& object_pose,
1738 std::vector<shapes::ShapeConstPtr>&
shapes,
1741 if (
object.primitives.size() <
object.primitive_poses.size())
1746 if (
object.meshes.size() <
object.mesh_poses.size())
1751 if (
object.planes.size() <
object.plane_poses.size())
1757 const int num_shapes =
object.primitives.size() +
object.meshes.size() +
object.planes.size();
1758 shapes.reserve(num_shapes);
1759 shape_poses.reserve(num_shapes);
1761 bool switch_object_pose_and_shape_pose =
false;
1765 switch_object_pose_and_shape_pose =
true;
1766 object_pose.setIdentity();
1772 &switch_object_pose_and_shape_pose](
shapes::Shape*
s,
const geometry_msgs::Pose& pose_msg) {
1775 Eigen::Isometry3d pose;
1777 if (!switch_object_pose_and_shape_pose)
1778 shape_poses.emplace_back(std::move(pose));
1781 shape_poses.emplace_back(std::move(object_pose));
1787 auto treat_shape_vectors = [&
append](
const auto& shape_vector,
1788 const auto& shape_poses_vector,
1789 const std::string& shape_type) {
1790 if (shape_vector.size() > shape_poses_vector.size())
1793 <<
" does not match number of poses "
1794 "in collision object message. Assuming identity.");
1795 for (std::size_t i = 0; i < shape_vector.size(); ++i)
1797 if (i >= shape_poses_vector.size())
1800 geometry_msgs::Pose identity;
1801 identity.orientation.w = 1.0;
1809 for (std::size_t i = 0; i < shape_vector.size(); ++i)
1813 treat_shape_vectors(
object.primitives,
object.primitive_poses, std::string(
"primitive_poses"));
1814 treat_shape_vectors(
object.meshes,
object.mesh_poses, std::string(
"meshes"));
1815 treat_shape_vectors(
object.planes,
object.plane_poses, std::string(
"planes"));
1827 if (
object.primitives.empty() &&
object.meshes.empty() &&
object.planes.empty())
1834 if (
object.operation == moveit_msgs::CollisionObject::ADD &&
world_->hasObject(
object.id))
1835 world_->removeObject(
object.
id);
1838 Eigen::Isometry3d header_to_pose_transform;
1839 std::vector<shapes::ShapeConstPtr>
shapes;
1843 const Eigen::Isometry3d object_frame_transform = world_to_object_header_transform * header_to_pose_transform;
1845 world_->addToObject(
object.
id, object_frame_transform,
shapes, shape_poses);
1847 if (!
object.type.key.empty() || !
object.type.db.empty())
1852 Eigen::Isometry3d subframe_pose;
1853 for (std::size_t i = 0; i <
object.subframe_poses.size(); ++i)
1856 std::string
name =
object.subframe_names[i];
1857 subframes[
name] = subframe_pose;
1859 world_->setSubframesOfObject(
object.
id, subframes);
1865 if (
object.
id.empty())
1871 if (!
world_->removeObject(
object.id))
1874 "Tried to remove world object '" <<
object.
id <<
"', but it does not exist in this scene.");
1887 if (
world_->hasObject(
object.id))
1890 if (!
object.primitives.empty() || !
object.meshes.empty() || !
object.planes.empty())
1891 ROS_WARN_NAMED(
LOGNAME,
"Move operation for object '%s' ignores the geometry specified in the message.",
1895 Eigen::Isometry3d header_to_pose_transform;
1899 const Eigen::Isometry3d object_frame_transform = world_to_object_header_transform * header_to_pose_transform;
1900 world_->setObjectPose(
object.
id, object_frame_transform);
1903 if (!
object.primitive_poses.empty() || !
object.mesh_poses.empty() || !
object.plane_poses.empty())
1905 auto world_object =
world_->getObject(
object.
id);
1907 std::size_t shape_size =
object.primitive_poses.size() +
object.mesh_poses.size() +
object.plane_poses.size();
1908 if (shape_size != world_object->shape_poses_.size())
1910 ROS_ERROR_NAMED(
LOGNAME,
"Move operation for object '%s' must have same number of geometry poses. Cannot move.",
1917 for (
const auto& shape_pose :
object.primitive_poses)
1919 shape_poses.emplace_back();
1922 for (
const auto& shape_pose :
object.mesh_poses)
1924 shape_poses.emplace_back();
1927 for (
const auto& shape_pose :
object.plane_poses)
1929 shape_poses.emplace_back();
1933 if (!
world_->moveShapesInObject(
object.id, shape_poses))
1935 ROS_ERROR_NAMED(
LOGNAME,
"Move operation for object '%s' internal world error. Cannot move.",
object.
id.c_str());
1961 const std::string& frame_id)
const
1963 if (!frame_id.empty() && frame_id[0] ==
'/')
1972 const Eigen::Isometry3d& t2 =
getWorld()->getTransform(frame_id, frame_found);
1985 if (!frame_id.empty() && frame_id[0] ==
'/')
1990 if (
getWorld()->knowsTransform(frame_id))
2001 return parent_->hasObjectType(object_id);
2009 ObjectTypeMap::const_iterator it =
object_types_->find(object_id);
2014 return parent_->getObjectType(object_id);
2015 static const object_recognition_msgs::ObjectType EMPTY;
2023 (*object_types_)[object_id] = type;
2036 parent_->getKnownObjectTypes(kc);
2039 kc[it->first] = it->second;
2048 return parent_->hasObjectColor(object_id);
2056 ObjectColorMap::const_iterator it =
object_colors_->find(object_id);
2061 return parent_->getObjectColor(object_id);
2062 static const std_msgs::ColorRGBA EMPTY;
2070 parent_->getKnownObjectColors(kc);
2073 kc[it->first] = it->second;
2078 if (object_id.empty())
2085 (*object_colors_)[object_id] = color;
2148 kinematic_constraints::KinematicConstraintSetPtr ks(
2173 static const moveit_msgs::Constraints EMP_CONSTRAINTS;
2179 static const moveit_msgs::Constraints EMP_CONSTRAINTS;
2184 const std::string& group,
bool verbose)
const
2192 const std::string& group,
bool verbose)
const
2213 const moveit_msgs::RobotTrajectory& trajectory,
const std::string& group,
bool verbose,
2214 std::vector<std::size_t>* invalid_index)
const
2216 static const moveit_msgs::Constraints EMP_CONSTRAINTS;
2217 static const std::vector<moveit_msgs::Constraints> EMP_CONSTRAINTS_VECTOR;
2218 return isPathValid(start_state, trajectory, EMP_CONSTRAINTS, EMP_CONSTRAINTS_VECTOR, group,
verbose, invalid_index);
2222 const moveit_msgs::RobotTrajectory& trajectory,
2223 const moveit_msgs::Constraints& path_constraints,
const std::string& group,
2224 bool verbose, std::vector<std::size_t>* invalid_index)
const
2226 static const std::vector<moveit_msgs::Constraints> EMP_CONSTRAINTS_VECTOR;
2227 return isPathValid(start_state, trajectory, path_constraints, EMP_CONSTRAINTS_VECTOR, group,
verbose, invalid_index);
2231 const moveit_msgs::RobotTrajectory& trajectory,
2232 const moveit_msgs::Constraints& path_constraints,
2233 const moveit_msgs::Constraints& goal_constraints,
const std::string& group,
2234 bool verbose, std::vector<std::size_t>* invalid_index)
const
2236 std::vector<moveit_msgs::Constraints> goal_constraints_vector(1, goal_constraints);
2237 return isPathValid(start_state, trajectory, path_constraints, goal_constraints_vector, group,
verbose, invalid_index);
2241 const moveit_msgs::RobotTrajectory& trajectory,
2242 const moveit_msgs::Constraints& path_constraints,
2243 const std::vector<moveit_msgs::Constraints>& goal_constraints,
const std::string& group,
2244 bool verbose, std::vector<std::size_t>* invalid_index)
const
2249 t.setRobotTrajectoryMsg(
start, trajectory);
2254 const moveit_msgs::Constraints& path_constraints,
2255 const std::vector<moveit_msgs::Constraints>& goal_constraints,
const std::string& group,
2256 bool verbose, std::vector<std::size_t>* invalid_index)
const
2260 invalid_index->clear();
2264 for (std::size_t i = 0; i < n_wp; ++i)
2268 bool this_state_valid =
true;
2270 this_state_valid =
false;
2272 this_state_valid =
false;
2274 this_state_valid =
false;
2276 if (!this_state_valid)
2279 invalid_index->push_back(i);
2286 if (i + 1 == n_wp && !goal_constraints.empty())
2289 for (
const moveit_msgs::Constraints& goal_constraint : goal_constraints)
2302 invalid_index->push_back(i);
2311 const moveit_msgs::Constraints& path_constraints,
2312 const moveit_msgs::Constraints& goal_constraints,
const std::string& group,
2313 bool verbose, std::vector<std::size_t>* invalid_index)
const
2315 std::vector<moveit_msgs::Constraints> goal_constraints_vector(1, goal_constraints);
2316 return isPathValid(trajectory, path_constraints, goal_constraints_vector, group, verbose, invalid_index);
2320 const moveit_msgs::Constraints& path_constraints,
const std::string& group,
2321 bool verbose, std::vector<std::size_t>* invalid_index)
const
2323 static const std::vector<moveit_msgs::Constraints> EMP_CONSTRAINTS_VECTOR;
2324 return isPathValid(trajectory, path_constraints, EMP_CONSTRAINTS_VECTOR, group, verbose, invalid_index);
2328 bool verbose, std::vector<std::size_t>* invalid_index)
const
2330 static const moveit_msgs::Constraints EMP_CONSTRAINTS;
2331 static const std::vector<moveit_msgs::Constraints> EMP_CONSTRAINTS_VECTOR;
2332 return isPathValid(trajectory, EMP_CONSTRAINTS, EMP_CONSTRAINTS_VECTOR, group, verbose, invalid_index);
2336 std::set<collision_detection::CostSource>& costs,
double overlap_fraction)
const
2338 getCostSources(trajectory, max_costs, std::string(), costs, overlap_fraction);
2342 const std::string& group_name, std::set<collision_detection::CostSource>& costs,
2343 double overlap_fraction)
const
2349 std::set<collision_detection::CostSource> cs;
2350 std::set<collision_detection::CostSource> cs_start;
2352 for (std::size_t i = 0; i < n_wp; ++i)
2361 if (cs.size() <= max_costs)
2367 for (std::set<collision_detection::CostSource>::iterator it = cs.begin(); i < max_costs; ++it, ++i)
2376 std::set<collision_detection::CostSource>& costs)
const
2382 const std::string& group_name,
2383 std::set<collision_detection::CostSource>& costs)
const
2396 const std::vector<std::string>& objects =
getWorld()->getObjectIds();
2397 std::vector<const moveit::core::AttachedBody*> attached_bodies;
2401 out <<
"-----------------------------------------\n";
2402 out <<
"PlanningScene Known Objects:\n";
2403 out <<
" - Collision World Objects:\n ";
2404 for (
const std::string&
object : objects)
2406 out <<
"\t- " <<
object <<
"\n";
2409 out <<
" - Attached Bodies:\n";
2412 out <<
"\t- " << attached_body->getName() <<
"\n";
2414 out <<
"-----------------------------------------\n";