Dubins.jl Library

Dubins.DubinsIntermediateResultsType

This data structure holds the information to compute the Dubins path in the transformed coordinates where the initial $(x,y)$ is translated to the origin, the final the coordinate axis is rotated to make the x-axis aligned with the line joining the two points. The variable names follow the convention used in the paper "Classification of the Dubins set" by Andrei M. Shkel and Vladimir Lumelsky

source
Dubins.DubinsPathType

The data structure that holds the full dubins path.

Its data fields are as follows:

  • the initial configuration, $q_i$,
  • the params vector that contains the length of each segment, params,
  • the turn-radius, $\rho$, and,
  • the Dubins path type given by the @enum DubinsPathType
source
Dubins.dubins_extract_subpathMethod

Convenience function to extract a sub-path

  • path - an initialized path
  • $t$ - a length measure, where $0 < t <$ dubinspathlength(path)
  • return - zero on successful completion and the subpath
source
Dubins.dubins_pathMethod

Generate a path with a specified word from an initial configuratioon to a target configuration, with a specified turning radius

  • $q_0$ - a configuration specified by a 3-element vector $x$, $y$, $\theta$
  • $q_1$ - a configuration specified by a 3-element vector $x$, $y$, $\theta$
  • $\rho$ - turning radius of the vehicle
  • path_type - the specified path type to use
  • return - tuple (error code, dubins path). If error code != 0, then nothing is returned as the second argument
source
Dubins.dubins_path_endpointMethod

Convenience function to identify the endpoint of a path

  • path - an initialized path
  • return - tuple containing (zero on successful completion and the end configuration $[x,y,\theta]$)
source
Dubins.dubins_path_sampleMethod

Calculate the configuration along the path, using the parameter t

  • path - an initialized path
  • $t$ - length measure where $0 \leq t <$ dubinspathlength(path)
  • return - tuple containing non-zero error code if 't' is not in the correct range and the configuration result $[x, y, \theta]$
source
Dubins.dubins_path_sample_manyMethod

Walk along the path at a fixed sampling interval, calling the callback function at each interval

The sampling process continues until the whole path is sampled, or the callback returns a non-zero value

  • path - the path to sample

  • step_size - the distance along the path for subsequent samples

  • return - tuple (error code, configuration vector). If error code != 0, then nothing is returned as the second argument

source
Dubins.dubins_path_typeMethod

Extract the integer that represents which path type was used

  • path - an initialized path
  • return - one of LSL-0, LSR-1, RSL-2, RSR-3, RLR-4, LRL-5
source
Dubins.dubins_segmentMethod

Operators that transform an arbitrary point $q_i$, $[x, y, \theta]$, into an image point given a parameter $t$ and segment type

The three operators correspond to $L$, $R$, and $S$

  • $L(x, y, \theta, t) = [x, y, \theta] + [ \sin(\theta + t) - \sin(\theta), -\cos(\theta + t) + \cos(\theta), t]$

  • $R(x, y, \theta, t) = [x, y, \theta] + [-\sin(\theta - t) + \sin(\theta), \cos(\theta - t) - \cos(\theta), -t]$

  • $S(x, y, \theta, t) = [x, y, \theta] + [ \cos(\theta) * t, \sin(\theta) * t, 0]$

  • return - the image point as a 3-element vector

source
Dubins.dubins_segment_lengthMethod

Calculate the length of a specific segment of an initialized path

  • path - path to find the length of
  • $i$ - the segment for which the length is required (1-3)
  • return - segment length
source
Dubins.dubins_segment_length_normalizedMethod

Calculate the normalized length of a specific segment of an initialized path

  • path - path to find the length of
  • $i$ - the segment for which the length is required (1-3)
  • return - normalized segment length
source
Dubins.dubins_shortest_pathMethod

Generate a path from an initial configuration to a target configuration with a specified maximum turning radius

A configuration is given by $[x, y, \theta]$, where $\theta$ is in radians,

  • $q_0$ - a configuration specified by a 3-element vector $[x, y, \theta]$
  • $q_1$ - a configuration specified by a 3-element vector $[x, y, \theta]$
  • $\rho$ - turning radius of the vehicle
  • return - tuple (error code, dubins path). If error code != 0, then nothing is returned as the second argument
source
Dubins.dubins_wordMethod

The function to call the corresponding Dubins path based on the path_type

  • return - tuple (error code, path length as a vector for corresponding path type)
source
Dubins.silenceMethod

Suppresses information and warning messages output by Dubins, for fine grained control use the Memento package

source