Implement an OMPL MotionValidator.
More...
#include <aikido/planner/ompl/MotionValidator.hpp>
|
| MotionValidator (const ::ompl::base::SpaceInformationPtr &_si, double _maxDistBtwValidityChecks) |
| Constructor. More...
|
|
bool | checkMotion (const ::ompl::base::State *_s1, const ::ompl::base::State *_s2) const override |
| Check if the path between two states, _s1 and _s2, is valid. More...
|
|
bool | checkMotion (const ::ompl::base::State *_s1, const ::ompl::base::State *_s2, std::pair<::ompl::base::State *, double > &_lastValid) const override |
|
Implement an OMPL MotionValidator.
This class checks the validity of path segments between states.
◆ MotionValidator()
aikido::planner::ompl::MotionValidator::MotionValidator |
( |
const ::ompl::base::SpaceInformationPtr & |
_si, |
|
|
double |
_maxDistBtwValidityChecks |
|
) |
| |
Constructor.
- Parameters
-
_si | The SpaceInformation describing the planning space where this MotionValidator will be used |
_maxDistBtwValidityChecks | The maximum distance (under the distance metric defined on the planning StateSpace) between two points on the segment checked for validity |
◆ checkMotion() [1/2]
bool aikido::planner::ompl::MotionValidator::checkMotion |
( |
const ::ompl::base::State * |
_s1, |
|
|
const ::ompl::base::State * |
_s2 |
|
) |
| const |
|
override |
Check if the path between two states, _s1 and _s2, is valid.
This function assumes _s1 is valid.
- Parameters
-
_s1 | The state at the start of the segment |
_s2 | The state at the end of the segment |
◆ checkMotion() [2/2]
bool aikido::planner::ompl::MotionValidator::checkMotion |
( |
const ::ompl::base::State * |
_s1, |
|
|
const ::ompl::base::State * |
_s2, |
|
|
std::pair<::ompl::base::State *, double > & |
_lastValid |
|
) |
| const |
|
override |
- Parameters
-
| _s1 | The state at the start of the segment |
| _s2 | The state at the end of the segment |
[out] | _lastValid | The last valid state on the segment and the segment time of that state (between 0 and 1) |
◆ mSequenceResolution
double aikido::planner::ompl::MotionValidator::mSequenceResolution |
|
private |