50 #include <gtest/gtest.h>
58 #include <tf2_geometry_msgs/tf2_geometry_msgs.hpp>
59 #include <tf2_eigen/tf2_eigen.hpp>
65 const double TAU = 2 * M_PI;
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.");
92 double z_offset_box = .25;
93 double z_offset_cylinder = .1;
95 moveit_msgs::CollisionObject box;
97 box.header.frame_id =
"panda_hand";
98 box.pose.position.z = z_offset_box;
99 box.pose.orientation.w = 1.0;
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;
110 box.subframe_names.resize(1);
111 box.subframe_poses.resize(1);
113 box.subframe_names[0] =
"bottom";
114 box.subframe_poses[0].position.y = -.05;
116 tf2::Quaternion orientation;
117 orientation.setRPY(
TAU / 4.0, 0, 0);
118 box.subframe_poses[0].orientation = tf2::toMsg(orientation);
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);
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;
133 cylinder.primitives[0].dimensions[1] = 0.005;
134 cylinder.primitive_poses[0].orientation.w = 1.0;
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;
143 box.operation = moveit_msgs::CollisionObject::ADD;
144 cylinder.operation = moveit_msgs::CollisionObject::ADD;
148 TEST(TestPlanUsingSubframes, SubframesTests)
150 const std::string log_name =
"test_plan_using_subframes";
151 ros::NodeHandle nh(log_name);
153 auto planning_scene_monitor = std::make_shared<planning_scene_monitor::PlanningSceneMonitor>(
"robot_description");
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;
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;
172 ROS_INFO_STREAM_NAMED(log_name,
"Moving to bottom of box with cylinder tip");
173 target_pose_stamped.header.frame_id =
"box/bottom";
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);
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();
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));
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();
202 int main(
int argc,
char** argv)
204 ros::init(argc, argv,
"moveit_test_plan_using_subframes");
205 testing::InitGoogleTest(&argc, argv);
207 ros::AsyncSpinner spinner(1);
210 int result = RUN_ALL_TESTS();
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)
TEST(TestPlanUsingSubframes, SubframesTests)
void spawnCollisionObjects(moveit::planning_interface::PlanningSceneInterface &planning_scene_interface)
constexpr double Z_OFFSET