56 #include <gtest/gtest.h>
63 #include <ompl/geometric/SimpleSetup.h>
68 constexpr
char LOGNAME[] =
"test_state_validity_checker";
71 std::ostream&
operator<<(std::ostream& os,
const std::vector<double>& v)
95 ompl::base::StateValidityCheckerPtr checker =
103 auto checker = std::make_shared<ompl_interface::StateValidityChecker>(
planning_context_.get());
132 auto checker = std::make_shared<ompl_interface::StateValidityChecker>(
planning_context_.get());
153 ASSERT_NE(
planning_context_,
nullptr) <<
"Initialize planning context before adding path constraints.";
159 moveit_msgs::Constraints path_constraints;
161 path_constraints.name =
"test_position_constraints";
163 { ee_pose.translation().
x(), ee_pose.translation().y(), ee_pose.translation().z() }, { 0.1, 0.1, 0.1 }));
165 moveit_msgs::MoveItErrorCodes error_code_not_used;
166 ASSERT_TRUE(
planning_context_->setPathConstraints(path_constraints, &error_code_not_used));
168 auto checker = std::make_shared<ompl_interface::StateValidityChecker>(
planning_context_.get());
181 moveit_msgs::Constraints path_constraints_2(path_constraints);
182 path_constraints_2.position_constraints.at(0).constraint_region.primitive_poses.at(0).position.z += 0.2;
184 ASSERT_TRUE(
planning_context_->setPathConstraints(path_constraints_2, &error_code_not_used));
208 state_space_ = std::make_shared<ompl_interface::JointModelStateSpace>(space_spec);
214 ASSERT_NE(
state_space_,
nullptr) <<
"Initialize state space before creating the planning context.";
230 std::array<double, 3> dimensions)
232 shape_msgs::SolidPrimitive box;
233 box.type = shape_msgs::SolidPrimitive::BOX;
234 box.dimensions.resize(3);
235 box.dimensions[shape_msgs::SolidPrimitive::BOX_X] = dimensions[0];
236 box.dimensions[shape_msgs::SolidPrimitive::BOX_Y] = dimensions[1];
237 box.dimensions[shape_msgs::SolidPrimitive::BOX_Z] = dimensions[2];
239 geometry_msgs::Pose box_pose;
240 box_pose.position.x = position[0];
241 box_pose.position.y = position[1];
242 box_pose.position.z = position[2];
243 box_pose.orientation.w = 1.0;
245 moveit_msgs::PositionConstraint position_constraint;
248 position_constraint.constraint_region.primitives.push_back(box);
249 position_constraint.constraint_region.primitive_poses.push_back(box_pose);
252 position_constraint.weight = 1.0;
254 return position_constraint;
283 testJointLimits({ 0, -0.785, 0, -2.356, 0, 1.571, 0.785 });
290 testSelfCollision({ 2.31827, -0.169668, 2.5225, -2.98568, -0.36355, 0.808339, 0.0843406 });
297 testPathConstraints({ 0, -0.785, 0, -2.356, 0, 1.571, 0.785 });
319 testJointLimits({ 0.0, 0.0, 0.0, 0.0, 0.0, 0.0 });
326 testSelfCollision({ -2.95993, -0.682185, -2.43873, -0.939784, 3.0544, 0.882294 });
332 testPathConstraints({ 0.0, 0.0, 0.0, 0.0, 0.0, 0.0 });
338 int main(
int argc,
char** argv)
340 testing::InitGoogleTest(&argc, argv);
341 return RUN_ALL_TESTS();