moveit2
The MoveIt Motion Planning Framework for ROS 2.
Protected Member Functions | Protected Attributes | List of all members
ompl_interface_testing::LoadTestRobot Class Reference

Robot independent test class setup. More...

#include <load_test_robot.h>

Inheritance diagram for ompl_interface_testing::LoadTestRobot:
Inheritance graph
[legend]
Collaboration diagram for ompl_interface_testing::LoadTestRobot:
Collaboration graph
[legend]

Protected Member Functions

 LoadTestRobot (const std::string &robot_name, const std::string &group_name)
 
Eigen::VectorXd getRandomState () const
 
Eigen::VectorXd getDeterministicState () const
 Create a joint position vector with values 0.1, 0.2, 0.3, ... where the length depends on the number of joints in the robot. More...
 

Protected Attributes

std::string group_name_
 
std::string robot_name_
 
moveit::core::RobotModelPtr robot_model_
 
moveit::core::RobotStatePtr robot_state_
 
const moveit::core::JointModelGroupjoint_model_group_
 
std::size_t num_dofs_
 
std::string base_link_name_
 
std::string ee_link_name_
 

Detailed Description

Robot independent test class setup.

The desired robot tests can be implemented in a derived class in a generic way.

It is implemented this way to avoid the ros specific test framework outside moveit_ros.

(This is an (uglier) alternative to using the rostest framework and reading the robot settings from the parameter server. Then we have several rostest launch files that load the parameters for a specific robot and run the same compiled tests for all robots.)

based on https://stackoverflow.com/questions/38207346/specify-constructor-arguments-for-a-google-test-fixture/38218657 (answer by PiotrNycz)

— example.cpp —

#include <gtest/gtest.h> #include "load_test_robot.h"

class GenericTests : public ompl_interface_testing::LoadTestRobot, public testing::Test { public: GenericTests(const std::string& robot_name, const std::string& group_name) : LoadTestRobot(robot_name, group_name) { } void SetUp() override { } void TearDown() override { }

void someTest() { // use robot_model_, robot_state_, .. here EXPECT_TRUE(true); } };

// now you can run someTest() on different robots:

class PandaTest : public GenericTests { protected: PandaTest() : GenericTests("panda", "panda_arm") { } };

TEST_F(PandaTest, someTest) { someTest(); }

— end example.cpp —

Definition at line 98 of file load_test_robot.h.

Constructor & Destructor Documentation

◆ LoadTestRobot()

ompl_interface_testing::LoadTestRobot::LoadTestRobot ( const std::string &  robot_name,
const std::string &  group_name 
)
inlineprotected

Definition at line 101 of file load_test_robot.h.

Here is the call graph for this function:

Member Function Documentation

◆ getDeterministicState()

Eigen::VectorXd ompl_interface_testing::LoadTestRobot::getDeterministicState ( ) const
inlineprotected

Create a joint position vector with values 0.1, 0.2, 0.3, ... where the length depends on the number of joints in the robot.

Definition at line 129 of file load_test_robot.h.

Here is the caller graph for this function:

◆ getRandomState()

Eigen::VectorXd ompl_interface_testing::LoadTestRobot::getRandomState ( ) const
inlineprotected

Definition at line 118 of file load_test_robot.h.

Member Data Documentation

◆ base_link_name_

std::string ompl_interface_testing::LoadTestRobot::base_link_name_
protected

Definition at line 150 of file load_test_robot.h.

◆ ee_link_name_

std::string ompl_interface_testing::LoadTestRobot::ee_link_name_
protected

Definition at line 151 of file load_test_robot.h.

◆ group_name_

std::string ompl_interface_testing::LoadTestRobot::group_name_
protected

Definition at line 142 of file load_test_robot.h.

◆ joint_model_group_

const moveit::core::JointModelGroup* ompl_interface_testing::LoadTestRobot::joint_model_group_
protected

Definition at line 147 of file load_test_robot.h.

◆ num_dofs_

std::size_t ompl_interface_testing::LoadTestRobot::num_dofs_
protected

Definition at line 149 of file load_test_robot.h.

◆ robot_model_

moveit::core::RobotModelPtr ompl_interface_testing::LoadTestRobot::robot_model_
protected

Definition at line 145 of file load_test_robot.h.

◆ robot_name_

std::string ompl_interface_testing::LoadTestRobot::robot_name_
protected

Definition at line 143 of file load_test_robot.h.

◆ robot_state_

moveit::core::RobotStatePtr ompl_interface_testing::LoadTestRobot::robot_state_
protected

Definition at line 146 of file load_test_robot.h.


The documentation for this class was generated from the following file: