moveit2
The MoveIt Motion Planning Framework for ROS 2.
Classes | Functions
unittest_trajectory_generator_ptp.cpp File Reference
#include <memory>
#include <gtest/gtest.h>
#include <pilz_industrial_motion_planner/joint_limits_aggregator.h>
#include <pilz_industrial_motion_planner/trajectory_generator_ptp.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 <pluginlib/class_loader.hpp>
#include <rclcpp/rclcpp.hpp>
Include dependency graph for unittest_trajectory_generator_ptp.cpp:

Go to the source code of this file.

Classes

class  TrajectoryGeneratorPTPTest
 

Functions

const std::string PARAM_PLANNING_GROUP_NAME ("planning_group")
 
const std::string PARAM_TARGET_LINK_NAME ("target_link")
 
const std::string JOINT_POSITION_TOLERANCE ("joint_position_tolerance")
 
const std::string JOINT_VELOCITY_TOLERANCE ("joint_velocity_tolerance")
 
const std::string JOINT_ACCELERATION_TOLERANCE ("joint_acceleration_tolerance")
 
const std::string POSE_TRANSFORM_MATRIX_NORM_TOLERANCE ("pose_norm_tolerance")
 
 TEST_F (TrajectoryGeneratorPTPTest, TestExceptionErrorCodeMapping)
 Checks that each derived MoveItErrorCodeException contains the correct error code. More...
 
 TEST_F (TrajectoryGeneratorPTPTest, noLimits)
 Construct a TrajectoryGeneratorPTP with no limits given. More...
 
 TEST_F (TrajectoryGeneratorPTPTest, emptyRequest)
 Send an empty request, define res.trajectory. More...
 
 TEST_F (TrajectoryGeneratorPTPTest, missingVelocityLimits)
 Construct a TrajectoryGeneratorPTP with missing velocity limits. More...
 
 TEST_F (TrajectoryGeneratorPTPTest, missingDecelerationimits)
 Construct a TrajectoryGeneratorPTP missing deceleration limits. More...
 
 TEST_F (TrajectoryGeneratorPTPTest, testInsufficientLimit)
 test the constructor when insufficient limits are given More...
 
 TEST_F (TrajectoryGeneratorPTPTest, testCartesianGoal)
 test the ptp trajectory generator of Cartesian space goal More...
 
 TEST_F (TrajectoryGeneratorPTPTest, testCartesianGoalMissingLinkNameConstraints)
 Check that missing a link_name in position or orientation constraints is detected. More...
 
 TEST_F (TrajectoryGeneratorPTPTest, testInvalidCartesianGoal)
 test the ptp trajectory generator of invalid Cartesian space goal More...
 
 TEST_F (TrajectoryGeneratorPTPTest, testJointGoalAlreadyReached)
 test the ptp trajectory generator of joint space goal which is close enough to the start which does not need to plan the trajectory More...
 
 TEST_F (TrajectoryGeneratorPTPTest, testScalingFactor)
 test scaling factor with zero start velocity More...
 
 TEST_F (TrajectoryGeneratorPTPTest, testJointGoalAndAlmostZeroStartVelocity)
 test the ptp trajectory generator of joint space goal with (almost) zero start velocity More...
 
 TEST_F (TrajectoryGeneratorPTPTest, testJointGoalNoStartVel)
 test the ptp_ trajectory generator of joint space goal with zero start velocity More...
 
int main (int argc, char **argv)
 

Function Documentation

◆ JOINT_ACCELERATION_TOLERANCE()

const std::string JOINT_ACCELERATION_TOLERANCE ( "joint_acceleration_tolerance"  )

◆ JOINT_POSITION_TOLERANCE()

const std::string JOINT_POSITION_TOLERANCE ( "joint_position_tolerance"  )

◆ JOINT_VELOCITY_TOLERANCE()

const std::string JOINT_VELOCITY_TOLERANCE ( "joint_velocity_tolerance"  )

◆ main()

int main ( int  argc,
char **  argv 
)

Definition at line 981 of file unittest_trajectory_generator_ptp.cpp.

◆ PARAM_PLANNING_GROUP_NAME()

const std::string PARAM_PLANNING_GROUP_NAME ( "planning_group"  )

◆ PARAM_TARGET_LINK_NAME()

const std::string PARAM_TARGET_LINK_NAME ( "target_link"  )

◆ POSE_TRANSFORM_MATRIX_NORM_TOLERANCE()

const std::string POSE_TRANSFORM_MATRIX_NORM_TOLERANCE ( "pose_norm_tolerance"  )

◆ TEST_F() [1/13]

TEST_F ( TrajectoryGeneratorPTPTest  ,
emptyRequest   
)

Send an empty request, define res.trajectory.

  • Test Sequence:
    1. Create request, define a trajectory in the result
    2. assign at least one joint limit will all required limits
  • Expected Results:
    1. the res.trajectory should be cleared (contain no waypoints)

Definition at line 197 of file unittest_trajectory_generator_ptp.cpp.

◆ TEST_F() [2/13]

TEST_F ( TrajectoryGeneratorPTPTest  ,
missingDecelerationimits   
)

Construct a TrajectoryGeneratorPTP missing deceleration limits.

Definition at line 244 of file unittest_trajectory_generator_ptp.cpp.

Here is the call graph for this function:

◆ TEST_F() [3/13]

TEST_F ( TrajectoryGeneratorPTPTest  ,
missingVelocityLimits   
)

Construct a TrajectoryGeneratorPTP with missing velocity limits.

Definition at line 219 of file unittest_trajectory_generator_ptp.cpp.

Here is the call graph for this function:

◆ TEST_F() [4/13]

TEST_F ( TrajectoryGeneratorPTPTest  ,
noLimits   
)

Construct a TrajectoryGeneratorPTP with no limits given.

Definition at line 180 of file unittest_trajectory_generator_ptp.cpp.

◆ TEST_F() [5/13]

TEST_F ( TrajectoryGeneratorPTPTest  ,
testCartesianGoal   
)

test the ptp trajectory generator of Cartesian space goal

Definition at line 351 of file unittest_trajectory_generator_ptp.cpp.

Here is the call graph for this function:

◆ TEST_F() [6/13]

TEST_F ( TrajectoryGeneratorPTPTest  ,
testCartesianGoalMissingLinkNameConstraints   
)

Check that missing a link_name in position or orientation constraints is detected.

Definition at line 400 of file unittest_trajectory_generator_ptp.cpp.

Here is the call graph for this function:

◆ TEST_F() [7/13]

TEST_F ( TrajectoryGeneratorPTPTest  ,
TestExceptionErrorCodeMapping   
)

Checks that each derived MoveItErrorCodeException contains the correct error code.

Definition at line 164 of file unittest_trajectory_generator_ptp.cpp.

◆ TEST_F() [8/13]

TEST_F ( TrajectoryGeneratorPTPTest  ,
testInsufficientLimit   
)

test the constructor when insufficient limits are given

  • Test Sequence:
    1. assign joint limits without acc and dec
    2. assign at least one joint limit per group with all required limits
  • Expected Results:
    1. the constructor throws an exception of type TrajectoryGeneratorInvalidLimitsException
    2. the constructor throws no exception

Definition at line 276 of file unittest_trajectory_generator_ptp.cpp.

Here is the call graph for this function:

◆ TEST_F() [9/13]

TEST_F ( TrajectoryGeneratorPTPTest  ,
testInvalidCartesianGoal   
)

test the ptp trajectory generator of invalid Cartesian space goal

Definition at line 438 of file unittest_trajectory_generator_ptp.cpp.

Here is the call graph for this function:

◆ TEST_F() [10/13]

TEST_F ( TrajectoryGeneratorPTPTest  ,
testJointGoalAlreadyReached   
)

test the ptp trajectory generator of joint space goal which is close enough to the start which does not need to plan the trajectory

Definition at line 468 of file unittest_trajectory_generator_ptp.cpp.

Here is the call graph for this function:

◆ TEST_F() [11/13]

TEST_F ( TrajectoryGeneratorPTPTest  ,
testJointGoalAndAlmostZeroStartVelocity   
)

test the ptp trajectory generator of joint space goal with (almost) zero start velocity

Definition at line 660 of file unittest_trajectory_generator_ptp.cpp.

Here is the call graph for this function:

◆ TEST_F() [12/13]

TEST_F ( TrajectoryGeneratorPTPTest  ,
testJointGoalNoStartVel   
)

test the ptp_ trajectory generator of joint space goal with zero start velocity

Definition at line 797 of file unittest_trajectory_generator_ptp.cpp.

Here is the call graph for this function:

◆ TEST_F() [13/13]

TEST_F ( TrajectoryGeneratorPTPTest  ,
testScalingFactor   
)

test scaling factor with zero start velocity

Definition at line 496 of file unittest_trajectory_generator_ptp.cpp.

Here is the call graph for this function: