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

Generic implementation of the tests that can be executed on different robots. More...

Inheritance diagram for TestStateValidityChecker:
Inheritance graph
[legend]
Collaboration diagram for TestStateValidityChecker:
Collaboration graph
[legend]

Public Member Functions

 TestStateValidityChecker (const std::string &robot_name, const std::string &group_name)
 
void testConstructor ()
 
void testJointLimits (const std::vector< double > &position_in_limits)
 
void testSelfCollision (const std::vector< double > &position_in_self_collision)
 
 TestStateValidityChecker (const std::string &robot_name, const std::string &group_name)
 
void testConstructor ()
 
void testJointLimits (const std::vector< double > &position_in_limits)
 
void testSelfCollision (const std::vector< double > &position_in_self_collision)
 
void testPathConstraints (const std::vector< double > &position_in_joint_limits)
 

Protected Member Functions

void SetUp () override
 
void TearDown () override
 
void setupStateSpace ()
 
void setupPlanningContext ()
 
void SetUp () override
 
void setupStateSpace ()
 
void setupPlanningContext ()
 
moveit_msgs::msg::PositionConstraint createPositionConstraint (std::array< double, 3 > position, std::array< double, 3 > dimensions)
 Helper function to create a position constraint. More...
 
- Protected Member Functions inherited from ompl_interface_testing::LoadTestRobot
 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

moveit::core::RobotStatePtr initial_robot_state_
 
ompl_interface::ModelBasedStateSpacePtr state_space_
 
ompl_interface::ModelBasedPlanningContextSpecification planning_context_spec_
 
ompl_interface::ModelBasedPlanningContextPtr planning_context_
 
planning_scene::PlanningScenePtr planning_scene_
 
ompl::base::ConstrainedStateSpacePtr constrained_state_space_
 
- Protected Attributes inherited from ompl_interface_testing::LoadTestRobot
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

Generic implementation of the tests that can be executed on different robots.

Definition at line 88 of file test_constrained_state_validity_checker.cpp.

Constructor & Destructor Documentation

◆ TestStateValidityChecker() [1/2]

TestStateValidityChecker::TestStateValidityChecker ( const std::string &  robot_name,
const std::string &  group_name 
)
inline

Definition at line 91 of file test_constrained_state_validity_checker.cpp.

◆ TestStateValidityChecker() [2/2]

TestStateValidityChecker::TestStateValidityChecker ( const std::string &  robot_name,
const std::string &  group_name 
)
inline

Definition at line 88 of file test_state_validity_checker.cpp.

Member Function Documentation

◆ createPositionConstraint()

moveit_msgs::msg::PositionConstraint TestStateValidityChecker::createPositionConstraint ( std::array< double, 3 >  position,
std::array< double, 3 >  dimensions 
)
inlineprotected

Helper function to create a position constraint.

Definition at line 231 of file test_state_validity_checker.cpp.

Here is the caller graph for this function:

◆ SetUp() [1/2]

void TestStateValidityChecker::SetUp ( )
inlineoverrideprotected

Definition at line 200 of file test_constrained_state_validity_checker.cpp.

Here is the call graph for this function:

◆ SetUp() [2/2]

void TestStateValidityChecker::SetUp ( )
inlineoverrideprotected

Definition at line 200 of file test_state_validity_checker.cpp.

Here is the call graph for this function:

◆ setupPlanningContext() [1/2]

void TestStateValidityChecker::setupPlanningContext ( )
inlineprotected

Definition at line 222 of file test_constrained_state_validity_checker.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ setupPlanningContext() [2/2]

void TestStateValidityChecker::setupPlanningContext ( )
inlineprotected

Definition at line 214 of file test_state_validity_checker.cpp.

Here is the call graph for this function:

◆ setupStateSpace() [1/2]

void TestStateValidityChecker::setupStateSpace ( )
inlineprotected

Definition at line 211 of file test_constrained_state_validity_checker.cpp.

Here is the caller graph for this function:

◆ setupStateSpace() [2/2]

void TestStateValidityChecker::setupStateSpace ( )
inlineprotected

Definition at line 207 of file test_state_validity_checker.cpp.

◆ TearDown()

void TestStateValidityChecker::TearDown ( )
inlineoverrideprotected

Definition at line 207 of file test_constrained_state_validity_checker.cpp.

◆ testConstructor() [1/2]

void TestStateValidityChecker::testConstructor ( )
inline

Definition at line 98 of file test_constrained_state_validity_checker.cpp.

◆ testConstructor() [2/2]

void TestStateValidityChecker::testConstructor ( )
inline

Definition at line 93 of file test_state_validity_checker.cpp.

◆ testJointLimits() [1/2]

void TestStateValidityChecker::testJointLimits ( const std::vector< double > &  position_in_limits)
inline

Definition at line 104 of file test_constrained_state_validity_checker.cpp.

Here is the call graph for this function:

◆ testJointLimits() [2/2]

void TestStateValidityChecker::testJointLimits ( const std::vector< double > &  position_in_limits)
inline

This test takes a state that is inside the joint limits and collision free as input.

Definition at line 100 of file test_state_validity_checker.cpp.

Here is the call graph for this function:

◆ testPathConstraints()

void TestStateValidityChecker::testPathConstraints ( const std::vector< double > &  position_in_joint_limits)
inline

Definition at line 155 of file test_state_validity_checker.cpp.

Here is the call graph for this function:

◆ testSelfCollision() [1/2]

void TestStateValidityChecker::testSelfCollision ( const std::vector< double > &  position_in_self_collision)
inline

Definition at line 156 of file test_constrained_state_validity_checker.cpp.

Here is the call graph for this function:

◆ testSelfCollision() [2/2]

void TestStateValidityChecker::testSelfCollision ( const std::vector< double > &  position_in_self_collision)
inline

This test takes a state that is known to be in self-collision and inside the joint limits as input.

Definition at line 131 of file test_state_validity_checker.cpp.

Here is the call graph for this function:

Member Data Documentation

◆ constrained_state_space_

ompl::base::ConstrainedStateSpacePtr TestStateValidityChecker::constrained_state_space_
protected

Definition at line 255 of file test_constrained_state_validity_checker.cpp.

◆ initial_robot_state_

moveit::core::RobotStatePtr TestStateValidityChecker::initial_robot_state_
protected

Definition at line 248 of file test_constrained_state_validity_checker.cpp.

◆ planning_context_

ompl_interface::ModelBasedPlanningContextPtr TestStateValidityChecker::planning_context_
protected

Definition at line 252 of file test_constrained_state_validity_checker.cpp.

◆ planning_context_spec_

ompl_interface::ModelBasedPlanningContextSpecification TestStateValidityChecker::planning_context_spec_
protected

Definition at line 251 of file test_constrained_state_validity_checker.cpp.

◆ planning_scene_

planning_scene::PlanningScenePtr TestStateValidityChecker::planning_scene_
protected

Definition at line 253 of file test_constrained_state_validity_checker.cpp.

◆ state_space_

ompl_interface::ModelBasedStateSpacePtr TestStateValidityChecker::state_space_
protected

Definition at line 250 of file test_constrained_state_validity_checker.cpp.


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