55 #include <gtest/gtest.h>
57 #include <tf2_eigen/tf2_eigen.hpp>
80 SCOPED_TRACE(
"testSimpleRequest");
86 pconfig_settings.
config = { {
"enforce_joint_model_state_space",
"0" } };
89 moveit_msgs::msg::MoveItErrorCodes error_code;
100 EXPECT_NE(pc->getOMPLSimpleSetup(),
nullptr);
106 EXPECT_TRUE(pc->getPathConstraints()->empty());
110 ASSERT_TRUE(pc->solve(res));
115 SCOPED_TRACE(
"testPathConstraints");
121 pconfig_settings.
config = { {
"enforce_joint_model_state_space",
"0" } };
124 moveit_msgs::msg::MoveItErrorCodes error_code;
128 request.allowed_planning_time = 10.0;
133 geometry_msgs::msg::Quaternion ee_orientation = tf2::toMsg(Eigen::Quaterniond(ee_pose.rotation()));
146 EXPECT_NE(pc->getOMPLSimpleSetup(),
nullptr);
152 ASSERT_TRUE(pc->solve(response));
165 for (
const robot_trajectory::RobotTrajectoryPtr& trajectory : response.
trajectory_)
167 for (std::size_t pt_index = 0; pt_index < trajectory->getWayPointCount(); ++pt_index)
169 EXPECT_TRUE(
path_constraints->decide(trajectory->getWayPoint(pt_index)).satisfied);
175 request.path_constraints.orientation_constraints.clear();
177 { ee_pose.translation().
x(), ee_pose.translation().y(), ee_pose.translation().z() }, { 0.1, 0.1, 0.1 }));
182 EXPECT_NE(pc->getOMPLSimpleSetup(),
nullptr);
189 ASSERT_TRUE(pc->solve(response2));
200 for (
const robot_trajectory::RobotTrajectoryPtr& trajectory : response2.
trajectory_)
202 for (std::size_t pt_index = 0; pt_index < trajectory->getWayPointCount(); ++pt_index)
204 EXPECT_TRUE(
path_constraints->decide(trajectory->getWayPoint(pt_index)).satisfied);
219 const std::vector<double>& goal)
const
223 request.allowed_planning_time = 5.0;
236 moveit_msgs::msg::Constraints joint_goal =
239 request.goal_constraints.push_back(joint_goal);
246 std::array<double, 3> dimensions)
248 shape_msgs::msg::SolidPrimitive box;
249 box.type = shape_msgs::msg::SolidPrimitive::BOX;
250 box.dimensions.resize(3);
251 box.dimensions[shape_msgs::msg::SolidPrimitive::BOX_X] = dimensions[0];
252 box.dimensions[shape_msgs::msg::SolidPrimitive::BOX_Y] = dimensions[1];
253 box.dimensions[shape_msgs::msg::SolidPrimitive::BOX_Z] = dimensions[2];
255 geometry_msgs::msg::Pose box_pose;
256 box_pose.position.x = position[0];
257 box_pose.position.y = position[1];
258 box_pose.position.z = position[2];
259 box_pose.orientation.w = 1.0;
261 moveit_msgs::msg::PositionConstraint pc;
264 pc.constraint_region.primitives.push_back(box);
265 pc.constraint_region.primitive_poses.push_back(box_pose);
271 moveit_msgs::msg::OrientationConstraint
274 moveit_msgs::msg::OrientationConstraint oc;
277 oc.orientation = nominal_orientation;
278 oc.absolute_x_axis_tolerance = 0.3;
279 oc.absolute_y_axis_tolerance = 0.3;
280 oc.absolute_z_axis_tolerance = 0.3;
316 testSimpleRequest({ 0., -0.785, 0., -2.356, 0, 1.571, 0.785 }, { 0., -0.785, 0., -2.356, 0, 1.571, 0.685 });
321 testPathConstraints({ 0., -0.785, 0., -2.356, 0., 1.571, 0.785 }, { .0, -0.785, 0., -2.356, 0., 1.571, 0.685 });
337 testSimpleRequest({ 0., 0., 0., 0., 0., 0. }, { 0., 0., 0., 0., 0., 0.1 });
342 testPathConstraints({ 0., 0., 0., 0., 0., 0. }, { 0., 0., 0., 0., 0., 0.1 });
348 int main(
int argc,
char** argv)
350 testing::InitGoogleTest(&argc, argv);
351 rclcpp::init(argc, argv);
353 const int ret = RUN_ALL_TESTS();
FanucTestPlanningContext()
PandaTestPlanningContext()
Generic implementation of the tests that can be executed on different robots.
TestPlanningContext(const std::string &robot_name, const std::string &group_name)
planning_interface::MotionPlanRequest createRequest(const std::vector< double > &start, const std::vector< double > &goal) const
moveit_msgs::msg::OrientationConstraint createOrientationConstraint(const geometry_msgs::msg::Quaternion &nominal_orientation)
Helper function to create a orientation constraint.
moveit_msgs::msg::PositionConstraint createPositionConstraint(std::array< double, 3 > position, std::array< double, 3 > dimensions)
Helper function to create a position constraint.
ompl_interface::ModelBasedStateSpacePtr state_space_
rclcpp::Node::SharedPtr node_
void testSimpleRequest(const std::vector< double > &start, const std::vector< double > &goal)
void testPathConstraints(const std::vector< double > &start, const std::vector< double > &goal)
planning_scene::PlanningScenePtr planning_scene_
ompl_interface::ModelBasedPlanningContextSpecification planning_context_spec_
constraint_samplers::ConstraintSamplerManagerPtr constraint_sampler_manager_
ompl_interface::ModelBasedPlanningContextPtr planning_context_
Representation of a robot's state. This includes position, velocity, acceleration and effort.
void setJointGroupPositions(const std::string &joint_group_name, const double *gstate)
Given positions for the variables that make up a group, in the order found in the group (including va...
void setToDefaultValues()
Set all joints to their default positions. The default position is 0, or if that is not within bounds...
ModelBasedPlanningContextPtr getPlanningContext(const planning_scene::PlanningSceneConstPtr &planning_scene, const planning_interface::MotionPlanRequest &req, moveit_msgs::msg::MoveItErrorCodes &error_code, const rclcpp::Node::SharedPtr &node, bool use_constraints_approximations) const
Returns a planning context to OMPLInterface, which in turn passes it to OMPLPlannerManager.
void setPlannerConfigurations(const planning_interface::PlannerConfigurationMap &pconfig)
Specify configurations for the planners.
Robot independent test class setup.
moveit::core::RobotStatePtr robot_state_
moveit::core::RobotModelPtr robot_model_
std::string ee_link_name_
LoadTestRobot(const std::string &robot_name, const std::string &group_name)
const moveit::core::JointModelGroup * joint_model_group_
std::string base_link_name_
moveit_msgs::msg::Constraints constructGoalConstraints(const moveit::core::RobotState &state, const moveit::core::JointModelGroup *jmg, double tolerance_below, double tolerance_above)
Generates a constraint message intended to be used as a goal constraint for a joint group....
void robotStateToRobotStateMsg(const RobotState &state, moveit_msgs::msg::RobotState &robot_state, bool copy_attached_bodies=true)
Convert a MoveIt robot state to a robot state message.
std::map< std::string, PlannerConfigurationSettings > PlannerConfigurationMap
Map from PlannerConfigurationSettings.name to PlannerConfigurationSettings.
moveit_msgs::msg::MotionPlanRequest MotionPlanRequest
std::vector< robot_trajectory::RobotTrajectoryPtr > trajectory_
Specify the settings for a particular planning algorithm, for a particular group. The Planner plugin ...
std::map< std::string, std::string > config
Key-value pairs of settings that get passed to the planning algorithm.
std::string group
The group (as defined in the SRDF) this configuration is meant for.
int main(int argc, char **argv)
TEST_F(PandaTestPlanningContext, testSimpleRequest)