Template Class VampMotionValidator

Inheritance Relationships

Base Type

Class Documentation

template<typename Robot, std::size_t rake = ::vamp::FloatVectorWidth>
class VampMotionValidator : public ompl::base::MotionValidator

Public Types

using Environment = ::vamp::collision::Environment<::vamp::FloatVector<rake>>

Public Functions

inline VampMotionValidator(ob::SpaceInformation *si, const Environment &env)
inline VampMotionValidator(const ob::SpaceInformationPtr &si, const Environment &env)
inline virtual auto checkMotion(const ob::State *s1, const ob::State *s2) const -> bool override

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.

inline auto checkMotion(const ob::State *s1, const ob::State *s2, std::pair<ob::State*, double> &last_valid) const -> bool override