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>
57 static const std::string PARAM_NAMESPACE_LIMITS =
"robot_description_planning";
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_);
108 node_, PARAM_NAMESPACE_LIMITS, robot_model_->getActiveJointModels());
118 planner_limits_.setCartesianLimits(cart_limits);
121 circ_ = std::make_unique<TrajectoryGeneratorCIRC>(robot_model_, planner_limits_, planning_group_);
122 ASSERT_NE(
nullptr, circ_) <<
"failed to create CIRC trajectory generator";
128 moveit_msgs::msg::MotionPlanResponse res_msg;
131 res_msg.trajectory.joint_trajectory, req, other_tolerance_));
136 EXPECT_EQ(req.path_constraints.position_constraints.size(), 1u);
137 EXPECT_EQ(req.path_constraints.position_constraints.at(0).constraint_region.primitive_poses.size(), 1u);
141 getCircCenter(req, res, circ_center);
143 for (std::size_t i = 0; i < res.
trajectory_->getWayPointCount(); ++i)
145 Eigen::Affine3d waypoint_pose = res.
trajectory_->getWayPointPtr(i)->getFrameTransform(target_link_);
147 (res.
trajectory_->getFirstWayPointPtr()->getFrameTransform(target_link_).translation() - circ_center).norm(),
148 (circ_center - waypoint_pose.translation()).norm(), cartesian_position_tolerance_);
154 rot_axis_norm_tolerance_));
156 for (
size_t idx = 0; idx < res.
trajectory_->getLastWayPointPtr()->getVariableCount(); ++idx)
158 EXPECT_NEAR(0.0, res.
trajectory_->getLastWayPointPtr()->getVariableVelocity(idx), other_tolerance_);
159 EXPECT_NEAR(0.0, res.
trajectory_->getLastWayPointPtr()->getVariableAcceleration(idx), other_tolerance_);
165 robot_model_.reset();
171 if (req.path_constraints.name ==
"center")
173 tf2::fromMsg(req.path_constraints.position_constraints.at(0).constraint_region.primitive_poses.at(0).position,
176 else if (req.path_constraints.name ==
"interim")
179 tf2::fromMsg(req.path_constraints.position_constraints.at(0).constraint_region.primitive_poses.at(0).position,
190 ASSERT_GT(
w.norm(), 1e-8) <<
"Circle center not well defined for given start, interim and goal.";
192 circ_center = start + (u * t.dot(t) * u.dot(v) - t * u.dot(u) * t.dot(v)) * 0.5 / pow(
w.norm(), 2);
200 std::unique_ptr<robot_model_loader::RobotModelLoader>
rm_loader_;
203 std::unique_ptr<TrajectoryGeneratorCIRC>
circ_;
205 std::unique_ptr<pilz_industrial_motion_planner_testutils::TestdataLoader>
tdp_;
222 std::shared_ptr<CircleNoPlane> cnp_ex{
new CircleNoPlane(
"") };
223 EXPECT_EQ(cnp_ex->getErrorCode(), moveit_msgs::msg::MoveItErrorCodes::INVALID_MOTION_PLAN);
227 std::shared_ptr<CircleToSmall> cts_ex{
new CircleToSmall(
"") };
228 EXPECT_EQ(cts_ex->getErrorCode(), moveit_msgs::msg::MoveItErrorCodes::INVALID_MOTION_PLAN);
232 std::shared_ptr<CenterPointDifferentRadius> cpdr_ex{
new CenterPointDifferentRadius(
"") };
233 EXPECT_EQ(cpdr_ex->getErrorCode(), moveit_msgs::msg::MoveItErrorCodes::INVALID_MOTION_PLAN);
237 std::shared_ptr<CircTrajectoryConversionFailure> ctcf_ex{
new CircTrajectoryConversionFailure(
"") };
238 EXPECT_EQ(ctcf_ex->getErrorCode(), moveit_msgs::msg::MoveItErrorCodes::INVALID_MOTION_PLAN);
242 std::shared_ptr<UnknownPathConstraintName> upcn_ex{
new UnknownPathConstraintName(
"") };
243 EXPECT_EQ(upcn_ex->getErrorCode(), moveit_msgs::msg::MoveItErrorCodes::INVALID_MOTION_PLAN);
247 std::shared_ptr<NoPositionConstraints> npc_ex{
new NoPositionConstraints(
"") };
248 EXPECT_EQ(npc_ex->getErrorCode(), moveit_msgs::msg::MoveItErrorCodes::INVALID_MOTION_PLAN);
252 std::shared_ptr<NoPrimitivePose> npp_ex{
new NoPrimitivePose(
"") };
253 EXPECT_EQ(npp_ex->getErrorCode(), moveit_msgs::msg::MoveItErrorCodes::INVALID_MOTION_PLAN);
257 std::shared_ptr<UnknownLinkNameOfAuxiliaryPoint> ulnoap_ex{
new UnknownLinkNameOfAuxiliaryPoint(
"") };
258 EXPECT_EQ(ulnoap_ex->getErrorCode(), moveit_msgs::msg::MoveItErrorCodes::INVALID_LINK_NAME);
262 std::shared_ptr<NumberOfConstraintsMismatch> nocm_ex{
new NumberOfConstraintsMismatch(
"") };
263 EXPECT_EQ(nocm_ex->getErrorCode(), moveit_msgs::msg::MoveItErrorCodes::INVALID_GOAL_CONSTRAINTS);
267 std::shared_ptr<CircJointMissingInStartState> cjmiss_ex{
new CircJointMissingInStartState(
"") };
268 EXPECT_EQ(cjmiss_ex->getErrorCode(), moveit_msgs::msg::MoveItErrorCodes::INVALID_ROBOT_STATE);
272 std::shared_ptr<CircInverseForGoalIncalculable> cifgi_ex{
new CircInverseForGoalIncalculable(
"") };
273 EXPECT_EQ(cifgi_ex->getErrorCode(), moveit_msgs::msg::MoveItErrorCodes::NO_IK_SOLUTION);
284 TrajectoryGeneratorInvalidLimitsException);
293 auto circ{ tdp_->getCircCartCenterCart(
"circ1_center_2") };
296 EXPECT_GT(req.start_state.joint_state.name.size(), 1u);
297 req.start_state.joint_state.name.resize(1);
298 req.start_state.joint_state.position.resize(1);
301 EXPECT_FALSE(circ_->generate(planning_scene_, req, res));
302 EXPECT_EQ(res.
error_code_.val, moveit_msgs::msg::MoveItErrorCodes::INVALID_ROBOT_STATE);
313 req.start_state.joint_state.velocity.push_back(1.0);
315 EXPECT_FALSE(circ_->generate(planning_scene_, req, res));
316 EXPECT_EQ(res.
error_code_.val, moveit_msgs::msg::MoveItErrorCodes::INVALID_ROBOT_STATE);
317 req.start_state.joint_state.velocity.clear();
322 auto circ{ tdp_->getCircCartCenterCart(
"circ1_center_2") };
325 EXPECT_TRUE(circ_->generate(planning_scene_, circ.toRequest(), res));
326 EXPECT_EQ(res.
error_code_.val, moveit_msgs::msg::MoveItErrorCodes::SUCCESS);
334 auto circ{ tdp_->getCircCartCenterCart(
"circ1_center_2") };
336 circ.setVelocityScale(1.0);
338 EXPECT_FALSE(circ_->generate(planning_scene_, circ.toRequest(), res));
339 EXPECT_EQ(res.
error_code_.val, moveit_msgs::msg::MoveItErrorCodes::PLANNING_FAILED);
347 auto circ{ tdp_->getCircCartCenterCart(
"circ1_center_2") };
349 circ.setAccelerationScale(1.0);
351 EXPECT_FALSE(circ_->generate(planning_scene_, circ.toRequest(), res));
352 EXPECT_EQ(res.
error_code_.val, moveit_msgs::msg::MoveItErrorCodes::PLANNING_FAILED);
362 auto circ{ tdp_->getCircCartCenterCart(
"circ1_center_2") };
363 circ.getAuxiliaryConfiguration().getConfiguration().setPose(circ.getStartConfiguration().getPose());
364 circ.getAuxiliaryConfiguration().getConfiguration().getPose().position.x += 1e-8;
365 circ.getAuxiliaryConfiguration().getConfiguration().getPose().position.y += 1e-8;
366 circ.getAuxiliaryConfiguration().getConfiguration().getPose().position.z += 1e-8;
367 circ.getGoalConfiguration().setPose(circ.getStartConfiguration().getPose());
368 circ.getGoalConfiguration().getPose().position.x -= 1e-8;
369 circ.getGoalConfiguration().getPose().position.y -= 1e-8;
370 circ.getGoalConfiguration().getPose().position.z -= 1e-8;
373 EXPECT_FALSE(circ_->generate(planning_scene_, circ.toRequest(), res));
374 EXPECT_EQ(res.
error_code_.val, moveit_msgs::msg::MoveItErrorCodes::INVALID_MOTION_PLAN);
385 auto circ{ tdp_->getCircCartInterimCart(
"circ3_interim") };
386 circ.getAuxiliaryConfiguration().getConfiguration().setPose(circ.getStartConfiguration().getPose());
387 circ.getAuxiliaryConfiguration().getConfiguration().getPose().position.x += 1e-8;
388 circ.getAuxiliaryConfiguration().getConfiguration().getPose().position.y += 1e-8;
389 circ.getAuxiliaryConfiguration().getConfiguration().getPose().position.z += 1e-8;
390 circ.getGoalConfiguration().setPose(circ.getStartConfiguration().getPose());
391 circ.getGoalConfiguration().getPose().position.x -= 1e-8;
392 circ.getGoalConfiguration().getPose().position.y -= 1e-8;
393 circ.getGoalConfiguration().getPose().position.z -= 1e-8;
396 EXPECT_FALSE(circ_->generate(planning_scene_, circ.toRequest(), res));
397 EXPECT_EQ(res.
error_code_.val, moveit_msgs::msg::MoveItErrorCodes::INVALID_MOTION_PLAN);
405 auto circ{ tdp_->getCircCartCenterCart(
"circ1_center_2") };
409 req.path_constraints.position_constraints.clear();
412 EXPECT_FALSE(circ_->generate(planning_scene_, req, res));
413 EXPECT_EQ(res.
error_code_.val, moveit_msgs::msg::MoveItErrorCodes::INVALID_MOTION_PLAN);
421 auto circ{ tdp_->getCircCartCenterCart(
"circ1_center_2") };
425 req.path_constraints.name =
"";
428 EXPECT_FALSE(circ_->generate(planning_scene_, req, res));
429 EXPECT_EQ(res.
error_code_.val, moveit_msgs::msg::MoveItErrorCodes::INVALID_MOTION_PLAN);
438 auto circ{ tdp_->getCircJointInterimCart(
"circ3_interim") };
442 req.path_constraints.position_constraints.front().link_name =
"INVALID";
445 EXPECT_FALSE(circ_->generate(planning_scene_, req, res));
446 EXPECT_EQ(res.
error_code_.val, moveit_msgs::msg::MoveItErrorCodes::INVALID_LINK_NAME);
454 auto circ{ tdp_->getCircCartCenterCart(
"circ1_center_2") };
455 circ.getAuxiliaryConfiguration().getConfiguration().setPose(circ.getStartConfiguration().getPose());
456 circ.getAuxiliaryConfiguration().getConfiguration().getPose().position.y += 1;
459 EXPECT_FALSE(circ_->generate(planning_scene_, circ.toRequest(), res));
460 EXPECT_EQ(res.
error_code_.val, moveit_msgs::msg::MoveItErrorCodes::INVALID_MOTION_PLAN);
470 auto circ{ tdp_->getCircCartCenterCart(
"circ1_center_2") };
471 circ.getAuxiliaryConfiguration().getConfiguration().setPose(circ.getStartConfiguration().getPose());
472 circ.getGoalConfiguration().setPose(circ.getStartConfiguration().getPose());
475 circ.getStartConfiguration().getPose().position.x -= 0.1;
476 circ.getGoalConfiguration().getPose().position.x += 0.1;
479 EXPECT_FALSE(circ_->generate(planning_scene_, circ.toRequest(), res));
480 EXPECT_EQ(res.
error_code_.val, moveit_msgs::msg::MoveItErrorCodes::INVALID_MOTION_PLAN);
491 auto circ{ tdp_->getCircCartInterimCart(
"circ3_interim") };
492 circ.getAuxiliaryConfiguration().getConfiguration().setPose(circ.getStartConfiguration().getPose());
493 circ.getGoalConfiguration().setPose(circ.getStartConfiguration().getPose());
496 circ.getStartConfiguration().getPose().position.x -= 0.1;
497 circ.getGoalConfiguration().getPose().position.x += 0.1;
500 EXPECT_FALSE(circ_->generate(planning_scene_, circ.toRequest(), res));
501 EXPECT_EQ(res.
error_code_.val, moveit_msgs::msg::MoveItErrorCodes::INVALID_MOTION_PLAN);
515 auto circ{ tdp_->getCircCartInterimCart(
"circ3_interim") };
518 ASSERT_TRUE(circ_->generate(planning_scene_, circ.toRequest(), res));
519 EXPECT_EQ(res.
error_code_.val, moveit_msgs::msg::MoveItErrorCodes::SUCCESS);
534 auto circ{ tdp_->getCircCartInterimCart(
"circ3_interim") };
538 circ.getAuxiliaryConfiguration().getConfiguration().setPose(circ.getStartConfiguration().getPose());
539 circ.getGoalConfiguration().setPose(circ.getStartConfiguration().getPose());
541 circ.getStartConfiguration().getPose().position.x -= 0.2;
542 circ.getAuxiliaryConfiguration().getConfiguration().getPose().position.x += 0.2;
543 circ.getGoalConfiguration().getPose().position.y -= 0.2;
545 circ.setAccelerationScale(0.05);
546 circ.setVelocityScale(0.05);
551 EXPECT_TRUE(circ_->generate(planning_scene_, req, res));
552 EXPECT_EQ(res.
error_code_.val, moveit_msgs::msg::MoveItErrorCodes::SUCCESS);
553 checkCircResult(req, res);
567 auto circ{ tdp_->getCircCartInterimCart(
"circ3_interim") };
571 circ.getAuxiliaryConfiguration().getConfiguration().setPose(circ.getStartConfiguration().getPose());
572 circ.getGoalConfiguration().setPose(circ.getStartConfiguration().getPose());
574 circ.getStartConfiguration().getPose().position.x -= 0.2;
575 circ.getAuxiliaryConfiguration().getConfiguration().getPose().position.x += 0.14142136;
576 circ.getAuxiliaryConfiguration().getConfiguration().getPose().position.y -= 0.14142136;
577 circ.getGoalConfiguration().getPose().position.y -= 0.2;
579 circ.setAccelerationScale(0.05);
580 circ.setVelocityScale(0.05);
585 EXPECT_TRUE(circ_->generate(planning_scene_, req, res));
586 EXPECT_EQ(res.
error_code_.val, moveit_msgs::msg::MoveItErrorCodes::SUCCESS);
587 checkCircResult(req, res);
595 auto circ{ tdp_->getCircJointCenterCart(
"circ1_center_2") };
599 ASSERT_TRUE(circ_->generate(planning_scene_, req, res));
600 EXPECT_EQ(res.
error_code_.val, moveit_msgs::msg::MoveItErrorCodes::SUCCESS);
601 checkCircResult(req, res);
611 auto circ{ tdp_->getCircCartCenterCart(
"circ1_center_2") };
616 ASSERT_EQ(req.path_constraints.position_constraints.back().constraint_region.primitive_poses.size(), 1u);
619 geometry_msgs::msg::Pose center_position;
620 center_position.position.x = 0.0;
621 center_position.position.y = 0.0;
622 center_position.position.z = 0.65;
623 req.path_constraints.position_constraints.back().constraint_region.primitive_poses.push_back(center_position);
626 ASSERT_FALSE(circ_->generate(planning_scene_, req, res));
627 EXPECT_EQ(res.
error_code_.val, moveit_msgs::msg::MoveItErrorCodes::INVALID_MOTION_PLAN);
638 auto circ{ tdp_->getCircJointCenterCart(
"circ1_center_2") };
643 moveit_msgs::msg::JointConstraint joint_constraint;
644 joint_constraint.joint_name = req.goal_constraints.front().joint_constraints.front().joint_name;
645 req.goal_constraints.front().joint_constraints.push_back(joint_constraint);
648 EXPECT_FALSE(circ_->generate(planning_scene_, req, res));
649 EXPECT_EQ(res.
error_code_.val, moveit_msgs::msg::MoveItErrorCodes::INVALID_GOAL_CONSTRAINTS);
657 auto circ{ tdp_->getCircCartCenterCart(
"circ1_center_2") };
662 ASSERT_TRUE(circ_->generate(planning_scene_, req, res));
663 EXPECT_EQ(res.
error_code_.val, moveit_msgs::msg::MoveItErrorCodes::SUCCESS);
664 checkCircResult(req, res);
672 auto circ{ tdp_->getCircCartCenterCart(
"circ1_center_2") };
676 req.goal_constraints.front().position_constraints.front().header.frame_id = robot_model_->getModelFrame();
679 ASSERT_TRUE(circ_->generate(planning_scene_, req, res));
680 EXPECT_EQ(res.
error_code_.val, moveit_msgs::msg::MoveItErrorCodes::SUCCESS);
681 checkCircResult(req, res);
689 auto circ{ tdp_->getCircCartCenterCart(
"circ1_center_2") };
692 req.goal_constraints.front().orientation_constraints.front().header.frame_id = robot_model_->getModelFrame();
695 ASSERT_TRUE(circ_->generate(planning_scene_, req, res));
696 EXPECT_EQ(res.
error_code_.val, moveit_msgs::msg::MoveItErrorCodes::SUCCESS);
697 checkCircResult(req, res);
705 auto circ{ tdp_->getCircCartCenterCart(
"circ1_center_2") };
710 req.goal_constraints.front().position_constraints.front().header.frame_id = robot_model_->getModelFrame();
711 req.goal_constraints.front().orientation_constraints.front().header.frame_id = robot_model_->getModelFrame();
714 ASSERT_TRUE(circ_->generate(planning_scene_, req, res));
715 EXPECT_EQ(res.
error_code_.val, moveit_msgs::msg::MoveItErrorCodes::SUCCESS);
716 checkCircResult(req, res);
724 auto circ{ tdp_->getCircJointInterimCart(
"circ3_interim") };
729 ASSERT_TRUE(circ_->generate(planning_scene_, req, res));
730 EXPECT_EQ(res.
error_code_.val, moveit_msgs::msg::MoveItErrorCodes::SUCCESS);
731 checkCircResult(req, res);
742 auto circ{ tdp_->getCircJointInterimCart(
"circ3_interim") };
747 req.start_state.joint_state.velocity = std::vector<double>(req.start_state.joint_state.position.size(), 1e-16);
750 ASSERT_TRUE(circ_->generate(planning_scene_, req, res));
751 EXPECT_EQ(res.
error_code_.val, moveit_msgs::msg::MoveItErrorCodes::SUCCESS);
752 checkCircResult(req, res);
760 auto circ{ tdp_->getCircJointInterimCart(
"circ3_interim") };
764 ASSERT_TRUE(circ_->generate(planning_scene_, req, res));
765 EXPECT_EQ(res.
error_code_.val, moveit_msgs::msg::MoveItErrorCodes::SUCCESS);
766 checkCircResult(req, res);
769 int main(
int argc,
char** argv)
771 rclcpp::init(argc, argv);
772 testing::InitGoogleTest(&argc, argv);
773 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_
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.
This class implements a trajectory generator of arcs in Cartesian space. The arc is specified by a st...
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 veryfied.
::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.
robot_trajectory::RobotTrajectoryPtr trajectory_
void getMessage(moveit_msgs::msg::MotionPlanResponse &msg) const
moveit_msgs::msg::MoveItErrorCodes error_code_
int main(int argc, char **argv)