1 Introduction

Mobile robot applications are becoming progressively more demanding in terms of expected throughput and agility. For instance, sentry robots travel at speeds exceeding 50 km/h while monitoring for suspect objects (GUARDIUM-UGV 2012; GUSS 2012). Another example is DARPA’s Urban Challenge, where autonomous cars were required to travel at speeds exceeding 20 miles/h while demonstrating safe behavior under urban traffic conditions (Buehler et al. 2010; DARPA 2007). This paper addresses the problem of navigating fast autonomous mobile robots between stationary obstacles while attempting to minimize total travel time subject to velocity dependent safety constraints. According to the classical path planning approach, one first determines a collision free path using the robot’s configuration space, then selects a time parametrization that attempts to minimize total travel time subject to velocity-dependent safety constraints (Iagnemma et al. 2008; Kant and Zucker 1986; Shiller and Gwo 1991). The more general approach of planning a path in a space that includes the robot position as well as velocity is a relatively unexplored area in robotics. This paper proposes a planning methodology in position-velocity configuration space. In this space, velocity dependent safety constraints can be treated on equal footing with obstacle avoidance constraints. Moreover, pseudo time optimal paths can readily be computed in this space.

Some notable planning approaches that account for the robot position and velocity are as follows. The dynamic window approach plans the robot’s path within a finite time horizon, by minimizing a velocity dependent cost function which encodes collision safety as well as target reachability constraints (Brock and Khatib 1999; Fox et al. 1997). The dynamic window approach was successfully implemented on the RHINO robot to guide museum visitors (Burgard et al. 1999). Another approach is the method of inevitable collision states (Fraichard 2007; Petti et al. 2005). This method encodes the surrounding obstacles as well as the robot’s braking capabilities into first-order differential equations. Numerical integration of these equations gives the inevitable collision states that can be incorporated into any fast mobile robot navigation scheme.

Other planning approaches were specifically designed for environments containing obstacles as well as other mobile agents. The velocity obstacle approach models the kinematically feasible velocities that prevent collision with obstacles and moving agents as a cone of permitted velocities (Fiorini and Shiller 1998; Snape et al. 2011). The robot selects at discrete steps the maximal velocity within the allowed cone which locally leads the robot to the target. The accessibility graph method connects the robot’s current state with feasible states at the next time step (Fujimura and Samet 1989). The graph connectivity depends on the surrounding obstacles and on linearly predicted motion of any moving agents. The graph is used to select a constant-velocity path leading to the target while avoiding other mobile agents. However, the method does not ensure velocity dependent safety constraints along the selected path. The RRT method, (Lavalle 1998; LaValle and Kuffner 2000, 2001), or rapidly-exploring random tree, constructs a search tree incrementally. The RRT’s edges are constructed in the state-space in such way that reduces the distance of a randomly-chosen point to the tree with a high speed and feasible maneuver. Searching the RRT for a collision free and high speed path is highly efficient when bias distribution of the random points towards the goal is added. However, due to the randomized nature of the method it may lead to local minima which prevent from reaching the goal.

The approach closest to the one proposed here is the kinodynamics approach (Donald et al. 1993; LaValle and Kuffner 2001). This approach discretizes position-velocity space into a regular grid, then searches the obstacle-free portion of the grid for an approximate shortest path subject to velocity dependent safety constraints. The kinodynamics approach requires a huge grid in complex environments (Hsu et al. 2002; LaValle and Kuffner 2001). The method’s running time is proportional to the grid size and can be very high in complex environments. Rather than discretize position-velocity space, this paper offers a more analytic approach. Using Morse theory, this paper identifies a natural cellular decomposition of the free position-velocity space into cells. The cells’ adjacency graph provides a highly reduced data structure whose size is linear in the number of obstacle features. A search along the cells’ adjacency graph yields a safe path from start to target which provides an acceptable approximation for the time optimal path.

This paper considers planar environments populated by stationary obstacles whose location is known to the robot. The assumption of stationary obstacles is a conservative approach, suitable for environments where emergency events occur along obstacle edges or just beyond corners obstructed by obstacles. For instance, an autonomous vehicle moving in an urban environment may detect another vehicle suddenly emerging from its parking space. By maintaining suitable safe velocity, the moving vehicle can brake and prevent collision with the emerging vehicle. More generally, any environment in which emergency events can be detected at a distance exceeding the robot’s braking distance can be modeled according to the method proposed in this paper. The extension to environments containing other mobile agents will be considered in future work.

There are two main safety concerns during execution of fast mobile robot tasks. The first is to ensure that the robot will always be able to reach a full stop without colliding with any of the stationary obstacles or moving agents (Fraichard 2007; Petti et al. 2005). The second is to ensure that the robot will not slide or tip-over while taking sharp turns at high velocity. This paper models the uniform braking constraint as vc-obstacles in position-velocity configuration space. The vc-obstacles’ cross section increases monotonically along the velocity coordinate. The paper characterizes the critical points where two vc-obstacles meet for the first time and locally disconnect the free position-velocity configuration space. In the physical environment, these are critical events where the robot’s velocity becomes too large to support safe passage between neighboring obstacles. The paper next describes a cellular decomposition of the free position-velocity space which is based on these critical points. An adjacency graph is constructed for the cellular decomposition, such that its edges project onto the Voronoi diagram of the planar environment. A specialized search algorithm called the vc-method finds an approximate time-minimal path along the adjacency graph. Finally, the path’s vertices are smoothed to ensure safe turning at the prescribed path velocity. The resulting path leads the robot from start to target with maximum velocity while guaranteeing safe braking and turning along the path.

The paper is structured as follows. Section 2 describes the main velocity dependent safety constraints governing high-speed mobile robot motion. Section 3 introduces position-velocity space and the vc-obstacles induced by the safe braking constraint in this space. Section 4 defines a cellular decomposition of the free position-velocity space. Section 5 constructs an adjacency graph for the cellular decomposition. A search along this graph yields a pseudo time optimal path that maintains safe braking distance from the obstacles. Practical path realization issues such as path turning safety are considered in Sect. 6. Simulations and experimental results of the method are discussed in Sects.  7 and 8. The concluding section discusses open problems, such as extension to non-uniform braking constraints and inclusion of other mobile agents.

2 Problem description and preliminaries

This section describes the velocity dependent safety constraints governing fast mobile robot motion. The robot, denoted \(R\), is assumed to be a disc that can freely move in the \((x,y)\) plane (Fig. 1). The robot position and linear velocity are denoted by \(q\in {\mathbb{R }}^2\) and \(v\in {\mathbb{R }}^2\). The robot is assumed to move with fixed orientation, so that its configuration space, or c-space, is \({\mathbb{R }}^2\).

Fig. 1
figure 1

The straight line braking path ends at the maximal Euclidean distance from the robot’s initial position

The main velocity dependent safety constraints are the need to maintain safe braking distance, and to prevent sliding as well as tipover during sharp turns. First consider the safe braking constraint. When the robot executes fast motion between obstacles, it must be able to brake and reach a full stop without hitting any obstacle during the braking process. This requirement ensures that sudden events, such as a pedestrian emerging between parked vehicles into the road, can be safely avoided by a fast moving mobile robot. The length of the shortest braking path is dictated by the robot’s maximal deceleration, a system dependent parameter which is part of the following definition.

Definition 1

(Linear Acceleration Constraint) The robot’s linear acceleration is constrained by system dependent parameters \(a_{min}\) and \(a_{max}\), which bound the robot’s acceleration by

$$\begin{aligned} a_{min}< \dot{v}\cdot \hat{v} <a_{max}, \end{aligned}$$

where \(\hat{v}\) is the robot’s linear velocity direction and \(a_{min}<0\) to represent deceleration.

The robot’s shortest braking path is defined as follows.

Definition 2

(Shortest Braking Path). The robot’s shortest braking path is any feasible path along which the robot applies the maximal deceleration \(a_{min}\).

The distance from the robot’s initial position to the point where it reaches a full stop is not constant. As the robot follows a wiggly but feasible path, this distance becomes shorter as depicted in Fig. 1. The robot’s minimal braking distance, denoted \(d\), is the length of any of its shortest braking paths along which the robot decelerate with \(a_{min}\). Stretching these braking paths into a linear path of length \(d\) will also give a shortest braking path, but the one with the largest distance measured between the robot’s initial position and the final braking point. For safety, the robot must keep at least \(d\) away from any of the obstacles. The minimal braking distance can be computed using energy balance as follows (Fraichard 2007). The mobile robot is modeled as a cylindrical rigid body moving with fixed orientation. Its kinetic energy is given by

$$\begin{aligned} E_{k}=\frac{1}{2} m \nu ^{2}, \end{aligned}$$
(1)

where \(m\) is the robot’s mass and \(\nu \) is the robot’s linear velocity magnitude.

Let \(\alpha (s)\) be a braking trajectory which brings the robot to a full stop along any of the shortest braking paths. The net work applied by the static friction force, which acts between the wheels and the ground in order to bring the robot to a complete stop is given by

$$\begin{aligned} E_{f}=\mu {\int }_{\alpha (s)}f_{N}ds=\mu f_{N}d=\mu mgd, \end{aligned}$$
(2)

where \(\mu \) is the static coefficient of friction between the wheels and the ground, \(g\) is the gravitational acceleration, and \(f_{N} \!= \! mg\) is the net normal force at the contacts. The minimal braking path, \(d\), occurs when the frictional reaction forces between the wheels and the ground are aligned with the friction-cone edge opposing the direction of motion. Note that during this braking phase, the wheels are rolling without sliding at the contacts. A complete stop of the mobile robot requires that all its initial kinetic energy be absorbed by the braking force,

$$\begin{aligned} E_{k}=E_{f}. \end{aligned}$$
(3)

Substituting for \(E_k\) and \(E_f\) gives \(\frac{1}{2}mv^{2}=\mu mg d\). The minimal braking distance is therefore

$$\begin{aligned} d(v)=\frac{1}{2\mu g}v^{2}=kv^{2}, \end{aligned}$$
(4)

where \(k= 1/2\mu g\) is a constant. Note that \(d(v)\) does not depend on the robot’s mass. This assumption is valid only under an ideal rigid body model. In practice the robot’s wheels are rubber coated and experience substantial deformations at the contacts. In these cases the friction coefficient \(\mu \) (and hence the braking distance \(d\)) is strongly influenced by the robot’s mass \(m\) (Smith 2008, chap. 3).

2.1 The uniform braking constraint

Uniform braking safety is ensured when the robot is kept at least \(d(\nu )\) away from the nearest obstacle. This conservative safety criterion is illustrated in Fig. 1. All paths that bring the robot to a full stop while applying the maximal deceleration \(a_{min}\) have the same length \(d\). When the closest obstacle is located at least \(d\) away from the robot’s initial position, the robot can reach a full stop without hitting any obstacle while following any maximal deceleration path.

The second major velocity dependent constraint is the robot’s minimal turning radius. While turning, centrifugal forces and lateral moments act on the robot’s body. A practical means to prevent sliding or tipping-over is to lower bound the robot’s turning radius at any given velocity, as specified in the following definition.

Definition 3

(Turning Radius Constraint). The robot minimal turning radius is specified by a system dependent function \(r_{min}(\nu )\), where \(\nu \) is the robot’s current velocity magnitude.

An expression for the robot’s minimal turning radius, \(r_{min}(\nu )\), is derived in Appendix. The high-speed navigation method proposed in this paper generates a pseudo time optimal path that maintains safe braking distance from the obstacles. The path is then locally smoothed to ensure safe turning radius at the prescribed velocity along the path.

3 Position velocity configuration space

This section defines the position-velocity configuration space and the “obstacles” that encode the safe braking constraint in this space. Consider the mobile robot to be a disc, \(R\), moving in the \((x,y)\) plane. Let \(R(q)\) be the set of points occupied by the disc robot when its center is located at \(q \!=\! (x,y)\). The obstacles occupy stationary sets denoted \(B_1,...,B_k\). Each obstacle \(B_i\) induces a c-obstacle, denoted \(C B_i\), given by

$$\begin{aligned} C B_{i}=\{q \!\in \! {\mathbb{R }}^2 : R(q)\cap {B_i}\ne \emptyset \} \quad i=1\ldots k. \end{aligned}$$
(5)

Each c-obstacle is obtained by uniformly expanding the physical obstacle by the robot’s radius, as depicted in Fig. 2a. The free configuration space is the complement of the c-obstacle interiors,

$$\begin{aligned} F ={\mathbb{R }}^{2}- \! \underset{i=1\ldots k}{\cup }\mathsf{int}(CB_i), \end{aligned}$$
(6)

where \(\mathsf{int}(CB_i)\) denotes the interior of \(CB_i\).

Fig. 2
figure 2

a The c-obstacle of a disc robot. b The vc-obstacle slice when the robot travels with velocity magnitude \(\nu \)

Position-velocity configuration space generalizes the notion of configuration space by adding the robot’s velocity magnitude, \(\nu \), as an additional coordinate.

Definition 4

The position velocity configuration space of a disc robot \(R\) is the three-dimensional space \({\mathbb{R }}^3\) with coordinates \(p=(x,y,\nu )\), where \(q \!=\! (x,y)\) is the robot’s position and \(\nu \) is the robot’s linear velocity magnitude.

The safe braking constraint is next defined as forbidden regions in position-velocity configuration space. Let \(\mathsf{dst}(q,B_i)\) be the minimal Euclidean distance of a point \(q \in {\mathbb{R }}^2\) from the obstacle \(B_i\).

Definition 5

Given a robot \(R\) and an obstacle \(B_i\), the vc-obstacle induced by \(B_i\), denoted \(C B_i^v\), is given by

$$\begin{aligned} C B_i^v=\left\{ (q,\nu ) \in {\mathbb{R }}^3 : dst\left(q,B_{i}\right)\le d(\nu )\right\} , \end{aligned}$$
(7)

where \(d(v)\) is the minimal braking distance for a robot traveling with velocity magnitude \(\nu \).

The free position-velocity configuration space, denoted \(F^v \!\), is the complement of the vc-obstacle interiors,

$$\begin{aligned} F^v={\mathbb{R }}^{3}-\underset{i=1..k}{\cup }\mathsf{int}(C B_i^v), \end{aligned}$$
(8)

where \(\mathsf{int}(C B_i^v)\) denotes the interior of \(C B_i^v\). At any point \(p\in F^v \!\), the robot initially positioned at \(q\) and traveling with velocity magnitude \(\nu \) can reach a c full stop, without hitting any of the obstacles \(B_{1},...,B_{k}\).

Each vc-obstacle forms a vertical column in position-velocity configuration space. The \(\nu \!=\! 0\) slice of this column coincides with the c-obstacle \(C B_i\). As \(\nu \) increases, the column’s cross section expands, since the braking distance increases quadratically with \(\nu \). Figure 2b depicts a fixed-\(\nu \) slice of a vc-obstacle, while Figs. 4 and 5 sketch the full vc-obstacles. The rate by which each vc-obstacle cross section expands is quadratic in \(\nu \), due to the relation \(d(\nu )=k \nu ^{2}\).

Example

The vc-obstacles associated with three polygonal obstacles are shown in Fig. 3. Their bottom cross sections are the c-space obstacles, drawn in the \((x,y)\) plane which corresponds to \(\nu \!=\! 0\). As \(\nu \) increases, the vc-obstacles expand outwards while the free space \(F^v\) shrinks inward. The graph depicted in the \((x,y)\) plane is the Voronoi diagram of the c-space obstacles and an outer boundary which is not shown. The Voronoi diagram will play an important role in Sect. 5.

Fig. 3
figure 3

The vc-obstacles resemble columns whose cross section expands monotonically along the \(\nu \) coordinate

4 Cellular decomposition of position-velocity configuration space

This section describes a cellular decomposition of the free position-velocity configuration space, \(F^v\), such that each cell is associated with a range of velocities that can be safely executed at a particular locality of the environment. Section 4.1 introduces the position-velocity height function, \(\varphi \), and analyzes its critical points. Section 4.2 partitions \(F^v\) into \(3D\) cells based on the critical points of \(\varphi \).

4.1 The critical points of the height function

The free position-velocity configuration space is a stratified set (Goresky and MacPherson 1980), consisting of the following manifolds. The interior of \(F^v\) is a three-dimensional manifold. The portions of the vc-obstacle surfaces on the boundary of \(F^v\) form two-dimensional manifolds. The intersection curves of vc-obstacle surfaces form one-dimensional manifolds. The isolated points where three vc-obstacle surfaces intersect form zero-dimensional manifolds.

The cellular decomposition of \(F^v\) will be determined by the critical points of the function \(\varphi : F^v \rightarrow {\mathbb{R }}\), which measures the “height” of points \(p \!=\! (x,y,\nu )\) along the \(\nu \) coordinate in position-velocity configuration space,

$$\begin{aligned} \varphi (x,y,\nu )= \nu . \end{aligned}$$
(9)

The critical points of \(\varphi \) in \(F^v\) are the union of the critical points of the restriction of \(\varphi \) to the individual manifolds comprising \(F^v\) (Goresky and MacPherson 1980). A point \(p\in F^v\) is a critical point of \(\varphi \) when \(\nabla \varphi (p)\) is collinear with the generalized normal to the particular manifold containing the point \(p\). The generalized normal of the manifolds comprising \(F^v\) can be characterized as follows (Clarke 1990). In the interior three-dimensional manifold, the generalized normal is the zero vector. At a point on a vc-obstacle surface, it is the usual surface normal pointing into \(F^v\). At a point on the intersection curve of two vc-obstacle surfaces, it is the convex combination of the two surface normals meeting at this point. Last, every zero-dimensional manifold is automatically a critical point of \(\varphi \). The following theorem asserts that \(\varphi \) has two types of critical points.

Theorem 1

The critical points of \(\varphi \) in \(F^v\) are located either on the intersection curve of two vc-obstacle surfaces, or at the intersection point of three vc-obstacle surfaces.

Proof

First consider the interior of \(F^v \!\). Since \(\nabla \varphi (p) = (0,0,1)\) is a non-zero vector, \(\varphi \) cannot have any critical point in the interior of \(F^v\). Next consider the vc-obstacle surfaces, denoted \(\mathsf{bdy}(C B_i^v)\) for \(i=1\ldots k\). Denote by \(\varvec{\eta }_i=(\eta _x,\eta _y,\eta _{\nu })\) the normal to \(\mathsf{bdy}(C B_i^v)\) at \(p\). If \(p\) is a critical point of \(\varphi \), \(\nabla \varphi \) must be collinear with \(\varvec{\eta }_i\):

$$\begin{aligned} \left(\!\begin{array}{l} 0\\ 0\\ 1\end{array}\!\right) \!\times \! \left(\!\begin{array}{l} \eta _{x}\\ \eta _{y}\\ \eta _{v}\end{array}\!\right) \!\!=\!\! \left(\!\!\begin{array}{l} -\eta _{y}\\ \eta _{x}\\ 0\end{array}\!\!\right) \!\!=\!\! \left(\!\begin{array}{l} 0\\ 0\\ 0\end{array}\!\right)\Rightarrow \eta \!\!=\!\! \left(\!\begin{array}{l} 0\\ 0\\ \eta _{v}\end{array}\!\right) \end{aligned}$$
(10)

Thus, a necessary condition for \(p\) to be a critical point is that \((\eta _x,\eta _y)=(0,0)\) at this point. The boundary of \(CB_i^{v}\) is the zero level-set of the scalar valued function: \(\psi (x,y,\nu )= \mathsf{dst}((x,y),B_i)-k \nu ^{2}=0\). Therefore \(\nabla \psi \) is collinear with the vc-obstacle normal \(\varvec{\eta }_i\), and up to a multiplicative factor:

$$\begin{aligned} \varvec{\eta }_i(x,y,\nu ) = \nabla \psi (x,y,\nu ) = \left(\! \begin{array}{c} \nabla \mathsf{dst}\left(q,B_{i}\right)\\ -2k \nu \end{array} \!\right)\!. \end{aligned}$$

The function \(\mathsf{dst}(q,B_i)\) measures the minimal Euclidean distance between \(q \!=\! (x,y)\) and \(B_i\). This function is known to have a unit magnitude gradient, pointing from the neatest point on \(B_i\)’s boundary to \(q\) (Clarke 1990) [Proposition 2.5.4].Footnote 1 Since \(\nabla \mathsf{dst}(q,B_{i})\) is a non-zero vector, \(\varphi \) cannot have critical points on \(\mathsf{bdy}(C B_i^v)\) for \(i=1\ldots k\).

Next consider a point \(p\) on the intersection curve of adjacent vc-obstacle surfaces. The generalized normal at \(p \in \mathsf{bdy}(CB_i^v)\cap \mathsf{bdy}(CB_j^v)\) is the convex combination of the vc-obstacle normals, \(\varvec{\eta }_i\) and \(\varvec{\eta }_j\),

$$\begin{aligned} \varvec{\eta }\in \lambda _1\varvec{\eta }_i + \lambda _2\varvec{\eta }_j \quad 0\le \lambda _1,\lambda _2 \le 1, \lambda _1 \!+\! \lambda _2 \!=\! 1. \end{aligned}$$

A critical point \(p\) must therefore satisfy the condition:

$$\begin{aligned} \nabla \varphi (p)= \left(\!\begin{array}{l} 0\\ 0\\ 1\\ \end{array}\!\right) = \lambda _1\varvec{\eta }_i+\lambda _2\varvec{\eta }_j \quad for some \lambda _1,\lambda _2 \ge 0. \end{aligned}$$
(11)

It follows from 11 that \(\varphi \) has a critical point at \(p\) when the tangent to the intersection curve at \(p\) is purely horizontal in \((x,y,\nu )\)-space. Such points occur at the lowest points along the intersection curves. Finally, every isolated point where three vc-obstacle surfaces intersect is automatically a critical point of \(\varphi \). \(\square \)

The critical points of \(\varphi \) on the intersection curve of vc-obstacle pairs will be called Type I points, while the critical points of \(\varphi \) at the intersection points of vc-obstacle triplets will be called Type II points. The two types of critical points are either saddles or local maxima, as stated in the following proposition.

Proposition 4.1

The function \(\varphi \!:\! F^v \!\rightarrow \! {\mathbb{R }}\) has non-smooth saddles at the Type I critical points, and non-smooth local maxima at the Type II critical points.

Proof Sketch:

Let \(p\) be a Type I critical point of \(\varphi \). Then \(p\in \mathsf{bdy}(CB_i^v)\cap \mathsf{bdy}(CB_j^v)\), such that the tangent to the curve \(\mathsf{bdy}(CB_i^v)\cap \mathsf{bdy}(CB_j^v)\) is purely horizontal at \(p\). Since the vc-obstacles form columns whose cross-section expands monotonically along the \(\nu \) axis, the point \(p\) must be a local minimum of \(\varphi \) along the intersection curve. Let \(V_p\) be the plane orthogonal to the curve \(\mathsf{bdy}(CB_i^v)\cap \mathsf{bdy}(CB_j^v)\) at \(p\). Let \(U_p\) be a small three-dimensional ball centered at \(p\). The free space in \(V_p \cap U_p\) looks like an inverted \(V\) shape, with \(p\) located at its upper vertex (see Fig. 4a). It follows that \(\varphi \) has a local maximum within the set \(V_p \cap U_p\). Since \(\varphi \) has a local minimum and maximum along orthogonal directions at \(p\), it has a non-smooth saddle at this point.

Fig. 4
figure 4

a A Type I critical point is a saddle point of \(\varphi \) in \(F^v\). b The vc-obstacles slices in the vicinity of the saddle point

When \(p\) is a Type II critical point of \(\varphi \), three vc-obstacles intersect at this point. The cross-section of each vc-obstacle expands monotonically along the \(\nu \) axis. Hence at any fixed-\(\nu \) slice above \(p\), the three vc-obstacles strictly penetrate each other. Since \(F^v\) is bounded from above by the three vc-obstacles at \(p\), the point \(p\) is a non-smooth local maximum of \(\varphi \).

A Type I critical point \(p\) is thus a saddle of \(\varphi \) in \(F^v\). Based on stratified Morse theory (Goresky and MacPherson 1980), a locally connected fixed-\(\nu \) slice of \(F^v\) just below \(p\) splits at the saddle and becomes two locally disconnected sets in the slices just above \(p\).

Example

Figure 4a shows a saddle point \(p\) where two vc-obstacles meet for the first time along the \(\nu \) axis. Note that \(\nabla \varphi =(0,0,1)\) is orthogonal to the intersection curve \(\mathsf{bdy}(CB_{i}^{v})\cap \mathsf{bdy}(CB_{j}^{v})\) at \(p\). Figure 4b depicts three fixed-\(\nu \) slices: below \(p\), through \(p\), and above \(p\).

The next example illustrates the free space \(F^v\) at a Type II critical point.

Example

Figure 5 illustrates a local maximum point \(p\), where three vc-obstacles meet for the first time along the \(\nu \) axis. The point \(p\) is a zero-dimensional manifold and hence it is a critical point of \(\varphi \).

Fig. 5
figure 5

A Type II critical point is a local maximum of \(\varphi \) in \(F^v\)

4.2 The partition of \(F^v\) into 3D cells

The free position-velocity configuration space will be partitioned by vertical planes called vertical partitions, and by horizontal planes called horizontal partitions. Each of these partitions will pass through a critical point of \(\varphi \). The vertical partitions are defined as follows.

Definition 6

Let \(p \in F^v\) be a saddle point of \(\varphi \). Let \(P\) be the plane which passes through \(p\) and spanned by the vc-obstacle normals at \(p\). The vertical partition at \(p\) is the portion of \(P\cap F^v\) containing the point \(p\).

Every vertical partition is bounded from below by the \((x,y,0)\) plane, from above by the saddle point \(p\), and from the “sides” by the vc-obstacles. The lower edges of the vertical partitions decompose the \((x,y)\) plane into two-dimensional regions, as shown in Fig. 6. To see that the vertical partitions are indeed vertically aligned, note that the tangent to the intersection curve of two vc-obstacles is purely horizontal at \(p\). At a critical point of \(\varphi \), the latter tangent is orthogonal to the vc-obstacle normals at \(p\). Hence the plane spanned by the vc-obstacle normals at \(p\) is vertically aligned in \((x,y,\nu )\) space. The horizontal partitions are next defined.

Fig. 6
figure 6

The \((x,y)\) projection of a stack of 3D cells

Definition 7

Let \(p \in F^v\) be a saddle or a local maximum point of \(\varphi \). Let \(H\) be a plane parallel to the \((x,y)\) plane passing through \(p\). The horizontal partition at \(p\) is the portion of \(H\cap F^v\) containing the point \(p\).

Each horizontal partition lies in a fixed-\(\nu \) slice. When a horizontal partition passes through a local maximum point, it consists of this single point. When the partition passes through a saddle point, it forms a two-dimensional planar set bounded by nearby vc-obstacles. The union of the horizontal and vertical partitions induces a cellular decomposition of the free position-velocity space into \(3D\) cells.

Definition 8

The cellular decomposition of the free position-velocity space, \(F^v \!\), consists of 3D cells bounded by the horizontal and vertical partitions passing through the critical points of \(\varphi \) and the vc-obstacles.

The cellular decomposition of \(F^v\) consists of “stacks” of \(3D\) cells separated by three vertical partitions (in the generic case) and vc-obstacles. The cells within each stack are separated by horizontal partitions, as illustrated in the following example.

Example

Figure 7 depicts three vc-obstacles together with their horizontal and vertical partitions. The portion of \(F^v\) between the vc-obstacles forms a stack of four \(3D\) cells, separated by horizontal partitions passing through three saddles and one local maximum of \(\varphi \).

Fig. 7
figure 7

A stack of 3D cells is generically surrounded by three vc-obstacle and three vertical partitions

A stack of \(3D\) cells can have a more complex structure in non-generic situations. For instance, when four identical obstacles are symmetrically arranged about a common center point, their stack of \(3D\) cells is surrounded by four vc-obstacles and four vertical partitions. However, almost any local perturbation of the obstacle positions will give the generic structure described above.

5 The cells adjacency graph

The vc-method constructs an adjacency graph, denoted \(G^v\), for the cellular decomposition of the free position-velocity space. Each vertex of \(G^v\) represents one \(3D\) cell in the cellular decomposition. The vertex, \(p_i \!=\! (x_i,y_i,\nu _i)\), is selected at the cell’s center as follows. Its \((x_i,y_i)\) coordinates are located at the point which maximizes the minimal distance from the surrounding c-obstacles in the \((x,y)\) plane (it is a node on the Voronoi diagram). Note that the vertices in a stack of cells project to the same point in the \((x,y)\) plane. The \(\nu _i\) coordinate is selected at the midpoint between the \(\nu \)-values of the cell’s bottom and top horizontal partitions (although it is possible to select any \(\nu \)-value inside the cell). The edges of \(G^v\) are of two types:

  1. (i)

    Type A edge connects two vertices whose cells share a common vertical partition. The \((x,y)\) projection of the edge coincides with the Voronoi edge connecting the \((x,y)\) projections of the respective cell vertices.

  2. (ii)

    Type B edge connects two vertices whose cells share a common horizontal partition. The edge forms a vertical line whose \((x,y)\) projection coincides with the Voronoi node underlying the cells’ vertices.

When the robot traces a Type A edge it moves along a Voronoi edge with a continuously varying velocity. Tracing of a Type B edge requires that the robot change its velocity without any positional change. While not physically realizable, the vertical edges will guide the search for a pseudo time optimal chain of cells in the cellular decomposition of \(F^v\).

Example

Figure 8 depicts three c-obstacles surrounded by a rectangular wall in the \((x,y)\) plane. The vc-obstacles shown in the figure induce a cellular decomposition of \(F^v \!\), and the cells adjacency graph is depicted in the figure.

Fig. 8
figure 8

The adjacency graph of the cellular decomposition induced by three polygonal obstacles and an outer wall

5.1 Path Search on \(\mathbf{G}^\mathbf{v}\)

The vc-method assigns positive weights to the Type A edges and zero weights to the Type B edges (as the latter edges do not correspond to any positional change of the robot). The weight of a Type A edge reflects the minimum travel time along its underlying Voronoi edge. Let a Type A edge connect two adjacency graph vertices, \(p_i \!=\! (q_i,\nu _i)\) and \(p_j \!=\! (q_j,\nu _j)\), and pass through a saddle point \(p_{ij} \!=\! (q_{ij},\nu _{ij})\). The points lying on the upper boundary of \(F^v\) above \(p_i\) and \(p_j\) are local maximum points. Denote by \(\nu _{max}(p_i)\) and \(\nu _{max}(p_j)\) the speeds at the two local maxima. The minimum travel time along the underlying Voronoi edge consists of two motion modes. Starting at \(q_i\) with maximal speed \(\nu _{max}(p_i)\), the robot traces the Voronoi edge with maximal deceleration \(a_{min}\), until reaching the \((x,y)\) projection of the saddle point \(p_{ij}\). The robot next traces the remaining portion of the Voronoi edge with maximal acceleration \(a_{max}\), until reaching the endpoint \(q_j\) with maximal speed \(\nu _{max}(p_j)\). The Type A edge cost is given by

$$\begin{aligned} \text{ Type} \text{ A} \text{ edge} \text{ cost} = \frac{\nu _{max}(p_i) - \nu _{ij}}{\left|a_{min}\right|} + \frac{ \nu _{max}(p_j)-\nu _{ij}}{a_{max}} \end{aligned}$$

where \(\nu _{ij}\) is the lowest speed at the saddle point \(p_{ij} \!=\! (q_{ij},\nu _{ij})\).

Any shortest path search algorithm on \(G^v\) gives a pseudo time optimal chain of \(3D\) cells connecting the start cell to the target cell. Note that the chain of cells does not necessarily contains the geometrically shortest path, but rather an approximate minimum-time path that guides the robot safely from start to target under a uniform braking distance constraint.

5.2 Computational complexity of the vc-method

The adjacency graph vertices project to Voronoi nodes in the \((x,y)\) plane, while the Type A edges project to Voronoi edges in the \((x,y)\) plane. In general, the Voronoi diagram of a polygonal environment containing \(n\) vertices has \(O(n)\) nodes and edges (Aurenhammer and Klein 2000; Shamos 1978). Each vertical stack in the cellular decomposition of \(F^v\) consists of four \(3D\) cells. Hence there are \(O(n)\) vertices in \(G^v\). Each \(3D\) cell is horizontally connected to at most three neighboring cells, and is vertically connected to at most two cells. Hence there are \(O(n)\) edges in \(G^v\). Standard shortest path search algorithms run in \(O(E \log E )\) steps, where \(E\) is the total number of graph edges. Since \(G^{v}\) has size \(O(n)\), the vc-method constructs the adjacency graph in \(O(n)\) time and searches the graph in \(O(n\log n)\) time. While the method is highly efficient, it only provides an approximate minimum-time path subject to a uniform braking distance constraint.

6 Practical path realization

There are two practical path realization concerns. First, the optimal path on \(G^v\) contains purely vertical Type B edges that must be modified into physically realizable arcs. Second, the Type A edges project to Voronoi edges in the \((x,y)\) plane. The Voronoi edges meet non-smoothly at the nodes, so they must be smoothed at the nodes according to the robot’s minimal turning radius. These two practical considerations are next discussed.

6.1 Path realization

Let the Type A edges along the optimal path be momentarily represented as horizontal edges in \((x,y,\nu )\) space, as illustrated in Fig. 9a. The vertical strips along the optimal path can be unfolded into a common vertical plane, as shown in Fig. 9b. Note that the horizontal coordinate within this plane is the distance traversed along the path’s horizontal edges, denoted \(s\) in the figure. For any physical robot, it is reasonable to assume that its maximal acceleration does not exceeds its maximal deceleration, \(a_{max} \le \left| a_{min}\right|\). Let us assume here that \(a_{max} \!=\! \left|a_{min}\right|\) (the path realization procedure can be adapted to the case where \(a_{max} < \left|a_{min}\right|\)). A time optimal realization is obtained by shifting the adjacency-graph path vertically upward in \((x,y,\nu )\) space, until it lies on the upper boundary of \(F^v\). The shifted path vertices lie at local maximum points. Each arc of the shifted path traces a vc-obstacle downward with minimal slope \(a_{min}\) until reaching a saddle point, then traces a vc-obstacle upward with maximal slope \(a_{max}\) until reaching the next local maximum point (Fig. 9b). The path realization procedure is summarized for start and target located on vc-obstacle boundaries.

Fig. 9
figure 9

a The optimal path lies in vertical strips. b Path unfolding and vertical edges realization

  1. 1.

    Accelerate from the start position with \(a_{max}\) to the first local maximum point along the path (arc 1 in Fig. 9b).

  2. 2.

    Decelerate from a local maximum point with \(a_{min}\) to the next saddle point along the path (arcs 2, 4, and 6 in Fig. 9b).

  3. 3.

    Accelerate from the saddle point with \(a_{max}\) to the next local maximum point along the path (arcs 3, 5, and 7 in Fig. 9b).

  4. 4.

    Decelerate from the last local maximum point with \(a_{min}\) along the path, until reaching the target with zero velocity (arc 8 in Fig. 9b).

The path realization procedure achieves minimum travel time among all possible realizations of the adjacency graph paths. The acceleration profile along the realized path is basically a Bang–Bang parametrization: it always selects the minimal deceleration and maximal acceleration, \(a_{min}\) or \(a_{max}\), while maintaining a safe braking distance from the obstacles.

6.2 Path smoothing at the nodes

The Type A edges project to Voronoi edges that meet non-smoothly at discrete nodes in the \((x,y)\) plane. But the robot must respect a velocity dependent lower bound on its turning radius, \(r_{min}(\nu )\), specified in Appendix. When the optimal path in \(G^v\) passes through a vertex \(p_i \!=\! (q_i,\nu _i)\), the robot changes its direction of motion along a circular arc of radius \(r_{min}(\nu _i)\) which is tangent to the Voronoi edges meeting at \(q_i\). By following this circular arc with velocity magnitude which varies linearly between its values at the arc’s endpoints, the robot executes a smooth edge transition while satisfying the minimum turning radius constraint. The path smoothing procedure is illustrated in the following example.

Example

Figure 10a depicts three c-obstacles in the \((x,y)\) plane, together with three Voronoi edges meeting at a node. The \((x,y)\) projection of the adjacency graph path follows the edges \(e_1\) and \(e_2\) indicated in the figure. The path must pass through the non-smooth node at a speed \(\nu \!=\! \nu _i\) prescribed by the \((x,y,\nu )\) path. Figure 10b schematically shows the circle having the minimal turning radius \(r_{min}(\nu _i)\) (specified in Appendix). The locally smoothed path replaces the node and portions of \(e_1\) and \(e_2\) with a circular arc of radius \(r_{min}(\nu _i)\) tangent to the path’s Voronoi edges at the node. The robot executes a smooth transition from \(e_1\) to \(e_2\) by following the circular arc with with speed that varies linearly between its values at the arc’s endpoints.

Fig. 10
figure 10

a The optimal path passing through a node. b The smoothed path follows the minimum safe turning radius arc

7 Simulations

This section describes two simulation studies. The first study considers the effect of the inter-obstacle clearance on the vc-method paths. The second simulation compares the vc-method with the classical dynamic window approach.

7.1 Influence of obstacles clearance on vc-method paths

Consider the simplified office environment depicted in Fig. 11. The left space is an empty room, while the right space contains a large table of variable length. The Voronoi diagram which guides the construction of the adjacency graph is also depicted in the figure. The upper passage is assigned a variable width \(W_u\), while the lower passage is kept at a fixed width, \(W_l\), which equals \(1.5\) times the robot’s diameter. The ratio between \(W_u\) and \(W_l\) is defined as \(\delta = W_u/W_l\), where \(\delta \ge 1\).

Fig. 11
figure 11

A disc robot navigating with high speed in an office environment

Using the start and target indicated in Fig. 11, the geometrically shortest path from start to target on the Voronoi diagram passes through the lower passage. In this particular environment, as long as \(1 \le \delta \le 3\) the vc-method travels with low speeds through the lower passage. When \(\delta > 3\), the geometrically longer path can be safely traced at a higher speed and hence with a shorter travel time. Figure 12 depicts the velocity profiles of the two paths for \(\delta = 3.4\). The vertical axis is the robot’s speed, \(v\), while the horizontal axis is the robot’s normalized position , \(s\) the path. Each velocity profile includes segments where the robot accelerates or decelerates with its maximal capabilities and segments where the robot travels with constant speed.

Fig. 12
figure 12

The speed of the robot for \(\delta =3.4\)

The graph in Fig. 13 plots the ratio between the vc-method travel time, \(t(\text{ vc-method})\), and the geometrically shortest path safe travel time on the Voronoi diagram, \(t(l_{min})\), as a function of \(\delta \). Note that \(t(l_{min})\) remains constant for all values of \(\delta \). When \(\delta \) is small, the robot cannot travel rapidly through the top passage due to the braking distance constraint. Therefore it selects the geometrically shortest path through the bottom passage. As \(\delta \) increases, the robot can safely travel with high speed through the top passage, thus achieving a sorter travel time compared with \(t(l_{min})\). While the travel time improvement is modest, congested obstacle scenarios would give substantial travel time savings.

Fig. 13
figure 13

The ratio \(t(\text{ vc-method})/t(l_{min})\) of the vc-method as a function of \(\delta \)

7.2 Comparison of the vc-method with the dynamic window approach

The vc-method is next compared with the dynamic window approach (Brock and Khatib 1999; Fox et al. 1997). The dynamic window approach, or \(DW\!A\), chooses the path’s velocity within a user specified time-window. Within each time-window the robot moves along a circular arc of radius \(r\). The selection of \(r\) and the speed \(\nu \) along this arc is based on maximization of an objective function that consists of three components:

  1. 1.

    Target heading: a function \(\mathsf{head}(r,\nu )\) measuring the inverse deviation of the robot heading from the target direction.

  2. 2.

    Obstacle clearance: a function \(\mathsf{dst}(r,\nu )\) measuring the minimal distance to the surrounding obstacles.

  3. 3.

    Forward velocity: a function \(\mathsf{vel}(r,\nu )\) specifying the robot’s normalized speed during tracing of the current circular arc. The objective function, denoted \(G(r,\nu )\), is the weighted sum of the three elements: \(G(r,\nu )=\alpha \cdot \mathsf{head}(r,\nu )+ \beta \cdot \mathsf{dst}(r,\nu ) + \gamma \cdot \mathsf{vel}(r,\nu )\), where \(\alpha \), \(\beta \), and \(\gamma \) are user-specified weights. In each time-window, \(G(r,\nu )\) is maximized over all turning radii \(r\) and speeds \(\nu \) that ensure collision-free trajectories as well as braking safety. In our simulations, the dynamic window approach is implemented with unit weights, \(\alpha \!=\! \beta \!=\! \gamma \!=\! 1\), and time-window of 1 s.

In order to study the difference between the vc-method and the dynamic window approach, two scenarios are considered. The first scenario, depicted in Fig. 14a–b, consists of an obstacle cluster in a rectangular room. In Example (i), the start and target lie at opposite sides of the obstacle cluster (Fig. 14a). The \(DW\!A\) path in this example passes between the obstacles through low-clearance passages. While the vc-method path is geometrically longer, it passes through wide-clearance passages that allow higher speeds subject to the uniform braking distance constraint. The robot’s speed profile is illustrated in Fig. 15a. As indicated in Table 1, the vc-method travel time is almost one half of the \(DW\!A\) travel time. In Example (ii), the target lies at the upper left corner of the room, where it is directly visible from the start (Fig. 14b). The \(DW\!A\) path moves through the narrow passage along the geometrically shortest path to the target. The vc-method path circumnavigates the obstacle cluster along a significantly longer path. However, this path allows the robot to maximize its velocity while respecting the braking distance constraint (Fig. 15b). The vc-method travel time is again almost one half of the \(DW\!A\) travel time (Table 1).

Fig. 14
figure 14

The vc-method and \(DW\!A\) paths in ab a rectangular room containing an obstacle cluster, and c a urban-like environment

Fig. 15
figure 15

The velocity profiles of the paths illustrated in Fig. 14 a–b

Table 1 Running time in seconds and length in meters of the three simulations

The second scenario, depicted in Fig. 14c, resembles urban city blocks surrounded by a rectangular boundary. The start and target are located at opposite corners of the environment. The vc-method path follows Voronoi edges that maintain wide clearance from the obstacles. This path permits high speeds subject to the uniform braking distance constraint. The \(DW\! A\) path passes through a low-clearance passage between adjacent city blocks. While this is a shorter path, the narrow passage forces the robot to slow down, resulting in a path whose travel time is almost twice longer than the vc-method travel time (Table 1).

The simulations indicate that when the motivation is to reduce travel time rather than path length, wide clearance paths support higher speeds (and hence reduced travel time) under the uniform braking constraint. By methodically searching the free cells of position-velocity configuration space, significant travel time improvements can be obtained relative to more traditional high-speed navigation methods.

8 Experiments

The vc-method was implemented on an Irobot Create 4400 platform. The robot’s minimal deceleration was set to \(a_{min} \!=\! -100\) \(\text{ mm/s}^2\), the maximal acceleration was set to \(a_{max} \!=\! 100\) \(\text{ mm/s}^2\), and the minimal turning radius was set to \(r_{min}\) \(= 300\) mm. These scaled values reflect those of autonomous high-speed platforms (e.g. GUSS 2012; GUARDIUM-UGV 2012). Figure 16 depicts the experimental setup. The environment contains three rectangular obstacles located within a rectangular outer boundary. The Voronoi diagram which underlies the adjacency graph construction is marked on the floor. The environment resembles the obstacle-cluster environment described in Sect. 7.

Fig. 16
figure 16

The experiment setup of three polygonal obstacles within a rectangular outer boundary

The robot was programmed to trace three trajectories along the Voronoi diagram edges (Fig. 16) and to implement different velocity profiles. The trajectories begin and end at the same start and target points, but each has a different velocity profile dictated by the uniform braking distance constraint. The experiment compares the geometrically shortest path along the Voronoi diagram (trajectory 1), an intermediate length path (trajectory 2), and the vc-method path (trajectory 3). The experimental path length, travel time, and average speed of the three trajectories are listed in Table 2. The velocity profiles of the three programmed paths are depicted in Fig. 17. The geometrically shortest path (trajectory 1) takes the longest time. The low-clearance passages along this path force low average speed of \(0.08\) m/s and travel time of \(45\) s. The intermediate length path (trajectory 2) moves with average speed of \(0.14\) m/s and travel time of \(32\) s. The vc-method path (trajectory 3) moves through wide clearance passages with average speed of \(0.26\) m/s and the shortest travel time of \(26\) s.

Fig. 17
figure 17

The velocity profiles of the three programmed paths

Table 2 Experiment results

The experiment corroborates the vc-method usefulness for high-speed safe navigation in congested environments. Controlling the Irobot position and speed proved to be difficult in the experiments, due to its position sensor inaccuracy. This inaccuracy limited the robot ability to precisely trace the Voronoi edges and implement the desired velocity profile. It is interesting to note that on-line implementation of the method (which requires obstacle detection sensors not available on the Irobot) will be able to compensate for such positional inaccuracies based on local sensor readings.

9 Conclusion

Maintaining safe braking distance from the obstacles is a major concern during high-speed mobile robot navigation. This paper introduces position-velocity configuration space, where the safe braking constraint is modeled as vc-obstacle. Based on the critical points of the robot’s velocity magnitude function, \(\varphi (x,y,\nu ) \!=\! \nu \), the paper described a cellular decomposition of position-velocity configuration space into free cells. Each cell is associated with a particular range of velocities that can be safely followed by the robot. An adjacency graph constructed for the cellular decomposition allows a search for a pseudo time optimal path from start to target which avoids the vc-obstacles. The path follows Voronoi edges which are smoothed to ensure safe turning at the prescribed velocity magnitudes. The resulting high-speed path leads the robot from start to target while maintaining safe braking distance from the obstacles.

The vc-method treats the two velocity-dependent safety concerns, safe braking distance and safe turning radius, at different stages of the planning process. The safe braking distance is modeled by the vc-obstacles in position-velocity configuration space. The adjacency graph path avoids the vc-obstacles and thus ensures the uniform braking distance constraint. The \((x,y)\) projection of the adjacency graph path traces Voronoi edges that meet non-smoothly at discrete nodes. The turning radius safety constraint is enforces as a post-processing stage, by locally smoothing the path at the Voronoi nodes. This division of the two velocity-dependent safety concerns seems to offer practical advantages in terms of computational efficiency and ease of implementation.

Based on simulations and experiments, the vc-method offers substantial improvement of total travel time required for safe mobile robot navigation. The method computes an approximate minimum-time safe path in \(O(n\log n)\) time, where \(n\) is the total number of obstacle vertices in the case of a polygonal environment. While the vc-method is highly efficient, it does not provide an upper bound on the quality of approximation with respect to the exact time-optimal safe path. Such a bound should be explored in future research, despite the fact that computation of the exact time-optimal path may be an NP-hard problem.

Two open problems are currently under investigation. The first problem is how to incorporate another moving agent into the vc-method. Our initial work indicates that position-velocity configuration space will have to be recomputed in discrete time periods. Every time period will be determined by the nearest critical predicted event between the moving agent and the stationary obstacles. These critical events occur when the free position-velocity space become locally disconnected when considering the current velocity of the moving agent. A modified adjacency graph generated within each time period will allow safe navigation between the stationary obstacles as well as the moving agent.

A second open problem is how to incorporate non-uniform braking distance safety constraints. Practical high-speed mobile robots can break much more efficiently along directions perpendicular to their current direction of motion. This leads to an oval-shaped safe braking zone aligned with the robot’s current heading rather than a uniform disc centered at the robot. Our initial work indicates that position-velocity configuration space becomes four-dimensional, with coordinates \((x,y,\phi ,\nu )\) representing the robot \((x,y)\) position, the robot instantaneous direction of motion \(\phi \), and the robot velocity magnitude \(\nu \). The non-uniform braking distance constraint can be represented as vc-obstacles in this four-dimensional space. A suitable cellular decomposition of this space will allow generation of significantly faster and more realistic paths then the ones generated under the uniform braking distance constraint. We hope to complete the investigation of this problem and experimentally demonstrate its advantages in the near future.