moveit2
The MoveIt Motion Planning Framework for ROS 2.
Classes | Functions | Variables
integrationtest_command_planning.cpp File Reference
#include <gtest/gtest.h>
#include <iostream>
#include <memory>
#include <string>
#include <vector>
#include <moveit/kinematic_constraints/utils.h>
#include <moveit/planning_interface/planning_request.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 <pilz_industrial_motion_planner_testutils/command_types_typedef.h>
#include <pilz_industrial_motion_planner_testutils/xml_testdata_loader.h>
#include <ros/ros.h>
#include <tf2_eigen/tf2_eigen.hpp>
#include <tf2_geometry_msgs/tf2_geometry_msgs.hpp>
#include "test_utils.h"
Include dependency graph for integrationtest_command_planning.cpp:

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. More...
 
 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. More...
 
 TEST_F (IntegrationTestCommandPlanning, LinJoint)
 Tests if linear motions with start and goal state given as joint configuration are executed correctly. More...
 
 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. More...
 
 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. More...
 
 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. More...
 
int main (int argc, char **argv)
 

Variables

const double EPSILON = 1.0e-6
 
const std::string PLAN_SERVICE_NAME = "/plan_kinematic_path"
 

Function Documentation

◆ main()

int main ( int  argc,
char **  argv 
)

Definition at line 492 of file integrationtest_command_planning.cpp.

◆ ORIENTATION_NORM_TOLERANCE()

const std::string ORIENTATION_NORM_TOLERANCE ( "orientation_norm_tolerance"  )
Here is the caller graph for this function:

◆ PARAM_PLANNING_GROUP_NAME()

const std::string PARAM_PLANNING_GROUP_NAME ( "planning_group"  )
Here is the caller graph for this function:

◆ PARAM_TARGET_LINK_NAME()

const std::string PARAM_TARGET_LINK_NAME ( "target_link"  )
Here is the caller graph for this function:

◆ POSE_TRANSFORM_MATRIX_NORM_TOLERANCE()

const std::string POSE_TRANSFORM_MATRIX_NORM_TOLERANCE ( "pose_norm_tolerance"  )
Here is the caller graph for this function:

◆ 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/6]

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.

  • Test Sequence:
    1. Generate request with POSE goal and start state call planning service.
  • Expected Results:
    1. Last point of the resulting trajectory is at the goal
    2. Waypoints are on the desired circle

Definition at line 423 of file integrationtest_command_planning.cpp.

Here is the call graph for this function:

◆ TEST_F() [2/6]

Tests if circular motions with start & goal state given as joint configuration and center point given as cartesian configuration are executed correctly.

Test Sequence:

  1. Generate request with JOINT goal and start state call planning service.

Expected Results:

  1. Last point of the resulting trajectory is at the goal
  2. Waypoints are on the desired circle

Definition at line 338 of file integrationtest_command_planning.cpp.

Here is the call graph for this function:

◆ TEST_F() [3/6]

Tests if linear motions with start and goal state given as joint configuration are executed correctly.

Test Sequence:

  1. Generate request and make service request.
  2. Check if target position correct.
  3. Check if trajectory is linear.

Expected Results:

  1. Planning request is successful.
  2. Goal position corresponds with the given goal position.
  3. Trajectory is a straight line.

Definition at line 239 of file integrationtest_command_planning.cpp.

Here is the call graph for this function:

◆ TEST_F() [4/6]

Tests if linear motions with start state given as joint configuration and goal state given as cartesian configuration are executed correctly.

Test Sequence:

  1. Generate request and make service request.
  2. Check if target position correct.
  3. Check if trajectory is linear.

Expected Results:

  1. Planning request is successful.
  2. Goal position corresponds with the given goal position.
  3. Trajectory is a straight line.

Definition at line 290 of file integrationtest_command_planning.cpp.

Here is the call graph for this function:

◆ TEST_F() [5/6]

Tests if ptp motions with start & goal state given as joint configuration are executed correctly.

Test Sequence:

  1. Generate request with joint goal and start state call planning service.

Expected Results:

  1. Last point of the resulting trajectory is at the goal

Definition at line 126 of file integrationtest_command_planning.cpp.

◆ TEST_F() [6/6]

Tests if ptp motions with start state given as joint configuration and goal state given as cartesian configuration are executed correctly.

Test Sequence:

  1. Generate request with pose goal and start state call planning service.

Expected Results:

  1. Last point of the resulting trajectory is at the goal

Definition at line 175 of file integrationtest_command_planning.cpp.

Here is the call graph for this function:

Variable Documentation

◆ EPSILON

const double EPSILON = 1.0e-6

Definition at line 57 of file integrationtest_command_planning.cpp.

◆ PLAN_SERVICE_NAME

const std::string PLAN_SERVICE_NAME = "/plan_kinematic_path"

Definition at line 58 of file integrationtest_command_planning.cpp.