This paper was converted on www.awesomepapers.org from LaTeX by an anonymous user.
Want to know more? Visit the Converter page.

Numerically Stable Dynamic Bicycle Model for Discrete-time Control

Qiang Ge1, Shengbo Eben Li1, Qi Sun1 and Sifa Zheng1∗ *This work is supported by National Key R&D Program of China with 2018YFB1600600. All correspondence should be sent to S. Zheng.1Qiang Ge, Shengbo Eben Li, Qi Sun and Sifa Zheng are with the School of Vehicle and Mobility, Tsinghua University, Beijing, China. ([email protected], {lishbo, zsf}@tsinghua.edu.cn, [email protected])
Abstract

Dynamic/kinematic model is of great significance in decision and control of intelligent vehicles. However, due to the singularity of dynamic models at low speed, kinematic models have been the only choice under many driving scenarios. This paper presents a discrete dynamic bicycle model feasible at any low speed utilizing the concept of backward Euler method. We further give a sufficient condition, based on which the numerical stability is proved. Simulation verifies that (1) the proposed model is numerically stable while the forward-Euler discretized dynamic model diverges; (2) the model reduces forecast error by up to 49% compared to the kinematic model. As far as we know, it is the first time that a dynamic bicycle model is qualified for urban driving scenarios involving stop-and-go tasks.

I Introduction

Model, especially one meets these requirements: simplicity, differentiability, nonsingularity, numerical stability, is widely used in sensing, decision, and control of automated vehicles. For instance, such model describes how the state evolves without noise in an unscented Kalman filter [1], simulates kinematically-feasible trajectories of ego vehicle[2] or surrounding vehicles [3], and forecasts future states in a Model Predictive Controller (MPC) [4]. Moreover, model-based reinforcement learning, such as Approximate Dynamic Programming (ADP), also relies on a state transition model [5].

The modeling of a typical front-steered four-wheel ground vehicle has been developed at various scales. Generally, they can be divided into two categories, i.e., kinematic and dynamic model [6]. Both contain a vast set of models, varying from 1-Degree-of-Freedom (DoF) integrator [7] to 15-DoF full car [8]. This paper focuses on the longitudinal and lateral control of vehicle, which involves 3 DoFs in the xyx-y planar coordinates. Thus, the simplest model is the 3-DoF bicycle, also known as single-track model.

The two types of bicycle model are applied in different scenarios or tasks. Kinematic model works at low speed, especially stop-and-go scenarios, despite its simplification on tire sideslip characteristics. It is believed to be irreplaceable because all dynamic model encounter a singularity point when approaching zero speed. The tire slip angle estimation term has the vehicle velocity in the denominator [9]. Actually, even at 8 m/s the dynamic model can be unstable (see Fig. 3 (c), forward Euler method). Therefore, though more accurate at certain speeds, dynamic bicycle model can only be adopted when speed is relatively high or the discretization step length is short enough.

An insight into practical control/planning problems requires us to transform the continuous differential kinematic/dynamic bicycle model into a discrete version, i.e. difference equations. Initial Value Problem (IVP) of Ordinary Differential Equations (ODE) is dealt with many mature mathematical techniques, like the Euler method, Runge-Kutta methods, and linear multistep methods [10]. With forward Euler method Xk+1X_{k+1} can be expressed as an explicit linear combination of the derivative f(Xk)f(X_{k}), the current state X(k)X(k) and the step length TsT_{s}, which accommodates any form of f(Xk)f(X_{k}) well. Though less accurate than other explicit methods, it is popular for single-step recurrence. Backward Euler method, one of the implicit methods, usually has better numerical stability but poor computational efficiency, because the next step state has to be approximated by iteration. More importantly, in control-oriented applications like MPC or ADP, the model must have an explicit form of forward propagation, limiting the backward Euler method to offline simulation.

As a result, a kinematic model discretized by forward Euler method is almost the default approach for autonomous parking [11], autonomous intersection management [12] and multi-vehicle formation [13]. However, the modeling error will inevitably grow with driving speed, as tire sideslip angle is no longer negligible.

The rest of this paper is organized as follows. In Section II, both kinematic and dynamic single-track models are illustrated. Section III derives an explicit discrete dynamic bicycle model with due simplifications, which is inspired by the idea of backward Euler method. Further, we manage to give a sufficient condition of provable numerical stability in section IV. The accuracy, stability, computational efficiency as well as support to stop-and-go tasks, are verified in Section V. Section VI gives some concluding remarks.

II Bicycle Model

II-A Dynamic Model

The continuous model is given in (1). Here the longitudinal acceleration a=TwmRwa=\frac{T_{w}}{mR_{w}}, where TwT_{w} is the longitudinal drive torque from ground, mm is mass of the vehcle, RwR_{w} is the rolling radius of the drive wheel.

X˙=f(X,U)=[ucosφvsinφvcosφ+usinφωa+vω1mFY1sinδuω+1m(FY1cosδ+FY2)1Iz(lfFY1cosδlrFY2)]\dot{X}=f(X,U)=\left[\begin{array}[]{c}u\cos\varphi-v\sin\varphi\\ v\cos\varphi+u\sin\varphi\\ \omega\\ a+v\omega-\frac{1}{m}F_{Y1}\sin\delta\\ -u\omega+\frac{1}{m}\left(F_{Y1}\cos\delta+F_{Y2}\right)\\ \frac{1}{I_{z}}\left(l_{f}F_{Y1}\cos\delta-l_{r}F_{Y2}\right)\end{array}\right] (1)

where

X=[xyφuvω],U=[aδ]X=\left[\begin{array}[]{l}x\\ y\\ \varphi\\ u\\ v\\ \omega\end{array}\right],\ U=\left[\begin{array}[]{l}a\\ \delta\end{array}\right] (2)
Refer to caption
(a) a
Refer to caption
(b) b
Figure 1: Bicycle model
(a) dynamic, (b) kinematic

The lateral forces FY1F_{Y1}, FY2F_{Y2} are functions of sideslip angle αf\alpha_{f} and αr\alpha_{r}. Under mild steering angle, we can assume that

cosδ\displaystyle\cos\delta 1\displaystyle\approx 1 (3a)
sinδ\displaystyle\sin\delta 0\displaystyle\approx 0 (3b)
FY1\displaystyle F_{Y1} =kfα1kf(v+lfωuδ)\displaystyle=k_{f}\alpha_{1}\approx k_{f}\left(\frac{v+l_{f}\omega}{u}-\delta\right) (3c)
FY2\displaystyle F_{Y2} =krα2krvlrωu\displaystyle=k_{r}\alpha_{2}\approx k_{r}\frac{v-l_{r}\omega}{u} (3d)

Note that we use a linear tire sideslip force model here, which is important for the deduction of an explicit discretized form later.

II-B Kinematic Model

The widely used kinematic bicycle model [6] assumes that both front and rear wheels have only longitudinal rolling movement, but no lateral slip. This is inaccurate because tire characteristics are neglected.

X˙kine =fkine(Xkine ,U)=[ucos(φ+β(δ))usin(φ+β(δ))aulrsin(β(δ))]\dot{X}_{\text{kine }}=f_{\text{kine}}\left(X_{\text{kine }},U\right)=\left[\begin{array}[]{c}u\cos(\varphi+\beta(\delta))\\ u\sin(\varphi+\beta(\delta))\\ a\\ \frac{u}{l_{r}}\sin(\beta(\delta))\end{array}\right] (4)

where

β(δ)=arctan(tanδlrlf+lr)\beta(\delta)=\arctan\left(\tan\delta\frac{l_{r}}{l_{f}+l_{r}}\right) (5)
Xkine=[xyuφ]X_{\text{kine}}=\left[\begin{array}[]{l}x\\ y\\ u\\ \varphi\\ \end{array}\right] (6)

Note that uu is longitudinal velocity in dynamic model, and absolute velocity in kinematic model.

III Discretization

To apply the ordinary differential equations (1), (4) to controller modeling or trajectory planning, the foremost step is to solve the initial value problems (IVP) with numerical methods.

As a typical implicit method, the main defect of backward Euler method is that Xk+1X_{k+1} has to be found by solving the rootfinding problem (7), usually using fixed-point iteration.

Xk+1Tsf(Xk+1,Uk)=XkX_{k+1}-T_{s}f\left(X_{k+1},U_{k}\right)=X_{k} (7)

In order to retain the advantage of explicit methods, we derive Xk+1X_{k+1} in a variable-by-variable fashion. xk+1x_{k+1}, yk+1y_{k+1} and φk+1\varphi_{k+1} are calculated by forward Euler method. vk+1v_{k+1} and ωk+1\omega_{k+1} are solved from

vk+1Ts(ukωk+1m(FY1(uk,vk+1,ωk,δk)+FY2(uk,vk+1,ωk)))=vk\!v_{k+1}-T_{s}\!\left(-u_{k}\omega_{k}\!+\!\frac{1}{m}\left(F_{Y1}(u_{k},v_{k+1},\omega_{k},\delta_{k})\!+\!F_{Y2}(u_{k},v_{k+1},\omega_{k})\right)\right)\!=\!v_{k}
ωk+1Ts(1Iz(lfFY1(uk,vk,ωk+1,δk)lrFY2(uk,vk,ωk+1)))=ωk\omega_{k+1}-T_{s}\left(\frac{1}{I_{z}}\left(l_{f}F_{Y1}(u_{k},v_{k},\omega_{k+1},\delta_{k})-l_{r}F_{Y2}(u_{k},v_{k},\omega_{k+1})\right)\right)=\omega_{k}

Owing to the linear sideslip force assumption, the above formulas have analytical solutions. uk+1u_{k+1} is special because theoretically, it belongs to a quadratic equation. Therefore, one item, i.e. vω1mFY1sinδv\omega-\frac{1}{m}F_{Y1}\sin\delta is simplified into zero. After that, uk+1u_{k+1} is also derived by forward Euler method. Although such simplification introduces minor modeling error, in a predictive controller, the receding-horizon self-correction will help compensate for possible negative effects.

Technically our discretization is not backward Euler method, but a variant inspired by it. It is the concept of backward Euler method that makes the model stable, which is proved in the next section. The nonlinear discrete model is

Xk+1F(Xk,Uk)X_{k+1}\triangleq F(X_{k},U_{k}) (8)

which is extended as:

[xk+1yk+1φk+1uk+1vk+1ωk+1]=[xk+Ts(ukcosφkvksinφk)yk+Ts(vkcosφk+uksinφk)φk+Tsωkuk+Tsakmukvk+Ts(lfkflrkr)ωkTskfδkukTsmuk2ωkmukTs(kf+kr)Izukωk+Ts(lfkflrkr)vkTslfkfδkukIzukTs(lf2kf+lr2kr)]\left[\begin{array}[]{c}x_{k+1}\\ y_{k+1}\\ \varphi_{k+1}\\ u_{k+1}\\ v_{k+1}\\ \omega_{k+1}\end{array}\right]=\left[\begin{array}[]{c}x_{k}+T_{s}\left(u_{k}\cos\varphi_{k}-v_{k}\sin\varphi_{k}\right)\\ y_{k}+T_{s}\left(v_{k}\cos\varphi_{k}+u_{k}\sin\varphi_{k}\right)\\ \varphi_{k}+T_{s}\omega_{k}\\ u_{k}+T_{s}a_{k}\\ \frac{mu_{k}v_{k}+T_{s}\left(l_{f}k_{f}-l_{r}k_{r}\right)\omega_{k}-T_{s}k_{f}\delta_{k}u_{k}-T_{s}mu_{k}^{2}\omega_{k}}{mu_{k}-T_{s}\left(k_{f}+k_{r}\right)}\\ \frac{I_{z}u_{k}\omega_{k}+T_{s}\left(l_{f}k_{f}-l_{r}k_{r}\right)v_{k}-T_{s}l_{f}k_{f}\delta_{k}u_{k}}{I_{z}u_{k}-T_{s}\left(l_{f}^{2}k_{f}+l_{r}^{2}k_{r}\right)}\end{array}\right] (9)

IV Numerical Stability

IV-A linearization of difference equation

The nonlinear recursive difference equation (8) can be linearized around a state point. Firstly, it can be seen as a reference point of the following nonlinear function

Y=F(X,U)Y=F(X,U) (10)

it can be derived that

YXk+1=FX|X=XkU=Uk(XXk)+FU|X=XkU=Uk(UUk)Y-X_{k+1}=\left.\frac{\partial F}{\partial X}\right|_{X=X_{k}\atop U=U_{k}}\left(X-X_{k}\right)+\left.\frac{\partial F}{\partial U}\right|_{X=X_{k}\atop U=U_{k}}\left(U-U_{k}\right) (11)

denote XXkX-X_{k} as εk\vec{\varepsilon_{k}}, and YXk+1Y-X_{k+1} as εk+1\vec{\varepsilon}_{k+1},

εk+1=JF,X(Xk,Uk)εkAkεk\vec{\varepsilon}_{k+1}=J_{F,X}\left(X_{k},U_{k}\right)\vec{\varepsilon}_{k}\triangleq A_{k}\vec{\varepsilon}_{k} (12)

Note that from (11) to (12), the difference item of input UU was ignored. This is because the input UU is defined rather than estimated by us. In another word, we do not consider any error originating from UUkU-U_{k}.

Additionally, note that the first three state variables, i.e. xkx_{k}, yky_{k} and φk\varphi_{k} are merely combination and integral of the other variables uku_{k}, vkv_{k} and ωk\omega_{k}. Thus, we can alternatively consider a dynamic system (still termed F(Xk,Uk)F(X_{k},U_{k}) for simplicity) with XkX_{k} containing only uku_{k},vkv_{k} and ωk\omega_{k}, which distinguishes (9) from other systems.

According to the definition of Jacobian matrix, under the reduced system,

Ak\displaystyle A_{k} =[FukFvkFωk]\displaystyle=\left[\begin{array}[]{ccc}\frac{\partial F}{\partial u_{k}}&\frac{\partial F}{\partial v_{k}}&\frac{\partial F}{\partial\omega_{k}}\end{array}\right]
=[100b1,kmukmukTs(kf+kr)Ts(lfkflrkr)Tsmuk2mukTs(kf+kr)b2,kTs(lfkflrkr)IzukTs(lf2kf+lr2kr)IzukIzukTs(lf2kf+lr2kr)]\displaystyle=\left[\begin{array}[]{ccc}1&0&0\\ b_{1,k}&\frac{mu_{k}}{mu_{k}-T_{s}\left(k_{f}+k_{r}\right)}&\frac{T_{s}\left(l_{f}k_{f}-l_{r}k_{r}\right)-T_{s}mu_{k}^{2}}{mu_{k}-T_{s}\left(k_{f}+k_{r}\right)}\\ b_{2,k}&\frac{T_{s}\left(l_{f}k_{f}-l_{r}k_{r}\right)}{I_{z}u_{k}-T_{s}\left(l_{f}^{2}k_{f}+l_{r}^{2}k_{r}\right)}&\frac{I_{z}u_{k}}{I_{z}u_{k}-T_{s}\left(l_{f}^{2}k_{f}+l_{r}^{2}k_{r}\right)}\end{array}\right]
[10bkA^k]\displaystyle\triangleq\left[\begin{array}[]{cc}1&\vec{0}\\ \vec{b}_{k}&\hat{A}_{k}\end{array}\right] (13)
b1,k=(mvkTskfδk2Tsmukωk)[mukTs(kf+kr)]m[mukvk+Ts(lfkflrkr)ωkTskfδkukTsmuk2ωk][mukTs(kf+kr)]2b_{1,k}=\frac{\left(mv_{k}-T_{s}k_{f}\delta_{k}-2T_{s}mu_{k}\omega_{k}\right)\left[mu_{k}-T_{s}\left(k_{f}+k_{r}\right)\right]-m\left[mu_{k}v_{k}+T_{s}\left(l_{f}k_{f}-l_{r}k_{r}\right)\omega_{k}-T_{s}k_{f}\delta_{k}u_{k}-T_{s}mu_{k}^{2}\omega_{k}\right]}{\left[mu_{k}-T_{s}\left(k_{f}+k_{r}\right)\right]^{2}} (14)
b2,k=(IzωkTslfkfδk)[IzukTs(lf2kf+lr2kr)]Iz[Izukωk+Ts(lfkflrkr)vkTslfkfδkuk][IzukTs(lf2kf+lr2kr)]2b_{2,k}=\frac{\left(I_{z}\omega_{k}-T_{s}l_{f}k_{f}\delta_{k}\right)\left[I_{z}u_{k}-T_{s}\left(l_{f}^{2}k_{f}+l_{r}^{2}k_{r}\right)\right]-I_{z}\left[I_{z}u_{k}\omega_{k}+T_{s}\left(l_{f}k_{f}-l_{r}k_{r}\right)v_{k}-T_{s}l_{f}k_{f}\delta_{k}u_{k}\right]}{\left[I_{z}u_{k}-T_{s}\left(l_{f}^{2}k_{f}+l_{r}^{2}k_{r}\right)\right]^{2}} (15)

IV-B analysis of numerical stability

Our definition of numerical stability is given hereby,

Definition 1

The system described by (9) is called numerically stable if such boundedness characteristic is satisfied:

ε03×1,C,s.t.limkAkA1A0ε0C\forall\vec{\varepsilon}_{0}\in\mathcal{R}^{3\times 1},\exists C\in\mathcal{R},s.t.\left\|\lim_{k\rightarrow\infty}A_{k}\cdots A_{1}A_{0}\vec{\varepsilon}_{0}\right\|\leq C

As a matter of fact, if (12) can be seen as a switched discrete linear system, the concept of Joint Spectral Radius could be of help in the stability proof [14]. However, since the matrix AkA_{k} in this case cannot be included by a finite set, we have to seek other methods.

Definition 1 requires that, each entry of the long product AkA1A0A_{k}\cdots A_{1}A_{0} does not grow infinity with increasing kk. This requirement, however, is difficult to be satisfied as the coefficient matrix AkA_{k} is varying with each step kk. More specifically, we believe that the rigorous stability only holds under certain conditions. Therefore, in what follows we manage to give a sufficient condition that will lead to this good feature.

As we have

AkA1A0\displaystyle A_{k}\cdots A_{1}A_{0} =[10bkA^k][10b0A^0]\displaystyle=\left[\begin{array}[]{cc}1&\vec{0}\\ \vec{b}_{k}&\hat{A}_{k}\end{array}\right]\cdots\left[\begin{array}[]{cc}1&\vec{0}\\ \vec{b}_{0}&\hat{A}_{0}\end{array}\right] (16)
[10bk,0A^k,0]\displaystyle\triangleq\left[\begin{array}[]{cc}1&\vec{0}\\ \vec{b}_{k,0}&\hat{A}_{k,0}\end{array}\right]

Thus, the numerical stability will be guaranteed as long as A^k,0\hat{A}_{k,0} and bk,0\vec{b}_{k,0} are both bounded.

IV-B1 boundedness of A^k,0\hat{A}_{k,0}

The sufficient condition is given as follows.

Condition 1

A^k1,k=1,2,\left\|\hat{A}_{k}\right\|\leq 1,k=1,2,\cdots

If Condition 1 is satisfied, the long product A^k,0\hat{A}_{k,0} will decay exponentially. Moreover, we notice that A^k\hat{A}_{k} involves uku_{k} and step length TsT_{s}, which means that the norm of A^k\hat{A}_{k} will not be an arbitrary value but restricted in a certain range. This physical meaning could be crucial for the establishment of Condition 1.

Proposition 1

A^k,0\hat{A}_{k,0} is always bounded when kk approaches infinity, given that Condition 1 is satisfied.

Proof

A^k,0\displaystyle\left\|\hat{A}_{k,0}\right\| =A^kA^1A^0\displaystyle=\left\|\hat{A}_{k}\cdots\hat{A}_{1}\hat{A}_{0}\right\| (17)
A^kA^1A^0\displaystyle\leq\left\|\hat{A}_{k}\right\|\left\|\hat{A}_{1}\right\|\cdots\left\|\hat{A}_{0}\right\|
1\displaystyle\leq 1

\blacksquare

Remark 1

Given that Condition 1 is established, with the submultiplicative property of induced norm, we prove that A^k,0\left\|\hat{A}_{k,0}\right\| is always bounded by 1 as kk increases. Moreover, as long as A^k1\left\|\hat{A}_{k}\right\|\not\equiv 1, each entry of the submatrix A^k,0\hat{A}_{k,0} in (16) will converge to zero exponentially, which is even more favorable for stability.

IV-B2 boundedness of bk,0\vec{b}_{k,0}

Proposition 2

bk,0\left\|\vec{b}_{k,0}\right\| is always bounded when kk approaches infinity, given that Condition 1 is satisfied.

Proof

bk,0\displaystyle\vec{b}_{k,0} =bk+A^kbk1,0\displaystyle=\vec{b}_{k}+\hat{A}_{k}\vec{b}_{k-1,0} (18)
=bk+A^kbk1+A^kA^k1bk2,0\displaystyle=\vec{b}_{k}+\hat{A}_{k}\vec{b}_{k-1}+\hat{A}_{k}\hat{A}_{k-1}\vec{b}_{k-2,0}
=\displaystyle=\cdots
=bk+A^kbk1++A^kA^k1A^1b0\displaystyle=\vec{b}_{k}+\hat{A}_{k}\vec{b}_{k-1}+\cdots+\hat{A}_{k}\hat{A}_{k-1}\cdots\hat{A}_{1}\vec{b}_{0}
bk,0\displaystyle\left\|\vec{b}_{k,0}\right\| =bk+A^kbk1++A^kA^k1A^1b0\displaystyle=\left\|\vec{b}_{k}+\hat{A}_{k}\vec{b}_{k-1}+\cdots+\hat{A}_{k}\hat{A}_{k-1}\cdots\hat{A}_{1}\vec{b}_{0}\right\| (19)
bk+A^kbk1++A^kA^k1A^1b0\displaystyle\leq\left\|\vec{b}_{k}\right\|+\left\|\hat{A}_{k}\vec{b}_{k-1}\right\|+\cdots+\left\|\hat{A}_{k}\hat{A}_{k-1}\cdots\hat{A}_{1}\vec{b}_{0}\right\|
bk+A^kbk1++A^kA^1b0\displaystyle\leq\left\|\vec{b}_{k}\right\|+\left\|\hat{A}_{k}\right\|\left\|\vec{b}_{k-1}\right\|+\cdots+\left\|\hat{A}_{k}\right\|\cdots\left\|\hat{A}_{1}\right\|\left\|\vec{b}_{0}\right\|
b+A^b++A^kb\displaystyle\leq\left\|\vec{b}_{*}\right\|+\left\|\hat{A}_{*}\right\|\left\|\vec{b}_{*}\right\|+\cdots+\left\|\hat{A}_{*}\right\|^{k}\left\|\vec{b}_{*}\right\|
=b1A^k+11A^\displaystyle=\left\|\vec{b}_{*}\right\|\frac{1-\left\|\hat{A}_{*}\right\|^{k+1}}{1-\left\|\hat{A}_{*}\right\|}

where

b=maxuk,vk,ωk,δk,TsbkA^=maxuk,TsA^k\begin{array}[]{l}\left\|\vec{b}_{*}\right\|=\max\limits_{u_{k},v_{k},\omega_{k},\delta_{k},T_{s}}\left\|\vec{b}_{k}\right\|\\ \left\|\hat{A}_{*}\right\|=\max\limits_{u_{k},T_{s}}\left\|\hat{A}_{k}\right\|\end{array} (20)

\blacksquare

Since the state variables uku_{k}, vkv_{k}, ωk\omega_{k} are all bounded by their physical meanings, as continuous functions defined over them, bk\left\|\vec{b}_{k}\right\| and A^k\left\|\hat{A}_{k}\right\| must have maximum values accordingly (20). According to our proof, given that Condition 1 is established, bk,0\left\|\vec{b}_{k,0}\right\| is always bounded by b1A^\frac{\left\|\vec{b}_{*}\right\|}{1-\left\|\hat{A}_{*}\right\|} as kk increases.

Remark 2

The proof is based on linearization of the initial nonlinear difference model. Nevertheless, according to Lagrange’s mean value theorem, the recursive formula (12) can be changed into

εk+1=AmidεkAmid=JF,X(Xk+(1τ)Xk+1,Uk),τ[0,1]\begin{array}[]{c}\vec{\varepsilon}_{k+1}=A_{\operatorname{mid}}\vec{\varepsilon}_{k}\\ A_{\operatorname{mid}}=J_{F,X}\left(X_{k}+(1-\tau)X_{k+1},U_{k}\right),\tau\in[0,1]\end{array} (21)

And obviously, this will not change the subsequent analysis and conclusion.

Remark 3

Here we give a sufficient instead of sufficient & necessary condition, which means that the violation of Condition 1 does not necessarily bring numerical instability. The main contribution of this condition, is the easy-to-satisfy property (see Fig. 2) under general settings and common speed, which imposes great practical meaning to the application of dynamic bicycle model (9).

V Simulation

As pointed out by Francesco Borrelli et al. [9], a kinematic model has these main advantages: low-speed feasibility and computational efficiency (2015). At the same time, they also observe significant growth of error on the higher speed sinusoidal and winding track tests. Arnaud de La Fortelle et al. [2] then find that ay0.5μga_{y}\leq 0.5\mu g is decisive, otherwise error of the kinematic bicycle model will become very large (2017).

Therefore, it is necessary to verify the low-speed feasibility of the proposed model, and compare the differences between both models. In what follows, we choose a vehicle (C-Class, Hatchback 2017) in CarSim as the prototype. Important parameters are listed in Table I. Open-loop simulation is about step steer response, whereas the closed-loop simulation involves a nonlinear MPC controller undertaking a stop-and-go task.

TABLE I: Simulation Parameters
Parameter Description Value
IzI_{z} yaw inertia of vehicle body 1536.7 kg\cdotm2
kfk_{f} front axle equivalent sideslip stiffness -128916 N/rad
krk_{r} rear axle equivalent sideslip stiffness -85944 N/rad
lfl_{f} distance between C.G. and front axle 1.06 m
lrl_{r} distance between C.G. and rear axle 1.85 m
mm mass of the vehicle 1412 kg
NpN_{p} predictive horizon 20
NcN_{c} control horizon 1
TsT_{s} discretization step length 0.1 s

V-A Open-loop Control

V-A1 backward versus forward

The numerical stability, as well as the insensitivity regarding step length and driving speed, is rather important for autonomous driving application. Before comparison, we first verify if the numerical stability Condition 1 is satisfied. Let 0 m/s uk\leq\ u_{k}\ \leq 15 m/s, the 2-norm of A^k\hat{A}_{k} is shown in Fig. 2. Since A^k21\left\|\hat{A}_{k}\right\|_{2}\ \leq 1, the numerical stability of our model is essentially guaranteed.

Refer to caption

Figure 2: Range of A^k2\left\|\hat{A}_{k}\right\|_{2} defined over varying uku_{k}
Refer to caption
(a) a
Refer to caption
(b) b
Refer to caption
(c) c
Figure 3: Lateral state with varying discretization step length under step steering input. Conditions: u0u_{0} = 8 m/s, δ\delta = 0.2674 rad
(a) TsT_{s} = 0.01 s, (b) TsT_{s} = 0.05 s, (c) TsT_{s} = 0.1 s

The model (1) with assumptions (3c and 3d) is built in MATLAB/Simulink with 4-order Runge-Kutta solver with a step length of 0.001s. The proposed model shows expected stability over time, and consistency over varying discretization step length TsT_{s} (Fig. 3). In contrast, the forward Euler method cannot hold this feature as TsT_{s} increases.

V-A2 dynamic versus kinematic

The open-loop step response of dynamic model (discretized by backward Euler method) and kinematic model (discretized by forward Euler method) are calculated, at different velocities. Simultaneously, the same input is imposed on a prototype model in CarSim to approximate the groundtruth.

TABLE II: Location RMS Error of 4-second Open-Loop Trajectory under Step Steer Input
Prototype: CarSim C-Class, Hatchback 2017
u0u_{0} (m/s) backward dynamic (m) forward kinematic (m) Accuracy Improvement
1 0.31 0.28 -11%11\%
2 0.42 0.38 -11%11\%
3 0.37 0.36 -3%3\%
4 0.60 0.73 +18%18\%
5 0.72 1.12 +36%36\%
6 0.93 1.72 +46%46\%
7 1.29 2.55 +49%49\%
8 1.83 3.62 +49%49\%
9 2.62 4.98 +47%47\%
10 3.89 6.85 +43%43\%

The open-loop trajectories of both models and their error relative to the prototype in CarSim are shown in Fig. 4.

Refer to caption
(a) a
Refer to caption
(b) b
Figure 4: Open-loop trajectory and error under step steer input. Conditions: u0u_{0} = 8 m/s, δ\delta = 0.2674 rad
(a) trajectory, (b) location error

Although kinematic model outperforms the backward-discretized dynamic model at lower speeds, this situation is inversed since u0=4u_{0}=4 m/s under defined parameters. To be emphasized, the absolute error at higher speed is much bigger than that of lower speeds. More importantly, the prediction accuracy is crucial at higher speeds where occupants’ lives are at stake.

V-B Closed-loop Control

In this section, we design a nonlinear model predictive controller with (9) to comprehensively verify its effect in practical application. Starting from (0,0), the vehicle model is always tracking a direct path connecting its center of gravity (C.G.) and the target (30,30). The reference speed is set to be 6 m/s. There is an obstacle (light blue round area in Fig. 5) located at (15,15) blocking its way. The parameters are deliberately co-designed so that the vehicle can not bypass with steering, but only stop to avoid collision. Note that collision is defined by overlapping of the obstacle and C.G. of the vehicle, instead of vehicle body profile. Once the vehicle stops, the obstacle is moved to (18,12) (dark blue round area in Fig. 5), giving way to the vehicle. Then the vehicle starts to execute a stop-and-go task. To be emphasized, the moved obstacle still requires it to steer and accelerate simultaneously, which is similar to a left-turning maneuver after red light at intersections.

Refer to caption

Figure 5: Trajectory of the vehicle, avoiding a moving obstacle

The longitudinal velocity is shown in Fig. 6, whereas the longitudinal input aa and lateral input δ\delta are recorded in Fig. 7(a) and (b) respectively.

Refer to caption

Figure 6: Longitudinal velocity of the vehicle
Refer to caption
(a) a
Refer to caption
(b) b
Figure 7: MPC control input
(a) longitudianl input, (b) lateral input

The constrained nonlinear optimal control problem is formulated as (22), satisfying (23).

mink=0N(X(k)XR(k))TQ(X(k)XR(k))+U(k)TRU(k)\min\sum_{k=0}^{N}\left(X(k)-X_{R}(k)\right)^{T}Q\left(X(k)-X_{R}(k)\right)+U(k)^{T}RU(k) (22)
X(k+1)\displaystyle X(k+1) =F(X(k),U(k))\displaystyle=F(X(k),U(k)) (23a)
(X(k)Xobs(k))T\displaystyle\left(X(k)-X_{obs}(k)\right)^{T} Qs(X(k)Xobs(k))Ds2\displaystyle Q_{s}\left(X(k)-X_{obs}(k)\right)\geq D_{s}^{2} (23b)
Xmin\displaystyle X_{\min}\leq X(k)Xmax\displaystyle X(k)\leq X_{\max} (23c)
Umin\displaystyle U_{\min}\leq U(k)Umax\displaystyle U(k)\leq U_{\max} (23d)

XR(k)X_{R}(k) is the kkth reference trajectory point in the predictive horizon, Xobs(k)X_{obs}(k) conveys location of the obstacle at kkth step in the predictive horizon. QQ = diag(100,100,0,0,0,0), RR = diag(10,500), QsQ_{s} = diag(1,1,0,0,0,0), DsD_{s} = 8. XminX_{min} = [-inf\inf,-inf\inf,-inf\inf,0,-4,-3], XmaxX_{max} = [+inf\inf,+inf\inf,+inf\inf,20,4,3]. UminU_{min} = [-5,-π\pi/4], UmaxU_{max} = [2,π\pi/4]. All quantities are in the international system of units.

Our model is computationally efficient as well. The average computation time of one-step MPC solution is 61.6 ms, whereas the same simulation carried out with kinematic model (4) has an average of 59.6 ms. The problem is solved by the nonlinear OCP solver ipopt [15] under the framework CasADi [16], on a laptop with an intel i7 CPU and 12 GB ram.

VI Conclusion

In this paper, we propose a discretized dynamic bicycle model inspired by backward Euler method and a sufficient condition that guarantees its numerical stability. The condition turns out easy to achieve under general vehicle parameters and common urban driving speed (e.g. 15m/s\leq 15m/s). Our method outperforms forward Euler method in stability and shows an advantage in accuracy up to 49% compared to the kinematic model. A comprehensive stop-and-go task further verifies its effectiveness. It could be applied to vast fields, like MPC, ADP, etc., under general urban scenarios.

ACKNOWLEDGMENT

The authors are grateful to Hao Chen and Xuewu Lin for their valuable advice in matrix product derivation.

References

  • [1] S. Antonov, A. Fehn, and A. Kugi, “Unscented kalman filter for vehicle state estimation,” Vehicle System Dynamics, vol. 49, no. 9, pp. 1497–1520, 2011.
  • [2] P. Polack, F. Altché, B. d’Andréa Novel, and A. de La Fortelle, “The kinematic bicycle model: A consistent model for planning feasible trajectories for autonomous vehicles?” in 2017 IEEE Intelligent Vehicles Symposium (IV).   IEEE, 2017, pp. 812–818.
  • [3] H. Cui, T. Nguyen, F.-C. Chou, T.-H. Lin, J. Schneider, D. Bradley, and N. Djuric, “Deep kinematic models for physically realistic prediction of vehicle trajectories,” arXiv preprint arXiv:1908.00219, 2019.
  • [4] P. Falcone, F. Borrelli, J. Asgari, H. E. Tseng, and D. Hrovat, “Predictive active steering control for autonomous vehicle systems,” IEEE Transactions on control systems technology, vol. 15, no. 3, pp. 566–580, 2007.
  • [5] Z. Lin, J. Duan, S. E. Li, H. Ma, and Y. Yin, “Continuous-time finite-horizon adp for automated vehicle controller design with high efficiency,” arXiv preprint arXiv:2007.02070, 2020.
  • [6] R. Rajamani, Vehicle dynamics and control.   Springer Science & Business Media, 2011.
  • [7] Y. Zheng, S. E. Li, J. Wang, D. Cao, and K. Li, “Stability and scalability of homogeneous vehicular platoon: Study on the influence of information flow topologies,” IEEE Transactions on intelligent transportation systems, vol. 17, no. 1, pp. 14–26, 2015.
  • [8] M. Perrelli, F. Farroni, F. Timpone, and D. Mundo, “Analysis of tire temperature influence on vehicle dynamic behaviour using a 15 dof lumped-parameter full-car model,” in International Conference on Robotics in Alpe-Adria Danube Region.   Springer, 2020, pp. 266–274.
  • [9] J. Kong, M. Pfeiffer, G. Schildbach, and F. Borrelli, “Kinematic and dynamic vehicle models for autonomous driving control design,” in 2015 IEEE Intelligent Vehicles Symposium (IV).   IEEE, 2015, pp. 1094–1099.
  • [10] J. C. Butcher and N. Goodwin, Numerical methods for ordinary differential equations.   Wiley Online Library, 2008, vol. 2.
  • [11] D. Xu, Y. Shi, and Z. Ji, “Model-free adaptive discrete-time integral sliding-mode-constrained-control for autonomous 4wmv parking systems,” IEEE Transactions on Industrial Electronics, vol. 65, no. 1, pp. 834–843, 2017.
  • [12] B. Li, Y. Zhang, Y. Zhang, N. Jia, and Y. Ge, “Near-optimal online motion planning of connected and automated vehicles at a signal-free and lane-free intersection,” in 2018 IEEE Intelligent Vehicles Symposium (IV).   IEEE, 2018, pp. 1432–1437.
  • [13] M. Cai, Q. Xu, K. Li, and J. Wang, “Multi-lane formation assignment and control for connected vehicles,” in 2019 IEEE Intelligent Vehicles Symposium (IV).   IEEE, 2019, pp. 1968–1973.
  • [14] R. Jungers, The joint spectral radius: theory and applications.   Springer Science & Business Media, 2009, vol. 385.
  • [15] A. Wächter and L. T. Biegler, “On the implementation of an interior-point filter line-search algorithm for large-scale nonlinear programming,” Mathematical programming, vol. 106, no. 1, pp. 25–57, 2006.
  • [16] J. A. Andersson, J. Gillis, G. Horn, J. B. Rawlings, and M. Diehl, “Casadi: a software framework for nonlinear optimization and optimal control,” Mathematical Programming Computation, vol. 11, no. 1, pp. 1–36, 2019.