37#include <gtest/gtest.h>
42#include <urdf_parser/urdf_parser.h>
46#include <tf2_eigen/tf2_eigen.hpp>
47#include <octomap_msgs/conversions.h>
48#include <octomap/octomap.h>
54TEST(PlanningScene, TestOneShapeObjectPose)
57 srdf::ModelSharedPtr srdf_model = std::make_shared<srdf::Model>();
60 const std::string object_name =
"object";
61 const Eigen::Isometry3d expected_transfrom = Eigen::Isometry3d::Identity() * Eigen::Translation3d(0.5, -0.25, 0.0);
63 moveit_msgs::msg::CollisionObject co;
64 co.header.frame_id =
"base_footprint";
66 co.operation = moveit_msgs::msg::CollisionObject::ADD;
67 co.primitives.push_back([] {
68 shape_msgs::msg::SolidPrimitive primitive;
69 primitive.type = shape_msgs::msg::SolidPrimitive::CYLINDER;
70 primitive.dimensions = { 0.25, 0.02 };
73 co.primitive_poses.push_back(tf2::toMsg(expected_transfrom));
80TEST(PlanningScene, LoadRestore)
83 srdf::ModelSharedPtr srdf_model = std::make_shared<srdf::Model>();
85 moveit_msgs::msg::PlanningScene ps_msg;
87 EXPECT_EQ(ps.
getName(), ps_msg.name);
88 EXPECT_EQ(ps.
getRobotModel()->getName(), ps_msg.robot_model_name);
90 EXPECT_EQ(ps.
getName(), ps_msg.name);
91 EXPECT_EQ(ps.
getRobotModel()->getName(), ps_msg.robot_model_name);
94TEST(PlanningScene, LoadOctomap)
97 srdf::ModelSharedPtr srdf_model(
new srdf::Model());
101 octomap_msgs::msg::OctomapWithPose msg;
103 EXPECT_TRUE(msg.octomap.id.empty());
104 EXPECT_TRUE(msg.octomap.data.empty());
109 octomap::point3d origin(0, 0, 0);
110 octomap::point3d end(0, 1, 2);
111 octomap.insertRay(origin, end);
114 moveit_msgs::msg::PlanningScene msg;
116 octomap_msgs::fullMapToMsg(
octomap, msg.world.octomap.octomap);
120 octomap_msgs::msg::OctomapWithPose octomap_msg;
122 EXPECT_EQ(octomap_msg.octomap.id,
"OcTree");
123 EXPECT_EQ(octomap_msg.octomap.data.size(), msg.world.octomap.octomap.data.size());
128 moveit_msgs::msg::PlanningScene msg;
132 octomap_msgs::msg::OctomapWithPose octomap_msg;
134 EXPECT_EQ(octomap_msg.octomap.id,
"OcTree");
135 EXPECT_FALSE(octomap_msg.octomap.data.empty());
139 moveit_msgs::msg::PlanningScene msg;
141 msg.world.octomap.octomap.id =
"xxx";
147TEST(PlanningScene, LoadRestoreDiff)
150 srdf::ModelSharedPtr srdf_model = std::make_shared<srdf::Model>();
151 auto ps = std::make_shared<planning_scene::PlanningScene>(urdf_model, srdf_model);
156 Eigen::Isometry3d
id = Eigen::Isometry3d::Identity();
157 world.
addToObject(
"sphere", std::make_shared<const shapes::Sphere>(0.4),
id);
160 moveit_msgs::msg::PlanningScene ps_msg;
161 ps_msg.robot_state.is_diff =
true;
163 ps->getPlanningSceneMsg(ps_msg);
164 ps->setPlanningSceneMsg(ps_msg);
165 EXPECT_EQ(ps_msg.world.collision_objects.size(), 1u);
166 EXPECT_EQ(ps_msg.world.collision_objects[0].id,
"sphere");
170 planning_scene::PlanningScenePtr next = ps->diff();
172 EXPECT_TRUE(next->getWorld()->hasObject(
"sphere"));
175 next->getWorldNonConst()->addToObject(
"sphere_in_next_only", std::make_shared<const shapes::Sphere>(0.5),
id);
176 EXPECT_EQ(next->getWorld()->size(), 2u);
177 EXPECT_EQ(ps->getWorld()->size(), 1u);
180 EXPECT_EQ(ps->getCollisionEnv()->getWorld()->size(), 1u);
181 EXPECT_EQ(ps->getCollisionEnvUnpadded()->getWorld()->size(), 1u);
183 EXPECT_EQ(next->getCollisionEnv()->getWorld()->size(), 2u);
184 EXPECT_EQ(next->getCollisionEnvUnpadded()->getWorld()->size(), 2u);
187 next->getPlanningSceneDiffMsg(ps_msg);
188 EXPECT_EQ(ps_msg.world.collision_objects.size(), 1u);
191 next->decoupleParent();
192 moveit_msgs::msg::PlanningScene ps_msg2;
195 next->getPlanningSceneDiffMsg(ps_msg2);
196 EXPECT_EQ(ps_msg2.world.collision_objects.size(), 0u);
199 next->getPlanningSceneMsg(ps_msg);
200 EXPECT_EQ(ps_msg.world.collision_objects.size(), 2u);
201 ps->setPlanningSceneMsg(ps_msg);
202 EXPECT_EQ(ps->getWorld()->size(), 2u);
203 EXPECT_EQ(ps->getCollisionEnv()->getWorld()->size(), 2u);
204 EXPECT_EQ(ps->getCollisionEnvUnpadded()->getWorld()->size(), 2u);
207TEST(PlanningScene, MakeAttachedDiff)
210 srdf::ModelSharedPtr srdf_model = std::make_shared<srdf::Model>();
211 auto ps = std::make_shared<planning_scene::PlanningScene>(urdf_model, srdf_model);
215 Eigen::Isometry3d
id = Eigen::Isometry3d::Identity();
216 world.
addToObject(
"sphere", std::make_shared<const shapes::Sphere>(0.4),
id);
219 planning_scene::PlanningScenePtr attached_object_diff_scene = ps->diff();
221 moveit_msgs::msg::AttachedCollisionObject att_obj;
222 att_obj.link_name =
"r_wrist_roll_link";
223 att_obj.object.operation = moveit_msgs::msg::CollisionObject::ADD;
224 att_obj.object.id =
"sphere";
225 attached_object_diff_scene->processAttachedCollisionObjectMsg(att_obj);
228 EXPECT_EQ(attached_object_diff_scene->getWorld()->size(), 0u);
230 EXPECT_TRUE(attached_object_diff_scene->getCurrentState().hasAttachedBody(
"sphere"));
234 attached_object_diff_scene->checkCollision(req, res);
235 ps->checkCollision(req, res);
238TEST(PlanningScene, isStateValid)
241 auto ps = std::make_shared<planning_scene::PlanningScene>(robot_model->getURDF(), robot_model->getSRDF());
243 if (ps->isStateColliding(current_state,
"left_arm"))
245 EXPECT_FALSE(ps->isStateValid(current_state,
"left_arm"));
249TEST(PlanningScene, loadGoodSceneGeometryNewFormat)
252 auto ps = std::make_shared<planning_scene::PlanningScene>(robot_model->getURDF(), robot_model->getSRDF());
254 std::istringstream good_scene_geometry;
255 good_scene_geometry.str(
"foobar_scene\n"
262 "1.49257 1.00222 0.170051\n"
263 "0 0 4.16377e-05 1\n"
272 "0.453709 0.499136 0.355051\n"
273 "0 0 4.16377e-05 1\n"
277 EXPECT_TRUE(ps->loadGeometryFromStream(good_scene_geometry));
278 EXPECT_EQ(ps->getName(),
"foobar_scene");
279 EXPECT_TRUE(ps->getWorld()->hasObject(
"foo"));
280 EXPECT_TRUE(ps->getWorld()->hasObject(
"bar"));
281 EXPECT_FALSE(ps->getWorld()->hasObject(
"baz"));
284TEST(PlanningScene, loadGoodSceneGeometryOldFormat)
287 auto ps = std::make_shared<planning_scene::PlanningScene>(robot_model->getURDF(), robot_model->getSRDF());
289 std::istringstream good_scene_geometry;
290 good_scene_geometry.str(
"foobar_scene\n"
304 EXPECT_TRUE(ps->loadGeometryFromStream(good_scene_geometry));
305 EXPECT_EQ(ps->getName(),
"foobar_scene");
306 EXPECT_TRUE(ps->getWorld()->hasObject(
"foo"));
307 EXPECT_FALSE(ps->getWorld()->hasObject(
"baz"));
310TEST(PlanningScene, loadBadSceneGeometry)
313 auto ps = std::make_shared<planning_scene::PlanningScene>(robot_model->getURDF(), robot_model->getSRDF());
314 std::istringstream empty_scene_geometry;
317 EXPECT_FALSE(ps->loadGeometryFromStream(empty_scene_geometry));
319 std::istringstream malformed_scene_geometry;
320 malformed_scene_geometry.str(
"malformed_scene_geometry\n"
327 "1.49257 1.00222 0.170051\n"
328 "0 0 4.16377e-05 1\n"
331 EXPECT_FALSE(ps->loadGeometryFromStream(malformed_scene_geometry));
336TEST(PlanningScene, switchCollisionDetectorType)
339 auto ps = std::make_shared<planning_scene::PlanningScene>(robot_model->getURDF(), robot_model->getSRDF());
341 if (ps->isStateColliding(current_state,
"left_arm"))
343 EXPECT_FALSE(ps->isStateValid(current_state,
"left_arm"));
347 if (ps->isStateColliding(current_state,
"left_arm"))
349 EXPECT_FALSE(ps->isStateValid(current_state,
"left_arm"));
353TEST(PlanningScene, FailRetrievingNonExistentObject)
357 moveit_msgs::msg::CollisionObject obj;
358 EXPECT_FALSE(ps.getCollisionObjectMsg(obj,
"non_existent_object"));
366 const std::string plugin_name = GetParam();
367 SCOPED_TRACE(plugin_name);
370 srdf::ModelSharedPtr srdf_model = std::make_shared<srdf::Model>();
372 planning_scene::PlanningScenePtr parent = std::make_shared<planning_scene::PlanningScene>(urdf_model, srdf_model);
375 if (!loader.
activate(plugin_name, parent))
377#if defined(GTEST_SKIP_)
378 GTEST_SKIP_(
"Failed to load collision plugin");
385 planning_scene::PlanningScenePtr child = parent->diff();
396 parent->getCollisionEnv()->checkRobotCollision(req, res, *state, parent->getAllowedCollisionMatrix());
399 child->getCollisionEnv()->checkRobotCollision(req, res, *state, child->getAllowedCollisionMatrix());
403 moveit_msgs::msg::PlanningScene ps_msg;
404 ps_msg.is_diff =
false;
405 moveit_msgs::msg::CollisionObject co;
406 co.header.frame_id =
"base_link";
407 co.operation = moveit_msgs::msg::CollisionObject::ADD;
409 co.pose.orientation.w = 1.0;
411 shape_msgs::msg::SolidPrimitive sp;
412 sp.type = shape_msgs::msg::SolidPrimitive::BOX;
413 sp.dimensions = { 1., 1., 1. };
414 co.primitives.push_back(sp);
415 geometry_msgs::msg::Pose sp_pose;
416 sp_pose.orientation.w = 1.0;
417 co.primitive_poses.push_back(sp_pose);
419 ps_msg.world.collision_objects.push_back(co);
422 parent->usePlanningSceneMsg(ps_msg);
426 parent->getCollisionEnv()->checkRobotCollision(req, res, *state, parent->getAllowedCollisionMatrix());
431 child->getCollisionEnv()->checkRobotCollision(req, res, *state, child->getAllowedCollisionMatrix());
439 parent->getCollisionEnv()->checkRobotCollision(req, res, *state, parent->getAllowedCollisionMatrix());
442 child->getCollisionEnv()->checkRobotCollision(req, res, *state, child->getAllowedCollisionMatrix());
451 const std::string& object_name,
const int8_t operation,
452 const bool attach_object =
false,
453 const bool create_object =
true)
456 auto add_object = [](
const std::string& object_name,
const int8_t operation) {
457 moveit_msgs::msg::CollisionObject co;
458 co.header.frame_id =
"panda_link0";
460 co.operation = operation;
461 co.primitives.push_back([] {
462 shape_msgs::msg::SolidPrimitive primitive;
463 primitive.type = shape_msgs::msg::SolidPrimitive::SPHERE;
464 primitive.dimensions.push_back(1.0);
467 co.primitive_poses.push_back([] {
468 geometry_msgs::msg::Pose pose;
469 pose.orientation.w = 1.0;
472 co.pose = co.primitive_poses[0];
476 auto add_attached_object = [](
const std::string& object_name,
const int8_t operation) {
477 moveit_msgs::msg::AttachedCollisionObject aco;
478 aco.object.operation = operation;
479 aco.object.id = object_name;
480 aco.link_name =
"panda_link0";
484 auto new_ps = ps.
diff();
485 if ((operation == moveit_msgs::msg::CollisionObject::REMOVE && !attach_object) ||
486 (operation == moveit_msgs::msg::CollisionObject::ADD && create_object))
487 new_ps->processCollisionObjectMsg(add_object(object_name, operation));
489 new_ps->processAttachedCollisionObjectMsg(add_attached_object(object_name, operation));
490 moveit_msgs::msg::PlanningScene scene_msg;
491 new_ps->getPlanningSceneDiffMsg(scene_msg);
498 std::vector<moveit_msgs::msg::CollisionObject> collision_objects;
500 std::set<std::string> collision_objects_names;
501 for (
const auto& collision_object : collision_objects)
502 collision_objects_names.emplace(collision_object.id);
503 return collision_objects_names;
509 std::vector<moveit_msgs::msg::AttachedCollisionObject> collision_objects;
511 std::set<std::string> collision_objects_names;
512 for (
const auto& collision_object : collision_objects)
513 collision_objects_names.emplace(collision_object.object.id);
514 return collision_objects_names;
517TEST(PlanningScene, RobotStateDiffBug)
520 auto srdf_model = std::make_shared<srdf::Model>();
521 auto ps = std::make_shared<planning_scene::PlanningScene>(urdf_model, srdf_model);
528 ps->usePlanningSceneMsg(ps1);
529 ps->usePlanningSceneMsg(ps2);
538 ps->usePlanningSceneMsg(ps1);
543 ps = std::make_shared<planning_scene::PlanningScene>(urdf_model, srdf_model);
548 ps->usePlanningSceneMsg(ps1);
549 ps->usePlanningSceneMsg(ps2);
557 ps->usePlanningSceneMsg(ps1);
566 ps->usePlanningSceneMsg(ps1);
574 auto ps1 = ps->diff();
575 moveit_msgs::msg::CollisionObject co;
577 co.operation = moveit_msgs::msg::CollisionObject::REMOVE;
578 moveit_msgs::msg::AttachedCollisionObject aco;
581 ps1->processAttachedCollisionObjectMsg(aco);
582 ps1->processCollisionObjectMsg(co);
584 moveit_msgs::msg::PlanningScene msg;
585 ps1->getPlanningSceneDiffMsg(msg);
586 ps->usePlanningSceneMsg(msg);
593#ifndef INSTANTIATE_TEST_SUITE_P
594#define INSTANTIATE_TEST_SUITE_P(...) INSTANTIATE_TEST_CASE_P(__VA_ARGS__)
602 testing::InitGoogleTest(&argc, argv);
603 return RUN_ALL_TESTS();
static CollisionDetectorAllocatorPtr create()
bool activate(const std::string &name, const planning_scene::PlanningScenePtr &scene)
Activate a specific collision plugin for the given planning scene instance.
Maintain a representation of the environment.
bool hasObject(const std::string &object_id) const
Check if a particular object exists in the collision world.
void addToObject(const std::string &object_id, const Eigen::Isometry3d &pose, const std::vector< shapes::ShapeConstPtr > &shapes, const EigenSTL::vector_Isometry3d &shape_poses)
Add a pose and shapes to an object in the map. This function makes repeated calls to addToObjectInter...
Representation of a robot's state. This includes position, velocity, acceleration and effort.
void update(bool force=false)
Update all transforms.
void setToDefaultValues()
Set all joints to their default positions. The default position is 0, or if that is not within bounds...
This class maintains the representation of the environment as seen by a planning instance....
void getAttachedCollisionObjectMsgs(std::vector< moveit_msgs::msg::AttachedCollisionObject > &attached_collision_objs) const
Construct a vector of messages (attached_collision_objects) with the attached collision object data f...
void getPlanningSceneMsg(moveit_msgs::msg::PlanningScene &scene) const
Construct a message (scene) with all the necessary data so that the scene can be later reconstructed ...
const moveit::core::RobotModelConstPtr & getRobotModel() const
Get the kinematic model for which the planning scene is maintained.
bool processCollisionObjectMsg(const moveit_msgs::msg::CollisionObject &object)
const Eigen::Isometry3d & getFrameTransform(const std::string &id) const
Get the transform corresponding to the frame id. This will be known if id is a link name,...
void getCollisionObjectMsgs(std::vector< moveit_msgs::msg::CollisionObject > &collision_objs) const
Construct a vector of messages (collision_objects) with the collision object data for all objects in ...
PlanningScenePtr diff() const
Return a new child PlanningScene that uses this one as parent.
const collision_detection::WorldConstPtr & getWorld() const
Get the representation of the world.
bool setPlanningSceneDiffMsg(const moveit_msgs::msg::PlanningScene &scene)
Apply changes to this planning scene as diffs, even if the message itself is not marked as being a di...
bool getOctomapMsg(octomap_msgs::msg::OctomapWithPose &octomap) const
Construct a message (octomap) with the octomap data from the planning_scene.
const std::string & getName() const
Get the name of the planning scene. This is empty by default.
bool setPlanningSceneMsg(const moveit_msgs::msg::PlanningScene &scene)
Set this instance of a planning scene to be the same as the one serialized in the scene message,...
static const std::string OCTOMAP_NS
bool isEmpty(const moveit_msgs::msg::PlanningScene &msg)
Check if a message includes any information about a planning scene, or whether it is empty.
moveit::core::RobotModelPtr loadTestingRobotModel(const std::string &package_name, const std::string &urdf_relative_path, const std::string &srdf_relative_path)
Loads a robot model given a URDF and SRDF file in a package.
urdf::ModelInterfaceSharedPtr loadModelInterface(const std::string &robot_name)
Loads a URDF Model Interface from moveit_resources.
Representation of a collision checking request.
Representation of a collision checking result.
EIGEN_MAKE_ALIGNED_OPERATOR_NEW void clear()
Clear a previously stored result.
bool collision
True if collision was found, false otherwise.
int main(int argc, char **argv)
TEST(PlanningScene, TestOneShapeObjectPose)
#define INSTANTIATE_TEST_SUITE_P(...)
moveit_msgs::msg::PlanningScene createPlanningSceneDiff(const planning_scene::PlanningScene &ps, const std::string &object_name, const int8_t operation, const bool attach_object=false, const bool create_object=true)
TEST_P(CollisionDetectorTests, ClearDiff)
std::set< std::string > getAttachedCollisionObjectsNames(const planning_scene::PlanningScene &ps)
std::set< std::string > getCollisionObjectsNames(const planning_scene::PlanningScene &ps)