37 #ifndef OMPL_BASE_MOTION_VALIDATOR_
38 #define OMPL_BASE_MOTION_VALIDATOR_
40 #include "ompl/base/State.h"
41 #include "ompl/util/ClassForward.h"
50 OMPL_CLASS_FORWARD(SpaceInformation);
55 OMPL_CLASS_FORWARD(MotionValidator);
86 virtual bool checkMotion(
const State *s1,
const State *s2)
const = 0;
96 virtual bool checkMotion(
const State *s1,
const State *s2, std::pair<State*, double> &lastValid)
const = 0;
unsigned int invalid_
Number of invalid segments.
double getValidMotionFraction(void) const
Get the fraction of segments that tested as valid.
virtual bool checkMotion(const State *s1, const State *s2) const =0
Check if the path between two states (from s1 to s2) is valid. This function assumes s1 is valid...
SpaceInformation * si_
The instance of space information this state validity checker operates on.
unsigned int valid_
Number of valid segments.
Abstract definition for a class checking the validity of motions – path segments between states...
void resetMotionCounter(void)
Reset the counters for valid and invalid segments.
MotionValidator(const SpaceInformationPtr &si)
Constructor.
MotionValidator(SpaceInformation *si)
Constructor.
unsigned int getValidMotionCount(void) const
Get the number of segments that tested as valid.
unsigned int getInvalidMotionCount(void) const
Get the number of segments that tested as invalid.