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.h>
58 
66 
68 class TestPlanningContext : public ompl_interface_testing::LoadTestRobot, public testing::Test
69 {
70 public:
71  TestPlanningContext(const std::string& robot_name, const std::string& group_name)
72  : LoadTestRobot(robot_name, group_name)
73  {
74  }
75 
76  // /***************************************************************************
77  // * START Test implementations
78  // * ************************************************************************/
79 
80  void testSimpleRequest(const std::vector<double>& start, const std::vector<double>& goal)
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::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_handle_, 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  // create all the test specific input necessary to make the getPlanningContext call possible
117  pconfig_settings.group = group_name_;
118  pconfig_settings.name = group_name_;
119  pconfig_settings.config = { { "enforce_joint_model_state_space", "0" } };
120 
121  planning_interface::PlannerConfigurationMap pconfig_map{ { pconfig_settings.name, pconfig_settings } };
122  moveit_msgs::MoveItErrorCodes error_code;
124 
125  // give it some more time, as rejection sampling of the path constraints occasionally takes some time
126  request.allowed_planning_time = 10.0;
127 
128  // create path constraints around start state, to make sure they are satisfied
129  robot_state_->setJointGroupPositions(joint_model_group_, start);
130  Eigen::Isometry3d ee_pose = robot_state_->getGlobalLinkTransform(ee_link_name_);
131  geometry_msgs::Quaternion ee_orientation = tf2::toMsg(Eigen::Quaterniond(ee_pose.rotation()));
132 
133  // setup the planning context manager
135  pcm.setPlannerConfigurations(pconfig_map);
136 
137  // ORIENTATION CONSTRAINTS
138  // ***********************
139  request.path_constraints.orientation_constraints.push_back(createOrientationConstraint(ee_orientation));
140 
141  // See if the planning context manager returns the expected planning context
142  auto pc = pcm.getPlanningContext(planning_scene_, request, error_code, node_handle_, false);
143 
144  EXPECT_NE(pc->getOMPLSimpleSetup(), nullptr);
145 
146  // As the joint_model_group_ has no IK solver initialized, we expect a joint model state space
147  EXPECT_NE(dynamic_cast<ompl_interface::JointModelStateSpace*>(pc->getOMPLStateSpace().get()), nullptr);
148 
150  ASSERT_TRUE(pc->solve(response));
151 
152  // Are the path constraints created in the planning context?
153  auto path_constraints = pc->getPathConstraints();
154  EXPECT_FALSE(path_constraints->empty());
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());
159 
160  // Check if all the states in the solution satisfy the path constraints.
161  // A detailed response returns 3 solutions: the ompl solution, the simplified solution and the interpolated
162  // solution. We test all of them here.
163  for (const robot_trajectory::RobotTrajectoryPtr& trajectory : response.trajectory_)
164  {
165  for (std::size_t pt_index = { 0 }; pt_index < trajectory->getWayPointCount(); ++pt_index)
166  {
167  EXPECT_TRUE(path_constraints->decide(trajectory->getWayPoint(pt_index)).satisfied);
168  }
169  }
170 
171  // POSITION CONSTRAINTS
172  // ***********************
173  request.path_constraints.orientation_constraints.clear();
174  request.path_constraints.position_constraints.push_back(createPositionConstraint(
175  { ee_pose.translation().x(), ee_pose.translation().y(), ee_pose.translation().z() }, { 0.1, 0.1, 0.1 }));
176 
177  // See if the planning context manager returns the expected planning context
178  pc = pcm.getPlanningContext(planning_scene_, request, error_code, node_handle_, false);
179 
180  EXPECT_NE(pc->getOMPLSimpleSetup(), nullptr);
181 
182  // As the joint_model_group_ has no IK solver initialized, we expect a joint model state space
183  EXPECT_NE(dynamic_cast<ompl_interface::JointModelStateSpace*>(pc->getOMPLStateSpace().get()), nullptr);
184 
185  // Create a new response, because the solve method does not clear the given respone
187  ASSERT_TRUE(pc->solve(response2));
188 
189  // Are the path constraints created in the planning context?
190  path_constraints = pc->getPathConstraints();
191  EXPECT_FALSE(path_constraints->empty());
192  EXPECT_EQ(path_constraints->getPositionConstraints().size(), 1u);
193  EXPECT_TRUE(path_constraints->getOrientationConstraints().empty());
194 
195  // Check if all the states in the solution satisfy the path constraints.
196  // A detailed response returns 3 solutions: the ompl solution, the simplified solution and the interpolated
197  // solution. We test all of them here.
198  for (const robot_trajectory::RobotTrajectoryPtr& trajectory : response2.trajectory_)
199  {
200  for (std::size_t pt_index = { 0 }; pt_index < trajectory->getWayPointCount(); ++pt_index)
201  {
202  EXPECT_TRUE(path_constraints->decide(trajectory->getWayPoint(pt_index)).satisfied);
203  }
204  }
205  }
206 
207  // /***************************************************************************
208  // * END Test implementation
209  // * ************************************************************************/
210 
211 protected:
212  void SetUp() override
213  {
214  // create all the fixed input necessary for all planning context managers
215  constraint_sampler_manager_ = std::make_shared<constraint_samplers::ConstraintSamplerManager>();
216  planning_scene_ = std::make_shared<planning_scene::PlanningScene>(robot_model_);
217  }
218 
219  void TearDown() override
220  {
221  }
222 
224  planning_interface::MotionPlanRequest createRequest(const std::vector<double>& start,
225  const std::vector<double>& goal) const
226  {
228  request.group_name = group_name_;
229  request.allowed_planning_time = 5.0;
230 
231  // fill out start state in request
232  robot_state::RobotState start_state(robot_model_);
233  start_state.setToDefaultValues();
234  start_state.setJointGroupPositions(joint_model_group_, start);
235  moveit::core::robotStateToRobotStateMsg(start_state, request.start_state);
236 
237  // fill out goal state in request
238  robot_state::RobotState goal_state(robot_model_);
239  goal_state.setToDefaultValues();
240  goal_state.setJointGroupPositions(joint_model_group_, goal);
241  moveit_msgs::Constraints joint_goal =
243  request.goal_constraints.push_back(joint_goal);
244 
245  return request;
246  }
247 
249  moveit_msgs::PositionConstraint createPositionConstraint(std::array<double, 3> position,
250  std::array<double, 3> dimensions)
251  {
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];
258 
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;
264 
265  moveit_msgs::PositionConstraint pc;
266  pc.header.frame_id = base_link_name_;
267  pc.link_name = ee_link_name_;
268  pc.constraint_region.primitives.push_back(box);
269  pc.constraint_region.primitive_poses.push_back(box_pose);
270 
271  return pc;
272  }
273 
275  moveit_msgs::OrientationConstraint createOrientationConstraint(const geometry_msgs::Quaternion& nominal_orientation)
276  {
277  moveit_msgs::OrientationConstraint oc;
278  oc.header.frame_id = base_link_name_;
279  oc.link_name = ee_link_name_;
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;
284 
285  return oc;
286  }
287 
288  ompl_interface::ModelBasedStateSpacePtr state_space_;
290  ompl_interface::ModelBasedPlanningContextPtr planning_context_;
291  planning_scene::PlanningScenePtr planning_scene_;
292 
293  constraint_samplers::ConstraintSamplerManagerPtr constraint_sampler_manager_;
294 
297  // std::shared_ptr<kinematics::KinematicsBase> ik_plugin_;
298 
302 };
303 
304 /***************************************************************************
305  * Run all tests on the Panda robot
306  * ************************************************************************/
308 {
309 protected:
310  PandaTestPlanningContext() : TestPlanningContext("panda", "panda_arm")
311  {
312  }
313 };
314 
315 TEST_F(PandaTestPlanningContext, testSimpleRequest)
316 {
317  // use the panda "ready" state from the srdf config as start state
318  // we know this state should be within limits and self-collision free
319  testSimpleRequest({ 0, -0.785, 0, -2.356, 0, 1.571, 0.785 }, { 0, -0.785, 0, -2.356, 0, 1.571, 0.685 });
320 }
321 
322 TEST_F(PandaTestPlanningContext, testPathConstraints)
323 {
324  testPathConstraints({ 0, -0.785, 0, -2.356, 0, 1.571, 0.785 }, { 0, -0.785, 0, -2.356, 0, 1.571, 0.685 });
325 }
326 
327 /***************************************************************************
328  * Run all tests on the Fanuc robot
329  * ************************************************************************/
331 {
332 protected:
333  FanucTestPlanningContext() : TestPlanningContext("fanuc", "manipulator")
334  {
335  }
336 };
337 
338 TEST_F(FanucTestPlanningContext, testSimpleRequest)
339 {
340  testSimpleRequest({ 0, 0, 0, 0, 0, 0 }, { 0, 0, 0, 0, 0, 0.1 });
341 }
342 
343 TEST_F(FanucTestPlanningContext, testPathConstraints)
344 {
345  testPathConstraints({ 0, 0, 0, 0, 0, 0 }, { 0, 0, 0, 0, 0, 0.1 });
346 }
347 
348 /***************************************************************************
349  * MAIN
350  * ************************************************************************/
351 int main(int argc, char** argv)
352 {
353  ros::init(argc, argv, "planning_context_manager_test");
354  testing::InitGoogleTest(&argc, argv);
355  return RUN_ALL_TESTS();
356 }
response
const std::string response
FanucTestPlanningContext::FanucTestPlanningContext
FanucTestPlanningContext()
Definition: test_planning_context_manager.cpp:335
ompl_interface_testing::LoadTestRobot::ee_link_name_
std::string ee_link_name_
Definition: load_test_robot.h:192
ros::init
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
planning_request.h
tf2_eigen.h
utils.h
TestPlanningContext::createOrientationConstraint
moveit_msgs::OrientationConstraint createOrientationConstraint(const geometry_msgs::Quaternion &nominal_orientation)
Helper function to create a orientation constraint.
Definition: test_planning_context_manager.cpp:307
TestPlanningContext::TearDown
void TearDown() override
Definition: test_planning_context_manager.cpp:251
ompl_interface::JointModelStateSpace
Definition: joint_model_state_space.h:75
kinematic_constraints::constructGoalConstraints
moveit_msgs::Constraints constructGoalConstraints(const moveit::core::RobotState &state, const moveit::core::JointModelGroup *jmg, double tolerance=std::numeric_limits< double >::epsilon())
TestPlanningContext::node_handle_
ros::NodeHandle node_handle_
Definition: test_planning_context_manager.cpp:333
ompl_interface::PlanningContextManager
Definition: planning_context_manager.h:111
ompl_interface_testing::LoadTestRobot
Robot independent test class setup.
Definition: load_test_robot.h:130
TestPlanningContext::planning_context_
ompl_interface::ModelBasedPlanningContextPtr planning_context_
Definition: test_planning_context_manager.cpp:322
ompl_interface_testing::LoadTestRobot::base_link_name_
std::string base_link_name_
Definition: load_test_robot.h:191
ompl_interface_testing::LoadTestRobot::LoadTestRobot
LoadTestRobot(const std::string &robot_name, const std::string &group_name)
Definition: load_test_robot.h:165
planning_interface::PlannerConfigurationMap
std::map< std::string, PlannerConfigurationSettings > PlannerConfigurationMap
planning_interface::PlannerConfigurationSettings::name
std::string name
EXPECT_TRUE
#define EXPECT_TRUE(args)
ompl_interface_testing::LoadTestRobot::joint_model_group_
const robot_state::JointModelGroup * joint_model_group_
Definition: load_test_robot.h:188
load_test_robot.h
TestPlanningContext::constraint_sampler_manager_
constraint_samplers::ConstraintSamplerManagerPtr constraint_sampler_manager_
Definition: test_planning_context_manager.cpp:325
ompl_interface::PlanningContextManager::setPlannerConfigurations
void setPlannerConfigurations(const planning_interface::PlannerConfigurationMap &pconfig)
Specify configurations for the planners.
Definition: planning_context_manager.cpp:321
joint_model_state_space.h
main
int main(int argc, char **argv)
Definition: test_planning_context_manager.cpp:351
FanucTestPlanningContext
Definition: test_planning_context_manager.cpp:330
ompl_interface::PlanningContextManager::getPlanningContext
ModelBasedPlanningContextPtr getPlanningContext(const planning_scene::PlanningSceneConstPtr &planning_scene, const planning_interface::MotionPlanRequest &req, moveit_msgs::MoveItErrorCodes &error_code, const ros::NodeHandle &nh, bool use_constraints_approximations) const
Returns a planning context to OMPLInterface, which in turn passes it to OMPLPlannerManager.
Definition: planning_context_manager.cpp:427
planning_interface::PlannerConfigurationSettings::config
std::map< std::string, std::string > config
TestPlanningContext::planning_context_spec_
ompl_interface::ModelBasedPlanningContextSpecification planning_context_spec_
Definition: test_planning_context_manager.cpp:321
planning_interface::MotionPlanDetailedResponse::trajectory_
std::vector< robot_trajectory::RobotTrajectoryPtr > trajectory_
ompl_interface_testing::LoadTestRobot::group_name_
const std::string group_name_
Definition: load_test_robot.h:183
planning_interface::MotionPlanRequest
moveit_msgs::MotionPlanRequest MotionPlanRequest
ompl_interface_testing::LoadTestRobot::robot_state_
robot_state::RobotStatePtr robot_state_
Definition: load_test_robot.h:187
ompl_interface::ModelBasedPlanningContextSpecification
Definition: model_based_planning_context.h:95
PandaTestPlanningContext::PandaTestPlanningContext
PandaTestPlanningContext()
Definition: test_planning_context_manager.cpp:312
start
ROSCPP_DECL void start()
TestPlanningContext::state_space_
ompl_interface::ModelBasedStateSpacePtr state_space_
Definition: test_planning_context_manager.cpp:320
planning_context_manager.h
planning_scene.h
constraint_sampler_manager.h
TestPlanningContext::createPositionConstraint
moveit_msgs::PositionConstraint createPositionConstraint(std::array< double, 3 > position, std::array< double, 3 > dimensions)
Helper function to create a position constraint.
Definition: test_planning_context_manager.cpp:281
TestPlanningContext::TestPlanningContext
TestPlanningContext(const std::string &robot_name, const std::string &group_name)
Definition: test_planning_context_manager.cpp:103
TestPlanningContext::SetUp
void SetUp() override
Definition: test_planning_context_manager.cpp:244
tf2::toMsg
B toMsg(const A &a)
TEST_F
TEST_F(PandaTestPlanningContext, testSimpleRequest)
Definition: test_planning_context_manager.cpp:315
conversions.h
x
double x
planning_interface::PlannerConfigurationSettings
ompl_interface_testing::LoadTestRobot::robot_model_
moveit::core::RobotModelPtr robot_model_
Definition: load_test_robot.h:186
PandaTestPlanningContext
Definition: test_planning_context_manager.cpp:307
planning_interface::PlannerConfigurationSettings::group
std::string group
TestPlanningContext::testPathConstraints
void testPathConstraints(const std::vector< double > &start, const std::vector< double > &goal)
Definition: test_planning_context_manager.cpp:145
TestPlanningContext::planning_scene_
planning_scene::PlanningScenePtr planning_scene_
Definition: test_planning_context_manager.cpp:323
TestPlanningContext::createRequest
planning_interface::MotionPlanRequest createRequest(const std::vector< double > &start, const std::vector< double > &goal) const
Definition: test_planning_context_manager.cpp:256
moveit::core::robotStateToRobotStateMsg
void robotStateToRobotStateMsg(const RobotState &state, moveit_msgs::RobotState &robot_state, bool copy_attached_bodies=true)
EXPECT_EQ
#define EXPECT_EQ(a, b)
EXPECT_FALSE
#define EXPECT_FALSE(args)
TestPlanningContext::testSimpleRequest
void testSimpleRequest(const std::vector< double > &start, const std::vector< double > &goal)
Definition: test_planning_context_manager.cpp:112
ros::NodeHandle
planning_interface::MotionPlanDetailedResponse
TestPlanningContext
Generic implementation of the tests that can be executed on different robots.
Definition: test_planning_context_manager.cpp:68


ompl
Author(s): Ioan Sucan
autogenerated on Wed Feb 21 2024 03:26:02