AbstractâIn this paper we present a Model Predictive. Control (MPC) approach for combined braking and steering systems in autonomous vehicles. We start ...
A Model Predictive Control Approach for Combined Braking and Steering in Autonomous Vehicles Paolo Falcone∗ , Francesco Borrelli∗ , Jahan Asgari† , H. Eric Tseng† , Davor Hrovat† ∗ Universit`a
del Sannio, Dipartimento di Ingegneria, 82100 Benevento, Italy Email: {falcone,francesco.borrelli}@unisannio.it † Ford Research Laboratories, Dearborn, MI 48124, USA Email: {jasgari,htseng,dhrovat}@ford.com
Abstract— In this paper we present a Model Predictive Control (MPC) approach for combined braking and steering systems in autonomous vehicles. We start from the result presented in [1] and [2], where a Model Predictive Controller (MPC) for autonomous steering systems has been presented. We formulate a predictive control problem in order to best follow a given path by controlling the front steering angle and the brakes at the four wheels independently, while fulfilling various physical and design constraints.
I. I NTRODUCTION Recent trends in automotive industry point in the direction of increased content of electronics, computers, and controls with emphasis on the improved functionality and overall system robustness. While this affects all of the vehicle areas, there is a particular interest in active safety. The available commercial active safety systems are mostly based on brake intervention. Anti-lock Braking Systems (ABS) and Electronic Stability Program (ESP) have been introduced to stabilize the longitudinal and yaw motion vehicle dynamics respectively. Future systems will be able to increase the effectiveness of active safety interventions by additional actuator types such as 4WS, active steering, active suspensions, or active differentials, and also by additional sensor information, such as the increased inclusion of onboard cameras, as well as infrared and other sensor alternatives. All these will be further complemented by GPS information including pre-stored mapping. In this context, it is possible to imagine that future vehicles would be able to identify obstacles on the road such as an animal, a rock, or fallen tree/branch, and assist the driver by following the best possible path, in terms of avoiding the obstacle and at the same time keeping the vehicle on the road at a safe distance from incoming traffic [1], [3]. At this stage, we assume this “ultimate” obstacle avoidance system will be possible sometime in the future and we propose a double lane change scenario on a slippery road, with a vehicle equipped with fully autonomous steering and braking systems. The control input are the front steering angle and the braking at the four wheels and the goal is to follow the desired trajectory or target as close as possible while fulfilling various constraints reflecting vehicle physical limits. We assume a given desired trajectory and we will design a controller that can
best follow the trajectory on slippery road at the highest possible entry speed. Anticipating sensor and infrastructure trends toward increased integration of information and control actuation agents, it is then appropriate to ask what is the best and optimum way in controlling the vehicle maneuver for given obstacle avoidance situation. This will be done in the spirit of Model Predictive Control, MPC [4], [5] along the lines of our ongoing internal research efforts dating from early 2000 [6]. We use a model of the plant to predict the future evolution of the system [5], [7], [8]. Based on this prediction, at each time step t a performance index is optimized under operating constraints with respect to a sequence of future steering and braking moves in order to best follow the given trajectory on a slippery road. The first of such optimal moves is the control action applied to the plant at time t. At time t + 1, a new optimization is solved over a shifted prediction horizon. In [1] a nonlinear vehicle model is considered to predict the future evolution of the system [5]. The resulting MPC controller requires a non-linear optimization problem to be solved at each time step. Although good results have been achieved, even at high vehicle speed, the computational burden is a serious obstacle for experimental validation. In [2] a sub-optimal MPC steering controller based on successive on-line linearizations of the nonlinear vehicle model is presented. The method stems from an accurate analysis of the vehicle nonlinearities, the constraints and the performance index in the optimal control problem. The presented experimental results demonstrated that the controller can stabilize the vehicle even at high speed on slippery surfaces. In this paper we reformulate the path following control problem in [1] and [2], as a MPC control problem where the control inputs are the front steering angle and the tire slip ratios at the four wheels. We assume that a lower level braking system is able to implement the desired tire slip ratios. The MPC formulation relies on a full four wheels nonlinear model including the tire nonlinearities. The paper is structured as follows. Section II describes the vehicle dynamical model used with a brief discussion on tire models. Section III formulates the control problem. The considered scenario is presented in Section IV. Sim-
ulation and experimental results are shown in section IV and concluding remarks in section V close the paper.
The vehicle’s equations of motion in an absolute inertial frame are
II. M ODELING
Y˙ = x˙ sin ψ + y˙ cos ψ, X˙ = x˙ cos ψ − y˙ sin ψ.
This section describes the vehicle and tire model we used for simulations and control design. The nomenclature refers to the model depicted in Figure 1. We denote by Fl , Fc the longitudinal (or “tractive”) and lateral (or “cornering”) tire forces, respectively, Fx , Fy the longitudinal and lateral forces acting on the vehicle center of gravity, Fz the normal tire load, X, Y the absolute car position inertial coordinates, a, b (distance of front and rear wheels from center of gravity) and c (distance of the vehicle longitudinal axis from the wheels) the car geometry , g the gravitational constant, m the car mass, I the car inertia, r the wheel radius, s the slip ratio, µ the road friction coefficient, vl , vc the longitudinal and lateral wheel velocities, ψ the heading angle, x˙ and y˙ the vehicle longitudinal and lateral speed respectively, α the slip angle, δ the wheel steering angle, µ the road friction coefficient and ψ the heading angle. The lower scripts (·)f and (·)r particularize a variable at the front wheels and the rear wheels, respectively, e.g. Flf is the front wheel longitudinal force. A. Vehicle Model We use a four wheels model to describe the dynamics of the car and assume constant normal tire load, i.e., Fzf,l , Fzf,r , Fzr,l , Fzr,r = constant. Such model captures the most relevant nonlinearities associated to lateral stabilization of the vehicle. Figure 1 depicts a diagram of the vehicle model, which has the following longitudinal, lateral and turning or yaw degrees of freedom (DOF) m¨ x = my˙ ψ˙ + Fxf,l + Fxf,r + Fxr,l + Fxr,r m¨ y = −mx˙ ψ˙ + Fyf,l + Fyf,r + Fyr,l + Fyr,r , ¡ ¢ ¡ ¢ I ψ¨ = a Fyf,l + Fyf,r − b Fyr,l + Fyr,r ¡ ¢ + c −Fxf,l + Fxf,r − Fxr,l + Fxr,r .
(1c) (1d)
(2b)
The longitudinal and lateral forces generated by the four tires lead to the following forces acting on the center of gravity: Fy = Fl sin δ + Fc cos δ,
(3a)
Fx = Fl cos δ − Fc sin δ.
(3b)
Tire forces for each tire are given by Fl = fl (α, s, µ, Fz ), Fc = fc (α, s, µ, Fz ),
(4a) (4b)
where α is the slip angle of the tire, s is the slip ratio defined as ½ s = rω vl − 1 if vl > rω, v 6= 0 for braking (5) s= vl if vl < rω, ω 6= 0 for driving s = 1 − rω where vl is the longitudinal wheel velocity, r and ω are the wheel radius and angular speed respectively. The slip angle represents the angle between the wheel velocity and the direction of the wheel itself: vc α = tan−1 . (6) vl In equations (5) and (6), vc and vl are the lateral (or cornering) and longitudinal wheel velocities, respectively, which are expressed as vl = vy sin δ + vx cos δ, vc = vy cos δ − vx sin δ,
(1a) (1b)
(2a)
(7a) (7b)
and vyf,l = y˙ + aψ˙ vy = y˙ + aψ˙
˙ vxf,l = x˙ − cψ, ˙ vx = x˙ + cψ,
= y˙ − bψ˙ = y˙ − bψ˙
˙ = x˙ − cψ, ˙ = x˙ + cψ.
f,r
vyr,l vyr,r
f,r
vxr,l vxr,r
(8a) (8b) (8c) (8d)
The parameter µ in (4) represents the road friction coefficient and Fz is the total vertical load of the vehicle. This is distributed between the front and rear wheels based on the geometry of the car model, described by the parameters a and b: Fzf =
bmg , 2(a + b)
Fzr =
amg . 2(a + b)
(9a)
Using the equations (1)-(9), the nonlinear vehicle dynamics can be described by the following compact differential equation assuming a certain friction coefficient value µ:
Fig. 1.
The simplified vehicle dynamical model.
ξ˙ = fµ (ξ, u),
(10a)
η = h(ξ),
(10b)
where the state and input vectors are ξ = ˙ Y, X] and u = [δf , sf,l , sf,r , sr,l , sr,r ] [y, ˙ x, ˙ ψ, ψ, respectively, and the output map is given as 0 1 0 0 0 0 0 0 1 0 0 0 h(ξ) = (11) 0 0 0 1 0 0 ξ. 0 0 0 0 1 0 B. Tire Model The model for tire tractive and cornering forces (4) used in this paper is described by a Pacejka model [9]. This is a complex, semi-empirical model that takes into consideration the interaction between the tractive force and the cornering force in combined braking and steering. The longitudinal and cornering forces are assumed to depend on the normal force, slip angle, surface friction, and longitudinal slip. Sample plots of predicted longitudinal and lateral force versus longitudinal slip and slip angle are shown in Figure 2. These plots are shown for a single tire.
Tire forces as a function of longitudinal slip, with zero slip angle and µ = [0.9, 0.7, 0.5, 0.3, 0.1] 4000
0
l
c
F , F [N]
2000
−2000 Fl − longitudinal force F − lateral force
−4000
c
−30
−20
−10
0 Tire slip ratio [%]
10
20
Q
2
k∆ut+i,t kR +
i=0
H c −1 X
2
kut+i,t kS + ρ²
i=0
(13)
where, as in standard MPC notation [5], ∆Ut = ∆ut,t , . . . , ∆ut+Hc −1,t is the optimization vector at time t and ηˆt+i,t denotes the output vector predicted at time t+ i obtained by starting from the state ξt,t = ξ(t) and applying to system (12) the input sequence ∆ut,t , . . . , ∆ut+i,t . Hp and Hc denote the output prediction horizon and the control horizon, respectively. As in standard MPC schemes, we use Hp > Hc and the control signal is assumed constant for all Hc ≤ t ≤ Hp , i.e., ∆ut+i,t = 0 ∀i ≥ Hc . The reference signal ηref represents the ˙ Y ]0 . Q, R and S desired outputs, where η = [x, ˙ ψ, ψ, are weighting matrices of appropriate dimensions. In (13) the first summand reflects the desired performance on target tracking, the second and the third summands are a measure of the steering and braking effort. The minimization of (13) subject to the model equation (12) is the base of the NLMPC scheme presented in [1], where a steering only controller is designed. The LTV-MPC scheme presented in [2], [10] is used next. It is based on the following optimization problem:
∆Ut
2000 0
J(ξt , Ut )
(14a)
subj. to ξk+1,t = At ξk,t + Bt uk,t + dk,t ,
(14b)
l
c
Hp ° °2 X ° ° ηt+i,t − ηref t+i,t ° + °ˆ
i=1 H c −1 X
min
Fl − longitudinal force F − lateral force c
F , F [N]
J(ξ(t), ∆Ut ) =
30
Tire forces as a function of slip angle, with zero slip ratio and µ = [0.9, 0.7, 0.5, 0.3, 0.1] 4000
We consider the following cost function:
−2000
αk,t = Ct ξk,t + Dt uk,t + ek,t
(14c)
ηk,t
(14d)
−4000 −40
−30
−20
−10 0 10 Tire slip angle [deg]
20
30
40
Fig. 2. Longitudinal and lateral tire forces with different µ coefficient values.
III. M ODEL PREDICTIVE CONTROL PROBLEM . We design a MPC controller computing the front steering angle and the slip ratios at the four wheels, such that a desired path is followed, while keeping the longitudinal speed as close as possible to a given reference. We assume the existence of a low level braking slip controller for each wheel and neglect their dynamics. In order to obtain a finite dimensional optimal control problem we consider the model (10) and discretize the system dynamics with the Euler method, to obtain ξ(k + 1) = fµdt (ξ(k), ∆u(k)), η(k) = h(ξ(k)),
(12a) (12b)
where the ∆u formulation is used, i.e., u(k) = u(k − 1) + ∆u(k) and u(k) = [δf (k), sf,l , sf,r , sr,l , sr,r ], ∆u(k) = [∆δf (k), ∆sf,l , ∆sf,r , ∆sr,l , ∆sr,r ].
0 0 = 0 0
1 0 0 0
0 1 0 0
0 0 1 0
0 0 0 1
0 0 0ξk,t 0
k = t, . . . , t + Hp − 1 uk,t = uk−1,t + ∆uk,t , (14e) ut−1,t = u(t − 1) (14f) uf,min ≤ uk,t ≤ uf,max (14g) ∆uf,min ≤ ∆uk,t ≤ ∆uf,max (14h) k = t, . . . , t + Hc − 1 ∆uk,t = 0, k = t + Hc , . . . , t + Hp (14i) αfmin − ² ≤ αfk,t ≤ αfmax + ² (14j) αrmin − ² ≤ αrk,t ≤ αrmax + ² (14k) k = t, . . . , t + Hp (14l) ²≥0 ξt,t = ξ(t)
(14m)
where the equations (14b) are a discrete linear approximation of (12) computed at the current state ξ(t) and the previously applied control input u(t − 1). In (14b)-(14c), the terms dk,t and ek,t take into account that the operating point ξ(t), u(t − 1) in general is not an equilibrium point.
6 Desired path Cone 5
4
3
Y [m]
2
1
0
−1
−2
−3
0
20
40
Fig. 3.
60 X [m]
80
100
120
The reference path to be followed
Further details can be found in [10]. The optimization problem (14) can be recast as a quadratic program (QP) (details can be found in [1]) and the resulting MPC controller for a Linear Time Varying (LTV) system will solve the problem (14) at each time step. Once a solution ∆Ut∗ to problem (14) has been obtained, the input command is computed as u(k) = u(k − 1) + ∆u∗t,t ,
(15)
where ∆u∗t,t is the vector of the first m elements of ∆Ut∗ if system (14b) has m inputs. At the next time step, the linear model (14b)-(14c) is computed based on new state and input measurements, and the new QP problem (14) is solved over a shifted horizon. Complexity of (14) reduces compared to the NLMPC in ref. [1], and it is function of the time needed to setup the problem (14), i.e., to compute the linear models (At , Bt , Ct , Dt ) in (14b)-(14c) along the trajectory, and of the time to solve it. As in [2], the stability of the closed loop system is enforced through the ad hoc constraints (14j), (14k). In particular, without the constraints (14j), (14k) the performance of the linear MPC controller (14)-(15) is not acceptable and sometime unstable. The motivations of constraints (14j), (14k) are further discussed in [2], [11]. IV. S IMULATION RESULTS . In the considered scenario, the control objective is to follow the path shown in Figure 3 as close as possible on a snow covered road (µ = 0.3), while minimizing the deviation from the desired longitudinal speed (ηref (1) = x˙ ref in (13)). The control inputs are the front tire steering angle and the slip ratios at the four wheels. Two tunings will be considered. In the first tuning the longitudinal speed x˙ in not weighted and the objective is to show that the car slows down and it follows perfectly the desired path. In the second tuning a weight on the longitudinal speed is used and the objective is to show that the controller (14)-(15) performs better than a controller without brake intervention, i.e. steering only
controller. The following parameters have been used for both tunings: • sample time: T = 0.05 sec; • constraints on inputs and input rates: δf,min =10 deg, δf,max =10 deg, ∆δf,min =-0.85 deg, ∆δf,max =0.85 deg. The upper and lower bounds on the four slip ratios are 0% and −2.7% respectively (i.e. the vehicle can brake only), the upper and lower bounds on the braking rate are 10% and −10% respectively. • constraints on the tire slip angles: αfmin = −3 deg, αfmax = 3 deg, αrmin = −3 deg, αrmax = 3 deg. Figures 4-6 report the simulation results of the controller (14)-(15) with x˙ ref = 21m/s and the first tuning, consisting in the following parameters: −12 • weights on tracking errors: Qx˙ = 10 , Qψ = 102 , 2 2 Qψ˙ = 10 , QY = 10 , Qij = 0 for i 6= j; 2 −5 • weights on input rates: Rδf = 5 · 10 , Rsf,l = 10 , −5 −5 −5 Rsf,r = 10 , Rsr,l = 10 , Rsr,r = 10 , Rij = 0 for i 6= j; −12 • weights on input: Si,j = 10 , for i = j, Si,j = 0, for i 6= j; • horizons: Hp = 50, Hc = 50. We remark that the considered tuning does not penalize the deviation from the desired longitudinal speed as well as the braking intervention. On the other hand, high weights are used for the yaw, yaw rate and lateral position tracking errors. Moreover the length of the prediction horizon has been selected in order to allow the controller to significantly decrease the longitudinal speed before the first lane change. For lack of space we do not report the longitudinal speed during the manoeuvre. The longitudinal speed at the end of the double lane change is 3.5 m/s. As shown in Figure 4 the yaw, yaw rate and lateral position references are tracked perfectly, since the vehicle slows down drastically during the double lane change. It is interesting to observe that, before the first lane change, at both the front and rear axles, the braking interventions at the left and the right wheels are identical. This slows the car down as quick as possible without generating an undesired yaw moment in the first straight part of the manoeuvre. We also observe that from 3 s to 5 s the braking intervention at the rear wheels does not generate any yaw moment, the braking at the front right wheel is almost zero, while the braking at the front left wheel is at its maximum value. The resulting yaw moment is positive (counterclockwise). This behavior is coherent with the steering action aiming at generating a positive yaw moment. Between 5 and 8 s the braking at the rear wheels does not generate yaw moment, although the slip at both the left and right wheels is at the maximum value and the longitudinal speed decreases. Within the same time interval the slip at the front left wheel is zero, while the braking at the right wheel is generating a negative (clockwise) yaw moment. We conclude that the controller decreases the longitudinal speed by braking at the rear axes and it generates a yaw moment by braking the front wheels.
0 −0.5
4
6
8
10
12
14
16
sf,r [%]
2
sf,l [%]
−10 0
−1 −1.5
−1 −1.5
−2
−2
−2.5
−2.5
5 0 −5 Actual Reference
−10 0
2
4
6
8
10
12
Y [m]
3
14
0
1 0 −1 0
2
4
6
8
10
12
14
10
15
0
0
−0.5
−0.5
Actual Reference
2
5
0
5
0
5
10
15
10
15
16
16
Time [s]
sr,r [%]
dΨ/dt [deg/s]
0 −0.5
Actual Reference
0
sr,l [%]
Ψ [deg]
10
−1 −1.5
−1 −1.5
−2
Fig. 4. Combined braking and steering MPC controller with small weight on the longitudinal velocity error. Yaw angle ψ (upper plot), yaw rate ψ˙ (middle plot), lateral position Y (lower plot)
−2
−2.5
−2.5 0
5
10
15
Time [s]
Time [s]
Fig. 6. Combined braking and steering MPC controller with small weight on the longitudinal velocity error. Slip ratios at the four wheels.
3
2
10
Actual Reference
Ψ [deg]
0
0
−10
−1
dΨ/dt [deg/s]
δf [deg]
1
−2
−3
0
1
2
3
4
5
6
7
8
0
1
2
3
4
5
6
7
8
9
10
20 10 0 −10 Actual Reference
−20
9
10
−4
2
4
6
8
10
12
14
16
Y [m]
0
Time [s]
Fig. 5. Combined braking and steering MPC controller with small weight on the longitudinal velocity error. Steering angle
Actual Reference
2 0 −2 0
1
2
3
4
5
6
7
8
9
10
Time [s]
Fig. 7. Controller A. Yaw angle ψ (upper plot), yaw rate ψ˙ (middle plot), lateral position Y (lower plot)
The second tuning will be considered next and compared to an MPC controller using steering only (Controller B). The MPC (14)-(15) is tuned in order to achieve a low deviation from the desired longitudinal speed in following the desired path (Controller A). In Figures 7-9 the simulation results of the Controller A are presented. The following tuning parameters have been used: −4 • weights on tracking errors: Qx˙ = 5 · 10 , Qψ = 100, Qψ˙ = 1, QY = 10, Qij = 0 for i 6= j; 3 • weights on input rates: Rδf = 5 · 10 , Rsf,l = 1 · −3 −3 10 , Rsf,r = 1 · 10 , Rsr,l = 1 · 10−3 , Rsr,r = 1 · 10−3 , Rij = 0 for i 6= j; −7 • weights on input: Sδf = 1 · 10 , Rsf,l = 1 · 10−5 , −5 −5 Rsf,r = 1 · 10 , Rsr,l = 1 · 10 , Rsr,r = 1 · 10−5 , Rij = 0 for i 6= j; • horizons: Hp = 25, Hc = 10. The longitudinal speed at the end of the manoeuvre is 16 m/s. In Figures 10-11 the simulation results of the Controller B at a longitudinal entry speed of 21 m/s are shown. The controller has been derived from the MPC formulation ˙ Y ]0 , u(k) = presented in Section III by setting η = [ψ, ψ, δf (k) and ∆u(k) = ∆δf (k), S = 0 in (13). The following tuning parameters have been used:
• • •
weights on tracking errors: Qψ = 3·102 , Qψ˙ = 102 , QY = 10, Qij = 0 for i 6= j; weights on input rates: Rδf = 5 · 103 ; horizons: Hp = 25, Hc = 10.
The longitudinal speed at the end of the manoeuvre is 20.6 m/s. By comparing the results in Figures 10 and 7 and the Root Mean Squared tracking errors reported in Table I, we observe that Controller A performs better than Controller B. In particular the RMS tracking error on the lateral position (¯ eY in Table I) for Controller A is less than 50% of the same error for Controller B. We remark that the final longitudinal speed for the Controller A is lower that the Controller B. Controller A Controller B
e¯Ψ 5.33 · 10−2 7.77 · 10−2
e¯Ψ˙ 2.73 · 10−1 3.24 · 10−1
TABLE I RMS TRACKING ERROR FOR C ONTROLLERS A
e¯Y 11.49 26
AND
B
3
Ψ [deg]
10
2
0
−10
Actual Reference 0
dΨ/dt [deg/s]
δf [deg]
1
0
1
2
3
4
5
6
7
8
9
10
Actual Reference
20 0 −20 0
1
2
3
4
5
6
7
8
9
10
Y [m]
−1
−2
Actual Reference
2 0 −2
0
1
2
3
4
5
6
7
8
9
0
10
1
2
3
4
0
0
−0.5
−0.5
−1
6
7
8
9
10
Fig. 10. Controller B. Yaw angle ψ (upper plot), yaw rate ψ˙ (middle plot), lateral position Y (lower plot)
Controller A. Steering angle
sf,r [%]
sf,l [%]
Fig. 8.
5
Time [s]
Time [s]
2
−1
1
−1.5 0
2
4
6
8
10
0
2
4
6
8
10
δf [deg]
−1.5 0
0
−0.5
−0.5
sr,r [%]
sr,l [%]
−1
0
−1
−2
−1 −3
−1.5
0
−1.5
1
2
3
4
5
6
7
8
9
10
−2
Fig. 11.
−2 0
2
4
6
8
10
0
Time [s]
Fig. 9.
2
4
6
8
Controller B. Steering angle.
10
Time [s]
Controller A. Slip ratios at the four wheels.
V. C ONCLUSIONS . We presented a Model Predictive Control for combined braking and steering in autonomous vehicles. The performance of the presented approach has been evaluated in simulations with a double lane change manoeuvre on a snow covered road at high speed. Performance enhancement is observed when combined braking and steering are used instead of steering only. Moreover the capability of the controller of slowing down the vehicle in order to perfectly follow the desired path has been shown. This will enable the use of hard constraints for obstacle avoidance strategies. R EFERENCES [1] F. Borrelli, P. Falcone, T. Keviczky, J. Asgari, and D. Hrovat, “MPC-based approach to active steering for autonomous vehicle systems,” Int. J. Vehicle Autonomous Systems, vol. 3, no. 2/3/4, pp. 265–291, 2005. [2] P. Falcone, F. Borrelli, J. Asgari, H. E. Tseng, and D. Hrovat, “Predictive active steering control for autonomous vehicle systems,” Accepted for publication in IEEE Trans. on Control System Technology, 2006. [3] Y. Fujiwara, Y. Shoda, and S. Adachi, “Development of obstacle avoidance system using co-operative control,” in 16th IFAC World Congress, Prague, Czech Republic, 2005. [4] C. Garcia, D. Prett, and M. Morari, “Model predictive control: Theory and practice-a survey,” Automatica, vol. 25, pp. 335–348, 1989.
[5] D. Mayne, J. Rawlings, C. Rao, and P. Scokaert, “Constrained model predictive control: Stability and optimality,” Automatica, vol. 36, no. 6, pp. 789–814, June 2000. [6] J. Asgari and D. Hrovat, Potential benefits of Interactive Vehicle Control Systems. Ford Motor Company, Dearborn (USA). Internal Report, 2002. [7] F. Borrelli, “Discrete time constrained optimal control,” Ph.D. dissertation, Automatic Control Labotatory - ETH, Zurich, 2002. [Online]. Available: http://control.ethz.ch [8] T. Keviczky, P. Falcone, F. Borrelli, J. Asgari, and D. Hrovat, “Predictive control approach to autonomous vehicle steering,” in Proc. American Contr. Conf., Minneapolis, Minnesota, 2006. [9] E. Bakker, L. Nyborg, and H. B. Pacejka, “Tyre modeling for use in vehicle dynamics studies,” SAE paper # 870421, 1987. [10] P. Falcone, F. Borrelli, J. Asgari, H. E. Tseng, and D. Hrovat, “Linear time varying model predictive control and its application to active steering systems: Stability analisys and experimental validation,” Technical Report TR414, Universit´a del Sannio (available at http://www.grace.ing.unisannio.it/home/pfalcone), 2006. [11] ——, “Predictive active steering control for autonomous vehicle systems,” Universit´a del Sannio. Dipartimento di Ingegneria., Tech. Rep., Jan. 2007, http://www.grace.ing.unisannio.it/publication/416.