moveit2
The MoveIt Motion Planning Framework for ROS 2.
unittest_planning_context.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2018 Pilz GmbH & Co. KG
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 Pilz GmbH & Co. KG 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 #include <boost/core/demangle.hpp>
36 #include <gtest/gtest.h>
37 
39 
44 
49 
50 #include "test_utils.h"
51 
52 // parameters from parameter server
53 const std::string PARAM_PLANNING_GROUP_NAME("planning_group");
54 const std::string PARAM_TARGET_LINK_NAME("target_link");
55 
62 template <typename T, int N>
64 {
65 public:
66  typedef T Type_;
67  static const int VALUE = N;
68 };
69 template <typename T, int N>
71 
78 
82 
86 template <typename T>
87 class PlanningContextTest : public ::testing::Test
88 {
89 protected:
90  void SetUp() override
91  {
92  rclcpp::NodeOptions node_options;
93  node_options.automatically_declare_parameters_from_overrides(true);
94  node_ = rclcpp::Node::make_shared("unittest_planning_context", node_options);
95 
96  // load robot model
97  rm_loader_ = std::make_unique<robot_model_loader::RobotModelLoader>(node_);
98  robot_model_ = rm_loader_->getModel();
99  ASSERT_FALSE(robot_model_ == nullptr) << "There is no robot model!";
100 
101  // get parameters
102  ASSERT_TRUE(node_->has_parameter(PARAM_PLANNING_GROUP_NAME)) << "Could not find parameter 'planning_group'";
103  node_->get_parameter<std::string>(PARAM_PLANNING_GROUP_NAME, planning_group_);
104 
105  ASSERT_TRUE(node_->has_parameter(PARAM_TARGET_LINK_NAME)) << "Could not find parameter 'target_link'";
106  node_->get_parameter<std::string>(PARAM_TARGET_LINK_NAME, target_link_);
107 
109  testutils::createFakeLimits(robot_model_->getVariableNames());
111  cartesian_limit.setMaxRotationalVelocity(1.0 * M_PI);
112  cartesian_limit.setMaxTranslationalAcceleration(1.0 * M_PI);
113  cartesian_limit.setMaxTranslationalDeceleration(1.0 * M_PI);
114  cartesian_limit.setMaxTranslationalVelocity(1.0 * M_PI);
115 
118  limits.setCartesianLimits(cartesian_limit);
119 
120  planning_context_ = std::unique_ptr<typename T::Type_>(
121  new typename T::Type_("TestPlanningContext", planning_group_, robot_model_, limits));
122 
123  // Define and set the current scene
124  auto scene = std::make_shared<planning_scene::PlanningScene>(robot_model_);
125  moveit::core::RobotState current_state(robot_model_);
126  current_state.setToDefaultValues();
127  current_state.setJointGroupPositions(planning_group_, std::vector<double>{ 0, 1.57, 1.57, 0, 0.2, 0 });
128  scene->setCurrentState(current_state);
129  planning_context_->setPlanningScene(scene); // TODO Check what happens if this is missing
130  }
131 
132  void TearDown() override
133  {
134  robot_model_.reset();
135  }
136 
140  planning_interface::MotionPlanRequest getValidRequest(const std::string& context_name) const
141  {
143 
144  req.planner_id =
145  std::string(context_name).erase(0, std::string("pilz_industrial_motion_planner::PlanningContext").length());
146  req.group_name = this->planning_group_;
147  req.max_velocity_scaling_factor = 0.01;
148  req.max_acceleration_scaling_factor = 0.01;
149 
150  // start state
152  rstate.setToDefaultValues();
153  // state state in joint space, used as initial positions, since IK does not
154  // work at zero positions
156  std::vector<double>{ 4.430233957464225e-12, 0.007881892504574495, -1.8157263253868452,
157  1.1801525390026025e-11, 1.8236082178909834,
158  8.591793942969161e-12 });
159  Eigen::Isometry3d start_pose(Eigen::Isometry3d::Identity());
160  start_pose.translation() = Eigen::Vector3d(0.3, 0, 0.65);
161  rstate.setFromIK(this->robot_model_->getJointModelGroup(this->planning_group_), start_pose);
162  moveit::core::robotStateToRobotStateMsg(rstate, req.start_state, false);
163 
164  // goal constraint
165  Eigen::Isometry3d goal_pose(Eigen::Isometry3d::Identity());
166  goal_pose.translation() = Eigen::Vector3d(0, 0.3, 0.65);
167  Eigen::Matrix3d goal_rotation;
168  goal_rotation = Eigen::AngleAxisd(0 * M_PI, Eigen::Vector3d::UnitZ());
169  goal_pose.linear() = goal_rotation;
170  rstate.setFromIK(this->robot_model_->getJointModelGroup(this->planning_group_), goal_pose);
171  req.goal_constraints.push_back(kinematic_constraints::constructGoalConstraints(
172  rstate, this->robot_model_->getJointModelGroup(this->planning_group_)));
173 
174  // path constraint
175  req.path_constraints.name = "center";
176  moveit_msgs::msg::PositionConstraint center_point;
177  center_point.link_name = this->target_link_;
178  geometry_msgs::msg::Pose center_position;
179  center_position.position.x = 0.0;
180  center_position.position.y = 0.0;
181  center_position.position.z = 0.65;
182  center_point.constraint_region.primitive_poses.push_back(center_position);
183  req.path_constraints.position_constraints.push_back(center_point);
184 
185  return req;
186  }
187 
188 protected:
189  // ros stuff
190  rclcpp::Node::SharedPtr node_;
191  moveit::core::RobotModelConstPtr robot_model_;
192  std::unique_ptr<robot_model_loader::RobotModelLoader> rm_loader_;
193 
194  std::unique_ptr<planning_interface::PlanningContext> planning_context_;
195 
197 };
198 
199 // Define the types we need to test
201 
207 {
209  bool result = this->planning_context_->solve(res);
210 
211  EXPECT_FALSE(result) << testutils::demangle(typeid(TypeParam).name());
212  EXPECT_EQ(moveit_msgs::msg::MoveItErrorCodes::INVALID_MOTION_PLAN, res.error_code_.val)
213  << testutils::demangle(typeid(TypeParam).name());
214 }
215 
219 TYPED_TEST(PlanningContextTest, SolveValidRequest)
220 {
222  planning_interface::MotionPlanRequest req = this->getValidRequest(testutils::demangle(typeid(TypeParam).name()));
223 
224  this->planning_context_->setMotionPlanRequest(req);
225 
226  // TODO Formulate valid request
227  bool result = this->planning_context_->solve(res);
228 
229  EXPECT_TRUE(result) << testutils::demangle(typeid(TypeParam).name());
230  EXPECT_EQ(moveit_msgs::msg::MoveItErrorCodes::SUCCESS, res.error_code_.val)
231  << testutils::demangle(typeid(TypeParam).name());
232 
234  bool result_detailed = this->planning_context_->solve(res_detailed);
235 
236  EXPECT_TRUE(result_detailed) << testutils::demangle(typeid(TypeParam).name());
237  EXPECT_EQ(moveit_msgs::msg::MoveItErrorCodes::SUCCESS, res.error_code_.val)
238  << testutils::demangle(typeid(TypeParam).name());
239 }
240 
244 TYPED_TEST(PlanningContextTest, SolveValidRequestDetailedResponse)
245 {
247  planning_interface::MotionPlanRequest req = this->getValidRequest(testutils::demangle(typeid(TypeParam).name()));
248 
249  this->planning_context_->setMotionPlanRequest(req);
250  bool result = this->planning_context_->solve(res);
251 
252  EXPECT_TRUE(result) << testutils::demangle(typeid(TypeParam).name());
253  EXPECT_EQ(moveit_msgs::msg::MoveItErrorCodes::SUCCESS, res.error_code_.val)
254  << testutils::demangle(typeid(TypeParam).name());
255 }
256 
260 TYPED_TEST(PlanningContextTest, SolveOnTerminated)
261 {
263  planning_interface::MotionPlanRequest req = this->getValidRequest(testutils::demangle(typeid(TypeParam).name()));
264 
265  this->planning_context_->setMotionPlanRequest(req);
266 
267  bool result_termination = this->planning_context_->terminate();
268  EXPECT_TRUE(result_termination) << testutils::demangle(typeid(TypeParam).name());
269 
270  bool result = this->planning_context_->solve(res);
271  EXPECT_FALSE(result) << testutils::demangle(typeid(TypeParam).name());
272 
273  EXPECT_EQ(moveit_msgs::msg::MoveItErrorCodes::PLANNING_FAILED, res.error_code_.val)
274  << testutils::demangle(typeid(TypeParam).name());
275 }
276 
281 {
282  EXPECT_NO_THROW(this->planning_context_->clear()) << testutils::demangle(typeid(TypeParam).name());
283 }
284 
285 int main(int argc, char** argv)
286 {
287  rclcpp::init(argc, argv);
288  testing::InitGoogleTest(&argc, argv);
289  return RUN_ALL_TESTS();
290 }
planning_interface::MotionPlanRequest getValidRequest(const std::string &context_name) const
Generate a valid fully defined request.
moveit::core::RobotModelConstPtr robot_model_
std::unique_ptr< planning_interface::PlanningContext > planning_context_
std::unique_ptr< robot_model_loader::RobotModelLoader > rm_loader_
rclcpp::Node::SharedPtr node_
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...
bool setFromIK(const JointModelGroup *group, const geometry_msgs::msg::Pose &pose, double timeout=0.0, const GroupStateValidityCallbackFn &constraint=GroupStateValidityCallbackFn(), const kinematics::KinematicsQueryOptions &options=kinematics::KinematicsQueryOptions(), const kinematics::KinematicsBase::IKCostFn &cost_function=kinematics::KinematicsBase::IKCostFn())
If the group this state corresponds to is a chain and a solver is available, then the joint values ca...
Set of cartesian limits, has values for velocity, acceleration and deceleration of both the translati...
void setMaxRotationalVelocity(double max_rot_vel)
Set the maximum rotational velocity.
void setMaxTranslationalVelocity(double max_trans_vel)
Set the maximal translational velocity.
void setMaxTranslationalAcceleration(double max_trans_acc)
Set the maximum translational acceleration.
void setMaxTranslationalDeceleration(double max_trans_dec)
Set the maximum translational deceleration.
Container for JointLimits, essentially a map with convenience functions. Adds the ability to as for l...
This class combines CartesianLimit and JointLimits into on single class.
void setCartesianLimits(CartesianLimit &cartesian_limit)
Set cartesian limits.
void setJointLimits(JointLimitsContainer &joint_limits)
Set joint limits.
Vec3fX< details::Vec3Data< double > > Vector3d
Definition: fcl_compat.h:89
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.
scene
Definition: pick.py:52
moveit_msgs::msg::MotionPlanRequest MotionPlanRequest
name
Definition: setup.py:7
pilz_industrial_motion_planner::JointLimitsContainer createFakeLimits(const std::vector< std::string > &joint_names)
Create limits for tests to avoid the need to get the limits from the node parameter.
Definition: test_utils.cpp:48
std::string demangle(char const *name)
Definition: test_utils.h:91
moveit_msgs::msg::MoveItErrorCodes error_code_
moveit_msgs::msg::MoveItErrorCodes error_code_
const std::string PARAM_PLANNING_GROUP_NAME("planning_group")
ValueTypeContainer< pilz_industrial_motion_planner::PlanningContextCIRC, 0 > CIRC_NO_GRIPPER
ValueTypeContainer< pilz_industrial_motion_planner::PlanningContextPTP, 1 > PTP_WITH_GRIPPER
int main(int argc, char **argv)
TYPED_TEST(PlanningContextTest, NoRequest)
No request is set. Check the output of solve. Using robot model without gripper.
const std::string PARAM_TARGET_LINK_NAME("target_link")
TYPED_TEST_SUITE(PlanningContextTest, PlanningContextTestTypes,)
::testing::Types< PTP_NO_GRIPPER, PTP_WITH_GRIPPER, LIN_NO_GRIPPER, LIN_WITH_GRIPPER, CIRC_NO_GRIPPER, CIRC_WITH_GRIPPER > PlanningContextTestTypes
ValueTypeContainer< pilz_industrial_motion_planner::PlanningContextLIN, 0 > LIN_NO_GRIPPER
ValueTypeContainer< pilz_industrial_motion_planner::PlanningContextPTP, 0 > PTP_NO_GRIPPER
ValueTypeContainer< pilz_industrial_motion_planner::PlanningContextCIRC, 1 > CIRC_WITH_GRIPPER
ValueTypeContainer< pilz_industrial_motion_planner::PlanningContextLIN, 1 > LIN_WITH_GRIPPER