|
moveit2
The MoveIt Motion Planning Framework for ROS 2.
|
#include <memory>#include <string>#include <gtest/gtest.h>#include <functional>#include <ros/ros.h>#include <ros/time.h>#include <moveit/kinematic_constraints/utils.hpp>#include <moveit/planning_scene/planning_scene.hpp>#include <moveit/robot_model_loader/robot_model_loader.hpp>#include <moveit_msgs/DisplayTrajectory.h>#include <moveit_msgs/MotionPlanResponse.h>#include <tf2_eigen/tf2_eigen.hpp>#include <pilz_industrial_motion_planner_testutils/gripper.hpp>#include <pilz_industrial_motion_planner_testutils/lin.hpp>#include <pilz_industrial_motion_planner_testutils/sequence.hpp>#include <pilz_industrial_motion_planner_testutils/xml_testdata_loader.hpp>#include "test_utils.hpp"#include <pilz_industrial_motion_planner/command_list_manager.hpp>#include <pilz_industrial_motion_planner/tip_frame_getter.hpp>
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. | |
| TEST_F (IntegrationTestCommandListManager, concatThreeSegments) | |
| Tests the concatenation of three motion commands. | |
| TEST_F (IntegrationTestCommandListManager, concatSegmentsSelectiveBlending) | |
| Tests if times are strictly increasing with selective blending. | |
| TEST_F (IntegrationTestCommandListManager, concatTwoPtpSegments) | |
| Tests the concatenation of two ptp commands. | |
| TEST_F (IntegrationTestCommandListManager, concatPtpAndLinSegments) | |
| Tests the concatenation of ptp and a lin command. | |
| TEST_F (IntegrationTestCommandListManager, concatLinAndPtpSegments) | |
| Tests the concatenation of a lin and a ptp command. | |
| TEST_F (IntegrationTestCommandListManager, blendTwoSegments) | |
| Tests the blending of motion commands. | |
| TEST_F (IntegrationTestCommandListManager, emptyList) | |
| Tests sending an empty blending request. | |
| TEST_F (IntegrationTestCommandListManager, firstGoalNotReachable) | |
| Checks that exception is thrown if first goal is not reachable. | |
| TEST_F (IntegrationTestCommandListManager, startStateNotFirstGoal) | |
| Checks that exception is thrown if second goal has a start state. | |
| TEST_F (IntegrationTestCommandListManager, blendingRadiusNegative) | |
| Checks that exception is thrown in case of blending request with negative blend_radius. | |
| TEST_F (IntegrationTestCommandListManager, lastBlendingRadiusNonZero) | |
| Checks that exception is thrown if last blend radius is not zero. | |
| TEST_F (IntegrationTestCommandListManager, blendRadiusGreaterThanSegment) | |
| Checks that exception is thrown if blend radius is greater than the segment. | |
| TEST_F (IntegrationTestCommandListManager, blendingRadiusOverlapping) | |
| Checks that exception is thrown if two consecutive blend radii overlap. | |
| TEST_F (IntegrationTestCommandListManager, TestExecutionTime) | |
| Tests if the planned execution time scales correctly with the number of repetitions. | |
| TEST_F (IntegrationTestCommandListManager, TestDifferentGroups) | |
| Tests if it possible to send requests which contain more than one group. | |
| TEST_F (IntegrationTestCommandListManager, TestGripperCmdBlending) | |
| Checks that no exception is thrown if two gripper commands are blended. | |
| 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_F (IntegrationTestCommandListManager, TestGetSolverTipFrameForSolverlessGroup) | |
| Checks that exception is thrown if Tip-Frame is requested for a group without a solver. | |
| int | main (int argc, char **argv) |
Variables | |
| const std::string | ROBOT_DESCRIPTION_STR { "robot_description" } |
| const std::string | EMPTY_VALUE { "" } |
| int main | ( | int | argc, |
| char ** | argv | ||
| ) |
Definition at line 653 of file integrationtest_command_list_manager.cpp.
| const std::string TEST_DATA_FILE_NAME | ( | "testdata_file_name" | ) |

| TEST_F | ( | IntegrationTestCommandListManager | , |
| blendingRadiusNegative | |||
| ) |
Checks that exception is thrown in case of blending request with negative blend_radius.
Test Sequence:
Expected Results:
Definition at line 423 of file integrationtest_command_list_manager.cpp.
| TEST_F | ( | IntegrationTestCommandListManager | , |
| blendingRadiusOverlapping | |||
| ) |
Checks that exception is thrown if two consecutive blend radii overlap.
Test Sequence:
Expected Results:
Definition at line 480 of file integrationtest_command_list_manager.cpp.
| TEST_F | ( | IntegrationTestCommandListManager | , |
| blendRadiusGreaterThanSegment | |||
| ) |
Checks that exception is thrown if blend radius is greater than the segment.
Test Sequence:
Expected Results:
Definition at line 460 of file integrationtest_command_list_manager.cpp.
| TEST_F | ( | IntegrationTestCommandListManager | , |
| blendTwoSegments | |||
| ) |
Tests the blending of motion commands.
Definition at line 333 of file integrationtest_command_list_manager.cpp.
| TEST_F | ( | IntegrationTestCommandListManager | , |
| concatLinAndPtpSegments | |||
| ) |
Tests the concatenation of a lin and a ptp command.
Test Sequence:
Expected Results:
Definition at line 312 of file integrationtest_command_list_manager.cpp.
| TEST_F | ( | IntegrationTestCommandListManager | , |
| concatPtpAndLinSegments | |||
| ) |
Tests the concatenation of ptp and a lin command.
Test Sequence:
Expected Results:
Definition at line 290 of file integrationtest_command_list_manager.cpp.
| TEST_F | ( | IntegrationTestCommandListManager | , |
| concatSegmentsSelectiveBlending | |||
| ) |
Tests if times are strictly increasing with selective blending.
Test Sequence:
Expected Results:
Definition at line 238 of file integrationtest_command_list_manager.cpp.
| TEST_F | ( | IntegrationTestCommandListManager | , |
| concatThreeSegments | |||
| ) |
Tests the concatenation of three motion commands.
Test Sequence:
Expected Results:
Definition at line 169 of file integrationtest_command_list_manager.cpp.
| TEST_F | ( | IntegrationTestCommandListManager | , |
| concatTwoPtpSegments | |||
| ) |
Tests the concatenation of two ptp commands.
Test Sequence:
Expected Results:
Definition at line 268 of file integrationtest_command_list_manager.cpp.
| TEST_F | ( | IntegrationTestCommandListManager | , |
| emptyList | |||
| ) |
Tests sending an empty blending request.
Test Sequence:
Expected Results:
Definition at line 369 of file integrationtest_command_list_manager.cpp.
| TEST_F | ( | IntegrationTestCommandListManager | , |
| firstGoalNotReachable | |||
| ) |
Checks that exception is thrown if first goal is not reachable.
Test Sequence:
Expected Results:
Definition at line 385 of file integrationtest_command_list_manager.cpp.

| TEST_F | ( | IntegrationTestCommandListManager | , |
| lastBlendingRadiusNonZero | |||
| ) |
Checks that exception is thrown if last blend radius is not zero.
Test Sequence:
Expected Results:
Definition at line 441 of file integrationtest_command_list_manager.cpp.
| TEST_F | ( | IntegrationTestCommandListManager | , |
| startStateNotFirstGoal | |||
| ) |
Checks that exception is thrown if second goal has a start state.
Test Sequence:
Expected Results:
Definition at line 403 of file integrationtest_command_list_manager.cpp.

| 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 | ( | 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 | ( | IntegrationTestCommandListManager | , |
| TestExecutionTime | |||
| ) |
Tests if the planned execution time scales correctly with the number of repetitions.
Test Sequence:
Expected Results:
Definition at line 516 of file integrationtest_command_list_manager.cpp.
| 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 | ( | 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 | ( | 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:
Expected Results:
Definition at line 618 of file integrationtest_command_list_manager.cpp.

| const std::string EMPTY_VALUE { "" } |
Definition at line 63 of file integrationtest_command_list_manager.cpp.
| const std::string ROBOT_DESCRIPTION_STR { "robot_description" } |
Definition at line 62 of file integrationtest_command_list_manager.cpp.