37 #include <gtest/gtest.h> 
   42 #include <urdf_parser/urdf_parser.h> 
   46 #include <tf2_eigen/tf2_eigen.hpp> 
   52 TEST(PlanningScene, TestOneShapeObjectPose)
 
   55   srdf::ModelSharedPtr srdf_model = std::make_shared<srdf::Model>();
 
   58   const std::string object_name = 
"object";
 
   59   const Eigen::Isometry3d expected_transfrom = Eigen::Isometry3d::Identity() * Eigen::Translation3d(0.5, -0.25, 0.0);
 
   61   moveit_msgs::msg::CollisionObject co;
 
   62   co.header.frame_id = 
"base_footprint";
 
   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 };
 
   71   co.primitive_poses.push_back(tf2::toMsg(expected_transfrom));
 
   78 TEST(PlanningScene, LoadRestore)
 
   81   srdf::ModelSharedPtr srdf_model = std::make_shared<srdf::Model>();
 
   83   moveit_msgs::msg::PlanningScene ps_msg;
 
   85   EXPECT_EQ(ps.
getName(), ps_msg.name);
 
   86   EXPECT_EQ(ps.
getRobotModel()->getName(), ps_msg.robot_model_name);
 
   88   EXPECT_EQ(ps.
getName(), ps_msg.name);
 
   89   EXPECT_EQ(ps.
getRobotModel()->getName(), ps_msg.robot_model_name);
 
   92 TEST(PlanningScene, LoadRestoreDiff)
 
   95   srdf::ModelSharedPtr srdf_model = std::make_shared<srdf::Model>();
 
   96   auto ps = std::make_shared<planning_scene::PlanningScene>(urdf_model, srdf_model);
 
  101   Eigen::Isometry3d 
id = Eigen::Isometry3d::Identity();
 
  102   world.
addToObject(
"sphere", std::make_shared<const shapes::Sphere>(0.4), 
id);
 
  105   moveit_msgs::msg::PlanningScene ps_msg;
 
  106   ps_msg.robot_state.is_diff = 
true;
 
  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");
 
  115   planning_scene::PlanningScenePtr next = ps->diff();
 
  117   EXPECT_TRUE(next->getWorld()->hasObject(
"sphere"));
 
  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);
 
  125   EXPECT_EQ(ps->getCollisionEnv()->getWorld()->size(), 1u);
 
  126   EXPECT_EQ(ps->getCollisionEnvUnpadded()->getWorld()->size(), 1u);
 
  128   EXPECT_EQ(next->getCollisionEnv()->getWorld()->size(), 2u);
 
  129   EXPECT_EQ(next->getCollisionEnvUnpadded()->getWorld()->size(), 2u);
 
  132   next->getPlanningSceneDiffMsg(ps_msg);
 
  133   EXPECT_EQ(ps_msg.world.collision_objects.size(), 1u);
 
  136   next->decoupleParent();
 
  137   moveit_msgs::msg::PlanningScene ps_msg2;
 
  140   next->getPlanningSceneDiffMsg(ps_msg2);
 
  141   EXPECT_EQ(ps_msg2.world.collision_objects.size(), 0u);
 
  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);
 
  152 TEST(PlanningScene, MakeAttachedDiff)
 
  155   srdf::ModelSharedPtr srdf_model = std::make_shared<srdf::Model>();
 
  156   auto ps = std::make_shared<planning_scene::PlanningScene>(urdf_model, srdf_model);
 
  160   Eigen::Isometry3d 
id = Eigen::Isometry3d::Identity();
 
  161   world.
addToObject(
"sphere", std::make_shared<const shapes::Sphere>(0.4), 
id);
 
  164   planning_scene::PlanningScenePtr attached_object_diff_scene = ps->diff();
 
  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);
 
  173   EXPECT_EQ(attached_object_diff_scene->getWorld()->size(), 0u);
 
  175   EXPECT_TRUE(attached_object_diff_scene->getCurrentState().hasAttachedBody(
"sphere"));
 
  179   attached_object_diff_scene->checkCollision(req, res);
 
  180   ps->checkCollision(req, res);
 
  183 TEST(PlanningScene, isStateValid)
 
  186   auto ps = std::make_shared<planning_scene::PlanningScene>(robot_model->getURDF(), robot_model->getSRDF());
 
  188   if (ps->isStateColliding(current_state, 
"left_arm"))
 
  190     EXPECT_FALSE(ps->isStateValid(current_state, 
"left_arm"));
 
  194 TEST(PlanningScene, loadGoodSceneGeometryNewFormat)
 
  197   auto ps = std::make_shared<planning_scene::PlanningScene>(robot_model->getURDF(), robot_model->getSRDF());
 
  199   std::istringstream good_scene_geometry;
 
  200   good_scene_geometry.str(
"foobar_scene\n" 
  207                           "1.49257 1.00222 0.170051\n" 
  208                           "0 0 4.16377e-05 1\n" 
  217                           "0.453709 0.499136 0.355051\n" 
  218                           "0 0 4.16377e-05 1\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"));  
 
  229 TEST(PlanningScene, loadGoodSceneGeometryOldFormat)
 
  232   auto ps = std::make_shared<planning_scene::PlanningScene>(robot_model->getURDF(), robot_model->getSRDF());
 
  234   std::istringstream good_scene_geometry;
 
  235   good_scene_geometry.str(
"foobar_scene\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"));  
 
  255 TEST(PlanningScene, loadBadSceneGeometry)
 
  258   auto ps = std::make_shared<planning_scene::PlanningScene>(robot_model->getURDF(), robot_model->getSRDF());
 
  259   std::istringstream empty_scene_geometry;
 
  262   EXPECT_FALSE(ps->loadGeometryFromStream(empty_scene_geometry));
 
  264   std::istringstream malformed_scene_geometry;
 
  265   malformed_scene_geometry.str(
"malformed_scene_geometry\n" 
  272                                "1.49257 1.00222 0.170051\n" 
  273                                "0 0 4.16377e-05 1\n" 
  276   EXPECT_FALSE(ps->loadGeometryFromStream(malformed_scene_geometry));
 
  281 TEST(PlanningScene, switchCollisionDetectorType)
 
  284   auto ps = std::make_shared<planning_scene::PlanningScene>(robot_model->getURDF(), robot_model->getSRDF());
 
  286   if (ps->isStateColliding(current_state, 
"left_arm"))
 
  288     EXPECT_FALSE(ps->isStateValid(current_state, 
"left_arm"));
 
  292   if (ps->isStateColliding(current_state, 
"left_arm"))
 
  294     EXPECT_FALSE(ps->isStateValid(current_state, 
"left_arm"));
 
  298 TEST(PlanningScene, FailRetrievingNonExistentObject)
 
  302   moveit_msgs::msg::CollisionObject obj;
 
  303   EXPECT_FALSE(ps.getCollisionObjectMsg(obj, 
"non_existent_object"));
 
  311   const std::string plugin_name = GetParam();
 
  312   SCOPED_TRACE(plugin_name);
 
  315   srdf::ModelSharedPtr srdf_model = std::make_shared<srdf::Model>();
 
  317   planning_scene::PlanningScenePtr parent = std::make_shared<planning_scene::PlanningScene>(urdf_model, srdf_model);
 
  320   if (!loader.
activate(plugin_name, parent))
 
  322 #if defined(GTEST_SKIP_) 
  323     GTEST_SKIP_(
"Failed to load collision plugin");
 
  330   planning_scene::PlanningScenePtr child = parent->diff();
 
  341   parent->getCollisionEnv()->checkRobotCollision(req, res, *state, parent->getAllowedCollisionMatrix());
 
  344   child->getCollisionEnv()->checkRobotCollision(req, res, *state, child->getAllowedCollisionMatrix());
 
  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;
 
  354   co.pose.orientation.w = 1.0;
 
  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);
 
  364   ps_msg.world.collision_objects.push_back(co);
 
  367   parent->usePlanningSceneMsg(ps_msg);
 
  371   parent->getCollisionEnv()->checkRobotCollision(req, res, *state, parent->getAllowedCollisionMatrix());
 
  376   child->getCollisionEnv()->checkRobotCollision(req, res, *state, child->getAllowedCollisionMatrix());
 
  384   parent->getCollisionEnv()->checkRobotCollision(req, res, *state, parent->getAllowedCollisionMatrix());
 
  387   child->getCollisionEnv()->checkRobotCollision(req, res, *state, child->getAllowedCollisionMatrix());
 
  396                                                            const std::string& object_name, 
const int8_t operation,
 
  397                                                            const bool attach_object = 
false,
 
  398                                                            const bool create_object = 
true)
 
  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";
 
  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);
 
  412     co.primitive_poses.push_back([] {
 
  413       geometry_msgs::msg::Pose pose;
 
  414       pose.orientation.w = 1.0;
 
  417     co.pose = co.primitive_poses[0];
 
  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";
 
  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));
 
  434     new_ps->processAttachedCollisionObjectMsg(add_attached_object(object_name, operation));
 
  435   moveit_msgs::msg::PlanningScene scene_msg;
 
  436   new_ps->getPlanningSceneDiffMsg(scene_msg);
 
  443   std::vector<moveit_msgs::msg::CollisionObject> 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;
 
  454   std::vector<moveit_msgs::msg::AttachedCollisionObject> 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;
 
  462 TEST(PlanningScene, RobotStateDiffBug)
 
  465   auto srdf_model = std::make_shared<srdf::Model>();
 
  466   auto ps = std::make_shared<planning_scene::PlanningScene>(urdf_model, srdf_model);
 
  473     ps->usePlanningSceneMsg(ps1);
 
  474     ps->usePlanningSceneMsg(ps2);
 
  483     ps->usePlanningSceneMsg(ps1);
 
  488   ps = std::make_shared<planning_scene::PlanningScene>(urdf_model, srdf_model);
 
  493     ps->usePlanningSceneMsg(ps1);
 
  494     ps->usePlanningSceneMsg(ps2);
 
  502     ps->usePlanningSceneMsg(ps1);
 
  511     ps->usePlanningSceneMsg(ps1);
 
  519     auto ps1 = ps->diff();
 
  520     moveit_msgs::msg::CollisionObject co;
 
  522     co.operation = moveit_msgs::msg::CollisionObject::REMOVE;
 
  523     moveit_msgs::msg::AttachedCollisionObject aco;
 
  526     ps1->processAttachedCollisionObjectMsg(aco);  
 
  527     ps1->processCollisionObjectMsg(co);           
 
  529     moveit_msgs::msg::PlanningScene msg;
 
  530     ps1->getPlanningSceneDiffMsg(msg);
 
  531     ps->usePlanningSceneMsg(msg);
 
  538 TEST(PlanningScene, UpdateACMAfterObjectRemoval)
 
  541   auto ps = std::make_shared<planning_scene::PlanningScene>(robot_model);
 
  543   const auto object_name = 
"object";
 
  546   collision_request.
verbose = 
true;
 
  549   auto add_object = [&] {
 
  551     ps->usePlanningSceneMsg(ps1);
 
  556   auto attach_object = [&] {
 
  558     ps->usePlanningSceneMsg(ps1);
 
  563   auto detach_object = [&] {
 
  565     ps->usePlanningSceneMsg(ps1);
 
  570   auto modify_acm = [&] {
 
  572     acm.
setEntry(object_name, ps->getRobotModel()->getJointModelGroup(
"hand")->getLinkModelNamesWithCollisionGeometry(),
 
  574     EXPECT_TRUE(ps->getAllowedCollisionMatrix().hasEntry(object_name));
 
  578   auto check_collision = [&] {
 
  580     ps->checkCollision(collision_request, res);
 
  586   EXPECT_TRUE(check_collision());
 
  588   EXPECT_FALSE(check_collision());
 
  591   EXPECT_FALSE(check_collision());
 
  593   EXPECT_FALSE(check_collision());
 
  596     ps->usePlanningSceneMsg(ps1);
 
  598     EXPECT_FALSE(ps->getAllowedCollisionMatrix().hasEntry(object_name));
 
  604   EXPECT_TRUE(check_collision());
 
  606   EXPECT_FALSE(check_collision());
 
  607   ps->removeAllCollisionObjects();
 
  609   EXPECT_FALSE(ps->getAllowedCollisionMatrix().hasEntry(object_name));
 
  612 #ifndef INSTANTIATE_TEST_SUITE_P   
  613 #define INSTANTIATE_TEST_SUITE_P(...) INSTANTIATE_TEST_CASE_P(__VA_ARGS__) 
  619 int main(
int argc, 
char** argv)
 
  621   testing::InitGoogleTest(&argc, argv);
 
  622   return RUN_ALL_TESTS();
 
Definition of a structure for the allowed collision matrix. All elements in the collision world are r...
 
void setEntry(const std::string &name1, const std::string &name2, bool allowed)
Set an entry corresponding to a pair of elements.
 
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 ...
 
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.
 
std::string group_name
The group name to check collisions for (optional; if empty, assume the complete robot)
 
bool verbose
Flag indicating whether information about detected collisions should be reported.
 
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)