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 
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 ljmiss_ex = std::make_shared<LinJointMissingInStartState>("");
203  EXPECT_EQ(ljmiss_ex->getErrorCode(), moveit_msgs::msg::MoveItErrorCodes::INVALID_ROBOT_STATE);
204  }
205 
206  {
207  auto lifgi_ex = std::make_shared<LinInverseForGoalIncalculable>("");
208  EXPECT_EQ(lifgi_ex->getErrorCode(), moveit_msgs::msg::MoveItErrorCodes::NO_IK_SOLUTION);
209  }
210 }
211 
216 TEST_F(TrajectoryGeneratorLINTest, nonZeroStartVelocity)
217 {
218  planning_interface::MotionPlanRequest req{ tdp_->getLinJoint("lin2").toRequest() };
219 
220  // add non-zero velocity in the start state
221  req.start_state.joint_state.velocity.push_back(1.0);
222 
223  // try to generate the result
225  lin_->generate(planning_scene_, req, res);
226  EXPECT_EQ(res.error_code.val, moveit_msgs::msg::MoveItErrorCodes::INVALID_ROBOT_STATE);
227 }
228 
233 {
234  planning_interface::MotionPlanRequest lin_joint_req{ tdp_->getLinJoint("lin2").toRequest() };
235 
236  // generate the LIN trajectory
238  lin_->generate(planning_scene_, lin_joint_req, res);
239  EXPECT_TRUE(res.error_code.val == moveit_msgs::msg::MoveItErrorCodes::SUCCESS);
240 
241  // check the resulted trajectory
242  EXPECT_TRUE(checkLinResponse(lin_joint_req, res));
243 }
244 
249 TEST_F(TrajectoryGeneratorLINTest, jointSpaceGoalNearZeroStartVelocity)
250 {
251  planning_interface::MotionPlanRequest lin_joint_req{ tdp_->getLinJoint("lin2").toRequest() };
252 
253  // Set velocity near zero
254  lin_joint_req.start_state.joint_state.velocity =
255  std::vector<double>(lin_joint_req.start_state.joint_state.position.size(), 1e-16);
256 
257  // generate the LIN trajectory
259  lin_->generate(planning_scene_, lin_joint_req, res);
260  EXPECT_TRUE(res.error_code.val == moveit_msgs::msg::MoveItErrorCodes::SUCCESS);
261 
262  // check the resulted trajectory
263  EXPECT_TRUE(checkLinResponse(lin_joint_req, res));
264 }
265 
269 TEST_F(TrajectoryGeneratorLINTest, cartesianSpaceGoal)
270 {
271  // construct motion plan request
272  moveit_msgs::msg::MotionPlanRequest lin_cart_req{ tdp_->getLinCart("lin2").toRequest() };
273 
274  // generate lin trajectory
276  lin_->generate(planning_scene_, lin_cart_req, res);
277  EXPECT_TRUE(res.error_code.val == moveit_msgs::msg::MoveItErrorCodes::SUCCESS);
278 
279  // check the resulted trajectory
280  EXPECT_TRUE(checkLinResponse(lin_cart_req, res));
281 }
282 
291 TEST_F(TrajectoryGeneratorLINTest, cartesianTrapezoidProfile)
292 {
293  // construct motion plan request
294  moveit_msgs::msg::MotionPlanRequest lin_joint_req{ tdp_->getLinJoint("lin2").toRequest() };
295 
300  lin_->generate(planning_scene_, lin_joint_req, res, 0.01);
301  EXPECT_EQ(res.error_code.val, moveit_msgs::msg::MoveItErrorCodes::SUCCESS);
302 
303  ASSERT_TRUE(testutils::checkCartesianTranslationalPath(res.trajectory, target_link_hcd_));
304 
305  // check last point for vel=acc=0
306  for (size_t idx = 0; idx < res.trajectory->getLastWayPointPtr()->getVariableCount(); ++idx)
307  {
308  EXPECT_NEAR(0.0, res.trajectory->getLastWayPointPtr()->getVariableVelocity(idx), other_tolerance_);
309  EXPECT_NEAR(0.0, res.trajectory->getLastWayPointPtr()->getVariableAcceleration(idx), other_tolerance_);
310  }
311 }
312 
326 TEST_F(TrajectoryGeneratorLINTest, LinPlannerLimitViolation)
327 {
328  LinJoint lin{ tdp_->getLinJoint("lin2") };
329  lin.setAccelerationScale(1.01);
330 
332  lin_->generate(planning_scene_, lin.toRequest(), res);
333  ASSERT_FALSE(res.error_code.val == moveit_msgs::msg::MoveItErrorCodes::SUCCESS);
334 }
335 
347 TEST_F(TrajectoryGeneratorLINTest, LinPlannerDiscontinuousJointTraj)
348 {
349  LinJoint lin{ tdp_->getLinJoint("lin2") };
350  // Alter goal joint configuration (represents the same cartesian pose, but
351  // does not fit together with start config)
352  lin.getGoalConfiguration().setJoint(1, 1.63);
353  lin.getGoalConfiguration().setJoint(2, 0.96);
354  lin.getGoalConfiguration().setJoint(4, -2.48);
355  lin.setVelocityScale(1.0);
356  lin.setAccelerationScale(1.0);
357 
359  lin_->generate(planning_scene_, lin.toRequest(), res);
360  ASSERT_FALSE(res.error_code.val == moveit_msgs::msg::MoveItErrorCodes::SUCCESS);
361 }
362 
372 TEST_F(TrajectoryGeneratorLINTest, LinStartEqualsGoal)
373 {
374  // construct motion plan request
375  moveit_msgs::msg::MotionPlanRequest lin_joint_req{ tdp_->getLinJoint("lin2").toRequest() };
376 
377  moveit::core::RobotState start_state(robot_model_);
378  jointStateToRobotState(lin_joint_req.start_state.joint_state, start_state);
379 
380  for (auto& joint_constraint : lin_joint_req.goal_constraints.at(0).joint_constraints)
381  {
382  joint_constraint.position = start_state.getVariablePosition(joint_constraint.joint_name);
383  }
384 
385  // generate the LIN trajectory
387  lin_->generate(planning_scene_, lin_joint_req, res);
388  EXPECT_TRUE(res.error_code.val == moveit_msgs::msg::MoveItErrorCodes::SUCCESS);
389 
390  // check the resulted trajectory
391  EXPECT_TRUE(checkLinResponse(lin_joint_req, res));
392 }
393 
404 TEST_F(TrajectoryGeneratorLINTest, IncorrectJointNumber)
405 {
406  // construct motion plan request
407  moveit_msgs::msg::MotionPlanRequest lin_joint_req{ tdp_->getLinJoint("lin2").toRequest() };
408 
409  // Ensure that request consists of an incorrect number of joints.
410  lin_joint_req.goal_constraints.front().joint_constraints.pop_back();
411 
412  // generate the LIN trajectory
414  lin_->generate(planning_scene_, lin_joint_req, res);
415  EXPECT_TRUE(res.error_code.val == moveit_msgs::msg::MoveItErrorCodes::INVALID_GOAL_CONSTRAINTS);
416 }
417 
422 TEST_F(TrajectoryGeneratorLINTest, cartGoalIncompleteStartState)
423 {
424  // construct motion plan request
425  moveit_msgs::msg::MotionPlanRequest lin_cart_req{ tdp_->getLinCart("lin2").toRequest() };
426  EXPECT_GT(lin_cart_req.start_state.joint_state.name.size(), 1u);
427  lin_cart_req.start_state.joint_state.name.resize(1);
428  lin_cart_req.start_state.joint_state.position.resize(1); // prevent failing check for equal sizes
429 
430  // generate lin trajectory
432  lin_->generate(planning_scene_, lin_cart_req, res);
433  EXPECT_EQ(res.error_code.val, moveit_msgs::msg::MoveItErrorCodes::INVALID_ROBOT_STATE);
434 }
435 
440 TEST_F(TrajectoryGeneratorLINTest, cartGoalFrameIdBothConstraints)
441 {
442  // construct motion plan request
443  moveit_msgs::msg::MotionPlanRequest lin_cart_req{ tdp_->getLinCart("lin2").toRequest() };
444 
445  lin_cart_req.goal_constraints.front().position_constraints.front().header.frame_id = robot_model_->getModelFrame();
446  lin_cart_req.goal_constraints.front().orientation_constraints.front().header.frame_id = robot_model_->getModelFrame();
447 
448  // generate lin trajectory
450  lin_->generate(planning_scene_, lin_cart_req, res);
451  EXPECT_TRUE(res.error_code.val == moveit_msgs::msg::MoveItErrorCodes::SUCCESS);
452 
453  // check the resulted trajectory
454  EXPECT_TRUE(checkLinResponse(lin_cart_req, res));
455 }
456 
457 int main(int argc, char** argv)
458 {
459  rclcpp::init(argc, argv);
460  testing::InitGoogleTest(&argc, argv);
461  return RUN_ALL_TESTS();
462 }
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
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.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 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)
Response to a planning query.
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")