37 #include <gtest/gtest.h>
43 #include <tf2_eigen/tf2_eigen.hpp>
44 #include <tf2_geometry_msgs/tf2_geometry_msgs.hpp>
52 #include <rclcpp/rclcpp.hpp>
68 rclcpp::NodeOptions node_options;
69 node_options.automatically_declare_parameters_from_overrides(
true);
70 node_ = rclcpp::Node::make_shared(
"unittest_trajectory_generator_circ", node_options);
73 rm_loader_ = std::make_unique<robot_model_loader::RobotModelLoader>(node_);
74 robot_model_ = rm_loader_->getModel();
75 ASSERT_TRUE(
bool(robot_model_)) <<
"Failed to load robot model";
76 planning_scene_ = std::make_shared<planning_scene::PlanningScene>(robot_model_);
79 ASSERT_TRUE(node_->has_parameter(
"testdata_file_name"));
80 node_->get_parameter<std::string>(
"testdata_file_name", test_data_file_name_);
81 ASSERT_TRUE(node_->has_parameter(
"planning_group"));
82 node_->get_parameter<std::string>(
"planning_group", planning_group_);
83 ASSERT_TRUE(node_->has_parameter(
"target_link"));
84 node_->get_parameter<std::string>(
"target_link", target_link_);
85 ASSERT_TRUE(node_->has_parameter(
"cartesian_position_tolerance"));
86 node_->get_parameter<
double>(
"cartesian_position_tolerance", cartesian_position_tolerance_);
87 ASSERT_TRUE(node_->has_parameter(
"angular_acc_tolerance"));
88 node_->get_parameter<
double>(
"angular_acc_tolerance", angular_acc_tolerance_);
89 ASSERT_TRUE(node_->has_parameter(
"rot_axis_norm_tolerance"));
90 node_->get_parameter<
double>(
"rot_axis_norm_tolerance", rot_axis_norm_tolerance_);
91 ASSERT_TRUE(node_->has_parameter(
"acceleration_tolerance"));
92 node_->get_parameter<
double>(
"acceleration_tolerance", acceleration_tolerance_);
93 ASSERT_TRUE(node_->has_parameter(
"other_tolerance"));
94 node_->get_parameter<
double>(
"other_tolerance", other_tolerance_);
100 tdp_ = std::make_unique<pilz_industrial_motion_planner_testutils::XmlTestdataLoader>(test_data_file_name_);
101 ASSERT_NE(
nullptr, tdp_) <<
"Failed to load test data by provider.";
103 tdp_->setRobotModel(robot_model_);
112 cartesian_limits::Params cartesian_limit;
113 cartesian_limit.max_trans_vel = 1.0 * M_PI;
114 cartesian_limit.max_trans_acc = 1.0 * M_PI;
115 cartesian_limit.max_trans_dec = 1.0 * M_PI;
116 cartesian_limit.max_rot_vel = 1.0 * M_PI;
119 planner_limits_.setCartesianLimits(cartesian_limit);
122 circ_ = std::make_unique<TrajectoryGeneratorCIRC>(robot_model_, planner_limits_, planning_group_);
123 ASSERT_NE(
nullptr, circ_) <<
"failed to create CIRC trajectory generator";
129 moveit_msgs::msg::MotionPlanResponse res_msg;
132 res_msg.trajectory.joint_trajectory, req, other_tolerance_));
137 EXPECT_EQ(req.path_constraints.position_constraints.size(), 1u);
138 EXPECT_EQ(req.path_constraints.position_constraints.at(0).constraint_region.primitive_poses.size(), 1u);
142 getCircCenter(req, res, circ_center);
144 for (std::size_t i = 0; i < res.
trajectory->getWayPointCount(); ++i)
146 Eigen::Affine3d waypoint_pose = res.
trajectory->getWayPointPtr(i)->getFrameTransform(target_link_);
148 (res.
trajectory->getFirstWayPointPtr()->getFrameTransform(target_link_).translation() - circ_center).norm(),
149 (circ_center - waypoint_pose.translation()).norm(), cartesian_position_tolerance_);
155 rot_axis_norm_tolerance_));
157 for (
size_t idx = 0; idx < res.
trajectory->getLastWayPointPtr()->getVariableCount(); ++idx)
159 EXPECT_NEAR(0.0, res.
trajectory->getLastWayPointPtr()->getVariableVelocity(idx), other_tolerance_);
160 EXPECT_NEAR(0.0, res.
trajectory->getLastWayPointPtr()->getVariableAcceleration(idx), other_tolerance_);
166 robot_model_.reset();
172 if (req.path_constraints.name ==
"center")
174 tf2::fromMsg(req.path_constraints.position_constraints.at(0).constraint_region.primitive_poses.at(0).position,
177 else if (req.path_constraints.name ==
"interim")
180 tf2::fromMsg(req.path_constraints.position_constraints.at(0).constraint_region.primitive_poses.at(0).position,
191 ASSERT_GT(w.norm(), 1e-8) <<
"Circle center not well defined for given start, interim and goal.";
193 circ_center = start + (u * t.dot(t) * u.dot(v) - t * u.dot(u) * t.dot(v)) * 0.5 / pow(w.norm(), 2);
201 std::unique_ptr<robot_model_loader::RobotModelLoader>
rm_loader_;
204 std::unique_ptr<TrajectoryGeneratorCIRC>
circ_;
206 std::unique_ptr<pilz_industrial_motion_planner_testutils::TestdataLoader>
tdp_;
223 auto cnp_ex = std::make_shared<CircleNoPlane>(
"");
224 EXPECT_EQ(cnp_ex->getErrorCode(), moveit_msgs::msg::MoveItErrorCodes::INVALID_MOTION_PLAN);
228 auto cts_ex = std::make_shared<CircleToSmall>(
"");
229 EXPECT_EQ(cts_ex->getErrorCode(), moveit_msgs::msg::MoveItErrorCodes::INVALID_MOTION_PLAN);
233 auto cpdr_ex = std::make_shared<CenterPointDifferentRadius>(
"");
234 EXPECT_EQ(cpdr_ex->getErrorCode(), moveit_msgs::msg::MoveItErrorCodes::INVALID_MOTION_PLAN);
238 auto ctcf_ex = std::make_shared<CircTrajectoryConversionFailure>(
"");
239 EXPECT_EQ(ctcf_ex->getErrorCode(), moveit_msgs::msg::MoveItErrorCodes::INVALID_MOTION_PLAN);
243 auto upcn_ex = std::make_shared<UnknownPathConstraintName>(
"");
244 EXPECT_EQ(upcn_ex->getErrorCode(), moveit_msgs::msg::MoveItErrorCodes::INVALID_MOTION_PLAN);
248 auto npc_ex = std::make_shared<NoPositionConstraints>(
"");
249 EXPECT_EQ(npc_ex->getErrorCode(), moveit_msgs::msg::MoveItErrorCodes::INVALID_MOTION_PLAN);
253 auto npp_ex = std::make_shared<NoPrimitivePose>(
"");
254 EXPECT_EQ(npp_ex->getErrorCode(), moveit_msgs::msg::MoveItErrorCodes::INVALID_MOTION_PLAN);
258 auto ulnoap_ex = std::make_shared<UnknownLinkNameOfAuxiliaryPoint>(
"");
259 EXPECT_EQ(ulnoap_ex->getErrorCode(), moveit_msgs::msg::MoveItErrorCodes::INVALID_LINK_NAME);
263 auto nocm_ex = std::make_shared<NumberOfConstraintsMismatch>(
"");
264 EXPECT_EQ(nocm_ex->getErrorCode(), moveit_msgs::msg::MoveItErrorCodes::INVALID_GOAL_CONSTRAINTS);
268 auto cifgi_ex = std::make_shared<CircInverseForGoalIncalculable>(
"");
269 EXPECT_EQ(cifgi_ex->getErrorCode(), moveit_msgs::msg::MoveItErrorCodes::NO_IK_SOLUTION);
281 req.start_state.joint_state.velocity.push_back(1.0);
283 circ_->generate(planning_scene_, req, res);
284 EXPECT_EQ(res.
error_code.val, moveit_msgs::msg::MoveItErrorCodes::INVALID_ROBOT_STATE);
285 req.start_state.joint_state.velocity.clear();
290 auto circ{ tdp_->getCircCartCenterCart(
"circ1_center_2") };
293 circ_->generate(planning_scene_, circ.toRequest(), res);
294 EXPECT_EQ(res.
error_code.val, moveit_msgs::msg::MoveItErrorCodes::SUCCESS);
302 auto circ{ tdp_->getCircCartCenterCart(
"circ1_center_2") };
304 circ.setVelocityScale(1.0);
306 circ_->generate(planning_scene_, circ.toRequest(), res);
307 EXPECT_EQ(res.
error_code.val, moveit_msgs::msg::MoveItErrorCodes::PLANNING_FAILED);
315 auto circ{ tdp_->getCircCartCenterCart(
"circ1_center_2") };
317 circ.setAccelerationScale(1.0);
319 circ_->generate(planning_scene_, circ.toRequest(), res);
320 EXPECT_EQ(res.
error_code.val, moveit_msgs::msg::MoveItErrorCodes::PLANNING_FAILED);
330 auto circ{ tdp_->getCircCartCenterCart(
"circ1_center_2") };
331 circ.getAuxiliaryConfiguration().getConfiguration().setPose(circ.getStartConfiguration().getPose());
332 circ.getAuxiliaryConfiguration().getConfiguration().getPose().position.x += 1e-8;
333 circ.getAuxiliaryConfiguration().getConfiguration().getPose().position.y += 1e-8;
334 circ.getAuxiliaryConfiguration().getConfiguration().getPose().position.z += 1e-8;
335 circ.getGoalConfiguration().setPose(circ.getStartConfiguration().getPose());
336 circ.getGoalConfiguration().getPose().position.x -= 1e-8;
337 circ.getGoalConfiguration().getPose().position.y -= 1e-8;
338 circ.getGoalConfiguration().getPose().position.z -= 1e-8;
341 circ_->generate(planning_scene_, circ.toRequest(), res);
342 EXPECT_EQ(res.
error_code.val, moveit_msgs::msg::MoveItErrorCodes::INVALID_MOTION_PLAN);
353 auto circ{ tdp_->getCircCartInterimCart(
"circ3_interim") };
354 circ.getAuxiliaryConfiguration().getConfiguration().setPose(circ.getStartConfiguration().getPose());
355 circ.getAuxiliaryConfiguration().getConfiguration().getPose().position.x += 1e-8;
356 circ.getAuxiliaryConfiguration().getConfiguration().getPose().position.y += 1e-8;
357 circ.getAuxiliaryConfiguration().getConfiguration().getPose().position.z += 1e-8;
358 circ.getGoalConfiguration().setPose(circ.getStartConfiguration().getPose());
359 circ.getGoalConfiguration().getPose().position.x -= 1e-8;
360 circ.getGoalConfiguration().getPose().position.y -= 1e-8;
361 circ.getGoalConfiguration().getPose().position.z -= 1e-8;
364 circ_->generate(planning_scene_, circ.toRequest(), res);
365 EXPECT_EQ(res.
error_code.val, moveit_msgs::msg::MoveItErrorCodes::INVALID_MOTION_PLAN);
373 auto circ{ tdp_->getCircCartCenterCart(
"circ1_center_2") };
377 req.path_constraints.position_constraints.clear();
380 circ_->generate(planning_scene_, req, res);
381 EXPECT_EQ(res.
error_code.val, moveit_msgs::msg::MoveItErrorCodes::INVALID_MOTION_PLAN);
389 auto circ{ tdp_->getCircCartCenterCart(
"circ1_center_2") };
393 req.path_constraints.name =
"";
396 circ_->generate(planning_scene_, req, res);
397 EXPECT_EQ(res.
error_code.val, moveit_msgs::msg::MoveItErrorCodes::INVALID_MOTION_PLAN);
406 auto circ{ tdp_->getCircJointInterimCart(
"circ3_interim") };
410 req.path_constraints.position_constraints.front().link_name =
"INVALID";
413 circ_->generate(planning_scene_, req, res);
414 EXPECT_EQ(res.
error_code.val, moveit_msgs::msg::MoveItErrorCodes::INVALID_LINK_NAME);
422 auto circ{ tdp_->getCircCartCenterCart(
"circ1_center_2") };
423 circ.getAuxiliaryConfiguration().getConfiguration().setPose(circ.getStartConfiguration().getPose());
424 circ.getAuxiliaryConfiguration().getConfiguration().getPose().position.y += 1;
427 circ_->generate(planning_scene_, circ.toRequest(), res);
428 EXPECT_EQ(res.
error_code.val, moveit_msgs::msg::MoveItErrorCodes::INVALID_MOTION_PLAN);
438 auto circ{ tdp_->getCircCartCenterCart(
"circ1_center_2") };
439 circ.getAuxiliaryConfiguration().getConfiguration().setPose(circ.getStartConfiguration().getPose());
440 circ.getGoalConfiguration().setPose(circ.getStartConfiguration().getPose());
443 circ.getStartConfiguration().getPose().position.x -= 0.1;
444 circ.getGoalConfiguration().getPose().position.x += 0.1;
447 circ_->generate(planning_scene_, circ.toRequest(), res);
448 EXPECT_EQ(res.
error_code.val, moveit_msgs::msg::MoveItErrorCodes::INVALID_MOTION_PLAN);
459 auto circ{ tdp_->getCircCartInterimCart(
"circ3_interim") };
460 circ.getAuxiliaryConfiguration().getConfiguration().setPose(circ.getStartConfiguration().getPose());
461 circ.getGoalConfiguration().setPose(circ.getStartConfiguration().getPose());
464 circ.getStartConfiguration().getPose().position.x -= 0.1;
465 circ.getGoalConfiguration().getPose().position.x += 0.1;
468 circ_->generate(planning_scene_, circ.toRequest(), res);
469 EXPECT_EQ(res.
error_code.val, moveit_msgs::msg::MoveItErrorCodes::INVALID_MOTION_PLAN);
483 auto circ{ tdp_->getCircCartInterimCart(
"circ3_interim") };
486 circ_->generate(planning_scene_, circ.toRequest(), res);
487 EXPECT_EQ(res.
error_code.val, moveit_msgs::msg::MoveItErrorCodes::SUCCESS);
502 auto circ{ tdp_->getCircCartInterimCart(
"circ3_interim") };
506 circ.getAuxiliaryConfiguration().getConfiguration().setPose(circ.getStartConfiguration().getPose());
507 circ.getGoalConfiguration().setPose(circ.getStartConfiguration().getPose());
509 circ.getStartConfiguration().getPose().position.x -= 0.2;
510 circ.getAuxiliaryConfiguration().getConfiguration().getPose().position.x += 0.2;
511 circ.getGoalConfiguration().getPose().position.y -= 0.2;
513 circ.setAccelerationScale(0.05);
514 circ.setVelocityScale(0.05);
519 circ_->generate(planning_scene_, req, res);
520 EXPECT_EQ(res.
error_code.val, moveit_msgs::msg::MoveItErrorCodes::SUCCESS);
521 checkCircResult(req, res);
535 auto circ{ tdp_->getCircCartInterimCart(
"circ3_interim") };
539 circ.getAuxiliaryConfiguration().getConfiguration().setPose(circ.getStartConfiguration().getPose());
540 circ.getGoalConfiguration().setPose(circ.getStartConfiguration().getPose());
542 circ.getStartConfiguration().getPose().position.x -= 0.2;
543 circ.getAuxiliaryConfiguration().getConfiguration().getPose().position.x += 0.14142136;
544 circ.getAuxiliaryConfiguration().getConfiguration().getPose().position.y -= 0.14142136;
545 circ.getGoalConfiguration().getPose().position.y -= 0.2;
547 circ.setAccelerationScale(0.05);
548 circ.setVelocityScale(0.05);
553 circ_->generate(planning_scene_, req, res);
554 EXPECT_EQ(res.
error_code.val, moveit_msgs::msg::MoveItErrorCodes::SUCCESS);
555 checkCircResult(req, res);
563 auto circ{ tdp_->getCircJointCenterCart(
"circ1_center_2") };
567 circ_->generate(planning_scene_, req, res);
568 EXPECT_EQ(res.
error_code.val, moveit_msgs::msg::MoveItErrorCodes::SUCCESS);
569 checkCircResult(req, res);
579 auto circ{ tdp_->getCircCartCenterCart(
"circ1_center_2") };
584 ASSERT_EQ(req.path_constraints.position_constraints.back().constraint_region.primitive_poses.size(), 1u);
587 geometry_msgs::msg::Pose center_position;
588 center_position.position.x = 0.0;
589 center_position.position.y = 0.0;
590 center_position.position.z = 0.65;
591 req.path_constraints.position_constraints.back().constraint_region.primitive_poses.push_back(center_position);
594 circ_->generate(planning_scene_, req, res);
595 EXPECT_EQ(res.
error_code.val, moveit_msgs::msg::MoveItErrorCodes::INVALID_MOTION_PLAN);
606 auto circ{ tdp_->getCircJointCenterCart(
"circ1_center_2") };
611 moveit_msgs::msg::JointConstraint joint_constraint;
612 joint_constraint.joint_name = req.goal_constraints.front().joint_constraints.front().joint_name;
613 req.goal_constraints.front().joint_constraints.push_back(joint_constraint);
616 circ_->generate(planning_scene_, req, res);
617 EXPECT_EQ(res.
error_code.val, moveit_msgs::msg::MoveItErrorCodes::INVALID_GOAL_CONSTRAINTS);
625 auto circ{ tdp_->getCircCartCenterCart(
"circ1_center_2") };
630 circ_->generate(planning_scene_, req, res);
631 EXPECT_EQ(res.
error_code.val, moveit_msgs::msg::MoveItErrorCodes::SUCCESS);
632 checkCircResult(req, res);
640 auto circ{ tdp_->getCircCartCenterCart(
"circ1_center_2") };
644 req.goal_constraints.front().position_constraints.front().header.frame_id = robot_model_->getModelFrame();
647 circ_->generate(planning_scene_, req, res);
648 EXPECT_EQ(res.
error_code.val, moveit_msgs::msg::MoveItErrorCodes::SUCCESS);
649 checkCircResult(req, res);
657 auto circ{ tdp_->getCircCartCenterCart(
"circ1_center_2") };
660 req.goal_constraints.front().orientation_constraints.front().header.frame_id = robot_model_->getModelFrame();
663 circ_->generate(planning_scene_, req, res);
664 EXPECT_EQ(res.
error_code.val, moveit_msgs::msg::MoveItErrorCodes::SUCCESS);
665 checkCircResult(req, res);
673 auto circ{ tdp_->getCircCartCenterCart(
"circ1_center_2") };
678 req.goal_constraints.front().position_constraints.front().header.frame_id = robot_model_->getModelFrame();
679 req.goal_constraints.front().orientation_constraints.front().header.frame_id = robot_model_->getModelFrame();
682 circ_->generate(planning_scene_, req, res);
683 EXPECT_EQ(res.
error_code.val, moveit_msgs::msg::MoveItErrorCodes::SUCCESS);
684 checkCircResult(req, res);
692 auto circ{ tdp_->getCircJointInterimCart(
"circ3_interim") };
697 circ_->generate(planning_scene_, req, res);
698 EXPECT_EQ(res.
error_code.val, moveit_msgs::msg::MoveItErrorCodes::SUCCESS);
699 checkCircResult(req, res);
710 auto circ{ tdp_->getCircJointInterimCart(
"circ3_interim") };
715 req.start_state.joint_state.velocity = std::vector<double>(req.start_state.joint_state.position.size(), 1e-16);
718 circ_->generate(planning_scene_, req, res);
719 EXPECT_EQ(res.
error_code.val, moveit_msgs::msg::MoveItErrorCodes::SUCCESS);
720 checkCircResult(req, res);
728 auto circ{ tdp_->getCircJointInterimCart(
"circ3_interim") };
732 circ_->generate(planning_scene_, req, res);
733 EXPECT_EQ(res.
error_code.val, moveit_msgs::msg::MoveItErrorCodes::SUCCESS);
734 checkCircResult(req, res);
737 int main(
int argc,
char** argv)
739 rclcpp::init(argc, argv);
740 testing::InitGoogleTest(&argc, argv);
741 return RUN_ALL_TESTS();
void SetUp() override
Create test scenario for circ trajectory generator.
std::unique_ptr< TrajectoryGeneratorCIRC > circ_
std::unique_ptr< pilz_industrial_motion_planner_testutils::TestdataLoader > tdp_
void getCircCenter(const planning_interface::MotionPlanRequest &req, const planning_interface::MotionPlanResponse &res, Eigen::Vector3d &circ_center)
double acceleration_tolerance_
LimitsContainer planner_limits_
moveit::core::RobotModelConstPtr robot_model_
void checkCircResult(const planning_interface::MotionPlanRequest &req, const planning_interface::MotionPlanResponse &res)
std::string planning_group_
planning_scene::PlanningSceneConstPtr planning_scene_
std::unique_ptr< robot_model_loader::RobotModelLoader > rm_loader_
rclcpp::Node::SharedPtr node_
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.
Vec3fX< details::Vec3Data< double > > Vector3d
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.
::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
void checkRobotModel(const moveit::core::RobotModelConstPtr &robot_model, const std::string &group_name, const std::string &link_name)
::testing::AssertionResult checkCartesianRotationalPath(const robot_trajectory::RobotTrajectoryConstPtr &trajectory, const std::string &link_name, const double rot_axis_tol=DEFAULT_ROTATION_AXIS_EQUALITY_TOLERANCE, const double acc_tol=DEFAULT_ACCELERATION_EQUALITY_TOLERANCE)
Check that the rotational path of a given trajectory is a quaternion slerp.
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.
int main(int argc, char **argv)
const std::string PARAM_NAMESPACE_LIMITS