Class MotionValidator
Defined in File MotionValidator.h
Inheritance Relationships
Derived Types
public ompl::base::ConstrainedMotionValidator
(Class ConstrainedMotionValidator)public ompl::base::DiscreteMotionValidator
(Class DiscreteMotionValidator)public ompl::base::Dubins3DMotionValidator< Dubins3DStateSpace >
(Template Class Dubins3DMotionValidator)public ompl::base::DubinsMotionValidator< Dubins2DStateSpace >
(Template Class DubinsMotionValidator)
Class Documentation
-
class MotionValidator
Abstract definition for a class checking the validity of motions — path segments between states. This is often called a local planner. The implementation of this class must be thread safe.
Subclassed by ompl::base::ConstrainedMotionValidator, ompl::base::DiscreteMotionValidator, ompl::base::Dubins3DMotionValidator< Dubins3DStateSpace >, ompl::base::DubinsMotionValidator< Dubins2DStateSpace >
Public Functions
-
inline MotionValidator(SpaceInformation *si)
Constructor.
-
inline MotionValidator(const SpaceInformationPtr &si)
Constructor.
-
virtual ~MotionValidator() = default
-
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.
Note
This function updates the number of valid and invalid segments.
-
virtual bool checkMotion(const State *s1, const State *s2, std::pair<State*, double> &lastValid) const = 0
Check if the path between two states is valid. Also compute the last state that was valid and the time of that state. The time is used to parametrize the motion from s1 to s2, s1 being at t = 0 and s2 being at t = 1. This function assumes s1 is valid.
Note
This function updates the number of valid and invalid segments.
- Parameters:
s1 – start state of the motion to be checked (assumed to be valid)
s2 – final state of the motion to be checked
lastValid – first: storage for the last valid state (may be nullptr, if the user does not care about the exact state); this need not be different from s1 or s2. second: the time (between 0 and 1) of the last valid state, on the motion from s1 to s2. If the function returns false, lastValid.first must be set to a valid state, even if that implies copying s1 to lastValid.first (in case lastValid.second = 0). If the function returns true, lastValid.first and lastValid.second should not be modified.
-
inline unsigned int getValidMotionCount() const
Get the number of segments that tested as valid.
-
inline unsigned int getInvalidMotionCount() const
Get the number of segments that tested as invalid.
-
inline unsigned int getCheckedMotionCount() const
Get the total number of segments tested, regardless of result.
-
inline double getValidMotionFraction() const
Get the fraction of segments that tested as valid.
-
inline void resetMotionCounter()
Reset the counters for valid and invalid segments.
Protected Attributes
-
SpaceInformation *si_
The instance of space information this state validity checker operates on.
-
mutable unsigned int valid_
Number of valid segments.
-
mutable unsigned int invalid_
Number of invalid segments.
-
inline MotionValidator(SpaceInformation *si)