#include <gtest/gtest.h>
#include <memory>
#include <functional>
#include <pluginlib/class_loader.hpp>
#include <rclcpp/rclcpp.hpp>
#include <tf2_eigen/tf2_eigen.hpp>
#include <moveit/kinematics_base/kinematics_base.h>
#include <moveit/rdf_loader/rdf_loader.h>
#include <moveit/robot_model/robot_model.h>
#include <moveit/robot_state/robot_state.h>
#include <moveit/kdl_kinematics_plugin/kdl_kinematics_plugin.h>
#include <moveit/robot_state/conversions.h>
#include <moveit_msgs/msg/display_trajectory.hpp>
#include <moveit/robot_trajectory/robot_trajectory.h>
#include <moveit/utils/robot_model_test_utils.h>
Go to the source code of this file.
◆ EXPECT_NEAR_POSES
| #define EXPECT_NEAR_POSES |
( |
|
lhs, |
|
|
|
rhs, |
|
|
|
near |
|
) |
| |
Value: SCOPED_TRACE("EXPECT_NEAR_POSES(" #lhs ", " #rhs ")"); \
GTEST_ASSERT_(expectNearHelper(#lhs, #rhs, #near, lhs, rhs, near), GTEST_NONFATAL_FAILURE_);
Definition at line 304 of file test_kinematics_plugin.cpp.
◆ main()
| int main |
( |
int |
argc, |
|
|
char ** |
argv |
|
) |
| |
◆ TEST_F() [1/8]
◆ TEST_F() [2/8]
◆ TEST_F() [3/8]
◆ TEST_F() [4/8]
◆ TEST_F() [5/8]
◆ TEST_F() [6/8]
◆ TEST_F() [7/8]
◆ TEST_F() [8/8]
◆ DEFAULT_SEARCH_DISCRETIZATION
| const double DEFAULT_SEARCH_DISCRETIZATION = 0.01f |
◆ EXPECTED_SUCCESS_RATE
| const double EXPECTED_SUCCESS_RATE = 0.8 |
◆ ROBOT_DESCRIPTION_PARAM
| const std::string ROBOT_DESCRIPTION_PARAM = "robot_description" |