All Classes Namespaces Functions Variables Typedefs Enumerations Enumerator
ompl::base::SE3StateSpace Class Reference

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

#include <SE3StateSpace.h>

Inheritance diagram for ompl::base::SE3StateSpace:

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

void setBounds (const RealVectorBounds &bounds)
 Set the bounds of this state space. This defines the range of the space in which sampling is performed.
const RealVectorBoundsgetBounds (void) const
 Get the bounds for this state space.
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.
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().

Detailed Description

A state space representing SE(3)

Definition at line 50 of file SE3StateSpace.h.


Member Function Documentation

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

Get the bounds for this state space.

Definition at line 140 of file SE3StateSpace.h.

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 134 of file SE3StateSpace.h.


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