moveit2
The MoveIt Motion Planning Framework for ROS 2.
test_planning_context_manager.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2020, KU Leuven
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of KU Leuven nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *********************************************************************/
34 
35 /* Author: Jeroen De Maeyer */
36 
53 #include "load_test_robot.h"
54 
55 #include <gtest/gtest.h>
56 
57 #include <tf2_eigen/tf2_eigen.hpp>
58 
66 
67 // static const rclcpp::Logger LOGGER = rclcpp::get_logger("moveit.ompl_planning.test.test_planning_context_manager");
68 
70 class TestPlanningContext : public ompl_interface_testing::LoadTestRobot, public testing::Test
71 {
72 public:
73  TestPlanningContext(const std::string& robot_name, const std::string& group_name)
74  : LoadTestRobot(robot_name, group_name), node_(std::make_shared<rclcpp::Node>("planning_context_manager_test"))
75  {
76  }
77 
78  void testSimpleRequest(const std::vector<double>& start, const std::vector<double>& goal)
79  {
80  SCOPED_TRACE("testSimpleRequest");
81 
82  // create all the test specific input necessary to make the getPlanningContext call possible
84  pconfig_settings.group = group_name_;
85  pconfig_settings.name = group_name_;
86  pconfig_settings.config = { { "enforce_joint_model_state_space", "0" } };
87 
88  planning_interface::PlannerConfigurationMap pconfig_map{ { pconfig_settings.name, pconfig_settings } };
89  moveit_msgs::msg::MoveItErrorCodes error_code;
91 
92  // setup the planning context manager
94  pcm.setPlannerConfigurations(pconfig_map);
95 
96  // see if it returns the expected planning context
97  auto pc = pcm.getPlanningContext(planning_scene_, request, error_code, node_, false);
98 
99  // the planning context should have a simple setup created
100  EXPECT_NE(pc->getOMPLSimpleSetup(), nullptr);
101 
102  // the OMPL state space in the planning context should be of type JointModelStateSpace
103  EXPECT_NE(dynamic_cast<ompl_interface::JointModelStateSpace*>(pc->getOMPLStateSpace().get()), nullptr);
104 
105  // there did not magically appear path constraints in the planning context
106  EXPECT_TRUE(pc->getPathConstraints()->empty());
107 
108  // solve the planning problem
110  ASSERT_TRUE(pc->solve(res));
111  }
112 
113  void testPathConstraints(const std::vector<double>& start, const std::vector<double>& goal)
114  {
115  SCOPED_TRACE("testPathConstraints");
116 
117  // create all the test specific input necessary to make the getPlanningContext call possible
119  pconfig_settings.group = group_name_;
120  pconfig_settings.name = group_name_;
121  pconfig_settings.config = { { "enforce_joint_model_state_space", "0" } };
122 
123  planning_interface::PlannerConfigurationMap pconfig_map{ { pconfig_settings.name, pconfig_settings } };
124  moveit_msgs::msg::MoveItErrorCodes error_code;
126 
127  // give it some more time, as rejection sampling of the path constraints occasionally takes some time
128  request.allowed_planning_time = 10.0;
129 
130  // create path constraints around start state, to make sure they are satisfied
131  robot_state_->setJointGroupPositions(joint_model_group_, start);
132  Eigen::Isometry3d ee_pose = robot_state_->getGlobalLinkTransform(ee_link_name_);
133  geometry_msgs::msg::Quaternion ee_orientation = tf2::toMsg(Eigen::Quaterniond(ee_pose.rotation()));
134 
135  // setup the planning context manager
137  pcm.setPlannerConfigurations(pconfig_map);
138 
139  // ORIENTATION CONSTRAINTS
140  // ***********************
141  request.path_constraints.orientation_constraints.push_back(createOrientationConstraint(ee_orientation));
142 
143  // See if the planning context manager returns the expected planning context
144  auto pc = pcm.getPlanningContext(planning_scene_, request, error_code, node_, false);
145 
146  EXPECT_NE(pc->getOMPLSimpleSetup(), nullptr);
147 
148  // As the joint_model_group_ has no IK solver initialized, we expect a joint model state space
149  EXPECT_NE(dynamic_cast<ompl_interface::JointModelStateSpace*>(pc->getOMPLStateSpace().get()), nullptr);
150 
152  ASSERT_TRUE(pc->solve(response));
153 
154  // Are the path constraints created in the planning context?
155  auto path_constraints = pc->getPathConstraints();
156  EXPECT_FALSE(path_constraints->empty());
157  EXPECT_EQ(path_constraints->getOrientationConstraints().size(), 1u);
158  EXPECT_TRUE(path_constraints->getPositionConstraints().empty());
159  EXPECT_TRUE(path_constraints->getJointConstraints().empty());
160  EXPECT_TRUE(path_constraints->getVisibilityConstraints().empty());
161 
162  // Check if all the states in the solution satisfy the path constraints.
163  // A detailed response returns 3 solutions: the ompl solution, the simplified solution and the interpolated
164  // solution. We test all of them here.
165  for (const robot_trajectory::RobotTrajectoryPtr& trajectory : response.trajectory_)
166  {
167  for (std::size_t pt_index = 0; pt_index < trajectory->getWayPointCount(); ++pt_index)
168  {
169  EXPECT_TRUE(path_constraints->decide(trajectory->getWayPoint(pt_index)).satisfied);
170  }
171  }
172 
173  // POSITION CONSTRAINTS
174  // ***********************
175  request.path_constraints.orientation_constraints.clear();
176  request.path_constraints.position_constraints.push_back(createPositionConstraint(
177  { ee_pose.translation().x(), ee_pose.translation().y(), ee_pose.translation().z() }, { 0.1, 0.1, 0.1 }));
178 
179  // See if the planning context manager returns the expected planning context
180  pc = pcm.getPlanningContext(planning_scene_, request, error_code, node_, false);
181 
182  EXPECT_NE(pc->getOMPLSimpleSetup(), nullptr);
183 
184  // As the joint_model_group_ has no IK solver initialized, we expect a joint model state space
185  EXPECT_NE(dynamic_cast<ompl_interface::JointModelStateSpace*>(pc->getOMPLStateSpace().get()), nullptr);
186 
187  // Create a new response, because the solve method does not clear the given respone
189  ASSERT_TRUE(pc->solve(response2));
190 
191  // Are the path constraints created in the planning context?
192  path_constraints = pc->getPathConstraints();
193  EXPECT_FALSE(path_constraints->empty());
194  EXPECT_EQ(path_constraints->getPositionConstraints().size(), 1u);
195  EXPECT_TRUE(path_constraints->getOrientationConstraints().empty());
196 
197  // Check if all the states in the solution satisfy the path constraints.
198  // A detailed response returns 3 solutions: the ompl solution, the simplified solution and the interpolated
199  // solution. We test all of them here.
200  for (const robot_trajectory::RobotTrajectoryPtr& trajectory : response2.trajectory_)
201  {
202  for (std::size_t pt_index = 0; pt_index < trajectory->getWayPointCount(); ++pt_index)
203  {
204  EXPECT_TRUE(path_constraints->decide(trajectory->getWayPoint(pt_index)).satisfied);
205  }
206  }
207  }
208 
209 protected:
210  void SetUp() override
211  {
212  // create all the fixed input necessary for all planning context managers
213  constraint_sampler_manager_ = std::make_shared<constraint_samplers::ConstraintSamplerManager>();
214  planning_scene_ = std::make_shared<planning_scene::PlanningScene>(robot_model_);
215  }
216 
218  planning_interface::MotionPlanRequest createRequest(const std::vector<double>& start,
219  const std::vector<double>& goal) const
220  {
222  request.group_name = group_name_;
223  request.allowed_planning_time = 5.0;
224 
225  // fill out start state in request
227  start_state.setToDefaultValues();
228  start_state.setJointGroupPositions(joint_model_group_, start);
229  moveit::core::robotStateToRobotStateMsg(start_state, request.start_state);
230 
231  // fill out goal state in request
233  goal_state.setToDefaultValues();
234  goal_state.setJointGroupPositions(joint_model_group_, goal);
235 
236  moveit_msgs::msg::Constraints joint_goal =
238 
239  request.goal_constraints.push_back(joint_goal);
240 
241  return request;
242  }
243 
245  moveit_msgs::msg::PositionConstraint createPositionConstraint(std::array<double, 3> position,
246  std::array<double, 3> dimensions)
247  {
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];
254 
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;
260 
261  moveit_msgs::msg::PositionConstraint pc;
262  pc.header.frame_id = base_link_name_;
263  pc.link_name = ee_link_name_;
264  pc.constraint_region.primitives.push_back(box);
265  pc.constraint_region.primitive_poses.push_back(box_pose);
266 
267  return pc;
268  }
269 
271  moveit_msgs::msg::OrientationConstraint
272  createOrientationConstraint(const geometry_msgs::msg::Quaternion& nominal_orientation)
273  {
274  moveit_msgs::msg::OrientationConstraint oc;
275  oc.header.frame_id = base_link_name_;
276  oc.link_name = ee_link_name_;
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;
281 
282  return oc;
283  }
284 
285  ompl_interface::ModelBasedStateSpacePtr state_space_;
287  ompl_interface::ModelBasedPlanningContextPtr planning_context_;
288  planning_scene::PlanningScenePtr planning_scene_;
289 
290  constraint_samplers::ConstraintSamplerManagerPtr constraint_sampler_manager_;
291 
294  // std::shared_ptr<kinematics::KinematicsBase> ik_plugin_;
295 
298  rclcpp::Node::SharedPtr node_;
299 };
300 
301 /***************************************************************************
302  * Run all tests on the Panda robot
303  * ************************************************************************/
305 {
306 protected:
308  {
309  }
310 };
311 
312 TEST_F(PandaTestPlanningContext, testSimpleRequest)
313 {
314  // use the panda "ready" state from the srdf config as start state
315  // we know this state should be within limits and self-collision free
316  testSimpleRequest({ 0., -0.785, 0., -2.356, 0, 1.571, 0.785 }, { 0., -0.785, 0., -2.356, 0, 1.571, 0.685 });
317 }
318 
319 TEST_F(PandaTestPlanningContext, testPathConstraints)
320 {
321  testPathConstraints({ 0., -0.785, 0., -2.356, 0., 1.571, 0.785 }, { .0, -0.785, 0., -2.356, 0., 1.571, 0.685 });
322 }
323 
324 /***************************************************************************
325  * Run all tests on the Fanuc robot
326  * ************************************************************************/
328 {
329 protected:
330  FanucTestPlanningContext() : TestPlanningContext("fanuc", "manipulator")
331  {
332  }
333 };
334 
335 TEST_F(FanucTestPlanningContext, testSimpleRequest)
336 {
337  testSimpleRequest({ 0., 0., 0., 0., 0., 0. }, { 0., 0., 0., 0., 0., 0.1 });
338 }
339 
340 TEST_F(FanucTestPlanningContext, testPathConstraints)
341 {
342  testPathConstraints({ 0., 0., 0., 0., 0., 0. }, { 0., 0., 0., 0., 0., 0.1 });
343 }
344 
345 /***************************************************************************
346  * MAIN
347  * ************************************************************************/
348 int main(int argc, char** argv)
349 {
350  testing::InitGoogleTest(&argc, argv);
351  rclcpp::init(argc, argv);
352 
353  const int ret = RUN_ALL_TESTS();
354  rclcpp::shutdown();
355  return ret;
356 }
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_
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.
Definition: robot_state.h:90
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...
Definition: robot_state.h:605
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_
LoadTestRobot(const std::string &robot_name, const std::string &group_name)
const moveit::core::JointModelGroup * joint_model_group_
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....
Definition: utils.cpp:144
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.
x
Definition: pick.py:64
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)