37 #include <gtest/gtest.h>
41 #include <urdf_parser/urdf_parser.h>
45 #include <boost/filesystem/path.hpp>
53 TEST(PlanningScene, LoadRestore)
56 auto srdf_model = std::make_shared<srdf::Model>();
58 moveit_msgs::PlanningScene ps_msg;
67 TEST(PlanningScene, LoadOctomap)
70 auto srdf_model = std::make_shared<srdf::Model>();
74 octomap_msgs::OctomapWithPose msg;
87 moveit_msgs::PlanningScene msg;
93 octomap_msgs::OctomapWithPose octomap_msg;
95 EXPECT_EQ(octomap_msg.octomap.id,
"OcTree");
96 EXPECT_EQ(octomap_msg.octomap.data.size(), msg.world.octomap.octomap.data.size());
101 moveit_msgs::PlanningScene msg;
105 octomap_msgs::OctomapWithPose octomap_msg;
107 EXPECT_EQ(octomap_msg.octomap.id,
"OcTree");
112 moveit_msgs::PlanningScene msg;
114 msg.world.octomap.octomap.id =
"xxx";
120 TEST(PlanningScene, LoadRestoreDiff)
123 auto srdf_model = std::make_shared<srdf::Model>();
124 auto ps = std::make_shared<planning_scene::PlanningScene>(urdf_model, srdf_model);
129 Eigen::Isometry3d
id = Eigen::Isometry3d::Identity();
133 moveit_msgs::PlanningScene ps_msg;
134 ps_msg.robot_state.is_diff =
true;
136 ps->getPlanningSceneMsg(ps_msg);
137 ps->setPlanningSceneMsg(ps_msg);
138 EXPECT_EQ(ps_msg.world.collision_objects.size(), 1u);
139 EXPECT_EQ(ps_msg.world.collision_objects[0].id,
"sphere");
143 planning_scene::PlanningScenePtr
next = ps->diff();
153 EXPECT_EQ(ps->getCollisionEnv()->getWorld()->size(), 1u);
154 EXPECT_EQ(ps->getCollisionEnvUnpadded()->getWorld()->size(), 1u);
157 EXPECT_EQ(
next->getCollisionEnvUnpadded()->getWorld()->size(), 2u);
160 next->getPlanningSceneDiffMsg(ps_msg);
161 EXPECT_EQ(ps_msg.world.collision_objects.size(), 1u);
164 next->decoupleParent();
165 moveit_msgs::PlanningScene ps_msg2;
168 next->getPlanningSceneDiffMsg(ps_msg2);
169 EXPECT_EQ(ps_msg2.world.collision_objects.size(), 0u);
172 next->getPlanningSceneMsg(ps_msg);
173 EXPECT_EQ(ps_msg.world.collision_objects.size(), 2u);
174 ps->setPlanningSceneMsg(ps_msg);
176 EXPECT_EQ(ps->getCollisionEnv()->getWorld()->size(), 2u);
177 EXPECT_EQ(ps->getCollisionEnvUnpadded()->getWorld()->size(), 2u);
180 TEST(PlanningScene, MakeAttachedDiff)
183 auto srdf_model = std::make_shared<srdf::Model>();
184 auto ps = std::make_shared<planning_scene::PlanningScene>(urdf_model, srdf_model);
188 Eigen::Isometry3d
id = Eigen::Isometry3d::Identity();
192 planning_scene::PlanningScenePtr attached_object_diff_scene = ps->diff();
194 moveit_msgs::AttachedCollisionObject att_obj;
195 att_obj.link_name =
"r_wrist_roll_link";
196 att_obj.object.operation = moveit_msgs::CollisionObject::ADD;
197 att_obj.object.id =
"sphere";
198 attached_object_diff_scene->processAttachedCollisionObjectMsg(att_obj);
201 EXPECT_EQ(attached_object_diff_scene->getWorld()->size(), 0u);
203 EXPECT_TRUE(attached_object_diff_scene->getCurrentState().hasAttachedBody(
"sphere"));
207 attached_object_diff_scene->checkCollision(req, res);
208 ps->checkCollision(req, res);
211 TEST(PlanningScene, isStateValid)
214 auto ps = std::make_shared<planning_scene::PlanningScene>(
robot_model->getURDF(),
robot_model->getSRDF());
216 if (ps->isStateColliding(current_state,
"left_arm"))
218 EXPECT_FALSE(ps->isStateValid(current_state,
"left_arm"));
222 TEST(PlanningScene, loadGoodSceneGeometryNewFormat)
225 auto ps = std::make_shared<planning_scene::PlanningScene>(
robot_model->getURDF(),
robot_model->getSRDF());
227 std::istringstream good_scene_geometry;
228 good_scene_geometry.str(
"foobar_scene\n"
235 "1.49257 1.00222 0.170051\n"
236 "0 0 4.16377e-05 1\n"
245 "0.453709 0.499136 0.355051\n"
246 "0 0 4.16377e-05 1\n"
250 EXPECT_TRUE(ps->loadGeometryFromStream(good_scene_geometry));
251 EXPECT_EQ(ps->getName(),
"foobar_scene");
257 TEST(PlanningScene, loadGoodSceneGeometryOldFormat)
260 auto ps = std::make_shared<planning_scene::PlanningScene>(
robot_model->getURDF(),
robot_model->getSRDF());
262 std::istringstream good_scene_geometry;
263 good_scene_geometry.str(
"foobar_scene\n"
277 EXPECT_TRUE(ps->loadGeometryFromStream(good_scene_geometry));
278 EXPECT_EQ(ps->getName(),
"foobar_scene");
283 TEST(PlanningScene, loadBadSceneGeometry)
286 auto ps = std::make_shared<planning_scene::PlanningScene>(
robot_model->getURDF(),
robot_model->getSRDF());
287 std::istringstream empty_scene_geometry;
290 EXPECT_FALSE(ps->loadGeometryFromStream(empty_scene_geometry));
292 std::istringstream malformed_scene_geometry;
293 malformed_scene_geometry.str(
"malformed_scene_geometry\n"
300 "1.49257 1.00222 0.170051\n"
301 "0 0 4.16377e-05 1\n"
304 EXPECT_FALSE(ps->loadGeometryFromStream(malformed_scene_geometry));
307 TEST(PlanningScene, FailRetrievingNonExistentObject)
311 moveit_msgs::CollisionObject
obj;
320 const std::string plugin_name = GetParam();
321 SCOPED_TRACE(plugin_name);
324 auto srdf_model = std::make_shared<srdf::Model>();
326 planning_scene::PlanningScenePtr parent = std::make_shared<planning_scene::PlanningScene>(urdf_model, srdf_model);
329 if (!loader.
activate(plugin_name, parent,
true))
331 #if defined(GTEST_SKIP_)
332 GTEST_SKIP_(
"Failed to load collision plugin");
339 planning_scene::PlanningScenePtr child = parent->diff();
350 parent->getCollisionEnv()->checkRobotCollision(req, res, *state, parent->getAllowedCollisionMatrix());
353 child->getCollisionEnv()->checkRobotCollision(req, res, *state, child->getAllowedCollisionMatrix());
357 moveit_msgs::PlanningScene ps_msg;
358 ps_msg.is_diff =
false;
359 moveit_msgs::CollisionObject co;
360 co.header.frame_id =
"base_link";
361 co.operation = moveit_msgs::CollisionObject::ADD;
363 co.pose.orientation.w = 1.0;
365 shape_msgs::SolidPrimitive sp;
366 sp.type = shape_msgs::SolidPrimitive::BOX;
367 sp.dimensions = { 1., 1., 1. };
368 co.primitives.push_back(sp);
369 geometry_msgs::Pose sp_pose;
370 sp_pose.orientation.w = 1.0;
371 co.primitive_poses.push_back(sp_pose);
373 ps_msg.world.collision_objects.push_back(co);
376 parent->usePlanningSceneMsg(ps_msg);
380 parent->getCollisionEnv()->checkRobotCollision(req, res, *state, parent->getAllowedCollisionMatrix());
385 child->getCollisionEnv()->checkRobotCollision(req, res, *state, child->getAllowedCollisionMatrix());
393 parent->getCollisionEnv()->checkRobotCollision(req, res, *state, parent->getAllowedCollisionMatrix());
396 child->getCollisionEnv()->checkRobotCollision(req, res, *state, child->getAllowedCollisionMatrix());
405 const std::string& object_name,
const int8_t operation,
406 const bool attach_object =
false,
const bool create_object =
true)
409 auto add_object = [](
const std::string& object_name,
const int8_t operation) {
410 moveit_msgs::CollisionObject co;
411 co.header.frame_id =
"panda_link0";
413 co.operation = operation;
414 co.primitives.push_back([] {
415 shape_msgs::SolidPrimitive primitive;
416 primitive.type = shape_msgs::SolidPrimitive::SPHERE;
417 primitive.dimensions.push_back(1.0);
420 co.primitive_poses.push_back([] {
421 geometry_msgs::Pose pose;
422 pose.orientation.w = 1.0;
425 co.pose = co.primitive_poses[0];
429 auto add_attached_object = [](
const std::string& object_name,
const int8_t operation) {
430 moveit_msgs::AttachedCollisionObject aco;
431 aco.object.operation = operation;
432 aco.object.id = object_name;
433 aco.link_name =
"panda_link0";
437 auto new_ps = ps.
diff();
438 if ((operation == moveit_msgs::CollisionObject::REMOVE && !attach_object) ||
439 (operation == moveit_msgs::CollisionObject::ADD && create_object))
440 new_ps->processCollisionObjectMsg(add_object(object_name, operation));
442 new_ps->processAttachedCollisionObjectMsg(add_attached_object(object_name, operation));
443 moveit_msgs::PlanningScene scene_msg;
444 new_ps->getPlanningSceneDiffMsg(scene_msg);
451 std::vector<moveit_msgs::CollisionObject> collision_objects;
453 std::set<std::string> collision_objects_names;
454 for (
const auto& collision_object : collision_objects)
455 collision_objects_names.emplace(collision_object.id);
456 return collision_objects_names;
462 std::vector<moveit_msgs::AttachedCollisionObject> collision_objects;
464 std::set<std::string> collision_objects_names;
465 for (
const auto& collision_object : collision_objects)
466 collision_objects_names.emplace(collision_object.object.id);
467 return collision_objects_names;
470 TEST(PlanningScene, RobotStateDiffBug)
473 auto srdf_model = std::make_shared<srdf::Model>();
474 auto ps = std::make_shared<planning_scene::PlanningScene>(urdf_model, srdf_model);
481 ps->usePlanningSceneMsg(ps1);
482 ps->usePlanningSceneMsg(ps2);
490 ps->usePlanningSceneMsg(ps1);
495 ps = std::make_shared<planning_scene::PlanningScene>(urdf_model, srdf_model);
500 ps->usePlanningSceneMsg(ps1);
501 ps->usePlanningSceneMsg(ps2);
509 ps->usePlanningSceneMsg(ps1);
518 ps->usePlanningSceneMsg(ps1);
526 auto ps1 = ps->diff();
527 moveit_msgs::CollisionObject co;
529 co.operation = moveit_msgs::CollisionObject::REMOVE;
530 moveit_msgs::AttachedCollisionObject aco;
533 ps1->processAttachedCollisionObjectMsg(aco);
534 ps1->processCollisionObjectMsg(co);
536 moveit_msgs::PlanningScene msg;
537 ps1->getPlanningSceneDiffMsg(msg);
538 ps->usePlanningSceneMsg(msg);
545 #ifndef INSTANTIATE_TEST_SUITE_P // prior to gtest 1.10
546 #define INSTANTIATE_TEST_SUITE_P(...) INSTANTIATE_TEST_CASE_P(__VA_ARGS__)
552 int main(
int argc,
char** argv)
554 testing::InitGoogleTest(&argc, argv);
555 return RUN_ALL_TESTS();