moveit2
The MoveIt Motion Planning Framework for ROS 2.
unittest_trajectory_generator_common.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 
44 
51 
52 #include "test_utils.h"
53 
54 #include <rclcpp/rclcpp.hpp>
55 
56 const std::string PARAM_MODEL_NO_GRIPPER_NAME{ "robot_description" };
57 const std::string PARAM_MODEL_WITH_GRIPPER_NAME{ "robot_description_pg70" };
58 const std::string PARAM_NAMESPACE_LIMITS{ "robot_description_planning" };
59 
66 template <typename T, int N>
68 {
69 public:
70  typedef T Type_;
71  static const int VALUE = N;
72 };
73 template <typename T, int N>
75 
82 
86 
87 typedef ::testing::Types<PTP_NO_GRIPPER, LIN_NO_GRIPPER, CIRC_NO_GRIPPER> TrajectoryGeneratorCommonTestTypesNoGripper;
88 
89 typedef ::testing::Types<PTP_WITH_GRIPPER, LIN_WITH_GRIPPER, CIRC_WITH_GRIPPER>
91 
95 template <typename T>
96 class TrajectoryGeneratorCommonTest : public ::testing::Test
97 {
98 protected:
99  void SetUp() override
100  {
101  rclcpp::NodeOptions node_options;
102  node_options.automatically_declare_parameters_from_overrides(true);
103  node_ = rclcpp::Node::make_shared("unittest_trajectory_generator_common", node_options);
104 
105  // load robot model
106  // const std::string robot_description_param = (!T::VALUE ? PARAM_MODEL_NO_GRIPPER_NAME : PARAM_MODEL_WITH_GRIPPER_NAME);
108  robot_model_ = rm_loader.getModel();
109  ASSERT_TRUE(bool(robot_model_)) << "Failed to load robot model";
110  planning_scene_ = std::make_shared<planning_scene::PlanningScene>(robot_model_);
111 
112  // get parameters
113  ASSERT_TRUE(node_->has_parameter("planning_group"));
114  node_->get_parameter<std::string>("planning_group", planning_group_);
115  ASSERT_TRUE(node_->has_parameter("target_link"));
116  node_->get_parameter<std::string>("target_link", target_link_);
117 
119 
120  // create the limits container
123  node_, PARAM_NAMESPACE_LIMITS, robot_model_->getActiveJointModels());
125  cart_limits.setMaxRotationalVelocity(0.5 * M_PI);
126  cart_limits.setMaxTranslationalAcceleration(2);
127  cart_limits.setMaxTranslationalDeceleration(2);
128  cart_limits.setMaxTranslationalVelocity(1);
130  planner_limits.setJointLimits(joint_limits);
131  planner_limits.setCartesianLimits(cart_limits);
132 
133  // create planner instance
134  trajectory_generator_ = std::make_unique<typename T::Type_>(robot_model_, planner_limits, planning_group_);
135  ASSERT_NE(nullptr, trajectory_generator_) << "failed to create trajectory generator";
136 
137  // create a valid motion plan request with goal in joint space as basis for
138  // tests
139  req_.group_name = planning_group_;
140  req_.max_velocity_scaling_factor = 1.0;
141  req_.max_acceleration_scaling_factor = 1.0;
143  rstate.setToDefaultValues();
144  rstate.setJointGroupPositions(planning_group_, std::vector<double>{ 0, M_PI / 2, 0, M_PI / 2, 0, 0 });
145  rstate.setVariableVelocities(std::vector<double>(rstate.getVariableCount(), 0.0));
146  moveit::core::robotStateToRobotStateMsg(rstate, req_.start_state, false);
147  moveit_msgs::msg::Constraints goal_constraint;
148  moveit_msgs::msg::JointConstraint joint_constraint;
149  joint_constraint.joint_name = this->robot_model_->getActiveJointModels().front()->getName();
150  joint_constraint.position = 0.5;
151  goal_constraint.joint_constraints.push_back(joint_constraint);
152  req_.goal_constraints.push_back(goal_constraint);
153  }
154 
155 protected:
156  // ros stuff
157  rclcpp::Node::SharedPtr node_;
158  moveit::core::RobotModelConstPtr robot_model_;
159  planning_scene::PlanningSceneConstPtr planning_scene_;
160 
161  // trajectory generator
162  std::unique_ptr<pilz_industrial_motion_planner::TrajectoryGenerator> trajectory_generator_;
165  // test parameters from parameter server
167 };
168 // Define the types we need to test
170 
171 template <typename T>
173 {
174 };
176 
177 // TODO(henningkayser):Enable tests with gripper support
178 // template <typename T>
179 // class TrajectoryGeneratorCommonTestWithGripper : public TrajectoryGeneratorCommonTest<T>
180 // {
181 // };
182 // TYPED_TEST_SUITE(TrajectoryGeneratorCommonTestWithGripper, TrajectoryGeneratorCommonTestTypesWithGripper, /* ... */);
183 
189 {
190  this->req_.max_velocity_scaling_factor = 2.0;
191  EXPECT_FALSE(this->trajectory_generator_->generate(this->planning_scene_, this->req_, this->res_));
192  EXPECT_EQ(this->res_.error_code_.val, moveit_msgs::msg::MoveItErrorCodes::INVALID_MOTION_PLAN);
193 
194  this->req_.max_velocity_scaling_factor = 1.0;
195  this->req_.max_acceleration_scaling_factor = 0;
196  EXPECT_FALSE(this->trajectory_generator_->generate(this->planning_scene_, this->req_, this->res_));
197  EXPECT_EQ(this->res_.error_code_.val, moveit_msgs::msg::MoveItErrorCodes::INVALID_MOTION_PLAN);
198 
199  this->req_.max_velocity_scaling_factor = 0.00001;
200  this->req_.max_acceleration_scaling_factor = 1;
201  EXPECT_FALSE(this->trajectory_generator_->generate(this->planning_scene_, this->req_, this->res_));
202  EXPECT_EQ(this->res_.error_code_.val, moveit_msgs::msg::MoveItErrorCodes::INVALID_MOTION_PLAN);
203 
204  this->req_.max_velocity_scaling_factor = 1;
205  this->req_.max_acceleration_scaling_factor = -1;
206  EXPECT_FALSE(this->trajectory_generator_->generate(this->planning_scene_, this->req_, this->res_));
207  EXPECT_EQ(this->res_.error_code_.val, moveit_msgs::msg::MoveItErrorCodes::INVALID_MOTION_PLAN);
208 }
209 
214 {
215  this->req_.group_name = "foot";
216  EXPECT_FALSE(this->trajectory_generator_->generate(this->planning_scene_, this->req_, this->res_));
217  EXPECT_EQ(moveit_msgs::msg::MoveItErrorCodes::INVALID_GROUP_NAME, this->res_.error_code_.val);
218 }
219 
224 {
225  this->req_.group_name = "gripper";
226  EXPECT_FALSE(this->trajectory_generator_->generate(this->planning_scene_, this->req_, this->res_));
227  EXPECT_EQ(moveit_msgs::msg::MoveItErrorCodes::INVALID_GROUP_NAME, this->res_.error_code_.val);
228 }
229 
233 // TYPED_TEST(TrajectoryGeneratorCommonTestWithGripper, GripperGroup)
234 // {
235 // this->req_.group_name = "gripper";
236 // EXPECT_FALSE(this->trajectory_generator_->generate(this->planning_scene_, this->req_, this->res_));
237 // EXPECT_EQ(moveit_msgs::msg::MoveItErrorCodes::INVALID_GOAL_CONSTRAINTS, this->res_.error_code_.val);
238 // }
239 
248 // TYPED_TEST(TrajectoryGeneratorCommonTest, NoIKSolver)
249 //{
250 // EXPECT_FALSE(this->trajectory_generator_->generate(this->req_, this->res_));
251 // EXPECT_EQ(this->res_.error_code_.val,
252 // moveit_msgs::msg::MoveItErrorCodes::INVALID_GROUP_NAME);
253 //}
254 
258 TYPED_TEST(TrajectoryGeneratorCommonTest, EmptyJointNamesInStartState)
259 {
260  this->req_.start_state.joint_state.name.clear();
261  EXPECT_FALSE(this->trajectory_generator_->generate(this->planning_scene_, this->req_, this->res_));
262  EXPECT_EQ(this->res_.error_code_.val, moveit_msgs::msg::MoveItErrorCodes::INVALID_ROBOT_STATE);
263 }
264 
269 {
270  this->req_.start_state.joint_state.name.push_back("joint_7");
271  EXPECT_FALSE(this->trajectory_generator_->generate(this->planning_scene_, this->req_, this->res_));
272  EXPECT_EQ(this->res_.error_code_.val, moveit_msgs::msg::MoveItErrorCodes::INVALID_ROBOT_STATE);
273 }
274 
279 {
280  this->req_.start_state.joint_state.position[0] = 100;
281  EXPECT_FALSE(this->trajectory_generator_->generate(this->planning_scene_, this->req_, this->res_));
282  EXPECT_EQ(this->res_.error_code_.val, moveit_msgs::msg::MoveItErrorCodes::INVALID_ROBOT_STATE);
283 }
284 
292 TYPED_TEST(TrajectoryGeneratorCommonTest, StartPositionVelocityNoneZero)
293 {
294  this->req_.start_state.joint_state.velocity[0] = 100;
295  EXPECT_FALSE(this->trajectory_generator_->generate(this->planning_scene_, this->req_, this->res_));
296  EXPECT_EQ(this->res_.error_code_.val, moveit_msgs::msg::MoveItErrorCodes::INVALID_ROBOT_STATE);
297 }
298 
303 {
304  this->req_.goal_constraints.clear();
305  EXPECT_FALSE(this->trajectory_generator_->generate(this->planning_scene_, this->req_, this->res_));
306  EXPECT_EQ(this->res_.error_code_.val, moveit_msgs::msg::MoveItErrorCodes::INVALID_GOAL_CONSTRAINTS);
307 }
308 
313 {
314  moveit_msgs::msg::JointConstraint joint_constraint;
315  moveit_msgs::msg::PositionConstraint position_constraint;
316  moveit_msgs::msg::OrientationConstraint orientation_constraint;
317  moveit_msgs::msg::Constraints goal_constraint;
318 
319  // two goal constraints
320  this->req_.goal_constraints.push_back(goal_constraint);
321  this->req_.goal_constraints.push_back(goal_constraint);
322  EXPECT_FALSE(this->trajectory_generator_->generate(this->planning_scene_, this->req_, this->res_));
323  EXPECT_EQ(this->res_.error_code_.val, moveit_msgs::msg::MoveItErrorCodes::INVALID_GOAL_CONSTRAINTS);
324 
325  // one joint constraint and one orientation constraint
326  goal_constraint.joint_constraints.push_back(joint_constraint);
327  goal_constraint.orientation_constraints.push_back(orientation_constraint);
328  this->req_.goal_constraints.clear();
329  this->req_.goal_constraints.push_back(goal_constraint);
330  EXPECT_FALSE(this->trajectory_generator_->generate(this->planning_scene_, this->req_, this->res_));
331  EXPECT_EQ(this->res_.error_code_.val, moveit_msgs::msg::MoveItErrorCodes::INVALID_GOAL_CONSTRAINTS);
332 
333  // one joint constraint and one Cartesian constraint
334  goal_constraint.position_constraints.push_back(position_constraint);
335  goal_constraint.orientation_constraints.push_back(orientation_constraint);
336  this->req_.goal_constraints.clear();
337  this->req_.goal_constraints.push_back(goal_constraint);
338  EXPECT_FALSE(this->trajectory_generator_->generate(this->planning_scene_, this->req_, this->res_));
339  EXPECT_EQ(this->res_.error_code_.val, moveit_msgs::msg::MoveItErrorCodes::INVALID_GOAL_CONSTRAINTS);
340 
341  // two Cartesian constraints
342  goal_constraint.joint_constraints.clear();
343  goal_constraint.position_constraints.push_back(position_constraint);
344  goal_constraint.orientation_constraints.push_back(orientation_constraint);
345  goal_constraint.position_constraints.push_back(position_constraint);
346  goal_constraint.orientation_constraints.push_back(orientation_constraint);
347  this->req_.goal_constraints.clear();
348  this->req_.goal_constraints.push_back(goal_constraint);
349  EXPECT_FALSE(this->trajectory_generator_->generate(this->planning_scene_, this->req_, this->res_));
350  EXPECT_EQ(this->res_.error_code_.val, moveit_msgs::msg::MoveItErrorCodes::INVALID_GOAL_CONSTRAINTS);
351 }
352 
356 TYPED_TEST(TrajectoryGeneratorCommonTest, InvalideJointNameInGoal)
357 {
358  moveit_msgs::msg::JointConstraint joint_constraint;
359  joint_constraint.joint_name = "test_joint_2";
360  this->req_.goal_constraints.front().joint_constraints[0] = joint_constraint;
361  EXPECT_FALSE(this->trajectory_generator_->generate(this->planning_scene_, this->req_, this->res_));
362  EXPECT_EQ(this->res_.error_code_.val, moveit_msgs::msg::MoveItErrorCodes::INVALID_GOAL_CONSTRAINTS);
363 }
364 
369 {
370  moveit_msgs::msg::JointConstraint joint_constraint;
371  joint_constraint.joint_name = "test_joint_2";
372  this->req_.goal_constraints.front().joint_constraints.pop_back(); //<-- Missing joint constraint
373  EXPECT_FALSE(this->trajectory_generator_->generate(this->planning_scene_, this->req_, this->res_));
374  EXPECT_EQ(this->res_.error_code_.val, moveit_msgs::msg::MoveItErrorCodes::INVALID_GOAL_CONSTRAINTS);
375 }
376 
380 TYPED_TEST(TrajectoryGeneratorCommonTest, InvalideJointPositionInGoal)
381 {
382  this->req_.goal_constraints.front().joint_constraints[0].position = 100;
383  EXPECT_FALSE(this->trajectory_generator_->generate(this->planning_scene_, this->req_, this->res_));
384  EXPECT_EQ(this->res_.error_code_.val, moveit_msgs::msg::MoveItErrorCodes::INVALID_GOAL_CONSTRAINTS);
385 }
386 
390 TYPED_TEST(TrajectoryGeneratorCommonTest, InvalidLinkNameInCartesianGoal)
391 {
392  moveit_msgs::msg::PositionConstraint position_constraint;
393  moveit_msgs::msg::OrientationConstraint orientation_constraint;
394  moveit_msgs::msg::Constraints goal_constraint;
395  // link name not set
396  goal_constraint.position_constraints.push_back(position_constraint);
397  goal_constraint.orientation_constraints.push_back(orientation_constraint);
398  this->req_.goal_constraints.clear();
399  this->req_.goal_constraints.push_back(goal_constraint);
400  EXPECT_FALSE(this->trajectory_generator_->generate(this->planning_scene_, this->req_, this->res_));
401  EXPECT_EQ(this->res_.error_code_.val, moveit_msgs::msg::MoveItErrorCodes::INVALID_GOAL_CONSTRAINTS);
402 
403  // different link names in position and orientation goals
404  goal_constraint.position_constraints.front().link_name = "test_link_1";
405  goal_constraint.orientation_constraints.front().link_name = "test_link_2";
406  this->req_.goal_constraints.clear();
407  this->req_.goal_constraints.push_back(goal_constraint);
408  EXPECT_FALSE(this->trajectory_generator_->generate(this->planning_scene_, this->req_, this->res_));
409  EXPECT_EQ(this->res_.error_code_.val, moveit_msgs::msg::MoveItErrorCodes::INVALID_GOAL_CONSTRAINTS);
410 
411  // no solver for the link
412  goal_constraint.orientation_constraints.front().link_name = "test_link_1";
413  this->req_.goal_constraints.clear();
414  this->req_.goal_constraints.push_back(goal_constraint);
415  EXPECT_FALSE(this->trajectory_generator_->generate(this->planning_scene_, this->req_, this->res_));
416  EXPECT_EQ(this->res_.error_code_.val, moveit_msgs::msg::MoveItErrorCodes::NO_IK_SOLUTION);
417 }
418 
423 {
424  moveit_msgs::msg::PositionConstraint position_constraint;
425  moveit_msgs::msg::OrientationConstraint orientation_constraint;
426  moveit_msgs::msg::Constraints goal_constraint;
427  position_constraint.link_name =
428  this->robot_model_->getJointModelGroup(this->planning_group_)->getLinkModelNames().back();
429  orientation_constraint.link_name = position_constraint.link_name;
430 
431  goal_constraint.position_constraints.push_back(position_constraint);
432  goal_constraint.orientation_constraints.push_back(orientation_constraint);
433  this->req_.goal_constraints.clear();
434  this->req_.goal_constraints.push_back(goal_constraint);
435  EXPECT_FALSE(this->trajectory_generator_->generate(this->planning_scene_, this->req_, this->res_));
436  EXPECT_EQ(this->res_.error_code_.val, moveit_msgs::msg::MoveItErrorCodes::INVALID_GOAL_CONSTRAINTS);
437 }
438 
439 int main(int argc, char** argv)
440 {
441  rclcpp::init(argc, argv);
442  testing::InitGoogleTest(&argc, argv);
443  return RUN_ALL_TESTS();
444 }
std::unique_ptr< pilz_industrial_motion_planner::TrajectoryGenerator > trajectory_generator_
planning_scene::PlanningSceneConstPtr planning_scene_
planning_interface::MotionPlanRequest req_
planning_interface::MotionPlanResponse res_
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 setVariableVelocities(const double *velocity)
Given an array with velocity values for all variables, set those values as the velocities in this sta...
Definition: robot_state.h:253
void setToDefaultValues()
Set all joints to their default positions. The default position is 0, or if that is not within bounds...
std::size_t getVariableCount() const
Get the number of variables that make up this state.
Definition: robot_state.h:110
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.
static JointLimitsContainer getAggregatedLimits(const rclcpp::Node::SharedPtr &node, const std::string &param_namespace, const std::vector< const moveit::core::JointModel * > &joint_models)
Aggregates(combines) the joint limits from joint model and node parameters. The rules for the combina...
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.
const moveit::core::RobotModelPtr & getModel() const
Get the constructed planning_models::RobotModel.
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.
moveit_msgs::msg::MotionPlanRequest MotionPlanRequest
void checkRobotModel(const moveit::core::RobotModelConstPtr &robot_model, const std::string &group_name, const std::string &link_name)
::testing::Types< PTP_NO_GRIPPER, LIN_NO_GRIPPER, CIRC_NO_GRIPPER > TrajectoryGeneratorCommonTestTypesNoGripper
ValueTypeContainer< pilz_industrial_motion_planner::TrajectoryGeneratorCIRC, 1 > CIRC_WITH_GRIPPER
const std::string PARAM_MODEL_WITH_GRIPPER_NAME
ValueTypeContainer< pilz_industrial_motion_planner::TrajectoryGeneratorCIRC, 0 > CIRC_NO_GRIPPER
::testing::Types< PTP_WITH_GRIPPER, LIN_WITH_GRIPPER, CIRC_WITH_GRIPPER > TrajectoryGeneratorCommonTestTypesWithGripper
int main(int argc, char **argv)
ValueTypeContainer< pilz_industrial_motion_planner::TrajectoryGeneratorLIN, 0 > LIN_NO_GRIPPER
TYPED_TEST(TrajectoryGeneratorCommonTest, InvalideScalingFactor)
test invalid scaling factor. The scaling factor must be in the range of [0.0001, 1]
const std::string PARAM_MODEL_NO_GRIPPER_NAME
ValueTypeContainer< pilz_industrial_motion_planner::TrajectoryGeneratorPTP, 1 > PTP_WITH_GRIPPER
ValueTypeContainer< pilz_industrial_motion_planner::TrajectoryGeneratorPTP, 0 > PTP_NO_GRIPPER
TYPED_TEST_SUITE(TrajectoryGeneratorCommonTest, TrajectoryGeneratorCommonTestTypes,)
ValueTypeContainer< pilz_industrial_motion_planner::TrajectoryGeneratorLIN, 1 > LIN_WITH_GRIPPER
::testing::Types< PTP_NO_GRIPPER, PTP_WITH_GRIPPER, LIN_NO_GRIPPER, LIN_WITH_GRIPPER, CIRC_NO_GRIPPER, CIRC_WITH_GRIPPER > TrajectoryGeneratorCommonTestTypes
const std::string PARAM_NAMESPACE_LIMITS