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 <ompl/base/SpaceInformation.h>

Inheritance diagram for ompl::base::SpaceInformation:

Public Member Functions

 SpaceInformation (const SpaceInformation &)=delete
 
SpaceInformationoperator= (const SpaceInformation &)=delete
 
 SpaceInformation (StateSpacePtr space)
 Constructor. Sets the instance of the state space to plan with.
 
bool isValid (const State *state) const
 Check if a given state is valid or not.
 
const StateSpacePtrgetStateSpace () const
 Return the instance of the used state space.
 
unsigned int getStateDimension () const
 Return the dimension of the state space.
 
double getSpaceMeasure () const
 Get a measure of the space (this can be thought of as a generalization of volume)
 
Topology-specific state operations (as in the state space)
bool equalStates (const State *state1, const State *state2) const
 Check if two states are the same.
 
bool satisfiesBounds (const State *state) const
 Check if a state is inside the bounding box.
 
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.
 
void printState (const State *state, std::ostream &out=std::cout) const
 Print a state to a stream.
 
Configuration of state validity checking
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 setStateValidityChecker (const StateValidityCheckerFn &svc)
 If no state validity checking class is specified (StateValidityChecker), a 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.
 
const StateValidityCheckerPtrgetStateValidityChecker () const
 Return the instance of the used state validity checker.
 
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.

 
const MotionValidatorPtrgetMotionValidator () const
 Return the instance of the used state validity checker.
 
MotionValidatorPtrgetMotionValidator ()
 Return the non-const instance of the used state validity checker.
 
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 State Validity Checking.
 
double getStateValidityCheckingResolution () const
 Get the resolution at which state validity is verified. This call is only applicable if a ompl::base::DiscreteMotionValidator is used. See State Validity Checking.
 
State memory management
StateallocState () const
 Allocate memory for a state.
 
void allocStates (std::vector< State * > &states) const
 Allocate memory for each element of the array states.
 
void freeState (State *state) const
 Free the memory of a state.
 
void freeStates (std::vector< State * > &states) const
 Free the memory of an array of states.
 
void copyState (State *destination, const State *source) const
 Copy a state to another.
 
StatecloneState (const State *source) const
 Clone a state.
 
Sampling of valid states
StateSamplerPtr allocStateSampler () const
 Allocate a uniform state sampler for the state space.
 
ValidStateSamplerPtr allocValidStateSampler () 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.
 
void clearValidStateSamplerAllocator ()
 Clear the allocator used for the valid state sampler. This will revert to using the uniform valid state sampler (the default).
 
Primitives typically used by motion planners
double getMaximumExtent () 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.
 
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. More...
 
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. More...
 
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). More...
 
virtual 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. More...
 
virtual bool checkMotion (const State *s1, const State *s2) const
 Check if the path between two states (from s1 to s2) is valid, using the MotionValidator. This function assumes s1 is valid.
 
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. More...
 
bool checkMotion (const std::vector< State * > &states, unsigned int count) const
 Check if a sequence of states is valid using subdivision.
 
virtual 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. These states are not checked for validity. 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. More...
 
unsigned int getCheckedMotionCount () const
 Get the total number of motion segments checked by the MotionValidator so far.
 

Routines for inferring information about the state space

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.
 
MotionValidatorPtr motionValidator_
 The instance of the motion validator to use when determining the validity of motions in the planning process.
 
bool setup_
 Flag indicating whether setup() has been called on this instance.
 
ValidStateSamplerAllocator vssa_
 The optional valid state sampler allocator.
 
ParamSet params_
 Combined parameters for the contained classes.
 
double probabilityOfValidState (unsigned int attempts) const
 Estimate probability of sampling a valid state. setup() is assumed to have been called.
 
double averageValidMotionLength (unsigned int attempts) const
 Estimate the length of a valid motion. setup() is assumed to have been called.
 
void samplesPerSecond (double &uniform, double &near, double &gaussian, unsigned int attempts) const
 Estimate the number of samples that can be drawn per second, using the sampler returned by allocStateSampler()
 
virtual void printSettings (std::ostream &out=std::cout) const
 Print information about the current instance of the state space.
 
virtual void printProperties (std::ostream &out=std::cout) const
 Print properties of the current instance of the state space.
 
ParamSetparams ()
 Get the combined parameters for the classes that the space information manages.
 
const ParamSetparams () const
 Get the combined parameters for the classes that the space information manages.
 
virtual void setup ()
 Perform additional setup tasks (run once, before use). If state validity checking resolution has not been set, estimateMaxResolution() is called to estimate it.
 
bool isSetup () const
 Return true if setup was called.
 
void setDefaultMotionValidator ()
 Set default motion validator for the state space.
 

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 145 of file SpaceInformation.h.

Member Function Documentation

◆ checkMotion() [1/2]

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

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
s1start state of the motion to be checked (assumed to be valid)
s2final state of the motion to be checked
lastValidfirst: storage for the last valid state (may be nullptr); 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

Reimplemented in ompl::base::TangentBundleSpaceInformation.

Definition at line 409 of file SpaceInformation.h.

◆ checkMotion() [2/2]

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
statesthe array of states to be checked
countthe number of states to be checked in the array (0 to count)
firstInvalidStateIndexlocation to store the first invalid state index. Unmodified if the function returns true

Definition at line 274 of file SpaceInformation.cpp.

◆ getMotionStates()

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

Get count states that make up a motion between s1 and s2. Returns the number of states that were added to states. These states are not checked for validity. 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
s1the start state of the considered motion
s2the end state of the considered motion
statesthe computed set of states along the specified motion
countthe number of intermediate states to compute
endpointsflag indicating whether s1 and s2 are to be included in states
allocflag indicating whether memory is to be allocated automatically

Reimplemented in ompl::base::TangentBundleSpaceInformation, and ompl::base::ConstrainedSpaceInformation.

Definition at line 201 of file SpaceInformation.cpp.

◆ randomBounceMotion()

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
sssthe state space sampler to use
startthe state at which to start bouncing
stepsthe number of bouncing steps to take
statesthe location at which generated states will be stored
allocflag indicating whether memory should be allocated for states

Definition at line 133 of file SpaceInformation.cpp.

◆ searchValidNearby() [1/2]

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
samplerthe valid state sampler to use when attemting to find a valid sample.
statethe location at which to store the valid state, if one is found. This location may be modified even if no valid state is found.
neara state that may be invalid near which we would like to find a valid state
distancethe maximum allowed distance between state and near

Definition at line 160 of file SpaceInformation.cpp.

◆ searchValidNearby() [2/2]

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
statethe location at which to store the valid state, if one is found. This location may be modified even if no valid state is found.
neara state that may be invalid near which we would like to find a valid state
distancethe maximum allowed distance between state and near
attemptsthe algorithm works by sampling states near state near. This parameter defines the maximum number of sampling attempts

Definition at line 183 of file SpaceInformation.cpp.


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