ompl::base::SE3StateSpace Class Reference

A state space representing SE(3). More...

#include <SE3StateSpace.h>

Inheritance diagram for ompl::base::SE3StateSpace:
Inheritance graph
[legend]

List of all members.

Classes

class  StateType
 A state in SE(3): position = (x, y, z), quaternion = (x, y, z, w). More...

Public Member Functions

virtual StateallocState (void) const
 Allocate a state that can store a point in the described space.
virtual void freeState (State *state) const
 Free the memory of the allocated state.
const RealVectorBoundsgetBounds (void) const
virtual void registerProjections (void)
 Register the projections for this state space. Usually, this is at least the default projection. These are implicit projections, set by the implementation of the state space. This is called by setup().
 SE3StateSpace (void)
void setBounds (const RealVectorBounds &bounds)
virtual ~SE3StateSpace (void)

Detailed Description

A state space representing SE(3).

Definition at line 46 of file SE3StateSpace.h.


Constructor & Destructor Documentation

ompl::base::SE3StateSpace::SE3StateSpace ( void   )  [inline]

Definition at line 112 of file SE3StateSpace.h.

virtual ompl::base::SE3StateSpace::~SE3StateSpace ( void   )  [inline, virtual]

Definition at line 121 of file SE3StateSpace.h.


Member Function Documentation

virtual State* ompl::base::SE3StateSpace::allocState ( void   )  const [virtual]

Allocate a state that can store a point in the described space.

Reimplemented from ompl::base::CompoundStateSpace.

virtual void ompl::base::SE3StateSpace::freeState ( State state  )  const [virtual]

Free the memory of the allocated state.

Reimplemented from ompl::base::CompoundStateSpace.

const RealVectorBounds& ompl::base::SE3StateSpace::getBounds ( void   )  const [inline]

Get the bounds for this state space.

Definition at line 132 of file SE3StateSpace.h.

virtual void ompl::base::SE3StateSpace::registerProjections ( void   )  [virtual]

Register the projections for this state space. Usually, this is at least the default projection. These are implicit projections, set by the implementation of the state space. This is called by setup().

Reimplemented from ompl::base::StateSpace.

void ompl::base::SE3StateSpace::setBounds ( const RealVectorBounds bounds  )  [inline]

Set the bounds of this state space. This defines the range of the space in which sampling is performed.

Definition at line 126 of file SE3StateSpace.h.


The documentation for this class was generated from the following file:
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends Defines


ompl
Author(s): Ioan Sucan/isucan@rice.edu, Mark Moll/mmoll@rice.edu, Lydia Kavraki/kavraki@rice.edu
autogenerated on Fri Jan 11 09:34:00 2013