| 
    moveit2
    
   The MoveIt Motion Planning Framework for ROS 2. 
   | 
 
#include <memory>#include <gtest/gtest.h>#include <pilz_industrial_motion_planner/joint_limits_aggregator.h>#include <pilz_industrial_motion_planner/trajectory_generator_lin.h>#include <pilz_industrial_motion_planner_testutils/command_types_typedef.h>#include <pilz_industrial_motion_planner_testutils/xml_testdata_loader.h>#include "test_utils.h"#include <moveit/kinematic_constraints/utils.h>#include <moveit/robot_model/robot_model.h>#include <moveit/robot_model_loader/robot_model_loader.h>#include <moveit/robot_state/conversions.h>#include <moveit/robot_state/robot_state.h>#include <rclcpp/rclcpp.hpp>
Go to the source code of this file.
Classes | |
| class | TrajectoryGeneratorLINTest | 
| Parameterized unittest of trajectory generator LIN to enable tests against different robot models.The parameter is the name of robot model parameter on the ros parameter server.  More... | |
Functions | |
| const std::string | TEST_DATA_FILE_NAME ("testdata_file_name") | 
| const std::string | PARAM_PLANNING_GROUP_NAME ("planning_group") | 
| const std::string | TARGET_LINK_HCD ("target_link_hand_computed_data") | 
| const std::string | RANDOM_TEST_TRIAL_NUM ("random_trial_number") | 
| const std::string | JOINT_POSITION_TOLERANCE ("joint_position_tolerance") | 
| const std::string | JOINT_VELOCITY_TOLERANCE ("joint_velocity_tolerance") | 
| const std::string | POSE_TRANSFORM_MATRIX_NORM_TOLERANCE ("pose_norm_tolerance") | 
| const std::string | ROTATION_AXIS_NORM_TOLERANCE ("rot_axis_norm_tolerance") | 
| const std::string | VELOCITY_SCALING_FACTOR ("velocity_scaling_factor") | 
| const std::string | OTHER_TOLERANCE ("other_tolerance") | 
| TEST_F (TrajectoryGeneratorLINTest, TestExceptionErrorCodeMapping) | |
| Checks that each derived MoveItErrorCodeException contains the correct error code.  More... | |
| TEST_F (TrajectoryGeneratorLINTest, nonZeroStartVelocity) | |
| test the lin planner with invalid motion plan request which has non zero start velocity  More... | |
| TEST_F (TrajectoryGeneratorLINTest, jointSpaceGoal) | |
| test the lin planner with joint space goal  More... | |
| TEST_F (TrajectoryGeneratorLINTest, jointSpaceGoalNearZeroStartVelocity) | |
| test the lin planner with joint space goal with start velocity almost zero  More... | |
| TEST_F (TrajectoryGeneratorLINTest, cartesianSpaceGoal) | |
| test the lin planner with Cartesian goal  More... | |
| TEST_F (TrajectoryGeneratorLINTest, cartesianTrapezoidProfile) | |
| test the trapezoid shape of the planning trajectory in Cartesian space  More... | |
| TEST_F (TrajectoryGeneratorLINTest, LinPlannerLimitViolation) | |
| Check that lin planner returns 'false' if calculated lin trajectory violates velocity/acceleration or deceleration limits.  More... | |
| TEST_F (TrajectoryGeneratorLINTest, LinPlannerDiscontinuousJointTraj) | |
| test joint linear movement with discontinuities in joint space  More... | |
| TEST_F (TrajectoryGeneratorLINTest, LinStartEqualsGoal) | |
| test joint linear movement with equal goal and start  More... | |
| TEST_F (TrajectoryGeneratorLINTest, CtorNoLimits) | |
| Checks that constructor throws an exception if no limits are given.  More... | |
| TEST_F (TrajectoryGeneratorLINTest, IncorrectJointNumber) | |
| Checks that generate() function returns 'false' if called with an incorrect number of joints.  More... | |
| TEST_F (TrajectoryGeneratorLINTest, cartGoalFrameIdBothConstraints) | |
| Set a frame id in goal constraint with cartesian goal on both position and orientation constraints.  More... | |
| int | main (int argc, char **argv) | 
| const std::string JOINT_POSITION_TOLERANCE | ( | "joint_position_tolerance" | ) | 

| const std::string JOINT_VELOCITY_TOLERANCE | ( | "joint_velocity_tolerance" | ) | 

| int main | ( | int | argc, | 
| char ** | argv | ||
| ) | 
Definition at line 447 of file unittest_trajectory_generator_lin.cpp.
| const std::string OTHER_TOLERANCE | ( | "other_tolerance" | ) | 

| const std::string PARAM_PLANNING_GROUP_NAME | ( | "planning_group" | ) | 

| const std::string POSE_TRANSFORM_MATRIX_NORM_TOLERANCE | ( | "pose_norm_tolerance" | ) | 

| const std::string RANDOM_TEST_TRIAL_NUM | ( | "random_trial_number" | ) | 

| const std::string ROTATION_AXIS_NORM_TOLERANCE | ( | "rot_axis_norm_tolerance" | ) | 

| const std::string TARGET_LINK_HCD | ( | "target_link_hand_computed_data" | ) | 

| const std::string TEST_DATA_FILE_NAME | ( | "testdata_file_name" | ) | 

| TEST_F | ( | TrajectoryGeneratorLINTest | , | 
| cartesianSpaceGoal | |||
| ) | 
test the lin planner with Cartesian goal
Definition at line 262 of file unittest_trajectory_generator_lin.cpp.
| TEST_F | ( | TrajectoryGeneratorLINTest | , | 
| cartesianTrapezoidProfile | |||
| ) | 
test the trapezoid shape of the planning trajectory in Cartesian space
The test checks translational path for a trapezoid velocity profile. Due to the way the acceleration is calculated 1 or 2 intermediate points occur that are neither acceleration, constant or deceleration.
+++++++++++++++++++++++
Definition at line 284 of file unittest_trajectory_generator_lin.cpp.

| TEST_F | ( | TrajectoryGeneratorLINTest | , | 
| cartGoalFrameIdBothConstraints | |||
| ) | 
Set a frame id in goal constraint with cartesian goal on both position and orientation constraints.
Definition at line 430 of file unittest_trajectory_generator_lin.cpp.
| TEST_F | ( | TrajectoryGeneratorLINTest | , | 
| CtorNoLimits | |||
| ) | 
Checks that constructor throws an exception if no limits are given.
Test Sequence:
Expected Results:
Definition at line 394 of file unittest_trajectory_generator_lin.cpp.
| TEST_F | ( | TrajectoryGeneratorLINTest | , | 
| IncorrectJointNumber | |||
| ) | 
Checks that generate() function returns 'false' if called with an incorrect number of joints.
Test Sequence:
Expected Results:
Definition at line 412 of file unittest_trajectory_generator_lin.cpp.
| TEST_F | ( | TrajectoryGeneratorLINTest | , | 
| jointSpaceGoal | |||
| ) | 
test the lin planner with joint space goal
Definition at line 225 of file unittest_trajectory_generator_lin.cpp.
| TEST_F | ( | TrajectoryGeneratorLINTest | , | 
| jointSpaceGoalNearZeroStartVelocity | |||
| ) | 
test the lin planner with joint space goal with start velocity almost zero
Definition at line 242 of file unittest_trajectory_generator_lin.cpp.
| TEST_F | ( | TrajectoryGeneratorLINTest | , | 
| LinPlannerDiscontinuousJointTraj | |||
| ) | 
test joint linear movement with discontinuities in joint space
This will violate joint velocity/acceleration limits.
Test Sequence:
Expected Results:
Definition at line 339 of file unittest_trajectory_generator_lin.cpp.

| TEST_F | ( | TrajectoryGeneratorLINTest | , | 
| LinPlannerLimitViolation | |||
| ) | 
Check that lin planner returns 'false' if calculated lin trajectory violates velocity/acceleration or deceleration limits.
Test Sequence:
Expected Results:
Definition at line 319 of file unittest_trajectory_generator_lin.cpp.

| TEST_F | ( | TrajectoryGeneratorLINTest | , | 
| LinStartEqualsGoal | |||
| ) | 
test joint linear movement with equal goal and start
Test Sequence:
Expected Results:
Definition at line 363 of file unittest_trajectory_generator_lin.cpp.

| TEST_F | ( | TrajectoryGeneratorLINTest | , | 
| nonZeroStartVelocity | |||
| ) | 
test the lin planner with invalid motion plan request which has non zero start velocity
Definition at line 209 of file unittest_trajectory_generator_lin.cpp.
| TEST_F | ( | TrajectoryGeneratorLINTest | , | 
| TestExceptionErrorCodeMapping | |||
| ) | 
Checks that each derived MoveItErrorCodeException contains the correct error code.
Definition at line 187 of file unittest_trajectory_generator_lin.cpp.
| const std::string VELOCITY_SCALING_FACTOR | ( | "velocity_scaling_factor" | ) | 
