50 #include <gtest/gtest.h> 
   70                     const std::string& end_effector_link)
 
   72   group.clearPoseTargets();
 
   73   group.setEndEffectorLink(end_effector_link);
 
   74   group.setStartStateToCurrentState();
 
   75   group.setPoseTarget(pose);
 
   78   if (
group.plan(myplan) && 
group.execute(myplan))
 
   83   ROS_WARN(
"Failed to perform motion.");
 
   89                        const std::string& end_effector_link)
 
   91   group.clearPoseTargets();
 
   92   group.setEndEffectorLink(end_effector_link);
 
   93   group.setStartStateToCurrentState();
 
   94   std::vector<double> initial_joint_position({ 0, -
TAU / 8, 0, -3 * 
TAU / 8, 0, 
TAU / 4, 
TAU / 8 });
 
   95   group.setJointValueTarget(initial_joint_position);
 
   97   if (!
group.plan(myplan) || !
group.execute(myplan))
 
   99     ROS_WARN(
"Failed to move to initial joint positions");
 
  103   std::vector<geometry_msgs::Pose> waypoints;
 
  104   waypoints.push_back(pose.pose);
 
  105   moveit_msgs::RobotTrajectory trajectory;
 
  106   double percent = 
group.computeCartesianPath(waypoints, 0.01, trajectory, 
true);
 
  109     group.execute(trajectory);
 
  115     ROS_WARN(
"Failed to compute cartesian path");
 
  129   double z_offset_box = .25;  
 
  130   double z_offset_cylinder = .1;
 
  132   moveit_msgs::CollisionObject box;
 
  134   box.header.frame_id = 
"panda_hand";
 
  135   box.pose.position.z = z_offset_box;
 
  136   box.pose.orientation.w = 1.0;  
 
  138   box.primitives.resize(1);
 
  139   box.primitive_poses.resize(1);
 
  140   box.primitives[0].type = box.primitives[0].BOX;
 
  141   box.primitives[0].dimensions.resize(3);
 
  142   box.primitives[0].dimensions[0] = 0.05;
 
  143   box.primitives[0].dimensions[1] = 0.1;
 
  144   box.primitives[0].dimensions[2] = 0.02;
 
  145   box.primitive_poses[0].orientation.w = 1.0;  
 
  147   box.subframe_names.resize(1);
 
  148   box.subframe_poses.resize(1);
 
  150   box.subframe_names[0] = 
"bottom";
 
  151   box.subframe_poses[0].position.y = -.05;
 
  155   box.subframe_poses[0].orientation = 
tf2::toMsg(orientation);
 
  158   moveit_msgs::CollisionObject cylinder;
 
  159   cylinder.id = 
"cylinder";
 
  160   cylinder.header.frame_id = 
"panda_hand";
 
  161   cylinder.pose.position.z = z_offset_cylinder;
 
  163   cylinder.pose.orientation = 
tf2::toMsg(orientation);
 
  165   cylinder.primitives.resize(1);
 
  166   cylinder.primitive_poses.resize(1);
 
  167   cylinder.primitives[0].type = box.primitives[0].CYLINDER;
 
  168   cylinder.primitives[0].dimensions.resize(2);
 
  169   cylinder.primitives[0].dimensions[0] = 0.06;      
 
  170   cylinder.primitives[0].dimensions[1] = 0.005;     
 
  171   cylinder.primitive_poses[0].orientation.w = 1.0;  
 
  173   cylinder.subframe_poses.resize(1);
 
  174   cylinder.subframe_names.resize(1);
 
  175   cylinder.subframe_names[0] = 
"tip";
 
  176   cylinder.subframe_poses[0].position.z = 0.03;
 
  177   cylinder.subframe_poses[0].orientation.w = 1.0;  
 
  180   box.operation = moveit_msgs::CollisionObject::ADD;
 
  181   cylinder.operation = moveit_msgs::CollisionObject::ADD;
 
  185 TEST(TestPlanUsingSubframes, SubframesTests)
 
  187   const std::string log_name = 
"test_plan_using_subframes";
 
  190   auto planning_scene_monitor = std::make_shared<planning_scene_monitor::PlanningSceneMonitor>(
"robot_description");
 
  196   moveit_msgs::AttachedCollisionObject att_coll_object;
 
  197   att_coll_object.object.id = 
"cylinder";
 
  198   att_coll_object.link_name = 
"panda_hand";
 
  199   att_coll_object.object.operation = att_coll_object.object.ADD;
 
  200   att_coll_object.object.pose.orientation.w = 1.0;
 
  205   geometry_msgs::PoseStamped target_pose_stamped;
 
  206   target_pose_stamped.pose.orientation = 
tf2::toMsg(target_orientation);
 
  207   target_pose_stamped.pose.position.z = 
Z_OFFSET;
 
  210   target_pose_stamped.header.frame_id = 
"box/bottom";
 
  218     Eigen::Isometry3d cyl_tip = 
planning_scene->getFrameTransform(
"cylinder/tip");
 
  219     Eigen::Isometry3d box_subframe = 
planning_scene->getFrameTransform(target_pose_stamped.header.frame_id);
 
  220     Eigen::Isometry3d target_pose;
 
  224     std::stringstream ss;
 
  225     ss << 
"target frame: \n" << (box_subframe * target_pose).matrix() << 
"\ncylinder frame: \n" << cyl_tip.matrix();
 
  229     Eigen::Isometry3d panda_link = 
planning_scene->getFrameTransform(
"panda_link8");
 
  230     Eigen::Isometry3d expected_pose = Eigen::Isometry3d(Eigen::Translation3d(0.307, 0.13, 0.44)) *
 
  231                                       Eigen::Isometry3d(Eigen::Quaterniond(0.0003809, -0.38303, 0.92373, 0.00028097));
 
  234     ss << 
"panda link frame: \n" << panda_link.matrix() << 
"\nexpected pose: \n" << expected_pose.matrix();
 
  237   att_coll_object.object.operation = att_coll_object.object.REMOVE;
 
  239   moveit_msgs::CollisionObject coll_object1, coll_object2;
 
  240   coll_object1.id = 
"cylinder";
 
  241   coll_object1.operation = moveit_msgs::CollisionObject::REMOVE;
 
  242   coll_object2.id = 
"box";
 
  243   coll_object2.operation = moveit_msgs::CollisionObject::REMOVE;
 
  248 TEST(TestPlanUsingSubframes, SubframesCartesianPathTests)
 
  250   const std::string log_name = 
"test_cartesian_path_using_subframes";
 
  253   auto planning_scene_monitor = std::make_shared<planning_scene_monitor::PlanningSceneMonitor>(
"robot_description");
 
  259   moveit_msgs::CollisionObject coll_object2;
 
  260   coll_object2.id = 
"box";
 
  261   coll_object2.operation = moveit_msgs::CollisionObject::REMOVE;
 
  264   moveit_msgs::AttachedCollisionObject att_coll_object;
 
  265   att_coll_object.object.id = 
"cylinder";
 
  266   att_coll_object.link_name = 
"panda_hand";
 
  267   att_coll_object.object.operation = att_coll_object.object.ADD;
 
  268   att_coll_object.object.pose.orientation.w = 1.0;
 
  272   geometry_msgs::PoseStamped target_pose_stamped;
 
  273   target_pose_stamped = 
group.getCurrentPose(
"panda_hand");
 
  276   target_pose_stamped.pose.orientation = 
tf2::toMsg(orientation);
 
  285     Eigen::Isometry3d cyl_tip = 
planning_scene->getFrameTransform(
"cylinder/tip");
 
  286     Eigen::Isometry3d 
base = 
planning_scene->getFrameTransform(target_pose_stamped.header.frame_id);
 
  287     Eigen::Isometry3d target_pose;
 
  291     std::stringstream ss;
 
  292     ss << 
"target frame: \n" << (
base * target_pose).matrix() << 
"\ncylinder frame: \n" << cyl_tip.matrix();
 
  297 int main(
int argc, 
char** argv)
 
  299   ros::init(argc, argv, 
"moveit_test_plan_using_subframes");
 
  300   testing::InitGoogleTest(&argc, argv);
 
  305   int result = RUN_ALL_TESTS();