Loading...
Searching...
No Matches
ReedsSheppStateSpace.h
111 virtual void interpolate(const State *from, const State *to, double t, bool &firstTime, PathType &path,
125 virtual void interpolate(const State *from, const PathType &path, double t, State *state) const;
const ReedsSheppPathSegmentType * type_
Definition ReedsSheppStateSpace.h:90
double length_[5]
Definition ReedsSheppStateSpace.h:92
double totalLength_
Definition ReedsSheppStateSpace.h:94
void sanityChecks() const override
Convenience function that allows derived state spaces to choose which checks should pass (see SanityC...
Definition ReedsSheppStateSpace.h:114
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:104
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:510
PathType getPath(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:586
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:505
static const ReedsSheppPathSegmentType reedsSheppPathType[18][5]
Reeds-Shepp path types.
Definition ReedsSheppStateSpace.h:472
@ STATESPACE_INTERPOLATION
Check whether calling StateSpace::interpolate() works as expected.
Definition StateSpace.h:145
virtual void sanityChecks() const
Convenience function that allows derived state spaces to choose which checks should pass (see SanityC...
Definition StateSpace.cpp:603
double longestValidSegment_
The longest valid segment at the time setup() was called.
Definition StateSpace.h:543
unsigned int longestValidSegmentCountFactor_
The factor to multiply the value returned by validSegmentCount(). Rarely used but useful for things l...
Definition StateSpace.h:547
This namespace contains sampling based planning routines shared by both planning under geometric cons...
Definition ConstrainedSpaceInformation.h:55
Main namespace. Contains everything in this library.
Definition MultiLevelPlanarManipulatorDemo.cpp:66