ReedsSheppStateSpace.h
117 virtual void interpolate(const State *from, const ReedsSheppPath &path, double t, State *state) const;
142 bool checkMotion(const State *s1, const State *s2, std::pair<State *, double> &lastValid) const override;
double length_[5]
Definition: ReedsSheppStateSpace.h:91
double distance(const State *state1, const State *state2) const override
Computes distance between two states. This function satisfies the properties of a metric if isMetricS...
Definition: ReedsSheppStateSpace.cpp:513
bool checkMotion(const State *s1, const State *s2) const override
Check if the path between two states (from s1 to s2) is valid. This function assumes s1 is valid...
Definition: ReedsSheppStateSpace.cpp:659
void interpolate(const State *from, const State *to, double t, State *state) const override
Computes the state that lies at time t in [0, 1] on the segment that connects from state to to state...
Definition: ReedsSheppStateSpace.cpp:518
double totalLength_
Definition: ReedsSheppStateSpace.h:93
const ReedsSheppPathSegmentType * type_
Definition: ReedsSheppStateSpace.h:89
Complete description of a ReedsShepp path.
Definition: ReedsSheppStateSpace.h:77
static const ReedsSheppPathSegmentType reedsSheppPathType[18][5]
Reeds-Shepp path types.
Definition: ReedsSheppStateSpace.h:75
Abstract definition for a class checking the validity of motions – path segments between states...
Definition: MotionValidator.h:64
void sanityChecks() const override
Convenience function that allows derived state spaces to choose which checks should pass (see SanityC...
Definition: ReedsSheppStateSpace.h:106
A Reeds-Shepp motion validator that only uses the state validity checker. Motions are checked for val...
Definition: ReedsSheppStateSpace.h:129
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:81
An SE(2) state space where distance is measured by the length of Reeds-Shepp curves.
Definition: ReedsSheppStateSpace.h:63
virtual void sanityChecks() const
Convenience function that allows derived state spaces to choose which checks should pass (see SanityC...
ReedsSheppPath reedsShepp(const State *state1, const State *state2) const
Return the shortest Reeds-Shepp path from SE(2) state state1 to SE(2) state state2.
Definition: ReedsSheppStateSpace.cpp:594
Check whether calling StateSpace::interpolate() works as expected.
Definition: StateSpace.h:145