Generic implementation of the tests that can be executed on different robots.
More...
Generic implementation of the tests that can be executed on different robots.
Definition at line 81 of file test_state_validity_checker.cpp.
◆ TestStateValidityChecker()
TestStateValidityChecker::TestStateValidityChecker |
( |
const std::string & |
robot_name, |
|
|
const std::string & |
group_name |
|
) |
| |
|
inline |
◆ createPositionConstraint()
moveit_msgs::PositionConstraint TestStateValidityChecker::createPositionConstraint |
( |
std::array< double, 3 > |
position, |
|
|
std::array< double, 3 > |
dimensions |
|
) |
| |
|
inlineprotected |
◆ SetUp()
void TestStateValidityChecker::SetUp |
( |
| ) |
|
|
inlineoverrideprotected |
◆ setupPlanningContext()
void TestStateValidityChecker::setupPlanningContext |
( |
| ) |
|
|
inlineprotected |
◆ setupStateSpace()
void TestStateValidityChecker::setupStateSpace |
( |
| ) |
|
|
inlineprotected |
◆ testConstructor()
void TestStateValidityChecker::testConstructor |
( |
| ) |
|
|
inline |
◆ testJointLimits()
void TestStateValidityChecker::testJointLimits |
( |
const std::vector< double > & |
position_in_limits | ) |
|
|
inline |
◆ testPathConstraints()
void TestStateValidityChecker::testPathConstraints |
( |
const std::vector< double > & |
position_in_joint_limits | ) |
|
|
inline |
◆ testSelfCollision()
void TestStateValidityChecker::testSelfCollision |
( |
const std::vector< double > & |
position_in_self_collision | ) |
|
|
inline |
◆ planning_context_
ompl_interface::ModelBasedPlanningContextPtr TestStateValidityChecker::planning_context_ |
|
protected |
◆ planning_context_spec_
◆ planning_scene_
planning_scene::PlanningScenePtr TestStateValidityChecker::planning_scene_ |
|
protected |
◆ state_space_
ompl_interface::ModelBasedStateSpacePtr TestStateValidityChecker::state_space_ |
|
protected |
The documentation for this class was generated from the following file: