37 #ifndef OMPL_BASE_STATE_VALIDITY_CHECKER_
38 #define OMPL_BASE_STATE_VALIDITY_CHECKER_
40 #include "ompl/base/State.h"
41 #include "ompl/util/ClassForward.h"
50 OMPL_CLASS_FORWARD(SpaceInformation);
55 OMPL_CLASS_FORWARD(StateValidityChecker);
64 enum ClearanceComputationType
109 virtual bool isValid(
const State *state)
const = 0;
122 virtual bool isValid(
const State *state,
double &dist,
State *validState,
bool &validStateAvailable)
const
124 dist =
clearance(state, validState, validStateAvailable);
140 validStateAvailable =
false;
StateValidityChecker(const SpaceInformationPtr &si)
Constructor.
virtual double clearance(const State *) const
Report the distance to the nearest invalid state when starting from state. If the distance is negativ...
StateValidityCheckerSpecs specs_
The specifications of the state validity checker (its capabilities)
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...
Properties that a state validity checker may have.
The simplest state validity checker: all states are valid.
bool hasValidDirectionComputation
Flag indicating that this state validity checker can return a direction that moves a state away from ...
const StateValidityCheckerSpecs & getSpecs(void) const
Return the specifications (capabilities of this state validity checker)
Abstract definition for a class checking the validity of states. The implementation of this class mus...
StateValidityChecker(SpaceInformation *si)
Constructor.
AllValidStateValidityChecker(SpaceInformation *si)
Constructor.
Definition of an abstract 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().
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...
SpaceInformation * si_
The instance of space information this state validity checker operates on.
virtual bool isValid(const State *) const
Always return true (all states are considered valid)
ClearanceComputationType clearanceComputationType
Value indicating the kind of clearance computation this StateValidityChecker can compute (if any)...
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...
AllValidStateValidityChecker(const SpaceInformationPtr &si)
Constructor.