An SE(2) state space where distance is measured by the length of Dubins curves. More...
#include <ompl/base/spaces/DubinsStateSpace.h>

Public Types | |
enum | DubinsPathSegmentType { DUBINS_LEFT = 0, DUBINS_STRAIGHT = 1, DUBINS_RIGHT = 2 } |
The Dubins path segment type. | |
Public Member Functions | |
DubinsStateSpace (double turningRadius=1.0, bool isSymmetric=false) | |
virtual bool | isMetricSpace () const |
Return true if the distance function associated with the space is a metric. | |
virtual double | distance (const State *state1, const State *state2) const |
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, 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. 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, const double t, bool &firstTime, DubinsPath &path, State *state) const |
virtual bool | hasSymmetricDistance () const |
Check if the distance function on this state space is symmetric, i.e. distance(s1,s2) = distance(s2,s1). Default implementation returns true. | |
virtual bool | hasSymmetricInterpolate () const |
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 void | sanityChecks () const |
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. | |
DubinsPath | dubins (const State *state1, const State *state2) const |
Return the shortest Dubins path from SE(2) state state1 to SE(2) state state2. | |
Static Public Attributes | |
static const DubinsPathSegmentType | dubinsPathType [6][3] |
Dubins path types. | |
Protected Member Functions | |
virtual void | interpolate (const State *from, const DubinsPath &path, const double t, State *state) const |
Protected Attributes | |
double | rho_ |
Turning radius. | |
bool | isSymmetric_ |
Whether the distance is "symmetrized". |
Detailed Description
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
The classification scheme described there is not actually used, since it only applies to “long” paths.
Definition at line 65 of file DubinsStateSpace.h.
Member Data Documentation
const ompl::base::DubinsStateSpace::DubinsPathSegmentType base::DubinsStateSpace::dubinsPathType [static] |
{ { DUBINS_LEFT, DUBINS_STRAIGHT, DUBINS_LEFT }, { DUBINS_RIGHT, DUBINS_STRAIGHT, DUBINS_RIGHT }, { DUBINS_RIGHT, DUBINS_STRAIGHT, DUBINS_LEFT }, { DUBINS_LEFT, DUBINS_STRAIGHT, DUBINS_RIGHT }, { DUBINS_RIGHT, DUBINS_LEFT, DUBINS_RIGHT }, { DUBINS_LEFT, DUBINS_RIGHT, DUBINS_LEFT } }
Dubins path types.
Definition at line 72 of file DubinsStateSpace.h.
bool base::DubinsStateSpace::isSymmetric_ [protected] |
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.
Definition at line 155 of file DubinsStateSpace.h.
The documentation for this class was generated from the following files:
- ompl/base/spaces/DubinsStateSpace.h
- ompl/base/spaces/src/DubinsStateSpace.cpp