37#include <gtest/gtest.h>
38#ifndef INSTANTIATE_TEST_SUITE_P
39#define INSTANTIATE_TEST_SUITE_P(...) INSTANTIATE_TEST_CASE_P(__VA_ARGS__)
41#ifndef TYPED_TEST_SUITE
42#define TYPED_TEST_SUITE(...) TYPED_TEST_CASE(__VA_ARGS__)
45#include <moveit_msgs/msg/motion_sequence_request.hpp>
50#include <boost/core/demangle.hpp>
55#include <moveit_msgs/msg/constraints.hpp>
56#include <moveit_msgs/action/move_group.hpp>
57#include <sensor_msgs/msg/joint_state.hpp>
59#include <tf2/LinearMath/Quaternion.h>
60#include <tf2/convert.h>
61#include <tf2_geometry_msgs/tf2_geometry_msgs.hpp>
68static constexpr int32_t DEFAULT_SERVICE_TIMEOUT(10);
69static constexpr double DEFAULT_ACCELERATION_EQUALITY_TOLERANCE{ 1e-6 };
70static constexpr double DEFAULT_ROTATION_AXIS_EQUALITY_TOLERANCE{ 1e-8 };
75static inline constexpr double deg2Rad(
double angle)
77 return (angle / 180.0) * M_PI;
80inline std::string
getJointName(
size_t joint_number,
const std::string& joint_prefix)
82 return joint_prefix + std::to_string(joint_number);
93 return boost::core::demangle(name);
100inline sensor_msgs::msg::JointState
generateJointState(
const std::vector<double>& pos,
const std::vector<double>& vel,
103 sensor_msgs::msg::JointState state;
104 auto posit = pos.cbegin();
107 while (posit != pos.cend())
110 state.position.push_back(*posit);
115 for (
const auto& one_vel : vel)
117 state.velocity.push_back(one_vel);
128inline moveit_msgs::msg::Constraints
132 moveit_msgs::msg::Constraints gc;
134 auto pos_it = pos_list.begin();
136 for (
size_t i = 0; i < pos_list.size(); ++i)
138 moveit_msgs::msg::JointConstraint jc;
140 jc.position = *pos_it;
141 gc.joint_constraints.push_back(jc);
155 Eigen::Isometry3d& goal_pose_expect);
164void createDummyRequest(
const moveit::core::RobotModelConstPtr& robot_model,
const std::string& planning_group,
179bool isGoalReached(
const trajectory_msgs::msg::JointTrajectory& trajectory,
180 const std::vector<moveit_msgs::msg::JointConstraint>& goal,
const double joint_position_tolerance,
181 const double joint_velocity_tolerance = 1.0e-6);
193bool isGoalReached(
const moveit::core::RobotModelConstPtr& robot_model,
194 const trajectory_msgs::msg::JointTrajectory& trajectory,
196 const double orientation_tolerance);
198bool isGoalReached(
const moveit::core::RobotModelConstPtr& robot_model,
199 const trajectory_msgs::msg::JointTrajectory& trajectory,
206 const trajectory_msgs::msg::JointTrajectory& trajectory,
208 const double rot_axis_norm_tolerance,
const double rot_angle_tolerance = 10e-5);
219bool checkSLERP(
const Eigen::Isometry3d& start_pose,
const Eigen::Isometry3d& goal_pose,
220 const Eigen::Isometry3d& wp_pose,
const double rot_axis_norm_tolerance,
221 const double rot_angle_tolerance = 10e-5);
229inline int getWayPointIndex(
const robot_trajectory::RobotTrajectoryPtr& trajectory,
const double time_from_start)
231 int index_before, index_after;
233 trajectory->findWayPointIndicesForDurationAfterStart(time_from_start, index_before, index_after, blend);
234 return blend > 0.5 ? index_after : index_before;
256::testing::AssertionResult hasStrictlyIncreasingTime(
const robot_trajectory::RobotTrajectoryPtr& trajectory);
302bool toTCPPose(
const moveit::core::RobotModelConstPtr& robot_model,
const std::string& link_name,
303 const std::vector<double>& joint_values, geometry_msgs::msg::Pose& pose,
314bool computeLinkFK(
const moveit::core::RobotModelConstPtr& robot_model,
const std::string& link_name,
315 const std::map<std::string, double>& joint_state, Eigen::Isometry3d& pose);
327 const double time_tolerance);
337 double joint_velocity_tolerance,
double joint_accleration_tolerance);
358void computeCartVelocity(
const Eigen::Isometry3d& pose_1,
const Eigen::Isometry3d& pose_2,
double duration,
359 Eigen::Vector3d& v, Eigen::Vector3d& w);
371 geometry_msgs::msg::PoseStamped& p1, geometry_msgs::msg::PoseStamped& p2);
373void getOriChange(Eigen::Matrix3d& ori1, Eigen::Matrix3d& ori2);
375void createFakeCartTraj(
const robot_trajectory::RobotTrajectoryPtr& traj,
const std::string& link_name,
376 moveit_msgs::msg::RobotTrajectory& fake_traj);
378inline geometry_msgs::msg::Quaternion
fromEuler(
double a,
double b,
double c)
380 tf2::Vector3 qvz(0., 0., 1.);
381 tf2::Vector3 qvy(0., 1., 0.);
382 tf2::Quaternion q1(qvz, a);
384 q1 = q1 * tf2::Quaternion(qvy, b);
385 q1 = q1 * tf2::Quaternion(qvz, c);
387 return tf2::toMsg(q1);
406bool getBlendTestData(
const rclcpp::Node::SharedPtr& node,
const size_t& dataset_num,
const std::string& name_prefix,
407 std::vector<BlendTestData>& datasets);
420 double joint_acceleration_tolerance,
double cartesian_velocity_tolerance,
421 double cartesian_angular_velocity_tolerance);
435 const std::shared_ptr<pilz_industrial_motion_planner::TrajectoryGenerator>& tg,
436 const std::string& group_name,
const std::string& link_name,
437 const BlendTestData& data,
double sampling_time_1,
double sampling_time_2,
443 const std::string& planner_id,
const std::string& group_name,
444 const std::string& link_name,
445 moveit_msgs::msg::MotionSequenceRequest& req_list);
447void checkRobotModel(
const moveit::core::RobotModelConstPtr& robot_model,
const std::string& group_name,
448 const std::string& link_name);
454::testing::AssertionResult
hasTrapezoidVelocity(std::vector<double> accelerations,
const double acc_tol);
461::testing::AssertionResult
463 const std::string& link_name,
464 const double acc_tol = DEFAULT_ACCELERATION_EQUALITY_TOLERANCE);
472::testing::AssertionResult
474 const double rot_axis_tol = DEFAULT_ROTATION_AXIS_EQUALITY_TOLERANCE,
475 const double acc_tol = DEFAULT_ACCELERATION_EQUALITY_TOLERANCE);
479 return std::is_sorted(vec.begin(), vec.end(), [tol](
double a,
double b) {
480 return std::abs(a - b) >= tol && a >= b;
Representation of a robot's state. This includes position, velocity, acceleration and effort.
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.
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)
std::string demangle(const char *name)
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.
int getWayPointIndex(const robot_trajectory::RobotTrajectoryPtr &trajectory, const double time_from_start)
get the waypoint index from time from start
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)
moveit_msgs::msg::Constraints generateJointConstraint(const std::vector< double > &pos_list, const std::string &joint_prefix=testutils::JOINT_NAME_PREFIX)
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.
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
geometry_msgs::msg::Quaternion fromEuler(double a, double b, double c)
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.
const std::string JOINT_NAME_PREFIX("prbt_joint_")
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.
Response to a planning query.
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