REFINE: Reachability-based Trajectory Design using Robust Feedback Linearization and Zonotopes
Abstract
Performing real-time receding horizon motion planning for autonomous vehicles while providing safety guarantees remains difficult. This is because existing methods to accurately predict ego vehicle behavior under a chosen controller use online numerical integration that requires a fine time discretization and thereby adversely affects real-time performance. To address this limitation, several recent papers have proposed to apply offline reachability analysis to conservatively predict the behavior of the ego vehicle. This reachable set can be constructed by utilizing a simplified model whose behavior is assumed a priori to conservatively bound the dynamics of a full-order model. However, guaranteeing that one satisfies this assumption is challenging. This paper proposes a framework named REFINE to overcome the limitations of these existing approaches. REFINE utilizes a parameterized robust controller that partially linearizes the vehicle dynamics even in the presence of modeling error. Zonotope-based reachability analysis is then performed on the closed-loop, full-order vehicle dynamics to compute the corresponding control-parameterized, over-approximate Forward Reachable Sets (FRS). Because reachability analysis is applied to the full-order model, the potential conservativeness introduced by using a simplified model is avoided. The pre-computed, control-parameterized FRS is then used online in an optimization framework to ensure safety. The proposed method is compared to several state of the art methods during a simulation-based evaluation on a full-size vehicle model and is evaluated on a th race car robot in real hardware testing. In contrast to existing methods, REFINE is shown to enable the vehicle to safely navigate itself through complex environments.
Index Terms:
Motion and path planning, robot safety, reachability analysis, control, zonotopes.I Introduction

Autonomous vehicles are expected to operate safely in unknown environments with limited sensing horizons. Because new sensor information is received while the autonomous vehicle is moving, it is vital to plan trajectories using a receding-horizon strategy in which the vehicle plans a new trajectory while executing the trajectory computed in the previous planning iteration. It is desirable for such motion planning frameworks to satisfy three properties: First, they should ensure that any computed trajectory is dynamically realizable by the vehicle. Second, they should operate in real time so that they can react to newly acquired environmental information collected. Finally, they should verify that any computed trajectory when realized by the vehicle does not give rise to collisions. This paper develops an algorithm to satisfy these three requirements by designing a robust, partial feedback linearization controller and performing zonotope-based reachability analysis on a full-order vehicle model.
We begin by summarizing related works on trajectory planning and discuss their potential abilities to ensure safe performance of the vehicle in real-time. To generate safe motion plan in real-time while satisfying vehicle dynamics, it is critical to have accurate predictions of vehicle behavior over the time horizon in which planning is occurring. Because vehicle dynamics are nonlinear, closed-form solutions of vehicle trajectories are incomputable and approximations to the vehicle dynamics are utilized. For example, sampling-based methods typically discretize the system dynamic model or state space to explore the environment and find a path, which reaches the goal location and is optimal with respect to a user-specified cost function [1, 2]. To model vehicle dynamics during real-time planning, sampling-based methods apply online numerical integration and buffer obstacles to compensate for numerical integration error [3, 4, 5]. Ensuring that a numerically integrated trajectory can be dynamically realized and be collision-free can require applying fine time discretization. This typically results in an undesirable trade-off between these two properties and real-time operation. Similarly, Nonlinear Model Predictive Control (NMPC) uses time discretization to generate an approximation of solution to the vehicle dynamics that is embedded in optimization program to compute a control input that is dynamically realizable while avoiding obstacles [6, 7, 8, 9]. Just as in the case of sampling-based methods, NMPC also suffers from the undesirable trade-off between safety and real-time operation.
To avoid this undesirable trade-off, researchers have begun to apply reachability-based analysis. Traditionally reachability analysis was applied to verify that a pre-computed trajectory could be executed safely [10, 11]. More recent techniques apply offline reachable set analysis to compute an over-approximation of the Forward Reachable Set (FRS), which collects all possible behaviors of the vehicle dynamics over a fixed-time horizon. Unfortunately computing this FRS is challenging for systems that are nonlinear or high dimensional. To address this challenge, these reachability-based techniques have focused on pre-specifying a set of maneuvers and simplifying the dynamics under consideration. For instance, the funnel library method [12] computes a finite library of funnels for different maneuvers and over approximates the FRS of the corresponding maneuver by applying Sums-of-Squares (SOS) Programming. Computing a rich enough library of maneuvers and FRS to operate in complex environments can be challenging and result in high memory consumption. To avoid using a finite number of maneuvers, a more recent method called Reachability-based Trajectory Design (RTD) was proposed [13] that considers a continuum of trajectories and applies SOS programming to represent the FRS of a dynamical system as a polynomial level set. This polynomial level set representation can be formulated as functions of time for collision checking [14, 15, 16]. Although such polynomial approximation of the FRS ensures strict vehicle safety guarantees while maintaining online computational efficiency, SOS optimization still struggles with high dimensional systems. As a result, RTD still relies on using a simplified, low-dimensional nonlinear model that is assumed to bound the behavior of a full-order vehicle model. Unfortunately it is difficult to ensure that this assumption is satisfied. More troublingly, this assumption can make the computed FRS overly conservative because the high dimensional properties of the full-order model are treated as disturbances within the simplified model.
These aforementioned reachability-based approaches still pre-specify a set of trajectories for the offline reachability analysis. To overcome this issue, recent work has applied a Hamilton-Jacobi-Bellman based-approach [17] to pose the offline reachability analysis as a differential game between a full-order model and a simplified planning model [18]. The reachability analysis computes the tracking error between the full-order and planning models, and an associated controller to keep the error within the computed bound at run-time. At run-time, one buffers obstacles by this bound, then ensures that the planning model can only plan outside of the buffered obstacles. This approach can be too conservative in practice because the planning model is treated as if it is trying to escape from the high-fidelity model.
To address the limitations of existing approaches, this paper proposes a real-time, receding-horizon motion planning algorithm named REchability-based trajectory design using robust Feedback lInearization and zoNotopEs (REFINE) depicted in Figure 1 that builds on the reachability-based approach developed in [13] by using feedback linearization and zonotopes. This papers contributions are three-fold: First, a novel parameterized robust controller that partially linearizes the vehicle dynamics even in the presence of modeling error. Second, a method to perform zonotope-based reachability analysis on a closed-loop, full-order vehicle dynamics to compute a control-parameterized, over-approximate Forward Reachable Sets (FRS) that describes the vehicle behavior. Because reachability analysis is applied to the full-order model, potential conservativeness introduced by using a simplified model is avoided. Finally, an online planning framework that performs control synthesis in a receding horizon fashion by solving optimization problems in which the offline computed FRS approximation is used to check against collisions. This control synthesis framework applies to All-Wheel, Front-Wheel, or Rear-Wheel-Drive vehicle models.
The rest of this manuscript is organized as follows: Section II describes necessary preliminaries and Section III describes the dynamics of Front-Wheel-Drive vehicles. Section IV explains the trajectory design and vehicle safety in considered dynamic environments. Section V formulates the robust partial feedback linearization controller. Section VI describes Reachability-based Trajectory Design and how to perform offline reachability analysis using zonotopes. Section VII formulates the online planning using an optimization program, and in Section VIII the proposed method is extended to various perspectives including All-Wheel-Drive and Rear-Wheel-Drive vehicle models. Section IX describes how the proposed method is evaluated and compared to other state of the art methods in simulation and in hardware demo on a 1/10th race car model. And Section X concludes the paper.
II Preliminaries
This section defines notations and set representations that are used throughout the remainder of this manuscript. Sets and subspaces are typeset using calligraphic font. Subscripts are primarily used as an index or to describe an particular coordinate of a vector.
Let , and denote the spaces of real numbers, real positive numbers, and natural numbers, respectively. Let denote the -by- zero matrix. The Minkowski sum between two sets and is . The power set of a set is denoted by . Given vectors , let denote the -th element of , let denote the summation of all elements of , let denote the Euclidean norm of , let denote the diagonal matrix with on the diagonal, and let denote the -dimensional box . Given and , let denote the -dimensional closed ball with center and radius under the Euclidean norm. Given arbitrary matrix , let be the transpose of , let and denote the -th row and column of for any respectively, and let be the matrix computed by taking the absolute value of every element in .
Next, we introduce a subclass of polytopes, called zonotopes, that are used throughout this paper:
Definition 1.
A zonotope is a subset of defined as
(1) |
with center and generators . For convenience, we denote as where .
Note that an -dimensional box is a zonotope because
(2) |
By definition the Minkowski sum of two arbitrary zonotopes and is still a zonotope as . Finally, one can define the multiplication of a matrix of appropriate size with a zonotope as
(3) |
Note in particular that is equal to the zonotope .
III Vehicle Dynamics
This section describes the vehicle models that we used in both high-speed and low-speed scenarios throughout this manuscript for autonomous navigation with safety concerns.
III-A Vehicle Model

The approach described in this paper can be applied to a front-wheel-drive (FWD), rear-wheel drive (RWD), or all-wheel drive (AWD) vehicle models. However, to simplify exposition, we focus on how the approach applies to FWD vehicles and describe how to extend the approach to AWD or RWD vehicles in Section VIII-C. To simplify exposition, we attach a body-fixed coordinate frame in the horizontal plane to the vehicle as shown in Fig. 2. This body frame’s origin is the center of mass of the vehicle, and its axes are aligned with the longitudinal and lateral directions of the vehicle. Let be the states of the vehicle model at time , where and are the position of vehicle’s center of mass in the world frame, is the heading of the vehicle in the world frame, and are the longitudinal and lateral speeds of the vehicle in its body frame, is the yaw rate of the vehicle center of mass, and is the steering angle of the front tire. To simplify exposition, we assume vehicle weight is uniformly distributed and ignore the aerodynamic effect while modeling the flat ground motion of the vehicles by the following dynamics [19, Chapter 10.4]:
(4) |
where and are the distances from center of mass to the front and back of the vehicle, is the vehicle’s moment of inertia, and is the vehicle’s mass. Note: , , and are all constants and are assumed to be known. The tire forces along the longitudinal and lateral directions of the vehicle at time are and respectively, where the ‘i’ subscript can be replaced by ‘f’ for the front wheels or ‘r’ for the rear wheels.
To describe the tire forces along the longitudinal and lateral directions, we first define the wheel slip ratio as
(5) |
where the ‘i’ subscript can be replaced as described above by ’f’ for the front wheels or ’r’ for the rear wheels, is the wheel radius, is the tire-rotational speed at time , braking corresponds to whenever , and acceleration corresponds to whenever . Then the longitudinal tire forces [20, Chapter 4] are computed as
(6) | ||||
(7) |
where is the gravitational acceleration constant, , and gives the surface-adhesion coefficient and is a function of the surface being driven on [20, Chapter 13.1]. Note that in FWD vehicles, the longitudinal rear wheel tire force has a much simpler expression:
Remark 2 ([19]).
In a FWD vehicle, for all .
For the lateral direction, define slip angles of front and rear tires as
(8) | ||||
(9) |
then the lateral tire forces [20, Chapter 4] are real-valued functions of the slip angles:
(10) | ||||
(11) |
Note and are all nonlinear functions, but share similar characteristics. In particular, they behave linearly when the slip ratio and slip angle are close to zero, but saturate when the magnitudes of the slip ratio and slip angle reach some critical values of and , respectively, then decrease slowly [20, Chapter 4, Chapter 13]. As we describe in Section VIII-B, during trajectory optimization we are able to guarantee that and operate in the linear regime. As a result, to simplify exposition until we reach Section VIII-B, we make the following assumption:
Assumption 3.
The absolute values of the the slip ratio and angle are bounded below their critical values (i.e., and hold for all time).
Assumption 3 ensures that the longitudinal tire forces can be described as
(12) | ||||
and the lateral tire forces can be described as
(13) | ||||
with constants . Note and are referred to as cornering stiffnesses.
Note that the steering angle of the front wheel, , and the tire rotational speed, , are the inputs that one is able to control. In particular for an AWD vehicle, both and are inputs; whereas, in a FWD vehicle only is an input. When we formulate our controller in Section V for a FWD vehicle we begin by assuming that we can directly control the front tire forces, and . We then illustrate how to compute and when given and . For an AWD vehicle, we describe in Section VIII-C, how to compute , , and .
In fact, as we describe in Section V, our approach to perform control relies upon estimating the rear tire forces and controlling the front tire forces by applying appropriate tire speed and steering angle. Unfortunately, in the real-world our state estimation and models for front and rear tire forces may be inaccurate and aerodynamic-drag force could also affect vehicle dynamics [20, Section 4.2]. To account for the inaccuracy, we extend the vehicle dynamic model in (4) by introducing a time-varying affine modeling error into the dynamics of and :
(14) |
Note, we have abused notation and redefined which was originally defined in (4). For the remainder of this paper, we assume that the dynamics evolves according to (14). To ensure that this definition is well-posed (i.e. their solution exists and is unique) and to aid in the development of our controller as described in Section V, we make the following assumption:
Assumption 4.
are all square integrable functions and are bounded (i.e., there exist real numbers such that for all ).
Note in Section IX-C1, we explain how to compute using real-world data.
III-B Low-Speed Vehicle Model
When the vehicle speed lowers below some critical value , the denominator of the wheel slip ratio (5) and tire slip angles (8) and (9) approach zero which makes applying the model described in (4) intractable. As a result, in this work when the dynamics of a vehicle are modeled using a steady-state cornering model [21, Chapter 6], [22, Chapter 5], [23, Chapter 10]. Note that the critical velocity can be found according to [24, (5) and (18)].
The steady-state cornering model or low-speed vehicle model is described using four states, at time . This model ignores transients on lateral velocity and yaw rate. Note that the dynamics of , , and are the same as in the high speed model (14); however, the steady-state corning model describes the yaw rate and lateral speed as
(15) | ||||
(16) |
with understeer coefficient
(17) |
As a result, satisfies the dynamics of the first four states in (4) except with taking the role of and taking the role of .
Notice when and the longitudinal tire forces are zero, could still be nonzero due to a nonzero . To avoid this issue, we make a tighter assumption on without violating Assumption 4:
Assumption 5.
For all such that , is bounded from above by a linear function of (i.e.,
(18) |
where and are constants satisfying ). In addition, if .
As we describe in detail in Section V-C, the high-speed and low-speed models can be combined together as a hybrid system to describe the behavior of the vehicle across all longitudinal speeds. In short, when transitions past the critical speed from above at time , the low speed model’s states are initialized as:
(19) |
where is the projection operator that projects onto its first four dimensions via the identity relation. If transitions past the critical speed from below at time , the high speed model’s states are initialized as
(20) |
IV Trajectory Design and Safety
This section describes the space of trajectories that are optimized over at run-time within REFINE, how this paper defines safety during motion planning via the notion of not-at-fault behavior, and what assumptions this paper makes about the environment surrounding the ego-vehicle.
IV-A Trajectory Parameterization
Each trajectory plan is specified over a compact time interval. Without loss of generality, we let this compact time interval have a fixed duration . Because REFINE performs receding-horizon planning, we make the following assumption about the time available to construct a new plan:
Assumption 6.
During each planning iteration starting from time , the ego vehicle has seconds to find a control input. This control input is applied during the time interval where is a user-specified constant. In addition, the state of the vehicle at time is known at time .
In each planning iteration, REFINE chooses a trajectory to be followed by the ego vehicle. These trajectories are chosen from a pre-specified continuum of trajectories, with each uniquely determined by a trajectory parameter . Let , be a n-dimensional box where indicate the element-wise lower and upper bounds of , respectively. We define these desired trajectories as follows:
Definition 7.
For each , a desired trajectory is a function for the longitudinal speed, , a function for the heading, , and a function for the yaw rate, , that satisfy the following properties.
-
1.
For all , there exists a time instant after which the desired trajectory begins to brake (i.e., , and are non-increasing for all ).
-
2.
The desired trajectory eventually comes to and remains stopped (i.e., there exists a such that for all ).
-
3.
and are piecewise continuously differentiable [25, Chapter 6, 1.1] with respect to and .
-
4.
The time derivative of the heading function is equal to the yaw rate function (i.e., over all regions that is continuously differentiable with respect to ).
The first two properties ensure that a fail safe contingency braking maneuver is always available and the latter two properties ensure that the tracking controller described in Section V is well-defined. Note that sometimes we abuse notation and evaluate a desired trajectory for . In this instance, the value of the desired trajectory is equal to its value at .
IV-B Not-At-Fault
In dynamic environments, avoiding collision may not always be possible (e.g. a parked car can be run into). As a result, we instead develop a trajectory synthesis technique which ensures that the ego vehicle is not-at-fault [26]:
Definition 8.
The ego vehicle is not-at-fault if it is stopped, or if it is never in collision with any obstacles while it is moving.
In other words, the ego vehicle is not responsible for a collision if it has stopped and another vehicle collides with it. One could use a variant of not-at-fault and require that when the ego-vehicle comes to a stop it leave enough time for all surrounding vehicles to come safely to a stop as well. The remainder of the paper can be generalized to accommodate this variant of not-at-fault; however, in the interest of simplicity we use the aforementioned definition.
Remark 9.
Under Assumption 3, neither longitudinal nor lateral tire forces saturate (i.e., drifting cannot occur). As a result, if the ego vehicle has zero longitudinal speed, it also has zero lateral speed and yaw rate. Therefore in Definition 8, the ego vehicle being stopped is equivalent to its longitudinal speed being .
IV-C Environment and Sensing
To provide guarantees about vehicle behavior in a receding horizon planning framework and inspired by [15, Section 3], we define the ego vehicle’s footprint as:
Definition 10.
Given as the world space, the ego vehicle is a rigid body that lies in a rectangular with width , length at time . Such is called the footprint of the ego vehicle.
In addition, we define the dynamic environment in which the ego vehicle is operating within as:
Definition 11.
An obstacle is a set that the ego vehicle cannot intersect with at time , where is the index of the obstacle and contains finitely many elements.
The dependency on in the definition of an obstacle allows the obstacle to move as varies. However if the -th obstacle is static, then remains constant at all time. Assuming that the ego vehicle has a maximum speed and all obstacles have a maximum speed for all time, we then make the following assumption on planning and sensing horizon.
Assumption 12.
The ego vehicle senses all obstacles within a sensor radius around its center of mass.
V Controller Design and Hybrid System Model
This section describes the control inputs that we use to follow the desired trajectories and describes the closed-loop hybrid system vehicle model. Recall that the control inputs to the vehicle dynamics model are the steering angle of the front wheel, , and the tire rotational speed, . Section V-A describes how to select front tire forces to follow a desired trajectory and Section V-B describes how to compute a steering angle and tire rotational speed input from these computed front tire forces. Section V-C describes the closed-loop hybrid system model of the vehicle under the chosen control input. Note that this section focuses on the FWD vehicle model.
V-A Robust Controller
Because applying reachability analysis to linear systems generates tighter approximations of the system behavior when compared to nonlinear systems, we propose to develop a feedback controller that linearizes the dynamics. Unfortunately, because both the high-speed and low-speed models introduced in Section III are under-actuated (i.e., the dimension of control inputs is smaller than that of system state), our controller is only able to partially feedback linearize the vehicle dynamics. Such controller is also expected to be robust such that it can account for computational errors as described in Assumptions 4 and 5.
We start by introducing the controller on longitudinal speed whose dynamics appears in both high-speed and low-speed models. Recall in Assumption 4. Inspired by the controller developed in [29], we set the longitudinal front tire force to be
(21) |
where
(22) | ||||
(23) | ||||
(24) | ||||
(25) |
with user-chosen constants . Note in (21) we have suppressed the dependence on in for notational convenience. Using (21), the closed-loop dynamics of become:
(26) |
The same control strategy can be applied to vehicle yaw rate whose dynamics only appear in the high-speed vehicle model. Let the lateral front tire force be
(27) |
where
(28) | ||||
(29) | ||||
(30) | ||||
(31) |
with user-chosen constants . Note in (27) we have again suppressed the dependence on in for notational convenience. Using (27), the closed-loop dynamics of become:
(32) |
Using (27), the closed-loop dynamics of become:
(33) |
Because , , and depend on trajectory parameter , one can rewrite the closed loop high-speed and low-speed vehicle models as
(34) | ||||
(35) |
where dynamics of , and are stated as the first three dimensions in (4), closed-loop dynamics of is described in (26), and closed-loop dynamics of and in the high-speed model are presented in (33) and (32). Note that the lateral tire force could be defined to simplify the dynamics on instead of , but the resulting closed loop system may differ. Controlling the yaw rate may be easier in real applications, because can be directly measured by an IMU unit.
V-B Extracting Wheel Speed and Steering Inputs
Because we are unable to directly control tire forces, it is vital to compute wheel speed and steering angle such that the proposed controller described in (21) and (27) is viable. Under Assumption 3, wheel speed and steering inputs can be directly computed in closed form. The wheel speed to realize longitudinal front tire force (21) can be derived from (5) and (12) as
(36) |
Similarly according to (8) and (13), the steering input
(37) |
achieves the lateral front tire force in (27) when .
Notice lateral tire forces does not appear in the low-speed dynamics, but one is still able to control the lateral behavior of the ego vehicle. Based on (15) and (16), yaw rate during low-speed motion is directly controlled by steering input and lateral velocity depends on yaw rate. Thus to achieve desired behavior on the lateral direction, one can set the steering input to be
(38) |
V-C Augmented State and Hybrid Vehicle Model
To simplify the presentation throughout the remainder of the paper, we define a hybrid system model of the vehicle dynamics that switches between the high and low speed vehicle models when passing through the critical longitudinal velocity. In addition, for computational reasons that are described in subsequent sections, we augment the initial condition of the system to the state vector while describing the vehicle dynamics. In particular, denote the initial condition of the ego vehicle where gives the value of and gives the value of at time . Then we augment the initial velocity condition of the vehicle model and trajectory parameter into the vehicle state vector as . Note the last states are static with respect to time. As a result, the dynamics of the augmented vehicle state during high-speed and low-speed scenarios can be written as
(39) |
which we refer to as the hybrid vehicle dynamics model. Notice when , assigning zero dynamics to and in (39) does not affect the evolution of the vehicle’s dynamics because the lateral speed and yaw rate are directly computed via longitudinal speed as in (15) and (16).
Because the vehicle’s dynamics changes depending on , it is natural to model the ego vehicle as a hybrid system [30, Section 1.2]. The hybrid system has as its state and consists of a high-speed mode and a low-speed mode with dynamics in (39). Instantaneous transition between the high and low speed models within are described using the notion of a guard and reset map. The guard triggers a transition and is defined as . Once a transition happens, the reset map maintains the last dimensions of , but resets the first dimensions of via (19) if approaches from above and via (20) if approaches from below.
We next prove that for desired trajectory defined as in Definition 7 under the controllers defined in Section V, the vehicle model eventually comes to a stop. To begin note that experimentally, we observed that the vehicle quickly comes to a stop during braking once its longitudinal speed becomes [m/s]. Thus we make the following assumption:
Assumption 13.
We use this assumption to prove that the vehicle can be brought to a stop within a specified amount of time in the following lemma whose proof can be found in Appendix A:
Lemma 14.
Let be a compact subset of initial conditions for the vehicle dynamic model and be a compact set of trajectory parameters. Let be bounded for all as in Assumptions 4 and 5 with constants , and . Let be a solution to the hybrid vehicle dynamics model (39) beginning from under trajectory parameter while applying the control inputs (21) and (27) to track some desired trajectory satisfying Definition 7. Assume the desired longitudinal speed satisfies the following properties: , is only discontinuous at time , and converges to as converges to from below. If , and are chosen such that and hold, then for all and satisfying , there exists such that for all .
VI Computing and Using the FRS
This section describes how REFINE operates at a high-level. It then describes the offline reachability analysis of the ego vehicle as a state-augmented hybrid system using zonotopes and illustrates how the ego vehicle’s footprint can be accounted for during reachability analysis.
REFINE conservatively approximates a control-parameterized FRS of the full-order vehicle dynamics. The FRS includes all behaviors of the ego vehicle over a finite time horizon and is mathematically defined in Section VI-A. To ensure the FRS is a tight representation, REFINE relies on the controller design described in Section V. Because this controller partially linearizes the dynamics, REFINE relies on a zonotope-based reachable set representation which behave well for nearly linear systems.
During online planning, REFINE performs control synthesis by solving optimization problems in a receding horizon fashion, where the optimization problem computes a trajectory parameter to navigate the ego vehicle to a waypoint while behaving in a not-at-fault manner. As in Assumption 6, each planning iteration in REFINE is allotted to generate a plan. As depicted in Figure 3, if a particular planning iteration begins at time , its goal is to find a control policy by solving an online optimization within seconds so that the control policy can be applied during . Because any trajectory in Definition 7 brings the ego vehicle to a stop, we partition into during which a driving maneuver is tracked and during which a contingency braking maneuver is activated. Note is not necessarily equal to . As a result of Lemma 14, by setting equal to one can guarantee that the ego vehicle comes to a complete stop by .

If the planning iteration at time is feasible (i.e., not-at-fault), then the entire feasible planned driving maneuver is applied during . If the planning iteration starting at time is infeasible, then the braking maneuver, whose safe behavior was verified in the previous planning iteration, can be applied starting at to bring the ego vehicle to a stop in a not-at-fault manner. To ensure real-time performance, . To simplify notation, we reset time to whenever a feasible control policy is about to be applied.
VI-A Offline FRS Computation
The FRS of the ego vehicle is
(40) |
where is the projection operator that outputs the first two coordinates from its argument. collects all possible behavior of the ego vehicle while following the dynamics of in the -plane over time interval for all possible and initial condition . Computing precisely is numerically challenging because the ego vehicle is modeled as a hybrid system with nonlinear dynamics, thus we aim to compute an outer-approximation of instead.
To outer-approximate , we start by making the following assumption:
Assumption 15.
The initial condition space where is a 3-dimensional box representing all possible initial velocity conditions of the ego vehicle.
Because vehicles operate within a bounded range of speeds, this assumption is trivial to satisfy. Notice in particular that is a zonotope where and . We assume a zero initial position condition in the first three dimensions of for simplicity, and nonzero can be dealt with via coordinate transformation online as described in Section VII-A.
Recall that because is a compact n-dimensional box, it can also be represented as a zonotope as where and . Then the set of initial conditions for can be represented as a zonotope where
(41) |
Observe that by construction each row of has at most nonzero element. Without loss of generality, we assume and has no zero rows. If there was a zero row it would mean that the corresponding dimension can only take one value and does not need to be augmented or traced in for reachability analysis.
Next we pick a time step such that , and partition the time interval into time segments as for each . Finally we use an open-source toolbox CORA [31], which takes and the initial condition space , to over-approximate the FRS in (40) by a collection of zonotopes over all time intervals where . As a direct application of Theorem 3.3, Proposition 3.7 and the derivation in Section 3.5.3 in [32], one can conclude the following theorem:
Theorem 16.
Let be the zonotopes computed by CORA under the hybrid vehicle dynamics model beginning from . Let be a solution to hybrid system starting from an initial condition in . Then for all and and
(42) |
Notice in (42) we have abused notation by extending the domain of to any zonotope in as
(43) |
VI-B Slicing
The FRS computed in the previous subsection contain the behavior of the hybrid vehicle dynamics model for all initial conditions belonging to and . To use this set during online optimization, REFINE plugs in the predicted initial velocity of the vehicle dynamics at time and then optimizes over the space of trajectory parameters. Recall the hybrid vehicle model is assumed to have zero initial position condition during the computation of by Assumption 15. This subsection describes how to plug in the initial velocity into the pre-computed FRS.
We start by describing the following useful property of the zonotopes that make up the FRS, which follows from Lemma 22 in [33]:
Proposition 17.
Let be the set of zonotopes computed by CORA under the hybrid vehicle dynamics model beginning from . Then for any , has only one generator, , that has a nonzero element in the -th dimension for each . In particular, for .
We refer to the generators with a nonzero element in the -th dimension for each as a sliceable generator of in the -th dimension. In other words, for each , there are exactly nonzero elements in the last rows of , and none of these nonzero elements appear in the same row or column. By construction has exactly generators, which are each sliceable. Using Proposition 17, one can conclude that has no less than generators (i.e., ).
Proposition 17 is useful because it allows us to take a known and and plug them into the computed to generate a slice of the conservative approximation of the FRS that includes the evolution of the hybrid vehicle dynamics model beginning from under trajectory parameter . In particular, one can plug the initial velocity into the sliceable generators as described in the following definition:
Definition 18.
Let be the set of zonotopes computed by CORA under the hybrid vehicle dynamics model beginning from where . Without loss of generality, assume that the sliceable generators of each are the first columns of . In addition, without loss of generality assume that the sliceable generators are ordered so that the dimension in which the non-zero element appears is increasing. The slicing operator is defined as
(44) |
where
(45) |
Note, that in the interest of avoiding introducing novel notation, we have abused notation and assumed that the domain of slice is rather than the space of zonotopes in . However, throughout this paper we only plug in zonotopes belonging to into the first argument of slice. Using this definition, one can show the following useful property whose proof can be found in Appendix B:
Theorem 19.
Let be the set of zonotopes computed by CORA under the hybrid vehicle dynamics model beginning from and satisfy the statement of Definition 18. Then for any , , and , . In addition, suppose is a solution to with initial condition and control parameter . Then for each and
(46) |
VI-C Accounting for the Vehicle Footprint in the FRS
The conservative representation of the FRS generated by CORA only accounts for the ego vehicle’s center of mass because treats the ego vehicle as a point mass. To ensure not-at-fault behavior while planning using REFINE, one must account for the footprint of the ego vehicle, , as in Definition 10.
To do this, define a projection operator as where is a zonotope computed by CORA as described in Section VI-A. Then by definition is a zonotope and it conservatively approximates of the ego vehicle’s heading during . Moreover, because is a 1-dimensional zonotope, it can be rewritten as a 1-dimensional box where and . We can then use to define a map to account for vehicle footprint within the FRS:
Definition 20.
Let be the zonotope computed by CORA under the hybrid vehicle dynamics model beginning from for arbitrary , and denote as . Let be a 2-dimensional box centered at the origin with length and width . Define the rotation map as
(47) |
Note that in the interest of simplicity, we have abused notation and assumed that the argument to rot is any subset of . In fact, it must always be a -dimensional box. In addition note that is a zonotope because the 2-dimenional box is equivalent to a 2-dimensional zonotope and it is multiplied by a matrix via (3). By applying geometry, one can verify that by definition bounds the area that travels through while rotating within the range . As a result, over-approximates the area over which sweeps according to as shown in Fig. 4.
Because can be represented as a zonotope with 2 generators, one can denote as where . Notice in (47) is a set in rather than the higher dimensional space where exists. We extend to as
(48) |
Using this definition, one can extend the FRS to account for the vehicle footprint as in the following lemma whose proof can be found in Appendix C:

Lemma 21.
Let be the set of zonotopes computed by CORA under the hybrid vehicle dynamics model beginning from . Let be a solution to with initial velocity and control parameter and let be defined as
(49) |
Then is a zonotope and for all and , the vehicle footprint oriented and centered according to is contained within .
Again note that in the interest of simplicity we have abused notation and assumed that the first argument to is any subset of . This argument is always a zonotope in .
VII Online Planning
This section begins by taking nonzero initial position condition into account and formulating the optimization for online planning in REFINE to search for a safety guaranteed control policy in real time. It then explains how to represent each of the constraints of the online optimization problem in a differentiable fashion, and concludes by describing the performance of the online planning loop.
Before continuing we make an assumption regarding predictions of surrounding obstacles. Because prediction is not the primary emphasis of this work, we assume that the future position of any sensed obstacle within the sensor horizon during is conservatively known at time :
Assumption 22.
There exists a map such that is a zonotope and
(50) |
VII-A Nonzero Initial Position
Recall that the FRS computed in Section VI is computed offline while assuming that the initial position of the ego vehicle is zero (i.e., Assumption 15). The zonotope collection can be understood as a local representation of the FRS in the local frame. This local frame is oriented at the ego vehicle’s location with its -axis aligned according to the ego vehicle’s heading , where gives the ego vehicle’s position at time in the world frame. Similarly, is a local representation of the area that the ego vehicle may occupy during in the same local frame.
Because obstacles are defined in the world frame, to generate not-at-fault trajectories, one has to either transfer from the local frame to the world frame, or transfer the obstacle position from the world frame to the local frame using a 2D rigid body transformation. This work utilizes the second option and transforms into the local frame as
(51) |
VII-B Online Optimization
Given the predicted initial condition of the vehicle at as , REFINE computes a not-at-fault trajectory by solving the following optimization problem at each planning iteration:
s.t. |
where is a user-specified cost function and is defined as in Lemma 21. Note that the constraint in (Opt) is satisfied if for a particular trajectory parameter , there is no intersection between any obstacle and the reachable set of the ego vehicle with its footprint considered during any time interval while following .
VII-C Representing the Constraint and its Gradient in (Opt)
The following theorem, whose proof can be found in Appendix D, describes how to represent the set intersection constraint in (Opt) and how to compute its derivative with respect to :
Theorem 23.
There exists matrices and and a vector such that if and only if . In addition, the subgradient of with respect to is , where .
VII-D Online Operation
Algorithm 1 summarizes the online operations of REFINE. In each planning iteration, the ego vehicle executes the feasible control parameter that is computed in the previous planning iteration (Line 3). Meanwhile, SenseObstacles senses and predicts obstacles as in Assumption 22 (Line 4) in local frame decided by . (Opt) is then solved to compute a control parameter using and (Line 5). If (Opt) fails to find a feasible solution within , the contingency braking maneuver whose safety is verified in the last planning iteration is executed, and REFINE is terminated (Line 6). In the case when (Opt) is able to find a feasible , StatePrediction predicts the state value at based on and as in Assumption 6 (Lines 7 and 8). If the predicted velocity value does not belong to , then its corresponding FRS is not available and the planning has to stop while executing a braking maneuver (Line 9). Otherwise we reset time to 0 (Line 10) and start the next planning iteration. Note Lines 4 and 7 are assumed to execute instantaneously, but in practice the time spent for these steps can be subtracted from to ensure real-time performance. By iteratively applying Definition 8, Lemmas 14 and 21, Assumption 22 and (51), the following theorem holds:
Theorem 24.
VIII Extensions
This section describes how to extend various components of REFINE. This section begins by describing how to apply CORA to compute tight, conservative approximations of the FRS. Next, it illustrates how to verify the satisfaction of Assumption 3. The section concludes by describing how to apply REFINE to AWD and RWD vehicles.
VIII-A Subdivision of Initial Set and Families of Trajectories
In practice, CORA may generate overly conservative representations for the FRS if the initial condition set is large. To address this challenge, one can instead partition and and compute a FRS beginning from each element in this partition. Note one could then still apply REFINE as in Algorithm 1. However in Line 5 must solve multiple optimizations of the form (Opt) in parallel. Each of these optimizations optimizes over a unique partition element that contains initial condition , then is set to be the feasible control parameter that achieves the minimum cost function value among these optimizations. Similarly note if one had multiple classes of desired trajectories (e.g. lane change, longitudinal speed changes, etc.) that were each parameterized in distinct ways, then one could extend REFINE just as in the instance of having a partition of the initial condition set. In this way one could apply REFINE to optimize over multiple families of desired trajectories to generate not-at-fault behavior. Note, that the planning horizon is constant within each element of the partition, but can vary between different elements in the partition.
VIII-B Satisfaction of Assumption 3
Throughout our analysis thus far, we assume that the slip ratios and slip angles stay within the linear regime as described in Assumption 3. This subsection describes how to ensure that Assumption 3 is satisfied by performing an offline verification on the computed reachable sets.
Recall that in an FWD vehicle model, for all as in Remark 2. By plugging (12) in (21), one can derive:
(52) |
Similarly by plugging (13) in (27) one can derive:
(53) |
If the slip ratio and slip angle computed in (52) and (53) satisfy Assumption 3, they achieve the expected tire forces as introduced in Section V-A.
By Definition 1 any that is computed by CORA under the hybrid vehicle dynamics model from a partition element in Section VIII-A, can be bounded by a multi-dimensional box where is a column vector of ones. This multi-dimensional box gives interval ranges of all elements in during , which allows us to conservatively estimate , and via (9), (13) and (52) respectively using Interval Arithmetic [34]. The approximation of makes it possible to over-approximate via (53).
Note in (52) and (53) integral terms are embedded in and as described in (22) and (28). Because it is nontrivial to perform Interval Arithmetic over integrals, we extend to by appending three more auxiliary states , and . Notice
(54) |
then we can compute a higher-dimensional FRS of during through the same process as described in Section VI. This higher-dimensional FRS makes over-approximations of , and available for computation in (52) and (53).
If the supremum of exceeds or any supremum of and exceeds , then the corresponding partition section of may result in a system trajectory that violates Assumption 3. Therefore to ensure not-at-fault, we only run optimization over partition elements whose FRS outer-approximations satisfy Assumption 3. Finally we emphasize that such verification of Assumption 3 over each partition element that is described in Section VIII-A can be done offline.
VIII-C Generalization to All-Wheel-Drive and Rear-Wheel-Drive
This subsection describes how REFINE can be extended to AWD and RWD vehicles. AWD vehicles share the same dynamics as (14) in Section III with one exception. In an AWD vehicle, only the lateral rear tire force is estimated and all the other three tire forces are controlled by using wheel speed and steering angle. In particular, computations related to the lateral tire forces as (27) and (53) are identical to the FWD case . However, both the front and rear tires contribute nonzero longitudinal forces, and they can be specified by solving the following system of linear equations:
(55) | ||||
Longitudinal tire forces and computed from (55) can then be used to compute wheel speed as in (36). In this formulation, (52) also needs to be modified to
(56) |
to verify Assumption 3 along the longitudinal direction. Compared to FWD, in RWD the longitudinal front tire force is and the longitudinal rear tire force is controlled. Thus one can generalize to RWD by switching all related computations on and from the FWD case.
IX Experiments
This section describes the implementation and evaluation of REFINE in simulation using a FWD, full-size vehicle model and on hardware using an AWD, th size race car model. Readers can find a link to the software implementation111https://github.com/roahmlab/REFINE and videos222https://drive.google.com/drive/folders/1bXl07gTnaA3rJBl7J05SL0tsfIJEDfKy?usp=sharing, https://drive.google.com/drive/folders/1FvGHuqIRQpDS5xWRgB30h7exmGTjRyel?usp=sharing online.
IX-A Desired Trajectories
As detailed in Section V-A, the proposed controller relies on desired trajectories of vehicle longitudinal speed and yaw rate satisfying Definition 7. To test the performance of the proposed controller and planning framework, we selected families of desired trajectories that are observed during daily driving. Each desired trajectory is the concatenation of a driving maneuver and a contingency braking maneuver. The driving maneuver is either a speed change, direction change, or lane change (i.e. each option corresponds to one of the families of desired trajectories). Moreover, each desired trajectory is parameterized by where denotes desired longitudinal speed, and decides desired lateral displacement.
Assuming that the ego vehicle has initial longitudinal speed at time , the desired trajectory for longitudinal speed is the same for each of the families of desired trajectories:
(57) |
where
(58) |
with some deceleration . Note by Definition 7 can be specified as
(59) |
The desired longitudinal speed approaches linearly from before braking begins at time , then decreases to with deceleration and immediately drops down to 0 at time . Moreover, one can verify that the chosen in (57) satisfies the assumptions on desired longitudinal speed in Lemma 14.

Assuming the ego vehicle has initial heading at time , the desired heading trajectory varies among the different trajectory families. Specifically, for the trajectory family associated with speed change:
(60) |
Desired heading trajectory for the trajectory family associated with direction change:
(61) |
and for the trajectory family associated with lane change:
(62) |
where is Euler’s number, and and are user-specified auxiliary constants that adjust the desired heading amplitude. Illustrations of speed change and direction change maneuvers can be found in the software repository333https://github.com/roahmlab/REFINE/blob/main/Rover_Robot_Implementation/README.md#1-desired-trajectories. As shown in Figure 5, remains constant for all among all families of desired trajectories. By Definition 7, desired trajectory of yaw rate is set as among all trajectory families.
In this work, for the speed change and direction change trajectory families are set equal to one another. for the lane change trajectory family is twice what it is for the direction change and speed change trajectory families. This is because a lane change can be treated as a concatenation of two direction changes. Because we do not know which desired trajectory ensures not-at-fault a priori, during each planning iteration, to guarantee real-time performance, should be no greater than the smallest duration of a driving maneuver, i.e. speed change or direction change.
IX-B Simulation on a FWD Model
This subsection describes the evaluation of REFINE in simulation. In particular, this section describes the simulation environment, how we implement REFINE, the methods we compare it to, and the results of the evaluation.
IX-B1 Simulation Environment
We evaluate the performance on randomly generated -lane highway scenarios in which the same full-size, FWD vehicle as the ego vehicle is expected to autonomously navigate through dynamic traffic for [km] from a fixed initial condition. All lanes of all highway scenario share the same lane width as [m]. Each highway scenario contains up to moving vehicles and up to static vehicles that start from random locations and are all treated as obstacles to the ego vehicle. Moreover, each moving obstacle maintains its randomly generated highway lane and initial speed up to [m/s] for all time. Because each highway scenario is randomly generated, there is no guarantee that the ego vehicle has a path to navigate itself from the start to the goal. Such cases allow us to verify if the tested methods can still keep the ego vehicle safe even in infeasible scenarios. Parameters of the ego vehicle can be found in the software implementation readme444https://github.com/roahmlab/REFINE/blob/main/Full_Size_Vehicle_Simulation/README.md#vehicle-and-control-parameters.
During each planning iteration, all evaluated methods use the same high level planner. This high level planner generates waypoints by first choosing the lane on which the nearest obstacle ahead has the largest distance from the ego vehicle. Subsequently it picks a waypoint that is ahead of the ego vehicle and stays along the center line of the chosen lane. The cost function in (Opt) or in any of the evaluated optimization-based motion planning algorithms is set to be the Euclidean distance between the waypoint generated by the high level planner and the predicted vehicle location based on initial state and decision variable . All simulations are implemented and evaluated in MATLAB R2022a on a laptop with an Intel i7-9750H processor and 16GB of RAM.
IX-B2 REFINE Simulation Implementation
REFINE invokes C++ for the online optimization using IPOPT [35]. Parameters of REFINE’s controller are chosen to satisfy the conditions in Lemma 14 and can be found in the software implementation readme555https://github.com/roahmlab/REFINE/blob/main/Full_Size_Vehicle_Simulation/README.md#vehicle-and-control-parameters. REFINE tracks families of desired trajectories as described in Section IX-A with , , and . The duration of driving maneuvers for each trajectory family is 3[s] for speed change, 3[s] for direction change and 6[s] for lane change, therefore is set to be 3[s]. As discussed in Section VIII-A, during offline computation, we evenly partition the first and second dimensions of into intervals of lengths and , respectively. For each partition element, is assigned to be the maximum possible value of as computed in (82) in which is by observation no greater than 0.1[s]. An outer-approximation of the FRS is computed for every partition element of using CORA with as [s], [s], [s] and [s]. Note, that we choose these different values of to highlight how this choice affects the performance of REFINE.
IX-B3 Other Implemented Methods
We compare REFINE against several state of the art trajectory planning methods: a baseline zonotope reachable set method [36], a Sum-of-Squares-based RTD (SOS-RTD) method [13], and an NMPC method using GPOPS-II [37].
The first trajectory planning method that we implement is a baseline zonotope based reachability method that selects a finite number of possible trajectories rather than a continuum of possible trajectories as REFINE does. This baseline method is similar to the classic funnel library approach to motion planning [12] in that it chooses a finite number of possible trajectories to track. The baseline method computes zonotope reachable sets using CORA with [s] over a sparse discrete control parameter space and a dense discrete control parameter space . We use and to illustrate the challenges associated with applying this baseline method in terms of computation time, memory consumption, and the ability to robustly travel through complex simulation environments. During each planning iteration, the baseline method searches through the discrete control parameter space until a feasible solution is found such that the corresponding zonotope reachable sets have no intersection with any obstacles over the planning horizon. The search procedure over this discrete control space is biased to select the same trajectory parameter that worked in the prior planning iteration or to search first from trajectory parameter that are close to one that worked in the previous planning iteration.
The SOS-RTD plans a controller that also tracks families of trajectories to achieve speed change, direction change and lane change maneuvers with braking maneuvers as described in Section IX-A. SOS-RTD offline approximates the FRS by solving a series of polynomial optimizations using Sum-of-Squares so that the FRS can be over-approximated as a union of superlevel sets of polynomials over successive time intervals of duration 0.1[s] [13]. Computed polynomial FRS are further expanded to account for footprints of other vehicles offline in order to avoid buffering each obstacle with discrete points online [16]. During online optimization, SOS-RTD plans every [s] and uses the same cost function as REFINE does, but checks collision against obstacles by enforcing that no obstacle has its center stay inside the FRS approximation during any time interval.
The NMPC method does not perform offline reachability analysis. Instead, it directly computes the control inputs that are applicable for seconds by solving an optimal control problem. This optimal control problem is solved using GPOPS-II in a receding horizon fashion. The NMPC method conservatively ensures collision-free trajectories by covering the footprints of the ego vehicle and all obstacles with two overlapping balls, and requiring that no ball of the ego vehicle intersects with any ball of any obstacle. Notice during each online planning iteration, the NMPC method does not need pre-defined desired trajectories for solving control inputs. Moreover, it does not require the planned control inputs to stop the vehicle by the end of planned horizon as the other three methods do.
Method | Safely Stop | Crash | Success | Average Travel Speed | Solving Time of Online Planning | Memory |
---|---|---|---|---|---|---|
(Average, Maximum) | ||||||
Baseline (sparse, ) | 38% | 0% | 62% | 22.3572[m/s] | (2.03[s], 4.15[s]) | 980 MB |
Baseline (dense, ) | 30% | 0% | 70% | 23.6327[m/s] | (12.42[s], 27.74[s]) | 9.1 GB |
SOS-RTD | 36% | 0% | 64% | 24.8049[m/s] | (0.05[s], 1.58[s]) | 2.4 GB |
NMPC | 3% | 29% | 68% | 27.3963[m/s] | (40.89[s], 534.82[s]) | N/A |
REFINE () | 27% | 0% | 73% | 23.2452[m/s] | (0.34[s], 0.95[s]) | 488 MB |
REFINE () | 17% | 0% | 83% | 24.8311[m/s] | (0.52[s], 1.57[s]) | 703 MB |
REFINE () | 16% | 0% | 84% | 24.8761[m/s] | (1.28[s], 4.35[s]) | 997 MB |
REFINE () | 16% | 0% | 84% | 24.8953[m/s] | (6.48[s], 10.78[s]) | 6.4 GB |
IX-B4 Evaluation Criteria
We evaluate each implemented trajectory planning method in several ways as summarized in Table I First, we report the percentage of times that each planning method either came safely to a stop (in a not-at-fault manner), crashed, or successfully navigated through the scenario. Note a scenario is terminated when one of those three conditions is satisfied. Second, we report the average travel speed during all scenarios. Third, we report the average and maximum planning time over all scenarios. Finally, we report on the size of the pre-computed reachable set.
IX-B5 Results
REFINE achieves the highest success rate among all evaluated methods and has no crashes. The success rate of REFINE converges to 84% as the value of decreases because the FRS approximation becomes tighter with denser time discretization. However as the time discretization becomes finer, memory consumption grows larger because more zonotopes are used to over-approximate FRS. Furthermore, due to the increasing number of zonotope reachable sets, the solving time also increases and begins to exceed the allotted planning time. According to our simulation, we see that [s] results in high enough successful rate while maintaining a planning time no greater than [s].
The baseline method with shares almost the same memory consumption as REFINE with [s], but results in a much lower successful rate and smaller average travel speed. When the baseline method runs over , its success rate is increased, but still smaller than that of REFINE. More troublingly, its memory consumption increases to GB. Neither evaluated baseline is able to finish online planning within [s]. Compared to REFINE, SOS-RTD completes online planning faster and can also guarantee vehicle safety with a similar average travel speed. However SOS-RTD needs a memory of GB to store its polynomial reachable sets, and its success rate is only % because the polynomial reachable sets are more conservative than zonotope reachable sets.
When the NMPC method is utilized for motion planning, the ego vehicle achieves a similar success rate as SOS-RTD, but crashes occur % of the time. Note the NMPC method achieves a higher average travel speed of the ego vehicle when compared to the other three methods. More aggressive operation can allow the ego vehicle drive closer to obstacles, but can make subsequent obstacle avoidance difficult. The NMPC method uses [s] on average to compute a solution, which makes real-time path planning untenable.



Figure 6 illustrates the performance of the three methods in the same scene at three different time instances. In Figure 6(a), because REFINE gives a tight approximation of the ego vehicle’s FRS using zonotopes, the ego vehicle is able to first bypass static vehicles in the top lane from [s] to [s], then switch to the top lane and bypass vehicles in the middle lane from [s] to [s]. In Figure 6(b) SOS-RTD is used for planning. In this case the ego vehicle bypasses the static vehicles in the top lane from [s] to [s]. However because online planing becomes infeasible due to the conservatism of polynomial reachable sets, the ego vehicle executes the braking maneuver to stop itself [s] to [s]. In Figure 6(c) because NMPC is used for planning, the ego vehicle drives at a faster speed and arrives at [m] before the other evaluated methods. Because the NMPC method only enforces collision avoidance constraints at discrete time instances, the ego vehicle ends up with a crash at [s] though NMPC claims to find a feasible solution for the planning iteration at [s].
IX-C Real World Experiments
REFINE was also implemented in C++17 and tested in the real world using a th All-Wheel-Drive car-like robot, Rover, based on a Traxxax RC platform. The Rover is equipped with a front-mounted Hokuyo UST-10LX 2D lidar that has a sensing range of 10[m] and a field of view of 270°. The Rover is equipped with a VectorNav VN-100 IMU unit which publishes data at 800Hz. Sensor drivers, state estimator, obstacle detection, and the proposed controller are run on an NVIDIA TX-1 on-board computer. A standby laptop with Intel i7-9750H processor and 32GB of RAM is used for localization, mapping, and solving (Opt) in over multiple partitions of . The rover and the standby laptop communicate over wifi using ROS [38].
The desired trajectories on the Rover are parameterized with , [m/sec2], and as described in Section IX-A. The duration of driving maneuvers for each trajectory family is set to [s] for speed change, [s] for direction change, and [s] for lane change, thus planning time for real world experiments is set as [s]. The parameter space is evenly partitioned along its first and second dimensions into small intervals of lengths 0.25 and 0.349, respectively. For each partition element, is set equal to the maximum possible value of as computed in (82) in which is by observation no greater than 0.1[s]. The FRS of the Rover for every partition element of is overapproximated using CORA with [s]. During online planning, a waypoint is selected in real time using Dijkstra’s algorithm [39], and the cost function of (Opt) is set in the same way as we do in simulation as described in Section IX-B. The robot model, environment sensing, and state estimation play key roles in real world experiments. In the rest of this subsection, we describe how to bound the modeling error in (14) and summarize the real world experiments. Details regarding Rover model parameters, the controller parameters, how the Rover performs localization, mapping, and obstacle detection and how we perform system identification of the tire models can be found in our software implementation readme666https://github.com/roahmlab/REFINE/blob/main/Rover_Robot_Implementation/README.md.
IX-C1 State Estimation and System Identification on Model Error in Vehicle Dynamics

The modeling error in the dynamics (14) arise from ignoring aerodynamic drag force and the inaccuracies of state estimation and the tire models. We use the data collected to fit the tire models to identify the modeling errors , , and .
We compute the model errors as the difference between the actual accelerations collected by the IMU and the estimation of applied accelerations computed via (4) in which tire forces are calculated via (12) and (13). The estimation of applied accelerations is computed using the estimated system states via an Unscented Kalman Filter (UKF) [40], which treats SLAM results, IMU readings, and encoding information of wheel and steering motors as observed outputs of the Rover model. The robot dynamics that UKF uses to estimate the states is the error-free, high-speed dynamics (4) with linear tire models. Note the UKF state estimator is still applicable in the low-speed case except the estimation of and are ignored. To ensure , and are square integrable, we set for all where is computed in Lemma 14. As shown in Figure 7 bounding parameters , , and are selected to be the maximum value of , , and respectively over all time, and and are generated by bounding from above when .
IX-C2 Demonstration
The Rover was tested indoors under the proposed controller and planning framework in 6 small trials and 1 loop trial777https://drive.google.com/drive/folders/1FvGHuqIRQpDS5xWRgB30h7exmGTjRyel?usp=sharing. In every small trail, up to identical [m]3 cardboard cubes were placed in the scene before the Rover began to navigate itself. The Rover was not given prior knowledge of the obstacles for each trial. Figure 8 illustrates the scene in the 6th small trial and illustrates REFINE’s performance. The zonotope reachable sets over-approximate the trajectory of the Rover and never intersect with obstacles.
In the loop trial, the Rover was required to perform 3 loops, and each loop is about 100[m] in length. In the first loop of the loop trial, no cardboard cube was placed in the loop, while in the last two loops the cardboard cubes were randomly thrown at least 5[m] ahead of the running Rover to test its maneuverability and safety. During the loop trial, the Rover occasionally stoped because a randomly thrown cardboard cube might be close to a waypoint or the end of an executing maneuver. In such cases, because the Rover was able to eventually locate obstacles more accurately when it was stopped, the Rover began a new planning iteration immediately after stopping and passed the cube when a feasible plan with safety guaranteed was found.
For all 7 real-world testing trials, the Rover either safely finishes the given task, or it stops itself before running into an obstacle if no clear path is found. The Rover is able to finish all computation of a planning iteration within 0.4021[s] on average and 0.6545[s] in maximum, which are both smaller than [s], thus real-time performance is achieved.


X Conclusion
This work presents a controller-oriented trajectory design framework using zonotope reachable sets. A robust controller is designed to partially linearize the full-order vehicle dynamics with modeling error by performing feedback linearization on a subset of vehicle states. Zonotope-based reachability analysis is performed on the closed-loop vehicle dynamics for FRS computation, and achieves less conservative FRS approximation than that of the traditional reachability-based approaches. Tests on a full-size vehicle model in simulation and a 1/10th race car robot in real hardware experiments show that the proposed method is able to safely navigate the vehicle through random environments in real time and outperforms all evaluated state of the art methods.
References
- [1] Steven M LaValle and James J Kuffner Jr “Randomized kinodynamic planning” In The international journal of robotics research 20.5 SAGE Publications, 2001, pp. 378–400
- [2] Lucas Janson, Edward Schmerling, Ashley Clark and Marco Pavone “Fast marching tree: A fast marching sampling-based method for optimal motion planning in many dimensions” In The International journal of robotics research 34.7 SAGE Publications Sage UK: London, England, 2015, pp. 883–921
- [3] Mohamed Elbanhawi and Milan Simic “Sampling-based robot motion planning: A review” In Ieee access 2 IEEE, 2014, pp. 56–77
- [4] Steven M LaValle “Planning algorithms” Cambridge university press, 2006
- [5] Yoshiaki Kuwata et al. “Real-time motion planning with applications to autonomous urban driving” In IEEE Transactions on control systems technology 17.5 IEEE, 2009, pp. 1105–1118
- [6] Thomas M Howard and Alonzo Kelly “Optimal rough terrain trajectory generation for wheeled mobile robots” In The International Journal of Robotics Research 26.2 Sage Publications Sage CA: Thousand Oaks, CA, 2007, pp. 141–166
- [7] Paolo Falcone et al. “Low complexity mpc schemes for integrated vehicle dynamics control problems” In 9th international symposium on advanced vehicle control (AVEC), 2008
- [8] Chris Urmson et al. “Autonomous driving in urban environments: Boss and the urban challenge” In Journal of Field Robotics 25.8 Wiley Online Library, 2008, pp. 425–466
- [9] John Wurts, Jeffrey L Stein and Tulga Ersal “Collision imminent steering using nonlinear model predictive control” In 2018 Annual American Control Conference (ACC), 2018, pp. 4772–4777 IEEE
- [10] Matthias Althoff and John M Dolan “Online verification of automated road vehicles using reachability analysis” In IEEE Transactions on Robotics 30.4 IEEE, 2014, pp. 903–918
- [11] Christian Pek, Stefanie Manzinger, Markus Koschi and Matthias Althoff “Using online verification to prevent autonomous vehicles from causing accidents” In Nature Machine Intelligence 2.9 Nature Publishing Group, 2020, pp. 518–528
- [12] Anirudha Majumdar and Russ Tedrake “Funnel libraries for real-time robust feedback motion planning” In The International Journal of Robotics Research 36.8 SAGE Publications Sage UK: London, England, 2017, pp. 947–982
- [13] Shreyas Kousik et al. “Bridging the gap between safety and real-time performance in receding-horizon trajectory design for mobile robots” In The International Journal of Robotics Research 39.12 SAGE Publications Sage UK: London, England, 2020, pp. 1419–1469
- [14] Shreyas Kousik, Sean Vaskov, Matthew Johnson-Roberson and Ram Vasudevan “Safe trajectory synthesis for autonomous driving in unforeseen environments” In ASME 2017 Dynamic Systems and Control Conference, 2017 American Society of Mechanical Engineers Digital Collection
- [15] Sean Vaskov et al. “Not-at-fault driving in traffic: A reachability-based approach” In 2019 IEEE Intelligent Transportation Systems Conference (ITSC), 2019, pp. 2785–2790 IEEE
- [16] Sean Vaskov et al. “Towards provably not-at-fault control of autonomous robots in arbitrary dynamic environments” In arXiv preprint arXiv:1902.02851, 2019
- [17] Somil Bansal, Mo Chen, Sylvia Herbert and Claire J Tomlin “Hamilton-jacobi reachability: A brief overview and recent advances” In 2017 IEEE 56th Annual Conference on Decision and Control (CDC), 2017, pp. 2242–2253 IEEE
- [18] Sylvia L Herbert et al. “FaSTrack: A modular framework for fast and guaranteed safe motion planning” In 2017 IEEE 56th Annual Conference on Decision and Control (CDC), 2017, pp. 1517–1522 IEEE
- [19] Reza N Jazar “Vehicle dynamics: theory and application” Springer, 2008 URL: https://link.springer.com/chapter/10.1007/978-0-387-74244-1_2
- [20] A Galip Ulsoy, Huei Peng and Melih Çakmakci “Automotive control systems” Cambridge University Press, 2012
- [21] Thomas D Gillespie “Fundamentals of vehicle dynamics”, 1992
- [22] James Balkwill “Performance vehicle dynamics: engineering and applications” Butterworth-Heinemann, 2017
- [23] S Dieter, M Hiller and R Baradini “Vehicle Dynamics: Modeling and Simulation” Springer-Verlag Berlin Heidelberg, Berlin, Germany, 2018
- [24] Tae-Yun Kim, Samuel Jung and Wan-Suk Yoo “Advanced slip ratio for ensuring numerical stability of low-speed driving simulation: Part II—lateral slip ratio” In Proceedings of the Institution of Mechanical Engineers, Part D: Journal of automobile engineering 233.11 SAGE Publications Sage UK: London, England, 2019, pp. 2903–2911
- [25] Reinhold Remmert “Theory of complex functions” Springer Science & Business Media, 1991
- [26] Shai Shalev-Shwartz, Shaked Shammah and Amnon Shashua “On a formal model of safe and scalable self-driving cars” In arXiv preprint arXiv:1708.06374, 2017
- [27] Ming-Yuan Yu, Ram Vasudevan and Matthew Johnson-Roberson “Occlusion-aware risk assessment for autonomous driving in urban environments” In IEEE Robotics and Automation Letters 4.2 IEEE, 2019, pp. 2235–2241
- [28] Ming-Yuan Yu, Ram Vasudevan and Matthew Johnson-Roberson “Risk assessment and planning with bidirectional reachability for autonomous driving” In 2020 IEEE International Conference on Robotics and Automation (ICRA), 2020, pp. 5363–5369 IEEE
- [29] Andrea Giusti and Matthias Althoff “Ultimate robust performance control of rigid robot manipulators using interval arithmetic” In 2016 American Control Conference (ACC), 2016, pp. 2995–3001 IEEE
- [30] Jan Lunze and Françoise Lamnabhi-Lagarrigue “Handbook of hybrid systems control: theory, tools, applications” Cambridge University Press, 2009
- [31] Matthias Althoff “An introduction to CORA 2015” In Proc. of the Workshop on Applied Verification for Continuous and Hybrid Systems, 2015
- [32] Matthias Althoff “Reachability analysis and its application to the safety assessment of autonomous cars”, 2010
- [33] Patrick Holmes et al. “Reachable sets for safe, real-time manipulator trajectory design (version 1)” https://arxiv.org/abs/2002.01591v1 In arXiv preprint arXiv:2002.01591, 2020
- [34] Timothy Hickey, Qun Ju and Maarten H Van Emden “Interval arithmetic: From principles to implementation” In Journal of the ACM (JACM) 48.5 ACM New York, NY, USA, 2001, pp. 1038–1068
- [35] Andreas Wächter and Lorenz T Biegler “On the implementation of an interior-point filter line-search algorithm for large-scale nonlinear programming” In Mathematical programming 106.1 Springer, 2006, pp. 25–57
- [36] Stefanie Manzinger, Christian Pek and Matthias Althoff “Using reachable sets for trajectory planning of automated vehicles” In IEEE Transactions on Intelligent Vehicles 6.2 IEEE, 2020, pp. 232–248
- [37] Michael A Patterson and Anil V Rao “GPOPS-II: A MATLAB software for solving multiple-phase optimal control problems using hp-adaptive Gaussian quadrature collocation methods and sparse nonlinear programming” In ACM Transactions on Mathematical Software (TOMS) 41.1 ACM New York, NY, USA, 2014, pp. 1–37
- [38] Stanford Artificial Intelligence Laboratory et al. “Robotic Operating System”, 2018 URL: https://www.ros.org
- [39] Edsger W Dijkstra “A note on two problems in connexion with graphs” In Numerische mathematik 1.1, 1959, pp. 269–271
- [40] E.A. Wan and R. Van Der Merwe “The unscented Kalman filter for nonlinear estimation” In Proceedings of the IEEE 2000 Adaptive Systems for Signal Processing, Communications, and Control Symposium (Cat. No.00EX373), 2000, pp. 153–158 DOI: 10.1109/ASSPCC.2000.882463
- [41] Leonidas J Guibas, An Thanh Nguyen and Li Zhang “Zonotopes as bounding volumes.” In SODA 3, 2003, pp. 803–812
- [42] Elijah Polak “Optimization: algorithms and consistent approximations” Springer Science & Business Media, 2012
Appendix A Proof of Lemma 14
Proof.
This proof defines a Lyapunov function candidate and uses it to analyze the tracking error of the ego vehicle’s longitudinal speed before time . Then it describes how evolves after time in different scenarios depending on the value of . Finally it describes how to set the time to guarantee for all . For convenience, let , then by assumption of the theorem . This proof suppresses the dependence on in , , , and .
Note by (25) and rearranging (26),
(63) |
Recall is piecewise continuously differentiable by Definition 7, so are and . Without loss of generality we denote a finite subdivision of with and such that is continuously differentiable over time interval for all . Define as a Lyapunov function candidate for , then for arbitrary and , one can check that is always non-negative and only if . Then
(64) | ||||
(65) | ||||
(66) | ||||
(67) |
in which the second equality comes from (63) and the third equality comes from (22). Because the integral terms in (23) and (24) are both non-negative, and hold. Then
(68) |
By factoring out in the last two terms in (68):
(69) |
holds when and . Note conservatively implies given for all time by Assumption 4. Then when we have (69) hold, or equivalently decreases. Therefore if , monotonically decreases during time interval as long as does not reach at the boundary of closed ball . Moreover, if hits the boundary of at some time , is prohibited from leaving the ball for all because is strictly negative when . Similarly implies for all .
We now analyze the behavior of for all . By assumption , then and thus for all . Because both and are continuous during , so is . Thus . By iteratively applying the same reasoning, one can show that for all and for all , therefore for all . Furthermore, because converges to as converges to from below, . Note because .
Next we analyze how longitudinal speed of the ego vehicle evolves after time . Using , we point out that (68) remains valid for all , and (69) also holds when with . Recall for all given for all , then for simplicity, the remainder of this proof replaces every by in (68), (69) and . Because and is continuous with respect to time, the longitudinal speed of the ego vehicle cannot decrease from a positive value to a negative value without passing 0. However when , by Assumption 5 , thus by (26) given for all . In other words, once arrives at 0, it remains at 0 forever. For the ease of expression, from now on we assume and for all . Recall and . We now discuss how evolves after time by considering three scenarios, and giving an upper bound of the time at when reaches 0 for each scenario.
Case 1 - When : Because the longitudinal speed stays at 0 once it becomes 0, by Assumption 13 the ego vehicle reaches to a full stop no later than .
Case 2 - When : By Assumption 5, upper bound of can be further relaxed from (68) to
(70) |
Moreover, by completing the square among the last two terms in (70), one can derive
(71) |
Notice by assumption, thus
(72) |
This means as long as with , we obtain , or equivalently decreases monotonically. Recall , then the longitudinal speed decreases monotonically from to 0.15 as time increases from . Suppose becomes 0.15 at time , then for all because of the fact that is strictly negative when .
Define , then when , (71) can be relaxed to
(73) |
Integrate both sides of (73) from time to results in
(74) |
Because ,
(75) |
Then becomes 0 no later than time based on Assumption 13, where as the upper bound of reads
(76) |
Case 3 - When : Recall (69) holds given , then
(77) |
and we have the longitudinal speed monotonically decreasing from at time until it reaches at at some time . Integrating the left hand side and right hand side of (77) from to gives
(78) |
Because , (78) results in
(79) |
Once the longitudinal speed decreases to , we can then follow the same reasoning as in the second scenario for seeking an upper bound of some time that is no smaller than and gives . However, this time we need to integrate both sides of (73) from time to . As a result,
(80) |
Then becomes 0 no later than time based on Assumption 13, where as the upper bound of reads
(81) |
Now that we have the upper bound for across these three scenarios, recall that once arrives at 0, it remains at 0 afterwards, and notice . Considering all three scenarios discussed above, setting as the maximum value among , and , i.e.,
(82) |
guarantees that for all . ∎
Appendix B Proof of Theorem 19
Proof.
Because and have zero dynamics in , the last dimensions in are identical to for all . A direct result of Proposition 17 and Definition 18 is where and for all . Because and , then for all , and for all by Definition 1. is generated by specifying the coefficients of the first generators in via (45), thus .
Appendix C Proof of Lemma 21
Before proving Lemma 21, we prove the following lemma:
Lemma 25.
Let be the zonotope computed by CORA under the hybrid vehicle dynamics model beginning from for arbitrary . Then for any and
(83) |
Proof.
Because is independent of and by definition, shares the same sliceable generators as . The slice operator only affects sliceable generators, thus (83) holds. ∎
Now we prove Lemma 21:
Proof.
By definition and are both zonotopes, thus is a zonotope per (83). For simplicity denote as , then is a zonotope because
(84) |
Note , and by using the definition of one can check that for any zonotopes . Then by Lemma 25,
(85) |
By Theorem 19 for any and , , then . Because by construction outer approximates the area over which sweeps according to all possible heading of the ego vehicle during , then contains the vehicle footprint oriented according to and centered at during . ∎
Appendix D Proof of Theorem 23
We first prove a pair of lemmas. The first lemma simplifies the expression of .
Lemma 26.
Let be the zonotope computed by CORA under the hybrid vehicle dynamics model beginning from for arbitrary , and let be defined as (47). Then for arbitrary and , there exist , and a real matrix with two rows such that .
Proof.
Note is a zonotope by construction in (51) because is assumed to be a zonotope. The following lemma follows from [41, Lem. 5.1] and allows us to represent the intersection constraint in (Opt) .
Lemma 27.
Now we can finally state the proof of Theorem 23:
Proof.
Let as computed in Lemma 26, and let be computed from Assumption 22 and (51). Because all zonotopes are convex polytopes [41], zonotope can be transferred into a half-space representation for some matrix and vector . To find such and , we denote and with some positive integer , and denote . Define
(89) |
Then as a result of [32, Thm 2.1], with
(90) | ||||
(91) |
where is the column vector of ones.
By Lemma 27, if and only if , or in other words . Notice if and only if .
The subgradient claim follows from [42, Theorem 5.4.5]. ∎