55 #include <gtest/gtest.h>
86 pconfig_settings.
config = { {
"enforce_joint_model_state_space",
"0" } };
89 moveit_msgs::MoveItErrorCodes error_code;
100 EXPECT_NE(pc->getOMPLSimpleSetup(),
nullptr);
110 ASSERT_TRUE(pc->solve(res));
113 void testPathConstraints(
const std::vector<double>& start,
const std::vector<double>& goal)
119 pconfig_settings.
config = { {
"enforce_joint_model_state_space",
"0" } };
122 moveit_msgs::MoveItErrorCodes error_code;
126 request.allowed_planning_time = 10.0;
131 geometry_msgs::Quaternion ee_orientation =
tf2::toMsg(Eigen::Quaterniond(ee_pose.rotation()));
144 EXPECT_NE(pc->getOMPLSimpleSetup(),
nullptr);
150 ASSERT_TRUE(pc->solve(response));
153 auto path_constraints = pc->getPathConstraints();
155 EXPECT_EQ(path_constraints->getOrientationConstraints().size(), 1u);
156 EXPECT_TRUE(path_constraints->getPositionConstraints().empty());
157 EXPECT_TRUE(path_constraints->getJointConstraints().empty());
158 EXPECT_TRUE(path_constraints->getVisibilityConstraints().empty());
163 for (
const robot_trajectory::RobotTrajectoryPtr& trajectory :
response.trajectory_)
165 for (std::size_t pt_index = { 0 }; pt_index < trajectory->getWayPointCount(); ++pt_index)
167 EXPECT_TRUE(path_constraints->decide(trajectory->getWayPoint(pt_index)).satisfied);
173 request.path_constraints.orientation_constraints.clear();
175 { ee_pose.translation().
x(), ee_pose.translation().y(), ee_pose.translation().z() }, { 0.1, 0.1, 0.1 }));
180 EXPECT_NE(pc->getOMPLSimpleSetup(),
nullptr);
187 ASSERT_TRUE(pc->solve(response2));
190 path_constraints = pc->getPathConstraints();
192 EXPECT_EQ(path_constraints->getPositionConstraints().size(), 1u);
193 EXPECT_TRUE(path_constraints->getOrientationConstraints().empty());
198 for (
const robot_trajectory::RobotTrajectoryPtr& trajectory : response2.
trajectory_)
200 for (std::size_t pt_index = { 0 }; pt_index < trajectory->getWayPointCount(); ++pt_index)
202 EXPECT_TRUE(path_constraints->decide(trajectory->getWayPoint(pt_index)).satisfied);
212 void SetUp()
override
225 const std::vector<double>& goal)
const
229 request.allowed_planning_time = 5.0;
233 start_state.setToDefaultValues();
239 goal_state.setToDefaultValues();
241 moveit_msgs::Constraints joint_goal =
243 request.goal_constraints.push_back(joint_goal);
250 std::array<double, 3> dimensions)
252 shape_msgs::SolidPrimitive box;
253 box.type = shape_msgs::SolidPrimitive::BOX;
254 box.dimensions.resize(3);
255 box.dimensions[shape_msgs::SolidPrimitive::BOX_X] = dimensions[0];
256 box.dimensions[shape_msgs::SolidPrimitive::BOX_Y] = dimensions[1];
257 box.dimensions[shape_msgs::SolidPrimitive::BOX_Z] = dimensions[2];
259 geometry_msgs::Pose box_pose;
260 box_pose.position.x = position[0];
261 box_pose.position.y = position[1];
262 box_pose.position.z = position[2];
263 box_pose.orientation.w = 1.0;
265 moveit_msgs::PositionConstraint pc;
268 pc.constraint_region.primitives.push_back(box);
269 pc.constraint_region.primitive_poses.push_back(box_pose);
277 moveit_msgs::OrientationConstraint oc;
280 oc.orientation = nominal_orientation;
281 oc.absolute_x_axis_tolerance = 0.3;
282 oc.absolute_y_axis_tolerance = 0.3;
283 oc.absolute_z_axis_tolerance = 0.3;
319 testSimpleRequest({ 0, -0.785, 0, -2.356, 0, 1.571, 0.785 }, { 0, -0.785, 0, -2.356, 0, 1.571, 0.685 });
324 testPathConstraints({ 0, -0.785, 0, -2.356, 0, 1.571, 0.785 }, { 0, -0.785, 0, -2.356, 0, 1.571, 0.685 });
340 testSimpleRequest({ 0, 0, 0, 0, 0, 0 }, { 0, 0, 0, 0, 0, 0.1 });
345 testPathConstraints({ 0, 0, 0, 0, 0, 0 }, { 0, 0, 0, 0, 0, 0.1 });
351 int main(
int argc,
char** argv)
353 ros::init(argc, argv,
"planning_context_manager_test");
354 testing::InitGoogleTest(&argc, argv);
355 return RUN_ALL_TESTS();