|
moveit2
The MoveIt Motion Planning Framework for ROS 2.
|
Classes | |
| struct | BlendTestData |
| Test data for blending, which contains three joint position vectors of three robot state. More... | |
Functions | |
| const std::string | JOINT_NAME_PREFIX ("prbt_joint_") |
| std::string | getJointName (size_t joint_number, const std::string &joint_prefix) |
| 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. More... | |
| std::string | demangle (const char *name) |
| sensor_msgs::msg::JointState | generateJointState (const std::vector< double > &pos, const std::vector< double > &vel, const std::string &joint_prefix=testutils::JOINT_NAME_PREFIX) |
| sensor_msgs::msg::JointState | generateJointState (const std::vector< double > &pos, const std::string &joint_prefix=testutils::JOINT_NAME_PREFIX) |
| moveit_msgs::msg::Constraints | generateJointConstraint (const std::vector< double > &pos_list, const std::string &joint_prefix=testutils::JOINT_NAME_PREFIX) |
| 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. More... | |
| 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. More... | |
| void | createPTPRequest (const std::string &planning_group, const moveit::core::RobotState &start_state, const moveit::core::RobotState &goal_state, planning_interface::MotionPlanRequest &req) |
| 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. More... | |
| bool | isGoalReached (const moveit::core::RobotModelConstPtr &robot_model, const trajectory_msgs::msg::JointTrajectory &trajectory, const planning_interface::MotionPlanRequest &req, const double pos_tolerance, const double orientation_tolerance) |
| check if the goal given in cartesian space is reached Only the last point in the trajectory is verified. More... | |
| bool | isGoalReached (const moveit::core::RobotModelConstPtr &robot_model, const trajectory_msgs::msg::JointTrajectory &trajectory, const planning_interface::MotionPlanRequest &req, const double tolerance) |
| 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. More... | |
| 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. More... | |
| int | getWayPointIndex (const robot_trajectory::RobotTrajectoryPtr &trajectory, const double time_from_start) |
| get the waypoint index from time from start More... | |
| 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 More... | |
| ::testing::AssertionResult | hasStrictlyIncreasingTime (const robot_trajectory::RobotTrajectoryPtr &trajectory) |
| Checks that every waypoint in the trajectory has a non-zero duration between itself and its predecessor. More... | |
| bool | isTrajectoryConsistent (const trajectory_msgs::msg::JointTrajectory &trajectory) |
| check if the sizes of the joint position/veloicty/acceleration are correct More... | |
| bool | isPositionBounded (const trajectory_msgs::msg::JointTrajectory &trajectory, const pilz_industrial_motion_planner::JointLimitsContainer &joint_limits) |
| is Position Bounded More... | |
| bool | isVelocityBounded (const trajectory_msgs::msg::JointTrajectory &trajectory, const pilz_industrial_motion_planner::JointLimitsContainer &joint_limits) |
| is Velocity Bounded More... | |
| bool | isAccelerationBounded (const trajectory_msgs::msg::JointTrajectory &trajectory, const pilz_industrial_motion_planner::JointLimitsContainer &joint_limits) |
| is Acceleration Bounded More... | |
| 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 More... | |
| 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 More... | |
| bool | checkOriginalTrajectoryAfterBlending (const pilz_industrial_motion_planner::TrajectoryBlendRequest &req, const pilz_industrial_motion_planner::TrajectoryBlendResponse &res, const double time_tolerance) |
| checkOriginalTrajectoryAfterBlending More... | |
| 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 More... | |
| 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 | 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. More... | |
| void | computeCartVelocity (const Eigen::Isometry3d &pose_1, const Eigen::Isometry3d &pose_2, double duration, Eigen::Vector3d &v, Eigen::Vector3d &w) |
| compute Cartesian velocity More... | |
| 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. More... | |
| void | getOriChange (Eigen::Matrix3d &ori1, Eigen::Matrix3d &ori2) |
| void | createFakeCartTraj (const robot_trajectory::RobotTrajectoryPtr &traj, const std::string &link_name, moveit_msgs::msg::RobotTrajectory &fake_traj) |
| geometry_msgs::msg::Quaternion | fromEuler (double a, double b, double c) |
| 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 More... | |
| 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 More... | |
| 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 More... | |
| 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) |
| void | checkRobotModel (const moveit::core::RobotModelConstPtr &robot_model, const std::string &group_name, const std::string &link_name) |
| ::testing::AssertionResult | hasTrapezoidVelocity (std::vector< double > accelerations, const double acc_tol) |
| Check that a given vector of accelerations represents a trapezoid velocity profile. More... | |
| ::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. More... | |
| ::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. More... | |
| bool | isMonotonouslyDecreasing (const std::vector< double > &vec, double tol) |
| bool testutils::checkBlendingCartSpaceContinuity | ( | const pilz_industrial_motion_planner::TrajectoryBlendRequest & | req, |
| const pilz_industrial_motion_planner::TrajectoryBlendResponse & | res, | ||
| const pilz_industrial_motion_planner::LimitsContainer & | planner_limits | ||
| ) |
Definition at line 775 of file test_utils.cpp.


| bool testutils::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
| res | trajectory blending response, contains three trajectories. Between these three trajectories should be continuous. |
Definition at line 671 of file test_utils.cpp.

| bool testutils::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
| lin_res_1 | |
| lin_res_2 | |
| blend_req | |
| blend_res | |
| checkAcceleration |
Definition at line 1119 of file test_utils.cpp.


| bool testutils::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.
Definition at line 222 of file test_utils.cpp.


| testing::AssertionResult testutils::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.
| rot_axis_tol | tolerance for comparing rotation axes (in the L2 norm) |
| acc_tol | tolerance for comparing angular acceleration values |
Definition at line 1392 of file test_utils.cpp.


| testing::AssertionResult testutils::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.
| acc_tol | tolerance for comparing acceleration values |
Definition at line 1363 of file test_utils.cpp.


| bool testutils::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
| trajectory | |
| joint_limits |
Definition at line 460 of file test_utils.cpp.


| bool testutils::checkOriginalTrajectoryAfterBlending | ( | const pilz_industrial_motion_planner::TrajectoryBlendRequest & | req, |
| const pilz_industrial_motion_planner::TrajectoryBlendResponse & | res, | ||
| const double | time_tolerance | ||
| ) |
checkOriginalTrajectoryAfterBlending
| blend_res | |
| traj_1_res | |
| traj_2_res | |
| time_tolerance |
Definition at line 561 of file test_utils.cpp.

| void testutils::checkRobotModel | ( | const moveit::core::RobotModelConstPtr & | robot_model, |
| const std::string & | group_name, | ||
| const std::string & | link_name | ||
| ) |
| bool testutils::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.
| start_pose | |
| goal_pose | |
| wp_pose | |
| rot_axis_norm_tolerance |
Definition at line 292 of file test_utils.cpp.

| bool testutils::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.
Definition at line 929 of file test_utils.cpp.

| void testutils::computeCartVelocity | ( | const Eigen::Isometry3d & | pose_1, |
| const Eigen::Isometry3d & | pose_2, | ||
| double | duration, | ||
| Eigen::Vector3d & | v, | ||
| Eigen::Vector3d & | w | ||
| ) |
compute Cartesian velocity
| pose_1 | |
| pose_2 | |
| duration | |
| v | |
| w |
Definition at line 946 of file test_utils.cpp.

| bool testutils::computeLinkFK | ( | const moveit::core::RobotModelConstPtr & | robot_model, |
| const std::string & | link_name, | ||
| const std::map< std::string, double > & | joint_state, | ||
| Eigen::Isometry3d & | pose | ||
| ) |
computeLinkFK
| robot_model | |
| link_name | |
| joint_state | |
| pose |
Definition at line 321 of file test_utils.cpp.


| void testutils::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.
| robot_model | |
| planning_group | |
| req |
Definition at line 504 of file test_utils.cpp.


| void testutils::createFakeCartTraj | ( | const robot_trajectory::RobotTrajectoryPtr & | traj, |
| const std::string & | link_name, | ||
| moveit_msgs::msg::RobotTrajectory & | fake_traj | ||
| ) |
Definition at line 990 of file test_utils.cpp.
| pilz_industrial_motion_planner::JointLimitsContainer testutils::createFakeLimits | ( | const std::vector< std::string > & | joint_names | ) |
Create limits for tests to avoid the need to get the limits from the node parameter.
Definition at line 48 of file test_utils.cpp.


| void testutils::createPTPRequest | ( | const std::string & | planning_group, |
| const moveit::core::RobotState & | start_state, | ||
| const moveit::core::RobotState & | goal_state, | ||
| planning_interface::MotionPlanRequest & | req | ||
| ) |
|
inline |
|
inline |
Definition at line 387 of file test_utils.hpp.
|
inline |
|
inline |
|
inline |
Definition at line 109 of file test_utils.hpp.


| void testutils::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 testutils::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
| data | contains joint poisitons of start/mid/end states | |
| sampling_time_1 | sampling time for first LIN | |
| sampling_time_2 | sampling time for second LIN | |
| [out] | res_lin_1 | result of the first LIN motion planning |
| [out] | res_lin_2 | result of the second LIN motion planning |
| [out] | dis_lin_1 | translational distance of the first LIN |
| [out] | dis_lin_2 | translational distance of the second LIN |
Definition at line 1052 of file test_utils.cpp.

| bool testutils::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
| nh |
| bool testutils::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.
Definition at line 71 of file test_utils.cpp.


|
inline |
| void testutils::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.
| frame_id | |
| initialJointState | As cartesian position: (0.3, 0, 0.65, 0, 0, 0) |
| p1 | (0.05, 0, 0.65, 0, 0, 0) |
| p2 | (0.05, 0.4, 0.65, 0, 0, 0) |
Definition at line 964 of file test_utils.cpp.

| void testutils::getOriChange | ( | Eigen::Matrix3d & | ori1, |
| Eigen::Matrix3d & | ori2 | ||
| ) |
Definition at line 984 of file test_utils.cpp.
|
inline |
get the waypoint index from time from start
| trajectory | |
| time_from_start |
Definition at line 238 of file test_utils.hpp.

| testing::AssertionResult testutils::hasStrictlyIncreasingTime | ( | const robot_trajectory::RobotTrajectoryPtr & | trajectory | ) |
Checks that every waypoint in the trajectory has a non-zero duration between itself and its predecessor.
Usage in tests:
Definition at line 487 of file test_utils.cpp.

| testing::AssertionResult testutils::hasTrapezoidVelocity | ( | std::vector< double > | accelerations, |
| const double | acc_tol | ||
| ) |
Check that a given vector of accelerations represents a trapezoid velocity profile.
| acc_tol | tolerance for comparing acceleration values |
Definition at line 1271 of file test_utils.cpp.


| bool testutils::isAccelerationBounded | ( | const trajectory_msgs::msg::JointTrajectory & | trajectory, |
| const pilz_industrial_motion_planner::JointLimitsContainer & | joint_limits | ||
| ) |
is Acceleration Bounded
| trajectory | |
| joint_limits |
Definition at line 393 of file test_utils.cpp.

| bool testutils::isGoalReached | ( | const moveit::core::RobotModelConstPtr & | robot_model, |
| const trajectory_msgs::msg::JointTrajectory & | trajectory, | ||
| const planning_interface::MotionPlanRequest & | req, | ||
| const double | pos_tolerance, | ||
| const double | orientation_tolerance | ||
| ) |
check if the goal given in cartesian space is reached Only the last point in the trajectory is verified.
| robot_model | |
| trajectory | |
| req | |
| matrix_norm_tolerance | used to compare the transformation matrix |
| joint_velocity_tolerance |
Definition at line 153 of file test_utils.cpp.

| bool testutils::isGoalReached | ( | const moveit::core::RobotModelConstPtr & | robot_model, |
| const trajectory_msgs::msg::JointTrajectory & | trajectory, | ||
| const planning_interface::MotionPlanRequest & | req, | ||
| const double | tolerance | ||
| ) |
| bool testutils::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.
| trajectory | generated trajectory |
| goal | goal in joint space |
| joint_position_tolerance | |
| joint_velocity_tolerance |
Definition at line 118 of file test_utils.cpp.

|
inline |
| bool testutils::isPositionBounded | ( | const trajectory_msgs::msg::JointTrajectory & | trajectory, |
| const pilz_industrial_motion_planner::JointLimitsContainer & | joint_limits | ||
| ) |
is Position Bounded
| trajectory | |
| joint_limits |
Definition at line 435 of file test_utils.cpp.

| bool testutils::isTrajectoryConsistent | ( | const trajectory_msgs::msg::JointTrajectory & | trajectory | ) |
check if the sizes of the joint position/veloicty/acceleration are correct
| trajectory |
Definition at line 376 of file test_utils.cpp.

| bool testutils::isVelocityBounded | ( | const trajectory_msgs::msg::JointTrajectory & | trajectory, |
| const pilz_industrial_motion_planner::JointLimitsContainer & | joint_limits | ||
| ) |
is Velocity Bounded
| trajectory | |
| joint_limits |
Definition at line 353 of file test_utils.cpp.

| const std::string testutils::JOINT_NAME_PREFIX | ( | "prbt_joint_" | ) |
| bool testutils::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
| robot_model | |
| link_name | |
| joint_values | |
| pose | |
| joint_prefix | Prefix of the joint names |
Definition at line 531 of file test_utils.cpp.
