37 #include <gtest/gtest.h>
43 #include <tf2_eigen/tf2_eigen.hpp>
44 #include <tf2_geometry_msgs/tf2_geometry_msgs.hpp>
57 #include <rclcpp/rclcpp.hpp>
62 static const std::string PARAM_NAMESPACE_LIMITS =
"robot_description_planning";
72 rclcpp::NodeOptions node_options;
73 node_options.automatically_declare_parameters_from_overrides(
true);
74 node_ = rclcpp::Node::make_shared(
"unittest_trajectory_blender_transition_window", node_options);
77 rm_loader_ = std::make_unique<robot_model_loader::RobotModelLoader>(node_);
78 robot_model_ = rm_loader_->getModel();
79 ASSERT_TRUE(
bool(robot_model_)) <<
"Failed to load robot model";
80 planning_scene_ = std::make_shared<planning_scene::PlanningScene>(robot_model_);
83 ASSERT_TRUE(node_->has_parameter(
"planning_group"));
84 node_->get_parameter<std::string>(
"planning_group", planning_group_);
85 ASSERT_TRUE(node_->has_parameter(
"target_link"));
86 node_->get_parameter<std::string>(
"target_link", target_link_);
87 ASSERT_TRUE(node_->has_parameter(
"cartesian_velocity_tolerance"));
88 node_->get_parameter<
double>(
"cartesian_velocity_tolerance", cartesian_velocity_tolerance_);
89 ASSERT_TRUE(node_->has_parameter(
"cartesian_angular_velocity_tolerance"));
90 node_->get_parameter<
double>(
"cartesian_angular_velocity_tolerance", cartesian_angular_velocity_tolerance_);
91 ASSERT_TRUE(node_->has_parameter(
"joint_velocity_tolerance"));
92 node_->get_parameter<
double>(
"joint_velocity_tolerance", joint_velocity_tolerance_);
93 ASSERT_TRUE(node_->has_parameter(
"joint_acceleration_tolerance"));
94 node_->get_parameter<
double>(
"joint_acceleration_tolerance", joint_acceleration_tolerance_);
95 ASSERT_TRUE(node_->has_parameter(
"sampling_time"));
96 node_->get_parameter<
double>(
"sampling_time", sampling_time_);
97 ASSERT_TRUE(node_->has_parameter(
"testdata_file_name"));
98 node_->get_parameter<std::string>(
"testdata_file_name", test_data_file_name_);
101 data_loader_ = std::make_unique<XmlTestdataLoader>(test_data_file_name_, robot_model_);
102 ASSERT_NE(
nullptr, data_loader_) <<
"Failed to load test data by provider.";
110 node_, PARAM_NAMESPACE_LIMITS, robot_model_->getActiveJointModels());
117 planner_limits_.setCartesianLimits(cart_limits);
120 lin_generator_ = std::make_unique<TrajectoryGeneratorLIN>(robot_model_, planner_limits_, planning_group_);
121 ASSERT_NE(
nullptr, lin_generator_) <<
"failed to create LIN trajectory generator";
122 blender_ = std::make_unique<TrajectoryBlenderTransitionWindow>(planner_limits_);
123 ASSERT_NE(
nullptr, blender_) <<
"failed to create trajectory blender";
128 robot_model_.reset();
136 std::vector<planning_interface::MotionPlanResponse> responses(num_cmds);
137 for (
size_t index = 0; index < num_cmds; ++index)
148 if (!lin_generator_->generate(planning_scene_, req, resp, sampling_time_))
150 std::runtime_error(
"Failed to generate trajectory.");
152 responses.at(index) = resp;
161 std::unique_ptr<robot_model_loader::RobotModelLoader>
rm_loader_;
165 std::unique_ptr<TrajectoryBlenderTransitionWindow>
blender_;
190 Sequence seq{ data_loader_->getSequence(
"SimpleSequence") };
192 std::vector<planning_interface::MotionPlanResponse> res{ generateLinTrajs(seq, 2) };
203 EXPECT_FALSE(blender_->blend(planning_scene_, blend_req, blend_res));
219 Sequence seq{ data_loader_->getSequence(
"SimpleSequence") };
221 std::vector<planning_interface::MotionPlanResponse> res{ generateLinTrajs(seq, 2) };
227 blend_req.
link_name =
"invalid_target_link";
232 EXPECT_FALSE(blender_->blend(planning_scene_, blend_req, blend_res));
249 Sequence seq{ data_loader_->getSequence(
"SimpleSequence") };
251 std::vector<planning_interface::MotionPlanResponse> res{ generateLinTrajs(seq, 2) };
262 EXPECT_FALSE(blender_->blend(planning_scene_, blend_req, blend_res));
278 Sequence seq{ data_loader_->getSequence(
"SimpleSequence") };
280 std::vector<planning_interface::MotionPlanResponse> res{ generateLinTrajs(seq, 2) };
291 EXPECT_FALSE(blender_->blend(planning_scene_, blend_req, blend_res));
308 Sequence seq{ data_loader_->getSequence(
"SimpleSequence") };
311 std::size_t num_cmds{ 2 };
312 std::vector<planning_interface::MotionPlanResponse> responses(num_cmds);
314 for (
size_t index = 0; index < num_cmds; ++index)
326 if (!lin_generator_->generate(planning_scene_, req, resp, sampling_time_))
328 std::runtime_error(
"Failed to generate trajectory.");
330 responses.at(index) = resp;
341 EXPECT_FALSE(blender_->blend(planning_scene_, blend_req, blend_res));
360 Sequence seq{ data_loader_->getSequence(
"SimpleSequence") };
362 std::vector<planning_interface::MotionPlanResponse> res{ generateLinTrajs(seq, 2) };
365 EXPECT_GT(res[0].trajectory_->getWayPointCount(), 2u);
366 res[0].trajectory_->setWayPointDurationFromPrevious(1, 2 * sampling_time_);
376 EXPECT_FALSE(blender_->blend(planning_scene_, blend_req, blend_res));
394 Sequence seq{ data_loader_->getSequence(
"SimpleSequence") };
396 std::vector<planning_interface::MotionPlanResponse> res{ generateLinTrajs(seq, 1) };
408 EXPECT_FALSE(blender_->blend(planning_scene_, blend_req, blend_res));
425 Sequence seq{ data_loader_->getSequence(
"SimpleSequence") };
427 std::vector<planning_interface::MotionPlanResponse> res{ generateLinTrajs(seq, 2) };
441 blend_req.
first_trajectory->getLastWayPointPtr()->setVariableVelocity(0, 1.0);
444 EXPECT_FALSE(blender_->blend(planning_scene_, blend_req, blend_res));
462 Sequence seq{ data_loader_->getSequence(
"SimpleSequence") };
464 std::vector<planning_interface::MotionPlanResponse> res{ generateLinTrajs(seq, 2) };
466 double lin1_distance;
467 lin1_distance = (res[0].trajectory_->getFirstWayPoint().getFrameTransform(target_link_).translation() -
468 res[0].trajectory_->getLastWayPoint().getFrameTransform(target_link_).translation())
481 EXPECT_FALSE(blender_->blend(planning_scene_, blend_req, blend_res));
499 Sequence seq{ data_loader_->getSequence(
"NoIntersectionTraj2") };
501 std::vector<planning_interface::MotionPlanResponse> res{ generateLinTrajs(seq, 2) };
513 EXPECT_FALSE(blender_->blend(planning_scene_, blend_req, blend_res));
536 Sequence seq{ data_loader_->getSequence(
"SimpleSequence") };
538 std::vector<planning_interface::MotionPlanResponse> res{ generateLinTrajs(seq, 2) };
550 EXPECT_TRUE(blender_->blend(planning_scene_, blend_req, blend_res));
553 joint_acceleration_tolerance_, cartesian_velocity_tolerance_,
554 cartesian_angular_velocity_tolerance_));
579 Sequence seq{ data_loader_->getSequence(
"SimpleSequence") };
583 std::vector<planning_interface::MotionPlanResponse> res{ generateLinTrajs(seq, 2) };
593 EXPECT_TRUE(blender_->blend(planning_scene_, blend_req, blend_res));
596 joint_acceleration_tolerance_, cartesian_velocity_tolerance_,
597 cartesian_angular_velocity_tolerance_));
625 const double sine_scaling_factor{ 0.01 };
626 const double time_scaling_factor{ 10 };
628 Sequence seq{ data_loader_->getSequence(
"SimpleSequence") };
630 std::vector<planning_interface::MotionPlanResponse> res{ generateLinTrajs(seq, 2) };
633 std::vector<robot_trajectory::RobotTrajectoryPtr> sine_trajs(2);
635 for (
size_t traj_index = 0; traj_index < 2; ++traj_index)
637 auto lin_traj{ res.at(traj_index).trajectory_ };
640 trajectory_msgs::msg::JointTrajectory joint_traj;
641 const double duration{ lin_traj->getWayPointDurationFromStart(lin_traj->getWayPointCount()) };
643 const double time_from_start_offset{ time_scaling_factor * lin_traj->getWayPointDurations().back() };
646 for (
size_t i = 0; i < lin_traj->getWayPointCount(); ++i)
649 const double sine_arg{ 4 * M_PI * lin_traj->getWayPointDurationFromStart(i) / duration };
653 const Eigen::Isometry3d eigen_pose{ lin_traj->getWayPointPtr(i)->getFrameTransform(target_link_) };
654 geometry_msgs::msg::Pose waypoint_pose = tf2::toMsg(eigen_pose);
657 waypoint_pose.position.x += sine_scaling_factor * sin(sine_arg);
658 waypoint_pose.position.y += sine_scaling_factor * sin(sine_arg);
659 waypoint_pose.position.z += sine_scaling_factor * sin(sine_arg);
662 waypoint.
pose = waypoint_pose;
664 time_from_start_offset + time_scaling_factor * lin_traj->getWayPointDurationFromStart(i));
665 cart_traj.
points.push_back(waypoint);
669 std::map<std::string, double> initial_joint_position, initial_joint_velocity;
670 for (
const std::string& joint_name :
671 lin_traj->getFirstWayPointPtr()->getJointModelGroup(planning_group_)->getActiveJointModelNames())
675 initial_joint_position[joint_name] = lin_traj->getFirstWayPoint().getVariablePosition(joint_name);
676 initial_joint_velocity[joint_name] = lin_traj->getFirstWayPoint().getVariableVelocity(joint_name);
680 initial_joint_position[joint_name] =
681 sine_trajs[traj_index - 1]->getLastWayPoint().getVariablePosition(joint_name);
682 initial_joint_velocity[joint_name] =
683 sine_trajs[traj_index - 1]->getLastWayPoint().getVariableVelocity(joint_name);
687 moveit_msgs::msg::MoveItErrorCodes error_code;
688 if (!
generateJointTrajectory(planning_scene_, planner_limits_.getJointLimitContainer(), cart_traj, planning_group_,
689 target_link_, initial_joint_position, initial_joint_velocity, joint_traj, error_code,
692 std::runtime_error(
"Failed to generate trajectory.");
695 joint_traj.points.back().velocities.assign(joint_traj.points.back().velocities.size(), 0.0);
696 joint_traj.points.back().accelerations.assign(joint_traj.points.back().accelerations.size(), 0.0);
699 sine_trajs[traj_index] = std::make_shared<robot_trajectory::RobotTrajectory>(robot_model_, planning_group_);
700 sine_trajs.at(traj_index)->setRobotTrajectoryMsg(lin_traj->getFirstWayPoint(), joint_traj);
713 EXPECT_TRUE(blender_->blend(planning_scene_, blend_req, blend_res));
716 joint_acceleration_tolerance_, cartesian_velocity_tolerance_,
717 cartesian_angular_velocity_tolerance_));
720 int main(
int argc,
char** argv)
722 rclcpp::init(argc, argv);
723 testing::InitGoogleTest(&argc, argv);
724 return RUN_ALL_TESTS();
void SetUp() override
Create test scenario for trajectory blender.
std::string planning_group_
moveit::core::RobotModelConstPtr robot_model_
std::string test_data_file_name_
std::unique_ptr< TrajectoryGenerator > lin_generator_
double joint_acceleration_tolerance_
double cartesian_angular_velocity_tolerance_
std::unique_ptr< TrajectoryBlenderTransitionWindow > blender_
std::unique_ptr< robot_model_loader::RobotModelLoader > rm_loader_
std::vector< planning_interface::MotionPlanResponse > generateLinTrajs(const Sequence &seq, size_t num_cmds)
Generate lin trajectories for blend sequences.
XmlTestDataLoaderUPtr data_loader_
planning_scene::PlanningSceneConstPtr planning_scene_
LimitsContainer planner_limits_
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.
StartType & getStartConfiguration()
Data class storing all information regarding a linear command.
Data class storing all information regarding a Sequence command.
T & getCmd(const size_t index_cmd)
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.
std::unique_ptr< TestdataLoader > XmlTestDataLoaderUPtr
bool generateJointTrajectory(const planning_scene::PlanningSceneConstPtr &scene, const JointLimitsContainer &joint_limits, const KDL::Trajectory &trajectory, const std::string &group_name, const std::string &link_name, const std::map< std::string, double > &initial_joint_position, const double &sampling_time, trajectory_msgs::msg::JointTrajectory &joint_trajectory, moveit_msgs::msg::MoveItErrorCodes &error_code, bool check_self_collision=false)
Generate joint trajectory from a KDL Cartesian trajectory.
TEST_F(GetSolverTipFrameIntegrationTest, TestHasSolverManipulator)
Check if hasSolver() can be called successfully for the manipulator group.
moveit_msgs::msg::MotionPlanRequest MotionPlanRequest
bool checkBlendResult(const pilz_industrial_motion_planner::TrajectoryBlendRequest &blend_req, const pilz_industrial_motion_planner::TrajectoryBlendResponse &blend_res, const pilz_industrial_motion_planner::LimitsContainer &limits, double joint_velocity_tolerance, double joint_acceleration_tolerance, double cartesian_velocity_tolerance, double cartesian_angular_velocity_tolerance)
check the blending result of lin-lin
void checkRobotModel(const moveit::core::RobotModelConstPtr &robot_model, const std::string &group_name, const std::string &link_name)
geometry_msgs::msg::Pose pose
rclcpp::Duration time_from_start
std::vector< CartesianTrajectoryPoint > points
robot_trajectory::RobotTrajectoryPtr second_trajectory
robot_trajectory::RobotTrajectoryPtr first_trajectory
int main(int argc, char **argv)