ompl::base::SpaceInformation Class Reference

The base class for space information. This contains all the information about the space planning is done in. setup() needs to be called as well, before use. More...

#include <SpaceInformation.h>

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

List of all members.

Public Member Functions

unsigned int getStateDimension (void) const
 Return the dimension of the state space.
const StateSpacePtrgetStateSpace (void) const
 Return the instance of the used state space.
bool isSetup (void) const
 Return true if setup was called.
bool isValid (const State *state) const
 Check if a given state is valid or not.
virtual void printSettings (std::ostream &out=std::cout) const
 Print information about the current instance of the state space.
virtual void setup (void)
 Perform additional setup tasks (run once, before use). If state validity checking resolution has not been set, estimateMaxResolution() is called to estimate it.
 SpaceInformation (const StateSpacePtr &space)
 Constructor. Sets the instance of the state space to plan with.
virtual ~SpaceInformation (void)
State memory management

StateallocState (void) const
 Allocate memory for a state.
StatecloneState (const State *source) const
 Clone a state.
void copyState (State *destination, const State *source) const
 Copy a state to another.
void freeState (State *state) const
 Free the memory of a state.
Sampling of valid states

StateSamplerPtr allocStateSampler (void) const
 Allocate a uniform state sampler for the state space.
ValidStateSamplerPtr allocValidStateSampler (void) const
 Allocate an instance of a valid state sampler for this space. If setValidStateSamplerAllocator() was previously called, the specified allocator is used to produce the state sampler. Otherwise, a ompl::base::UniformValidStateSampler() is allocated.
void setValidStateSamplerAllocator (const ValidStateSamplerAllocator &vssa)
 Set the allocator to use for a valid state sampler. This replaces the default uniform valid state sampler. This call can be made at any time, but it should not be changed while ompl::base::Planner::solve() is executing.
Primitives typically used by motion planners

bool checkMotion (const std::vector< State * > &states, unsigned int count) const
 Check if a sequence of states is valid using subdivision.
bool checkMotion (const std::vector< State * > &states, unsigned int count, unsigned int &firstInvalidStateIndex) const
 Incrementally check if a sequence of states is valid. Given a vector of states, this routine only checks the first count elements and marks the index of the first invalid state.
bool checkMotion (const State *s1, const State *s2) const
 Check if the path between two states (from s1 to s2) is valid, using subdivision. This function assumes s1 is valid.
bool checkMotion (const State *s1, const State *s2, std::pair< State *, double > &lastValid) const
 Incrementally check if the path between two motions is valid. Also compute the last state that was valid and the time of that state. The time is used to parametrize the motion from s1 to s2, s1 being at t = 0 and s2 being at t = 1. This function assumes s1 is valid.
double getMaximumExtent (void) const
 Get the maximum extent of the space we are planning in. This is the maximum distance that could be reported between any two given states.
unsigned int getMotionStates (const State *s1, const State *s2, std::vector< State * > &states, unsigned int count, bool endpoints, bool alloc) const
 Get count states that make up a motion between s1 and s2. Returns the number of states that were added to states. If states.size() >= count or alloc is true, the returned value is equal to count (or count + 2, if endpoints is true). Otherwise, fewer states can be returned.
unsigned int randomBounceMotion (const StateSamplerPtr &sss, const State *start, unsigned int steps, std::vector< State * > &states, bool alloc) const
 Produce a valid motion starting at start by randomly bouncing off of invalid states. The start state start is not included in the computed motion (states). Returns the number of elements written to states (less or equal to steps).
bool searchValidNearby (const ValidStateSamplerPtr &sampler, State *state, const State *near, double distance) const
 Find a valid state near a given one. If the given state is valid, it will be returned itself. The two passed state pointers need not point to different memory. Returns true on success.
bool searchValidNearby (State *state, const State *near, double distance, unsigned int attempts) const
 Find a valid state near a given one. If the given state is valid, it will be returned itself. The two passed state pointers need not point to different memory. Returns true on success.
Topology-specific state operations (as in the state space)

double distance (const State *state1, const State *state2) const
 Compute the distance between two states.
void enforceBounds (State *state) const
 Bring the state within the bounds of the state space.
bool equalStates (const State *state1, const State *state2) const
 Check if two states are the same.
void printState (const State *state, std::ostream &out=std::cout) const
 Print a state to a stream.
bool satisfiesBounds (const State *state) const
 Check if a state is inside the bounding box.
Configuration of state validity checking

const MotionValidatorPtrgetMotionValidator (void) const
 Return the instance of the used state validity checker.
const StateValidityCheckerPtrgetStateValidityChecker (void) const
 Return the instance of the used state validity checker.
double getStateValidityCheckingResolution (void) const
 Get the resolution at which state validity is verified. This call is only applicable if a ompl::base::DiscreteMotionValidator is used. See stateValidation.
void setMotionValidator (const MotionValidatorPtr &mv)
 Set the instance of the motion validity checker to use. Parallel implementations of planners assume this validity checker is thread safe.
void setStateValidityChecker (const StateValidityCheckerFn &svc)
 If no state validity checking class is specified (StateValidityChecker), a boost function can be specified instead. This version however incurs a small additional overhead when calling the function, since there is one more level of indirection.
void setStateValidityChecker (const StateValidityCheckerPtr &svc)
 Set the instance of the state validity checker to use. Parallel implementations of planners assume this validity checker is thread safe.
void setStateValidityCheckingResolution (double resolution)
 Set the resolution at which state validity needs to be verified in order for a motion between two states to be considered valid. This value is specified as a fraction of the space's extent. This call is only applicable if a ompl::base::DiscreteMotionValidator is used. See stateValidation.

Protected Attributes

MotionValidatorPtr motionValidator_
 The instance of the motion validator to use when determining the validity of motions in the planning process.
msg::Interface msg_
 The console interface.
bool setup_
 Flag indicating whether setup() has been called on this instance.
StateSpacePtr stateSpace_
 The state space planning is to be performed in.
StateValidityCheckerPtr stateValidityChecker_
 The instance of the state validity checker used for determining the validity of states in the planning process.
ValidStateSamplerAllocator vssa_
 The optional valid state sampler allocator.

Detailed Description

The base class for space information. This contains all the information about the space planning is done in. setup() needs to be called as well, before use.

Definition at line 84 of file base/SpaceInformation.h.


Constructor & Destructor Documentation

ompl::base::SpaceInformation::SpaceInformation ( const StateSpacePtr space  ) 

Constructor. Sets the instance of the state space to plan with.

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

Reimplemented in ompl::control::SpaceInformation.

Definition at line 91 of file base/SpaceInformation.h.


Member Function Documentation

State* ompl::base::SpaceInformation::allocState ( void   )  const [inline]

Allocate memory for a state.

Definition at line 216 of file base/SpaceInformation.h.

StateSamplerPtr ompl::base::SpaceInformation::allocStateSampler ( void   )  const [inline]

Allocate a uniform state sampler for the state space.

Definition at line 248 of file base/SpaceInformation.h.

ValidStateSamplerPtr ompl::base::SpaceInformation::allocValidStateSampler ( void   )  const

Allocate an instance of a valid state sampler for this space. If setValidStateSamplerAllocator() was previously called, the specified allocator is used to produce the state sampler. Otherwise, a ompl::base::UniformValidStateSampler() is allocated.

bool ompl::base::SpaceInformation::checkMotion ( const std::vector< State * > &  states,
unsigned int  count 
) const

Check if a sequence of states is valid using subdivision.

bool ompl::base::SpaceInformation::checkMotion ( const std::vector< State * > &  states,
unsigned int  count,
unsigned int &  firstInvalidStateIndex 
) const

Incrementally check if a sequence of states is valid. Given a vector of states, this routine only checks the first count elements and marks the index of the first invalid state.

Parameters:
states the array of states to be checked
count the number of states to be checked in the array (0 to count)
firstInvalidStateIndex location to store the first invalid state index. Unmodified if the function returns true
bool ompl::base::SpaceInformation::checkMotion ( const State s1,
const State s2 
) const [inline]

Check if the path between two states (from s1 to s2) is valid, using subdivision. This function assumes s1 is valid.

Definition at line 319 of file base/SpaceInformation.h.

bool ompl::base::SpaceInformation::checkMotion ( const State s1,
const State s2,
std::pair< State *, double > &  lastValid 
) const [inline]

Incrementally check if the path between two motions is valid. Also compute the last state that was valid and the time of that state. The time is used to parametrize the motion from s1 to s2, s1 being at t = 0 and s2 being at t = 1. This function assumes s1 is valid.

Parameters:
s1 start state of the motion to be checked (assumed to be valid)
s2 final state of the motion to be checked
lastValid first: storage for the last valid state; this need not be different from s1 or s2. second: the time (between 0 and 1) of the last valid state, on the motion from s1 to s2

Definition at line 312 of file base/SpaceInformation.h.

State* ompl::base::SpaceInformation::cloneState ( const State source  )  const [inline]

Clone a state.

Definition at line 234 of file base/SpaceInformation.h.

void ompl::base::SpaceInformation::copyState ( State destination,
const State source 
) const [inline]

Copy a state to another.

Definition at line 228 of file base/SpaceInformation.h.

double ompl::base::SpaceInformation::distance ( const State state1,
const State state2 
) const [inline]

Compute the distance between two states.

Definition at line 123 of file base/SpaceInformation.h.

void ompl::base::SpaceInformation::enforceBounds ( State state  )  const [inline]

Bring the state within the bounds of the state space.

Definition at line 129 of file base/SpaceInformation.h.

bool ompl::base::SpaceInformation::equalStates ( const State state1,
const State state2 
) const [inline]

Check if two states are the same.

Definition at line 111 of file base/SpaceInformation.h.

void ompl::base::SpaceInformation::freeState ( State state  )  const [inline]

Free the memory of a state.

Definition at line 222 of file base/SpaceInformation.h.

double ompl::base::SpaceInformation::getMaximumExtent ( void   )  const [inline]

Get the maximum extent of the space we are planning in. This is the maximum distance that could be reported between any two given states.

Definition at line 275 of file base/SpaceInformation.h.

unsigned int ompl::base::SpaceInformation::getMotionStates ( const State s1,
const State s2,
std::vector< State * > &  states,
unsigned int  count,
bool  endpoints,
bool  alloc 
) const

Get count states that make up a motion between s1 and s2. Returns the number of states that were added to states. If states.size() >= count or alloc is true, the returned value is equal to count (or count + 2, if endpoints is true). Otherwise, fewer states can be returned.

Parameters:
s1 the start state of the considered motion
s2 the end state of the considered motion
states the computed set of states along the specified motion
count the number of intermediate states to compute
endpoints flag indicating whether s1 and s2 are to be included in states
alloc flag indicating whether memory is to be allocated automatically
const MotionValidatorPtr& ompl::base::SpaceInformation::getMotionValidator ( void   )  const [inline]

Return the instance of the used state validity checker.

Definition at line 177 of file base/SpaceInformation.h.

unsigned int ompl::base::SpaceInformation::getStateDimension ( void   )  const [inline]

Return the dimension of the state space.

Definition at line 207 of file base/SpaceInformation.h.

const StateSpacePtr& ompl::base::SpaceInformation::getStateSpace ( void   )  const [inline]

Return the instance of the used state space.

Definition at line 102 of file base/SpaceInformation.h.

const StateValidityCheckerPtr& ompl::base::SpaceInformation::getStateValidityChecker ( void   )  const [inline]

Return the instance of the used state validity checker.

Definition at line 162 of file base/SpaceInformation.h.

double ompl::base::SpaceInformation::getStateValidityCheckingResolution ( void   )  const [inline]

Get the resolution at which state validity is verified. This call is only applicable if a ompl::base::DiscreteMotionValidator is used. See stateValidation.

Definition at line 198 of file base/SpaceInformation.h.

bool ompl::base::SpaceInformation::isSetup ( void   )  const

Return true if setup was called.

bool ompl::base::SpaceInformation::isValid ( const State state  )  const [inline]

Check if a given state is valid or not.

Definition at line 96 of file base/SpaceInformation.h.

virtual void ompl::base::SpaceInformation::printSettings ( std::ostream &  out = std::cout  )  const [virtual]

Print information about the current instance of the state space.

Reimplemented in ompl::control::SpaceInformation.

void ompl::base::SpaceInformation::printState ( const State state,
std::ostream &  out = std::cout 
) const [inline]

Print a state to a stream.

Definition at line 135 of file base/SpaceInformation.h.

unsigned int ompl::base::SpaceInformation::randomBounceMotion ( const StateSamplerPtr sss,
const State start,
unsigned int  steps,
std::vector< State * > &  states,
bool  alloc 
) const

Produce a valid motion starting at start by randomly bouncing off of invalid states. The start state start is not included in the computed motion (states). Returns the number of elements written to states (less or equal to steps).

Parameters:
sss the state space sampler to use
start the state at which to start bouncing
steps the number of bouncing steps to take
states the location at which generated states will be stored
alloc flag indicating whether memory should be allocated for states
bool ompl::base::SpaceInformation::satisfiesBounds ( const State state  )  const [inline]

Check if a state is inside the bounding box.

Definition at line 117 of file base/SpaceInformation.h.

bool ompl::base::SpaceInformation::searchValidNearby ( const ValidStateSamplerPtr sampler,
State state,
const State near,
double  distance 
) const

Find a valid state near a given one. If the given state is valid, it will be returned itself. The two passed state pointers need not point to different memory. Returns true on success.

Parameters:
sampler the valid state sampler to use when attemting to find a valid sample.
state the location at which to store the valid state, if one is found. This location may be modified even if no valid state is found.
near a state that may be invalid near which we would like to find a valid state
distance the maximum allowed distance between state and near
bool ompl::base::SpaceInformation::searchValidNearby ( State state,
const State near,
double  distance,
unsigned int  attempts 
) const

Find a valid state near a given one. If the given state is valid, it will be returned itself. The two passed state pointers need not point to different memory. Returns true on success.

Parameters:
state the location at which to store the valid state, if one is found. This location may be modified even if no valid state is found.
near a state that may be invalid near which we would like to find a valid state
distance the maximum allowed distance between state and near
attempts the algorithm works by sampling states near state near. This parameter defines the maximum number of sampling attempts
void ompl::base::SpaceInformation::setMotionValidator ( const MotionValidatorPtr mv  )  [inline]

Set the instance of the motion validity checker to use. Parallel implementations of planners assume this validity checker is thread safe.

Definition at line 170 of file base/SpaceInformation.h.

void ompl::base::SpaceInformation::setStateValidityChecker ( const StateValidityCheckerFn svc  ) 

If no state validity checking class is specified (StateValidityChecker), a boost function can be specified instead. This version however incurs a small additional overhead when calling the function, since there is one more level of indirection.

void ompl::base::SpaceInformation::setStateValidityChecker ( const StateValidityCheckerPtr svc  )  [inline]

Set the instance of the state validity checker to use. Parallel implementations of planners assume this validity checker is thread safe.

Definition at line 148 of file base/SpaceInformation.h.

void ompl::base::SpaceInformation::setStateValidityCheckingResolution ( double  resolution  )  [inline]

Set the resolution at which state validity needs to be verified in order for a motion between two states to be considered valid. This value is specified as a fraction of the space's extent. This call is only applicable if a ompl::base::DiscreteMotionValidator is used. See stateValidation.

Definition at line 188 of file base/SpaceInformation.h.

virtual void ompl::base::SpaceInformation::setup ( void   )  [virtual]

Perform additional setup tasks (run once, before use). If state validity checking resolution has not been set, estimateMaxResolution() is called to estimate it.

Reimplemented in ompl::control::SpaceInformation.

void ompl::base::SpaceInformation::setValidStateSamplerAllocator ( const ValidStateSamplerAllocator vssa  )  [inline]

Set the allocator to use for a valid state sampler. This replaces the default uniform valid state sampler. This call can be made at any time, but it should not be changed while ompl::base::Planner::solve() is executing.

Definition at line 261 of file base/SpaceInformation.h.


Member Data Documentation

The instance of the motion validator to use when determining the validity of motions in the planning process.

Definition at line 367 of file base/SpaceInformation.h.

The console interface.

Definition at line 376 of file base/SpaceInformation.h.

Flag indicating whether setup() has been called on this instance.

Definition at line 370 of file base/SpaceInformation.h.

The state space planning is to be performed in.

Definition at line 361 of file base/SpaceInformation.h.

The instance of the state validity checker used for determining the validity of states in the planning process.

Definition at line 364 of file base/SpaceInformation.h.

The optional valid state sampler allocator.

Definition at line 373 of file base/SpaceInformation.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:01 2013