moveit2
The MoveIt Motion Planning Framework for ROS 2.
Loading...
Searching...
No Matches
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#include "cartesian_limits_parameters.hpp"
57
58const std::string PARAM_MODEL_NO_GRIPPER_NAME{ "robot_description" };
59const std::string PARAM_MODEL_WITH_GRIPPER_NAME{ "robot_description_pg70" };
60const std::string PARAM_NAMESPACE_LIMITS{ "robot_description_planning" };
61
68template <typename T, int N>
70{
71public:
72 typedef T Type_;
73 static const int VALUE = N;
74};
75template <typename T, int N>
77
84
88
89typedef ::testing::Types<PTP_NO_GRIPPER, LIN_NO_GRIPPER, CIRC_NO_GRIPPER> TrajectoryGeneratorCommonTestTypesNoGripper;
90
91typedef ::testing::Types<PTP_WITH_GRIPPER, LIN_WITH_GRIPPER, CIRC_WITH_GRIPPER>
93
97template <typename T>
98class TrajectoryGeneratorCommonTest : public ::testing::Test
99{
100protected:
101 void SetUp() override
102 {
103 rclcpp::NodeOptions node_options;
104 node_options.automatically_declare_parameters_from_overrides(true);
105 node_ = rclcpp::Node::make_shared("unittest_trajectory_generator_common", node_options);
106
107 // load robot model
108 // const std::string robot_description_param = (!T::VALUE ? PARAM_MODEL_NO_GRIPPER_NAME : PARAM_MODEL_WITH_GRIPPER_NAME);
110 robot_model_ = rm_loader.getModel();
111 ASSERT_TRUE(bool(robot_model_)) << "Failed to load robot model";
112 planning_scene_ = std::make_shared<planning_scene::PlanningScene>(robot_model_);
113
114 // get parameters
115 ASSERT_TRUE(node_->has_parameter("planning_group"));
116 node_->get_parameter<std::string>("planning_group", planning_group_);
117 ASSERT_TRUE(node_->has_parameter("target_link"));
118 node_->get_parameter<std::string>("target_link", target_link_);
119
121
122 // create the limits container
125 node_, PARAM_NAMESPACE_LIMITS, robot_model_->getActiveJointModels());
126
127 cartesian_limits::Params cart_limits;
128 cart_limits.max_trans_vel = 0.5 * M_PI;
129 cart_limits.max_trans_acc = 2;
130 cart_limits.max_trans_dec = 2;
131 cart_limits.max_rot_vel = 1;
132
134 planner_limits.setJointLimits(joint_limits);
135 planner_limits.setCartesianLimits(cart_limits);
136
137 // create planner instance
138 trajectory_generator_ = std::make_unique<typename T::Type_>(robot_model_, planner_limits, planning_group_);
139 ASSERT_NE(nullptr, trajectory_generator_) << "failed to create trajectory generator";
140
141 // create a valid motion plan request with goal in joint space as basis for
142 // tests
143 req_.group_name = planning_group_;
144 req_.max_velocity_scaling_factor = 1.0;
145 req_.max_acceleration_scaling_factor = 1.0;
147 rstate.setToDefaultValues();
148 rstate.setJointGroupPositions(planning_group_, std::vector<double>{ 0, M_PI / 2, 0, M_PI / 2, 0, 0 });
149 rstate.setVariableVelocities(std::vector<double>(rstate.getVariableCount(), 0.0));
150 moveit::core::robotStateToRobotStateMsg(rstate, req_.start_state, false);
151 moveit_msgs::msg::Constraints goal_constraint;
152 moveit_msgs::msg::JointConstraint joint_constraint;
153 joint_constraint.joint_name = this->robot_model_->getActiveJointModels().front()->getName();
154 joint_constraint.position = 0.5;
155 goal_constraint.joint_constraints.push_back(joint_constraint);
156 req_.goal_constraints.push_back(goal_constraint);
157 }
158
159protected:
160 // ros stuff
161 rclcpp::Node::SharedPtr node_;
162 moveit::core::RobotModelConstPtr robot_model_;
163 planning_scene::PlanningSceneConstPtr planning_scene_;
164
165 // trajectory generator
166 std::unique_ptr<pilz_industrial_motion_planner::TrajectoryGenerator> trajectory_generator_;
169 // test parameters from parameter server
171};
172// Define the types we need to test
174
175template <typename T>
180
181// TODO(henningkayser):Enable tests with gripper support
182// template <typename T>
183// class TrajectoryGeneratorCommonTestWithGripper : public TrajectoryGeneratorCommonTest<T>
184// {
185// };
186// TYPED_TEST_SUITE(TrajectoryGeneratorCommonTestWithGripper, TrajectoryGeneratorCommonTestTypesWithGripper, /* ... */);
187
193{
194 this->req_.max_velocity_scaling_factor = 2.0;
195 this->trajectory_generator_->generate(this->planning_scene_, this->req_, this->res_);
196 EXPECT_EQ(this->res_.error_code.val, moveit_msgs::msg::MoveItErrorCodes::INVALID_MOTION_PLAN);
197
198 this->req_.max_velocity_scaling_factor = 1.0;
199 this->req_.max_acceleration_scaling_factor = 0;
200 this->trajectory_generator_->generate(this->planning_scene_, this->req_, this->res_);
201 EXPECT_EQ(this->res_.error_code.val, moveit_msgs::msg::MoveItErrorCodes::INVALID_MOTION_PLAN);
202
203 this->req_.max_velocity_scaling_factor = 0.00001;
204 this->req_.max_acceleration_scaling_factor = 1;
205 this->trajectory_generator_->generate(this->planning_scene_, this->req_, this->res_);
206 EXPECT_EQ(this->res_.error_code.val, moveit_msgs::msg::MoveItErrorCodes::INVALID_MOTION_PLAN);
207
208 this->req_.max_velocity_scaling_factor = 1;
209 this->req_.max_acceleration_scaling_factor = -1;
210 this->trajectory_generator_->generate(this->planning_scene_, this->req_, this->res_);
211 EXPECT_EQ(this->res_.error_code.val, moveit_msgs::msg::MoveItErrorCodes::INVALID_MOTION_PLAN);
212}
213
218{
219 this->req_.group_name = "foot";
220 this->trajectory_generator_->generate(this->planning_scene_, this->req_, this->res_);
221 EXPECT_EQ(moveit_msgs::msg::MoveItErrorCodes::INVALID_GROUP_NAME, this->res_.error_code.val);
222}
223
228{
229 this->req_.group_name = "gripper";
230 this->trajectory_generator_->generate(this->planning_scene_, this->req_, this->res_);
231 EXPECT_EQ(moveit_msgs::msg::MoveItErrorCodes::INVALID_GROUP_NAME, this->res_.error_code.val);
232}
233
237// TYPED_TEST(TrajectoryGeneratorCommonTestWithGripper, GripperGroup)
238// {
239// this->req_.group_name = "gripper";
240// this->trajectory_generator_->generate(this->planning_scene_, this->req_, this->res_);
241// EXPECT_EQ(moveit_msgs::msg::MoveItErrorCodes::INVALID_GOAL_CONSTRAINTS, this->res_.error_code.val);
242// }
243
252// TYPED_TEST(TrajectoryGeneratorCommonTest, NoIKSolver)
253//{
254// EXPECT_FALSE(this->trajectory_generator_->generate(this->req_, this->res_));
255// EXPECT_EQ(this->res_.error_code.val,
256// moveit_msgs::msg::MoveItErrorCodes::INVALID_GROUP_NAME);
257//}
258
262TYPED_TEST(TrajectoryGeneratorCommonTest, EmptyJointNamesInStartState)
263{
264 this->req_.start_state.joint_state.name.clear();
265 this->trajectory_generator_->generate(this->planning_scene_, this->req_, this->res_);
266 EXPECT_EQ(this->res_.error_code.val, moveit_msgs::msg::MoveItErrorCodes::INVALID_ROBOT_STATE);
267}
268
273{
274 this->req_.start_state.joint_state.name.push_back("joint_7");
275 this->trajectory_generator_->generate(this->planning_scene_, this->req_, this->res_);
276 EXPECT_EQ(this->res_.error_code.val, moveit_msgs::msg::MoveItErrorCodes::INVALID_ROBOT_STATE);
277}
278
283{
284 this->req_.start_state.joint_state.position[0] = 100;
285 this->trajectory_generator_->generate(this->planning_scene_, this->req_, this->res_);
286 EXPECT_EQ(this->res_.error_code.val, moveit_msgs::msg::MoveItErrorCodes::INVALID_ROBOT_STATE);
287}
288
296TYPED_TEST(TrajectoryGeneratorCommonTest, StartPositionVelocityNoneZero)
297{
298 this->req_.start_state.joint_state.velocity[0] = 100;
299 this->trajectory_generator_->generate(this->planning_scene_, this->req_, this->res_);
300 EXPECT_EQ(this->res_.error_code.val, moveit_msgs::msg::MoveItErrorCodes::INVALID_ROBOT_STATE);
301}
302
307{
308 this->req_.goal_constraints.clear();
309 this->trajectory_generator_->generate(this->planning_scene_, this->req_, this->res_);
310 EXPECT_EQ(this->res_.error_code.val, moveit_msgs::msg::MoveItErrorCodes::INVALID_GOAL_CONSTRAINTS);
311}
312
317{
318 moveit_msgs::msg::JointConstraint joint_constraint;
319 moveit_msgs::msg::PositionConstraint position_constraint;
320 moveit_msgs::msg::OrientationConstraint orientation_constraint;
321 moveit_msgs::msg::Constraints goal_constraint;
322
323 // two goal constraints
324 this->req_.goal_constraints.push_back(goal_constraint);
325 this->req_.goal_constraints.push_back(goal_constraint);
326 this->trajectory_generator_->generate(this->planning_scene_, this->req_, this->res_);
327 EXPECT_EQ(this->res_.error_code.val, moveit_msgs::msg::MoveItErrorCodes::INVALID_GOAL_CONSTRAINTS);
328
329 // one joint constraint and one orientation constraint
330 goal_constraint.joint_constraints.push_back(joint_constraint);
331 goal_constraint.orientation_constraints.push_back(orientation_constraint);
332 this->req_.goal_constraints.clear();
333 this->req_.goal_constraints.push_back(goal_constraint);
334 this->trajectory_generator_->generate(this->planning_scene_, this->req_, this->res_);
335 EXPECT_EQ(this->res_.error_code.val, moveit_msgs::msg::MoveItErrorCodes::INVALID_GOAL_CONSTRAINTS);
336
337 // one joint constraint and one Cartesian constraint
338 goal_constraint.position_constraints.push_back(position_constraint);
339 goal_constraint.orientation_constraints.push_back(orientation_constraint);
340 this->req_.goal_constraints.clear();
341 this->req_.goal_constraints.push_back(goal_constraint);
342 this->trajectory_generator_->generate(this->planning_scene_, this->req_, this->res_);
343 EXPECT_EQ(this->res_.error_code.val, moveit_msgs::msg::MoveItErrorCodes::INVALID_GOAL_CONSTRAINTS);
344
345 // two Cartesian constraints
346 goal_constraint.joint_constraints.clear();
347 goal_constraint.position_constraints.push_back(position_constraint);
348 goal_constraint.orientation_constraints.push_back(orientation_constraint);
349 goal_constraint.position_constraints.push_back(position_constraint);
350 goal_constraint.orientation_constraints.push_back(orientation_constraint);
351 this->req_.goal_constraints.clear();
352 this->req_.goal_constraints.push_back(goal_constraint);
353 this->trajectory_generator_->generate(this->planning_scene_, this->req_, this->res_);
354 EXPECT_EQ(this->res_.error_code.val, moveit_msgs::msg::MoveItErrorCodes::INVALID_GOAL_CONSTRAINTS);
355}
356
361{
362 moveit_msgs::msg::JointConstraint joint_constraint;
363 joint_constraint.joint_name = "test_joint_2";
364 this->req_.goal_constraints.front().joint_constraints[0] = joint_constraint;
365 this->trajectory_generator_->generate(this->planning_scene_, this->req_, this->res_);
366 EXPECT_EQ(this->res_.error_code.val, moveit_msgs::msg::MoveItErrorCodes::INVALID_GOAL_CONSTRAINTS);
367}
368
373{
374 moveit_msgs::msg::JointConstraint joint_constraint;
375 joint_constraint.joint_name = "test_joint_2";
376 this->req_.goal_constraints.front().joint_constraints.pop_back(); //<-- Missing joint constraint
377 this->trajectory_generator_->generate(this->planning_scene_, this->req_, this->res_);
378 EXPECT_EQ(this->res_.error_code.val, moveit_msgs::msg::MoveItErrorCodes::INVALID_GOAL_CONSTRAINTS);
379}
380
384TYPED_TEST(TrajectoryGeneratorCommonTest, InvalideJointPositionInGoal)
385{
386 this->req_.goal_constraints.front().joint_constraints[0].position = 100;
387 this->trajectory_generator_->generate(this->planning_scene_, this->req_, this->res_);
388 EXPECT_EQ(this->res_.error_code.val, moveit_msgs::msg::MoveItErrorCodes::INVALID_GOAL_CONSTRAINTS);
389}
390
394TYPED_TEST(TrajectoryGeneratorCommonTest, InvalidLinkNameInCartesianGoal)
395{
396 moveit_msgs::msg::PositionConstraint position_constraint;
397 moveit_msgs::msg::OrientationConstraint orientation_constraint;
398 moveit_msgs::msg::Constraints goal_constraint;
399 // link name not set
400 goal_constraint.position_constraints.push_back(position_constraint);
401 goal_constraint.orientation_constraints.push_back(orientation_constraint);
402 this->req_.goal_constraints.clear();
403 this->req_.goal_constraints.push_back(goal_constraint);
404 this->trajectory_generator_->generate(this->planning_scene_, this->req_, this->res_);
405 EXPECT_EQ(this->res_.error_code.val, moveit_msgs::msg::MoveItErrorCodes::INVALID_GOAL_CONSTRAINTS);
406
407 // different link names in position and orientation goals
408 goal_constraint.position_constraints.front().link_name = "test_link_1";
409 goal_constraint.orientation_constraints.front().link_name = "test_link_2";
410 this->req_.goal_constraints.clear();
411 this->req_.goal_constraints.push_back(goal_constraint);
412 this->trajectory_generator_->generate(this->planning_scene_, this->req_, this->res_);
413 EXPECT_EQ(this->res_.error_code.val, moveit_msgs::msg::MoveItErrorCodes::INVALID_GOAL_CONSTRAINTS);
414
415 // no solver for the link
416 goal_constraint.orientation_constraints.front().link_name = "test_link_1";
417 this->req_.goal_constraints.clear();
418 this->req_.goal_constraints.push_back(goal_constraint);
419 this->trajectory_generator_->generate(this->planning_scene_, this->req_, this->res_);
420 EXPECT_EQ(this->res_.error_code.val, moveit_msgs::msg::MoveItErrorCodes::NO_IK_SOLUTION);
421}
422
427{
428 moveit_msgs::msg::PositionConstraint position_constraint;
429 moveit_msgs::msg::OrientationConstraint orientation_constraint;
430 moveit_msgs::msg::Constraints goal_constraint;
431 position_constraint.link_name =
432 this->robot_model_->getJointModelGroup(this->planning_group_)->getLinkModelNames().back();
433 orientation_constraint.link_name = position_constraint.link_name;
434
435 goal_constraint.position_constraints.push_back(position_constraint);
436 goal_constraint.orientation_constraints.push_back(orientation_constraint);
437 this->req_.goal_constraints.clear();
438 this->req_.goal_constraints.push_back(goal_constraint);
439 this->trajectory_generator_->generate(this->planning_scene_, this->req_, this->res_);
440 EXPECT_EQ(this->res_.error_code.val, moveit_msgs::msg::MoveItErrorCodes::INVALID_GOAL_CONSTRAINTS);
441}
442
443int main(int argc, char** argv)
444{
445 rclcpp::init(argc, argv);
446 testing::InitGoogleTest(&argc, argv);
447 return RUN_ALL_TESTS();
448}
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...
void setVariableVelocities(const double *velocity)
Given an array with velocity values for all variables, set those values as the velocities in this sta...
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.
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(cartesian_limits::Params &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)
Response to a planning query.
#define TYPED_TEST_SUITE(...)
Definition test_utils.h:42
::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
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