ompl_ros_interface::OmplRosStateTransformer Class Reference

#include <ompl_ros_state_transformer.h>

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

List of all members.

Public Member Functions

virtual bool configureOnRequest (const motion_planning_msgs::GetMotionPlan::Request &request, motion_planning_msgs::GetMotionPlan::Response &response)=0
 Configure the transformer when a request is received. This is typically a one time configuration for each planning request.
virtual bool forwardTransform (const motion_planning_msgs::RobotState &robot_state, ompl::base::State &ompl_state)=0
 Compute the forward transform (from physical state to planning state).
virtual
motion_planning_msgs::RobotState 
getDefaultState ()=0
 Return a default state.
virtual std::string getFrame ()
 Return the frame in which planning state space is defined.
virtual bool initialize ()=0
 Custom initialization can be performed here.
virtual bool inverseTransform (const ompl::base::State &ompl_state, motion_planning_msgs::RobotState &robot_state)=0
 Compute the inverse transform (from planning state to physical state).
 OmplRosStateTransformer (const ompl::base::StateSpacePtr &state_space, const planning_models::KinematicModel::JointModelGroup *physical_joint_model_group)
 Default constructor.
 ~OmplRosStateTransformer ()
 Default constructor.

Protected Attributes

const
planning_models::KinematicModel::JointModelGroup * 
physical_joint_model_group_
ompl::base::StateSpacePtr state_space_

Detailed Description

Definition at line 58 of file ompl_ros_state_transformer.h.


Constructor & Destructor Documentation

ompl_ros_interface::OmplRosStateTransformer::OmplRosStateTransformer ( const ompl::base::StateSpacePtr &  state_space,
const planning_models::KinematicModel::JointModelGroup *  physical_joint_model_group 
) [inline]

Default constructor.

Parameters:
state_space - The state space that the planner is operating on
physical_joint_model_group - The "physical" joint model group that the planner is operating on
frame_id - The (possibly abstract) frame_id that the planner operates in. The frame_id in the planning request must match this frame_id.

Definition at line 67 of file ompl_ros_state_transformer.h.

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

Default constructor.

Definition at line 77 of file ompl_ros_state_transformer.h.


Member Function Documentation

virtual bool ompl_ros_interface::OmplRosStateTransformer::configureOnRequest ( const motion_planning_msgs::GetMotionPlan::Request &  request,
motion_planning_msgs::GetMotionPlan::Response &  response 
) [pure virtual]

Configure the transformer when a request is received. This is typically a one time configuration for each planning request.

Parameters:
request The request that the planner gets
response The response to the planning request

Implemented in ompl_ros_interface::OmplRosIKStateTransformer, and ompl_ros_interface::OmplRosRPYIKStateTransformer.

virtual bool ompl_ros_interface::OmplRosStateTransformer::forwardTransform ( const motion_planning_msgs::RobotState &  robot_state,
ompl::base::State &  ompl_state 
) [pure virtual]

Compute the forward transform (from physical state to planning state).

Parameters:
robot_State - the physical state
ompl_state - the corresponding planning state

Implemented in ompl_ros_interface::OmplRosIKStateTransformer, and ompl_ros_interface::OmplRosRPYIKStateTransformer.

virtual motion_planning_msgs::RobotState ompl_ros_interface::OmplRosStateTransformer::getDefaultState (  )  [pure virtual]
virtual std::string ompl_ros_interface::OmplRosStateTransformer::getFrame (  )  [inline, virtual]

Return the frame in which planning state space is defined.

Reimplemented in ompl_ros_interface::OmplRosIKStateTransformer.

Definition at line 112 of file ompl_ros_state_transformer.h.

virtual bool ompl_ros_interface::OmplRosStateTransformer::initialize (  )  [pure virtual]

Custom initialization can be performed here.

Implemented in ompl_ros_interface::OmplRosIKStateTransformer, and ompl_ros_interface::OmplRosRPYIKStateTransformer.

virtual bool ompl_ros_interface::OmplRosStateTransformer::inverseTransform ( const ompl::base::State &  ompl_state,
motion_planning_msgs::RobotState &  robot_state 
) [pure virtual]

Compute the inverse transform (from planning state to physical state).

Parameters:
ompl_state - the planning state
robot_State - the corresponding physical state

Implemented in ompl_ros_interface::OmplRosIKStateTransformer, and ompl_ros_interface::OmplRosRPYIKStateTransformer.


Member Data Documentation

const planning_models::KinematicModel::JointModelGroup* ompl_ros_interface::OmplRosStateTransformer::physical_joint_model_group_ [protected]

Definition at line 121 of file ompl_ros_state_transformer.h.

ompl::base::StateSpacePtr ompl_ros_interface::OmplRosStateTransformer::state_space_ [protected]

Definition at line 120 of file ompl_ros_state_transformer.h.


The documentation for this class was generated from the following file:
 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