Aikido
|
Wraps an aikido StateSpace into a space recognized by OMPL. More...
#include <aikido/planner/ompl/GeometricStateSpace.hpp>
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... | |
Wraps an aikido StateSpace into a space recognized by OMPL.
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.
[in] | sspace | The aikido::statespace::StateSpace to expose to OMPL |
[in] | interpolator | An aikido interpolator used by the interpolate method |
[in] | dmetric | The distance metric to use to compute distance between two states in the StateSpace |
[in] | sampler | A state sampler used to sample new states in the StateSpace |
[in] | boundsConstraint | A Testable used to determine whether states fall with in bounds defined on the space. |
[in] | boundsProjection | A Projectable that can be used to project a state back within the valid boundary defined on the space. |
[in] | maxDistanceBetweenValidityChecks | The 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. |
|
override |
Allocate an instance of the state sampler for this space.
|
override |
Allocate a state that can store a point in the described space.
::ompl::base::State* aikido::planner::ompl::GeometricStateSpace::allocState | ( | const statespace::StateSpace::State * | state | ) | const |
Allocate a state constaining a copy of the aikido state.
[in] | state | The aikido state to copy and wrap in an OMPL state |
|
override |
Copy the value of one state to another.
[out] | destination | The state to copy to. |
[in] | source | The state to copy from. |
|
override |
Computes distance between two states using the dmetric.
[in] | state1 | The first state. |
[in] | state2 | The second state. |
|
override |
Bring the state within the bounds of the statespace using boundsProjection.
[in] | state | The state to modify. |
|
override |
Check state equality.
Returns true if the distance between the states less than EQUALITY_EPSILON.
[in] | state1 | The first state |
[in] | state2 | The second state |
|
override |
Free the memory of the allocated state.
This also frees the memory of the wrapped aikido state.
[in] | state | The state to free. |
statespace::ConstStateSpacePtr aikido::planner::ompl::GeometricStateSpace::getAikidoStateSpace | ( | ) | const |
Return the Aikido StateSpace that this OMPL StateSpace wraps.
aikido::constraint::ConstTestablePtr aikido::planner::ompl::GeometricStateSpace::getBoundsConstraint | ( | ) | const |
Return the bounds constraint for the statespace.
Used to specify constraints to the OMPL planner.
|
override |
Get the dimension of the space.
aikido::statespace::ConstInterpolatorPtr aikido::planner::ompl::GeometricStateSpace::getInterpolator | ( | ) | const |
Return the interpolator used to interpolate between states in the space.
double aikido::planner::ompl::GeometricStateSpace::getMaxDistanceBetweenValidityChecks | ( | ) | const |
Returns the collision checking resolution.
|
override |
Get the maximum value a call to distance() can return (or an upper bound).
For unbounded state spaces, this function can return infinity.
double aikido::planner::ompl::GeometricStateSpace::getMeasure | ( | ) | const |
|
override |
Computes the state that lies at time t in [0, 1] on the segment that connects from state to to state.
[in] | from | The state that begins the segment. |
[in] | to | The state that ends the segment. |
[in] | t | The interpolation parameter (between 0 and 1). |
[out] | state | The result of the interpolation. |
|
override |
Check if a state satisfies the boundsConstraint.
[in] | state | The state to check. |
|
private |
Constraint to determine if a state is within statespace bounds.
|
private |
A Projectable that projects a state within valid bounds of statespace.
|
private |
Distance metric to compute distance between states in the statespace.
|
private |
An aikido interpolator to interpolate between states of the statespace.
|
private |
Collision checking resolution.
|
private |
State sampler used to sample states in the statespace.
|
private |
The AIKIDO statespace to be exposed to OMPL.