ReedsSheppStateSpace.h
123 virtual void interpolate(const State *from, const ReedsSheppPath &path, double t, State *state) const;
127 };
148 bool checkMotion(const State *s1, const State *s2, std::pair<State *, double> &lastValid) const override;
The base class for space information. This contains all the information about the space planning is d...
Definition: SpaceInformation.h:145
A shared pointer wrapper for ompl::base::SpaceInformation.
double longestValidSegment_
The longest valid segment at the time setup() was called.
Definition: StateSpace.h:607
double length_[5]
Definition: ReedsSheppStateSpace.h:187
ReedsSheppPath reedsShepp(const State *state1, const State *state2) const
Return a shortest Reeds-Shepp path from SE(2) state state1 to SE(2) state state2.
Definition: ReedsSheppStateSpace.cpp:596
virtual void sanityChecks() const
Convenience function that allows derived state spaces to choose which checks should pass (see SanityC...
Definition: StateSpace.cpp:603
double totalLength_
Definition: ReedsSheppStateSpace.h:189
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:661
const ReedsSheppPathSegmentType * type_
Definition: ReedsSheppStateSpace.h:185
A Reeds-Shepp motion validator that only uses the state validity checker. Motions are checked for val...
Definition: ReedsSheppStateSpace.h:199
Abstract definition for a class checking the validity of motions – path segments between states....
Definition: MotionValidator.h:128
static const ReedsSheppPathSegmentType reedsSheppPathType[18][5]
Reeds-Shepp path types.
Definition: ReedsSheppStateSpace.h:171
unsigned int validSegmentCount(const State *state1, const State *state2) const override
Count how many segments of the "longest valid length" fit on the motion from state1 to state2.
Definition: ReedsSheppStateSpace.h:198
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:520
unsigned int longestValidSegmentCountFactor_
The factor to multiply the value returned by validSegmentCount(). Rarely used but useful for things l...
Definition: StateSpace.h:611
@ STATESPACE_INTERPOLATION
Check whether calling StateSpace::interpolate() works as expected.
Definition: StateSpace.h:209
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:515
void sanityChecks() const override
Convenience function that allows derived state spaces to choose which checks should pass (see SanityC...
Definition: ReedsSheppStateSpace.h:208