Public Member Functions | Private Member Functions | Private Attributes
ompl_ros_interface::OmplRosRPYIKStateTransformer Class Reference

#include <ompl_ros_rpy_ik_state_transformer.h>

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

List of all members.

Public Member Functions

virtual bool configureOnRequest (const arm_navigation_msgs::GetMotionPlan::Request &request, arm_navigation_msgs::GetMotionPlan::Response &response)
 Configure the transformer when a request is received. This is typically a one time configuration for each planning request.
virtual bool forwardTransform (const arm_navigation_msgs::RobotState &robot_state, ompl::base::State &ompl_state)
 Compute the forward transform (from physical state to planning state)
virtual
arm_navigation_msgs::RobotState 
getDefaultState ()
 Get a default physical state.
virtual bool initialize ()
 Custom initialization can be performed here.
virtual bool inverseTransform (const ompl::base::State &ompl_state, arm_navigation_msgs::RobotState &robot_state)
 Compute the inverse transform (from planning state to physical state)
 OmplRosRPYIKStateTransformer (const ompl::base::StateSpacePtr &state_space, const planning_models::KinematicModel::JointModelGroup *physical_joint_model_group)
 ~OmplRosRPYIKStateTransformer ()

Private Member Functions

double generateRandomNumber (const double &min, const double &max)
void generateRandomState (arm_navigation_msgs::RobotState &robot_state)
void omplStateToPose (const ompl::base::State &ompl_state, geometry_msgs::Pose &pose)

Private Attributes

ompl_ros_interface::OmplStateToRobotStateMapping ompl_state_to_robot_state_mapping_
int pitch_index_
int real_vector_index_
ompl_ros_interface::RobotStateToOmplStateMapping robot_state_to_ompl_state_mapping_
int roll_index_
boost::shared_ptr
< ompl::base::ScopedState
< ompl::base::CompoundStateSpace > > 
scoped_state_
arm_navigation_msgs::RobotState seed_state_
arm_navigation_msgs::RobotState solution_state_
int x_index_
int y_index_
int yaw_index_
int z_index_

Detailed Description

Definition at line 50 of file ompl_ros_rpy_ik_state_transformer.h.


Constructor & Destructor Documentation

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

Definition at line 57 of file ompl_ros_rpy_ik_state_transformer.h.

Definition at line 61 of file ompl_ros_rpy_ik_state_transformer.h.


Member Function Documentation

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

Implements ompl_ros_interface::OmplRosIKStateTransformer.

Definition at line 80 of file ompl_ros_rpy_ik_state_transformer.cpp.

bool ompl_ros_interface::OmplRosRPYIKStateTransformer::forwardTransform ( const arm_navigation_msgs::RobotState robot_state,
ompl::base::State &  ompl_state 
) [virtual]

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

Implements ompl_ros_interface::OmplRosIKStateTransformer.

Definition at line 119 of file ompl_ros_rpy_ik_state_transformer.cpp.

double ompl_ros_interface::OmplRosRPYIKStateTransformer::generateRandomNumber ( const double &  min,
const double &  max 
) [private]

Definition at line 167 of file ompl_ros_rpy_ik_state_transformer.cpp.

Definition at line 156 of file ompl_ros_rpy_ik_state_transformer.cpp.

Get a default physical state.

Implements ompl_ros_interface::OmplRosIKStateTransformer.

Definition at line 141 of file ompl_ros_rpy_ik_state_transformer.cpp.

Custom initialization can be performed here.

Implements ompl_ros_interface::OmplRosIKStateTransformer.

Definition at line 42 of file ompl_ros_rpy_ik_state_transformer.cpp.

bool ompl_ros_interface::OmplRosRPYIKStateTransformer::inverseTransform ( const ompl::base::State &  ompl_state,
arm_navigation_msgs::RobotState robot_state 
) [virtual]

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

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

Implements ompl_ros_interface::OmplRosIKStateTransformer.

Definition at line 87 of file ompl_ros_rpy_ik_state_transformer.cpp.

void ompl_ros_interface::OmplRosRPYIKStateTransformer::omplStateToPose ( const ompl::base::State &  ompl_state,
geometry_msgs::Pose pose 
) [private]

Definition at line 125 of file ompl_ros_rpy_ik_state_transformer.cpp.


Member Data Documentation

Definition at line 95 of file ompl_ros_rpy_ik_state_transformer.h.

Definition at line 92 of file ompl_ros_rpy_ik_state_transformer.h.

Definition at line 90 of file ompl_ros_rpy_ik_state_transformer.h.

Definition at line 96 of file ompl_ros_rpy_ik_state_transformer.h.

Definition at line 92 of file ompl_ros_rpy_ik_state_transformer.h.

boost::shared_ptr<ompl::base::ScopedState<ompl::base::CompoundStateSpace> > ompl_ros_interface::OmplRosRPYIKStateTransformer::scoped_state_ [private]

Definition at line 93 of file ompl_ros_rpy_ik_state_transformer.h.

Definition at line 91 of file ompl_ros_rpy_ik_state_transformer.h.

Definition at line 91 of file ompl_ros_rpy_ik_state_transformer.h.

Definition at line 92 of file ompl_ros_rpy_ik_state_transformer.h.

Definition at line 92 of file ompl_ros_rpy_ik_state_transformer.h.

Definition at line 92 of file ompl_ros_rpy_ik_state_transformer.h.

Definition at line 92 of file ompl_ros_rpy_ik_state_transformer.h.


The documentation for this class was generated from the following files:


ompl_ros_interface
Author(s): Sachin Chitta
autogenerated on Mon Dec 2 2013 12:38:54