|
moveit2
The MoveIt Motion Planning Framework for ROS 2.
|
#include <gtest/gtest.h>#include <iostream>#include <memory>#include <string>#include <vector>#include <moveit/kinematic_constraints/utils.hpp>#include <moveit/planning_interface/planning_request.hpp>#include <moveit/robot_model_loader/robot_model_loader.hpp>#include <moveit/robot_state/conversions.hpp>#include <moveit_msgs/Constraints.h>#include <moveit_msgs/GetMotionPlan.h>#include <moveit_msgs/JointConstraint.h>#include <pilz_industrial_motion_planner_testutils/command_types_typedef.hpp>#include <pilz_industrial_motion_planner_testutils/xml_testdata_loader.hpp>#include <ros/ros.h>#include <tf2_eigen/tf2_eigen.hpp>#include <tf2_geometry_msgs/tf2_geometry_msgs.hpp>#include "test_utils.hpp"
Go to the source code of this file.
Classes | |
| class | IntegrationTestCommandPlanning |
Functions | |
| const std::string | PARAM_PLANNING_GROUP_NAME ("planning_group") |
| const std::string | POSE_TRANSFORM_MATRIX_NORM_TOLERANCE ("pose_norm_tolerance") |
| const std::string | ORIENTATION_NORM_TOLERANCE ("orientation_norm_tolerance") |
| const std::string | PARAM_TARGET_LINK_NAME ("target_link") |
| const std::string | TEST_DATA_FILE_NAME ("testdata_file_name") |
| TEST_F (IntegrationTestCommandPlanning, PtpJoint) | |
| Tests if ptp motions with start & goal state given as joint configuration are executed correctly. | |
| TEST_F (IntegrationTestCommandPlanning, PtpJointCart) | |
| Tests if ptp motions with start state given as joint configuration and goal state given as cartesian configuration are executed correctly. | |
| TEST_F (IntegrationTestCommandPlanning, LinJoint) | |
| Tests if linear motions with start and goal state given as joint configuration are executed correctly. | |
| TEST_F (IntegrationTestCommandPlanning, LinJointCart) | |
| Tests if linear motions with start state given as joint configuration and goal state given as cartesian configuration are executed correctly. | |
| TEST_F (IntegrationTestCommandPlanning, CircJointCenterCart) | |
| Tests if circular motions with start & goal state given as joint configuration and center point given as cartesian configuration are executed correctly. | |
| TEST_F (IntegrationTestCommandPlanning, CircCartCenterCart) | |
| Tests if linear motions with start state given as cartesian configuration and goal state given as cartesian configuration are executed correctly. | |
| int | main (int argc, char **argv) |
Variables | |
| const double | EPSILON = 1.0e-6 |
| const std::string | PLAN_SERVICE_NAME = "/plan_kinematic_path" |
| int main | ( | int | argc, |
| char ** | argv | ||
| ) |
Definition at line 492 of file integrationtest_command_planning.cpp.
| const std::string ORIENTATION_NORM_TOLERANCE | ( | "orientation_norm_tolerance" | ) |

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

| const std::string PARAM_TARGET_LINK_NAME | ( | "target_link" | ) |

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

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

| TEST_F | ( | IntegrationTestCommandPlanning | , |
| CircCartCenterCart | |||
| ) |
Tests if linear motions with start state given as cartesian configuration and goal state given as cartesian configuration are executed correctly.
Definition at line 423 of file integrationtest_command_planning.cpp.

| TEST_F | ( | IntegrationTestCommandPlanning | , |
| CircJointCenterCart | |||
| ) |
Tests if circular motions with start & goal state given as joint configuration and center point given as cartesian configuration are executed correctly.
Test Sequence:
Expected Results:
Definition at line 338 of file integrationtest_command_planning.cpp.

| TEST_F | ( | IntegrationTestCommandPlanning | , |
| LinJoint | |||
| ) |
Tests if linear motions with start and goal state given as joint configuration are executed correctly.
Test Sequence:
Expected Results:
Definition at line 239 of file integrationtest_command_planning.cpp.

| TEST_F | ( | IntegrationTestCommandPlanning | , |
| LinJointCart | |||
| ) |
Tests if linear motions with start state given as joint configuration and goal state given as cartesian configuration are executed correctly.
Test Sequence:
Expected Results:
Definition at line 290 of file integrationtest_command_planning.cpp.

| TEST_F | ( | IntegrationTestCommandPlanning | , |
| PtpJoint | |||
| ) |
Tests if ptp motions with start & goal state given as joint configuration are executed correctly.
Test Sequence:
Expected Results:
Definition at line 126 of file integrationtest_command_planning.cpp.
| TEST_F | ( | IntegrationTestCommandPlanning | , |
| PtpJointCart | |||
| ) |
Tests if ptp motions with start state given as joint configuration and goal state given as cartesian configuration are executed correctly.
Test Sequence:
Expected Results:
Definition at line 175 of file integrationtest_command_planning.cpp.

| const double EPSILON = 1.0e-6 |
Definition at line 57 of file integrationtest_command_planning.cpp.
| const std::string PLAN_SERVICE_NAME = "/plan_kinematic_path" |
Definition at line 58 of file integrationtest_command_planning.cpp.