moveit2
The MoveIt Motion Planning Framework for ROS 2.
unittest_trajectory_generator_lin.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 <memory>
36 
37 #include <gtest/gtest.h>
38 
43 #include "test_utils.h"
44 
50 
51 #include <rclcpp/rclcpp.hpp>
52 
53 using namespace pilz_industrial_motion_planner;
55 
56 static const std::string PARAM_NAMESPACE_LIMITS = "robot_description_planning";
57 
58 // Parameter names
59 const std::string TEST_DATA_FILE_NAME("testdata_file_name");
60 const std::string PARAM_PLANNING_GROUP_NAME("planning_group");
61 const std::string TARGET_LINK_HCD("target_link_hand_computed_data");
62 const std::string RANDOM_TEST_TRIAL_NUM("random_trial_number");
63 const std::string JOINT_POSITION_TOLERANCE("joint_position_tolerance");
64 const std::string JOINT_VELOCITY_TOLERANCE("joint_velocity_tolerance");
65 const std::string POSE_TRANSFORM_MATRIX_NORM_TOLERANCE("pose_norm_tolerance");
66 const std::string ROTATION_AXIS_NORM_TOLERANCE("rot_axis_norm_tolerance");
67 const std::string VELOCITY_SCALING_FACTOR("velocity_scaling_factor");
68 const std::string OTHER_TOLERANCE("other_tolerance");
69 
77 class TrajectoryGeneratorLINTest : public testing::Test
78 {
79 protected:
84  void SetUp() override
85  {
86  rclcpp::NodeOptions node_options;
87  node_options.automatically_declare_parameters_from_overrides(true);
88  node_ = rclcpp::Node::make_shared("unittest_trajectory_generator_lin", node_options);
89 
90  // load robot model
91  rm_loader_ = std::make_unique<robot_model_loader::RobotModelLoader>(node_);
92  robot_model_ = rm_loader_->getModel();
93  ASSERT_TRUE(bool(robot_model_)) << "Failed to load robot model";
94  planning_scene_ = std::make_shared<planning_scene::PlanningScene>(robot_model_);
95 
96  // get parameters
97  ASSERT_TRUE(node_->get_parameter(TEST_DATA_FILE_NAME, test_data_file_name_));
98  ASSERT_TRUE(node_->get_parameter(PARAM_PLANNING_GROUP_NAME, planning_group_));
99  ASSERT_TRUE(node_->get_parameter(TARGET_LINK_HCD, target_link_hcd_));
100  ASSERT_TRUE(node_->get_parameter(RANDOM_TEST_TRIAL_NUM, random_trial_num_));
101  ASSERT_TRUE(node_->get_parameter(JOINT_POSITION_TOLERANCE, joint_position_tolerance_));
102  ASSERT_TRUE(node_->get_parameter(JOINT_VELOCITY_TOLERANCE, joint_velocity_tolerance_));
103  ASSERT_TRUE(node_->get_parameter(POSE_TRANSFORM_MATRIX_NORM_TOLERANCE, pose_norm_tolerance_));
104  ASSERT_TRUE(node_->get_parameter(ROTATION_AXIS_NORM_TOLERANCE, rot_axis_norm_tolerance_));
105  ASSERT_TRUE(node_->get_parameter(VELOCITY_SCALING_FACTOR, velocity_scaling_factor_));
106  ASSERT_TRUE(node_->get_parameter(OTHER_TOLERANCE, other_tolerance_));
107 
108  testutils::checkRobotModel(robot_model_, planning_group_, target_link_hcd_);
109 
110  // load the test data provider
111  tdp_ = std::make_unique<pilz_industrial_motion_planner_testutils::XmlTestdataLoader>(test_data_file_name_);
112  ASSERT_NE(nullptr, tdp_) << "Failed to load test data by provider.";
113 
114  tdp_->setRobotModel(robot_model_);
115 
116  // create the limits container
117  // TODO, move this also into test data set
120  node_, PARAM_NAMESPACE_LIMITS, robot_model_->getActiveJointModels());
121  CartesianLimit cart_limits;
122  cart_limits.setMaxRotationalVelocity(0.5 * M_PI);
123  cart_limits.setMaxTranslationalAcceleration(2);
124  cart_limits.setMaxTranslationalDeceleration(2);
125  cart_limits.setMaxTranslationalVelocity(1);
126  planner_limits_.setJointLimits(joint_limits);
127  planner_limits_.setCartesianLimits(cart_limits);
128 
129  // initialize the LIN trajectory generator
130  lin_ = std::make_unique<TrajectoryGeneratorLIN>(robot_model_, planner_limits_, planning_group_);
131  ASSERT_NE(nullptr, lin_) << "Failed to create LIN trajectory generator.";
132  }
133 
134  void TearDown() override
135  {
136  robot_model_.reset();
137  }
138 
141  {
142  moveit_msgs::msg::MotionPlanResponse res_msg;
143  res.getMessage(res_msg);
144  if (!testutils::isGoalReached(robot_model_, res_msg.trajectory.joint_trajectory, req, pose_norm_tolerance_))
145  {
146  return false;
147  }
148 
149  if (!testutils::checkCartesianLinearity(robot_model_, res_msg.trajectory.joint_trajectory, req,
150  pose_norm_tolerance_, rot_axis_norm_tolerance_))
151  {
152  return false;
153  }
154 
155  if (!testutils::checkJointTrajectory(res_msg.trajectory.joint_trajectory, planner_limits_.getJointLimitContainer()))
156  {
157  return false;
158  }
159 
160  return true;
161  }
162 
163 protected:
164  // ros stuff
165  rclcpp::Node::SharedPtr node_;
166  moveit::core::RobotModelConstPtr robot_model_;
167  std::unique_ptr<robot_model_loader::RobotModelLoader> rm_loader_;
168  planning_scene::PlanningSceneConstPtr planning_scene_;
169 
170  // lin trajectory generator using model without gripper
171  std::unique_ptr<TrajectoryGenerator> lin_;
172  // test data provider
173  std::unique_ptr<pilz_industrial_motion_planner_testutils::TestdataLoader> tdp_;
174 
175  // test parameters from parameter server
176  std::string planning_group_, target_link_hcd_, test_data_file_name_;
178  double joint_position_tolerance_, joint_velocity_tolerance_, pose_norm_tolerance_, rot_axis_norm_tolerance_,
179  velocity_scaling_factor_, other_tolerance_;
181 };
182 
187 TEST_F(TrajectoryGeneratorLINTest, TestExceptionErrorCodeMapping)
188 {
189  {
190  std::shared_ptr<LinTrajectoryConversionFailure> ltcf_ex{ new LinTrajectoryConversionFailure("") };
191  EXPECT_EQ(ltcf_ex->getErrorCode(), moveit_msgs::msg::MoveItErrorCodes::FAILURE);
192  }
193 
194  {
195  std::shared_ptr<JointNumberMismatch> jnm_ex{ new JointNumberMismatch("") };
196  EXPECT_EQ(jnm_ex->getErrorCode(), moveit_msgs::msg::MoveItErrorCodes::INVALID_GOAL_CONSTRAINTS);
197  }
198 
199  {
200  std::shared_ptr<LinJointMissingInStartState> ljmiss_ex{ new LinJointMissingInStartState("") };
201  EXPECT_EQ(ljmiss_ex->getErrorCode(), moveit_msgs::msg::MoveItErrorCodes::INVALID_ROBOT_STATE);
202  }
203 
204  {
205  std::shared_ptr<LinInverseForGoalIncalculable> lifgi_ex{ new LinInverseForGoalIncalculable("") };
206  EXPECT_EQ(lifgi_ex->getErrorCode(), moveit_msgs::msg::MoveItErrorCodes::NO_IK_SOLUTION);
207  }
208 }
209 
214 TEST_F(TrajectoryGeneratorLINTest, nonZeroStartVelocity)
215 {
216  planning_interface::MotionPlanRequest req{ tdp_->getLinJoint("lin2").toRequest() };
217 
218  // add non-zero velocity in the start state
219  req.start_state.joint_state.velocity.push_back(1.0);
220 
221  // try to generate the result
223  EXPECT_FALSE(lin_->generate(planning_scene_, req, res));
224  EXPECT_EQ(res.error_code_.val, moveit_msgs::msg::MoveItErrorCodes::INVALID_ROBOT_STATE);
225 }
226 
231 {
232  planning_interface::MotionPlanRequest lin_joint_req{ tdp_->getLinJoint("lin2").toRequest() };
233 
234  // generate the LIN trajectory
236  ASSERT_TRUE(lin_->generate(planning_scene_, lin_joint_req, res));
237  EXPECT_TRUE(res.error_code_.val == moveit_msgs::msg::MoveItErrorCodes::SUCCESS);
238 
239  // check the resulted trajectory
240  EXPECT_TRUE(checkLinResponse(lin_joint_req, res));
241 }
242 
247 TEST_F(TrajectoryGeneratorLINTest, jointSpaceGoalNearZeroStartVelocity)
248 {
249  planning_interface::MotionPlanRequest lin_joint_req{ tdp_->getLinJoint("lin2").toRequest() };
250 
251  // Set velocity near zero
252  lin_joint_req.start_state.joint_state.velocity =
253  std::vector<double>(lin_joint_req.start_state.joint_state.position.size(), 1e-16);
254 
255  // generate the LIN trajectory
257  ASSERT_TRUE(lin_->generate(planning_scene_, lin_joint_req, res));
258  EXPECT_TRUE(res.error_code_.val == moveit_msgs::msg::MoveItErrorCodes::SUCCESS);
259 
260  // check the resulted trajectory
261  EXPECT_TRUE(checkLinResponse(lin_joint_req, res));
262 }
263 
267 TEST_F(TrajectoryGeneratorLINTest, cartesianSpaceGoal)
268 {
269  // construct motion plan request
270  moveit_msgs::msg::MotionPlanRequest lin_cart_req{ tdp_->getLinCart("lin2").toRequest() };
271 
272  // generate lin trajectory
274  ASSERT_TRUE(lin_->generate(planning_scene_, lin_cart_req, res));
275  EXPECT_TRUE(res.error_code_.val == moveit_msgs::msg::MoveItErrorCodes::SUCCESS);
276 
277  // check the resulted trajectory
278  EXPECT_TRUE(checkLinResponse(lin_cart_req, res));
279 }
280 
289 TEST_F(TrajectoryGeneratorLINTest, cartesianTrapezoidProfile)
290 {
291  // construct motion plan request
292  moveit_msgs::msg::MotionPlanRequest lin_joint_req{ tdp_->getLinJoint("lin2").toRequest() };
293 
298  ASSERT_TRUE(lin_->generate(planning_scene_, lin_joint_req, res, 0.01));
299  EXPECT_EQ(res.error_code_.val, moveit_msgs::msg::MoveItErrorCodes::SUCCESS);
300 
301  ASSERT_TRUE(testutils::checkCartesianTranslationalPath(res.trajectory_, target_link_hcd_));
302 
303  // check last point for vel=acc=0
304  for (size_t idx = 0; idx < res.trajectory_->getLastWayPointPtr()->getVariableCount(); ++idx)
305  {
306  EXPECT_NEAR(0.0, res.trajectory_->getLastWayPointPtr()->getVariableVelocity(idx), other_tolerance_);
307  EXPECT_NEAR(0.0, res.trajectory_->getLastWayPointPtr()->getVariableAcceleration(idx), other_tolerance_);
308  }
309 }
310 
324 TEST_F(TrajectoryGeneratorLINTest, LinPlannerLimitViolation)
325 {
326  LinJoint lin{ tdp_->getLinJoint("lin2") };
327  lin.setAccelerationScale(1.01);
328 
330  ASSERT_FALSE(lin_->generate(planning_scene_, lin.toRequest(), res));
331 }
332 
344 TEST_F(TrajectoryGeneratorLINTest, LinPlannerDiscontinuousJointTraj)
345 {
346  LinJoint lin{ tdp_->getLinJoint("lin2") };
347  // Alter goal joint configuration (represents the same cartesian pose, but
348  // does not fit together with start config)
349  lin.getGoalConfiguration().setJoint(1, 1.63);
350  lin.getGoalConfiguration().setJoint(2, 0.96);
351  lin.getGoalConfiguration().setJoint(4, -2.48);
352  lin.setVelocityScale(1.0);
353  lin.setAccelerationScale(1.0);
354 
356  ASSERT_FALSE(lin_->generate(planning_scene_, lin.toRequest(), res));
357 }
358 
368 TEST_F(TrajectoryGeneratorLINTest, LinStartEqualsGoal)
369 {
370  // construct motion plan request
371  moveit_msgs::msg::MotionPlanRequest lin_joint_req{ tdp_->getLinJoint("lin2").toRequest() };
372 
373  moveit::core::RobotState start_state(robot_model_);
374  jointStateToRobotState(lin_joint_req.start_state.joint_state, start_state);
375 
376  for (auto& joint_constraint : lin_joint_req.goal_constraints.at(0).joint_constraints)
377  {
378  joint_constraint.position = start_state.getVariablePosition(joint_constraint.joint_name);
379  }
380 
381  // generate the LIN trajectory
383  ASSERT_TRUE(lin_->generate(planning_scene_, lin_joint_req, res));
384  EXPECT_TRUE(res.error_code_.val == moveit_msgs::msg::MoveItErrorCodes::SUCCESS);
385 
386  // check the resulted trajectory
387  EXPECT_TRUE(checkLinResponse(lin_joint_req, res));
388 }
389 
400 {
402 
403  EXPECT_THROW(pilz_industrial_motion_planner::TrajectoryGeneratorLIN(robot_model_, planner_limits, planning_group_),
404  pilz_industrial_motion_planner::TrajectoryGeneratorInvalidLimitsException);
405 }
406 
417 TEST_F(TrajectoryGeneratorLINTest, IncorrectJointNumber)
418 {
419  // construct motion plan request
420  moveit_msgs::msg::MotionPlanRequest lin_joint_req{ tdp_->getLinJoint("lin2").toRequest() };
421 
422  // Ensure that request consists of an incorrect number of joints.
423  lin_joint_req.goal_constraints.front().joint_constraints.pop_back();
424 
425  // generate the LIN trajectory
427  ASSERT_FALSE(lin_->generate(planning_scene_, lin_joint_req, res));
428  EXPECT_TRUE(res.error_code_.val == moveit_msgs::msg::MoveItErrorCodes::INVALID_GOAL_CONSTRAINTS);
429 }
430 
435 TEST_F(TrajectoryGeneratorLINTest, cartGoalIncompleteStartState)
436 {
437  // construct motion plan request
438  moveit_msgs::msg::MotionPlanRequest lin_cart_req{ tdp_->getLinCart("lin2").toRequest() };
439  EXPECT_GT(lin_cart_req.start_state.joint_state.name.size(), 1u);
440  lin_cart_req.start_state.joint_state.name.resize(1);
441  lin_cart_req.start_state.joint_state.position.resize(1); // prevent failing check for equal sizes
442 
443  // generate lin trajectory
445  EXPECT_FALSE(lin_->generate(planning_scene_, lin_cart_req, res));
446  EXPECT_EQ(res.error_code_.val, moveit_msgs::msg::MoveItErrorCodes::INVALID_ROBOT_STATE);
447 }
448 
453 TEST_F(TrajectoryGeneratorLINTest, cartGoalFrameIdBothConstraints)
454 {
455  // construct motion plan request
456  moveit_msgs::msg::MotionPlanRequest lin_cart_req{ tdp_->getLinCart("lin2").toRequest() };
457 
458  lin_cart_req.goal_constraints.front().position_constraints.front().header.frame_id = robot_model_->getModelFrame();
459  lin_cart_req.goal_constraints.front().orientation_constraints.front().header.frame_id = robot_model_->getModelFrame();
460 
461  // generate lin trajectory
463  ASSERT_TRUE(lin_->generate(planning_scene_, lin_cart_req, res));
464  EXPECT_TRUE(res.error_code_.val == moveit_msgs::msg::MoveItErrorCodes::SUCCESS);
465 
466  // check the resulted trajectory
467  EXPECT_TRUE(checkLinResponse(lin_cart_req, res));
468 }
469 
470 int main(int argc, char** argv)
471 {
472  rclcpp::init(argc, argv);
473  testing::InitGoogleTest(&argc, argv);
474  return RUN_ALL_TESTS();
475 }
Parameterized unittest of trajectory generator LIN to enable tests against different robot models....
bool checkLinResponse(const planning_interface::MotionPlanRequest &req, const planning_interface::MotionPlanResponse &res)
moveit::core::RobotModelConstPtr robot_model_
std::unique_ptr< pilz_industrial_motion_planner_testutils::TestdataLoader > tdp_
void SetUp() override
Create test scenario for lin trajectory generator.
std::unique_ptr< TrajectoryGenerator > lin_
planning_scene::PlanningSceneConstPtr planning_scene_
std::unique_ptr< robot_model_loader::RobotModelLoader > rm_loader_
Representation of a robot's state. This includes position, velocity, acceleration and effort.
Definition: robot_state.h:90
double getVariablePosition(const std::string &variable) const
Get the position of a particular variable. An exception is thrown if the variable is not known.
Definition: robot_state.h:207
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.
This class implements a linear trajectory generator in Cartesian space. The Cartesian trajetory are b...
Data class storing all information regarding a linear command.
Definition: lin.h:48
void setAccelerationScale(double acceleration_scale)
Definition: motioncmd.h:84
bool jointStateToRobotState(const sensor_msgs::msg::JointState &joint_state, RobotState &state)
Convert a joint state to a MoveIt robot state.
TEST_F(GetSolverTipFrameIntegrationTest, TestHasSolverManipulator)
Check if hasSolver() can be called successfully for the manipulator group.
moveit_msgs::msg::MotionPlanRequest MotionPlanRequest
bool isGoalReached(const trajectory_msgs::msg::JointTrajectory &trajectory, const std::vector< moveit_msgs::msg::JointConstraint > &goal, const double joint_position_tolerance, const double joint_velocity_tolerance=1.0e-6)
check if the goal given in joint space is reached Only the last point in the trajectory is veryfied.
Definition: test_utils.cpp:118
::testing::AssertionResult checkCartesianTranslationalPath(const robot_trajectory::RobotTrajectoryConstPtr &trajectory, const std::string &link_name, const double acc_tol=DEFAULT_ACCELERATION_EQUALITY_TOLERANCE)
Check that the translational path of a given trajectory has a trapezoid velocity profile.
bool checkJointTrajectory(const trajectory_msgs::msg::JointTrajectory &trajectory, const pilz_industrial_motion_planner::JointLimitsContainer &joint_limits)
check joint trajectory of consistency, position, velocity and acceleration limits
Definition: test_utils.cpp:460
bool checkCartesianLinearity(const moveit::core::RobotModelConstPtr &robot_model, const trajectory_msgs::msg::JointTrajectory &trajectory, const planning_interface::MotionPlanRequest &req, const double translation_norm_tolerance, const double rot_axis_norm_tolerance, const double rot_angle_tolerance=10e-5)
Check that given trajectory is straight line.
Definition: test_utils.cpp:222
void checkRobotModel(const moveit::core::RobotModelConstPtr &robot_model, const std::string &group_name, const std::string &link_name)
robot_trajectory::RobotTrajectoryPtr trajectory_
void getMessage(moveit_msgs::msg::MotionPlanResponse &msg) const
moveit_msgs::msg::MoveItErrorCodes error_code_
const std::string PARAM_NAMESPACE_LIMITS
const std::string PARAM_PLANNING_GROUP_NAME("planning_group")
const std::string RANDOM_TEST_TRIAL_NUM("random_trial_number")
const std::string ROTATION_AXIS_NORM_TOLERANCE("rot_axis_norm_tolerance")
const std::string JOINT_POSITION_TOLERANCE("joint_position_tolerance")
int main(int argc, char **argv)
const std::string TARGET_LINK_HCD("target_link_hand_computed_data")
const std::string VELOCITY_SCALING_FACTOR("velocity_scaling_factor")
const std::string POSE_TRANSFORM_MATRIX_NORM_TOLERANCE("pose_norm_tolerance")
const std::string TEST_DATA_FILE_NAME("testdata_file_name")
const std::string OTHER_TOLERANCE("other_tolerance")
const std::string JOINT_VELOCITY_TOLERANCE("joint_velocity_tolerance")