ompl::base::MotionValidator Class Referenceabstract

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. More...

#include <ompl/base/MotionValidator.h>

Inheritance diagram for ompl::base::MotionValidator:

Public Member Functions

 MotionValidator (SpaceInformation *si)
 Constructor.
 
 MotionValidator (const SpaceInformationPtr &si)
 Constructor.
 
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. More...
 
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. More...
 
unsigned int getValidMotionCount () const
 Get the number of segments that tested as valid.
 
unsigned int getInvalidMotionCount () const
 Get the number of segments that tested as invalid.
 
unsigned int getCheckedMotionCount () const
 Get the total number of segments tested, regardless of result.
 
double getValidMotionFraction () const
 Get the fraction of segments that tested as valid.
 
void resetMotionCounter ()
 Reset the counters for valid and invalid segments.
 

Protected Attributes

SpaceInformationsi_
 The instance of space information this state validity checker operates on.
 
unsigned int valid_
 Number of valid segments.
 
unsigned int invalid_
 Number of invalid segments.
 

Detailed Description

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.

Definition at line 128 of file MotionValidator.h.

Member Function Documentation

◆ checkMotion() [1/2]

virtual bool ompl::base::MotionValidator::checkMotion ( const State s1,
const State s2 
) const
pure virtual

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.

Implemented in ompl::base::DubinsMotionValidator, ompl::base::ReedsSheppMotionValidator, ompl::base::DiscreteMotionValidator, and ompl::base::ConstrainedMotionValidator.

◆ checkMotion() [2/2]

virtual bool ompl::base::MotionValidator::checkMotion ( const State s1,
const State s2,
std::pair< State *, double > &  lastValid 
) const
pure virtual

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.

Parameters
s1start state of the motion to be checked (assumed to be valid)
s2final state of the motion to be checked
lastValidfirst: 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.
Note
This function updates the number of valid and invalid segments.

Implemented in ompl::base::DubinsMotionValidator, ompl::base::ReedsSheppMotionValidator, ompl::base::DiscreteMotionValidator, and ompl::base::ConstrainedMotionValidator.


The documentation for this class was generated from the following file: