35#include <gtest/gtest.h>
38#include <tf2_eigen/tf2_eigen.hpp>
39#include <tf2_geometry_msgs/tf2_geometry_msgs.hpp>
41#include <rclcpp/logger.hpp>
45static const rclcpp::Logger LOGGER = rclcpp::get_logger(
"pilz_industrial_motion_planner.test_utils");
52 for (
const std::string& name : joint_names)
73 Eigen::Isometry3d& goal_pose_expect)
78 if (!req.goal_constraints.front().joint_constraints.empty())
80 std::map<std::string, double> goal_joint_position;
83 for (
const auto& joint_name : robot_model->getVariableNames())
85 goal_joint_position[joint_name] = 0;
88 for (
const auto& joint_item : req.goal_constraints.front().joint_constraints)
90 goal_joint_position[joint_item.joint_name] = joint_item.position;
93 link_name = robot_model->getJointModelGroup(req.group_name)->getSolverInstance()->getTipFrame();
95 if (!computeLinkFK(robot_model, link_name, goal_joint_position, goal_pose_expect))
97 std::cerr <<
"Failed to compute forward kinematics for link in goal "
108 link_name = req.goal_constraints.front().position_constraints.front().link_name;
109 geometry_msgs::msg::Pose goal_pose_msg;
110 goal_pose_msg.position =
111 req.goal_constraints.front().position_constraints.front().constraint_region.primitive_poses.front().position;
112 goal_pose_msg.orientation = req.goal_constraints.front().orientation_constraints.front().orientation;
114 tf2::fromMsg(goal_pose_msg, goal_pose_expect);
119 const std::vector<moveit_msgs::msg::JointConstraint>& goal,
120 const double joint_position_tolerance,
const double joint_velocity_tolerance)
122 trajectory_msgs::msg::JointTrajectoryPoint last_point = trajectory.points.back();
124 for (
unsigned int i = 0; i < trajectory.joint_names.size(); ++i)
126 if (fabs(last_point.velocities.at(i)) > joint_velocity_tolerance)
128 std::cerr <<
"[ Fail ] goal has non zero velocity."
129 <<
" Joint Name: " << trajectory.joint_names.at(i) <<
"; Velocity: " << last_point.velocities.at(i)
134 for (
const auto& joint_goal : goal)
136 if (trajectory.joint_names.at(i) == joint_goal.joint_name)
138 if (fabs(last_point.positions.at(i) - joint_goal.position) > joint_position_tolerance)
140 std::cerr <<
"[ Fail ] goal position not reached."
141 <<
" Joint Name: " << trajectory.joint_names.at(i)
142 <<
"; Actual Position: " << last_point.positions.at(i)
143 <<
"; Expected Position: " << joint_goal.position <<
'\n';
154 const trajectory_msgs::msg::JointTrajectory& trajectory,
156 const double orientation_tolerance)
158 std::string link_name;
159 Eigen::Isometry3d goal_pose_expect;
166 trajectory_msgs::msg::JointTrajectoryPoint last_point = trajectory.points.back();
167 Eigen::Isometry3d goal_pose_actual;
168 std::map<std::string, double> joint_state;
171 for (
const auto& joint_name : robot_model->getVariableNames())
173 joint_state[joint_name] = 0;
176 for (std::size_t i = 0; i < trajectory.joint_names.size(); ++i)
178 joint_state[trajectory.joint_names.at(i)] = last_point.positions.at(i);
181 if (!computeLinkFK(robot_model, link_name, joint_state, goal_pose_actual))
183 std::cerr <<
"[ Fail ] forward kinematics computation failed for link: " << link_name <<
'\n';
186 auto actual_rotation{ goal_pose_actual.rotation() };
187 auto expected_rotation{ goal_pose_expect.rotation() };
188 auto rot_diff{ actual_rotation - expected_rotation };
189 if (rot_diff.norm() > orientation_tolerance)
191 std::cout <<
"\nOrientation difference = " << rot_diff.norm() <<
" (eps=" << orientation_tolerance <<
')'
192 <<
"\n### Expected goal orientation: ### \n"
193 << expected_rotation <<
'\n'
194 <<
"### Actual goal orientation ### \n"
195 << actual_rotation <<
'\n';
199 auto actual_position{ goal_pose_actual.translation() };
200 auto expected_position{ goal_pose_expect.translation() };
201 auto pos_diff{ actual_position - expected_position };
202 if (pos_diff.norm() > pos_tolerance)
204 std::cout <<
"\nPosition difference = " << pos_diff.norm() <<
" (eps=" << pos_tolerance <<
')'
205 <<
"\n### Expected goal position: ### \n"
206 << expected_position <<
'\n'
207 <<
"### Actual goal position ### \n"
208 << actual_position <<
'\n';
216 const trajectory_msgs::msg::JointTrajectory& trajectory,
219 return isGoalReached(robot_model, trajectory, req, tolerance, tolerance);
223 const trajectory_msgs::msg::JointTrajectory& trajectory,
225 const double translation_norm_tolerance,
const double rot_axis_norm_tolerance,
228 std::string link_name;
229 Eigen::Isometry3d goal_pose_expect;
242 Eigen::AngleAxisd start_goal_aa(start_pose.rotation().transpose() * goal_pose_expect.rotation());
245 for (trajectory_msgs::msg::JointTrajectoryPoint way_point : trajectory.points)
247 Eigen::Isometry3d way_point_pose;
248 std::map<std::string, double> way_point_joint_state;
251 for (
const auto& joint_name : robot_model->getVariableNames())
253 way_point_joint_state[joint_name] = 0;
256 for (std::size_t i = 0; i < trajectory.joint_names.size(); ++i)
258 way_point_joint_state[trajectory.joint_names.at(i)] = way_point.positions.at(i);
261 if (!computeLinkFK(robot_model, link_name, way_point_joint_state, way_point_pose))
263 std::cerr <<
"Failed to compute forward kinematics for link in goal "
269 Eigen::Vector3d goal_start_translation = goal_pose_expect.translation() - start_pose.translation();
272 if (fabs((goal_start_translation.cross(way_point_pose.translation()) -
273 goal_start_translation.cross(start_pose.translation()))
274 .norm()) > fabs(translation_norm_tolerance))
276 std::cout <<
"Translational linearity is violated. \n"
277 <<
"goal translation: " << goal_pose_expect.translation() <<
'\n'
278 <<
"start translation: " << start_pose.translation() <<
'\n'
279 <<
"actual translation " << way_point_pose.translation() <<
'\n';
283 if (!
checkSLERP(start_pose, goal_pose_expect, way_point_pose, rot_axis_norm_tolerance))
293 const Eigen::Isometry3d& wp_pose,
const double rot_axis_norm_tolerance,
294 const double rot_angle_tolerance)
298 Eigen::AngleAxisd start_goal_aa(start_pose.rotation().transpose() * goal_pose.rotation());
299 Eigen::AngleAxisd start_wp_aa(start_pose.rotation().transpose() * wp_pose.rotation());
304 if (((start_goal_aa.axis() - start_wp_aa.axis()).norm() >= fabs(rot_axis_norm_tolerance)) &&
305 ((start_goal_aa.axis() + start_wp_aa.axis()).norm() >= fabs(rot_axis_norm_tolerance)) &&
306 (fabs(start_wp_aa.angle()) >= fabs(rot_angle_tolerance)))
308 std::cout <<
"Rotational linearity is violated. \n"
310 <<
"start goal angle: " << start_goal_aa.angle() <<
"; axis: " <<
'\n'
311 << start_goal_aa.axis() <<
'\n'
312 <<
"start waypoint angle: " << start_wp_aa.angle() <<
"; axis: " <<
'\n'
313 << start_wp_aa.axis() <<
'\n';
322 const std::map<std::string, double>& joint_state, Eigen::Isometry3d& pose)
331 RCLCPP_ERROR_STREAM(LOGGER,
"The target link " << link_name <<
" is not known by robot.");
340 catch (
const std::exception& e)
342 std::cerr << e.what() <<
'\n';
356 for (
const auto& point : trajectory.points)
358 for (std::size_t i = 0; i < point.velocities.size(); ++i)
360 if (fabs(point.velocities.at(i)) > fabs(
joint_limits.getLimit(trajectory.joint_names.at(i)).max_velocity))
362 std::cerr <<
"[ Fail ] Joint velocity limit violated in " << i <<
"th waypoint of joint: "
363 <<
" Joint Name: " << trajectory.joint_names.at(i) <<
"; Position: " << point.positions.at(i)
364 <<
"; Velocity: " << point.velocities.at(i) <<
"; Acceleration: " << point.accelerations.at(i)
365 <<
"; Time from start: " << rclcpp::Duration(point.time_from_start).seconds()
366 <<
"; Velocity Limit: " <<
joint_limits.getLimit(trajectory.joint_names.at(i)).max_velocity <<
'\n';
378 for (
const auto& point : trajectory.points)
380 if (trajectory.joint_names.size() != point.positions.size() ||
381 trajectory.joint_names.size() != point.velocities.size() ||
382 trajectory.joint_names.size() != point.accelerations.size())
396 for (
const auto& point : trajectory.points)
398 for (std::size_t i = 0; i < point.velocities.size(); ++i)
401 if (point.velocities.at(i) * point.accelerations.at(i) <= 0)
403 if (fabs(point.accelerations.at(i)) > fabs(
joint_limits.getLimit(trajectory.joint_names.at(i)).max_deceleration))
405 std::cerr <<
"[ Fail ] Deceleration limit violated of joint: " << trajectory.joint_names.at(i)
406 <<
": Position: " << point.positions.at(i) <<
"; Velocity: " << point.velocities.at(i)
407 <<
"; Acceleration: " << point.accelerations.at(i)
408 <<
"; Time from start: " << rclcpp::Duration(point.time_from_start).seconds()
409 <<
". Deceleration Limit: " <<
joint_limits.getLimit(trajectory.joint_names.at(i)).max_deceleration
417 if (fabs(point.accelerations.at(i)) > fabs(
joint_limits.getLimit(trajectory.joint_names.at(i)).max_acceleration))
419 std::cerr <<
"[ Fail ] Acceleration limit violated of joint: " << trajectory.joint_names.at(i)
420 <<
": Position: " << point.positions.at(i) <<
"; Velocity: " << point.velocities.at(i)
421 <<
"; Acceleration: " << point.accelerations.at(i)
422 <<
"; Time from start: " << rclcpp::Duration(point.time_from_start).seconds()
423 <<
". Acceleration Limit: " <<
joint_limits.getLimit(trajectory.joint_names.at(i)).max_acceleration
438 for (
const auto& point : trajectory.points)
440 for (std::size_t i = 0; i < point.positions.size(); ++i)
442 if (point.positions.at(i) >
joint_limits.getLimit(trajectory.joint_names.at(i)).max_position ||
443 point.positions.at(i) <
joint_limits.getLimit(trajectory.joint_names.at(i)).min_position)
445 std::cerr <<
"[ Fail ] Joint position limit violated in " << i <<
"th waypoint of joint: "
446 <<
" Joint Name: " << trajectory.joint_names.at(i) <<
"; Position: " << point.positions.at(i)
447 <<
"; Velocity: " << point.velocities.at(i) <<
"; Acceleration: " << point.accelerations.at(i)
448 <<
"; Time from start: " << rclcpp::Duration(point.time_from_start).seconds()
449 <<
"; Max Position: " <<
joint_limits.getLimit(trajectory.joint_names.at(i)).max_position
450 <<
"; Min Position: " <<
joint_limits.getLimit(trajectory.joint_names.at(i)).min_position <<
'\n';
465 std::cout <<
"Joint trajectory is not consistent." <<
'\n';
470 std::cout <<
"Joint poisiton violated the limits." <<
'\n';
475 std::cout <<
"Joint velocity violated the limits." <<
'\n';
480 std::cout <<
"Joint acceleration violated the limits." <<
'\n';
490 for (
unsigned int i = 1; i < trajectory->getWayPointCount(); ++i)
492 if (trajectory->getWayPointDurationFromPrevious(i) <= 0.0)
494 return ::testing::AssertionFailure()
495 <<
"Waypoint " << (i) <<
" has " << trajectory->getWayPointDurationFromPrevious(i)
496 <<
" time between itself and its predecessor."
497 <<
" Total points in trajectory: " << trajectory->getWayPointCount() <<
'.';
501 return ::testing::AssertionSuccess();
508 req.group_name = planning_group;
509 req.max_velocity_scaling_factor = 1.0;
510 req.max_acceleration_scaling_factor = 1.0;
520 req.planner_id =
"PTP";
521 req.group_name = planning_group;
522 req.max_velocity_scaling_factor = 0.5;
523 req.max_acceleration_scaling_factor = 0.5;
528 goal_state, goal_state.
getRobotModel()->getJointModelGroup(planning_group)));
532 const std::vector<double>& joint_values, geometry_msgs::msg::Pose& pose,
533 const std::string& joint_prefix)
536 std::map<std::string, double> joint_state;
537 auto joint_values_it = joint_values.begin();
540 for (
const auto& joint_name : robot_model->getVariableNames())
542 joint_state[joint_name] = 0;
545 for (std::size_t i = 0; i < joint_values.size(); ++i)
551 Eigen::Isometry3d eig_pose;
556 pose = tf2::toMsg(eig_pose);
563 const double time_tolerance)
567 for (
const std::string& joint_name :
574 std::cout << i <<
"th position of the first trajectory is not same." <<
'\n';
582 std::cout << i <<
"th velocity of the first trajectory is not same." <<
'\n';
587 if (res.
first_trajectory->getWayPoint(i).getVariableAcceleration(joint_name) !=
590 std::cout << i <<
"th acceleration of the first trajectory is not same." <<
'\n';
598 std::cout << i <<
"th time_from_start of the first trajectory is not same." <<
'\n';
605 for (std::size_t i = 0; i < size_second; ++i)
607 for (
const std::string& joint_name : res.
second_trajectory->getWayPoint(size_second - i - 1)
609 ->getActiveJointModelNames())
612 if (res.
second_trajectory->getWayPoint(size_second - i - 1).getVariablePosition(joint_name) !=
613 req.
second_trajectory->getWayPoint(size_second_original - i - 1).getVariablePosition(joint_name))
615 std::cout << i - 1 <<
"th position of the second trajectory is not same." <<
'\n';
620 if (res.
second_trajectory->getWayPoint(size_second - i - 1).getVariableVelocity(joint_name) !=
621 req.
second_trajectory->getWayPoint(size_second_original - i - 1).getVariableVelocity(joint_name))
623 std::cout << i - 1 <<
"th position of the second trajectory is not same." <<
'\n';
628 if (res.
second_trajectory->getWayPoint(size_second - i - 1).getVariableAcceleration(joint_name) !=
629 req.
second_trajectory->getWayPoint(size_second_original - i - 1).getVariableAcceleration(joint_name))
631 std::cout << i - 1 <<
"th position of the second trajectory is not same." <<
'\n';
637 if (i < size_second - 1)
639 if (fabs((res.
second_trajectory->getWayPointDurationFromStart(size_second - i - 1) -
641 (req.
second_trajectory->getWayPointDurationFromStart(size_second_original - i - 1) -
642 req.
second_trajectory->getWayPointDurationFromStart(size_second_original - i - 2))) > time_tolerance)
644 std::cout << size_second - i - 1 <<
"th time from start of the second trajectory is not same."
645 << res.
second_trajectory->getWayPointDurationFromStart(size_second - i - 1) <<
", "
646 << res.
second_trajectory->getWayPointDurationFromStart(size_second - i - 2) <<
", "
647 << req.
second_trajectory->getWayPointDurationFromStart(size_second_original - i - 1) <<
", "
648 << req.
second_trajectory->getWayPointDurationFromStart(size_second_original - i - 2) <<
'\n';
654 if (fabs((res.
second_trajectory->getWayPointDurationFromStart(size_second - i - 1)) -
655 (req.
second_trajectory->getWayPointDurationFromStart(size_second_original - i - 1) -
656 req.
second_trajectory->getWayPointDurationFromStart(size_second_original - i - 2))) > time_tolerance)
658 std::cout << size_second - i - 1 <<
"th time from start of the second trajectory is not same."
659 << res.
second_trajectory->getWayPointDurationFromStart(size_second - i - 1) <<
", "
660 << req.
second_trajectory->getWayPointDurationFromStart(size_second_original - i - 1) -
661 req.
second_trajectory->getWayPointDurationFromStart(size_second_original - i - 2)
672 double joint_velocity_tolerance,
double joint_accleration_tolerance)
675 moveit_msgs::msg::RobotTrajectory first_traj, blend_traj, second_traj;
681 trajectory_msgs::msg::JointTrajectoryPoint first_end, blend_start;
682 first_end = first_traj.joint_trajectory.points.back();
683 blend_start = blend_traj.joint_trajectory.points.front();
686 if (first_end.positions.size() != blend_start.positions.size() ||
687 first_end.velocities.size() != blend_start.velocities.size() ||
688 first_end.accelerations.size() != blend_start.accelerations.size())
690 std::cout <<
"Different sizes of the position/velocity/acceleration "
691 "between first trajectory and blend trajectory."
697 for (std::size_t i = 0; i < first_end.positions.size(); ++i)
699 double blend_start_velo = (blend_start.positions.at(i) - first_end.positions.at(i)) /
700 rclcpp::Duration(blend_start.time_from_start).seconds();
701 if (fabs(blend_start_velo - blend_start.velocities.at(i)) > joint_velocity_tolerance)
703 std::cout <<
"Velocity computed from positions are different from the "
704 "value in trajectory."
706 <<
"position: " << blend_start.positions.at(i) <<
"; " << first_end.positions.at(i)
707 <<
"computed: " << blend_start_velo <<
"; "
708 <<
"in trajectory: " << blend_start.velocities.at(i) <<
'\n';
712 double blend_start_acc =
713 (blend_start_velo - first_end.velocities.at(i)) / rclcpp::Duration(blend_start.time_from_start).seconds();
714 if (fabs(blend_start_acc - blend_start.accelerations.at(i)) > joint_velocity_tolerance)
716 std::cout <<
"Acceleration computed from positions/velocities are "
717 "different from the value in trajectory."
719 <<
"computed: " << blend_start_acc <<
"; "
720 <<
"in trajectory: " << blend_start.accelerations.at(i) <<
'\n';
726 trajectory_msgs::msg::JointTrajectoryPoint blend_end, second_start;
727 blend_end = blend_traj.joint_trajectory.points.back();
728 second_start = second_traj.joint_trajectory.points.front();
731 if (blend_end.positions.size() != second_start.positions.size() ||
732 blend_end.velocities.size() != second_start.velocities.size() ||
733 blend_end.accelerations.size() != second_start.accelerations.size())
735 std::cout <<
"Different sizes of the position/velocity/acceleration "
736 "between first trajectory and blend trajectory."
738 << blend_end.positions.size() <<
", " << second_start.positions.size() <<
'\n'
739 << blend_end.velocities.size() <<
", " << second_start.positions.size() <<
'\n'
740 << blend_end.accelerations.size() <<
", " << second_start.accelerations.size() <<
'\n';
745 for (std::size_t i = 0; i < blend_end.positions.size(); ++i)
747 double second_start_velo = (second_start.positions.at(i) - blend_end.positions.at(i)) /
748 rclcpp::Duration(second_start.time_from_start).seconds();
749 if (fabs(second_start_velo - second_start.velocities.at(i)) > joint_accleration_tolerance)
751 std::cout <<
"Velocity computed from positions are different from the "
752 "value in trajectory."
754 <<
"computed: " << second_start_velo <<
"; "
755 <<
"in trajectory: " << second_start.velocities.at(i) <<
'\n';
759 double second_start_acc =
760 (second_start_velo - blend_end.velocities.at(i)) / rclcpp::Duration(second_start.time_from_start).seconds();
761 if (fabs(second_start_acc - second_start.accelerations.at(i)) > joint_accleration_tolerance)
763 std::cout <<
"Acceleration computed from positions/velocities are "
764 "different from the value in trajectory."
766 <<
"computed: " << second_start_acc <<
"; "
767 <<
"in trajectory: " << second_start.accelerations.at(i) <<
'\n';
783 std::cout <<
"Cannot perform check of cartesian space continuity with "
793 double max_rot_acc = max_trans_acc / max_trans_velo * max_rot_velo;
800 Eigen::Isometry3d pose_first_end, pose_first_end_1, pose_blend_start, pose_blend_start_1, pose_blend_end,
801 pose_blend_end_1, pose_second_start, pose_second_start_1;
845 Eigen::Vector3d v_1, w_1, v_2, w_2, v_3, w_3;
851 if (v_2.norm() > max_trans_velo)
853 std::cout <<
"Translational velocity between first trajectory and blend "
854 "trajectory exceeds the limit."
855 <<
"Actual velocity (norm): " << v_2.norm() <<
"; "
856 <<
"Limits: " << max_trans_velo <<
'\n';
859 if (w_2.norm() > max_rot_velo)
861 std::cout <<
"Rotational velocity between first trajectory and blend "
862 "trajectory exceeds the limit."
863 <<
"Actual velocity (norm): " << w_2.norm() <<
"; "
864 <<
"Limits: " << max_rot_velo <<
'\n';
867 Eigen::Vector3d a_1 = (v_2 - v_1) / duration;
868 Eigen::Vector3d a_2 = (v_3 - v_2) / duration;
869 if (a_1.norm() > max_trans_acc || a_2.norm() > max_trans_acc)
871 std::cout <<
"Translational acceleration between first trajectory and "
872 "blend trajectory exceeds the limit."
873 <<
"Actual acceleration (norm): " << a_1.norm() <<
", " << a_1.norm() <<
"; "
874 <<
"Limits: " << max_trans_acc <<
'\n';
878 a_1 = (w_2 - w_1) / duration;
879 a_2 = (w_3 - w_2) / duration;
880 if (a_1.norm() > max_rot_acc || a_2.norm() > max_rot_acc)
882 std::cout <<
"Rotational acceleration between first trajectory and blend "
883 "trajectory exceeds the limit."
884 <<
"Actual acceleration (norm): " << a_1.norm() <<
", " << a_1.norm() <<
"; "
885 <<
"Limits: " << max_rot_acc <<
'\n';
892 if (v_2.norm() > max_trans_velo)
894 std::cout <<
"Translational velocity between blend trajectory and second "
895 "trajectory exceeds the limit."
896 <<
"Actual velocity (norm): " << v_2.norm() <<
"; "
897 <<
"Limits: " << max_trans_velo <<
'\n';
899 if (w_2.norm() > max_rot_velo)
901 std::cout <<
"Rotational velocity between blend trajectory and second "
902 "trajectory exceeds the limit."
903 <<
"Actual velocity (norm): " << w_2.norm() <<
"; "
904 <<
"Limits: " << max_rot_velo <<
'\n';
906 a_1 = (v_2 - v_1) / duration;
907 a_2 = (v_3 - v_2) / duration;
908 if (a_1.norm() > max_trans_acc || a_2.norm() > max_trans_acc)
910 std::cout <<
"Translational acceleration between blend trajectory and "
911 "second trajectory exceeds the limit."
912 <<
"Actual acceleration (norm): " << a_1.norm() <<
", " << a_1.norm() <<
"; "
913 <<
"Limits: " << max_trans_acc <<
'\n';
916 a_1 = (w_2 - w_1) / duration;
917 a_2 = (w_3 - w_2) / duration;
918 if (a_1.norm() > max_rot_acc || a_2.norm() > max_rot_acc)
920 std::cout <<
"Rotational acceleration between blend trajectory and second "
921 "trajectory exceeds the limit."
922 <<
"Actual acceleration (norm): " << a_1.norm() <<
", " << a_1.norm() <<
"; "
923 <<
"Limits: " << max_rot_acc <<
'\n';
935 Eigen::Isometry3d curr_pos(res.
blend_trajectory->getWayPointPtr(i)->getFrameTransform(link_name));
936 if ((curr_pos.translation() - circ_pose.translation()).norm() > r)
938 std::cout <<
"Point " << i <<
" does not lie within blending radius (dist: "
939 << ((curr_pos.translation() - circ_pose.translation()).norm() - r) <<
")." <<
'\n';
947 Eigen::Vector3d& v, Eigen::Vector3d& w)
950 v = (pose_2.translation() - pose_1.translation()) / duration;
955 Eigen::Matrix3d rm_1 = pose_1.linear();
956 Eigen::Matrix3d rm_2 = pose_2.linear();
957 Eigen::Matrix3d rm_dot = (rm_2 - rm_1) / duration;
958 Eigen::Matrix3d w_hat = rm_dot * rm_1.transpose();
965 sensor_msgs::msg::JointState& initialJointState,
966 geometry_msgs::msg::PoseStamped& p1, geometry_msgs::msg::PoseStamped& p2)
971 p1.header.frame_id = frame_id;
972 p1.pose.position.x = 0.25;
973 p1.pose.position.y = 0.3;
974 p1.pose.position.z = 0.65;
975 p1.pose.orientation.x = 0.;
976 p1.pose.orientation.y = 0.;
977 p1.pose.orientation.z = 0.;
978 p1.pose.orientation.w = 1.;
981 p2.pose.position.x -= 0.15;
986 ori1 = Eigen::AngleAxisd(0.2 * M_PI, Eigen::Vector3d::UnitZ());
987 ori2 = Eigen::AngleAxisd(0.4 * M_PI, Eigen::Vector3d::UnitZ());
991 moveit_msgs::msg::RobotTrajectory& fake_traj)
993 fake_traj.joint_trajectory.joint_names.push_back(
"x");
994 fake_traj.joint_trajectory.joint_names.push_back(
"y");
995 fake_traj.joint_trajectory.joint_names.push_back(
"z");
1000 for (
size_t i = 0; i < traj->getWayPointCount(); ++i)
1002 trajectory_msgs::msg::JointTrajectoryPoint waypoint;
1003 waypoint.time_from_start = rclcpp::Duration::from_seconds(traj->getWayPointDurationFromStart(i));
1004 Eigen::Isometry3d waypoint_pose = traj->getWayPointPtr(i)->getFrameTransform(link_name);
1005 Eigen::Vector3d waypoint_position = waypoint_pose.translation();
1006 waypoint.positions.push_back(waypoint_position(0));
1007 waypoint.positions.push_back(waypoint_position(1));
1008 waypoint.positions.push_back(waypoint_position(2));
1009 waypoint.velocities.push_back(0);
1010 waypoint.velocities.push_back(0);
1011 waypoint.velocities.push_back(0);
1012 waypoint.accelerations.push_back(0);
1013 waypoint.accelerations.push_back(0);
1014 waypoint.accelerations.push_back(0);
1015 fake_traj.joint_trajectory.points.push_back(waypoint);
1020 const std::string& name_prefix, std::vector<testutils::BlendTestData>& datasets)
1024 auto get_parameter = [&](
const std::string& name, std::vector<double>& parameter,
1025 const rclcpp::Node::SharedPtr& node) {
1026 if (node->has_parameter(name))
1028 node->get_parameter<std::vector<double>>(name, parameter);
1035 for (
size_t i = 1; i < dataset_num + 1; ++i)
1037 std::string data_set_name =
"blend_set_" + std::to_string(i);
1038 if (get_parameter(name_prefix + data_set_name +
"/start_position", dataset.
start_position, node) &&
1039 get_parameter(name_prefix + data_set_name +
"/mid_position", dataset.
mid_position, node) &&
1040 get_parameter(name_prefix + data_set_name +
"/end_position", dataset.
end_position, node))
1042 datasets.push_back(dataset);
1053 const planning_scene::PlanningSceneConstPtr& scene,
1054 const std::shared_ptr<pilz_industrial_motion_planner::TrajectoryGenerator>& tg,
const std::string& group_name,
1055 const std::string& link_name,
const testutils::BlendTestData& data,
double sampling_time_1,
double sampling_time_2,
1059 const moveit::core::RobotModelConstPtr robot_model = scene->getRobotModel();
1063 req_1.group_name = group_name;
1064 req_1.max_velocity_scaling_factor = 0.1;
1065 req_1.max_acceleration_scaling_factor = 0.1;
1076 goal_state_1, goal_state_1.
getRobotModel()->getJointModelGroup(group_name)));
1079 tg->generate(scene, req_1, res_1, sampling_time_1);
1080 if (res_1.
error_code.val != moveit_msgs::msg::MoveItErrorCodes::SUCCESS)
1082 std::cout <<
"Failed to generate first trajectory." <<
'\n';
1088 req_2.group_name = group_name;
1089 req_2.max_velocity_scaling_factor = 0.1;
1090 req_2.max_acceleration_scaling_factor = 0.1;
1098 goal_state_2, goal_state_2.
getRobotModel()->getJointModelGroup(group_name)));
1100 tg->generate(scene, req_2, res_2, sampling_time_2);
1101 if (res_2.
error_code.val != moveit_msgs::msg::MoveItErrorCodes::SUCCESS)
1103 std::cout <<
"Failed to generate second trajectory." <<
'\n';
1122 double joint_velocity_tolerance,
double joint_acceleration_tolerance,
1129 moveit_msgs::msg::RobotTrajectory traj_msg;
1148 Eigen::Isometry3d circ_pose =
1201 const std::string& group_name,
const std::string& link_name,
1202 moveit_msgs::msg::MotionSequenceRequest& req_list)
1206 req_1.planner_id = planner_id;
1207 req_1.group_name = group_name;
1208 req_1.max_velocity_scaling_factor = 0.1;
1209 req_1.max_acceleration_scaling_factor = 0.1;
1220 goal_state_1, goal_state_1.
getRobotModel()->getJointModelGroup(group_name)));
1224 req_2.planner_id = planner_id;
1225 req_2.group_name = group_name;
1226 req_2.max_velocity_scaling_factor = 0.1;
1227 req_2.max_acceleration_scaling_factor = 0.1;
1236 goal_state_2, goal_state_2.
getRobotModel()->getJointModelGroup(group_name)));
1248 double blend_radius = 0.5 * std::min(dis_1, dis_2);
1250 moveit_msgs::msg::MotionSequenceItem blend_req_1, blend_req_2;
1251 blend_req_1.req = req_1;
1252 blend_req_1.blend_radius = blend_radius;
1253 blend_req_2.req = req_2;
1254 blend_req_2.blend_radius = 0.0;
1256 req_list.items.push_back(blend_req_1);
1257 req_list.items.push_back(blend_req_2);
1261 const std::string& link_name)
1263 ASSERT_TRUE(robot_model !=
nullptr) <<
"failed to load robot model";
1264 ASSERT_FALSE(robot_model->isEmpty()) <<
"robot model is empty";
1265 ASSERT_TRUE(robot_model->hasJointModelGroup(group_name)) << group_name <<
" is not known to robot";
1266 ASSERT_TRUE(robot_model->hasLinkModel(link_name)) << link_name <<
" is not known to robot";
1268 <<
"Transform of " << link_name <<
" is unknown";
1276 return ::testing::AssertionFailure() <<
"Cannot be a trapezoid since "
1277 "acceleration is not monotonously "
1282 double first_acc = accelerations.front();
1283 auto it_last_acc = std::find_if(accelerations.begin(), accelerations.end(),
1284 [first_acc, acc_tol](
double el) { return (std::abs(el - first_acc) > acc_tol); }) -
1287 auto it_last_intermediate =
1288 std::find_if(it_last_acc + 1, accelerations.end(), [acc_tol](
double el) { return (el < acc_tol); }) - 1;
1291 auto n_intermediate_1 = std::distance(it_last_acc, it_last_intermediate);
1293 if (n_intermediate_1 != 1 && n_intermediate_1 != 2)
1295 return ::testing::AssertionFailure() <<
"Expected 1 or 2 intermediate points between acceleration and "
1297 "velocity phase but found: "
1298 << n_intermediate_1;
1302 auto it_first_const = it_last_intermediate + 1;
1303 auto it_last_const =
1304 std::find_if(it_first_const, accelerations.end(), [acc_tol](
double el) { return (std::abs(el) > acc_tol); }) - 1;
1307 if (std::distance(it_first_const, it_last_const) < 3)
1309 return ::testing::AssertionFailure() <<
"Expected the have at least 3 points during the phase of "
1315 double deceleration = accelerations.back();
1317 std::find_if(it_last_const + 1, accelerations.end(),
1318 [deceleration, acc_tol](
double el) { return (std::abs(el - deceleration) > acc_tol); }) +
1322 auto n_intermediate_2 = std::distance(it_last_const, it_first_dec);
1323 if (n_intermediate_2 != 1 && n_intermediate_2 != 2)
1325 return ::testing::AssertionFailure() <<
"Expected 1 or 2 intermediate points between constant velocity "
1327 "deceleration phase but found: "
1328 << n_intermediate_2;
1331 std::stringstream debug_stream;
1332 for (
auto it = accelerations.begin(); it != it_last_acc + 1; ++it)
1334 debug_stream << *it <<
"(Acc)" <<
'\n';
1337 for (
auto it = it_last_acc + 1; it != it_last_intermediate + 1; ++it)
1339 debug_stream << *it <<
"(Inter1)" <<
'\n';
1342 for (
auto it = it_first_const; it != it_last_const + 1; ++it)
1344 debug_stream << *it <<
"(Const)" <<
'\n';
1347 for (
auto it = it_last_const + 1; it != it_first_dec; ++it)
1349 debug_stream << *it <<
"(Inter2)" <<
'\n';
1352 for (
auto it = it_first_dec; it != accelerations.end(); ++it)
1354 debug_stream << *it <<
"(Dec)" <<
'\n';
1357 RCLCPP_DEBUG_STREAM(LOGGER, debug_stream.str());
1359 return ::testing::AssertionSuccess();
1362::testing::AssertionResult
1364 const std::string& link_name,
const double acc_tol)
1368 EXPECT_GT(trajectory->getWayPointCount(), 9u);
1370 std::vector<double> accelerations;
1373 for (
size_t i = 2; i < trajectory->getWayPointCount(); ++i)
1375 auto waypoint_pose_0 = trajectory->getWayPoint(i - 2).getFrameTransform(link_name);
1376 auto waypoint_pose_1 = trajectory->getWayPoint(i - 1).getFrameTransform(link_name);
1377 auto waypoint_pose_2 = trajectory->getWayPoint(i).getFrameTransform(link_name);
1379 auto t1 = trajectory->getWayPointDurationFromPrevious(i - 1);
1380 auto t2 = trajectory->getWayPointDurationFromPrevious(i);
1382 auto vel1 = (waypoint_pose_1.translation() - waypoint_pose_0.translation()).norm() / t1;
1383 auto vel2 = (waypoint_pose_2.translation() - waypoint_pose_1.translation()).norm() / t2;
1384 auto acc_transl = (vel2 - vel1) / (t1 + t2);
1385 accelerations.push_back(acc_transl);
1391::testing::AssertionResult
1393 const std::string& link_name,
const double rot_axis_tol,
const double acc_tol)
1396 if (trajectory->getFirstWayPoint().getFrameTransform(link_name).rotation().isApprox(
1397 trajectory->getLastWayPoint().getFrameTransform(link_name).rotation(), rot_axis_tol))
1399 return ::testing::AssertionSuccess();
1404 EXPECT_GT(trajectory->getWayPointCount(), 9u);
1406 std::vector<double> accelerations;
1407 std::vector<Eigen::AngleAxisd> rotation_axes;
1410 for (
size_t i = 2; i < trajectory->getWayPointCount(); ++i)
1412 auto waypoint_pose_0 = trajectory->getWayPoint(i - 2).getFrameTransform(link_name);
1413 auto waypoint_pose_1 = trajectory->getWayPoint(i - 1).getFrameTransform(link_name);
1414 auto waypoint_pose_2 = trajectory->getWayPoint(i).getFrameTransform(link_name);
1416 auto t1 = trajectory->getWayPointDurationFromPrevious(i - 1);
1417 auto t2 = trajectory->getWayPointDurationFromPrevious(i);
1419 Eigen::Quaterniond orientation0(waypoint_pose_0.rotation());
1420 Eigen::Quaterniond orientation1(waypoint_pose_1.rotation());
1421 Eigen::Quaterniond orientation2(waypoint_pose_2.rotation());
1423 Eigen::AngleAxisd axis1(orientation0 * orientation1.inverse());
1424 Eigen::AngleAxisd axis2(orientation1 * orientation2.inverse());
1427 rotation_axes.push_back(axis1);
1429 rotation_axes.push_back(axis2);
1431 double angular_vel1 = axis1.angle() / t1;
1432 double angular_vel2 = axis2.angle() / t2;
1433 double angular_acc = (angular_vel2 - angular_vel1) / (t1 + t2);
1434 accelerations.push_back(angular_acc);
1438 if (std::adjacent_find(rotation_axes.begin(), rotation_axes.end(),
1439 [rot_axis_tol](
const Eigen::AngleAxisd& axis1,
const Eigen::AngleAxisd& axis2) {
1440 return ((axis1.axis() - axis2.axis()).norm() > rot_axis_tol);
1441 }) != rotation_axes.end())
1443 return ::testing::AssertionFailure() <<
"Rotational path of trajectory "
1444 "does not have a fixed rotation "
Representation of a robot's state. This includes position, velocity, acceleration and effort.
void setVariablePositions(const double *position)
It is assumed positions is an array containing the new positions for all variables in this state....
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...
const RobotModelConstPtr & getRobotModel() const
Get the robot model this state is constructed for.
const Eigen::Isometry3d & getFrameTransform(const std::string &frame_id, bool *frame_found=nullptr)
Get the transformation matrix from the model frame (root of model) to the frame identified by frame_i...
void update(bool force=false)
Update all transforms.
void setToDefaultValues()
Set all joints to their default positions. The default position is 0, or if that is not within bounds...
bool knowsFrameTransform(const std::string &frame_id) const
Check if a transformation matrix from the model frame (root of model) to frame frame_id is known.
Container for JointLimits, essentially a map with convenience functions. Adds the ability to as for l...
bool addLimit(const std::string &joint_name, JointLimit joint_limit)
Add a limit.
This class combines CartesianLimit and JointLimits into on single class.
const cartesian_limits::Params & getCartesianLimits() const
Return the cartesian limits.
const JointLimitsContainer & getJointLimitContainer() const
Obtain the Joint Limits from the container.
moveit_msgs::msg::Constraints constructGoalConstraints(const moveit::core::RobotState &state, const moveit::core::JointModelGroup *jmg, double tolerance_below, double tolerance_above)
Generates a constraint message intended to be used as a goal constraint for a joint group....
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.
bool jointStateToRobotState(const sensor_msgs::msg::JointState &joint_state, RobotState &state)
Convert a joint state to a MoveIt robot state.
moveit_msgs::msg::MotionPlanRequest MotionPlanRequest
bool checkBlendingCartSpaceContinuity(const pilz_industrial_motion_planner::TrajectoryBlendRequest &req, const pilz_industrial_motion_planner::TrajectoryBlendResponse &res, const pilz_industrial_motion_planner::LimitsContainer &planner_limits)
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.
bool computeLinkFK(const moveit::core::RobotModelConstPtr &robot_model, const std::string &link_name, const std::map< std::string, double > &joint_state, Eigen::Isometry3d &pose)
computeLinkFK
sensor_msgs::msg::JointState generateJointState(const std::vector< double > &pos, const std::vector< double > &vel, const std::string &joint_prefix=testutils::JOINT_NAME_PREFIX)
::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 isVelocityBounded(const trajectory_msgs::msg::JointTrajectory &trajectory, const pilz_industrial_motion_planner::JointLimitsContainer &joint_limits)
is Velocity Bounded
void createDummyRequest(const moveit::core::RobotModelConstPtr &robot_model, const std::string &planning_group, planning_interface::MotionPlanRequest &req)
create a dummy motion plan request with zero start state No goal constraint is given.
bool getExpectedGoalPose(const moveit::core::RobotModelConstPtr &robot_model, const planning_interface::MotionPlanRequest &req, std::string &link_name, Eigen::Isometry3d &goal_pose_expect)
Determines the goal position from the given request. TRUE if successful, FALSE otherwise.
bool isAccelerationBounded(const trajectory_msgs::msg::JointTrajectory &trajectory, const pilz_industrial_motion_planner::JointLimitsContainer &joint_limits)
is Acceleration Bounded
bool checkThatPointsInRadius(const std::string &link_name, double r, Eigen::Isometry3d &circ_pose, const pilz_industrial_motion_planner::TrajectoryBlendResponse &res)
Checks if all points of the blending trajectory lie within the blending radius.
void generateRequestMsgFromBlendTestData(const moveit::core::RobotModelConstPtr &robot_model, const BlendTestData &data, const std::string &planner_id, const std::string &group_name, const std::string &link_name, moveit_msgs::msg::MotionSequenceRequest &req_list)
bool isMonotonouslyDecreasing(const std::vector< double > &vec, double tol)
bool isTrajectoryConsistent(const trajectory_msgs::msg::JointTrajectory &trajectory)
check if the sizes of the joint position/veloicty/acceleration are correct
void createFakeCartTraj(const robot_trajectory::RobotTrajectoryPtr &traj, const std::string &link_name, moveit_msgs::msg::RobotTrajectory &fake_traj)
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
bool getBlendTestData(const rclcpp::Node::SharedPtr &node, const size_t &dataset_num, const std::string &name_prefix, std::vector< BlendTestData > &datasets)
fetch test datasets from node parameters
pilz_industrial_motion_planner::JointLimitsContainer createFakeLimits(const std::vector< std::string > &joint_names)
Create limits for tests to avoid the need to get the limits from the node parameter.
bool checkSLERP(const Eigen::Isometry3d &start_pose, const Eigen::Isometry3d &goal_pose, const Eigen::Isometry3d &wp_pose, const double rot_axis_norm_tolerance, const double rot_angle_tolerance=10e-5)
check SLERP. The orientation should rotate around the same axis linearly.
::testing::AssertionResult hasStrictlyIncreasingTime(const robot_trajectory::RobotTrajectoryPtr &trajectory)
Checks that every waypoint in the trajectory has a non-zero duration between itself and its predecess...
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
std::string getJointName(size_t joint_number, const std::string &joint_prefix)
void computeCartVelocity(const Eigen::Isometry3d &pose_1, const Eigen::Isometry3d &pose_2, double duration, Eigen::Vector3d &v, Eigen::Vector3d &w)
compute Cartesian velocity
bool generateTrajFromBlendTestData(const planning_scene::PlanningSceneConstPtr &scene, const std::shared_ptr< pilz_industrial_motion_planner::TrajectoryGenerator > &tg, const std::string &group_name, const std::string &link_name, const BlendTestData &data, double sampling_time_1, double sampling_time_2, planning_interface::MotionPlanResponse &res_lin_1, planning_interface::MotionPlanResponse &res_lin_2, double &dis_lin_1, double &dis_lin_2)
generate two LIN trajectories from test data set
void getOriChange(Eigen::Matrix3d &ori1, Eigen::Matrix3d &ori2)
bool toTCPPose(const moveit::core::RobotModelConstPtr &robot_model, const std::string &link_name, const std::vector< double > &joint_values, geometry_msgs::msg::Pose &pose, const std::string &joint_prefix=testutils::JOINT_NAME_PREFIX)
compute the tcp pose from joint values
void getLinLinPosesWithoutOriChange(const std::string &frame_id, sensor_msgs::msg::JointState &initialJointState, geometry_msgs::msg::PoseStamped &p1, geometry_msgs::msg::PoseStamped &p2)
Returns an initial joint state and two poses which can be used to perform a Lin-Lin movement.
bool checkCartesianLinearity(const moveit::core::RobotModelConstPtr &robot_model, const trajectory_msgs::msg::JointTrajectory &trajectory, const planning_interface::MotionPlanRequest &req, const double translation_norm_tolerance, const double rot_axis_norm_tolerance, const double rot_angle_tolerance=10e-5)
Check that given trajectory is straight line.
bool isPositionBounded(const trajectory_msgs::msg::JointTrajectory &trajectory, const pilz_industrial_motion_planner::JointLimitsContainer &joint_limits)
is Position Bounded
::testing::AssertionResult hasTrapezoidVelocity(std::vector< double > accelerations, const double acc_tol)
Check that a given vector of accelerations represents a trapezoid velocity profile.
bool checkOriginalTrajectoryAfterBlending(const pilz_industrial_motion_planner::TrajectoryBlendRequest &req, const pilz_industrial_motion_planner::TrajectoryBlendResponse &res, const double time_tolerance)
checkOriginalTrajectoryAfterBlending
bool checkBlendingJointSpaceContinuity(const pilz_industrial_motion_planner::TrajectoryBlendResponse &res, double joint_velocity_tolerance, double joint_accleration_tolerance)
check the blending result, if the joint space continuity is fulfilled
void createPTPRequest(const std::string &planning_group, const moveit::core::RobotState &start_state, const moveit::core::RobotState &goal_state, planning_interface::MotionPlanRequest &req)
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.
bool has_acceleration_limits
robot_trajectory::RobotTrajectoryPtr second_trajectory
robot_trajectory::RobotTrajectoryPtr first_trajectory
robot_trajectory::RobotTrajectoryPtr first_trajectory
robot_trajectory::RobotTrajectoryPtr blend_trajectory
robot_trajectory::RobotTrajectoryPtr second_trajectory
Extends joint_limits_interface::JointLimits with a deceleration parameter.
bool has_deceleration_limits
double max_deceleration
maximum deceleration MUST(!) be negative
Response to a planning query.
moveit::core::MoveItErrorCode error_code
Test data for blending, which contains three joint position vectors of three robot state.
std::vector< double > end_position
std::vector< double > start_position
std::vector< double > mid_position
void normalizeQuaternion(geometry_msgs::msg::Quaternion &quat)