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);
446 if (!scene->getCurrentState().hasAttachedBody(it.first))
448 scene->getAllowedCollisionMatrixNonConst().removeEntry(it.first);
454 scene->world_->removeObject(
obj.id_);
455 scene->world_->addToObject(
obj.id_,
obj.pose_,
obj.shapes_,
obj.shape_poses_);
461 scene->world_->setSubframesOfObject(
obj.id_,
obj.subframe_poses_);
540 const std::string& group_name)
const
566 for (collision_detection::CollisionResult::ContactMap::const_iterator it = contacts.begin(); it != contacts.end();
619 acm_ = std::make_shared<collision_detection::AllowedCollisionMatrix>(
parent_->getAllowedCollisionMatrix());
646 scene_msg.name =
name_;
648 scene_msg.is_diff =
true;
653 scene_msg.fixed_frame_transforms.clear();
658 scene_msg.robot_state = moveit_msgs::RobotState();
659 scene_msg.robot_state.is_diff =
true;
662 acm_->getMessage(scene_msg.allowed_collision_matrix);
664 scene_msg.allowed_collision_matrix = moveit_msgs::AllowedCollisionMatrix();
669 scene_msg.object_colors.clear();
676 scene_msg.object_colors[i].id = it->first;
677 scene_msg.object_colors[i].color = it->second;
681 scene_msg.world.collision_objects.clear();
682 scene_msg.world.octomap = octomap_msgs::OctomapWithPose();
686 bool do_omap =
false;
687 for (
const std::pair<const std::string, collision_detection::World::Action>& it : *
world_diff_)
692 scene_msg.world.octomap.octomap.id =
"cleared";
699 if (!std::count_if(scene_msg.robot_state.attached_collision_objects.cbegin(),
700 scene_msg.robot_state.attached_collision_objects.cend(),
701 [&it](
const moveit_msgs::AttachedCollisionObject& aco) {
702 return aco.object.id == it.first &&
703 aco.object.operation == moveit_msgs::CollisionObject::ADD;
706 moveit_msgs::CollisionObject co;
709 co.operation = moveit_msgs::CollisionObject::REMOVE;
710 scene_msg.world.collision_objects.push_back(co);
715 scene_msg.world.collision_objects.emplace_back();
726 for (
const auto& collision_object : scene_msg.world.collision_objects)
728 if (
parent_ &&
parent_->getCurrentState().hasAttachedBody(collision_object.id))
730 moveit_msgs::AttachedCollisionObject aco;
731 aco.object.id = collision_object.id;
732 aco.object.operation = moveit_msgs::CollisionObject::REMOVE;
733 scene_msg.robot_state.attached_collision_objects.push_back(aco);
740 class ShapeVisitorAddToCollisionObject :
public boost::static_visitor<void>
743 ShapeVisitorAddToCollisionObject(moveit_msgs::CollisionObject* obj) :
boost::static_visitor<void>(),
obj_(
obj)
747 void setPoseMessage(
const geometry_msgs::Pose* pose)
752 void operator()(
const shape_msgs::Plane& shape_msg)
const
754 obj_->planes.push_back(shape_msg);
758 void operator()(
const shape_msgs::Mesh& shape_msg)
const
760 obj_->meshes.push_back(shape_msg);
764 void operator()(
const shape_msgs::SolidPrimitive& shape_msg)
const
766 obj_->primitives.push_back(shape_msg);
771 moveit_msgs::CollisionObject*
obj_;
772 const geometry_msgs::Pose*
pose_;
783 collision_obj.id = ns;
784 collision_obj.operation = moveit_msgs::CollisionObject::ADD;
785 ShapeVisitorAddToCollisionObject sv(&collision_obj);
786 for (std::size_t j = 0; j <
obj->shapes_.size(); ++j)
792 sv.setPoseMessage(&p);
793 boost::apply_visitor(sv, sm);
797 if (!collision_obj.primitives.empty() || !collision_obj.meshes.empty() || !collision_obj.planes.empty())
802 for (
const auto& frame_pair :
obj->subframe_poses_)
804 collision_obj.subframe_names.push_back(frame_pair.first);
805 geometry_msgs::Pose p;
807 collision_obj.subframe_poses.push_back(p);
815 collision_objs.clear();
816 const std::vector<std::string>& ids =
world_->getObjectIds();
817 for (
const std::string&
id : ids)
820 collision_objs.emplace_back();
826 const std::string& ns)
const
828 std::vector<moveit_msgs::AttachedCollisionObject> attached_collision_objs;
830 for (moveit_msgs::AttachedCollisionObject& it : attached_collision_objs)
832 if (it.object.id == ns)
834 attached_collision_obj = it;
842 std::vector<moveit_msgs::AttachedCollisionObject>& attached_collision_objs)
const
844 std::vector<const moveit::core::AttachedBody*> attached_bodies;
852 octomap.octomap = octomap_msgs::Octomap();
857 if (map->shapes_.size() == 1)
864 ROS_ERROR_NAMED(
LOGNAME,
"Unexpected number of shapes in octomap collision object. Not including '%s' object",
872 object_colors.clear();
877 object_colors.resize(cmap.size());
878 for (ObjectColorMap::const_iterator it = cmap.begin(); it != cmap.end(); ++it, ++i)
880 object_colors[i].id = it->first;
881 object_colors[i].color = it->second;
887 scene_msg.name =
name_;
888 scene_msg.is_diff =
false;
907 const moveit_msgs::PlanningSceneComponents& comp)
const
909 scene_msg.is_diff =
false;
910 if (comp.components & moveit_msgs::PlanningSceneComponents::SCENE_SETTINGS)
912 scene_msg.name =
name_;
916 if (comp.components & moveit_msgs::PlanningSceneComponents::TRANSFORMS)
919 if (comp.components & moveit_msgs::PlanningSceneComponents::ROBOT_STATE_ATTACHED_OBJECTS)
922 for (moveit_msgs::AttachedCollisionObject& attached_collision_object :
923 scene_msg.robot_state.attached_collision_objects)
927 attached_collision_object.object.type =
getObjectType(attached_collision_object.object.id);
931 else if (comp.components & moveit_msgs::PlanningSceneComponents::ROBOT_STATE)
936 if (comp.components & moveit_msgs::PlanningSceneComponents::ALLOWED_COLLISION_MATRIX)
939 if (comp.components & moveit_msgs::PlanningSceneComponents::LINK_PADDING_AND_SCALING)
945 if (comp.components & moveit_msgs::PlanningSceneComponents::OBJECT_COLORS)
949 if (comp.components & moveit_msgs::PlanningSceneComponents::WORLD_OBJECT_GEOMETRY)
951 else if (comp.components & moveit_msgs::PlanningSceneComponents::WORLD_OBJECT_NAMES)
953 const std::vector<std::string>& ids =
world_->getObjectIds();
954 scene_msg.world.collision_objects.clear();
955 scene_msg.world.collision_objects.reserve(ids.size());
956 for (
const std::string&
id : ids)
959 moveit_msgs::CollisionObject co;
963 scene_msg.world.collision_objects.push_back(co);
968 if (comp.components & moveit_msgs::PlanningSceneComponents::OCTOMAP)
974 out <<
name_ << std::endl;
975 const std::vector<std::string>& ids =
world_->getObjectIds();
976 for (
const std::string&
id : ids)
982 out <<
"* " <<
id << std::endl;
987 out <<
obj->shapes_.size() << std::endl;
988 for (std::size_t j = 0; j <
obj->shapes_.size(); ++j)
996 out << c.r <<
" " << c.g <<
" " << c.b <<
" " << c.a << std::endl;
999 out <<
"0 0 0 0" << std::endl;
1003 out <<
obj->subframe_poses_.size() << std::endl;
1004 for (
auto& pose_pair :
obj->subframe_poses_)
1006 out << pose_pair.first << std::endl;
1011 out <<
"." << std::endl;
1021 if (!in.good() || in.eof())
1027 std::getline(in,
name_);
1030 auto pos = in.tellg();
1034 std::getline(in, line);
1035 }
while (in.good() && !in.eof() && (line.empty() || line[0] !=
'*'));
1036 std::getline(in, line);
1037 boost::algorithm::trim(line);
1040 bool uses_new_scene_format = line.find(
' ') != std::string::npos;
1043 Eigen::Isometry3d pose;
1048 if (!in.good() || in.eof())
1055 std::string object_id;
1056 std::getline(in, object_id);
1057 if (!in.good() || in.eof())
1062 boost::algorithm::trim(object_id);
1071 Eigen::Isometry3d object_pose = offset * pose;
1074 unsigned int shape_count;
1077 world_->removeObject(object_id);
1078 for (std::size_t i = 0; i < shape_count && in.good() && !in.eof(); ++i)
1092 if (!(in >> r >> g >> b >> a))
1099 world_->addToObject(object_id, shape, pose);
1100 if (r > 0.0f || g > 0.0f || b > 0.0f || a > 0.0f)
1102 std_msgs::ColorRGBA color;
1113 world_->setObjectPose(object_id, object_pose);
1116 if (uses_new_scene_format)
1119 unsigned int subframe_count;
1120 in >> subframe_count;
1121 for (std::size_t i = 0; i < subframe_count && in.good() && !in.eof(); ++i)
1123 std::string subframe_name;
1124 in >> subframe_name;
1130 subframes[subframe_name] = pose;
1132 world_->setSubframesOfObject(object_id, subframes);
1135 else if (marker ==
".")
1150 double x,
y,
z, rx, ry, rz, rw;
1151 if (!(in >> x >> y >> z))
1156 if (!(in >> rx >> ry >> rz >> rw))
1161 pose = Eigen::Translation3d(x, y, z) * Eigen::Quaterniond(rw, rx, ry, rz);
1167 out << pose.translation().x() <<
" " << pose.translation().y() <<
" " << pose.translation().z() << std::endl;
1168 Eigen::Quaterniond
r(pose.linear());
1169 out <<
r.x() <<
" " <<
r.y() <<
" " <<
r.z() <<
" " <<
r.w() << std::endl;
1176 moveit_msgs::RobotState state_no_attached(state);
1177 state_no_attached.attached_collision_objects.clear();
1191 for (std::size_t i = 0; i < state.attached_collision_objects.size(); ++i)
1193 if (!state.is_diff && state.attached_collision_objects[i].object.operation != moveit_msgs::CollisionObject::ADD)
1196 "The specified RobotState is not marked as is_diff. "
1197 "The request to modify the object '%s' is not supported. Object is ignored.",
1198 state.attached_collision_objects[i].object.id.c_str());
1229 acm_ = std::make_shared<collision_detection::AllowedCollisionMatrix>(
parent_->getAllowedCollisionMatrix());
1231 for (std::pair<const std::string, CollisionDetectorPtr>& it :
collision_)
1233 it.second->parent_.reset();
1240 parent_->getKnownObjectColors(kc);
1246 parent_->getKnownObjectColors(kc);
1247 for (ObjectColorMap::const_iterator it = kc.begin(); it != kc.end(); ++it)
1249 (*object_colors_)[it->first] = it->second;
1255 parent_->getKnownObjectTypes(kc);
1261 parent_->getKnownObjectTypes(kc);
1262 for (ObjectTypeMap::const_iterator it = kc.begin(); it != kc.end(); ++it)
1264 (*object_types_)[it->first] = it->second;
1275 if (!scene_msg.name.empty())
1276 name_ = scene_msg.name;
1278 if (!scene_msg.robot_model_name.empty() && scene_msg.robot_model_name !=
getRobotModel()->
getName())
1284 if (!scene_msg.fixed_frame_transforms.empty())
1292 if (!scene_msg.robot_state.multi_dof_joint_state.joint_names.empty() ||
1293 !scene_msg.robot_state.joint_state.name.empty() || !scene_msg.robot_state.attached_collision_objects.empty())
1297 if (!scene_msg.allowed_collision_matrix.entry_names.empty())
1298 acm_ = std::make_shared<collision_detection::AllowedCollisionMatrix>(scene_msg.allowed_collision_matrix);
1300 if (!scene_msg.link_padding.empty() || !scene_msg.link_scale.empty())
1302 for (std::pair<const std::string, CollisionDetectorPtr>& it :
collision_)
1304 it.second->cenv_->setPadding(scene_msg.link_padding);
1305 it.second->cenv_->setScale(scene_msg.link_scale);
1310 for (
const moveit_msgs::ObjectColor& object_color : scene_msg.object_colors)
1314 for (
const moveit_msgs::CollisionObject& collision_object : scene_msg.world.collision_objects)
1318 if (!scene_msg.world.octomap.octomap.id.empty())
1326 assert(scene_msg.is_diff ==
false);
1328 name_ = scene_msg.name;
1330 if (!scene_msg.robot_model_name.empty() && scene_msg.robot_model_name !=
getRobotModel()->
getName())
1340 acm_ = std::make_shared<collision_detection::AllowedCollisionMatrix>(scene_msg.allowed_collision_matrix);
1341 for (std::pair<const std::string, CollisionDetectorPtr>& it :
collision_)
1343 it.second->cenv_->setPadding(scene_msg.link_padding);
1344 it.second->cenv_->setScale(scene_msg.link_scale);
1347 for (
const moveit_msgs::ObjectColor& object_color : scene_msg.object_colors)
1356 for (
const moveit_msgs::CollisionObject& collision_object : world.collision_objects)
1364 if (scene_msg.is_diff)
1372 std::shared_ptr<collision_detection::OccMapTree> om =
1373 std::make_shared<collision_detection::OccMapTree>(map.resolution);
1380 std::stringstream datastream;
1381 if (!map.data.empty())
1383 datastream.write((
const char*)&map.data[0], map.data.size());
1384 om->readData(datastream);
1395 if (map.data.empty())
1398 if (map.id !=
"OcTree")
1400 ROS_ERROR_NAMED(
LOGNAME,
"Received octomap is of type '%s' but type 'OcTree' is expected.", map.id.c_str());
1404 std::shared_ptr<collision_detection::OccMapTree> om =
createOctomap(map);
1405 if (!map.header.frame_id.empty())
1418 const std::vector<std::string>& object_ids =
world_->getObjectIds();
1419 for (
const std::string& object_id : object_ids)
1434 if (map.octomap.data.empty())
1437 if (map.octomap.id !=
"OcTree")
1439 ROS_ERROR_NAMED(
LOGNAME,
"Received octomap is of type '%s' but type 'OcTree' is expected.", map.octomap.id.c_str());
1443 std::shared_ptr<collision_detection::OccMapTree> om =
createOctomap(map.octomap);
1446 Eigen::Isometry3d p;
1457 if (map->shapes_.size() == 1)
1464 if (map->shape_poses_[0].isApprox(
t, std::numeric_limits<double>::epsilon() * 100.0))
1487 if (
object.
object.operation == moveit_msgs::CollisionObject::ADD && !
getRobotModel()->hasLinkModel(
object.link_name))
1489 ROS_ERROR_NAMED(
LOGNAME,
"Unable to attach a body to link '%s' (link not found)",
object.link_name.c_str());
1511 if (
object.
object.operation == moveit_msgs::CollisionObject::ADD ||
1512 object.
object.operation == moveit_msgs::CollisionObject::APPEND)
1518 Eigen::Isometry3d object_pose_in_link;
1519 std::vector<shapes::ShapeConstPtr>
shapes;
1527 if (
object.
object.operation == moveit_msgs::CollisionObject::ADD &&
object.
object.primitives.empty() &&
1528 object.object.meshes.empty() &&
object.object.planes.empty())
1533 object.link_name.c_str());
1534 object_pose_in_link =
robot_state_->getGlobalLinkTransform(link_model).inverse() * obj_in_world->pose_;
1535 shapes = obj_in_world->shapes_;
1536 shape_poses = obj_in_world->shape_poses_;
1537 subframe_poses = obj_in_world->subframe_poses_;
1542 "Attempting to attach object '%s' to link '%s' but no geometry specified "
1543 "and such an object does not exist in the collision world",
1544 object.
object.
id.c_str(),
object.link_name.c_str());
1550 Eigen::Isometry3d header_frame_to_object_pose;
1554 const Eigen::Isometry3d link_to_header_frame =
1555 robot_state_->getGlobalLinkTransform(link_model).inverse() * world_to_header_frame;
1556 object_pose_in_link = link_to_header_frame * header_frame_to_object_pose;
1558 Eigen::Isometry3d subframe_pose;
1559 for (std::size_t i = 0; i <
object.object.subframe_poses.size(); ++i)
1562 std::string
name =
object.object.subframe_names[i];
1563 subframe_poses[
name] = subframe_pose;
1570 object.link_name.c_str(),
object.object.id.c_str());
1574 if (!
object.
object.type.db.empty() || !
object.object.type.key.empty())
1578 if (obj_in_world &&
world_->removeObject(
object.object.id))
1580 if (
object.
object.operation == moveit_msgs::CollisionObject::ADD)
1582 object.
object.
id.c_str());
1585 "You tried to append geometry to an attached object "
1586 "that is actually a world object ('%s'). World geometry is ignored.",
1587 object.
object.
id.c_str());
1591 if (
object.
object.operation == moveit_msgs::CollisionObject::ADD ||
1596 "The robot state already had an object named '%s' attached to link '%s'. "
1597 "The object was replaced.",
1598 object.
object.
id.c_str(),
object.link_name.c_str());
1600 robot_state_->attachBody(
object.
object.
id, object_pose_in_link,
shapes, shape_poses,
object.touch_links,
1601 object.link_name,
object.detach_posture, subframe_poses);
1603 object.link_name.c_str());
1611 object_pose_in_link = ab->
getPose();
1616 trajectory_msgs::JointTrajectory detach_posture =
1617 object.detach_posture.joint_names.empty() ? ab->
getDetachPosture() :
object.detach_posture;
1620 touch_links.insert(std::make_move_iterator(
object.touch_links.begin()),
1621 std::make_move_iterator(
object.touch_links.end()));
1624 robot_state_->attachBody(
object.
object.
id, object_pose_in_link,
shapes, shape_poses, touch_links,
1625 object.link_name, detach_posture, subframe_poses);
1626 ROS_DEBUG_NAMED(
LOGNAME,
"Appended things to object '%s' attached to link '%s'",
object.
object.
id.c_str(),
1627 object.link_name.c_str());
1634 else if (
object.
object.operation == moveit_msgs::CollisionObject::REMOVE)
1637 std::vector<const moveit::core::AttachedBody*> attached_bodies;
1638 if (
object.
object.
id.empty())
1641 object.link_name.empty() ? nullptr :
getRobotModel()->getLinkModel(
object.link_name);
1643 robot_state_->getAttachedBodies(attached_bodies, link_model);
1655 <<
object.link_name <<
", but it is actually attached to "
1657 <<
". Leave the link_name empty or specify the correct link.");
1660 attached_bodies.push_back(body);
1667 const std::string&
name = attached_body->getName();
1668 if (
world_->hasObject(name))
1670 "The collision world already has an object with the same name as the body about to be detached. "
1671 "NOT adding the detached body '%s' to the collision world.",
1672 object.
object.
id.c_str());
1675 const Eigen::Isometry3d& pose = attached_body->getGlobalPose();
1676 world_->addToObject(name, pose, attached_body->getShapes(), attached_body->getShapePoses());
1677 world_->setSubframesOfObject(name, attached_body->getSubframes());
1679 name.c_str(),
object.link_name.c_str());
1684 if (!attached_bodies.empty() ||
object.object.id.empty())
1687 else if (
object.
object.operation == moveit_msgs::CollisionObject::MOVE)
1707 if (
object.operation == moveit_msgs::CollisionObject::ADD ||
object.operation == moveit_msgs::CollisionObject::APPEND)
1711 else if (
object.operation == moveit_msgs::CollisionObject::REMOVE)
1715 else if (
object.operation == moveit_msgs::CollisionObject::MOVE)
1726 Eigen::Translation3d translation(msg.position.x, msg.position.y, msg.position.z);
1727 Eigen::Quaterniond quaternion(msg.orientation.w, msg.orientation.x, msg.orientation.y, msg.orientation.z);
1728 if ((quaternion.x() == 0) && (quaternion.y() == 0) && (quaternion.z() == 0) && (quaternion.w() == 0))
1731 quaternion.setIdentity();
1735 quaternion.normalize();
1737 out = translation * quaternion;
1741 Eigen::Isometry3d& object_pose,
1742 std::vector<shapes::ShapeConstPtr>&
shapes,
1745 if (
object.primitives.size() <
object.primitive_poses.size())
1750 if (
object.meshes.size() <
object.mesh_poses.size())
1755 if (
object.planes.size() <
object.plane_poses.size())
1761 const int num_shapes =
object.primitives.size() +
object.meshes.size() +
object.planes.size();
1762 shapes.reserve(num_shapes);
1763 shape_poses.reserve(num_shapes);
1765 bool switch_object_pose_and_shape_pose =
false;
1769 switch_object_pose_and_shape_pose =
true;
1770 object_pose.setIdentity();
1776 &switch_object_pose_and_shape_pose](
shapes::Shape*
s,
const geometry_msgs::Pose& pose_msg) {
1779 Eigen::Isometry3d pose;
1781 if (!switch_object_pose_and_shape_pose)
1782 shape_poses.emplace_back(std::move(pose));
1785 shape_poses.emplace_back(std::move(object_pose));
1791 auto treat_shape_vectors = [&
append](
const auto& shape_vector,
1792 const auto& shape_poses_vector,
1793 const std::string& shape_type) {
1794 if (shape_vector.size() > shape_poses_vector.size())
1797 <<
" does not match number of poses "
1798 "in collision object message. Assuming identity.");
1799 for (std::size_t i = 0; i < shape_vector.size(); ++i)
1801 if (i >= shape_poses_vector.size())
1804 geometry_msgs::Pose identity;
1805 identity.orientation.w = 1.0;
1813 for (std::size_t i = 0; i < shape_vector.size(); ++i)
1817 treat_shape_vectors(
object.primitives,
object.primitive_poses, std::string(
"primitive_poses"));
1818 treat_shape_vectors(
object.meshes,
object.mesh_poses, std::string(
"meshes"));
1819 treat_shape_vectors(
object.planes,
object.plane_poses, std::string(
"planes"));
1831 if (
object.primitives.empty() &&
object.meshes.empty() &&
object.planes.empty())
1838 if (
object.operation == moveit_msgs::CollisionObject::ADD &&
world_->hasObject(
object.id))
1839 world_->removeObject(
object.
id);
1842 Eigen::Isometry3d header_to_pose_transform;
1843 std::vector<shapes::ShapeConstPtr>
shapes;
1847 const Eigen::Isometry3d object_frame_transform = world_to_object_header_transform * header_to_pose_transform;
1849 world_->addToObject(
object.
id, object_frame_transform,
shapes, shape_poses);
1851 if (!
object.type.key.empty() || !
object.type.db.empty())
1856 Eigen::Isometry3d subframe_pose;
1857 for (std::size_t i = 0; i <
object.subframe_poses.size(); ++i)
1860 std::string
name =
object.subframe_names[i];
1861 subframes[
name] = subframe_pose;
1863 world_->setSubframesOfObject(
object.
id, subframes);
1869 if (
object.
id.empty())
1875 if (!
world_->removeObject(
object.id))
1878 "Tried to remove world object '" <<
object.
id <<
"', but it does not exist in this scene.");
1891 if (
world_->hasObject(
object.id))
1894 if (!
object.primitives.empty() || !
object.meshes.empty() || !
object.planes.empty())
1895 ROS_WARN_NAMED(
LOGNAME,
"Move operation for object '%s' ignores the geometry specified in the message.",
1899 Eigen::Isometry3d header_to_pose_transform;
1903 const Eigen::Isometry3d object_frame_transform = world_to_object_header_transform * header_to_pose_transform;
1904 world_->setObjectPose(
object.
id, object_frame_transform);
1907 if (!
object.primitive_poses.empty() || !
object.mesh_poses.empty() || !
object.plane_poses.empty())
1909 auto world_object =
world_->getObject(
object.
id);
1911 std::size_t shape_size =
object.primitive_poses.size() +
object.mesh_poses.size() +
object.plane_poses.size();
1912 if (shape_size != world_object->shape_poses_.size())
1914 ROS_ERROR_NAMED(
LOGNAME,
"Move operation for object '%s' must have same number of geometry poses. Cannot move.",
1921 for (
const auto& shape_pose :
object.primitive_poses)
1923 shape_poses.emplace_back();
1926 for (
const auto& shape_pose :
object.mesh_poses)
1928 shape_poses.emplace_back();
1931 for (
const auto& shape_pose :
object.plane_poses)
1933 shape_poses.emplace_back();
1937 if (!
world_->moveShapesInObject(
object.id, shape_poses))
1939 ROS_ERROR_NAMED(
LOGNAME,
"Move operation for object '%s' internal world error. Cannot move.",
object.
id.c_str());
1965 const std::string& frame_id)
const
1967 if (!frame_id.empty() && frame_id[0] ==
'/')
1976 const Eigen::Isometry3d& t2 =
getWorld()->getTransform(frame_id, frame_found);
1989 if (!frame_id.empty() && frame_id[0] ==
'/')
1994 if (
getWorld()->knowsTransform(frame_id))
2005 return parent_->hasObjectType(object_id);
2013 ObjectTypeMap::const_iterator it =
object_types_->find(object_id);
2018 return parent_->getObjectType(object_id);
2019 static const object_recognition_msgs::ObjectType EMPTY;
2027 (*object_types_)[object_id] = type;
2040 parent_->getKnownObjectTypes(kc);
2043 kc[it->first] = it->second;
2052 return parent_->hasObjectColor(object_id);
2060 ObjectColorMap::const_iterator it =
object_colors_->find(object_id);
2065 return parent_->getObjectColor(object_id);
2066 static const std_msgs::ColorRGBA EMPTY;
2074 parent_->getKnownObjectColors(kc);
2077 kc[it->first] = it->second;
2082 if (object_id.empty())
2089 (*object_colors_)[object_id] = color;
2152 kinematic_constraints::KinematicConstraintSetPtr ks(
2177 static const moveit_msgs::Constraints EMP_CONSTRAINTS;
2183 static const moveit_msgs::Constraints EMP_CONSTRAINTS;
2188 const std::string& group,
bool verbose)
const
2196 const std::string& group,
bool verbose)
const
2217 const moveit_msgs::RobotTrajectory& trajectory,
const std::string& group,
bool verbose,
2218 std::vector<std::size_t>* invalid_index)
const
2220 static const moveit_msgs::Constraints EMP_CONSTRAINTS;
2221 static const std::vector<moveit_msgs::Constraints> EMP_CONSTRAINTS_VECTOR;
2222 return isPathValid(start_state, trajectory, EMP_CONSTRAINTS, EMP_CONSTRAINTS_VECTOR, group,
verbose, invalid_index);
2226 const moveit_msgs::RobotTrajectory& trajectory,
2227 const moveit_msgs::Constraints& path_constraints,
const std::string& group,
2228 bool verbose, std::vector<std::size_t>* invalid_index)
const
2230 static const std::vector<moveit_msgs::Constraints> EMP_CONSTRAINTS_VECTOR;
2231 return isPathValid(start_state, trajectory, path_constraints, EMP_CONSTRAINTS_VECTOR, group,
verbose, invalid_index);
2235 const moveit_msgs::RobotTrajectory& trajectory,
2236 const moveit_msgs::Constraints& path_constraints,
2237 const moveit_msgs::Constraints& goal_constraints,
const std::string& group,
2238 bool verbose, std::vector<std::size_t>* invalid_index)
const
2240 std::vector<moveit_msgs::Constraints> goal_constraints_vector(1, goal_constraints);
2241 return isPathValid(start_state, trajectory, path_constraints, goal_constraints_vector, group,
verbose, invalid_index);
2245 const moveit_msgs::RobotTrajectory& trajectory,
2246 const moveit_msgs::Constraints& path_constraints,
2247 const std::vector<moveit_msgs::Constraints>& goal_constraints,
const std::string& group,
2248 bool verbose, std::vector<std::size_t>* invalid_index)
const
2253 t.setRobotTrajectoryMsg(
start, trajectory);
2258 const moveit_msgs::Constraints& path_constraints,
2259 const std::vector<moveit_msgs::Constraints>& goal_constraints,
const std::string& group,
2260 bool verbose, std::vector<std::size_t>* invalid_index)
const
2264 invalid_index->clear();
2268 for (std::size_t i = 0; i < n_wp; ++i)
2272 bool this_state_valid =
true;
2274 this_state_valid =
false;
2276 this_state_valid =
false;
2278 this_state_valid =
false;
2280 if (!this_state_valid)
2283 invalid_index->push_back(i);
2290 if (i + 1 == n_wp && !goal_constraints.empty())
2293 for (
const moveit_msgs::Constraints& goal_constraint : goal_constraints)
2306 invalid_index->push_back(i);
2315 const moveit_msgs::Constraints& path_constraints,
2316 const moveit_msgs::Constraints& goal_constraints,
const std::string& group,
2317 bool verbose, std::vector<std::size_t>* invalid_index)
const
2319 std::vector<moveit_msgs::Constraints> goal_constraints_vector(1, goal_constraints);
2320 return isPathValid(trajectory, path_constraints, goal_constraints_vector, group, verbose, invalid_index);
2324 const moveit_msgs::Constraints& path_constraints,
const std::string& group,
2325 bool verbose, std::vector<std::size_t>* invalid_index)
const
2327 static const std::vector<moveit_msgs::Constraints> EMP_CONSTRAINTS_VECTOR;
2328 return isPathValid(trajectory, path_constraints, EMP_CONSTRAINTS_VECTOR, group, verbose, invalid_index);
2332 bool verbose, std::vector<std::size_t>* invalid_index)
const
2334 static const moveit_msgs::Constraints EMP_CONSTRAINTS;
2335 static const std::vector<moveit_msgs::Constraints> EMP_CONSTRAINTS_VECTOR;
2336 return isPathValid(trajectory, EMP_CONSTRAINTS, EMP_CONSTRAINTS_VECTOR, group, verbose, invalid_index);
2340 std::set<collision_detection::CostSource>& costs,
double overlap_fraction)
const
2342 getCostSources(trajectory, max_costs, std::string(), costs, overlap_fraction);
2346 const std::string& group_name, std::set<collision_detection::CostSource>& costs,
2347 double overlap_fraction)
const
2353 std::set<collision_detection::CostSource> cs;
2354 std::set<collision_detection::CostSource> cs_start;
2356 for (std::size_t i = 0; i < n_wp; ++i)
2365 if (cs.size() <= max_costs)
2371 for (std::set<collision_detection::CostSource>::iterator it = cs.begin(); i < max_costs; ++it, ++i)
2380 std::set<collision_detection::CostSource>& costs)
const
2386 const std::string& group_name,
2387 std::set<collision_detection::CostSource>& costs)
const
2400 const std::vector<std::string>& objects =
getWorld()->getObjectIds();
2401 std::vector<const moveit::core::AttachedBody*> attached_bodies;
2405 out <<
"-----------------------------------------\n";
2406 out <<
"PlanningScene Known Objects:\n";
2407 out <<
" - Collision World Objects:\n ";
2408 for (
const std::string&
object : objects)
2410 out <<
"\t- " <<
object <<
"\n";
2413 out <<
" - Attached Bodies:\n";
2416 out <<
"\t- " << attached_body->getName() <<
"\n";
2418 out <<
"-----------------------------------------\n";