ompl::base::ConstrainedMotionValidator Class Reference
Constrained configuration space specific implementation of checkMotion() that uses discreteGeodesic(). More...
#include <ompl/base/spaces/constraint/ConstrainedStateSpace.h>
Inheritance diagram for ompl::base::ConstrainedMotionValidator:
Public Member Functions | |
ConstrainedMotionValidator (SpaceInformation *si) | |
Constructor. More... | |
ConstrainedMotionValidator (const SpaceInformationPtr &si) | |
Constructor. | |
bool | checkMotion (const State *s1, const State *s2) const override |
Return whether we can step from s1 to s2 along the manifold without collision. | |
bool | checkMotion (const State *s1, const State *s2, std::pair< State *, double > &lastValid) const override |
Return whether we can step from s1 to s2 along the manifold without collision. If not, return the last valid state and its interpolation parameter in lastValid. More... | |
Public Member Functions inherited from ompl::base::MotionValidator | |
MotionValidator (SpaceInformation *si) | |
Constructor. | |
MotionValidator (const SpaceInformationPtr &si) | |
Constructor. | |
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 | |
const ConstrainedStateSpace & | ss_ |
Space in which we check motion. | |
Protected Attributes inherited from ompl::base::MotionValidator | |
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. | |
Detailed Description
Constrained configuration space specific implementation of checkMotion() that uses discreteGeodesic().
Definition at line 98 of file ConstrainedStateSpace.h.
Constructor & Destructor Documentation
◆ ConstrainedMotionValidator()
ompl::base::ConstrainedMotionValidator::ConstrainedMotionValidator | ( | SpaceInformation * | si | ) |
Member Function Documentation
◆ checkMotion()
|
overridevirtual |
Return whether we can step from s1 to s2 along the manifold without collision. If not, return the last valid state and its interpolation parameter in lastValid.
- Note
- The interpolation parameter will not likely reproduce the last valid state if used in interpolation since the distance between the last valid state and s2 is estimated using the ambient metric.
Implements ompl::base::MotionValidator.
Definition at line 60 of file ConstrainedStateSpace.cpp.
The documentation for this class was generated from the following files:
- ompl/base/spaces/constraint/ConstrainedStateSpace.h
- ompl/base/spaces/constraint/src/ConstrainedStateSpace.cpp