35 #include <boost/core/demangle.hpp>
36 #include <gtest/gtest.h>
54 #include <rclcpp/rclcpp.hpp>
66 template <
typename T,
int N>
71 static const int VALUE = N;
73 template <
typename T,
int N>
89 typedef ::testing::Types<PTP_WITH_GRIPPER, LIN_WITH_GRIPPER, CIRC_WITH_GRIPPER>
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);
109 ASSERT_TRUE(
bool(
robot_model_)) <<
"Failed to load robot model";
113 ASSERT_TRUE(
node_->has_parameter(
"planning_group"));
115 ASSERT_TRUE(
node_->has_parameter(
"target_link"));
140 req_.max_velocity_scaling_factor = 1.0;
141 req_.max_acceleration_scaling_factor = 1.0;
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);
171 template <
typename T>
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);
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);
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);
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);
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);
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);
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);
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);
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);
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);
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);
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;
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);
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);
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);
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);
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);
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();
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);
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);
392 moveit_msgs::msg::PositionConstraint position_constraint;
393 moveit_msgs::msg::OrientationConstraint orientation_constraint;
394 moveit_msgs::msg::Constraints goal_constraint;
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);
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);
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);
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;
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);
439 int main(
int argc,
char** argv)
441 rclcpp::init(argc, argv);
442 testing::InitGoogleTest(&argc, argv);
443 return RUN_ALL_TESTS();
std::string planning_group_
rclcpp::Node::SharedPtr node_
std::unique_ptr< pilz_industrial_motion_planner::TrajectoryGenerator > trajectory_generator_
moveit::core::RobotModelConstPtr robot_model_
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.
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.
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 ¶m_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