moveit2
The MoveIt Motion Planning Framework for ROS 2.
Loading...
Searching...
No Matches
test_planning_scene.cpp
Go to the documentation of this file.
1/*********************************************************************
2 * Software License Agreement (BSD License)
3 *
4 * Copyright (c) 2011, Willow Garage, Inc.
5 * All rights reserved.
6 *
7 * Redistribution and use in source and binary forms, with or without
8 * modification, are permitted provided that the following conditions
9 * are met:
10 *
11 * * Redistributions of source code must retain the above copyright
12 * notice, this list of conditions and the following disclaimer.
13 * * Redistributions in binary form must reproduce the above
14 * copyright notice, this list of conditions and the following
15 * disclaimer in the documentation and/or other materials provided
16 * with the distribution.
17 * * Neither the name of Willow Garage nor the names of its
18 * contributors may be used to endorse or promote products derived
19 * from this software without specific prior written permission.
20 *
21 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32 * POSSIBILITY OF SUCH DAMAGE.
33 *********************************************************************/
34
35/* Author: Ioan Sucan */
36
37#include <gtest/gtest.h>
42#include <urdf_parser/urdf_parser.h>
43#include <fstream>
44#include <sstream>
45#include <string>
46#include <tf2_eigen/tf2_eigen.hpp>
47#include <octomap_msgs/conversions.h>
48#include <octomap/octomap.h>
49
52
53// Test not setting the object's pose should use the shape pose as the object pose
54TEST(PlanningScene, TestOneShapeObjectPose)
55{
56 urdf::ModelInterfaceSharedPtr urdf_model = moveit::core::loadModelInterface("pr2");
57 srdf::ModelSharedPtr srdf_model = std::make_shared<srdf::Model>();
58 planning_scene::PlanningScene ps(urdf_model, srdf_model);
59
60 const std::string object_name = "object";
61 const Eigen::Isometry3d expected_transfrom = Eigen::Isometry3d::Identity() * Eigen::Translation3d(0.5, -0.25, 0.0);
62
63 moveit_msgs::msg::CollisionObject co;
64 co.header.frame_id = "base_footprint";
65 co.id = object_name;
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 };
71 return primitive;
72 }());
73 co.primitive_poses.push_back(tf2::toMsg(expected_transfrom));
74
76
77 EXPECT_TRUE(expected_transfrom.isApprox(ps.getFrameTransform(object_name)));
78}
79
80TEST(PlanningScene, LoadRestore)
81{
82 urdf::ModelInterfaceSharedPtr urdf_model = moveit::core::loadModelInterface("pr2");
83 srdf::ModelSharedPtr srdf_model = std::make_shared<srdf::Model>();
84 planning_scene::PlanningScene ps(urdf_model, srdf_model);
85 moveit_msgs::msg::PlanningScene ps_msg;
86 ps.getPlanningSceneMsg(ps_msg);
87 EXPECT_EQ(ps.getName(), ps_msg.name);
88 EXPECT_EQ(ps.getRobotModel()->getName(), ps_msg.robot_model_name);
89 ps.setPlanningSceneMsg(ps_msg);
90 EXPECT_EQ(ps.getName(), ps_msg.name);
91 EXPECT_EQ(ps.getRobotModel()->getName(), ps_msg.robot_model_name);
92}
93
94TEST(PlanningScene, LoadOctomap)
95{
96 urdf::ModelInterfaceSharedPtr urdf_model = moveit::core::loadModelInterface("pr2");
97 srdf::ModelSharedPtr srdf_model(new srdf::Model());
98 planning_scene::PlanningScene ps(urdf_model, srdf_model);
99
100 { // check octomap before doing any operations on it
101 octomap_msgs::msg::OctomapWithPose msg;
102 ps.getOctomapMsg(msg);
103 EXPECT_TRUE(msg.octomap.id.empty());
104 EXPECT_TRUE(msg.octomap.data.empty());
105 }
106
107 { // fill PlanningScene's octomap
108 octomap::OcTree octomap(0.1);
109 octomap::point3d origin(0, 0, 0);
110 octomap::point3d end(0, 1, 2);
111 octomap.insertRay(origin, end);
112
113 // populate PlanningScene with octomap
114 moveit_msgs::msg::PlanningScene msg;
115 msg.is_diff = true;
116 octomap_msgs::fullMapToMsg(octomap, msg.world.octomap.octomap);
118
119 // validate octomap message
120 octomap_msgs::msg::OctomapWithPose octomap_msg;
121 ps.getOctomapMsg(octomap_msg);
122 EXPECT_EQ(octomap_msg.octomap.id, "OcTree");
123 EXPECT_EQ(octomap_msg.octomap.data.size(), msg.world.octomap.octomap.data.size());
124 }
125
126 { // verify that a PlanningScene msg with an empty octomap id does not modify the octomap
127 // create planning scene
128 moveit_msgs::msg::PlanningScene msg;
129 msg.is_diff = true;
131
132 octomap_msgs::msg::OctomapWithPose octomap_msg;
133 ps.getOctomapMsg(octomap_msg);
134 EXPECT_EQ(octomap_msg.octomap.id, "OcTree");
135 EXPECT_FALSE(octomap_msg.octomap.data.empty());
136 }
137
138 { // check that a non-empty octomap id, but empty octomap will clear the octomap
139 moveit_msgs::msg::PlanningScene msg;
140 msg.is_diff = true;
141 msg.world.octomap.octomap.id = "xxx";
143 EXPECT_FALSE(static_cast<bool>(ps.getWorld()->getObject(planning_scene::PlanningScene::OCTOMAP_NS)));
144 }
145}
146
147TEST(PlanningScene, LoadRestoreDiff)
148{
149 urdf::ModelInterfaceSharedPtr urdf_model = moveit::core::loadModelInterface("pr2");
150 srdf::ModelSharedPtr srdf_model = std::make_shared<srdf::Model>();
151 auto ps = std::make_shared<planning_scene::PlanningScene>(urdf_model, srdf_model);
152
153 collision_detection::World& world = *ps->getWorldNonConst();
154
155 /* add one object to ps's world */
156 Eigen::Isometry3d id = Eigen::Isometry3d::Identity();
157 world.addToObject("sphere", std::make_shared<const shapes::Sphere>(0.4), id);
158
159 /* ps can be written to and set from message */
160 moveit_msgs::msg::PlanningScene ps_msg;
161 ps_msg.robot_state.is_diff = true;
162 EXPECT_TRUE(moveit::core::isEmpty(ps_msg));
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");
167 EXPECT_TRUE(world.hasObject("sphere"));
168
169 /* test diff scene on top of ps */
170 planning_scene::PlanningScenePtr next = ps->diff();
171 /* world is inherited from ps */
172 EXPECT_TRUE(next->getWorld()->hasObject("sphere"));
173
174 /* object in overlay is only added in overlay */
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);
178
179 /* the worlds used for collision detection contain one and two objects, respectively */
180 EXPECT_EQ(ps->getCollisionEnv()->getWorld()->size(), 1u);
181 EXPECT_EQ(ps->getCollisionEnvUnpadded()->getWorld()->size(), 1u);
182
183 EXPECT_EQ(next->getCollisionEnv()->getWorld()->size(), 2u);
184 EXPECT_EQ(next->getCollisionEnvUnpadded()->getWorld()->size(), 2u);
185
186 /* maintained diff contains only overlay object */
187 next->getPlanningSceneDiffMsg(ps_msg);
188 EXPECT_EQ(ps_msg.world.collision_objects.size(), 1u);
189
190 /* copy ps to next and apply diff */
191 next->decoupleParent();
192 moveit_msgs::msg::PlanningScene ps_msg2;
193
194 /* diff is empty now */
195 next->getPlanningSceneDiffMsg(ps_msg2);
196 EXPECT_EQ(ps_msg2.world.collision_objects.size(), 0u);
197
198 /* next's world contains both objects */
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);
205}
206
207TEST(PlanningScene, MakeAttachedDiff)
208{
209 urdf::ModelInterfaceSharedPtr urdf_model = moveit::core::loadModelInterface("pr2");
210 srdf::ModelSharedPtr srdf_model = std::make_shared<srdf::Model>();
211 auto ps = std::make_shared<planning_scene::PlanningScene>(urdf_model, srdf_model);
212
213 /* add a single object to ps's world */
214 collision_detection::World& world = *ps->getWorldNonConst();
215 Eigen::Isometry3d id = Eigen::Isometry3d::Identity();
216 world.addToObject("sphere", std::make_shared<const shapes::Sphere>(0.4), id);
217
218 /* attach object in diff */
219 planning_scene::PlanningScenePtr attached_object_diff_scene = ps->diff();
220
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);
226
227 /* object is not in world anymore */
228 EXPECT_EQ(attached_object_diff_scene->getWorld()->size(), 0u);
229 /* it became part of the robot state though */
230 EXPECT_TRUE(attached_object_diff_scene->getCurrentState().hasAttachedBody("sphere"));
231
234 attached_object_diff_scene->checkCollision(req, res);
235 ps->checkCollision(req, res);
236}
237
238TEST(PlanningScene, isStateValid)
239{
240 moveit::core::RobotModelPtr robot_model = moveit::core::loadTestingRobotModel("pr2");
241 auto ps = std::make_shared<planning_scene::PlanningScene>(robot_model->getURDF(), robot_model->getSRDF());
242 moveit::core::RobotState current_state = ps->getCurrentState();
243 if (ps->isStateColliding(current_state, "left_arm"))
244 {
245 EXPECT_FALSE(ps->isStateValid(current_state, "left_arm"));
246 }
247}
248
249TEST(PlanningScene, loadGoodSceneGeometryNewFormat)
250{
251 moveit::core::RobotModelPtr robot_model = moveit::core::loadTestingRobotModel("pr2");
252 auto ps = std::make_shared<planning_scene::PlanningScene>(robot_model->getURDF(), robot_model->getSRDF());
253
254 std::istringstream good_scene_geometry;
255 good_scene_geometry.str("foobar_scene\n"
256 "* foo\n"
257 "0 0 0\n"
258 "0 0 0 1\n"
259 "1\n"
260 "box\n"
261 "2.58 1.36 0.31\n"
262 "1.49257 1.00222 0.170051\n"
263 "0 0 4.16377e-05 1\n"
264 "0 0 1 0.3\n"
265 "0\n"
266 "* bar\n"
267 "0 0 0\n"
268 "0 0 0 1\n"
269 "1\n"
270 "cylinder\n"
271 "0.02 0.0001\n"
272 "0.453709 0.499136 0.355051\n"
273 "0 0 4.16377e-05 1\n"
274 "1 0 0 1\n"
275 "0\n"
276 ".\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")); // Sanity check.
282}
283
284TEST(PlanningScene, loadGoodSceneGeometryOldFormat)
285{
286 moveit::core::RobotModelPtr robot_model = moveit::core::loadTestingRobotModel("pr2");
287 auto ps = std::make_shared<planning_scene::PlanningScene>(robot_model->getURDF(), robot_model->getSRDF());
288
289 std::istringstream good_scene_geometry;
290 good_scene_geometry.str("foobar_scene\n"
291 "* foo\n"
292 "2\n"
293 "box\n"
294 ".77 0.39 0.05\n"
295 "0 0 0.025\n"
296 "0 0 0 1\n"
297 "0.82 0.75 0.60 1\n"
298 "box\n"
299 ".77 0.39 0.05\n"
300 "0 0 1.445\n"
301 "0 0 0 1\n"
302 "0.82 0.75 0.60 1\n"
303 ".\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")); // Sanity check.
308}
309
310TEST(PlanningScene, loadBadSceneGeometry)
311{
312 moveit::core::RobotModelPtr robot_model = moveit::core::loadTestingRobotModel("pr2");
313 auto ps = std::make_shared<planning_scene::PlanningScene>(robot_model->getURDF(), robot_model->getSRDF());
314 std::istringstream empty_scene_geometry;
315
316 // This should fail since there is no planning scene name and no end of geometry marker.
317 EXPECT_FALSE(ps->loadGeometryFromStream(empty_scene_geometry));
318
319 std::istringstream malformed_scene_geometry;
320 malformed_scene_geometry.str("malformed_scene_geometry\n"
321 "* foo\n"
322 "0 0 0\n"
323 "0 0 0 1\n"
324 "1\n"
325 "box\n"
326 "2.58 1.36\n" /* Only two tokens; should be 3 */
327 "1.49257 1.00222 0.170051\n"
328 "0 0 4.16377e-05 1\n"
329 "0 0 1 0.3\n"
330 ".\n");
331 EXPECT_FALSE(ps->loadGeometryFromStream(malformed_scene_geometry));
332}
333
334// Test the setting of a new collision detector type. For now, only FCL is available in MoveIt2.
335// TODO(andyz): switch to a different type when one becomes available.
336TEST(PlanningScene, switchCollisionDetectorType)
337{
338 moveit::core::RobotModelPtr robot_model = moveit::core::loadTestingRobotModel("pr2");
339 auto ps = std::make_shared<planning_scene::PlanningScene>(robot_model->getURDF(), robot_model->getSRDF());
340 moveit::core::RobotState current_state = ps->getCurrentState();
341 if (ps->isStateColliding(current_state, "left_arm"))
342 {
343 EXPECT_FALSE(ps->isStateValid(current_state, "left_arm"));
344 }
345
346 ps->allocateCollisionDetector(collision_detection::CollisionDetectorAllocatorFCL::create());
347 if (ps->isStateColliding(current_state, "left_arm"))
348 {
349 EXPECT_FALSE(ps->isStateValid(current_state, "left_arm"));
350 }
351}
352
353TEST(PlanningScene, FailRetrievingNonExistentObject)
354{
355 moveit::core::RobotModelPtr robot_model = moveit::core::loadTestingRobotModel("pr2");
356 planning_scene::PlanningScene ps{ robot_model };
357 moveit_msgs::msg::CollisionObject obj;
358 EXPECT_FALSE(ps.getCollisionObjectMsg(obj, "non_existent_object"));
359}
360
361class CollisionDetectorTests : public testing::TestWithParam<const char*>
362{
363};
365{
366 const std::string plugin_name = GetParam();
367 SCOPED_TRACE(plugin_name);
368
369 urdf::ModelInterfaceSharedPtr urdf_model = moveit::core::loadModelInterface("pr2");
370 srdf::ModelSharedPtr srdf_model = std::make_shared<srdf::Model>();
371 // create parent scene
372 planning_scene::PlanningScenePtr parent = std::make_shared<planning_scene::PlanningScene>(urdf_model, srdf_model);
373
375 if (!loader.activate(plugin_name, parent))
376 {
377#if defined(GTEST_SKIP_)
378 GTEST_SKIP_("Failed to load collision plugin");
379#else
380 return;
381#endif
382 }
383
384 // create child scene
385 planning_scene::PlanningScenePtr child = parent->diff();
386
387 // create collision request variables
390 moveit::core::RobotState* state = new moveit::core::RobotState(child->getRobotModel());
391 state->setToDefaultValues();
392 state->update();
393
394 // there should be no collision with the environment
395 res.clear();
396 parent->getCollisionEnv()->checkRobotCollision(req, res, *state, parent->getAllowedCollisionMatrix());
397 EXPECT_FALSE(res.collision);
398 res.clear();
399 child->getCollisionEnv()->checkRobotCollision(req, res, *state, child->getAllowedCollisionMatrix());
400 EXPECT_FALSE(res.collision);
401
402 // create message to add a collision object at the world origin
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;
408 co.id = "box";
409 co.pose.orientation.w = 1.0;
410 {
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);
418 }
419 ps_msg.world.collision_objects.push_back(co);
420
421 // add object to the parent planning scene
422 parent->usePlanningSceneMsg(ps_msg);
423
424 // the parent scene should be in collision
425 res.clear();
426 parent->getCollisionEnv()->checkRobotCollision(req, res, *state, parent->getAllowedCollisionMatrix());
427 EXPECT_TRUE(res.collision);
428
429 // the child scene was not updated yet, so no collision
430 res.clear();
431 child->getCollisionEnv()->checkRobotCollision(req, res, *state, child->getAllowedCollisionMatrix());
432 EXPECT_FALSE(res.collision);
433
434 // update the child scene
435 child->clearDiffs();
436
437 // child and parent scene should be in collision
438 res.clear();
439 parent->getCollisionEnv()->checkRobotCollision(req, res, *state, parent->getAllowedCollisionMatrix());
440 EXPECT_TRUE(res.collision);
441 res.clear();
442 child->getCollisionEnv()->checkRobotCollision(req, res, *state, child->getAllowedCollisionMatrix());
443 EXPECT_TRUE(res.collision);
444
445 child.reset();
446 parent.reset();
447}
448
449// Returns a planning scene diff message
450moveit_msgs::msg::PlanningScene createPlanningSceneDiff(const planning_scene::PlanningScene& ps,
451 const std::string& object_name, const int8_t operation,
452 const bool attach_object = false,
453 const bool create_object = true)
454{
455 // Helper function to create an object for RobotStateDiffBug
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";
459 co.id = object_name;
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);
465 return primitive;
466 }());
467 co.primitive_poses.push_back([] {
468 geometry_msgs::msg::Pose pose;
469 pose.orientation.w = 1.0;
470 return pose;
471 }());
472 co.pose = co.primitive_poses[0];
473 return co;
474 };
475 // Helper function to create an attached object for RobotStateDiffBug
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";
481 return aco;
482 };
483
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));
488 if (attach_object)
489 new_ps->processAttachedCollisionObjectMsg(add_attached_object(object_name, operation));
490 moveit_msgs::msg::PlanningScene scene_msg;
491 new_ps->getPlanningSceneDiffMsg(scene_msg);
492 return scene_msg;
493}
494
495// Returns collision objects names sorted alphabetically
497{
498 std::vector<moveit_msgs::msg::CollisionObject> collision_objects;
499 ps.getCollisionObjectMsgs(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;
504}
505
506// Returns attached collision objects names sorted alphabetically
508{
509 std::vector<moveit_msgs::msg::AttachedCollisionObject> collision_objects;
510 ps.getAttachedCollisionObjectMsgs(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;
515}
516
517TEST(PlanningScene, RobotStateDiffBug)
518{
519 auto urdf_model = moveit::core::loadModelInterface("panda");
520 auto srdf_model = std::make_shared<srdf::Model>();
521 auto ps = std::make_shared<planning_scene::PlanningScene>(urdf_model, srdf_model);
522
523 // Adding collision objects incrementally
524 {
525 const auto ps1 = createPlanningSceneDiff(*ps, "object1", moveit_msgs::msg::CollisionObject::ADD);
526 const auto ps2 = createPlanningSceneDiff(*ps, "object2", moveit_msgs::msg::CollisionObject::ADD);
527
528 ps->usePlanningSceneMsg(ps1);
529 ps->usePlanningSceneMsg(ps2);
530
531 EXPECT_EQ(getCollisionObjectsNames(*ps), (std::set<std::string>{ "object1", "object2" }));
532 }
533
534 // Removing a collision object
535 {
536 const auto ps1 = createPlanningSceneDiff(*ps, "object2", moveit_msgs::msg::CollisionObject::REMOVE);
537
538 ps->usePlanningSceneMsg(ps1);
539 EXPECT_EQ(getCollisionObjectsNames(*ps), (std::set<std::string>{ "object1" }));
540 }
541
542 // Adding attached collision objects incrementally
543 ps = std::make_shared<planning_scene::PlanningScene>(urdf_model, srdf_model);
544 {
545 const auto ps1 = createPlanningSceneDiff(*ps, "object1", moveit_msgs::msg::CollisionObject::ADD, true);
546 const auto ps2 = createPlanningSceneDiff(*ps, "object2", moveit_msgs::msg::CollisionObject::ADD, true);
547
548 ps->usePlanningSceneMsg(ps1);
549 ps->usePlanningSceneMsg(ps2);
550 EXPECT_TRUE(getCollisionObjectsNames(*ps).empty());
551 EXPECT_EQ(getAttachedCollisionObjectsNames(*ps), (std::set<std::string>{ "object1", "object2" }));
552 }
553
554 // Removing an attached collision object
555 {
556 const auto ps1 = createPlanningSceneDiff(*ps, "object2", moveit_msgs::msg::CollisionObject::REMOVE, true);
557 ps->usePlanningSceneMsg(ps1);
558
559 EXPECT_EQ(getCollisionObjectsNames(*ps), (std::set<std::string>{ "object2" }));
560 EXPECT_EQ(getAttachedCollisionObjectsNames(*ps), (std::set<std::string>{ "object1" }));
561 }
562
563 // Turn an existing collision object into an attached object
564 {
565 const auto ps1 = createPlanningSceneDiff(*ps, "object2", moveit_msgs::msg::CollisionObject::ADD, true, false);
566 ps->usePlanningSceneMsg(ps1);
567
568 EXPECT_TRUE(getCollisionObjectsNames(*ps).empty());
569 EXPECT_EQ(getAttachedCollisionObjectsNames(*ps), (std::set<std::string>{ "object1", "object2" }));
570 }
571
572 // Removing an attached collision object completely
573 {
574 auto ps1 = ps->diff();
575 moveit_msgs::msg::CollisionObject co;
576 co.id = "object2";
577 co.operation = moveit_msgs::msg::CollisionObject::REMOVE;
578 moveit_msgs::msg::AttachedCollisionObject aco;
579 aco.object = co;
580
581 ps1->processAttachedCollisionObjectMsg(aco); // detach
582 ps1->processCollisionObjectMsg(co); // and eventually remove object
583
584 moveit_msgs::msg::PlanningScene msg;
585 ps1->getPlanningSceneDiffMsg(msg);
586 ps->usePlanningSceneMsg(msg);
587
588 EXPECT_TRUE(getCollisionObjectsNames(*ps).empty());
589 EXPECT_EQ(getAttachedCollisionObjectsNames(*ps), (std::set<std::string>{ "object1" }));
590 }
591}
592
593#ifndef INSTANTIATE_TEST_SUITE_P // prior to gtest 1.10
594#define INSTANTIATE_TEST_SUITE_P(...) INSTANTIATE_TEST_CASE_P(__VA_ARGS__)
595#endif
596
597// instantiate parameterized tests for common collision plugins
598INSTANTIATE_TEST_SUITE_P(PluginTests, CollisionDetectorTests, testing::Values("FCL", "Bullet"));
599
600int main(int argc, char** argv)
601{
602 testing::InitGoogleTest(&argc, argv);
603 return RUN_ALL_TESTS();
604}
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.
Definition world.h:59
bool hasObject(const std::string &object_id) const
Check if a particular object exists in the collision world.
Definition world.cpp:137
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...
Definition world.cpp:77
Representation of a robot's state. This includes position, velocity, acceleration and effort.
Definition robot_state.h:90
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)