moveit2
The MoveIt Motion Planning Framework for ROS 2.
Classes | Functions | Variables
integrationtest_command_list_manager.cpp File Reference
#include <memory>
#include <string>
#include <gtest/gtest.h>
#include <functional>
#include <ros/ros.h>
#include <ros/time.h>
#include <moveit/kinematic_constraints/utils.h>
#include <moveit/planning_scene/planning_scene.h>
#include <moveit/robot_model_loader/robot_model_loader.h>
#include <moveit_msgs/DisplayTrajectory.h>
#include <moveit_msgs/MotionPlanResponse.h>
#include <tf2_eigen/tf2_eigen.hpp>
#include <pilz_industrial_motion_planner_testutils/gripper.h>
#include <pilz_industrial_motion_planner_testutils/lin.h>
#include <pilz_industrial_motion_planner_testutils/sequence.h>
#include <pilz_industrial_motion_planner_testutils/xml_testdata_loader.h>
#include "test_utils.h"
#include <pilz_industrial_motion_planner/command_list_manager.h>
#include <pilz_industrial_motion_planner/tip_frame_getter.h>
Include dependency graph for integrationtest_command_list_manager.cpp:

Go to the source code of this file.

Classes

class  IntegrationTestCommandListManager
 

Functions

const std::string TEST_DATA_FILE_NAME ("testdata_file_name")
 
 TEST_F (IntegrationTestCommandListManager, TestExceptionErrorCodeMapping)
 Checks that each derived MoveItErrorCodeException contains the correct error code. More...
 
 TEST_F (IntegrationTestCommandListManager, concatThreeSegments)
 Tests the concatenation of three motion commands. More...
 
 TEST_F (IntegrationTestCommandListManager, concatSegmentsSelectiveBlending)
 Tests if times are strictly increasing with selective blending. More...
 
 TEST_F (IntegrationTestCommandListManager, concatTwoPtpSegments)
 Tests the concatenation of two ptp commands. More...
 
 TEST_F (IntegrationTestCommandListManager, concatPtpAndLinSegments)
 Tests the concatenation of ptp and a lin command. More...
 
 TEST_F (IntegrationTestCommandListManager, concatLinAndPtpSegments)
 Tests the concatenation of a lin and a ptp command. More...
 
 TEST_F (IntegrationTestCommandListManager, blendTwoSegments)
 Tests the blending of motion commands. More...
 
 TEST_F (IntegrationTestCommandListManager, emptyList)
 Tests sending an empty blending request. More...
 
 TEST_F (IntegrationTestCommandListManager, firstGoalNotReachable)
 Checks that exception is thrown if first goal is not reachable. More...
 
 TEST_F (IntegrationTestCommandListManager, startStateNotFirstGoal)
 Checks that exception is thrown if second goal has a start state. More...
 
 TEST_F (IntegrationTestCommandListManager, blendingRadiusNegative)
 Checks that exception is thrown in case of blending request with negative blend_radius. More...
 
 TEST_F (IntegrationTestCommandListManager, lastBlendingRadiusNonZero)
 Checks that exception is thrown if last blend radius is not zero. More...
 
 TEST_F (IntegrationTestCommandListManager, blendRadiusGreaterThanSegment)
 Checks that exception is thrown if blend radius is greater than the segment. More...
 
 TEST_F (IntegrationTestCommandListManager, blendingRadiusOverlapping)
 Checks that exception is thrown if two consecutive blend radii overlap. More...
 
 TEST_F (IntegrationTestCommandListManager, TestExecutionTime)
 Tests if the planned execution time scales correctly with the number of repetitions. More...
 
 TEST_F (IntegrationTestCommandListManager, TestDifferentGroups)
 Tests if it possible to send requests which contain more than one group. More...
 
 TEST_F (IntegrationTestCommandListManager, TestGripperCmdBlending)
 Checks that no exception is thrown if two gripper commands are blended. More...
 
 TEST_F (IntegrationTestCommandListManager, TestGroupSpecificStartState)
 Tests the execution of a sequence in which each group states a start state only consisting of joints of the corresponding group. More...
 
 TEST_F (IntegrationTestCommandListManager, TestGetSolverTipFrameForSolverlessGroup)
 Checks that exception is thrown if Tip-Frame is requested for a group without a solver. More...
 
int main (int argc, char **argv)
 

Variables

const std::string ROBOT_DESCRIPTION_STR { "robot_description" }
 
const std::string EMPTY_VALUE { "" }
 

Function Documentation

◆ main()

int main ( int  argc,
char **  argv 
)

Definition at line 653 of file integrationtest_command_list_manager.cpp.

◆ TEST_DATA_FILE_NAME()

const std::string TEST_DATA_FILE_NAME ( "testdata_file_name"  )
Here is the caller graph for this function:

◆ TEST_F() [1/19]

TEST_F ( IntegrationTestCommandListManager  ,
blendingRadiusNegative   
)

Checks that exception is thrown in case of blending request with negative blend_radius.

Test Sequence:

  1. Generate request, first goal has negative blend_radius.

Expected Results:

  1. Exception is thrown.

Definition at line 423 of file integrationtest_command_list_manager.cpp.

◆ TEST_F() [2/19]

TEST_F ( IntegrationTestCommandListManager  ,
blendingRadiusOverlapping   
)

Checks that exception is thrown if two consecutive blend radii overlap.

Test Sequence:

  1. Generate request with three trajectories
  2. Increase second blend radius, so that the radii overlap

Expected Results:

  1. blending succeeds, result trajectory is not empty
  2. Exception is thrown.

Definition at line 480 of file integrationtest_command_list_manager.cpp.

Here is the call graph for this function:

◆ TEST_F() [3/19]

TEST_F ( IntegrationTestCommandListManager  ,
blendRadiusGreaterThanSegment   
)

Checks that exception is thrown if blend radius is greater than the segment.

Test Sequence:

  1. Generate request with huge blending radius, so that trajectories are completely inside

Expected Results:

  1. Exception is thrown.

Definition at line 460 of file integrationtest_command_list_manager.cpp.

◆ TEST_F() [4/19]

TEST_F ( IntegrationTestCommandListManager  ,
blendTwoSegments   
)

Tests the blending of motion commands.

  • Test Sequence:
    1. Generate request with two trajectories and request blending.
  • Expected Results:
    1. blending is successful, result trajectory is not empty

Definition at line 333 of file integrationtest_command_list_manager.cpp.

◆ TEST_F() [5/19]

TEST_F ( IntegrationTestCommandListManager  ,
concatLinAndPtpSegments   
)

Tests the concatenation of a lin and a ptp command.

Test Sequence:

  1. Generate request with LIN and PTP trajectory and zero blend radius.

Expected Results:

  1. Generation of concatenated trajectory is successful. All time steps of resulting trajectory are strictly positive.

Definition at line 312 of file integrationtest_command_list_manager.cpp.

Here is the call graph for this function:

◆ TEST_F() [6/19]

TEST_F ( IntegrationTestCommandListManager  ,
concatPtpAndLinSegments   
)

Tests the concatenation of ptp and a lin command.

Test Sequence:

  1. Generate request with PTP and LIN trajectory and zero blend radius.

Expected Results:

  1. Generation of concatenated trajectory is successful. All time steps of resulting trajectory are strictly positive.

Definition at line 290 of file integrationtest_command_list_manager.cpp.

Here is the call graph for this function:

◆ TEST_F() [7/19]

TEST_F ( IntegrationTestCommandListManager  ,
concatSegmentsSelectiveBlending   
)

Tests if times are strictly increasing with selective blending.

Test Sequence:

  1. Generate request with three trajectories where only the first has a blend radius.
  1. Generate request with three trajectories where only the second has a blend radius.

Expected Results:

  1. Generation of concatenated trajectory is successful. All time steps of resulting trajectory are strictly increasing in time
  2. Generation of concatenated trajectory is successful. All time steps of resulting trajectory are strictly increasing in time

Definition at line 238 of file integrationtest_command_list_manager.cpp.

Here is the call graph for this function:

◆ TEST_F() [8/19]

TEST_F ( IntegrationTestCommandListManager  ,
concatThreeSegments   
)

Tests the concatenation of three motion commands.

Test Sequence:

  1. Generate request with three trajectories and zero blend radius.
  2. Generate request with first trajectory and zero blend radius.
  3. Generate request with second trajectory and zero blend radius.
  4. Generate request with third trajectory and zero blend radius.

Expected Results:

  1. Generation of concatenated trajectory is successful. All time steps of resulting trajectory are strictly positive
  2. Generation of concatenated trajectory is successful. All time steps of resulting trajectory are strictly positive
  3. Generation of concatenated trajectory is successful. All time steps of resulting trajectory are strictly positive
  4. Generation of concatenated trajectory is successful. All time steps of resulting trajectory are strictly positive resulting duration in step1 is approximately step2 + step3 + step4

Definition at line 169 of file integrationtest_command_list_manager.cpp.

Here is the call graph for this function:

◆ TEST_F() [9/19]

TEST_F ( IntegrationTestCommandListManager  ,
concatTwoPtpSegments   
)

Tests the concatenation of two ptp commands.

Test Sequence:

  1. Generate request with two PTP trajectories and zero blend radius.

Expected Results:

  1. Generation of concatenated trajectory is successful. All time steps of resulting trajectory are strictly positive.

Definition at line 268 of file integrationtest_command_list_manager.cpp.

Here is the call graph for this function:

◆ TEST_F() [10/19]

TEST_F ( IntegrationTestCommandListManager  ,
emptyList   
)

Tests sending an empty blending request.

Test Sequence:

  1. Generate empty request and request blending.

Expected Results:

  1. blending is successful, result trajectory container is empty

Definition at line 369 of file integrationtest_command_list_manager.cpp.

◆ TEST_F() [11/19]

TEST_F ( IntegrationTestCommandListManager  ,
firstGoalNotReachable   
)

Checks that exception is thrown if first goal is not reachable.

Test Sequence:

  1. Generate request with first goal out of workspace.

Expected Results:

  1. Exception is thrown.

Definition at line 385 of file integrationtest_command_list_manager.cpp.

Here is the call graph for this function:

◆ TEST_F() [12/19]

TEST_F ( IntegrationTestCommandListManager  ,
lastBlendingRadiusNonZero   
)

Checks that exception is thrown if last blend radius is not zero.

Test Sequence:

  1. Generate request, second goal has non-zero blend_radius.

Expected Results:

  1. Exception is thrown.

Definition at line 441 of file integrationtest_command_list_manager.cpp.

◆ TEST_F() [13/19]

TEST_F ( IntegrationTestCommandListManager  ,
startStateNotFirstGoal   
)

Checks that exception is thrown if second goal has a start state.

Test Sequence:

  1. Generate request, second goal has an invalid start state set.

Expected Results:

  1. Exception is thrown.

Definition at line 403 of file integrationtest_command_list_manager.cpp.

Here is the call graph for this function:

◆ TEST_F() [14/19]

TEST_F ( IntegrationTestCommandListManager  ,
TestDifferentGroups   
)

Tests if it possible to send requests which contain more than one group.

Please note: This test is still quite trivial. It does not check the "correctness" of a calculated trajectory. It only checks that for each group and group change there exists a calculated trajectory.

Definition at line 562 of file integrationtest_command_list_manager.cpp.

◆ TEST_F() [15/19]

TEST_F ( IntegrationTestCommandListManager  ,
TestExceptionErrorCodeMapping   
)

Checks that each derived MoveItErrorCodeException contains the correct error code.

Definition at line 131 of file integrationtest_command_list_manager.cpp.

◆ TEST_F() [16/19]

TEST_F ( IntegrationTestCommandListManager  ,
TestExecutionTime   
)

Tests if the planned execution time scales correctly with the number of repetitions.

Test Sequence:

  1. Generate trajectory and save calculated execution time.
  2. Generate request with repeated path along the points from Test Step 1 (repeated two times).

Expected Results:

  1. Blending succeeds, result trajectory is not empty.
  2. Blending succeeds, planned execution time should be approx N times the single planned execution time.

Definition at line 516 of file integrationtest_command_list_manager.cpp.

◆ TEST_F() [17/19]

TEST_F ( IntegrationTestCommandListManager  ,
TestGetSolverTipFrameForSolverlessGroup   
)

Checks that exception is thrown if Tip-Frame is requested for a group without a solver.

Definition at line 647 of file integrationtest_command_list_manager.cpp.

◆ TEST_F() [18/19]

TEST_F ( IntegrationTestCommandListManager  ,
TestGripperCmdBlending   
)

Checks that no exception is thrown if two gripper commands are blended.

Definition at line 592 of file integrationtest_command_list_manager.cpp.

◆ TEST_F() [19/19]

TEST_F ( IntegrationTestCommandListManager  ,
TestGroupSpecificStartState   
)

Tests the execution of a sequence in which each group states a start state only consisting of joints of the corresponding group.

Test Sequence:

  1. Create sequence request for which each start state only consists of joints of the corresponding group

Expected Results:

  1. Trajectory generation is successful, result trajectory is not empty.

Definition at line 618 of file integrationtest_command_list_manager.cpp.

Here is the call graph for this function:

Variable Documentation

◆ EMPTY_VALUE

const std::string EMPTY_VALUE { "" }

Definition at line 63 of file integrationtest_command_list_manager.cpp.

◆ ROBOT_DESCRIPTION_STR

const std::string ROBOT_DESCRIPTION_STR { "robot_description" }

Definition at line 62 of file integrationtest_command_list_manager.cpp.