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>
41 #include <urdf_parser/urdf_parser.h>
42 #include <fstream>
43 #include <sstream>
44 #include <string>
45 #include <boost/filesystem/path.hpp>
46 #include <ros/package.h>
48 #include <octomap/octomap.h>
49 
52 
53 TEST(PlanningScene, LoadRestore)
54 {
55  urdf::ModelInterfaceSharedPtr urdf_model = moveit::core::loadModelInterface("pr2");
56  auto srdf_model = std::make_shared<srdf::Model>();
57  planning_scene::PlanningScene ps(urdf_model, srdf_model);
58  moveit_msgs::PlanningScene ps_msg;
59  ps.getPlanningSceneMsg(ps_msg);
60  EXPECT_EQ(ps.getName(), ps_msg.name);
61  EXPECT_EQ(ps.getRobotModel()->getName(), ps_msg.robot_model_name);
62  ps.setPlanningSceneMsg(ps_msg);
63  EXPECT_EQ(ps.getName(), ps_msg.name);
64  EXPECT_EQ(ps.getRobotModel()->getName(), ps_msg.robot_model_name);
65 }
66 
67 TEST(PlanningScene, LoadOctomap)
68 {
69  urdf::ModelInterfaceSharedPtr urdf_model = moveit::core::loadModelInterface("pr2");
70  auto srdf_model = std::make_shared<srdf::Model>();
71  planning_scene::PlanningScene ps(urdf_model, srdf_model);
72 
73  { // check octomap before doing any operations on it
74  octomap_msgs::OctomapWithPose msg;
75  ps.getOctomapMsg(msg);
76  EXPECT_TRUE(msg.octomap.id.empty());
77  EXPECT_TRUE(msg.octomap.data.empty());
78  }
79 
80  { // fill PlanningScene's octomap
82  octomap::point3d origin(0, 0, 0);
83  octomap::point3d end(0, 1, 2);
84  octomap.insertRay(origin, end);
85 
86  // populate PlanningScene with octomap
87  moveit_msgs::PlanningScene msg;
88  msg.is_diff = true;
89  octomap_msgs::fullMapToMsg(octomap, msg.world.octomap.octomap);
91 
92  // validate octomap message
93  octomap_msgs::OctomapWithPose octomap_msg;
94  ps.getOctomapMsg(octomap_msg);
95  EXPECT_EQ(octomap_msg.octomap.id, "OcTree");
96  EXPECT_EQ(octomap_msg.octomap.data.size(), msg.world.octomap.octomap.data.size());
97  }
98 
99  { // verify that a PlanningScene msg with an empty octomap id does not modify the octomap
100  // create planning scene
101  moveit_msgs::PlanningScene msg;
102  msg.is_diff = true;
103  ps.setPlanningSceneDiffMsg(msg);
104 
105  octomap_msgs::OctomapWithPose octomap_msg;
106  ps.getOctomapMsg(octomap_msg);
107  EXPECT_EQ(octomap_msg.octomap.id, "OcTree");
108  EXPECT_FALSE(octomap_msg.octomap.data.empty());
109  }
110 
111  { // check that a non-empty octomap id, but empty octomap will clear the octomap
112  moveit_msgs::PlanningScene msg;
113  msg.is_diff = true;
114  msg.world.octomap.octomap.id = "xxx";
115  ps.setPlanningSceneDiffMsg(msg);
116  EXPECT_FALSE(static_cast<bool>(ps.getWorld()->getObject(planning_scene::PlanningScene::OCTOMAP_NS)));
117  }
118 }
119 
120 TEST(PlanningScene, LoadRestoreDiff)
121 {
122  urdf::ModelInterfaceSharedPtr urdf_model = moveit::core::loadModelInterface("pr2");
123  auto srdf_model = std::make_shared<srdf::Model>();
124  auto ps = std::make_shared<planning_scene::PlanningScene>(urdf_model, srdf_model);
125 
126  collision_detection::World& world = *ps->getWorldNonConst();
127 
128  /* add one object to ps's world */
129  Eigen::Isometry3d id = Eigen::Isometry3d::Identity();
130  world.addToObject("sphere", shapes::ShapeConstPtr(new shapes::Sphere(0.4)), id);
131 
132  /* ps can be written to and set from message */
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");
140  EXPECT_TRUE(world.hasObject("sphere"));
141 
142  /* test diff scene on top of ps */
143  planning_scene::PlanningScenePtr next = ps->diff();
144  /* world is inherited from ps */
145  EXPECT_TRUE(next->getWorld()->hasObject("sphere"));
146 
147  /* object in overlay is only added in overlay */
148  next->getWorldNonConst()->addToObject("sphere_in_next_only", shapes::ShapeConstPtr(new shapes::Sphere(0.5)), id);
149  EXPECT_EQ(next->getWorld()->size(), 2u);
150  EXPECT_EQ(ps->getWorld()->size(), 1u);
151 
152  /* the worlds used for collision detection contain one and two objects, respectively */
153  EXPECT_EQ(ps->getCollisionEnv()->getWorld()->size(), 1u);
154  EXPECT_EQ(ps->getCollisionEnvUnpadded()->getWorld()->size(), 1u);
155 
156  EXPECT_EQ(next->getCollisionEnv()->getWorld()->size(), 2u);
157  EXPECT_EQ(next->getCollisionEnvUnpadded()->getWorld()->size(), 2u);
158 
159  /* maintained diff contains only overlay object */
160  next->getPlanningSceneDiffMsg(ps_msg);
161  EXPECT_EQ(ps_msg.world.collision_objects.size(), 1u);
162 
163  /* copy ps to next and apply diff */
164  next->decoupleParent();
165  moveit_msgs::PlanningScene ps_msg2;
166 
167  /* diff is empty now */
168  next->getPlanningSceneDiffMsg(ps_msg2);
169  EXPECT_EQ(ps_msg2.world.collision_objects.size(), 0u);
170 
171  /* next's world contains both objects */
172  next->getPlanningSceneMsg(ps_msg);
173  EXPECT_EQ(ps_msg.world.collision_objects.size(), 2u);
174  ps->setPlanningSceneMsg(ps_msg);
175  EXPECT_EQ(ps->getWorld()->size(), 2u);
176  EXPECT_EQ(ps->getCollisionEnv()->getWorld()->size(), 2u);
177  EXPECT_EQ(ps->getCollisionEnvUnpadded()->getWorld()->size(), 2u);
178 }
179 
180 TEST(PlanningScene, MakeAttachedDiff)
181 {
182  urdf::ModelInterfaceSharedPtr urdf_model = moveit::core::loadModelInterface("pr2");
183  auto srdf_model = std::make_shared<srdf::Model>();
184  auto ps = std::make_shared<planning_scene::PlanningScene>(urdf_model, srdf_model);
185 
186  /* add a single object to ps's world */
187  collision_detection::World& world = *ps->getWorldNonConst();
188  Eigen::Isometry3d id = Eigen::Isometry3d::Identity();
189  world.addToObject("sphere", shapes::ShapeConstPtr(new shapes::Sphere(0.4)), id);
190 
191  /* attach object in diff */
192  planning_scene::PlanningScenePtr attached_object_diff_scene = ps->diff();
193 
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);
199 
200  /* object is not in world anymore */
201  EXPECT_EQ(attached_object_diff_scene->getWorld()->size(), 0u);
202  /* it became part of the robot state though */
203  EXPECT_TRUE(attached_object_diff_scene->getCurrentState().hasAttachedBody("sphere"));
204 
207  attached_object_diff_scene->checkCollision(req, res);
208  ps->checkCollision(req, res);
209 }
210 
211 TEST(PlanningScene, isStateValid)
212 {
213  moveit::core::RobotModelPtr robot_model = moveit::core::loadTestingRobotModel("pr2");
214  auto ps = std::make_shared<planning_scene::PlanningScene>(robot_model->getURDF(), robot_model->getSRDF());
215  moveit::core::RobotState current_state = ps->getCurrentState();
216  if (ps->isStateColliding(current_state, "left_arm"))
217  {
218  EXPECT_FALSE(ps->isStateValid(current_state, "left_arm"));
219  }
220 }
221 
222 TEST(PlanningScene, loadGoodSceneGeometryNewFormat)
223 {
224  moveit::core::RobotModelPtr robot_model = moveit::core::loadTestingRobotModel("pr2");
225  auto ps = std::make_shared<planning_scene::PlanningScene>(robot_model->getURDF(), robot_model->getSRDF());
226 
227  std::istringstream good_scene_geometry;
228  good_scene_geometry.str("foobar_scene\n"
229  "* foo\n"
230  "0 0 0\n"
231  "0 0 0 1\n"
232  "1\n"
233  "box\n"
234  "2.58 1.36 0.31\n"
235  "1.49257 1.00222 0.170051\n"
236  "0 0 4.16377e-05 1\n"
237  "0 0 1 0.3\n"
238  "0\n"
239  "* bar\n"
240  "0 0 0\n"
241  "0 0 0 1\n"
242  "1\n"
243  "cylinder\n"
244  "0.02 0.0001\n"
245  "0.453709 0.499136 0.355051\n"
246  "0 0 4.16377e-05 1\n"
247  "1 0 0 1\n"
248  "0\n"
249  ".\n");
250  EXPECT_TRUE(ps->loadGeometryFromStream(good_scene_geometry));
251  EXPECT_EQ(ps->getName(), "foobar_scene");
252  EXPECT_TRUE(ps->getWorld()->hasObject("foo"));
253  EXPECT_TRUE(ps->getWorld()->hasObject("bar"));
254  EXPECT_FALSE(ps->getWorld()->hasObject("baz")); // Sanity check.
255 }
256 
257 TEST(PlanningScene, loadGoodSceneGeometryOldFormat)
258 {
259  moveit::core::RobotModelPtr robot_model = moveit::core::loadTestingRobotModel("pr2");
260  auto ps = std::make_shared<planning_scene::PlanningScene>(robot_model->getURDF(), robot_model->getSRDF());
261 
262  std::istringstream good_scene_geometry;
263  good_scene_geometry.str("foobar_scene\n"
264  "* foo\n"
265  "2\n"
266  "box\n"
267  ".77 0.39 0.05\n"
268  "0 0 0.025\n"
269  "0 0 0 1\n"
270  "0.82 0.75 0.60 1\n"
271  "box\n"
272  ".77 0.39 0.05\n"
273  "0 0 1.445\n"
274  "0 0 0 1\n"
275  "0.82 0.75 0.60 1\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_FALSE(ps->getWorld()->hasObject("baz")); // Sanity check.
281 }
282 
283 TEST(PlanningScene, loadBadSceneGeometry)
284 {
285  moveit::core::RobotModelPtr robot_model = moveit::core::loadTestingRobotModel("pr2");
286  auto ps = std::make_shared<planning_scene::PlanningScene>(robot_model->getURDF(), robot_model->getSRDF());
287  std::istringstream empty_scene_geometry;
288 
289  // This should fail since there is no planning scene name and no end of geometry marker.
290  EXPECT_FALSE(ps->loadGeometryFromStream(empty_scene_geometry));
291 
292  std::istringstream malformed_scene_geometry;
293  malformed_scene_geometry.str("malformed_scene_geometry\n"
294  "* foo\n"
295  "0 0 0\n"
296  "0 0 0 1\n"
297  "1\n"
298  "box\n"
299  "2.58 1.36\n" /* Only two tokens; should be 3 */
300  "1.49257 1.00222 0.170051\n"
301  "0 0 4.16377e-05 1\n"
302  "0 0 1 0.3\n"
303  ".\n");
304  EXPECT_FALSE(ps->loadGeometryFromStream(malformed_scene_geometry));
305 }
306 
307 TEST(PlanningScene, FailRetrievingNonExistentObject)
308 {
309  moveit::core::RobotModelPtr robot_model = moveit::core::loadTestingRobotModel("pr2");
311  moveit_msgs::CollisionObject obj;
312  EXPECT_FALSE(ps.getCollisionObjectMsg(obj, "non_existent_object"));
313 }
314 
315 class CollisionDetectorTests : public testing::TestWithParam<const char*>
316 {
317 };
319 {
320  const std::string plugin_name = GetParam();
321  SCOPED_TRACE(plugin_name);
322 
323  urdf::ModelInterfaceSharedPtr urdf_model = moveit::core::loadModelInterface("pr2");
324  auto srdf_model = std::make_shared<srdf::Model>();
325  // create parent scene
326  planning_scene::PlanningScenePtr parent = std::make_shared<planning_scene::PlanningScene>(urdf_model, srdf_model);
327 
329  if (!loader.activate(plugin_name, parent, true))
330  {
331 #if defined(GTEST_SKIP_)
332  GTEST_SKIP_("Failed to load collision plugin");
333 #else
334  return;
335 #endif
336  }
337 
338  // create child scene
339  planning_scene::PlanningScenePtr child = parent->diff();
340 
341  // create collision request variables
344  moveit::core::RobotState* state = new moveit::core::RobotState(child->getRobotModel());
345  state->setToDefaultValues();
346  state->update();
347 
348  // there should be no collision with the environment
349  res.clear();
350  parent->getCollisionEnv()->checkRobotCollision(req, res, *state, parent->getAllowedCollisionMatrix());
351  EXPECT_FALSE(res.collision);
352  res.clear();
353  child->getCollisionEnv()->checkRobotCollision(req, res, *state, child->getAllowedCollisionMatrix());
354  EXPECT_FALSE(res.collision);
355 
356  // create message to add a collision object at the world origin
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;
362  co.id = "box";
363  co.pose.orientation.w = 1.0;
364  {
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);
372  }
373  ps_msg.world.collision_objects.push_back(co);
374 
375  // add object to the parent planning scene
376  parent->usePlanningSceneMsg(ps_msg);
377 
378  // the parent scene should be in collision
379  res.clear();
380  parent->getCollisionEnv()->checkRobotCollision(req, res, *state, parent->getAllowedCollisionMatrix());
381  EXPECT_TRUE(res.collision);
382 
383  // the child scene was not updated yet, so no collision
384  res.clear();
385  child->getCollisionEnv()->checkRobotCollision(req, res, *state, child->getAllowedCollisionMatrix());
386  EXPECT_FALSE(res.collision);
387 
388  // update the child scene
389  child->clearDiffs();
390 
391  // child and parent scene should be in collision
392  res.clear();
393  parent->getCollisionEnv()->checkRobotCollision(req, res, *state, parent->getAllowedCollisionMatrix());
394  EXPECT_TRUE(res.collision);
395  res.clear();
396  child->getCollisionEnv()->checkRobotCollision(req, res, *state, child->getAllowedCollisionMatrix());
397  EXPECT_TRUE(res.collision);
398 
399  child.reset();
400  parent.reset();
401 }
402 
403 // Returns a planning scene diff message
404 moveit_msgs::PlanningScene create_planning_scene_diff(const planning_scene::PlanningScene& ps,
405  const std::string& object_name, const int8_t operation,
406  const bool attach_object = false, const bool create_object = true)
407 {
408  // Helper function to create an object for RobotStateDiffBug
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";
412  co.id = object_name;
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);
418  return primitive;
419  }());
420  co.primitive_poses.push_back([] {
421  geometry_msgs::Pose pose;
422  pose.orientation.w = 1.0;
423  return pose;
424  }());
425  co.pose = co.primitive_poses[0];
426  return co;
427  };
428  // Helper function to create an attached object for RobotStateDiffBug
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";
434  return aco;
435  };
436 
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));
441  if (attach_object)
442  new_ps->processAttachedCollisionObjectMsg(add_attached_object(object_name, operation));
443  moveit_msgs::PlanningScene scene_msg;
444  new_ps->getPlanningSceneDiffMsg(scene_msg);
445  return scene_msg;
446 }
447 
448 // Returns collision objects names sorted alphabetically
450 {
451  std::vector<moveit_msgs::CollisionObject> collision_objects;
452  ps.getCollisionObjectMsgs(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;
457 }
458 
459 // Returns attached collision objects names sorted alphabetically
461 {
462  std::vector<moveit_msgs::AttachedCollisionObject> collision_objects;
463  ps.getAttachedCollisionObjectMsgs(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;
468 }
469 
470 TEST(PlanningScene, RobotStateDiffBug)
471 {
472  auto urdf_model = moveit::core::loadModelInterface("panda");
473  auto srdf_model = std::make_shared<srdf::Model>();
474  auto ps = std::make_shared<planning_scene::PlanningScene>(urdf_model, srdf_model);
475 
476  // Adding collision objects incrementally
477  {
478  const auto ps1 = create_planning_scene_diff(*ps, "object1", moveit_msgs::CollisionObject::ADD);
479  const auto ps2 = create_planning_scene_diff(*ps, "object2", moveit_msgs::CollisionObject::ADD);
480 
481  ps->usePlanningSceneMsg(ps1);
482  ps->usePlanningSceneMsg(ps2);
483  EXPECT_EQ(get_collision_objects_names(*ps), (std::set<std::string>{ "object1", "object2" }));
484  }
485 
486  // Removing a collision object
487  {
488  const auto ps1 = create_planning_scene_diff(*ps, "object2", moveit_msgs::CollisionObject::REMOVE);
489 
490  ps->usePlanningSceneMsg(ps1);
491  EXPECT_EQ(get_collision_objects_names(*ps), (std::set<std::string>{ "object1" }));
492  }
493 
494  // Adding attached collision objects incrementally
495  ps = std::make_shared<planning_scene::PlanningScene>(urdf_model, srdf_model);
496  {
497  const auto ps1 = create_planning_scene_diff(*ps, "object1", moveit_msgs::CollisionObject::ADD, true);
498  const auto ps2 = create_planning_scene_diff(*ps, "object2", moveit_msgs::CollisionObject::ADD, true);
499 
500  ps->usePlanningSceneMsg(ps1);
501  ps->usePlanningSceneMsg(ps2);
503  EXPECT_EQ(get_attached_collision_objects_names(*ps), (std::set<std::string>{ "object1", "object2" }));
504  }
505 
506  // Removing an attached collision object
507  {
508  const auto ps1 = create_planning_scene_diff(*ps, "object2", moveit_msgs::CollisionObject::REMOVE, true);
509  ps->usePlanningSceneMsg(ps1);
510 
511  EXPECT_EQ(get_collision_objects_names(*ps), (std::set<std::string>{ "object2" }));
512  EXPECT_EQ(get_attached_collision_objects_names(*ps), (std::set<std::string>{ "object1" }));
513  }
514 
515  // Turn an existing collision object into an attached object
516  {
517  const auto ps1 = create_planning_scene_diff(*ps, "object2", moveit_msgs::CollisionObject::ADD, true, false);
518  ps->usePlanningSceneMsg(ps1);
519 
521  EXPECT_EQ(get_attached_collision_objects_names(*ps), (std::set<std::string>{ "object1", "object2" }));
522  }
523 
524  // Removing an attached collision object completely
525  {
526  auto ps1 = ps->diff();
527  moveit_msgs::CollisionObject co;
528  co.id = "object2";
529  co.operation = moveit_msgs::CollisionObject::REMOVE;
530  moveit_msgs::AttachedCollisionObject aco;
531  aco.object = co;
532 
533  ps1->processAttachedCollisionObjectMsg(aco); // detach
534  ps1->processCollisionObjectMsg(co); // and eventually remove object
535 
536  moveit_msgs::PlanningScene msg;
537  ps1->getPlanningSceneDiffMsg(msg);
538  ps->usePlanningSceneMsg(msg);
539 
541  EXPECT_EQ(get_attached_collision_objects_names(*ps), (std::set<std::string>{ "object1" }));
542  }
543 }
544 
545 #ifndef INSTANTIATE_TEST_SUITE_P // prior to gtest 1.10
546 #define INSTANTIATE_TEST_SUITE_P(...) INSTANTIATE_TEST_CASE_P(__VA_ARGS__)
547 #endif
548 
549 // instantiate parameterized tests for common collision plugins
550 INSTANTIATE_TEST_SUITE_P(PluginTests, CollisionDetectorTests, testing::Values("FCL", "Bullet"));
551 
552 int main(int argc, char** argv)
553 {
554  testing::InitGoogleTest(&argc, argv);
555  return RUN_ALL_TESTS();
556 }
get_collision_objects_names
std::set< std::string > get_collision_objects_names(const planning_scene::PlanningScene &ps)
Definition: test_planning_scene.cpp:449
moveit::core
Core components of MoveIt.
Definition: kinematics_base.h:83
octomap_msgs::fullMapToMsg
static bool fullMapToMsg(const OctomapT &octomap, Octomap &msg)
collision_detection::World::hasObject
bool hasObject(const std::string &object_id) const
Check if a particular object exists in the collision world.
Definition: world.cpp:155
main
int main(int argc, char **argv)
Definition: test_planning_scene.cpp:552
planning_scene::PlanningScene::getRobotModel
const moveit::core::RobotModelConstPtr & getRobotModel() const
Get the kinematic model for which the planning scene is maintained.
Definition: planning_scene.h:254
planning_scene::PlanningScene::getWorld
const collision_detection::WorldConstPtr & getWorld() const
Get the representation of the world.
Definition: planning_scene.h:397
planning_scene::PlanningScene::getCollisionObjectMsgs
void getCollisionObjectMsgs(std::vector< moveit_msgs::CollisionObject > &collision_objs) const
Construct a vector of messages (collision_objects) with the collision object data for all objects in ...
Definition: planning_scene.cpp:840
planning_scene.h
collision_detection::World
Maintain a representation of the environment.
Definition: world.h:59
moveit::core::RobotState
Representation of a robot's state. This includes position, velocity, acceleration and effort.
Definition: robot_state.h:155
obj
CollisionObject< S > * obj
collision_detection::CollisionRequest
Representation of a collision checking request.
Definition: include/moveit/collision_detection/collision_common.h:179
moveit::core::loadModelInterface
urdf::ModelInterfaceSharedPtr loadModelInterface(const std::string &robot_name)
Loads a URDF Model Interface from moveit_resources.
Definition: robot_model_test_utils.cpp:126
EXPECT_TRUE
#define EXPECT_TRUE(args)
octomath::Vector3
planning_scene::PlanningScene::getPlanningSceneMsg
void getPlanningSceneMsg(moveit_msgs::PlanningScene &scene) const
Construct a message (scene) with all the necessary data so that the scene can be later reconstructed ...
Definition: planning_scene.cpp:912
collision_detection::CollisionPluginCache
Definition: collision_plugin_cache.h:75
octomap::OcTree
planning_scene::PlanningScene::getAttachedCollisionObjectMsgs
void getAttachedCollisionObjectMsgs(std::vector< moveit_msgs::AttachedCollisionObject > &attached_collision_objs) const
Construct a vector of messages (attached_collision_objects) with the attached collision object data f...
Definition: planning_scene.cpp:868
collision_common.h
planning_scene::PlanningScene
This class maintains the representation of the environment as seen by a planning instance....
Definition: planning_scene.h:202
collision_detection::World::addToObject
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:100
moveit::core::RobotState::update
void update(bool force=false)
Update all transforms.
Definition: robot_state.cpp:729
collision_detection::CollisionPluginCache::activate
bool activate(const std::string &name, const planning_scene::PlanningScenePtr &scene, bool exclusive)
Activate a specific collision plugin for the given planning scene instance.
Definition: collision_plugin_cache.cpp:105
shapes::Sphere
collision_detection::CollisionResult
Representation of a collision checking result.
Definition: include/moveit/collision_detection/collision_common.h:382
get_attached_collision_objects_names
std::set< std::string > get_attached_collision_objects_names(const planning_scene::PlanningScene &ps)
Definition: test_planning_scene.cpp:460
moveit::core::RobotState::setToDefaultValues
void setToDefaultValues()
Set all joints to their default positions. The default position is 0, or if that is not within bounds...
Definition: robot_state.cpp:434
collision_plugin_cache.h
next
EndPoint * next[3]
package.h
planning_scene::PlanningScene::getName
const std::string & getName() const
Get the name of the planning scene. This is empty by default.
Definition: planning_scene.h:220
robot_model_test_utils.h
planning_scene::PlanningScene::setPlanningSceneDiffMsg
bool setPlanningSceneDiffMsg(const moveit_msgs::PlanningScene &scene)
Apply changes to this planning scene as diffs, even if the message itself is not marked as being a di...
Definition: planning_scene.cpp:1297
planning_scene::PlanningScene::setPlanningSceneMsg
bool setPlanningSceneMsg(const moveit_msgs::PlanningScene &scene)
Set this instance of a planning scene to be the same as the one serialized in the scene message,...
Definition: planning_scene.cpp:1351
create_planning_scene_diff
moveit_msgs::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)
Definition: test_planning_scene.cpp:404
planning_scene::PlanningScene::OCTOMAP_NS
static const MOVEIT_PLANNING_SCENE_EXPORT std::string OCTOMAP_NS
Definition: planning_scene.h:214
octomap.h
shapes::ShapeConstPtr
std::shared_ptr< const Shape > ShapeConstPtr
collision_detection::CollisionResult::collision
bool collision
True if collision was found, false otherwise.
Definition: include/moveit/collision_detection/collision_common.h:406
conversions.h
octomap
planning_scene::PlanningScene::getOctomapMsg
bool getOctomapMsg(octomap_msgs::OctomapWithPose &octomap) const
Construct a message (octomap) with the octomap data from the planning_scene.
Definition: planning_scene.cpp:876
CollisionDetectorTests
Definition: test_multi_threaded.cpp:69
collision_detection::CollisionResult::clear
EIGEN_MAKE_ALIGNED_OPERATOR_NEW void clear()
Clear a previously stored result.
Definition: include/moveit/collision_detection/collision_common.h:392
message_checks.h
EXPECT_EQ
#define EXPECT_EQ(a, b)
EXPECT_FALSE
#define EXPECT_FALSE(args)
planning_scene::PlanningScene::diff
PlanningScenePtr diff() const
Return a new child PlanningScene that uses this one as parent.
Definition: planning_scene.cpp:246
TEST_P
TEST_P(CollisionDetectorTests, ClearDiff)
Definition: test_planning_scene.cpp:318
moveit::core::loadTestingRobotModel
moveit::core::RobotModelPtr loadTestingRobotModel(const std::string &robot_name)
Loads a robot from moveit_resources.
Definition: robot_model_test_utils.cpp:117
INSTANTIATE_TEST_SUITE_P
#define INSTANTIATE_TEST_SUITE_P(...)
Definition: test_planning_scene.cpp:546
TEST
TEST(PlanningScene, LoadRestore)
Definition: test_planning_scene.cpp:53
moveit::core::isEmpty
bool isEmpty(const moveit_msgs::PlanningScene &msg)
Check if a message includes any information about a planning scene, or whether it is empty.
Definition: message_checks.cpp:107


moveit_core
Author(s): Ioan Sucan , Sachin Chitta , Acorn Pooley
autogenerated on Fri May 3 2024 02:28:41