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.hpp"
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 
122  cartesian_limits::Params cart_limits;
123  cart_limits.max_rot_vel = 0.5 * M_PI;
124  cart_limits.max_trans_acc = 2;
125  cart_limits.max_trans_dec = 2;
126  cart_limits.max_trans_vel = 1;
127 
128  planner_limits_.setJointLimits(joint_limits);
129  planner_limits_.setCartesianLimits(cart_limits);
130 
131  // initialize the LIN trajectory generator
132  lin_ = std::make_unique<TrajectoryGeneratorLIN>(robot_model_, planner_limits_, planning_group_);
133  ASSERT_NE(nullptr, lin_) << "Failed to create LIN trajectory generator.";
134  }
135 
136  void TearDown() override
137  {
138  robot_model_.reset();
139  }
140 
143  {
144  moveit_msgs::msg::MotionPlanResponse res_msg;
145  res.getMessage(res_msg);
146  if (!testutils::isGoalReached(robot_model_, res_msg.trajectory.joint_trajectory, req, pose_norm_tolerance_))
147  {
148  return false;
149  }
150 
151  if (!testutils::checkCartesianLinearity(robot_model_, res_msg.trajectory.joint_trajectory, req,
152  pose_norm_tolerance_, rot_axis_norm_tolerance_))
153  {
154  return false;
155  }
156 
157  if (!testutils::checkJointTrajectory(res_msg.trajectory.joint_trajectory, planner_limits_.getJointLimitContainer()))
158  {
159  return false;
160  }
161 
162  return true;
163  }
164 
165 protected:
166  // ros stuff
167  rclcpp::Node::SharedPtr node_;
168  moveit::core::RobotModelConstPtr robot_model_;
169  std::unique_ptr<robot_model_loader::RobotModelLoader> rm_loader_;
170  planning_scene::PlanningSceneConstPtr planning_scene_;
171 
172  // lin trajectory generator using model without gripper
173  std::unique_ptr<TrajectoryGenerator> lin_;
174  // test data provider
175  std::unique_ptr<pilz_industrial_motion_planner_testutils::TestdataLoader> tdp_;
176 
177  // test parameters from parameter server
178  std::string planning_group_, target_link_hcd_, test_data_file_name_;
180  double joint_position_tolerance_, joint_velocity_tolerance_, pose_norm_tolerance_, rot_axis_norm_tolerance_,
181  velocity_scaling_factor_, other_tolerance_;
183 };
184 
189 TEST_F(TrajectoryGeneratorLINTest, TestExceptionErrorCodeMapping)
190 {
191  {
192  auto ltcf_ex = std::make_shared<LinTrajectoryConversionFailure>("");
193  EXPECT_EQ(ltcf_ex->getErrorCode(), moveit_msgs::msg::MoveItErrorCodes::FAILURE);
194  }
195 
196  {
197  auto jnm_ex = std::make_shared<JointNumberMismatch>("");
198  EXPECT_EQ(jnm_ex->getErrorCode(), moveit_msgs::msg::MoveItErrorCodes::INVALID_GOAL_CONSTRAINTS);
199  }
200 
201  {
202  auto lifgi_ex = std::make_shared<LinInverseForGoalIncalculable>("");
203  EXPECT_EQ(lifgi_ex->getErrorCode(), moveit_msgs::msg::MoveItErrorCodes::NO_IK_SOLUTION);
204  }
205 }
206 
211 TEST_F(TrajectoryGeneratorLINTest, nonZeroStartVelocity)
212 {
213  planning_interface::MotionPlanRequest req{ tdp_->getLinJoint("lin2").toRequest() };
214 
215  // add non-zero velocity in the start state
216  req.start_state.joint_state.velocity.push_back(1.0);
217 
218  // try to generate the result
220  lin_->generate(planning_scene_, req, res);
221  EXPECT_EQ(res.error_code.val, moveit_msgs::msg::MoveItErrorCodes::INVALID_ROBOT_STATE);
222 }
223 
228 {
229  planning_interface::MotionPlanRequest lin_joint_req{ tdp_->getLinJoint("lin2").toRequest() };
230 
231  // generate the LIN trajectory
233  lin_->generate(planning_scene_, lin_joint_req, res);
234  EXPECT_TRUE(res.error_code.val == moveit_msgs::msg::MoveItErrorCodes::SUCCESS);
235 
236  // check the resulted trajectory
237  EXPECT_TRUE(checkLinResponse(lin_joint_req, res));
238 }
239 
244 TEST_F(TrajectoryGeneratorLINTest, jointSpaceGoalNearZeroStartVelocity)
245 {
246  planning_interface::MotionPlanRequest lin_joint_req{ tdp_->getLinJoint("lin2").toRequest() };
247 
248  // Set velocity near zero
249  lin_joint_req.start_state.joint_state.velocity =
250  std::vector<double>(lin_joint_req.start_state.joint_state.position.size(), 1e-16);
251 
252  // generate the LIN trajectory
254  lin_->generate(planning_scene_, lin_joint_req, res);
255  EXPECT_TRUE(res.error_code.val == moveit_msgs::msg::MoveItErrorCodes::SUCCESS);
256 
257  // check the resulted trajectory
258  EXPECT_TRUE(checkLinResponse(lin_joint_req, res));
259 }
260 
264 TEST_F(TrajectoryGeneratorLINTest, cartesianSpaceGoal)
265 {
266  // construct motion plan request
267  moveit_msgs::msg::MotionPlanRequest lin_cart_req{ tdp_->getLinCart("lin2").toRequest() };
268 
269  // generate lin trajectory
271  lin_->generate(planning_scene_, lin_cart_req, res);
272  EXPECT_TRUE(res.error_code.val == moveit_msgs::msg::MoveItErrorCodes::SUCCESS);
273 
274  // check the resulted trajectory
275  EXPECT_TRUE(checkLinResponse(lin_cart_req, res));
276 }
277 
286 TEST_F(TrajectoryGeneratorLINTest, cartesianTrapezoidProfile)
287 {
288  // construct motion plan request
289  moveit_msgs::msg::MotionPlanRequest lin_joint_req{ tdp_->getLinJoint("lin2").toRequest() };
290 
295  lin_->generate(planning_scene_, lin_joint_req, res, 0.01);
296  EXPECT_EQ(res.error_code.val, moveit_msgs::msg::MoveItErrorCodes::SUCCESS);
297 
298  ASSERT_TRUE(testutils::checkCartesianTranslationalPath(res.trajectory, target_link_hcd_));
299 
300  // check last point for vel=acc=0
301  for (size_t idx = 0; idx < res.trajectory->getLastWayPointPtr()->getVariableCount(); ++idx)
302  {
303  EXPECT_NEAR(0.0, res.trajectory->getLastWayPointPtr()->getVariableVelocity(idx), other_tolerance_);
304  EXPECT_NEAR(0.0, res.trajectory->getLastWayPointPtr()->getVariableAcceleration(idx), other_tolerance_);
305  }
306 }
307 
321 TEST_F(TrajectoryGeneratorLINTest, LinPlannerLimitViolation)
322 {
323  LinJoint lin{ tdp_->getLinJoint("lin2") };
324  lin.setAccelerationScale(1.01);
325 
327  lin_->generate(planning_scene_, lin.toRequest(), res);
328  ASSERT_FALSE(res.error_code.val == moveit_msgs::msg::MoveItErrorCodes::SUCCESS);
329 }
330 
342 TEST_F(TrajectoryGeneratorLINTest, LinPlannerDiscontinuousJointTraj)
343 {
344  LinJoint lin{ tdp_->getLinJoint("lin2") };
345  // Alter goal joint configuration (represents the same cartesian pose, but
346  // does not fit together with start config)
347  lin.getGoalConfiguration().setJoint(1, 1.63);
348  lin.getGoalConfiguration().setJoint(2, 0.96);
349  lin.getGoalConfiguration().setJoint(4, -2.48);
350  lin.setVelocityScale(1.0);
351  lin.setAccelerationScale(1.0);
352 
354  lin_->generate(planning_scene_, lin.toRequest(), res);
355  ASSERT_FALSE(res.error_code.val == moveit_msgs::msg::MoveItErrorCodes::SUCCESS);
356 }
357 
367 TEST_F(TrajectoryGeneratorLINTest, LinStartEqualsGoal)
368 {
369  // construct motion plan request
370  moveit_msgs::msg::MotionPlanRequest lin_joint_req{ tdp_->getLinJoint("lin2").toRequest() };
371 
372  moveit::core::RobotState start_state(robot_model_);
373  jointStateToRobotState(lin_joint_req.start_state.joint_state, start_state);
374 
375  for (auto& joint_constraint : lin_joint_req.goal_constraints.at(0).joint_constraints)
376  {
377  joint_constraint.position = start_state.getVariablePosition(joint_constraint.joint_name);
378  }
379 
380  // generate the LIN trajectory
382  lin_->generate(planning_scene_, lin_joint_req, res);
383  EXPECT_TRUE(res.error_code.val == moveit_msgs::msg::MoveItErrorCodes::SUCCESS);
384 
385  // check the resulted trajectory
386  EXPECT_TRUE(checkLinResponse(lin_joint_req, res));
387 }
388 
399 TEST_F(TrajectoryGeneratorLINTest, IncorrectJointNumber)
400 {
401  // construct motion plan request
402  moveit_msgs::msg::MotionPlanRequest lin_joint_req{ tdp_->getLinJoint("lin2").toRequest() };
403 
404  // Ensure that request consists of an incorrect number of joints.
405  lin_joint_req.goal_constraints.front().joint_constraints.pop_back();
406 
407  // generate the LIN trajectory
409  lin_->generate(planning_scene_, lin_joint_req, res);
410  EXPECT_TRUE(res.error_code.val == moveit_msgs::msg::MoveItErrorCodes::INVALID_GOAL_CONSTRAINTS);
411 }
412 
417 TEST_F(TrajectoryGeneratorLINTest, cartGoalFrameIdBothConstraints)
418 {
419  // construct motion plan request
420  moveit_msgs::msg::MotionPlanRequest lin_cart_req{ tdp_->getLinCart("lin2").toRequest() };
421 
422  lin_cart_req.goal_constraints.front().position_constraints.front().header.frame_id = robot_model_->getModelFrame();
423  lin_cart_req.goal_constraints.front().orientation_constraints.front().header.frame_id = robot_model_->getModelFrame();
424 
425  // generate lin trajectory
427  lin_->generate(planning_scene_, lin_cart_req, res);
428  EXPECT_TRUE(res.error_code.val == moveit_msgs::msg::MoveItErrorCodes::SUCCESS);
429 
430  // check the resulted trajectory
431  EXPECT_TRUE(checkLinResponse(lin_cart_req, res));
432 }
433 
434 int main(int argc, char** argv)
435 {
436  rclcpp::init(argc, argv);
437  testing::InitGoogleTest(&argc, argv);
438  return RUN_ALL_TESTS();
439 }
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.hpp: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.
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.
Data class storing all information regarding a linear command.
Definition: lin.hpp:48
void setAccelerationScale(double acceleration_scale)
Definition: motioncmd.hpp: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 verified.
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)
moveit::core::MoveItErrorCode error_code
robot_trajectory::RobotTrajectoryPtr trajectory
void getMessage(moveit_msgs::msg::MotionPlanResponse &msg) const
Construct a ROS message from struct data.
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")