Template Class DubinsMotionValidator

Inheritance Relationships

Base Type

Class Documentation

template<class Dubins2DStateSpace>
class DubinsMotionValidator : public ompl::base::MotionValidator

A Dubins motion validator that only uses the state validity checker. Motions are checked for validity at a specified resolution.

This motion validator is almost identical to the DiscreteMotionValidator except that it remembers the optimal DubinsPath between different calls to interpolate.

Public Functions

inline DubinsMotionValidator(SpaceInformation *si)
inline DubinsMotionValidator(const SpaceInformationPtr &si)
~DubinsMotionValidator() override = default
inline virtual bool checkMotion(const State *s1, const State *s2) const override

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.

inline virtual bool checkMotion(const State *s1, const State *s2, std::pair<State*, double> &lastValid) const override

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.