ReedsSheppStateSpace.h
140 virtual bool checkMotion(const State *s1, const State *s2, std::pair<State*, double> &lastValid) const;
double length_[5]
Definition: ReedsSheppStateSpace.h:84
double totalLength_
Definition: ReedsSheppStateSpace.h:86
const ReedsSheppPathSegmentType * type_
Definition: ReedsSheppStateSpace.h:82
Complete description of a ReedsShepp path.
Definition: ReedsSheppStateSpace.h:73
static const ReedsSheppPathSegmentType reedsSheppPathType[18][5]
Reeds-Shepp path types.
Definition: ReedsSheppStateSpace.h:71
Abstract definition for a class checking the validity of motions – path segments between states...
Definition: MotionValidator.h:65
virtual void interpolate(const State *from, const State *to, const double t, State *state) const
Computes the state that lies at time t in [0, 1] on the segment that connects from state to to state...
Definition: ReedsSheppStateSpace.cpp:547
virtual void sanityChecks() const
Convenience function that allows derived state spaces to choose which checks should pass (see SanityC...
Definition: ReedsSheppStateSpace.h:101
A Reeds-Shepp motion validator that only uses the state validity checker. Motions are checked for val...
Definition: ReedsSheppStateSpace.h:125
A boost 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:86
virtual void sanityChecks() const
Convenience function that allows derived state spaces to choose which checks should pass (see SanityC...
Definition: StateSpace.cpp:591
An SE(2) state space where distance is measured by the length of Reeds-Shepp curves.
Definition: ReedsSheppStateSpace.h:64
virtual double distance(const State *state1, const State *state2) const
Computes distance between two states. This function satisfies the properties of a metric if isMetricS...
Definition: ReedsSheppStateSpace.cpp:542
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:621
Check whether calling StateSpace::interpolate() works as expected.
Definition: StateSpace.h:141