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 Robotics 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://moveit.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
59 #include <tf2_eigen/tf2_eigen.h>
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 // similar to MoveToCartPose, but tries to plan a cartesian path with a subframe link
88 bool moveCartesianPath(const geometry_msgs::PoseStamped& pose, moveit::planning_interface::MoveGroupInterface& group,
89  const std::string& end_effector_link)
90 {
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))
98  {
99  ROS_WARN("Failed to move to initial joint positions");
100  return false;
101  }
102 
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);
107  if (percent == 1.0)
108  {
109  group.execute(trajectory);
110  return true;
111  }
112 
113  if (percent == -1.0)
114  {
115  ROS_WARN("Failed to compute cartesian path");
116  }
117  else
118  {
119  ROS_WARN_STREAM("Computed only " << percent * 100.0 << "% of path");
120  }
121  return false;
122 }
123 
124 // Function copied from subframes tutorial
125 // This helper function creates two objects and publishes them to the PlanningScene: a box and a cylinder.
126 // The box spawns in front of the gripper, the cylinder at the tip of the gripper, as if it had been grasped.
128 {
129  double z_offset_box = .25; // The z-axis points away from the gripper
130  double z_offset_cylinder = .1;
131 
132  moveit_msgs::CollisionObject box;
133  box.id = "box";
134  box.header.frame_id = "panda_hand";
135  box.pose.position.z = z_offset_box;
136  box.pose.orientation.w = 1.0; // Neutral orientation
137 
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; // Neutral orientation
146 
147  box.subframe_names.resize(1);
148  box.subframe_poses.resize(1);
149 
150  box.subframe_names[0] = "bottom";
151  box.subframe_poses[0].position.y = -.05;
152 
153  tf2::Quaternion orientation;
154  orientation.setRPY(TAU / 4.0, 0, 0); // 1/4 turn
155  box.subframe_poses[0].orientation = tf2::toMsg(orientation);
156 
157  // Next, define the cylinder
158  moveit_msgs::CollisionObject cylinder;
159  cylinder.id = "cylinder";
160  cylinder.header.frame_id = "panda_hand";
161  cylinder.pose.position.z = z_offset_cylinder;
162  orientation.setRPY(0, TAU / 4.0, 0);
163  cylinder.pose.orientation = tf2::toMsg(orientation);
164 
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; // height (along x)
170  cylinder.primitives[0].dimensions[1] = 0.005; // radius
171  cylinder.primitive_poses[0].orientation.w = 1.0; // Neutral orientation
172 
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; // Neutral orientation
178 
179  // Lastly, the objects are published to the PlanningScene. In this tutorial, we publish a box and a cylinder.
180  box.operation = moveit_msgs::CollisionObject::ADD;
181  cylinder.operation = moveit_msgs::CollisionObject::ADD;
182  planning_scene_interface.applyCollisionObjects({ box, cylinder });
183 }
184 
185 TEST(TestPlanUsingSubframes, SubframesTests)
186 {
187  const std::string log_name = "test_plan_using_subframes";
188  ros::NodeHandle nh(log_name);
189 
190  auto planning_scene_monitor = std::make_shared<planning_scene_monitor::PlanningSceneMonitor>("robot_description");
193  group.setPlanningTime(PLANNING_TIME_S);
194 
195  spawnCollisionObjects(planning_scene_interface);
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;
201  planning_scene_interface.applyAttachedCollisionObject(att_coll_object);
202 
203  tf2::Quaternion target_orientation;
204  target_orientation.setRPY(0, TAU / 2.0, TAU / 4.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;
208 
209  ROS_INFO_STREAM_NAMED(log_name, "Moving to bottom of box with cylinder tip, and then away");
210  target_pose_stamped.header.frame_id = "box/bottom";
211  ASSERT_TRUE(moveToCartPose(target_pose_stamped, group, "cylinder/tip"));
212  planning_scene_monitor->requestPlanningSceneState();
213  {
215 
216  // get the tip and box subframe locations in world
217  // TODO (felixvd): Get these from the plan's goal state instead, so we don't have to execute the motion in CI
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;
221  tf2::fromMsg(target_pose_stamped.pose, target_pose);
222 
223  // expect that they are identical
224  std::stringstream ss;
225  ss << "target frame: \n" << (box_subframe * target_pose).matrix() << "\ncylinder frame: \n" << cyl_tip.matrix();
226  EXPECT_TRUE(cyl_tip.isApprox(box_subframe * target_pose, EPSILON)) << ss.str();
227 
228  // Check that robot wrist is where we expect it to be
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));
232 
233  ss.str("");
234  ss << "panda link frame: \n" << panda_link.matrix() << "\nexpected pose: \n" << expected_pose.matrix();
235  EXPECT_TRUE(panda_link.isApprox(expected_pose, EPSILON)) << ss.str();
236  }
237  att_coll_object.object.operation = att_coll_object.object.REMOVE;
238  planning_scene_interface.applyAttachedCollisionObject(att_coll_object);
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;
244  planning_scene_interface.applyCollisionObject(coll_object1);
245  planning_scene_interface.applyCollisionObject(coll_object2);
246 }
247 
248 TEST(TestPlanUsingSubframes, SubframesCartesianPathTests)
249 {
250  const std::string log_name = "test_cartesian_path_using_subframes";
251  ros::NodeHandle nh(log_name);
252 
253  auto planning_scene_monitor = std::make_shared<planning_scene_monitor::PlanningSceneMonitor>("robot_description");
256  group.setPlanningTime(PLANNING_TIME_S);
257 
258  spawnCollisionObjects(planning_scene_interface);
259  moveit_msgs::CollisionObject coll_object2;
260  coll_object2.id = "box";
261  coll_object2.operation = moveit_msgs::CollisionObject::REMOVE;
262  planning_scene_interface.applyCollisionObject(coll_object2);
263 
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;
269  planning_scene_interface.applyAttachedCollisionObject(att_coll_object);
270 
271  // Move to where panda_hand is at when it graps cylinder
272  geometry_msgs::PoseStamped target_pose_stamped;
273  target_pose_stamped = group.getCurrentPose("panda_hand");
274  tf2::Quaternion orientation;
275  orientation.setRPY(TAU / 2, -TAU / 4.0, 0);
276  target_pose_stamped.pose.orientation = tf2::toMsg(orientation);
277 
278  ROS_INFO_STREAM_NAMED(log_name, "Moving hand in cartesian path to hand grasping location");
279  ASSERT_TRUE(moveCartesianPath(target_pose_stamped, group, "cylinder/tip"));
280  planning_scene_monitor->requestPlanningSceneState();
281  {
283 
284  // get the tip and base frames
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;
288  tf2::fromMsg(target_pose_stamped.pose, target_pose);
289 
290  // expect that they are identical
291  std::stringstream ss;
292  ss << "target frame: \n" << (base * target_pose).matrix() << "\ncylinder frame: \n" << cyl_tip.matrix();
293  EXPECT_TRUE(cyl_tip.isApprox(base * target_pose, EPSILON)) << ss.str();
294  }
295 }
296 
297 int main(int argc, char** argv)
298 {
299  ros::init(argc, argv, "moveit_test_plan_using_subframes");
300  testing::InitGoogleTest(&argc, argv);
301 
303  spinner.start();
304 
305  int result = RUN_ALL_TESTS();
306  return result;
307 }
planning_scene_monitor
moveit::planning_interface::PlanningSceneInterface::applyAttachedCollisionObject
bool applyAttachedCollisionObject(const moveit_msgs::AttachedCollisionObject &attached_collision_object)
Apply attached collision object to the planning scene of the move_group node synchronously....
Definition: planning_scene_interface/src/planning_scene_interface.cpp:540
moveit::planning_interface::MoveGroupInterface::Plan
The representation of a motion plan (as ROS messasges)
Definition: move_group_interface.h:187
moveit::planning_interface::MoveGroupInterface
Client class to conveniently use the ROS interfaces provided by the move_group node.
Definition: move_group_interface.h:139
ros::init
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
tf2_eigen.h
tf2::fromMsg
void fromMsg(const A &, B &b)
ros.h
tf2::Quaternion::setRPY
void setRPY(const tf2Scalar &roll, const tf2Scalar &pitch, const tf2Scalar &yaw)
ros::AsyncSpinner
moveit::planning_interface::PlanningSceneInterface
Definition: planning_scene_interface.h:116
moveToCartPose
bool moveToCartPose(const geometry_msgs::PoseStamped &pose, moveit::planning_interface::MoveGroupInterface &group, const std::string &end_effector_link)
Definition: subframes_test.cpp:69
TEST
TEST(TestPlanUsingSubframes, SubframesTests)
Definition: subframes_test.cpp:185
EXPECT_TRUE
#define EXPECT_TRUE(args)
spinner
void spinner()
moveCartesianPath
bool moveCartesianPath(const geometry_msgs::PoseStamped &pose, moveit::planning_interface::MoveGroupInterface &group, const std::string &end_effector_link)
Definition: subframes_test.cpp:88
ROS_WARN_STREAM
#define ROS_WARN_STREAM(args)
planning_scene_monitor.h
Z_OFFSET
constexpr double Z_OFFSET
Definition: subframes_test.cpp:62
ROS_WARN
#define ROS_WARN(...)
main
int main(int argc, char **argv)
Definition: subframes_test.cpp:297
EPSILON
constexpr double EPSILON
Definition: subframes_test.cpp:61
planning_scene_interface.h
spawnCollisionObjects
void spawnCollisionObjects(moveit::planning_interface::PlanningSceneInterface &planning_scene_interface)
Definition: subframes_test.cpp:127
PLANNING_TIME_S
constexpr double PLANNING_TIME_S
Definition: subframes_test.cpp:63
planning_scene_monitor::LockedPlanningSceneRO
moveit::planning_interface::PlanningSceneInterface::applyCollisionObjects
bool applyCollisionObjects(const std::vector< moveit_msgs::CollisionObject > &collision_objects, const std::vector< moveit_msgs::ObjectColor > &object_colors=std::vector< moveit_msgs::ObjectColor >())
Apply collision objects to the planning scene of the move_group node synchronously....
Definition: planning_scene_interface/src/planning_scene_interface.cpp:520
move_group_interface.h
M_PI
#define M_PI
TAU
const double TAU
Definition: subframes_test.cpp:65
tf2::Quaternion
ROS_INFO_STREAM_NAMED
#define ROS_INFO_STREAM_NAMED(name, args)
tf2_geometry_msgs.h
tf2::toMsg
B toMsg(const A &a)
planning_scene
moveit::planning_interface::PlanningSceneInterface::applyCollisionObject
bool applyCollisionObject(const moveit_msgs::CollisionObject &collision_object)
Apply collision object to the planning scene of the move_group node synchronously....
Definition: planning_scene_interface/src/planning_scene_interface.cpp:495
base
MatrixDerived base(const Eigen::MatrixBase< MatrixDerived > &m)
ros::NodeHandle
test_cleanup.group
group
Definition: test_cleanup.py:8


planning_interface
Author(s): Ioan Sucan
autogenerated on Thu Nov 21 2024 03:25:12