Classes | Public Member Functions | Static Public Attributes | Private Member Functions | Private Attributes
ompl_interface::PoseModelStateSpace Class Reference

#include <pose_model_state_space.h>

Inheritance diagram for ompl_interface::PoseModelStateSpace:
Inheritance graph
[legend]

List of all members.

Classes

struct  PoseComponent
class  StateType
 Add a tag to the state representation. More...

Public Member Functions

virtual ompl::base::State * allocState () const
bool computeStateFK (ompl::base::State *state) const
bool computeStateIK (ompl::base::State *state) const
bool computeStateK (ompl::base::State *state) const
virtual void copyState (ompl::base::State *destination, const ompl::base::State *source) const
virtual void copyToOMPLState (ompl::base::State *state, const robot_state::JointStateGroup *jsg) const
 Copy the data from a set of joint states to an OMPL state. The join states must be specified in the same order as the joint models in the constructor.
virtual double distance (const ompl::base::State *state1, const ompl::base::State *state2) const
virtual void freeState (ompl::base::State *state) const
virtual double getMaximumExtent () const
virtual void interpolate (const ompl::base::State *from, const ompl::base::State *to, const double t, ompl::base::State *state) const
 PoseModelStateSpace (const ModelBasedStateSpaceSpecification &spec)
virtual void sanityChecks () const
virtual void setPlanningVolume (double minX, double maxX, double minY, double maxY, double minZ, double maxZ)
 Set the planning volume for the possible SE2 and/or SE3 components of the state space.
virtual ~PoseModelStateSpace ()

Static Public Attributes

static const std::string PARAMETERIZATION_TYPE = "PoseModel"

Private Member Functions

virtual void afterStateSample (ompl::base::State *sample) const
void constructSpaceFromPoses ()

Private Attributes

double jump_factor_
std::vector< PoseComponentposes_

Detailed Description

Definition at line 45 of file pose_model_state_space.h.


Constructor & Destructor Documentation

Definition at line 43 of file pose_model_state_space.cpp.

Definition at line 60 of file pose_model_state_space.cpp.


Member Function Documentation

void ompl_interface::PoseModelStateSpace::afterStateSample ( ompl::base::State *  sample) const [private, virtual]

Reimplemented from ompl_interface::ModelBasedStateSpace.

Definition at line 299 of file pose_model_state_space.cpp.

ompl::base::State * ompl_interface::PoseModelStateSpace::allocState ( ) const [virtual]

Reimplemented from ompl_interface::ModelBasedStateSpace.

Definition at line 91 of file pose_model_state_space.cpp.

bool ompl_interface::PoseModelStateSpace::computeStateFK ( ompl::base::State *  state) const

Definition at line 259 of file pose_model_state_space.cpp.

bool ompl_interface::PoseModelStateSpace::computeStateIK ( ompl::base::State *  state) const

Definition at line 273 of file pose_model_state_space.cpp.

bool ompl_interface::PoseModelStateSpace::computeStateK ( ompl::base::State *  state) const

Definition at line 287 of file pose_model_state_space.cpp.

Definition at line 64 of file pose_model_state_space.cpp.

void ompl_interface::PoseModelStateSpace::copyState ( ompl::base::State *  destination,
const ompl::base::State *  source 
) const [virtual]

Reimplemented from ompl_interface::ModelBasedStateSpace.

Definition at line 103 of file pose_model_state_space.cpp.

void ompl_interface::PoseModelStateSpace::copyToOMPLState ( ompl::base::State *  state,
const robot_state::JointStateGroup jsg 
) const [virtual]

Copy the data from a set of joint states to an OMPL state. The join states must be specified in the same order as the joint models in the constructor.

Reimplemented from ompl_interface::ModelBasedStateSpace.

Definition at line 311 of file pose_model_state_space.cpp.

double ompl_interface::PoseModelStateSpace::distance ( const ompl::base::State *  state1,
const ompl::base::State *  state2 
) const [virtual]

Reimplemented from ompl_interface::ModelBasedStateSpace.

Definition at line 75 of file pose_model_state_space.cpp.

void ompl_interface::PoseModelStateSpace::freeState ( ompl::base::State *  state) const [virtual]

Reimplemented from ompl_interface::ModelBasedStateSpace.

Definition at line 98 of file pose_model_state_space.cpp.

double ompl_interface::PoseModelStateSpace::getMaximumExtent ( void  ) const [virtual]

Reimplemented from ompl_interface::ModelBasedStateSpace.

Definition at line 83 of file pose_model_state_space.cpp.

void ompl_interface::PoseModelStateSpace::interpolate ( const ompl::base::State *  from,
const ompl::base::State *  to,
const double  t,
ompl::base::State *  state 
) const [virtual]

Reimplemented from ompl_interface::ModelBasedStateSpace.

Definition at line 117 of file pose_model_state_space.cpp.

Definition at line 112 of file pose_model_state_space.cpp.

void ompl_interface::PoseModelStateSpace::setPlanningVolume ( double  minX,
double  maxX,
double  minY,
double  maxY,
double  minZ,
double  maxZ 
) [virtual]

Set the planning volume for the possible SE2 and/or SE3 components of the state space.

Reimplemented from ompl_interface::ModelBasedStateSpace.

Definition at line 156 of file pose_model_state_space.cpp.


Member Data Documentation

Definition at line 139 of file pose_model_state_space.h.

const std::string ompl_interface::PoseModelStateSpace::PARAMETERIZATION_TYPE = "PoseModel" [static]

Definition at line 49 of file pose_model_state_space.h.

Definition at line 138 of file pose_model_state_space.h.


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


ompl
Author(s): Ioan Sucan
autogenerated on Mon Oct 6 2014 11:12:04