All Classes Namespaces Functions Variables Typedefs Enumerations Enumerator

Representation of a space in which planning can be performed. Topology specific sampling, interpolation and distance are defined. More...

#include <StateSpace.h>

Inheritance diagram for ompl::base::StateSpace:

List of all members.

Public Types

typedef State StateType
 Define the type of state allocated by this space.

Public Member Functions

 StateSpace (void)
 Constructor. Assigns a unique name to the space.
template<class T >
T * as (void)
 Cast this instance to a desired type.
template<class T >
const T * as (void) const
 Cast this instance to a desired type.
virtual void setup (void)
 Perform final setup steps. This function is automatically called by the SpaceInformation. If any default projections are to be registered, this call will set them. It is safe to call this function multiple times.
Generic functionality for state spaces
virtual bool isCompound (void) const
 Check if the state space is compound.
virtual bool isDiscrete (void) const
 Check if the set of states is discrete.
virtual bool isHybrid (void) const
 Check if this is a hybrid state space (i.e., both discrete and continuous components exist)
const std::string & getName (void) const
 Get the name of the state space.
void setName (const std::string &name)
 Set the name of the state space.
int getType (void) const
 Get the type of the state space. The type can be used to verify whether two space instances are of the same type (e.g., SO2)
bool includes (const StateSpacePtr &other) const
 Return true if other is a space included (perhaps equal, perhaps a subspace) in this one.
bool covers (const StateSpacePtr &other) const
 Return true if other is a space that is either included (perhaps equal, perhaps a subspace) in this one, or all of its subspaces are included in this one.
Functionality specific to state spaces (to be implemented by derived state spaces)
virtual unsigned int getDimension (void) const =0
 Get the dimension of the space (not the dimension of the surrounding ambient space)
virtual double getMaximumExtent (void) const =0
 Get the maximum value a call to distance() can return (or an upper bound). For unbounded state spaces, this function can return infinity.
virtual void enforceBounds (State *state) const =0
 Bring the state within the bounds of the state space. For unbounded spaces this function can be a no-op.
virtual bool satisfiesBounds (const State *state) const =0
 Check if a state is inside the bounding box. For unbounded spaces this function can always return true.
virtual void copyState (State *destination, const State *source) const =0
 Copy a state to another. The memory of source and destination should NOT overlap.
virtual double distance (const State *state1, const State *state2) const =0
 Computes distance to between two states. This function satisfies the properties of a metric and its return value will always be between 0 and getMaximumExtent()
virtual double * getValueAddressAtIndex (State *state, const unsigned int index) const
 Many states contain a number of double values. This function provides a means to get the memory address of a double value from state state located at position index. The first double value is returned for index = 0. If index is too large (does not point to any double values in the state), the return value is NULL.
virtual double getLongestValidSegmentFraction (void) const
 When performing discrete validation of motions, the length of the longest segment that does not require state validation needs to be specified. This function returns this length, for this state space, as a fraction of the space's maximum extent.
virtual void setLongestValidSegmentFraction (double segmentFraction)
 When performing discrete validation of motions, the length of the longest segment that does not require state validation needs to be specified. This function sets this length as a fraction of the space's maximum extent.
virtual unsigned int validSegmentCount (const State *state1, const State *state2) const
 Count how many segments of the "longest valid length" fit on the motion from state1 to state2.
void setValidSegmentCountFactor (unsigned int factor)
 Set factor to be the value to multiply the return value of validSegmentCount(). By default, this value is 1. The higher the value, the smaller the size of the segments considered valid. The effect of this function is immediate (setup() does not need to be called).
unsigned int getValidSegmentCountFactor (void) const
 Get the value used to multiply the return value of validSegmentCount().
virtual bool equalStates (const State *state1, const State *state2) const =0
 Checks whether two states are equal.
virtual void interpolate (const State *from, const State *to, const double t, State *state) const =0
 Computes the state that lies at time t in [0, 1] on the segment that connects from state to to state. The memory location of state is not required to be different from the memory of either from or to.
virtual StateSamplerPtr allocStateSampler (void) const =0
 Allocate an instance of a uniform state sampler for this space.
virtual StateallocState (void) const =0
 Allocate a state that can store a point in the described space.
virtual void freeState (State *state) const =0
 Free the memory of the allocated state.
Management of projections from this state space to Euclidean spaces
void registerProjection (const std::string &name, const ProjectionEvaluatorPtr &projection)
 Register a projection for this state space under a specified name.
void registerDefaultProjection (const ProjectionEvaluatorPtr &projection)
 Register the default projection for this state space.
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().
ProjectionEvaluatorPtr getProjection (const std::string &name) const
 Get the projection registered under a specific name.
ProjectionEvaluatorPtr getDefaultProjection (void) const
 Get the default projection.
bool hasProjection (const std::string &name) const
 Check if a projection with a specified name is available.
bool hasDefaultProjection (void) const
 Check if a default projection is available.
const std::map< std::string,
ProjectionEvaluatorPtr > & 
getRegisteredProjections (void) const
 Get all the registered projections.

Protected Attributes

int type_
 A type assigned for this state space.
double maxExtent_
 The extent of this space at the time setup() was called.
double longestValidSegmentFraction_
 The fraction of the longest valid segment.
double longestValidSegment_
 The longest valid segment at the time setup() was called.
unsigned int longestValidSegmentCountFactor_
 The factor to multiply the value returned by validSegmentCount()
msg::Interface msg_
 Interface used for console output.
std::map< std::string,
ProjectionEvaluatorPtr
projections_
 List of available projections.

Static Protected Attributes

static const std::string DEFAULT_PROJECTION_NAME = ""
 The name used for the default projection.

Debugging tools

virtual void printState (const State *state, std::ostream &out) const
 Print a state to a stream.
virtual void printSettings (std::ostream &out) const
 Print the settings for this state space to a stream.
virtual void printProjections (std::ostream &out) const
 Print the list of registered projections. This function is also called by printSettings()
virtual void sanityChecks (void) const
 Perform sanity checks for this state space. Throws an exception if failures are found.
static void Diagram (std::ostream &out)
 Print a Graphviz digraph that represents the containment diagram for all the instantiated state spaces.

Detailed Description

Representation of a space in which planning can be performed. Topology specific sampling, interpolation and distance are defined.

See Implementing State Spaces.

Definition at line 70 of file StateSpace.h.


Member Function Documentation

template<class T >
T* ompl::base::StateSpace::as ( void  ) [inline]

Cast this instance to a desired type.

Make sure the type we are casting to is indeed a state space

Definition at line 84 of file StateSpace.h.

template<class T >
const T* ompl::base::StateSpace::as ( void  ) const [inline]

Cast this instance to a desired type.

Make sure the type we are casting to is indeed a state space

Definition at line 94 of file StateSpace.h.

virtual double ompl::base::StateSpace::getMaximumExtent ( void  ) const [pure virtual]

Get the maximum value a call to distance() can return (or an upper bound). For unbounded state spaces, this function can return infinity.

Note:
Tight upper bounds are preferred because the value of the extent is used in the automatic computation of parameters for planning. If the bounds are less tight, the automatically computed parameters will be less useful.

Implemented in ompl::base::CompoundStateSpace, ompl::base::RealVectorStateSpace, ompl::base::SO3StateSpace, ompl::base::DiscreteStateSpace, ompl::base::SO2StateSpace, and ompl::base::TimeStateSpace.

double * ompl::base::StateSpace::getValueAddressAtIndex ( State state,
const unsigned int  index 
) const [virtual]

Many states contain a number of double values. This function provides a means to get the memory address of a double value from state state located at position index. The first double value is returned for index = 0. If index is too large (does not point to any double values in the state), the return value is NULL.

Note:
This function does not map a state to an array of doubles. There may be components of a state that do not correspond to double values and they are 'invisible' to this function. Furthermore, this function is slow and is not intended for use in the implementation of planners.

Reimplemented in ompl::base::CompoundStateSpace, ompl::base::RealVectorStateSpace, ompl::base::TimeStateSpace, ompl::base::SO3StateSpace, and ompl::base::SO2StateSpace.

Definition at line 129 of file StateSpace.cpp.

bool ompl::base::StateSpace::isDiscrete ( void  ) const [virtual]

Check if the set of states is discrete.

Note:
In fact, because of limited numerical precision, the representation of all spaces is discrete; this function returns true if the corresponding mathematical object is a discrete one.

Reimplemented in ompl::base::DiscreteStateSpace.

Definition at line 371 of file StateSpace.cpp.

void ompl::base::StateSpace::sanityChecks ( void  ) const [virtual]

Perform sanity checks for this state space. Throws an exception if failures are found.

Note:
This checks if distances are always positive, whether the integration works as expected.

Definition at line 242 of file StateSpace.cpp.

void ompl::base::StateSpace::setLongestValidSegmentFraction ( double  segmentFraction) [virtual]

When performing discrete validation of motions, the length of the longest segment that does not require state validation needs to be specified. This function sets this length as a fraction of the space's maximum extent.

Note:
This function's effect is not considered until after setup() has been called. For immediate effects (i.e., during planning) use setValidSegmentCountFactor()

Reimplemented in ompl::base::CompoundStateSpace.

Definition at line 388 of file StateSpace.cpp.


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