Class DubinsStateSpace

Nested Relationships

Nested Types

Inheritance Relationships

Base Type

Class Documentation

class DubinsStateSpace : public ompl::base::SE2StateSpace

An SE(2) state space where distance is measured by the length of Dubins curves.

Note that this Dubins distance is not a proper distance metric, so nearest neighbor methods that rely on distance() being a metric (such as ompl::NearestNeighborsGNAT) will not always return the true nearest neighbors or get stuck in an infinite loop.

The notation and solutions in the code are taken from:

A.M. Shkel and V. Lumelsky, “Classification of the Dubins set,” Robotics and Autonomous Systems, 34(4):179-202, 2001. DOI:

10.1016/S0921-8890(00)00127-5

Public Types

enum DubinsPathSegmentType

The Dubins path segment type.

Values:

enumerator DUBINS_LEFT
enumerator DUBINS_STRAIGHT
enumerator DUBINS_RIGHT

Public Functions

inline DubinsStateSpace(double turningRadius = 1.0, bool isSymmetric = false)
inline virtual bool isMetricSpace() const override

Return true if the distance function associated with the space is a metric.

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()

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
virtual void interpolate(const State *from, const PathType &path, double t, State *state, double radius) const
inline virtual bool hasSymmetricDistance() const override

Check if the distance function on this state space is symmetric, i.e. distance(s1,s2) = distance(s2,s1). Default implementation returns true.

inline virtual bool hasSymmetricInterpolate() const override

Check if the interpolation function on this state space is symmetric, i.e. interpolate(from, to,

t, state) = interpolate(to, from, 1-t, state). Default implementation returns true.

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.

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.

PathType getPath(const State *state1, const State *state2) const

Return a shortest Dubins path from SE(2) state state1 to SE(2) state state2.

Public Static Functions

static const std::vector<std::vector<DubinsPathSegmentType>> &dubinsPathType()

Dubins path types.

static double distance(const State *state1, const State *state2, double radius)
static double symmetricDistance(const State *state1, const State *state2, double radius)
static PathType getPath(const State *state1, const State *state2, double radius)

Return a shortest Dubins path for a vehicle with given turning radius.

Protected Attributes

double rho_

Turning radius.

bool isSymmetric_

Whether the distance is “symmetrized”.

If true the distance from state s1 to state s2 is the same as the distance from s2 to s1. This is done by taking the minimum length of the Dubins curves that connect s1 to s2 and s2 to s1. If isSymmetric_ is true, then the distance no longer satisfies the triangle inequality.

class PathType

Complete description of a Dubins path.

Public Functions

inline PathType(const std::vector<DubinsPathSegmentType> &type = dubinsPathType()[0], double t = 0., double p = std::numeric_limits<double>::max(), double q = 0.)
inline double length() const

Public Members

const std::vector<DubinsPathSegmentType> *type_

Path segment types

double length_[3]

Path segment lengths

bool reverse_ = {false}

Whether the path should be followed “in reverse”

Friends

friend std::ostream &operator<<(std::ostream &os, const PathType &path)