A Dubins motion validator that only uses the state validity checker. Motions are checked for validity at a specified resolution. More...
#include <DubinsStateSpace.h>
Public Member Functions | |
DubinsMotionValidator (SpaceInformation *si) | |
DubinsMotionValidator (const SpaceInformationPtr &si) | |
virtual bool | checkMotion (const State *s1, const State *s2) const |
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 |
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... | |
![]() | |
MotionValidator (SpaceInformation *si) | |
Constructor. | |
MotionValidator (const SpaceInformationPtr &si) | |
Constructor. | |
virtual void | computeMotionCost (const State *s1, const State *s2, double &cost, std::pair< double, double > &bounds) const |
Compute the cost of a path segment from s1 to s2 (including endpoints) More... | |
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. | |
double | getValidMotionFraction (void) const |
Get the fraction of segments that tested as valid. | |
void | resetMotionCounter (void) |
Reset the counters for valid and invalid segments. | |
Additional Inherited Members | |
![]() | |
SpaceInformation * | si_ |
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. | |
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.
Definition at line 155 of file DubinsStateSpace.h.
|
virtual |
Check if the path between two states (from s1 to s2) is valid. This function assumes s1 is valid.
Implements ompl::base::MotionValidator.
Definition at line 386 of file DubinsStateSpace.cpp.
|
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.
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 NULL, 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. |
Implements ompl::base::MotionValidator.
Definition at line 341 of file DubinsStateSpace.cpp.