moveit2
The MoveIt Motion Planning Framework for ROS 2.
|
#include <memory>
#include <gtest/gtest.h>
#include <moveit/kinematic_constraints/utils.h>
#include <moveit/robot_model/robot_model.h>
#include <moveit/robot_model_loader/robot_model_loader.h>
#include <moveit/robot_state/conversions.h>
#include <tf2_eigen/tf2_eigen.hpp>
#include <tf2_geometry_msgs/tf2_geometry_msgs.hpp>
#include <pilz_industrial_motion_planner_testutils/command_types_typedef.h>
#include <pilz_industrial_motion_planner_testutils/sequence.h>
#include <pilz_industrial_motion_planner_testutils/xml_testdata_loader.h>
#include <pilz_industrial_motion_planner/joint_limits_aggregator.h>
#include <pilz_industrial_motion_planner/trajectory_blend_request.h>
#include <pilz_industrial_motion_planner/trajectory_blend_response.h>
#include <pilz_industrial_motion_planner/trajectory_blender_transition_window.h>
#include <pilz_industrial_motion_planner/trajectory_generator_lin.h>
#include "test_utils.h"
#include <rclcpp/rclcpp.hpp>
Go to the source code of this file.
Classes | |
class | TrajectoryBlenderTransitionWindowTest |
Functions | |
TEST_F (TrajectoryBlenderTransitionWindowTest, testInvalidGroupName) | |
Tests the blending of two trajectories with an invalid group name. | |
TEST_F (TrajectoryBlenderTransitionWindowTest, testInvalidTargetLink) | |
Tests the blending of two trajectories with an invalid target link. | |
TEST_F (TrajectoryBlenderTransitionWindowTest, testNegativeRadius) | |
Tests the blending of two trajectories with a negative blending radius. | |
TEST_F (TrajectoryBlenderTransitionWindowTest, testZeroRadius) | |
Tests the blending of two trajectories with zero blending radius. | |
TEST_F (TrajectoryBlenderTransitionWindowTest, testDifferentSamplingTimes) | |
Tests the blending of two trajectories with differenent sampling times. | |
TEST_F (TrajectoryBlenderTransitionWindowTest, testNonUniformSamplingTime) | |
Tests the blending of two trajectories with one trajectory having non-uniform sampling time (apart from the last sample, which is ignored). | |
TEST_F (TrajectoryBlenderTransitionWindowTest, testNotIntersectingTrajectories) | |
Tests the blending of two trajectories which do not intersect. | |
TEST_F (TrajectoryBlenderTransitionWindowTest, testNonStationaryPoint) | |
Tests the blending of two cartesian trajectories with the shared point (last point of first, first point of second trajectory) having a non-zero velocity. | |
TEST_F (TrajectoryBlenderTransitionWindowTest, testTraj1InsideBlendRadius) | |
Tests the blending of two cartesian trajectories where the first trajectory is completely within the sphere defined by the blend radius. | |
TEST_F (TrajectoryBlenderTransitionWindowTest, testTraj2InsideBlendRadius) | |
Tests the blending of two cartesian trajectories where the second trajectory is completely within the sphere defined by the blend radius. | |
TEST_F (TrajectoryBlenderTransitionWindowTest, testLinLinBlending) | |
Tests the blending of two cartesian linear trajectories using robot model. | |
TEST_F (TrajectoryBlenderTransitionWindowTest, testOverlappingBlendTrajectories) | |
Tests the blending of two cartesian linear trajectories which have an overlap in the blending sphere using robot model. To be precise, the trajectories exactly lie on top of each other. | |
TEST_F (TrajectoryBlenderTransitionWindowTest, testNonLinearBlending) | |
Tests the blending of two cartesian trajectories which differ from a straight line. | |
int | main (int argc, char **argv) |
int main | ( | int | argc, |
char ** | argv | ||
) |
Definition at line 724 of file unittest_trajectory_blender_transition_window.cpp.
TEST_F | ( | TrajectoryBlenderTransitionWindowTest | , |
testDifferentSamplingTimes | |||
) |
Tests the blending of two trajectories with differenent sampling times.
Test Sequence:
Expected Results:
Definition at line 309 of file unittest_trajectory_blender_transition_window.cpp.
TEST_F | ( | TrajectoryBlenderTransitionWindowTest | , |
testInvalidGroupName | |||
) |
Tests the blending of two trajectories with an invalid group name.
Test Sequence:
Expected Results:
Definition at line 191 of file unittest_trajectory_blender_transition_window.cpp.
TEST_F | ( | TrajectoryBlenderTransitionWindowTest | , |
testInvalidTargetLink | |||
) |
Tests the blending of two trajectories with an invalid target link.
Test Sequence:
Expected Results:
Definition at line 220 of file unittest_trajectory_blender_transition_window.cpp.
TEST_F | ( | TrajectoryBlenderTransitionWindowTest | , |
testLinLinBlending | |||
) |
Tests the blending of two cartesian linear trajectories using robot model.
Test Sequence:
Expected Results:
Definition at line 538 of file unittest_trajectory_blender_transition_window.cpp.
TEST_F | ( | TrajectoryBlenderTransitionWindowTest | , |
testNegativeRadius | |||
) |
Tests the blending of two trajectories with a negative blending radius.
Test Sequence:
Expected Results:
Definition at line 250 of file unittest_trajectory_blender_transition_window.cpp.
TEST_F | ( | TrajectoryBlenderTransitionWindowTest | , |
testNonLinearBlending | |||
) |
Tests the blending of two cartesian trajectories which differ from a straight line.
Test Sequence:
Expected Results:
Definition at line 627 of file unittest_trajectory_blender_transition_window.cpp.
TEST_F | ( | TrajectoryBlenderTransitionWindowTest | , |
testNonStationaryPoint | |||
) |
Tests the blending of two cartesian trajectories with the shared point (last point of first, first point of second trajectory) having a non-zero velocity.
Test Sequence:
Definition at line 427 of file unittest_trajectory_blender_transition_window.cpp.
TEST_F | ( | TrajectoryBlenderTransitionWindowTest | , |
testNonUniformSamplingTime | |||
) |
Tests the blending of two trajectories with one trajectory having non-uniform sampling time (apart from the last sample, which is ignored).
Test Sequence:
Expected Results:
Definition at line 362 of file unittest_trajectory_blender_transition_window.cpp.
TEST_F | ( | TrajectoryBlenderTransitionWindowTest | , |
testNotIntersectingTrajectories | |||
) |
Tests the blending of two trajectories which do not intersect.
Test Sequence:
Expected Results:
Definition at line 396 of file unittest_trajectory_blender_transition_window.cpp.
TEST_F | ( | TrajectoryBlenderTransitionWindowTest | , |
testOverlappingBlendTrajectories | |||
) |
Tests the blending of two cartesian linear trajectories which have an overlap in the blending sphere using robot model. To be precise, the trajectories exactly lie on top of each other.
Test Sequence:
Expected Results:
Definition at line 581 of file unittest_trajectory_blender_transition_window.cpp.
TEST_F | ( | TrajectoryBlenderTransitionWindowTest | , |
testTraj1InsideBlendRadius | |||
) |
Tests the blending of two cartesian trajectories where the first trajectory is completely within the sphere defined by the blend radius.
Test Sequence:
Expected Results:
Definition at line 464 of file unittest_trajectory_blender_transition_window.cpp.
TEST_F | ( | TrajectoryBlenderTransitionWindowTest | , |
testTraj2InsideBlendRadius | |||
) |
Tests the blending of two cartesian trajectories where the second trajectory is completely within the sphere defined by the blend radius.
Test Sequence:
Expected Results:
Definition at line 501 of file unittest_trajectory_blender_transition_window.cpp.
TEST_F | ( | TrajectoryBlenderTransitionWindowTest | , |
testZeroRadius | |||
) |
Tests the blending of two trajectories with zero blending radius.
Test Sequence:
Expected Results:
Definition at line 279 of file unittest_trajectory_blender_transition_window.cpp.