Generic implementation of the tests that can be executed on different robots. More...
Public Member Functions | |
void | testPathConstraints (const std::vector< double > &start, const std::vector< double > &goal) |
TestPlanningContext (const std::string &robot_name, const std::string &group_name) | |
void | testSimpleRequest (const std::vector< double > &start, const std::vector< double > &goal) |
Protected Member Functions | |
moveit_msgs::OrientationConstraint | createOrientationConstraint (const geometry_msgs::Quaternion &nominal_orientation) |
Helper function to create a orientation constraint. More... | |
moveit_msgs::PositionConstraint | createPositionConstraint (std::array< double, 3 > position, std::array< double, 3 > dimensions) |
Helper function to create a position constraint. More... | |
planning_interface::MotionPlanRequest | createRequest (const std::vector< double > &start, const std::vector< double > &goal) const |
void | SetUp () override |
void | TearDown () override |
Protected Member Functions inherited from ompl_interface_testing::LoadTestRobot | |
LoadTestRobot (const std::string &robot_name, const std::string &group_name) | |
Protected Attributes | |
constraint_samplers::ConstraintSamplerManagerPtr | constraint_sampler_manager_ |
ros::NodeHandle | node_handle_ |
ompl_interface::ModelBasedPlanningContextPtr | planning_context_ |
ompl_interface::ModelBasedPlanningContextSpecification | planning_context_spec_ |
planning_scene::PlanningScenePtr | planning_scene_ |
ompl_interface::ModelBasedStateSpacePtr | state_space_ |
Protected Attributes inherited from ompl_interface_testing::LoadTestRobot | |
std::string | base_link_name_ |
std::string | ee_link_name_ |
const std::string | group_name_ |
const robot_state::JointModelGroup * | joint_model_group_ |
std::size_t | num_dofs_ |
moveit::core::RobotModelPtr | robot_model_ |
const std::string | robot_name_ |
robot_state::RobotStatePtr | robot_state_ |
Generic implementation of the tests that can be executed on different robots.
Test the creation of a ModelBasedPlanningContext through the PlanningContextManager.
The tests use a default robot state as start state, and then moves the last joint 0.1 radians/meters to create a joint goal. This creates an extremely simple planning problem to test general mechanics of the interface.
In the test with path constraints, we create an orientation constraint around the start orientation of the end-effector, with a tolerance on the rotation larger than the change in the last joint of the goal state. This makes sure the path constraints are easy to satisfy.
TODO(jeroendm) I also tried something similar with position constraints, but get a segmentation fault that occurs in the 'geometric_shapes' package, in the method 'useDimensions' in 'bodies.h'. git permalink: https://github.com/moveit/geometric_shapes/blob/df0478870b8592ce789ee1919f3124058c4327d7/include/geometric_shapes/bodies.h#L196
Definition at line 68 of file test_planning_context_manager.cpp.
|
inline |
Definition at line 103 of file test_planning_context_manager.cpp.
|
inlineprotected |
Helper function to create a orientation constraint.
Definition at line 307 of file test_planning_context_manager.cpp.
|
inlineprotected |
Helper function to create a position constraint.
Definition at line 281 of file test_planning_context_manager.cpp.
|
inlineprotected |
Create a planning request to plan from a given start state to a joint space goal.
Definition at line 256 of file test_planning_context_manager.cpp.
|
inlineoverrideprotected |
Definition at line 244 of file test_planning_context_manager.cpp.
|
inlineoverrideprotected |
Definition at line 251 of file test_planning_context_manager.cpp.
|
inline |
Definition at line 145 of file test_planning_context_manager.cpp.
|
inline |
Definition at line 112 of file test_planning_context_manager.cpp.
|
protected |
Definition at line 325 of file test_planning_context_manager.cpp.
|
protected |
Ideally we add an IK plugin to the joint_model_group_ to test the PoseModel state space, using the pluginlib to load the default KDL plugin? we need a node handle to call getPlanningRequest, but it is never used, as we disable the 'use_constraints_approximation' option.
Definition at line 333 of file test_planning_context_manager.cpp.
|
protected |
Definition at line 322 of file test_planning_context_manager.cpp.
|
protected |
Definition at line 321 of file test_planning_context_manager.cpp.
|
protected |
Definition at line 323 of file test_planning_context_manager.cpp.
|
protected |
Definition at line 320 of file test_planning_context_manager.cpp.