Class ReedsSheppStateSpace
Defined in File ReedsSheppStateSpace.h
Nested Relationships
Nested Types
Inheritance Relationships
Base Type
public ompl::base::SE2StateSpace
(Class SE2StateSpace)
Class Documentation
-
class ReedsSheppStateSpace : public ompl::base::SE2StateSpace
An SE(2) state space where distance is measured by the length of Reeds-Shepp curves.
The notation and solutions are taken from: J.A. Reeds and L.A. Shepp, “Optimal paths for a car that goes both forwards and backwards,” Pacific Journal of Mathematics, 145(2):367–393, 1990.
This implementation explicitly computes all 48 Reeds-Shepp curves and returns a shortest valid solution. This can be improved by using the configuration space partition described in: P. Souères and J.-P. Laumond, “Shortest paths synthesis for a car-like robot,” IEEE Trans. on Automatic Control, 41(5):672–688, May 1996.
Public Types
Public Functions
-
inline ReedsSheppStateSpace(double turningRadius = 1.0)
-
virtual double distance(const State *state1, const State *state2) const override
Computes distance between two states. This function satisfies the properties of a metric if isMetricSpace() is true, and its return value will always be between 0 and getMaximumExtent()
-
inline virtual 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. This is the max() of the counts returned by contained subspaces.
-
virtual 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. The memory location of state is not required to be different from the memory of either from or to.
-
virtual void interpolate(const State *from, const State *to, double t, bool &firstTime, PathType &path, State *state) const
-
inline virtual void sanityChecks() const override
Convenience function that allows derived state spaces to choose which checks should pass (see SanityChecks flags) and how strict the checks are. This just calls sanityChecks() with some default arguments.
Public Static Attributes
-
static const ReedsSheppPathSegmentType reedsSheppPathType[18][5]
Reeds-Shepp path types.
Protected Functions
Protected Attributes
-
double rho_
Turning radius.
-
class PathType
Complete description of a ReedsShepp path.
Public Functions
-
PathType(const ReedsSheppPathSegmentType *type = reedsSheppPathType[0], double t = std::numeric_limits<double>::max(), double u = 0., double v = 0., double w = 0., double x = 0.)
-
inline double length() const
-
PathType(const ReedsSheppPathSegmentType *type = reedsSheppPathType[0], double t = std::numeric_limits<double>::max(), double u = 0., double v = 0., double w = 0., double x = 0.)
-
inline ReedsSheppStateSpace(double turningRadius = 1.0)