moveit2
The MoveIt Motion Planning Framework for ROS 2.
|
#include <boost/core/demangle.hpp>
#include <gtest/gtest.h>
#include <moveit/planning_interface/planning_interface.h>
#include <moveit/planning_scene/planning_scene.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/robot_state/robot_state.h>
#include <pilz_industrial_motion_planner/joint_limits_aggregator.h>
#include <pilz_industrial_motion_planner/joint_limits_container.h>
#include <pilz_industrial_motion_planner/trajectory_generator_circ.h>
#include <pilz_industrial_motion_planner/trajectory_generator_lin.h>
#include <pilz_industrial_motion_planner/trajectory_generator_ptp.h>
#include <pilz_industrial_motion_planner/trajectory_blender_transition_window.h>
#include "test_utils.h"
#include <rclcpp/rclcpp.hpp>
#include "cartesian_limits_parameters.hpp"
Go to the source code of this file.
Classes | |
class | ValueTypeContainer< T, N > |
class | TrajectoryGeneratorCommonTest< T > |
class | TrajectoryGeneratorCommonTestNoGripper< T > |
Functions | |
TYPED_TEST_SUITE (TrajectoryGeneratorCommonTest, TrajectoryGeneratorCommonTestTypes,) | |
TYPED_TEST_SUITE (TrajectoryGeneratorCommonTestNoGripper, TrajectoryGeneratorCommonTestTypesNoGripper,) | |
TYPED_TEST (TrajectoryGeneratorCommonTest, InvalideScalingFactor) | |
test invalid scaling factor. The scaling factor must be in the range of [0.0001, 1] | |
TYPED_TEST (TrajectoryGeneratorCommonTest, InvalidGroupName) | |
Test invalid motion plan request for all trajectory generators. | |
TYPED_TEST (TrajectoryGeneratorCommonTestNoGripper, GripperGroup) | |
Test invalid motion plan request for all trajectory generators. | |
TYPED_TEST (TrajectoryGeneratorCommonTest, EmptyJointNamesInStartState) | |
Test invalid motion plan request for all trajectory generators. | |
TYPED_TEST (TrajectoryGeneratorCommonTest, InconsistentStartState) | |
size of joint name and joint position does not match in start state | |
TYPED_TEST (TrajectoryGeneratorCommonTest, StartPostionOutOfLimit) | |
joint position out of limit in start state | |
TYPED_TEST (TrajectoryGeneratorCommonTest, StartPositionVelocityNoneZero) | |
Check that no trajectory is generated if a start velocity is given. | |
TYPED_TEST (TrajectoryGeneratorCommonTest, EmptyGoalConstraints) | |
goal constraints is empty | |
TYPED_TEST (TrajectoryGeneratorCommonTest, MultipleGoals) | |
multiple goals | |
TYPED_TEST (TrajectoryGeneratorCommonTest, InvalideJointNameInGoal) | |
invalid joint name in joint constraint | |
TYPED_TEST (TrajectoryGeneratorCommonTest, MissingJointConstraint) | |
MissingJointConstraint. | |
TYPED_TEST (TrajectoryGeneratorCommonTest, InvalideJointPositionInGoal) | |
invalid joint position in joint constraint | |
TYPED_TEST (TrajectoryGeneratorCommonTest, InvalidLinkNameInCartesianGoal) | |
invalid link name in Cartesian goal constraint | |
TYPED_TEST (TrajectoryGeneratorCommonTest, EmptyPrimitivePoses) | |
no pose set in position constraint | |
int | main (int argc, char **argv) |
Variables | |
const std::string | PARAM_MODEL_NO_GRIPPER_NAME { "robot_description" } |
const std::string | PARAM_MODEL_WITH_GRIPPER_NAME { "robot_description_pg70" } |
const std::string | PARAM_NAMESPACE_LIMITS { "robot_description_planning" } |
typedef ValueTypeContainer<pilz_industrial_motion_planner::TrajectoryGeneratorCIRC, 0> CIRC_NO_GRIPPER |
Definition at line 82 of file unittest_trajectory_generator_common.cpp.
typedef ValueTypeContainer<pilz_industrial_motion_planner::TrajectoryGeneratorCIRC, 1> CIRC_WITH_GRIPPER |
Definition at line 83 of file unittest_trajectory_generator_common.cpp.
typedef ValueTypeContainer<pilz_industrial_motion_planner::TrajectoryGeneratorLIN, 0> LIN_NO_GRIPPER |
Definition at line 80 of file unittest_trajectory_generator_common.cpp.
typedef ValueTypeContainer<pilz_industrial_motion_planner::TrajectoryGeneratorLIN, 1> LIN_WITH_GRIPPER |
Definition at line 81 of file unittest_trajectory_generator_common.cpp.
typedef ValueTypeContainer<pilz_industrial_motion_planner::TrajectoryGeneratorPTP, 0> PTP_NO_GRIPPER |
Definition at line 78 of file unittest_trajectory_generator_common.cpp.
typedef ValueTypeContainer<pilz_industrial_motion_planner::TrajectoryGeneratorPTP, 1> PTP_WITH_GRIPPER |
Definition at line 79 of file unittest_trajectory_generator_common.cpp.
typedef ::testing::Types<PTP_NO_GRIPPER, PTP_WITH_GRIPPER, LIN_NO_GRIPPER, LIN_WITH_GRIPPER, CIRC_NO_GRIPPER, CIRC_WITH_GRIPPER> TrajectoryGeneratorCommonTestTypes |
Definition at line 87 of file unittest_trajectory_generator_common.cpp.
typedef ::testing::Types<PTP_NO_GRIPPER, LIN_NO_GRIPPER, CIRC_NO_GRIPPER> TrajectoryGeneratorCommonTestTypesNoGripper |
Definition at line 89 of file unittest_trajectory_generator_common.cpp.
typedef ::testing::Types<PTP_WITH_GRIPPER, LIN_WITH_GRIPPER, CIRC_WITH_GRIPPER> TrajectoryGeneratorCommonTestTypesWithGripper |
Definition at line 92 of file unittest_trajectory_generator_common.cpp.
int main | ( | int | argc, |
char ** | argv | ||
) |
Definition at line 443 of file unittest_trajectory_generator_common.cpp.
TYPED_TEST | ( | TrajectoryGeneratorCommonTest | , |
EmptyGoalConstraints | |||
) |
goal constraints is empty
Definition at line 306 of file unittest_trajectory_generator_common.cpp.
TYPED_TEST | ( | TrajectoryGeneratorCommonTest | , |
EmptyJointNamesInStartState | |||
) |
Test invalid motion plan request for all trajectory generators.
Test if there is a valid inverse kinematics solver for this planning group You can only test this case by commenting the planning_context.launch in the .test file //TODO create a separate robot model without ik solver and use it to create a trajectory generator
test the case of empty joint names in start state
Definition at line 262 of file unittest_trajectory_generator_common.cpp.
TYPED_TEST | ( | TrajectoryGeneratorCommonTest | , |
EmptyPrimitivePoses | |||
) |
no pose set in position constraint
Definition at line 426 of file unittest_trajectory_generator_common.cpp.
TYPED_TEST | ( | TrajectoryGeneratorCommonTest | , |
InconsistentStartState | |||
) |
size of joint name and joint position does not match in start state
Definition at line 272 of file unittest_trajectory_generator_common.cpp.
TYPED_TEST | ( | TrajectoryGeneratorCommonTest | , |
InvalideJointNameInGoal | |||
) |
invalid joint name in joint constraint
Definition at line 360 of file unittest_trajectory_generator_common.cpp.
TYPED_TEST | ( | TrajectoryGeneratorCommonTest | , |
InvalideJointPositionInGoal | |||
) |
invalid joint position in joint constraint
Definition at line 384 of file unittest_trajectory_generator_common.cpp.
TYPED_TEST | ( | TrajectoryGeneratorCommonTest | , |
InvalideScalingFactor | |||
) |
test invalid scaling factor. The scaling factor must be in the range of [0.0001, 1]
Definition at line 192 of file unittest_trajectory_generator_common.cpp.
TYPED_TEST | ( | TrajectoryGeneratorCommonTest | , |
InvalidGroupName | |||
) |
Test invalid motion plan request for all trajectory generators.
Definition at line 217 of file unittest_trajectory_generator_common.cpp.
TYPED_TEST | ( | TrajectoryGeneratorCommonTest | , |
InvalidLinkNameInCartesianGoal | |||
) |
invalid link name in Cartesian goal constraint
Definition at line 394 of file unittest_trajectory_generator_common.cpp.
TYPED_TEST | ( | TrajectoryGeneratorCommonTest | , |
MissingJointConstraint | |||
) |
MissingJointConstraint.
Definition at line 372 of file unittest_trajectory_generator_common.cpp.
TYPED_TEST | ( | TrajectoryGeneratorCommonTest | , |
MultipleGoals | |||
) |
multiple goals
Definition at line 316 of file unittest_trajectory_generator_common.cpp.
TYPED_TEST | ( | TrajectoryGeneratorCommonTest | , |
StartPositionVelocityNoneZero | |||
) |
Check that no trajectory is generated if a start velocity is given.
Definition at line 296 of file unittest_trajectory_generator_common.cpp.
TYPED_TEST | ( | TrajectoryGeneratorCommonTest | , |
StartPostionOutOfLimit | |||
) |
joint position out of limit in start state
Definition at line 282 of file unittest_trajectory_generator_common.cpp.
TYPED_TEST | ( | TrajectoryGeneratorCommonTestNoGripper | , |
GripperGroup | |||
) |
Test invalid motion plan request for all trajectory generators.
Definition at line 227 of file unittest_trajectory_generator_common.cpp.
TYPED_TEST_SUITE | ( | TrajectoryGeneratorCommonTest | , |
TrajectoryGeneratorCommonTestTypes | |||
) |
TYPED_TEST_SUITE | ( | TrajectoryGeneratorCommonTestNoGripper | , |
TrajectoryGeneratorCommonTestTypesNoGripper | |||
) |
const std::string PARAM_MODEL_NO_GRIPPER_NAME { "robot_description" } |
Definition at line 58 of file unittest_trajectory_generator_common.cpp.
const std::string PARAM_MODEL_WITH_GRIPPER_NAME { "robot_description_pg70" } |
Definition at line 59 of file unittest_trajectory_generator_common.cpp.
const std::string PARAM_NAMESPACE_LIMITS { "robot_description_planning" } |
Definition at line 60 of file unittest_trajectory_generator_common.cpp.