ompl_ros_interface::OmplRosTaskSpacePlanner Class Reference

A generic task space planner. More...

#include <ompl_ros_task_space_planner.h>

Inheritance diagram for ompl_ros_interface::OmplRosTaskSpacePlanner:
Inheritance graph
[legend]

List of all members.

Public Member Functions

 OmplRosTaskSpacePlanner ()
 ~OmplRosTaskSpacePlanner ()

Protected Member Functions

virtual bool constraintsToOmplState (const motion_planning_msgs::Constraints &constraints, ompl::base::ScopedState< ompl::base::CompoundStateSpace > &goal)
virtual
motion_planning_msgs::RobotTrajectory 
getSolutionPath ()=0
 Returns the solution path.
bool getSpaceFromParamServer (const ros::NodeHandle &node_handle, const std::string &space_name, ompl::base::StateSpacePtr &state_space, int &real_vector_index)
 Load a state space from the parameter server.
virtual bool initializePlanningStateSpace (ompl::base::StateSpacePtr &state_space)
 Initialize the planning state space.
virtual bool initializeStateValidityChecker (ompl_ros_interface::OmplRosStateValidityCheckerPtr &state_validity_checker)
 Initialize the state validity checker.
virtual bool isRequestValid (motion_planning_msgs::GetMotionPlan::Request &request, motion_planning_msgs::GetMotionPlan::Response &response)
 Returns whether the motion planning request is valid.
virtual bool setGoal (motion_planning_msgs::GetMotionPlan::Request &request, motion_planning_msgs::GetMotionPlan::Response &response)
 Set the goal state(s).
virtual bool setStart (motion_planning_msgs::GetMotionPlan::Request &request, motion_planning_msgs::GetMotionPlan::Response &response)
 Set the start state(s).

Protected Attributes

std::string end_effector_name_
std::string planning_frame_id_
boost::shared_ptr
< ompl_ros_interface::OmplRosStateTransformer
state_transformer_

Detailed Description

A generic task space planner.

Definition at line 53 of file ompl_ros_task_space_planner.h.


Constructor & Destructor Documentation

ompl_ros_interface::OmplRosTaskSpacePlanner::OmplRosTaskSpacePlanner (  )  [inline]

Definition at line 57 of file ompl_ros_task_space_planner.h.

ompl_ros_interface::OmplRosTaskSpacePlanner::~OmplRosTaskSpacePlanner (  )  [inline]

Definition at line 58 of file ompl_ros_task_space_planner.h.


Member Function Documentation

bool ompl_ros_interface::OmplRosTaskSpacePlanner::constraintsToOmplState ( const motion_planning_msgs::Constraints &  constraints,
ompl::base::ScopedState< ompl::base::CompoundStateSpace > &  goal 
) [protected, virtual]
virtual motion_planning_msgs::RobotTrajectory ompl_ros_interface::OmplRosTaskSpacePlanner::getSolutionPath (  )  [protected, pure virtual]
bool ompl_ros_interface::OmplRosTaskSpacePlanner::getSpaceFromParamServer ( const ros::NodeHandle &  node_handle,
const std::string &  space_name,
ompl::base::StateSpacePtr &  state_space,
int &  real_vector_index 
) [protected]

Load a state space from the parameter server.

Parameters:
node_handle - The node handle to load the state space information from
space_name - The name of the state space to initialize
state_space - The state space to use
real_vector_index - The index of the real vector state space in the state space (treated as a compound state space)

Definition at line 102 of file ompl_ros_task_space_planner.cpp.

bool ompl_ros_interface::OmplRosTaskSpacePlanner::initializePlanningStateSpace ( ompl::base::StateSpacePtr &  state_space  )  [protected, virtual]

Initialize the planning state space.

Implements ompl_ros_interface::OmplRosPlanningGroup.

Definition at line 41 of file ompl_ros_task_space_planner.cpp.

bool ompl_ros_interface::OmplRosTaskSpacePlanner::initializeStateValidityChecker ( ompl_ros_interface::OmplRosStateValidityCheckerPtr state_validity_checker  )  [protected, virtual]

Initialize the state validity checker.

Implements ompl_ros_interface::OmplRosPlanningGroup.

Reimplemented in ompl_ros_interface::OmplRosRPYIKTaskSpacePlanner.

Definition at line 271 of file ompl_ros_task_space_planner.cpp.

bool ompl_ros_interface::OmplRosTaskSpacePlanner::isRequestValid ( motion_planning_msgs::GetMotionPlan::Request &  request,
motion_planning_msgs::GetMotionPlan::Response &  response 
) [protected, virtual]

Returns whether the motion planning request is valid.

Implements ompl_ros_interface::OmplRosPlanningGroup.

Definition at line 184 of file ompl_ros_task_space_planner.cpp.

bool ompl_ros_interface::OmplRosTaskSpacePlanner::setGoal ( motion_planning_msgs::GetMotionPlan::Request &  request,
motion_planning_msgs::GetMotionPlan::Response &  response 
) [protected, virtual]

Set the goal state(s).

Implements ompl_ros_interface::OmplRosPlanningGroup.

Definition at line 217 of file ompl_ros_task_space_planner.cpp.

bool ompl_ros_interface::OmplRosTaskSpacePlanner::setStart ( motion_planning_msgs::GetMotionPlan::Request &  request,
motion_planning_msgs::GetMotionPlan::Response &  response 
) [protected, virtual]

Set the start state(s).

Implements ompl_ros_interface::OmplRosPlanningGroup.

Reimplemented in ompl_ros_interface::OmplRosRPYIKTaskSpacePlanner.

Definition at line 251 of file ompl_ros_task_space_planner.cpp.


Member Data Documentation

Definition at line 104 of file ompl_ros_task_space_planner.h.

Definition at line 112 of file ompl_ros_task_space_planner.h.


The documentation for this class was generated from the following files:
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator


ompl_ros_interface
Author(s): Sachin Chitta
autogenerated on Fri Jan 11 10:08:06 2013