moveit2
The MoveIt Motion Planning Framework for ROS 2.
subframes_test.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2019, Felix von Drigalski, Jacob Aas, Tyler Weaver
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 OMRON SINIC X or PickNik Inc. nor the
18  * names of its contributors may be used to endorse or promote
19  * products derived from this software without specific prior
20  * written permission.
21  *
22  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33  * POSSIBILITY OF SUCH DAMAGE.
34  *********************************************************************/
35 
36 /* Author: Felix von Drigalski, Jacob Aas, Tyler Weaver, Boston Cleek */
37 
38 /* This integration test is based on the tutorial for using subframes
39  * https://ros-planning.github.io/moveit_tutorials/doc/subframes/subframes_tutorial.html
40  */
41 
42 // C++
43 #include <vector>
44 #include <map>
45 
46 // ROS
47 #include <ros/ros.h>
48 
49 // The Testing Framework and Utils
50 #include <gtest/gtest.h>
51 
52 // MoveIt
56 
57 // TF2
58 #include <tf2_geometry_msgs/tf2_geometry_msgs.hpp>
59 #include <tf2_eigen/tf2_eigen.hpp>
60 
61 constexpr double EPSILON = 1e-2;
62 constexpr double Z_OFFSET = 0.05;
63 constexpr double PLANNING_TIME_S = 30.0;
64 
65 const double TAU = 2 * M_PI; // One turn (360°) in radians
66 
67 // Function copied from tutorial
68 // a small helper function to create our planning requests and move the robot.
69 bool moveToCartPose(const geometry_msgs::PoseStamped& pose, moveit::planning_interface::MoveGroupInterface& group,
70  const std::string& end_effector_link)
71 {
72  group.clearPoseTargets();
73  group.setEndEffectorLink(end_effector_link);
74  group.setStartStateToCurrentState();
75  group.setPoseTarget(pose);
76 
78  if (group.plan(myplan) && group.execute(myplan))
79  {
80  return true;
81  }
82 
83  ROS_WARN("Failed to perform motion.");
84  return false;
85 }
86 
87 // Function copied from subframes tutorial
88 // This helper function creates two objects and publishes them to the PlanningScene: a box and a cylinder.
89 // The box spawns in front of the gripper, the cylinder at the tip of the gripper, as if it had been grasped.
91 {
92  double z_offset_box = .25; // The z-axis points away from the gripper
93  double z_offset_cylinder = .1;
94 
95  moveit_msgs::CollisionObject box;
96  box.id = "box";
97  box.header.frame_id = "panda_hand";
98  box.pose.position.z = z_offset_box;
99  box.pose.orientation.w = 1.0; // Neutral orientation
100 
101  box.primitives.resize(1);
102  box.primitive_poses.resize(1);
103  box.primitives[0].type = box.primitives[0].BOX;
104  box.primitives[0].dimensions.resize(3);
105  box.primitives[0].dimensions[0] = 0.05;
106  box.primitives[0].dimensions[1] = 0.1;
107  box.primitives[0].dimensions[2] = 0.02;
108  box.primitive_poses[0].orientation.w = 1.0; // Neutral orientation
109 
110  box.subframe_names.resize(1);
111  box.subframe_poses.resize(1);
112 
113  box.subframe_names[0] = "bottom";
114  box.subframe_poses[0].position.y = -.05;
115 
116  tf2::Quaternion orientation;
117  orientation.setRPY(TAU / 4.0, 0, 0); // 1/4 turn
118  box.subframe_poses[0].orientation = tf2::toMsg(orientation);
119 
120  // Next, define the cylinder
121  moveit_msgs::CollisionObject cylinder;
122  cylinder.id = "cylinder";
123  cylinder.header.frame_id = "panda_hand";
124  cylinder.pose.position.z = z_offset_cylinder;
125  orientation.setRPY(0, TAU / 4.0, 0);
126  cylinder.pose.orientation = tf2::toMsg(orientation);
127 
128  cylinder.primitives.resize(1);
129  cylinder.primitive_poses.resize(1);
130  cylinder.primitives[0].type = box.primitives[0].CYLINDER;
131  cylinder.primitives[0].dimensions.resize(2);
132  cylinder.primitives[0].dimensions[0] = 0.06; // height (along x)
133  cylinder.primitives[0].dimensions[1] = 0.005; // radius
134  cylinder.primitive_poses[0].orientation.w = 1.0; // Neutral orientation
135 
136  cylinder.subframe_poses.resize(1);
137  cylinder.subframe_names.resize(1);
138  cylinder.subframe_names[0] = "tip";
139  cylinder.subframe_poses[0].position.z = 0.03;
140  cylinder.subframe_poses[0].orientation.w = 1.0; // Neutral orientation
141 
142  // Lastly, the objects are published to the PlanningScene. In this tutorial, we publish a box and a cylinder.
143  box.operation = moveit_msgs::CollisionObject::ADD;
144  cylinder.operation = moveit_msgs::CollisionObject::ADD;
145  planning_scene_interface.applyCollisionObjects({ box, cylinder });
146 }
147 
148 TEST(TestPlanUsingSubframes, SubframesTests)
149 {
150  const std::string log_name = "test_plan_using_subframes";
151  ros::NodeHandle nh(log_name);
152 
153  auto planning_scene_monitor = std::make_shared<planning_scene_monitor::PlanningSceneMonitor>("robot_description");
156  group.setPlanningTime(PLANNING_TIME_S);
157 
158  spawnCollisionObjects(planning_scene_interface);
159  moveit_msgs::AttachedCollisionObject att_coll_object;
160  att_coll_object.object.id = "cylinder";
161  att_coll_object.link_name = "panda_hand";
162  att_coll_object.object.operation = att_coll_object.object.ADD;
163  att_coll_object.object.pose.orientation.w = 1.0;
164  planning_scene_interface.applyAttachedCollisionObject(att_coll_object);
165 
166  tf2::Quaternion target_orientation;
167  target_orientation.setRPY(0, TAU / 2.0, TAU / 4.0);
168  geometry_msgs::PoseStamped target_pose_stamped;
169  target_pose_stamped.pose.orientation = tf2::toMsg(target_orientation);
170  target_pose_stamped.pose.position.z = Z_OFFSET;
171 
172  ROS_INFO_STREAM_NAMED(log_name, "Moving to bottom of box with cylinder tip");
173  target_pose_stamped.header.frame_id = "box/bottom";
174  ASSERT_TRUE(moveToCartPose(target_pose_stamped, group, "cylinder/tip"));
175  planning_scene_monitor->requestPlanningSceneState();
176  {
178 
179  // get the tip and box subframe locations in world
180  // TODO (felixvd): Get these from the plan's goal state instead, so we don't have to execute the motion in CI
181  Eigen::Isometry3d cyl_tip = planning_scene->getFrameTransform("cylinder/tip");
182  Eigen::Isometry3d box_subframe = planning_scene->getFrameTransform(target_pose_stamped.header.frame_id);
183  Eigen::Isometry3d target_pose;
184  tf2::fromMsg(target_pose_stamped.pose, target_pose);
185 
186  // expect that they are identical
187  std::stringstream ss;
188  ss << "target frame: \n" << (box_subframe * target_pose).matrix() << "\ncylinder frame: \n" << cyl_tip.matrix();
189  EXPECT_TRUE(cyl_tip.isApprox(box_subframe * target_pose, EPSILON)) << ss.str();
190 
191  // Check that robot wrist is where we expect it to be
192  Eigen::Isometry3d panda_link = planning_scene->getFrameTransform("panda_link8");
193  Eigen::Isometry3d expected_pose = Eigen::Isometry3d(Eigen::Translation3d(0.307, 0.13, 0.44)) *
194  Eigen::Isometry3d(Eigen::Quaterniond(0.0003809, -0.38303, 0.92373, 0.00028097));
195 
196  ss.str("");
197  ss << "panda link frame: \n" << panda_link.matrix() << "\nexpected pose: \n" << expected_pose.matrix();
198  EXPECT_TRUE(panda_link.isApprox(expected_pose, EPSILON)) << ss.str();
199  }
200 }
201 
202 int main(int argc, char** argv)
203 {
204  ros::init(argc, argv, "moveit_test_plan_using_subframes");
205  testing::InitGoogleTest(&argc, argv);
206 
207  ros::AsyncSpinner spinner(1);
208  spinner.start();
209 
210  int result = RUN_ALL_TESTS();
211  return result;
212 }
Client class to conveniently use the ROS interfaces provided by the move_group node.
bool applyAttachedCollisionObject(const moveit_msgs::msg::AttachedCollisionObject &attached_collision_object)
Apply attached collision object to the planning scene of the move_group node synchronously....
bool applyCollisionObjects(const std::vector< moveit_msgs::msg::CollisionObject > &collision_objects, const std::vector< moveit_msgs::msg::ObjectColor > &object_colors=std::vector< moveit_msgs::msg::ObjectColor >())
Apply collision objects to the planning scene of the move_group node synchronously....
This is a convenience class for obtaining access to an instance of a locked PlanningScene.
This namespace includes the central class for representing planning contexts.
The representation of a motion plan (as ROS messasges)
constexpr double PLANNING_TIME_S
bool moveToCartPose(const geometry_msgs::PoseStamped &pose, moveit::planning_interface::MoveGroupInterface &group, const std::string &end_effector_link)
int main(int argc, char **argv)
constexpr double EPSILON
TEST(TestPlanUsingSubframes, SubframesTests)
const double TAU
void spawnCollisionObjects(moveit::planning_interface::PlanningSceneInterface &planning_scene_interface)
constexpr double Z_OFFSET