Aikido
aikido::planner::ompl::GeometricStateSpace Class Reference

Wraps an aikido StateSpace into a space recognized by OMPL. More...

#include <aikido/planner/ompl/GeometricStateSpace.hpp>

Inheritance diagram for aikido::planner::ompl::GeometricStateSpace:

Classes

class  StateType
 Wraps an aikido::statespace::StateSpace::State in an OMPL StateType. More...
 

Public Member Functions

 GeometricStateSpace (statespace::ConstStateSpacePtr sspace, statespace::ConstInterpolatorPtr interpolator, distance::DistanceMetricPtr dmetric, constraint::SampleablePtr sampler, constraint::ConstTestablePtr boundsConstraint, constraint::ProjectablePtr boundsProjection, double maxDistanceBetweenValidityChecks)
 Construct a state space. More...
 
unsigned int getDimension () const override
 Get the dimension of the space. More...
 
double getMaximumExtent () const override
 Get the maximum value a call to distance() can return (or an upper bound). More...
 
double getMeasure () const
 
void enforceBounds (::ompl::base::State *state) const override
 Bring the state within the bounds of the statespace using boundsProjection. More...
 
bool satisfiesBounds (const ::ompl::base::State *state) const override
 Check if a state satisfies the boundsConstraint. More...
 
void copyState (::ompl::base::State *destination, const ::ompl::base::State *source) const override
 Copy the value of one state to another. More...
 
double distance (const ::ompl::base::State *state1, const ::ompl::base::State *state2) const override
 Computes distance between two states using the dmetric. More...
 
bool equalStates (const ::ompl::base::State *state1, const ::ompl::base::State *state2) const override
 Check state equality. More...
 
void interpolate (const ::ompl::base::State *from, const ::ompl::base::State *to, double t, ::ompl::base::State *state) const override
 Computes the state that lies at time t in [0, 1] on the segment that connects from state to to state. More...
 
::ompl::base::StateSamplerPtr allocDefaultStateSampler () const override
 Allocate an instance of the state sampler for this space. More...
 
::ompl::base::State * allocState () const override
 Allocate a state that can store a point in the described space. More...
 
::ompl::base::State * allocState (const statespace::StateSpace::State *state) const
 Allocate a state constaining a copy of the aikido state. More...
 
void freeState (::ompl::base::State *state) const override
 Free the memory of the allocated state. More...
 
statespace::ConstStateSpacePtr getAikidoStateSpace () const
 Return the Aikido StateSpace that this OMPL StateSpace wraps. More...
 
aikido::statespace::ConstInterpolatorPtr getInterpolator () const
 Return the interpolator used to interpolate between states in the space. More...
 
aikido::constraint::ConstTestablePtr getBoundsConstraint () const
 Return the bounds constraint for the statespace. More...
 
double getMaxDistanceBetweenValidityChecks () const
 Returns the collision checking resolution. More...
 

Private Attributes

statespace::ConstStateSpacePtr mStateSpace
 The AIKIDO statespace to be exposed to OMPL. More...
 
statespace::ConstInterpolatorPtr mInterpolator
 An aikido interpolator to interpolate between states of the statespace. More...
 
distance::DistanceMetricPtr mDistance
 Distance metric to compute distance between states in the statespace. More...
 
constraint::SampleablePtr mSampler
 State sampler used to sample states in the statespace. More...
 
constraint::ConstTestablePtr mBoundsConstraint
 Constraint to determine if a state is within statespace bounds. More...
 
constraint::ProjectablePtr mBoundsProjection
 A Projectable that projects a state within valid bounds of statespace. More...
 
double mMaxDistanceBetweenValidityChecks
 Collision checking resolution. More...
 

Detailed Description

Wraps an aikido StateSpace into a space recognized by OMPL.

Constructor & Destructor Documentation

◆ GeometricStateSpace()

aikido::planner::ompl::GeometricStateSpace::GeometricStateSpace ( statespace::ConstStateSpacePtr  sspace,
statespace::ConstInterpolatorPtr  interpolator,
distance::DistanceMetricPtr  dmetric,
constraint::SampleablePtr  sampler,
constraint::ConstTestablePtr  boundsConstraint,
constraint::ProjectablePtr  boundsProjection,
double  maxDistanceBetweenValidityChecks 
)

Construct a state space.

Parameters
[in]sspaceThe aikido::statespace::StateSpace to expose to OMPL
[in]interpolatorAn aikido interpolator used by the interpolate method
[in]dmetricThe distance metric to use to compute distance between two states in the StateSpace
[in]samplerA state sampler used to sample new states in the StateSpace
[in]boundsConstraintA Testable used to determine whether states fall with in bounds defined on the space.
[in]boundsProjectionA Projectable that can be used to project a state back within the valid boundary defined on the space.
[in]maxDistanceBetweenValidityChecksThe maximum distance (under dmetric) between validity checking two successive points on a tree extension or an edge in a graph. Defines the "discreteness" of statespace.

Member Function Documentation

◆ allocDefaultStateSampler()

::ompl::base::StateSamplerPtr aikido::planner::ompl::GeometricStateSpace::allocDefaultStateSampler ( ) const
override

Allocate an instance of the state sampler for this space.

◆ allocState() [1/2]

::ompl::base::State* aikido::planner::ompl::GeometricStateSpace::allocState ( ) const
override

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

◆ allocState() [2/2]

::ompl::base::State* aikido::planner::ompl::GeometricStateSpace::allocState ( const statespace::StateSpace::State state) const

Allocate a state constaining a copy of the aikido state.

Parameters
[in]stateThe aikido state to copy and wrap in an OMPL state

◆ copyState()

void aikido::planner::ompl::GeometricStateSpace::copyState ( ::ompl::base::State *  destination,
const ::ompl::base::State *  source 
) const
override

Copy the value of one state to another.

Parameters
[out]destinationThe state to copy to.
[in]sourceThe state to copy from.

◆ distance()

double aikido::planner::ompl::GeometricStateSpace::distance ( const ::ompl::base::State *  state1,
const ::ompl::base::State *  state2 
) const
override

Computes distance between two states using the dmetric.

Parameters
[in]state1The first state.
[in]state2The second state.

◆ enforceBounds()

void aikido::planner::ompl::GeometricStateSpace::enforceBounds ( ::ompl::base::State *  state) const
override

Bring the state within the bounds of the statespace using boundsProjection.

Parameters
[in]stateThe state to modify.

◆ equalStates()

bool aikido::planner::ompl::GeometricStateSpace::equalStates ( const ::ompl::base::State *  state1,
const ::ompl::base::State *  state2 
) const
override

Check state equality.

Returns true if the distance between the states less than EQUALITY_EPSILON.

Parameters
[in]state1The first state
[in]state2The second state

◆ freeState()

void aikido::planner::ompl::GeometricStateSpace::freeState ( ::ompl::base::State *  state) const
override

Free the memory of the allocated state.

This also frees the memory of the wrapped aikido state.

Parameters
[in]stateThe state to free.

◆ getAikidoStateSpace()

statespace::ConstStateSpacePtr aikido::planner::ompl::GeometricStateSpace::getAikidoStateSpace ( ) const

Return the Aikido StateSpace that this OMPL StateSpace wraps.

◆ getBoundsConstraint()

aikido::constraint::ConstTestablePtr aikido::planner::ompl::GeometricStateSpace::getBoundsConstraint ( ) const

Return the bounds constraint for the statespace.

Used to specify constraints to the OMPL planner.

◆ getDimension()

unsigned int aikido::planner::ompl::GeometricStateSpace::getDimension ( ) const
override

Get the dimension of the space.

◆ getInterpolator()

aikido::statespace::ConstInterpolatorPtr aikido::planner::ompl::GeometricStateSpace::getInterpolator ( ) const

Return the interpolator used to interpolate between states in the space.

◆ getMaxDistanceBetweenValidityChecks()

double aikido::planner::ompl::GeometricStateSpace::getMaxDistanceBetweenValidityChecks ( ) const

Returns the collision checking resolution.

◆ getMaximumExtent()

double aikido::planner::ompl::GeometricStateSpace::getMaximumExtent ( ) const
override

Get the maximum value a call to distance() can return (or an upper bound).

For unbounded state spaces, this function can return infinity.

◆ getMeasure()

double aikido::planner::ompl::GeometricStateSpace::getMeasure ( ) const

◆ interpolate()

void aikido::planner::ompl::GeometricStateSpace::interpolate ( const ::ompl::base::State *  from,
const ::ompl::base::State *  to,
double  t,
::ompl::base::State *  state 
) const
override

Computes the state that lies at time t in [0, 1] on the segment that connects from state to to state.

Parameters
[in]fromThe state that begins the segment.
[in]toThe state that ends the segment.
[in]tThe interpolation parameter (between 0 and 1).
[out]stateThe result of the interpolation.

◆ satisfiesBounds()

bool aikido::planner::ompl::GeometricStateSpace::satisfiesBounds ( const ::ompl::base::State *  state) const
override

Check if a state satisfies the boundsConstraint.

Parameters
[in]stateThe state to check.

Member Data Documentation

◆ mBoundsConstraint

constraint::ConstTestablePtr aikido::planner::ompl::GeometricStateSpace::mBoundsConstraint
private

Constraint to determine if a state is within statespace bounds.

◆ mBoundsProjection

constraint::ProjectablePtr aikido::planner::ompl::GeometricStateSpace::mBoundsProjection
private

A Projectable that projects a state within valid bounds of statespace.

◆ mDistance

distance::DistanceMetricPtr aikido::planner::ompl::GeometricStateSpace::mDistance
private

Distance metric to compute distance between states in the statespace.

◆ mInterpolator

statespace::ConstInterpolatorPtr aikido::planner::ompl::GeometricStateSpace::mInterpolator
private

An aikido interpolator to interpolate between states of the statespace.

◆ mMaxDistanceBetweenValidityChecks

double aikido::planner::ompl::GeometricStateSpace::mMaxDistanceBetweenValidityChecks
private

Collision checking resolution.

◆ mSampler

constraint::SampleablePtr aikido::planner::ompl::GeometricStateSpace::mSampler
private

State sampler used to sample states in the statespace.

◆ mStateSpace

statespace::ConstStateSpacePtr aikido::planner::ompl::GeometricStateSpace::mStateSpace
private

The AIKIDO statespace to be exposed to OMPL.