35#include <boost/core/demangle.hpp>
36#include <gtest/gtest.h>
54#include <rclcpp/rclcpp.hpp>
56#include "cartesian_limits_parameters.hpp"
68template <
typename T,
int N>
73 static const int VALUE = N;
75template <
typename T,
int N>
91typedef ::testing::Types<PTP_WITH_GRIPPER, LIN_WITH_GRIPPER, CIRC_WITH_GRIPPER>
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);
111 ASSERT_TRUE(
bool(
robot_model_)) <<
"Failed to load robot model";
115 ASSERT_TRUE(
node_->has_parameter(
"planning_group"));
117 ASSERT_TRUE(
node_->has_parameter(
"target_link"));
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;
144 req_.max_velocity_scaling_factor = 1.0;
145 req_.max_acceleration_scaling_factor = 1.0;
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);
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);
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);
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);
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);
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);
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);
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);
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);
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);
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);
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);
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;
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);
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);
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);
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);
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);
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();
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);
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);
396 moveit_msgs::msg::PositionConstraint position_constraint;
397 moveit_msgs::msg::OrientationConstraint orientation_constraint;
398 moveit_msgs::msg::Constraints goal_constraint;
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);
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);
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);
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;
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);
445 rclcpp::init(argc, argv);
446 testing::InitGoogleTest(&argc, argv);
447 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.
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(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(...)
::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