Abstract definition for a class checking the validity of states. The implementation of this class must be thread safe. More...
#include <StateValidityChecker.h>
Public Member Functions | |
virtual double | clearance (const State *state, State *gradient, bool &gradientAvailable) const |
Report the distance to the nearest invalid state when starting from state, and if available, also set the gradient: the direction that moves away from the colliding state. gradientAvailable is set to true if gradient is updated. | |
virtual double | clearance (const State *state) const |
Report the distance to the nearest invalid state when starting from state. If the distance is negative, the value of clearance is the penetration depth. | |
virtual bool | isValid (const State *state, double &dist, State *gradient, bool &gradientAvailable) const |
Return true if the state state is valid. In addition, set dist to the distance to the nearest invalid state. If a direction that moves state away from being invalid is available, it is set in gradient. gradient is an element of the tangent space that contains state. gradientAvailable is set to true if gradient is updated. | |
virtual bool | isValid (const State *state, double &dist) const |
Return true if the state state is valid. In addition, set dist to the distance to the nearest invalid state. | |
virtual bool | isValid (const State *state) const =0 |
Return true if the state state is valid. Usually, this means at least collision checking. If it is possible that ompl::base::StateSpace::interpolate() or ompl::control::ControlSpace::propagate() return states that are outside of bounds, this function should also make a call to ompl::base::SpaceInformation::satisfiesBounds(). | |
StateValidityChecker (const SpaceInformationPtr &si) | |
Constructor. | |
StateValidityChecker (SpaceInformation *si) | |
Constructor. | |
virtual | ~StateValidityChecker (void) |
Protected Attributes | |
SpaceInformation * | si_ |
The instance of space information this state validity checker operates on. |
Abstract definition for a class checking the validity of states. The implementation of this class must be thread safe.
Definition at line 60 of file StateValidityChecker.h.
ompl::base::StateValidityChecker::StateValidityChecker | ( | SpaceInformation * | si | ) | [inline] |
Constructor.
Definition at line 65 of file StateValidityChecker.h.
ompl::base::StateValidityChecker::StateValidityChecker | ( | const SpaceInformationPtr & | si | ) | [inline] |
Constructor.
Definition at line 70 of file StateValidityChecker.h.
virtual ompl::base::StateValidityChecker::~StateValidityChecker | ( | void | ) | [inline, virtual] |
Definition at line 74 of file StateValidityChecker.h.
virtual double ompl::base::StateValidityChecker::clearance | ( | const State * | state, | |
State * | gradient, | |||
bool & | gradientAvailable | |||
) | const [inline, virtual] |
Report the distance to the nearest invalid state when starting from state, and if available, also set the gradient: the direction that moves away from the colliding state. gradientAvailable is set to true if gradient is updated.
Definition at line 109 of file StateValidityChecker.h.
virtual double ompl::base::StateValidityChecker::clearance | ( | const State * | state | ) | const [inline, virtual] |
Report the distance to the nearest invalid state when starting from state. If the distance is negative, the value of clearance is the penetration depth.
Definition at line 101 of file StateValidityChecker.h.
virtual bool ompl::base::StateValidityChecker::isValid | ( | const State * | state, | |
double & | dist, | |||
State * | gradient, | |||
bool & | gradientAvailable | |||
) | const [inline, virtual] |
Return true if the state state is valid. In addition, set dist to the distance to the nearest invalid state. If a direction that moves state away from being invalid is available, it is set in gradient. gradient is an element of the tangent space that contains state. gradientAvailable is set to true if gradient is updated.
Definition at line 93 of file StateValidityChecker.h.
virtual bool ompl::base::StateValidityChecker::isValid | ( | const State * | state, | |
double & | dist | |||
) | const [inline, virtual] |
Return true if the state state is valid. In addition, set dist to the distance to the nearest invalid state.
Definition at line 84 of file StateValidityChecker.h.
virtual bool ompl::base::StateValidityChecker::isValid | ( | const State * | state | ) | const [pure virtual] |
Return true if the state state is valid. Usually, this means at least collision checking. If it is possible that ompl::base::StateSpace::interpolate() or ompl::control::ControlSpace::propagate() return states that are outside of bounds, this function should also make a call to ompl::base::SpaceInformation::satisfiesBounds().
Implemented in ompl::base::AllValidStateValidityChecker, and ompl::control::ODEStateValidityChecker.
SpaceInformation* ompl::base::StateValidityChecker::si_ [protected] |
The instance of space information this state validity checker operates on.
Definition at line 118 of file StateValidityChecker.h.