moveit2
The MoveIt Motion Planning Framework for ROS 2.
|
#include <chrono>
#include <condition_variable>
#include <gmock/gmock.h>
#include <gtest/gtest.h>
#include <iostream>
#include <memory>
#include <mutex>
#include <stdexcept>
#include <thread>
#include <actionlib/client/simple_action_client.h>
#include <moveit/move_group_interface/move_group_interface.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_msgs/Constraints.h>
#include <moveit_msgs/GetMotionPlan.h>
#include <moveit_msgs/JointConstraint.h>
#include <ros/ros.h>
#include <pilz_industrial_motion_planner_testutils/async_test.h>
#include <pilz_industrial_motion_planner_testutils/checks.h>
#include <pilz_industrial_motion_planner_testutils/sequence.h>
#include <pilz_industrial_motion_planner_testutils/xml_testdata_loader.h>
#include <moveit_msgs/MoveGroupSequenceAction.h>
Go to the source code of this file.
Classes | |
class | IntegrationTestSequenceAction |
Functions | |
const std::string | SEQUENCE_ACTION_NAME ("/sequence_move_group") |
const std::string | JOINT_POSITION_TOLERANCE ("joint_position_tolerance") |
const std::string | TEST_DATA_FILE_NAME ("testdata_file_name") |
const std::string | GROUP_NAME ("group_name") |
TEST_F (IntegrationTestSequenceAction, TestSendingOfEmptySequence) | |
Test behavior of sequence action server when empty sequence is sent. More... | |
TEST_F (IntegrationTestSequenceAction, TestDifferingGroupNames) | |
Tests that invalid (differing) group names are detected. More... | |
TEST_F (IntegrationTestSequenceAction, TestNegativeBlendRadius) | |
Tests that negative blend radii are detected. More... | |
TEST_F (IntegrationTestSequenceAction, TestOverlappingBlendRadii) | |
Tests that overlapping blend radii are detected. More... | |
TEST_F (IntegrationTestSequenceAction, TestTooLargeBlendRadii) | |
Tests that too large blend radii are detected. More... | |
TEST_F (IntegrationTestSequenceAction, TestInvalidCmd) | |
Tests what happens if sequence contains not executable (invalid) command. More... | |
TEST_F (IntegrationTestSequenceAction, TestInvalidLinkName) | |
Tests that incorrect link_names are detected. More... | |
MATCHER_P (FeedbackStateEq, state, "") | |
MATCHER (IsResultSuccess, "") | |
MATCHER (IsResultNotEmpty, "") | |
TEST_F (IntegrationTestSequenceAction, TestActionServerCallbacks) | |
Tests that action server callbacks are called correctly. More... | |
TEST_F (IntegrationTestSequenceAction, TestPlanOnlyFlag) | |
Tests the "only planning" flag. More... | |
TEST_F (IntegrationTestSequenceAction, TestIgnoreRobotStateForPlanOnly) | |
Tests that robot state in planning_scene_diff is ignored (Mainly for full coverage) in case "plan only" flag is set. More... | |
TEST_F (IntegrationTestSequenceAction, TestNegativeBlendRadiusForPlanOnly) | |
Tests that negative blend radii are detected (Mainly for full coverage) in case "plan only" flag is set. More... | |
TEST_F (IntegrationTestSequenceAction, TestIgnoreRobotState) | |
Tests that robot state in planning_scene_diff is ignored (Mainly for full coverage). More... | |
TEST_F (IntegrationTestSequenceAction, TestLargeRequest) | |
Tests the execution of a sequence with more than two commands. More... | |
TEST_F (IntegrationTestSequenceAction, TestComplexSequenceWithoutBlending) | |
Tests the execution of a sequence command (without blending) consisting of most of the possible command type combination. More... | |
TEST_F (IntegrationTestSequenceAction, TestComplexSequenceWithBlending) | |
Tests the execution of a sequence command (with blending) consisting of most of the possible command type combination. More... | |
int | main (int argc, char **argv) |
Variables | |
const std::string | GOAL_SUCCEEDED_EVENT = "GOAL_SUCCEEDED" |
const std::string | SERVER_IDLE_EVENT = "SERVER_IDLE" |
const std::string GROUP_NAME | ( | "group_name" | ) |
const std::string JOINT_POSITION_TOLERANCE | ( | "joint_position_tolerance" | ) |
int main | ( | int | argc, |
char ** | argv | ||
) |
Definition at line 623 of file integrationtest_sequence_action.cpp.
MATCHER | ( | IsResultNotEmpty | , |
"" | |||
) |
Definition at line 341 of file integrationtest_sequence_action.cpp.
MATCHER | ( | IsResultSuccess | , |
"" | |||
) |
Definition at line 337 of file integrationtest_sequence_action.cpp.
MATCHER_P | ( | FeedbackStateEq | , |
state | , | ||
"" | |||
) |
Definition at line 333 of file integrationtest_sequence_action.cpp.
const std::string SEQUENCE_ACTION_NAME | ( | "/sequence_move_group" | ) |
const std::string TEST_DATA_FILE_NAME | ( | "testdata_file_name" | ) |
TEST_F | ( | IntegrationTestSequenceAction | , |
TestActionServerCallbacks | |||
) |
Tests that action server callbacks are called correctly.
Test Sequence:
Expected Results:
Definition at line 358 of file integrationtest_sequence_action.cpp.
TEST_F | ( | IntegrationTestSequenceAction | , |
TestComplexSequenceWithBlending | |||
) |
Tests the execution of a sequence command (with blending) consisting of most of the possible command type combination.
Test Sequence:
Expected Results:
Definition at line 610 of file integrationtest_sequence_action.cpp.
TEST_F | ( | IntegrationTestSequenceAction | , |
TestComplexSequenceWithoutBlending | |||
) |
Tests the execution of a sequence command (without blending) consisting of most of the possible command type combination.
Test Sequence:
Expected Results:
Definition at line 583 of file integrationtest_sequence_action.cpp.
TEST_F | ( | IntegrationTestSequenceAction | , |
TestDifferingGroupNames | |||
) |
Tests that invalid (differing) group names are detected.
Test Sequence:
Expected Results:
Definition at line 170 of file integrationtest_sequence_action.cpp.
TEST_F | ( | IntegrationTestSequenceAction | , |
TestIgnoreRobotState | |||
) |
Tests that robot state in planning_scene_diff is ignored (Mainly for full coverage).
Test Sequence:
Expected Results:
Definition at line 513 of file integrationtest_sequence_action.cpp.
TEST_F | ( | IntegrationTestSequenceAction | , |
TestIgnoreRobotStateForPlanOnly | |||
) |
Tests that robot state in planning_scene_diff is ignored (Mainly for full coverage) in case "plan only" flag is set.
Test Sequence:
Expected Results:
Definition at line 447 of file integrationtest_sequence_action.cpp.
TEST_F | ( | IntegrationTestSequenceAction | , |
TestInvalidCmd | |||
) |
Tests what happens if sequence contains not executable (invalid) command.
Test Sequence:
Expected Results:
Definition at line 286 of file integrationtest_sequence_action.cpp.
TEST_F | ( | IntegrationTestSequenceAction | , |
TestInvalidLinkName | |||
) |
Tests that incorrect link_names are detected.
Test Sequence:
Expected Results:
Definition at line 312 of file integrationtest_sequence_action.cpp.
TEST_F | ( | IntegrationTestSequenceAction | , |
TestLargeRequest | |||
) |
Tests the execution of a sequence with more than two commands.
Test Sequence:
Expected Results:
Definition at line 543 of file integrationtest_sequence_action.cpp.
TEST_F | ( | IntegrationTestSequenceAction | , |
TestNegativeBlendRadius | |||
) |
Tests that negative blend radii are detected.
Test Sequence:
Expected Results:
Definition at line 198 of file integrationtest_sequence_action.cpp.
TEST_F | ( | IntegrationTestSequenceAction | , |
TestNegativeBlendRadiusForPlanOnly | |||
) |
Tests that negative blend radii are detected (Mainly for full coverage) in case "plan only" flag is set.
Test Sequence:
Expected Results:
Definition at line 484 of file integrationtest_sequence_action.cpp.
TEST_F | ( | IntegrationTestSequenceAction | , |
TestOverlappingBlendRadii | |||
) |
Tests that overlapping blend radii are detected.
Test Sequence:
Expected Results:
Definition at line 227 of file integrationtest_sequence_action.cpp.
TEST_F | ( | IntegrationTestSequenceAction | , |
TestPlanOnlyFlag | |||
) |
Tests the "only planning" flag.
Test Sequence:
Expected Results:
Definition at line 415 of file integrationtest_sequence_action.cpp.
TEST_F | ( | IntegrationTestSequenceAction | , |
TestSendingOfEmptySequence | |||
) |
Test behavior of sequence action server when empty sequence is sent.
Test Sequence:
Expected Results:
Definition at line 147 of file integrationtest_sequence_action.cpp.
TEST_F | ( | IntegrationTestSequenceAction | , |
TestTooLargeBlendRadii | |||
) |
Tests that too large blend radii are detected.
Test Sequence:
Expected Results:
Definition at line 256 of file integrationtest_sequence_action.cpp.
const std::string GOAL_SUCCEEDED_EVENT = "GOAL_SUCCEEDED" |
Definition at line 71 of file integrationtest_sequence_action.cpp.
const std::string SERVER_IDLE_EVENT = "SERVER_IDLE" |
Definition at line 72 of file integrationtest_sequence_action.cpp.