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. More... | |
TEST_F (TrajectoryBlenderTransitionWindowTest, testInvalidTargetLink) | |
Tests the blending of two trajectories with an invalid target link. More... | |
TEST_F (TrajectoryBlenderTransitionWindowTest, testNegativeRadius) | |
Tests the blending of two trajectories with a negative blending radius. More... | |
TEST_F (TrajectoryBlenderTransitionWindowTest, testZeroRadius) | |
Tests the blending of two trajectories with zero blending radius. More... | |
TEST_F (TrajectoryBlenderTransitionWindowTest, testDifferentSamplingTimes) | |
Tests the blending of two trajectories with differenent sampling times. More... | |
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). More... | |
TEST_F (TrajectoryBlenderTransitionWindowTest, testNotIntersectingTrajectories) | |
Tests the blending of two trajectories which do not intersect. More... | |
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. More... | |
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. More... | |
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. More... | |
TEST_F (TrajectoryBlenderTransitionWindowTest, testLinLinBlending) | |
Tests the blending of two cartesian linear trajectories using robot model. More... | |
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. More... | |
TEST_F (TrajectoryBlenderTransitionWindowTest, testNonLinearBlending) | |
Tests the blending of two cartesian trajectories which differ from a straight line. More... | |
int | main (int argc, char **argv) |
int main | ( | int | argc, |
char ** | argv | ||
) |
Definition at line 720 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 306 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 188 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 217 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 534 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 247 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 623 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 423 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 358 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 392 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 577 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 460 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 497 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 276 of file unittest_trajectory_blender_transition_window.cpp.