Classes | Public Member Functions | Protected Member Functions | Protected Attributes | Friends
ompl_interface::ModelBasedStateSpace Class Reference

#include <model_based_state_space.h>

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

List of all members.

Classes

class  StateType

Public Member Functions

virtual ompl::base::State * allocState () const
virtual ompl::base::StateSamplerPtr allocStateSampler () const
virtual ompl::base::StateSamplerPtr allocSubspaceStateSampler (const ompl::base::StateSpace *subspace) const
virtual void copyState (ompl::base::State *destination, const ompl::base::State *source) const
void copyToOMPLState (ompl::base::State *state, const robot_state::RobotState &kstate) const
 Copy the data from a value vector that corresponds to the state of the considered joint model group (or array of joints)
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 void copyToRobotState (robot_state::JointStateGroup *jsg, const ompl::base::State *state) const
 Copy the data from an OMPL state to a set of joint states. The join states must be specified in the same order as the joint models in the constructor.
void copyToRobotState (robot_state::RobotState &kstate, const ompl::base::State *state) const
 Copy the data from an OMPL state to a kinematic state. The join states must be specified in the same order as the joint models in the constructor. This function is implemented in terms of the previous definition with the same name.
virtual void deserialize (ompl::base::State *state, const void *serialization) const
virtual double distance (const ompl::base::State *state1, const ompl::base::State *state2) const
virtual void freeState (ompl::base::State *state) const
const
robot_model::JointModelGroup
getJointModelGroup () const
const std::string & getJointModelGroupName () const
const std::vector
< robot_model::JointModel::Bounds > & 
getJointsBounds () const
virtual double getMaximumExtent () const
const
robot_model::RobotModelConstPtr
getRobotModel () const
virtual unsigned int getSerializationLength () const
const
ModelBasedStateSpaceSpecification
getSpecification () const
double getTagSnapToSegment () const
virtual void interpolate (const ompl::base::State *from, const ompl::base::State *to, const double t, ompl::base::State *state) const
 ModelBasedStateSpace (const ModelBasedStateSpaceSpecification &spec)
virtual void printState (const ompl::base::State *state, std::ostream &out) const
virtual void serialize (void *serialization, const ompl::base::State *state) const
void setDistanceFunction (const DistanceFunction &fun)
void setInterpolationFunction (const InterpolationFunction &fun)
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.
void setTagSnapToSegment (double snap)
virtual ~ModelBasedStateSpace ()

Protected Member Functions

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

Protected Attributes

DistanceFunction distance_function_
InterpolationFunction interpolation_function_
unsigned int jointSubspaceCount_
ModelBasedStateSpaceSpecification spec_
double tag_snap_to_segment_
double tag_snap_to_segment_complement_

Friends

class WrappedStateSampler

Detailed Description

Definition at line 71 of file model_based_state_space.h.


Constructor & Destructor Documentation

expose parameters

Definition at line 40 of file model_based_state_space.cpp.

Definition at line 72 of file model_based_state_space.cpp.


Member Function Documentation

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

Reimplemented in ompl_interface::PoseModelStateSpace.

Definition at line 177 of file model_based_state_space.cpp.

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

Reimplemented in ompl_interface::PoseModelStateSpace.

Definition at line 92 of file model_based_state_space.cpp.

ompl::base::StateSamplerPtr ompl_interface::ModelBasedStateSpace::allocStateSampler ( ) const [virtual]

Definition at line 221 of file model_based_state_space.cpp.

ompl::base::StateSamplerPtr ompl_interface::ModelBasedStateSpace::allocSubspaceStateSampler ( const ompl::base::StateSpace *  subspace) const [virtual]

Definition at line 216 of file model_based_state_space.cpp.

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

Reimplemented in ompl_interface::PoseModelStateSpace.

Definition at line 104 of file model_based_state_space.cpp.

void ompl_interface::ModelBasedStateSpace::copyToOMPLState ( ompl::base::State *  state,
const robot_state::RobotState kstate 
) const [inline]

Copy the data from a value vector that corresponds to the state of the considered joint model group (or array of joints)

Copy the data from a kinematic state to an OMPL state. Only needed joint states are copied. This function is implemented in terms of the previous definition with the same name.

Definition at line 237 of file model_based_state_space.h.

void ompl_interface::ModelBasedStateSpace::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 in ompl_interface::PoseModelStateSpace.

Definition at line 257 of file model_based_state_space.cpp.

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

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

Definition at line 249 of file model_based_state_space.cpp.

void ompl_interface::ModelBasedStateSpace::copyToRobotState ( robot_state::RobotState kstate,
const ompl::base::State *  state 
) const [inline]

Copy the data from an OMPL state to a kinematic state. The join states must be specified in the same order as the joint models in the constructor. This function is implemented in terms of the previous definition with the same name.

Definition at line 228 of file model_based_state_space.h.

void ompl_interface::ModelBasedStateSpace::deserialize ( ompl::base::State *  state,
const void *  serialization 
) const [virtual]

Definition at line 123 of file model_based_state_space.cpp.

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

Reimplemented in ompl_interface::PoseModelStateSpace.

Definition at line 140 of file model_based_state_space.cpp.

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

Reimplemented in ompl_interface::PoseModelStateSpace.

Definition at line 99 of file model_based_state_space.cpp.

Definition at line 199 of file model_based_state_space.h.

const std::string& ompl_interface::ModelBasedStateSpace::getJointModelGroupName ( ) const [inline]

Definition at line 204 of file model_based_state_space.h.

Definition at line 219 of file model_based_state_space.h.

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

Reimplemented in ompl_interface::PoseModelStateSpace.

Definition at line 129 of file model_based_state_space.cpp.

Definition at line 194 of file model_based_state_space.h.

Definition at line 112 of file model_based_state_space.cpp.

Definition at line 209 of file model_based_state_space.h.

Definition at line 76 of file model_based_state_space.cpp.

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

Reimplemented in ompl_interface::PoseModelStateSpace.

Definition at line 156 of file model_based_state_space.cpp.

void ompl_interface::ModelBasedStateSpace::printState ( const ompl::base::State *  state,
std::ostream &  out 
) const [virtual]

Definition at line 226 of file model_based_state_space.cpp.

void ompl_interface::ModelBasedStateSpace::serialize ( void *  serialization,
const ompl::base::State *  state 
) const [virtual]

Definition at line 117 of file model_based_state_space.cpp.

Definition at line 175 of file model_based_state_space.h.

Definition at line 170 of file model_based_state_space.h.

void ompl_interface::ModelBasedStateSpace::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 in ompl_interface::PoseModelStateSpace.

Definition at line 243 of file model_based_state_space.cpp.

Definition at line 81 of file model_based_state_space.cpp.


Friends And Related Function Documentation

friend class WrappedStateSampler [friend]

Definition at line 249 of file model_based_state_space.h.


Member Data Documentation

Definition at line 257 of file model_based_state_space.h.

Definition at line 256 of file model_based_state_space.h.

Definition at line 254 of file model_based_state_space.h.

Definition at line 253 of file model_based_state_space.h.

Definition at line 259 of file model_based_state_space.h.

Definition at line 260 of file model_based_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