15.3.1 Dubins Curves

Recall the Dubins version of the simple car given in Section 13.1.2. The system was specified in (13.15). It is assumed here that the car moves at constant forward speed, $ u_s
= 1$. The other important constraint is the maximum steering angle $ \phi_{max}$, which results in a minimum turning radius $ \rho_{min}$. As the car travels, consider the length of the curve in $ {\cal W}= {\mathbb{R}}^2$ traced out by a pencil attached to the center of the rear axle. This is the location of the body-frame origin in Figure 13.1. The task is to minimize the length of this curve as the car travels between any $ {q_{I}}$ and $ {q_{G}}$. Due to $ \rho_{min}$, this can be considered as a bounded-curvature shortest-path problem. If $ \rho_{min} = 0$, then there is no curvature bound, and the shortest path follows a straight line in $ {\mathbb{R}}^2$. In terms of a cost functional of the form (8.39), the criterion to optimize is

$\displaystyle L({\tilde q},{\tilde{u}}) = \int_0^{t_F} \sqrt{{\dot x}(t)^2 + {\dot y}(t)^2} dt ,$ (15.42)

in which $ t_F$ is the time at which $ {q_{G}}$ is reached, and a configuration is denoted as $ q = (x,y,\theta)$. If $ {q_{G}}$ is not reached, then it is assumed that $ L({\tilde q},{\tilde{u}}) = \infty$.

Since the speed is constant, the system can be simplified to

\begin{displaymath}\begin{split}{\dot x}& = \cos \theta  {\dot y}& = \sin \theta  {\dot \theta}& = u , \end{split}\end{displaymath} (15.43)

in which $ u$ is chosen from the interval $ U = [-\tan \phi_{max},\tan
\phi_{max}]$. This implies that (15.42) reduces to optimizing the time $ t_F$ to reach $ {q_{G}}$ because the integrand reduces to $ 1$. For simplicity, assume that $ \tan\phi = 1$. The following results also hold for any $ \phi_{max} \in (0,\pi/2)$.

Figure 15.3: The three motion primitives from which all optimal curves for the Dubins car can be constructed.
\begin{figure}\begin{center}
\begin{tabular}{\vert c\vert c\vert} \hline
Symbol ...
... \hline
L & 1  \hline
R & -1  \hline
\end{tabular}\end{center}
\end{figure}

It was shown in [294] that between any two configurations, the shortest path for the Dubins car can always be expressed as a combination of no more than three motion primitives. Each motion primitive applies a constant action over an interval of time. Furthermore, the only actions that are needed to traverse the shortest paths are $ u \in \{-1,0,1\}$. The primitives and their associated symbols are shown in Figure 15.3. The $ S$ primitive drives the car straight ahead. The $ L$ and $ R$ primitives turn as sharply as possible to the left and right, respectively. Using these symbols, each possible kind of shortest path can be designated as a sequence of three symbols that corresponds to the order in which the primitives are applied. Let such a sequence be called a word . There is no need to have two consecutive primitives of the same kind because they can be merged into one. Under this observation, ten possible words of length three are possible. Dubins showed that only these six words are possibly optimal:

$\displaystyle \{ LRL,\; RLR, \; LSL,\; LSR,\; RSL,\; RSR \} .$ (15.44)

The shortest path between any two configurations can always be characterized by one of these words. These are called the Dubins curves.

Figure 15.4: The trajectories for two words are shown in $ {\cal W}= {\mathbb{R}}^2$.
\begin{figure}\begin{center}
\begin{tabular}{cc}
\psfig{file=figs/dubinsrsl.eps,...
...amma$ & $R_\alpha L_\beta R_\gamma$ \\
\end{tabular}
\end{center}\end{figure}

To be more precise, the duration of each primitive should also be specified. For $ L$ or $ R$, let a subscript denote the total amount of rotation that accumulates during the application of the primitive. For $ S$, let a subscript denote the total distance traveled. Using such subscripts, the Dubins curves can be more precisely characterized as

$\displaystyle \{ L_\alpha   R_\beta   L_\gamma, \; R_\alpha   L_\beta   R_\...
..., R_\gamma, \; R_\alpha   S_d   L_\gamma, \; R_\alpha   S_d   R_\gamma \} ,$ (15.45)

in which $ \alpha, \gamma \in [0,2 \pi)$, $ \beta \in (\pi,2 \pi)$, and $ d \geq 0$. Figure 15.4 illustrates two cases. Note that $ \beta$ must be greater than $ \pi $ (if it is less, then some other word becomes optimal).

It will be convenient to invent a compressed form of the words to group together paths that are qualitatively similar. This will be particularly valuable when Reeds-Shepp curves are introduced in Section 15.3.2 because there are 46 of them, as opposed to $ 6$ Dubins curves. Let $ C$ denote a symbol that means ``curve,'' and represents either $ R$ or $ L$. Using $ C$, the six words in (15.44) can be compressed to only two base words:

$\displaystyle \{ CCC, \; CSC \} .$ (15.46)

In this compressed form, remember that two consecutive $ C$s must be filled in by distinct turns ($ RR$ and $ LL$ are not allowed as subsequences). In compressed form, the base words can be specified more precisely as

$\displaystyle \{ C_\alpha   C_\beta   C_\gamma, \; C_\alpha   S_d   C_\gamma \} ,$ (15.47)

in which $ \alpha, \gamma \in [0,2 \pi)$, $ \beta \in (\pi,2 \pi)$, and $ d \geq 0$.

Figure 15.5: A slice at $ \theta = \pi $ of the partition into word-invariant cells for the Dubins car. The circle is centered on the origin.
\begin{figure}\centerline{\psfig{figure=figs/dubinsslice.eps,height=3.0truein} }\end{figure}

Powerful information has been provided so far for characterizing the shortest paths; however, for a given $ {q_{I}}$ and $ {q_{G}}$, two problems remain:

  1. Which of the six words in (15.45) yields the shortest path between $ {q_{I}}$ and $ {q_{G}}$?
  2. What are the values of the subscripts, $ \alpha$, $ \beta$, $ \gamma$, and $ d$ for the particular word?
To use the Dubins curves as an LPM, these questions should be answered efficiently. One simple approach is to try all six words and choose the shortest one. The parameters for each word can be determined by tracing out minimum-radius circles from $ {q_{I}}$ and $ {q_{G}}$, as shown in Figure 14.23. Another way is to use the precise characterization of the regions over which a particular word is optimal. Suppose that $ {q_{G}}$ is fixed at $ (0,0,0)$. Based on the possible placements of $ {q_{I}}$, the C-space can be partitioned into cells for which the same word is optimal. The cells and their boundaries are given precisely in [903]. As an example, a slice of the cell decomposition for $ \theta = \pi $ is shown in Figure 15.5.

Figure 15.6: Level sets of the Dubins metric are shown in the plane. Along two circular arcs, the metric is discontinuous (courtesy of Philippe Souères).
\begin{figure}\centerline{\psfig{file=figs/soueres.eps,width=2.0in}}\end{figure}

In addition to use as an LPM, the resulting cost of the shortest path may be a useful distance function in many sampling-based planning algorithms. This is sometimes called the Dubins metric (it is not, however, a true metric because it violates the symmetry axiom). This can be considered as the optimal cost-to-go $ G^*$. It could have been computed approximately using the dynamic programming approach in Section 14.5; however, thanks to careful analysis, the exact values are known. One interesting property of the Dubins metric is that it is discontinuous; see Figure 15.6. Compare the cost of traveling $ \pi/2$ using the $ R$ primitive to the cost of traveling to a nearby point that would require a smaller turning radius than that achieved by the $ R$ primitive. The required action does not exist in $ U$, and the point will have to be reached by a longer sequence of primitives. The discontinuity in $ G^*$ is enabled by the fact that the Dubins car fails to possess the STLC property from Section 15.1.3. For STLC systems, $ G^*$ is continuous.

Steven M LaValle 2012-04-20