StateValidityChecker.h
128 virtual bool isValid(const State *state, double &dist, State *validState, bool &validStateAvailable) const
144 virtual double clearance(const State *state, State * /*validState*/, bool &validStateAvailable) const
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...
Definition: StateValidityChecker.h:128
StateValidityChecker(const SpaceInformationPtr &si)
Constructor.
Definition: StateValidityChecker.h:99
Clearance computation is not implemented.
Definition: StateValidityChecker.h:66
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...
Definition: StateValidityChecker.h:115
ClearanceComputationType
Specify the type of clearance computation.
Definition: StateValidityChecker.h:63
virtual double clearance(const State *) const
Report the distance to the nearest invalid state when starting from state. If the distance is negativ...
Definition: StateValidityChecker.h:136
StateValidityCheckerSpecs specs_
The specifications of the state validity checker (its capabilities)
Definition: StateValidityChecker.h:161
Properties that a state validity checker may have.
Definition: StateValidityChecker.h:60
The simplest state validity checker: all states are valid.
Definition: StateValidityChecker.h:165
bool isValid(const State *) const override
Always return true (all states are considered valid)
Definition: StateValidityChecker.h:179
bool hasValidDirectionComputation
Flag indicating that this state validity checker can return a direction that moves a state away from ...
Definition: StateValidityChecker.h:84
Abstract definition for a class checking the validity of states. The implementation of this class mus...
Definition: StateValidityChecker.h:90
Exact clearance computation is available.
Definition: StateValidityChecker.h:68
A shared pointer wrapper for ompl::base::SpaceInformation.
The base class for space information. This contains all the information about the space planning is d...
Definition: SpaceInformation.h:81
AllValidStateValidityChecker(SpaceInformation *si)
Constructor.
Definition: StateValidityChecker.h:169
A lower bound on clearance is computed.
Definition: StateValidityChecker.h:73
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 double clearance(const State *state, State *, bool &validStateAvailable) const
Report the distance to the nearest invalid state when starting from state, and if possible...
Definition: StateValidityChecker.h:144
const StateValidityCheckerSpecs & getSpecs() const
Return the specifications (capabilities of this state validity checker)
Definition: StateValidityChecker.h:151
SpaceInformation * si_
The instance of space information this state validity checker operates on.
Definition: StateValidityChecker.h:158
ClearanceComputationType clearanceComputationType
Value indicating the kind of clearance computation this StateValidityChecker can compute (if any)...
Definition: StateValidityChecker.h:80
AllValidStateValidityChecker(const SpaceInformationPtr &si)
Constructor.
Definition: StateValidityChecker.h:174