ompl_ros_interface::OmplRosTaskSpaceValidityChecker Class Reference

This class implements a state validity checker in task space. More...

#include <ompl_ros_task_space_validity_checker.h>

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

List of all members.

Public Member Functions

virtual void configureOnRequest (planning_models::KinematicState *kinematic_state, planning_models::KinematicState::JointStateGroup *joint_state_group, const motion_planning_msgs::GetMotionPlan::Request &request)
 Configure the transformer when a request is received. This is typically a one time configuration for each planning request.
boost::shared_ptr
< ompl_ros_interface::OmplRosStateTransformer > & 
getStateTransformer ()
 Return a shared pointer to the state transformer used by this validity checker.
virtual bool isStateValid (const ompl::base::State *ompl_state)
virtual bool isValid (const ompl::base::State *ompl_state) const
 The callback function used by the planners to determine if a state is valid.
 OmplRosTaskSpaceValidityChecker (ompl::base::SpaceInformation *si, planning_environment::PlanningMonitor *planning_monitor, const std::string &parent_frame)
 Default constructor.
bool setStateTransformer (boost::shared_ptr< ompl_ros_interface::OmplRosStateTransformer > &state_transformer)
 Instantiate the state transformer.
 ~OmplRosTaskSpaceValidityChecker ()

Protected Member Functions

virtual bool initialize ()

Protected Attributes

std::string parent_frame_
motion_planning_msgs::RobotState robot_state_msg_
ompl_ros_interface::RobotStateToKinematicStateMapping robot_state_to_joint_state_group_mapping_
boost::shared_ptr
< ompl_ros_interface::OmplRosStateTransformer
state_transformer_

Detailed Description

This class implements a state validity checker in task space.

Definition at line 49 of file ompl_ros_task_space_validity_checker.h.


Constructor & Destructor Documentation

ompl_ros_interface::OmplRosTaskSpaceValidityChecker::OmplRosTaskSpaceValidityChecker ( ompl::base::SpaceInformation *  si,
planning_environment::PlanningMonitor *  planning_monitor,
const std::string &  parent_frame 
) [inline]

Default constructor.

Parameters:
si - The space information for this validity checker
planning_monitor - The planning monitor
mapping - The mapping between the ompl state and the kinematic state that the planning monitor will use

Definition at line 58 of file ompl_ros_task_space_validity_checker.h.

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

Definition at line 64 of file ompl_ros_task_space_validity_checker.h.


Member Function Documentation

void ompl_ros_interface::OmplRosTaskSpaceValidityChecker::configureOnRequest ( planning_models::KinematicState *  kinematic_state,
planning_models::KinematicState::JointStateGroup *  joint_state_group,
const motion_planning_msgs::GetMotionPlan::Request &  request 
) [virtual]

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

Parameters:
kinematic_state - The kinematic state corresponding to the current state of the robot
joint_state_group - The state of the joint group on which this validity checker will operate
request - The motion planning request

Reimplemented from ompl_ros_interface::OmplRosStateValidityChecker.

Definition at line 139 of file ompl_ros_task_space_validity_checker.cpp.

boost::shared_ptr<ompl_ros_interface::OmplRosStateTransformer>& ompl_ros_interface::OmplRosTaskSpaceValidityChecker::getStateTransformer (  )  [inline]

Return a shared pointer to the state transformer used by this validity checker.

Returns:
A shared pointer to the state transformer

Definition at line 89 of file ompl_ros_task_space_validity_checker.h.

bool ompl_ros_interface::OmplRosTaskSpaceValidityChecker::initialize (  )  [protected, virtual]

Definition at line 118 of file ompl_ros_task_space_validity_checker.cpp.

bool ompl_ros_interface::OmplRosTaskSpaceValidityChecker::isStateValid ( const ompl::base::State *  ompl_state  )  [virtual]
bool ompl_ros_interface::OmplRosTaskSpaceValidityChecker::isValid ( const ompl::base::State *  ompl_state  )  const [virtual]

The callback function used by the planners to determine if a state is valid.

Parameters:
ompl_state The state that needs to be checked

Implements ompl_ros_interface::OmplRosStateValidityChecker.

Definition at line 42 of file ompl_ros_task_space_validity_checker.cpp.

bool ompl_ros_interface::OmplRosTaskSpaceValidityChecker::setStateTransformer ( boost::shared_ptr< ompl_ros_interface::OmplRosStateTransformer > &  state_transformer  ) 

Instantiate the state transformer.

Parameters:
ompl_state An instance of the state transformer passed in for initialization
Returns:
false if an error has occured

Definition at line 123 of file ompl_ros_task_space_validity_checker.cpp.


Member Data Documentation

Definition at line 108 of file ompl_ros_task_space_validity_checker.h.

motion_planning_msgs::RobotState ompl_ros_interface::OmplRosTaskSpaceValidityChecker::robot_state_msg_ [protected]

Definition at line 107 of file ompl_ros_task_space_validity_checker.h.

Definition at line 111 of file ompl_ros_task_space_validity_checker.h.

Definition at line 110 of file ompl_ros_task_space_validity_checker.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