moveit2
The MoveIt Motion Planning Framework for ROS 2.
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 
50 
51 // Test not setting the object's pose should use the shape pose as the object pose
52 TEST(PlanningScene, TestOneShapeObjectPose)
53 {
54  urdf::ModelInterfaceSharedPtr urdf_model = moveit::core::loadModelInterface("pr2");
55  srdf::ModelSharedPtr srdf_model = std::make_shared<srdf::Model>();
56  planning_scene::PlanningScene ps(urdf_model, srdf_model);
57 
58  const std::string object_name = "object";
59  const Eigen::Isometry3d expected_transfrom = Eigen::Isometry3d::Identity() * Eigen::Translation3d(0.5, -0.25, 0.0);
60 
61  moveit_msgs::msg::CollisionObject co;
62  co.header.frame_id = "base_footprint";
63  co.id = object_name;
64  co.operation = moveit_msgs::msg::CollisionObject::ADD;
65  co.primitives.push_back([] {
66  shape_msgs::msg::SolidPrimitive primitive;
67  primitive.type = shape_msgs::msg::SolidPrimitive::CYLINDER;
68  primitive.dimensions = { 0.25, 0.02 };
69  return primitive;
70  }());
71  co.primitive_poses.push_back(tf2::toMsg(expected_transfrom));
72 
74 
75  EXPECT_TRUE(expected_transfrom.isApprox(ps.getFrameTransform(object_name)));
76 }
77 
78 TEST(PlanningScene, LoadRestore)
79 {
80  urdf::ModelInterfaceSharedPtr urdf_model = moveit::core::loadModelInterface("pr2");
81  srdf::ModelSharedPtr srdf_model = std::make_shared<srdf::Model>();
82  planning_scene::PlanningScene ps(urdf_model, srdf_model);
83  moveit_msgs::msg::PlanningScene ps_msg;
84  ps.getPlanningSceneMsg(ps_msg);
85  EXPECT_EQ(ps.getName(), ps_msg.name);
86  EXPECT_EQ(ps.getRobotModel()->getName(), ps_msg.robot_model_name);
87  ps.setPlanningSceneMsg(ps_msg);
88  EXPECT_EQ(ps.getName(), ps_msg.name);
89  EXPECT_EQ(ps.getRobotModel()->getName(), ps_msg.robot_model_name);
90 }
91 
92 TEST(PlanningScene, LoadRestoreDiff)
93 {
94  urdf::ModelInterfaceSharedPtr urdf_model = moveit::core::loadModelInterface("pr2");
95  srdf::ModelSharedPtr srdf_model = std::make_shared<srdf::Model>();
96  auto ps = std::make_shared<planning_scene::PlanningScene>(urdf_model, srdf_model);
97 
98  collision_detection::World& world = *ps->getWorldNonConst();
99 
100  /* add one object to ps's world */
101  Eigen::Isometry3d id = Eigen::Isometry3d::Identity();
102  world.addToObject("sphere", std::make_shared<const shapes::Sphere>(0.4), id);
103 
104  /* ps can be written to and set from message */
105  moveit_msgs::msg::PlanningScene ps_msg;
106  ps_msg.robot_state.is_diff = true;
107  EXPECT_TRUE(moveit::core::isEmpty(ps_msg));
108  ps->getPlanningSceneMsg(ps_msg);
109  ps->setPlanningSceneMsg(ps_msg);
110  EXPECT_EQ(ps_msg.world.collision_objects.size(), 1u);
111  EXPECT_EQ(ps_msg.world.collision_objects[0].id, "sphere");
112  EXPECT_TRUE(world.hasObject("sphere"));
113 
114  /* test diff scene on top of ps */
115  planning_scene::PlanningScenePtr next = ps->diff();
116  /* world is inherited from ps */
117  EXPECT_TRUE(next->getWorld()->hasObject("sphere"));
118 
119  /* object in overlay is only added in overlay */
120  next->getWorldNonConst()->addToObject("sphere_in_next_only", std::make_shared<const shapes::Sphere>(0.5), id);
121  EXPECT_EQ(next->getWorld()->size(), 2u);
122  EXPECT_EQ(ps->getWorld()->size(), 1u);
123 
124  /* the worlds used for collision detection contain one and two objects, respectively */
125  EXPECT_EQ(ps->getCollisionEnv()->getWorld()->size(), 1u);
126  EXPECT_EQ(ps->getCollisionEnvUnpadded()->getWorld()->size(), 1u);
127 
128  EXPECT_EQ(next->getCollisionEnv()->getWorld()->size(), 2u);
129  EXPECT_EQ(next->getCollisionEnvUnpadded()->getWorld()->size(), 2u);
130 
131  /* maintained diff contains only overlay object */
132  next->getPlanningSceneDiffMsg(ps_msg);
133  EXPECT_EQ(ps_msg.world.collision_objects.size(), 1u);
134 
135  /* copy ps to next and apply diff */
136  next->decoupleParent();
137  moveit_msgs::msg::PlanningScene ps_msg2;
138 
139  /* diff is empty now */
140  next->getPlanningSceneDiffMsg(ps_msg2);
141  EXPECT_EQ(ps_msg2.world.collision_objects.size(), 0u);
142 
143  /* next's world contains both objects */
144  next->getPlanningSceneMsg(ps_msg);
145  EXPECT_EQ(ps_msg.world.collision_objects.size(), 2u);
146  ps->setPlanningSceneMsg(ps_msg);
147  EXPECT_EQ(ps->getWorld()->size(), 2u);
148  EXPECT_EQ(ps->getCollisionEnv()->getWorld()->size(), 2u);
149  EXPECT_EQ(ps->getCollisionEnvUnpadded()->getWorld()->size(), 2u);
150 }
151 
152 TEST(PlanningScene, MakeAttachedDiff)
153 {
154  urdf::ModelInterfaceSharedPtr urdf_model = moveit::core::loadModelInterface("pr2");
155  srdf::ModelSharedPtr srdf_model = std::make_shared<srdf::Model>();
156  auto ps = std::make_shared<planning_scene::PlanningScene>(urdf_model, srdf_model);
157 
158  /* add a single object to ps's world */
159  collision_detection::World& world = *ps->getWorldNonConst();
160  Eigen::Isometry3d id = Eigen::Isometry3d::Identity();
161  world.addToObject("sphere", std::make_shared<const shapes::Sphere>(0.4), id);
162 
163  /* attach object in diff */
164  planning_scene::PlanningScenePtr attached_object_diff_scene = ps->diff();
165 
166  moveit_msgs::msg::AttachedCollisionObject att_obj;
167  att_obj.link_name = "r_wrist_roll_link";
168  att_obj.object.operation = moveit_msgs::msg::CollisionObject::ADD;
169  att_obj.object.id = "sphere";
170  attached_object_diff_scene->processAttachedCollisionObjectMsg(att_obj);
171 
172  /* object is not in world anymore */
173  EXPECT_EQ(attached_object_diff_scene->getWorld()->size(), 0u);
174  /* it became part of the robot state though */
175  EXPECT_TRUE(attached_object_diff_scene->getCurrentState().hasAttachedBody("sphere"));
176 
179  attached_object_diff_scene->checkCollision(req, res);
180  ps->checkCollision(req, res);
181 }
182 
183 TEST(PlanningScene, isStateValid)
184 {
185  moveit::core::RobotModelPtr robot_model = moveit::core::loadTestingRobotModel("pr2");
186  auto ps = std::make_shared<planning_scene::PlanningScene>(robot_model->getURDF(), robot_model->getSRDF());
187  moveit::core::RobotState current_state = ps->getCurrentState();
188  if (ps->isStateColliding(current_state, "left_arm"))
189  {
190  EXPECT_FALSE(ps->isStateValid(current_state, "left_arm"));
191  }
192 }
193 
194 TEST(PlanningScene, loadGoodSceneGeometryNewFormat)
195 {
196  moveit::core::RobotModelPtr robot_model = moveit::core::loadTestingRobotModel("pr2");
197  auto ps = std::make_shared<planning_scene::PlanningScene>(robot_model->getURDF(), robot_model->getSRDF());
198 
199  std::istringstream good_scene_geometry;
200  good_scene_geometry.str("foobar_scene\n"
201  "* foo\n"
202  "0 0 0\n"
203  "0 0 0 1\n"
204  "1\n"
205  "box\n"
206  "2.58 1.36 0.31\n"
207  "1.49257 1.00222 0.170051\n"
208  "0 0 4.16377e-05 1\n"
209  "0 0 1 0.3\n"
210  "0\n"
211  "* bar\n"
212  "0 0 0\n"
213  "0 0 0 1\n"
214  "1\n"
215  "cylinder\n"
216  "0.02 0.0001\n"
217  "0.453709 0.499136 0.355051\n"
218  "0 0 4.16377e-05 1\n"
219  "1 0 0 1\n"
220  "0\n"
221  ".\n");
222  EXPECT_TRUE(ps->loadGeometryFromStream(good_scene_geometry));
223  EXPECT_EQ(ps->getName(), "foobar_scene");
224  EXPECT_TRUE(ps->getWorld()->hasObject("foo"));
225  EXPECT_TRUE(ps->getWorld()->hasObject("bar"));
226  EXPECT_FALSE(ps->getWorld()->hasObject("baz")); // Sanity check.
227 }
228 
229 TEST(PlanningScene, loadGoodSceneGeometryOldFormat)
230 {
231  moveit::core::RobotModelPtr robot_model = moveit::core::loadTestingRobotModel("pr2");
232  auto ps = std::make_shared<planning_scene::PlanningScene>(robot_model->getURDF(), robot_model->getSRDF());
233 
234  std::istringstream good_scene_geometry;
235  good_scene_geometry.str("foobar_scene\n"
236  "* foo\n"
237  "2\n"
238  "box\n"
239  ".77 0.39 0.05\n"
240  "0 0 0.025\n"
241  "0 0 0 1\n"
242  "0.82 0.75 0.60 1\n"
243  "box\n"
244  ".77 0.39 0.05\n"
245  "0 0 1.445\n"
246  "0 0 0 1\n"
247  "0.82 0.75 0.60 1\n"
248  ".\n");
249  EXPECT_TRUE(ps->loadGeometryFromStream(good_scene_geometry));
250  EXPECT_EQ(ps->getName(), "foobar_scene");
251  EXPECT_TRUE(ps->getWorld()->hasObject("foo"));
252  EXPECT_FALSE(ps->getWorld()->hasObject("baz")); // Sanity check.
253 }
254 
255 TEST(PlanningScene, loadBadSceneGeometry)
256 {
257  moveit::core::RobotModelPtr robot_model = moveit::core::loadTestingRobotModel("pr2");
258  auto ps = std::make_shared<planning_scene::PlanningScene>(robot_model->getURDF(), robot_model->getSRDF());
259  std::istringstream empty_scene_geometry;
260 
261  // This should fail since there is no planning scene name and no end of geometry marker.
262  EXPECT_FALSE(ps->loadGeometryFromStream(empty_scene_geometry));
263 
264  std::istringstream malformed_scene_geometry;
265  malformed_scene_geometry.str("malformed_scene_geometry\n"
266  "* foo\n"
267  "0 0 0\n"
268  "0 0 0 1\n"
269  "1\n"
270  "box\n"
271  "2.58 1.36\n" /* Only two tokens; should be 3 */
272  "1.49257 1.00222 0.170051\n"
273  "0 0 4.16377e-05 1\n"
274  "0 0 1 0.3\n"
275  ".\n");
276  EXPECT_FALSE(ps->loadGeometryFromStream(malformed_scene_geometry));
277 }
278 
279 // Test the setting of a new collision detector type. For now, only FCL is available in MoveIt2.
280 // TODO(andyz): switch to a different type when one becomes available.
281 TEST(PlanningScene, switchCollisionDetectorType)
282 {
283  moveit::core::RobotModelPtr robot_model = moveit::core::loadTestingRobotModel("pr2");
284  auto ps = std::make_shared<planning_scene::PlanningScene>(robot_model->getURDF(), robot_model->getSRDF());
285  moveit::core::RobotState current_state = ps->getCurrentState();
286  if (ps->isStateColliding(current_state, "left_arm"))
287  {
288  EXPECT_FALSE(ps->isStateValid(current_state, "left_arm"));
289  }
290 
291  ps->allocateCollisionDetector(collision_detection::CollisionDetectorAllocatorFCL::create());
292  if (ps->isStateColliding(current_state, "left_arm"))
293  {
294  EXPECT_FALSE(ps->isStateValid(current_state, "left_arm"));
295  }
296 }
297 
298 TEST(PlanningScene, FailRetrievingNonExistentObject)
299 {
300  moveit::core::RobotModelPtr robot_model = moveit::core::loadTestingRobotModel("pr2");
301  planning_scene::PlanningScene ps{ robot_model };
302  moveit_msgs::msg::CollisionObject obj;
303  EXPECT_FALSE(ps.getCollisionObjectMsg(obj, "non_existent_object"));
304 }
305 
306 class CollisionDetectorTests : public testing::TestWithParam<const char*>
307 {
308 };
310 {
311  const std::string plugin_name = GetParam();
312  SCOPED_TRACE(plugin_name);
313 
314  urdf::ModelInterfaceSharedPtr urdf_model = moveit::core::loadModelInterface("pr2");
315  srdf::ModelSharedPtr srdf_model = std::make_shared<srdf::Model>();
316  // create parent scene
317  planning_scene::PlanningScenePtr parent = std::make_shared<planning_scene::PlanningScene>(urdf_model, srdf_model);
318 
320  if (!loader.activate(plugin_name, parent))
321  {
322 #if defined(GTEST_SKIP_)
323  GTEST_SKIP_("Failed to load collision plugin");
324 #else
325  return;
326 #endif
327  }
328 
329  // create child scene
330  planning_scene::PlanningScenePtr child = parent->diff();
331 
332  // create collision request variables
335  moveit::core::RobotState* state = new moveit::core::RobotState(child->getRobotModel());
336  state->setToDefaultValues();
337  state->update();
338 
339  // there should be no collision with the environment
340  res.clear();
341  parent->getCollisionEnv()->checkRobotCollision(req, res, *state, parent->getAllowedCollisionMatrix());
342  EXPECT_FALSE(res.collision);
343  res.clear();
344  child->getCollisionEnv()->checkRobotCollision(req, res, *state, child->getAllowedCollisionMatrix());
345  EXPECT_FALSE(res.collision);
346 
347  // create message to add a collision object at the world origin
348  moveit_msgs::msg::PlanningScene ps_msg;
349  ps_msg.is_diff = false;
350  moveit_msgs::msg::CollisionObject co;
351  co.header.frame_id = "base_link";
352  co.operation = moveit_msgs::msg::CollisionObject::ADD;
353  co.id = "box";
354  co.pose.orientation.w = 1.0;
355  {
356  shape_msgs::msg::SolidPrimitive sp;
357  sp.type = shape_msgs::msg::SolidPrimitive::BOX;
358  sp.dimensions = { 1., 1., 1. };
359  co.primitives.push_back(sp);
360  geometry_msgs::msg::Pose sp_pose;
361  sp_pose.orientation.w = 1.0;
362  co.primitive_poses.push_back(sp_pose);
363  }
364  ps_msg.world.collision_objects.push_back(co);
365 
366  // add object to the parent planning scene
367  parent->usePlanningSceneMsg(ps_msg);
368 
369  // the parent scene should be in collision
370  res.clear();
371  parent->getCollisionEnv()->checkRobotCollision(req, res, *state, parent->getAllowedCollisionMatrix());
372  EXPECT_TRUE(res.collision);
373 
374  // the child scene was not updated yet, so no collision
375  res.clear();
376  child->getCollisionEnv()->checkRobotCollision(req, res, *state, child->getAllowedCollisionMatrix());
377  EXPECT_FALSE(res.collision);
378 
379  // update the child scene
380  child->clearDiffs();
381 
382  // child and parent scene should be in collision
383  res.clear();
384  parent->getCollisionEnv()->checkRobotCollision(req, res, *state, parent->getAllowedCollisionMatrix());
385  EXPECT_TRUE(res.collision);
386  res.clear();
387  child->getCollisionEnv()->checkRobotCollision(req, res, *state, child->getAllowedCollisionMatrix());
388  EXPECT_TRUE(res.collision);
389 
390  child.reset();
391  parent.reset();
392 }
393 
394 // Returns a planning scene diff message
395 moveit_msgs::msg::PlanningScene create_planning_scene_diff(const planning_scene::PlanningScene& ps,
396  const std::string& object_name, const int8_t operation,
397  const bool attach_object = false,
398  const bool create_object = true)
399 {
400  // Helper function to create an object for RobotStateDiffBug
401  auto add_object = [](const std::string& object_name, const int8_t operation) {
402  moveit_msgs::msg::CollisionObject co;
403  co.header.frame_id = "panda_link0";
404  co.id = object_name;
405  co.operation = operation;
406  co.primitives.push_back([] {
407  shape_msgs::msg::SolidPrimitive primitive;
408  primitive.type = shape_msgs::msg::SolidPrimitive::SPHERE;
409  primitive.dimensions.push_back(1.0);
410  return primitive;
411  }());
412  co.primitive_poses.push_back([] {
413  geometry_msgs::msg::Pose pose;
414  pose.orientation.w = 1.0;
415  return pose;
416  }());
417  co.pose = co.primitive_poses[0];
418  return co;
419  };
420  // Helper function to create an attached object for RobotStateDiffBug
421  auto add_attached_object = [](const std::string& object_name, const int8_t operation) {
422  moveit_msgs::msg::AttachedCollisionObject aco;
423  aco.object.operation = operation;
424  aco.object.id = object_name;
425  aco.link_name = "panda_link0";
426  return aco;
427  };
428 
429  auto new_ps = ps.diff();
430  if ((operation == moveit_msgs::msg::CollisionObject::REMOVE && !attach_object) ||
431  (operation == moveit_msgs::msg::CollisionObject::ADD && create_object))
432  new_ps->processCollisionObjectMsg(add_object(object_name, operation));
433  if (attach_object)
434  new_ps->processAttachedCollisionObjectMsg(add_attached_object(object_name, operation));
435  moveit_msgs::msg::PlanningScene scene_msg;
436  new_ps->getPlanningSceneDiffMsg(scene_msg);
437  return scene_msg;
438 }
439 
440 // Returns collision objects names sorted alphabetically
442 {
443  std::vector<moveit_msgs::msg::CollisionObject> collision_objects;
444  ps.getCollisionObjectMsgs(collision_objects);
445  std::set<std::string> collision_objects_names;
446  for (const auto& collision_object : collision_objects)
447  collision_objects_names.emplace(collision_object.id);
448  return collision_objects_names;
449 }
450 
451 // Returns attached collision objects names sorted alphabetically
453 {
454  std::vector<moveit_msgs::msg::AttachedCollisionObject> collision_objects;
455  ps.getAttachedCollisionObjectMsgs(collision_objects);
456  std::set<std::string> collision_objects_names;
457  for (const auto& collision_object : collision_objects)
458  collision_objects_names.emplace(collision_object.object.id);
459  return collision_objects_names;
460 }
461 
462 TEST(PlanningScene, RobotStateDiffBug)
463 {
464  auto urdf_model = moveit::core::loadModelInterface("panda");
465  auto srdf_model = std::make_shared<srdf::Model>();
466  auto ps = std::make_shared<planning_scene::PlanningScene>(urdf_model, srdf_model);
467 
468  // Adding collision objects incrementally
469  {
470  const auto ps1 = create_planning_scene_diff(*ps, "object1", moveit_msgs::msg::CollisionObject::ADD);
471  const auto ps2 = create_planning_scene_diff(*ps, "object2", moveit_msgs::msg::CollisionObject::ADD);
472 
473  ps->usePlanningSceneMsg(ps1);
474  ps->usePlanningSceneMsg(ps2);
475 
476  EXPECT_EQ(get_collision_objects_names(*ps), (std::set<std::string>{ "object1", "object2" }));
477  }
478 
479  // Removing a collision object
480  {
481  const auto ps1 = create_planning_scene_diff(*ps, "object2", moveit_msgs::msg::CollisionObject::REMOVE);
482 
483  ps->usePlanningSceneMsg(ps1);
484  EXPECT_EQ(get_collision_objects_names(*ps), (std::set<std::string>{ "object1" }));
485  }
486 
487  // Adding attached collision objects incrementally
488  ps = std::make_shared<planning_scene::PlanningScene>(urdf_model, srdf_model);
489  {
490  const auto ps1 = create_planning_scene_diff(*ps, "object1", moveit_msgs::msg::CollisionObject::ADD, true);
491  const auto ps2 = create_planning_scene_diff(*ps, "object2", moveit_msgs::msg::CollisionObject::ADD, true);
492 
493  ps->usePlanningSceneMsg(ps1);
494  ps->usePlanningSceneMsg(ps2);
495  EXPECT_TRUE(get_collision_objects_names(*ps).empty());
496  EXPECT_EQ(get_attached_collision_objects_names(*ps), (std::set<std::string>{ "object1", "object2" }));
497  }
498 
499  // Removing an attached collision object
500  {
501  const auto ps1 = create_planning_scene_diff(*ps, "object2", moveit_msgs::msg::CollisionObject::REMOVE, true);
502  ps->usePlanningSceneMsg(ps1);
503 
504  EXPECT_EQ(get_collision_objects_names(*ps), (std::set<std::string>{ "object2" }));
505  EXPECT_EQ(get_attached_collision_objects_names(*ps), (std::set<std::string>{ "object1" }));
506  }
507 
508  // Turn an existing collision object into an attached object
509  {
510  const auto ps1 = create_planning_scene_diff(*ps, "object2", moveit_msgs::msg::CollisionObject::ADD, true, false);
511  ps->usePlanningSceneMsg(ps1);
512 
513  EXPECT_TRUE(get_collision_objects_names(*ps).empty());
514  EXPECT_EQ(get_attached_collision_objects_names(*ps), (std::set<std::string>{ "object1", "object2" }));
515  }
516 
517  // Removing an attached collision object completely
518  {
519  auto ps1 = ps->diff();
520  moveit_msgs::msg::CollisionObject co;
521  co.id = "object2";
522  co.operation = moveit_msgs::msg::CollisionObject::REMOVE;
523  moveit_msgs::msg::AttachedCollisionObject aco;
524  aco.object = co;
525 
526  ps1->processAttachedCollisionObjectMsg(aco); // detach
527  ps1->processCollisionObjectMsg(co); // and eventually remove object
528 
529  moveit_msgs::msg::PlanningScene msg;
530  ps1->getPlanningSceneDiffMsg(msg);
531  ps->usePlanningSceneMsg(msg);
532 
533  EXPECT_TRUE(get_collision_objects_names(*ps).empty());
534  EXPECT_EQ(get_attached_collision_objects_names(*ps), (std::set<std::string>{ "object1" }));
535  }
536 }
537 
538 #ifndef INSTANTIATE_TEST_SUITE_P // prior to gtest 1.10
539 #define INSTANTIATE_TEST_SUITE_P(...) INSTANTIATE_TEST_CASE_P(__VA_ARGS__)
540 #endif
541 
542 // instantiate parameterized tests for common collision plugins
543 INSTANTIATE_TEST_SUITE_P(PluginTests, CollisionDetectorTests, testing::Values("FCL", "Bullet"));
544 
545 int main(int argc, char** argv)
546 {
547  testing::InitGoogleTest(&argc, argv);
548  return RUN_ALL_TESTS();
549 }
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:126
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:71
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 ...
bool processCollisionObjectMsg(const moveit_msgs::msg::CollisionObject &object)
const std::string & getName() const
Get the name of the planning scene. This is empty by default.
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.
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,...
const moveit::core::RobotModelConstPtr & getRobotModel() const
Get the kinematic model for which the planning scene is maintained.
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 &robot_name)
Loads a robot from moveit_resources.
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(...)
std::set< std::string > get_collision_objects_names(const planning_scene::PlanningScene &ps)
std::set< std::string > get_attached_collision_objects_names(const planning_scene::PlanningScene &ps)
TEST_P(CollisionDetectorTests, ClearDiff)
moveit_msgs::msg::PlanningScene create_planning_scene_diff(const planning_scene::PlanningScene &ps, const std::string &object_name, const int8_t operation, const bool attach_object=false, const bool create_object=true)