52 #include <gtest/gtest.h>
61 #include <tf2_geometry_msgs/tf2_geometry_msgs.hpp>
62 #include <tf2_eigen/tf2_eigen.hpp>
67 static const std::string PLANNING_GROUP =
"panda_arm";
78 nh_ = ros::NodeHandle(
"/move_group_interface_cpp_test");
79 move_group_ = std::make_shared<moveit::planning_interface::MoveGroupInterface>(PLANNING_GROUP);
93 psm_ = std::make_shared<planning_scene_monitor::PlanningSceneMonitor>(
"robot_description",
95 psm_->startSceneMonitor(
"/move_group/monitored_planning_scene");
96 psm_->requestPlanningSceneState();
99 ros::Duration(0.5).sleep();
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();
138 EXPECT_TRUE(actual.isApprox(expected,
EPSILON)) << ss.str();
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;
147 tf2::fromMsg(actual_pose_stamped.pose, 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;
157 tf2::fromMsg(expected_pose_msg, expected_pose);
163 SCOPED_TRACE(
"testJointPositions");
165 move_group_->getCurrentState()->getJointModelGroup(PLANNING_GROUP);
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;
207 tf2::fromMsg(target_pose, 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();
247 moveit_msgs::CollisionObject collision_object;
248 collision_object.header.frame_id = move_group_->getPlanningFrame();
251 collision_object.id =
"box1";
254 shape_msgs::SolidPrimitive primitive;
255 primitive.type = primitive.BOX;
256 primitive.dimensions.resize(3);
257 primitive.dimensions[0] = 0.1;
258 primitive.dimensions[1] = 1.0;
259 primitive.dimensions[2] = 1.0;
262 geometry_msgs::Pose box_pose;
263 box_pose.orientation.w = 1.0;
264 box_pose.position.x = 0.5;
265 box_pose.position.y = 0.0;
266 box_pose.position.z = 0.5;
268 collision_object.primitives.push_back(primitive);
269 collision_object.primitive_poses.push_back(box_pose);
270 collision_object.operation = collision_object.ADD;
272 std::vector<moveit_msgs::CollisionObject> collision_objects;
273 collision_objects.push_back(collision_object);
276 synchronizeGeometryUpdate([&]() { planning_scene_interface_.addCollisionObjects(collision_objects); });
279 synchronizeGeometryUpdate([&]() { EXPECT_TRUE(move_group_->attachObject(collision_object.id)); });
280 EXPECT_EQ(planning_scene_interface_.getAttachedObjects().size(), std::size_t(1));
281 synchronizeGeometryUpdate([&]() { EXPECT_TRUE(move_group_->detachObject(collision_object.id)); });
282 EXPECT_EQ(planning_scene_interface_.getAttachedObjects().size(), std::size_t(0));
285 const std::vector<std::string> object_ids = { collision_object.id };
286 EXPECT_EQ(planning_scene_interface_.getObjects().size(), std::size_t(1));
287 synchronizeGeometryUpdate([&]() { planning_scene_interface_.removeCollisionObjects(object_ids); });
288 EXPECT_EQ(planning_scene_interface_.getObjects().size(), std::size_t(0));
293 SCOPED_TRACE(
"CartPathTest");
296 const geometry_msgs::PoseStamped start_pose = move_group_->getCurrentPose();
298 std::vector<geometry_msgs::Pose>
waypoints;
301 geometry_msgs::Pose target_waypoint = start_pose.pose;
302 target_waypoint.position.z -= 0.2;
305 target_waypoint.position.y -= 0.2;
308 target_waypoint.position.z += 0.2;
309 target_waypoint.position.y += 0.2;
310 target_waypoint.position.x -= 0.2;
313 moveit_msgs::RobotTrajectory trajectory;
314 const auto jump_threshold = 0.0;
315 const auto eef_step = 0.01;
318 ASSERT_GE(
EPSILON + move_group_->computeCartesianPath(
waypoints, eef_step, jump_threshold, trajectory), 1.0);
321 EXPECT_EQ(move_group_->execute(trajectory), moveit::core::MoveItErrorCode::SUCCESS);
324 testPose(target_waypoint);
329 SCOPED_TRACE(
"JointSpaceGoalTest");
332 std::vector<double> plan_joint_positions;
333 move_group_->getCurrentState()->copyJointGroupPositions(
334 move_group_->getCurrentState()->getJointModelGroup(PLANNING_GROUP), plan_joint_positions);
337 ASSERT_EQ(plan_joint_positions.size(), std::size_t(7));
338 plan_joint_positions = { 1.2, -1.0, -0.1, -2.4, 0.0, 1.5, 0.6 };
339 move_group_->setJointValueTarget(plan_joint_positions);
345 testJointPositions(plan_joint_positions);
348 int main(
int argc,
char** argv)
350 ros::init(argc, argv,
"move_group_interface_cpp_test");
351 testing::InitGoogleTest(&argc, argv);
353 ros::AsyncSpinner spinner(1);
356 int result = RUN_ALL_TESTS();
void synchronizeGeometryUpdate(const std::function< void()> &updater)
void testJointPositions(const std::vector< double > &expected)
void testPose(const geometry_msgs::Pose &expected_pose_msg)
void testPose(const Eigen::Isometry3d &expected_pose)
void testEigenPose(const Eigen::Isometry3d &expected, const Eigen::Isometry3d &actual)
moveit::planning_interface::MoveGroupInterfacePtr move_group_
moveit::planning_interface::PlanningSceneInterface planning_scene_interface_
planning_scene_monitor::PlanningSceneMonitorPtr psm_
void planAndMoveToPose(const geometry_msgs::Pose &pose)
@ UPDATE_GEOMETRY
The geometry of the scene was updated. This includes receiving new octomaps, collision objects,...
constexpr double PLANNING_TIME_S
constexpr double MAX_ACCELERATION_SCALE
int main(int argc, char **argv)
constexpr double GOAL_TOLERANCE
constexpr double MAX_VELOCITY_SCALE
TEST_F(MoveGroupTestFixture, PathConstraintCollisionTest)
std::shared_ptr< tf2_ros::Buffer > getSharedTF()
The representation of a motion plan (as ROS messasges)