ompl::base::StateValidityChecker Class Referenceabstract
Abstract definition for a class checking the validity of states. The implementation of this class must be thread safe. More...
#include <ompl/base/StateValidityChecker.h>
Inheritance diagram for ompl::base::StateValidityChecker:
Public Member Functions | |
StateValidityChecker (SpaceInformation *si) | |
Constructor. | |
StateValidityChecker (const SpaceInformationPtr &si) | |
Constructor. | |
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(). | |
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, double &dist, State *validState, bool &validStateAvailable) const |
Return true if the state state is valid. In addition, set dist to the distance to the nearest invalid state (using clearance()). If a direction that moves state away from being invalid is available, a valid state in that direction is also set (validState). validStateAvailable is set to true if validState is updated. | |
virtual double | clearance (const 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 double | clearance (const State *state, State *, bool &validStateAvailable) const |
Report the distance to the nearest invalid state when starting from state, and if possible, also specify a valid state validState in the direction that moves away from the colliding state. The validStateAvailable flag is set to true if validState is updated. | |
const StateValidityCheckerSpecs & | getSpecs () const |
Return the specifications (capabilities of this state validity checker) | |
virtual bool | operator== (const StateValidityChecker &) const |
Checks for equivalence between two Statevaliditycheckers. | |
bool | operator!= (const StateValidityChecker &rhs) const |
Protected Attributes | |
SpaceInformation * | si_ |
The instance of space information this state validity checker operates on. | |
StateValidityCheckerSpecs | specs_ |
The specifications of the state validity checker (its capabilities) | |
Detailed Description
Abstract definition for a class checking the validity of states. The implementation of this class must be thread safe.
Definition at line 154 of file StateValidityChecker.h.
The documentation for this class was generated from the following file:
- ompl/base/StateValidityChecker.h