Loading...
Searching...
No Matches
MotionValidator.h
99 virtual bool checkMotion(const State *s1, const State *s2, std::pair<State *, double> &lastValid) const = 0;
Abstract definition for a class checking the validity of motions – path segments between states....
Definition MotionValidator.h:65
SpaceInformation * si_
The instance of space information this state validity checker operates on.
Definition MotionValidator.h:133
double getValidMotionFraction() const
Get the fraction of segments that tested as valid.
Definition MotionValidator.h:120
unsigned int getCheckedMotionCount() const
Get the total number of segments tested, regardless of result.
Definition MotionValidator.h:114
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 tim...
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.
void resetMotionCounter()
Reset the counters for valid and invalid segments.
Definition MotionValidator.h:126
unsigned int getInvalidMotionCount() const
Get the number of segments that tested as invalid.
Definition MotionValidator.h:108
unsigned int getValidMotionCount() const
Get the number of segments that tested as valid.
Definition MotionValidator.h:102
A shared pointer wrapper for ompl::base::SpaceInformation.
The base class for space information. This contains all the information about the space planning is d...
Definition SpaceInformation.h:82
This namespace contains sampling based planning routines shared by both planning under geometric cons...
Definition ConstrainedSpaceInformation.h:55
Main namespace. Contains everything in this library.
Definition MultiLevelPlanarManipulatorDemo.cpp:66