52 #include <gtest/gtest.h> 
   93     psm_ = std::make_shared<planning_scene_monitor::PlanningSceneMonitor>(
"robot_description",
 
   95     psm_->startSceneMonitor(
"/move_group/monitored_planning_scene");
 
   96     psm_->requestPlanningSceneState();
 
  105     SCOPED_TRACE(
"synchronizeGeometryUpdate");
 
  106     std::promise<void> promise;
 
  107     std::future<void> future = promise.get_future();
 
  111       psm_->clearUpdateCallbacks();
 
  115     ASSERT_EQ(future.wait_for(std::chrono::seconds(5)), std::future_status::ready);
 
  120     SCOPED_TRACE(
"planAndMoveToPose");
 
  121     ASSERT_TRUE(
move_group_->setJointValueTarget(pose));
 
  127     SCOPED_TRACE(
"planAndMove");
 
  129     ASSERT_EQ(
move_group_->plan(my_plan), moveit::core::MoveItErrorCode::SUCCESS);
 
  130     ASSERT_EQ(
move_group_->move(), moveit::core::MoveItErrorCode::SUCCESS);
 
  133   void testEigenPose(
const Eigen::Isometry3d& expected, 
const Eigen::Isometry3d& actual)
 
  135     SCOPED_TRACE(
"testEigenPose");
 
  136     std::stringstream ss;
 
  137     ss << 
"expected: \n" << expected.matrix() << 
"\nactual: \n" << actual.matrix();
 
  141   void testPose(
const Eigen::Isometry3d& expected_pose)
 
  143     SCOPED_TRACE(
"testPose(const Eigen::Isometry3d&)");
 
  145     geometry_msgs::PoseStamped actual_pose_stamped = 
move_group_->getCurrentPose();
 
  146     Eigen::Isometry3d actual_pose;
 
  153   void testPose(
const geometry_msgs::Pose& expected_pose_msg)
 
  155     SCOPED_TRACE(
"testPose(const geometry_msgs::Pose&)");
 
  156     Eigen::Isometry3d expected_pose;
 
  163     SCOPED_TRACE(
"testJointPositions");
 
  166     std::vector<double> actual;
 
  167     move_group_->getCurrentState()->copyJointGroupPositions(joint_model_group, actual);
 
  168     ASSERT_EQ(expected.size(), actual.size());
 
  169     for (
size_t i = 0; i < actual.size(); ++i)
 
  171       double delta = std::abs(expected[i] - actual[i]);
 
  172       EXPECT_LT(delta, 
EPSILON) << 
"joint index: " << i << 
", plan: " << expected[i] << 
", result: " << actual[i];
 
  180   planning_scene_monitor::PlanningSceneMonitorPtr 
psm_;
 
  185   SCOPED_TRACE(
"PathConstraintCollisionTest");
 
  190   geometry_msgs::Pose start_pose;
 
  191   start_pose.orientation.w = 1.0;
 
  192   start_pose.position.x = 0.3;
 
  193   start_pose.position.y = 0.0;
 
  194   start_pose.position.z = 0.6;
 
  195   planAndMoveToPose(start_pose);
 
  199   geometry_msgs::Pose target_pose;
 
  200   target_pose.orientation.w = 1.0;
 
  201   target_pose.position.x = 0.3;
 
  202   target_pose.position.y = -0.3;
 
  203   target_pose.position.z = 0.6;
 
  206   Eigen::Isometry3d eigen_target_pose;
 
  210   move_group_->setPoseTarget(eigen_target_pose);
 
  211   geometry_msgs::PoseStamped set_target_pose = move_group_->getPoseTarget();
 
  212   Eigen::Isometry3d eigen_set_target_pose;
 
  213   tf2::fromMsg(set_target_pose.pose, eigen_set_target_pose);
 
  216   testEigenPose(eigen_target_pose, eigen_set_target_pose);
 
  220   moveit_msgs::OrientationConstraint ocm;
 
  221   ocm.link_name = move_group_->getEndEffectorLink();
 
  222   ocm.header.frame_id = move_group_->getPlanningFrame();
 
  223   ocm.orientation.w = 1.0;
 
  224   ocm.absolute_x_axis_tolerance = 0.1;
 
  225   ocm.absolute_y_axis_tolerance = 0.1;
 
  226   ocm.absolute_z_axis_tolerance = 0.1;
 
  228   moveit_msgs::Constraints test_constraints;
 
  229   test_constraints.orientation_constraints.push_back(ocm);
 
  230   move_group_->setPathConstraints(test_constraints);
 
  237   testPose(eigen_target_pose);
 
  240   move_group_->clearPathConstraints();
 
  243   move_group_->setNamedTarget(
"ready");
 
  251   moveit_msgs::CollisionObject collision_object;
 
  252   collision_object.header.frame_id = move_group_->getPlanningFrame();
 
  255   collision_object.id = 
"box1";
 
  258   shape_msgs::SolidPrimitive primitive;
 
  259   primitive.type = primitive.BOX;
 
  260   primitive.dimensions.resize(3);
 
  261   primitive.dimensions[0] = 0.1;
 
  262   primitive.dimensions[1] = 1.0;
 
  263   primitive.dimensions[2] = 1.0;
 
  266   geometry_msgs::Pose box_pose;
 
  267   box_pose.orientation.w = 1.0;
 
  268   box_pose.position.x = 0.5;
 
  269   box_pose.position.y = 0.0;
 
  270   box_pose.position.z = 0.5;
 
  272   collision_object.primitives.push_back(primitive);
 
  273   collision_object.primitive_poses.push_back(box_pose);
 
  274   collision_object.operation = collision_object.ADD;
 
  276   std::vector<moveit_msgs::CollisionObject> collision_objects;
 
  277   collision_objects.push_back(collision_object);
 
  280   synchronizeGeometryUpdate([&]() { planning_scene_interface_.addCollisionObjects(collision_objects); });
 
  283   synchronizeGeometryUpdate([&]() { 
EXPECT_TRUE(move_group_->attachObject(collision_object.id)); });
 
  284   EXPECT_EQ(planning_scene_interface_.getAttachedObjects().size(), std::size_t(1));
 
  285   synchronizeGeometryUpdate([&]() { 
EXPECT_TRUE(move_group_->detachObject(collision_object.id)); });
 
  286   EXPECT_EQ(planning_scene_interface_.getAttachedObjects().size(), std::size_t(0));
 
  289   const std::vector<std::string> object_ids = { collision_object.id };
 
  290   EXPECT_EQ(planning_scene_interface_.getObjects().size(), std::size_t(1));
 
  291   synchronizeGeometryUpdate([&]() { planning_scene_interface_.removeCollisionObjects(object_ids); });
 
  292   EXPECT_EQ(planning_scene_interface_.getObjects().size(), std::size_t(0));
 
  297   SCOPED_TRACE(
"CartPathTest");
 
  300   const geometry_msgs::PoseStamped start_pose = move_group_->getCurrentPose();
 
  302   std::vector<geometry_msgs::Pose> waypoints;
 
  303   waypoints.push_back(start_pose.pose);
 
  305   geometry_msgs::Pose target_waypoint = start_pose.pose;
 
  306   target_waypoint.position.z -= 0.2;
 
  307   waypoints.push_back(target_waypoint);  
 
  309   target_waypoint.position.y -= 0.2;
 
  310   waypoints.push_back(target_waypoint);  
 
  312   target_waypoint.position.z += 0.2;
 
  313   target_waypoint.position.y += 0.2;
 
  314   target_waypoint.position.x -= 0.2;
 
  315   waypoints.push_back(target_waypoint);  
 
  317   moveit_msgs::RobotTrajectory trajectory;
 
  318   const auto eef_step = 0.01;
 
  321   ASSERT_GE(
EPSILON + move_group_->computeCartesianPath(waypoints, eef_step, trajectory), 1.0);
 
  324   EXPECT_EQ(move_group_->execute(trajectory), moveit::core::MoveItErrorCode::SUCCESS);
 
  327   testPose(target_waypoint);
 
  332   SCOPED_TRACE(
"JointSpaceGoalTest");
 
  335   std::vector<double> plan_joint_positions;
 
  336   move_group_->getCurrentState()->copyJointGroupPositions(
 
  337       move_group_->getCurrentState()->getJointModelGroup(
PLANNING_GROUP), plan_joint_positions);
 
  340   ASSERT_EQ(plan_joint_positions.size(), std::size_t(7));
 
  341   plan_joint_positions = { 1.2, -1.0, -0.1, -2.4, 0.0, 1.5, 0.6 };
 
  342   move_group_->setJointValueTarget(plan_joint_positions);
 
  348   testJointPositions(plan_joint_positions);
 
  353   move_group_->setPoseReferenceFrame(
"world");
 
  354   move_group_->setEndEffectorLink(
"panda_hand");
 
  355   geometry_msgs::Pose pose;
 
  356   pose.position.x = 0.417;
 
  357   pose.position.y = 0.240;
 
  358   pose.position.z = 0.532;
 
  359   pose.orientation.w = 1.0;
 
  360   EXPECT_TRUE(move_group_->setJointValueTarget(pose));
 
  363 int main(
int argc, 
char** argv)
 
  365   ros::init(argc, argv, 
"move_group_interface_cpp_test");
 
  366   testing::InitGoogleTest(&argc, argv);
 
  371   int result = RUN_ALL_TESTS();