Next Article in Journal
Strain Transfer Mechanism in Surface-Bonded Distributed Fiber Optic Sensors under Different Strain Fields
Previous Article in Journal
LED-Based Desktop Analyzer for Fat Content Determination in Milk
 
 
Font Type:
Arial Georgia Verdana
Font Size:
Aa Aa Aa
Line Spacing:
Column Width:
Background:
Article

Model Predictive Controller Approach for Automated Vehicle’s Path Tracking

Department of Automotive Technologies, Budapest University of Technology and Economics, 1111 Budapest, Hungary
*
Author to whom correspondence should be addressed.
Sensors 2023, 23(15), 6862; https://doi.org/10.3390/s23156862
Submission received: 24 May 2023 / Revised: 26 July 2023 / Accepted: 27 July 2023 / Published: 1 August 2023
(This article belongs to the Section Vehicular Sensing)

Abstract

:
In this paper, a model predictive control (MPC) approach for controlling automated vehicle steering during path tracking is presented. A (linear parameter-varying) LPV vehicle plant model including steering dynamics is proposed to determine the system evolution matrices. The steering dynamics are modeled in two different ways by using first-order lag and a second-order lag; the application of the first-order system resulted in a slightly more accurate path-following. Additionally, a cascade MPC structure is applied in which two MPCs are used; the second-order steering dynamics are separated from the path-following controller in a second MPC. Both steering system models and the cascade MPC are evaluated in simulation and on a test vehicle. The reference trajectory is calculated based on a fixed predefined path by transforming the necessary path segment to the vehicle ego coordinate system, thereby describing the reference for the path-following task in a novel way. The MPC method computes the optimal steering angle vector at each time step for following the path. The longitudinal dynamics is controlled separately by a PI controller. After simulation evaluation, experimental tests were conducted on a test vehicle on an asphalt surface. Both simulation and experimental results prove the effectiveness of the proposed reference definition method. The effect of the applied steering system models is evaluated. The inclusion of the steering dynamics in the prediction model resulted in a significant increase in controller performance. Finally, the computational requirements of the proposed control and modeling methods are also discussed.

1. Introduction

In recent years, collision avoidance systems, advanced driver-assistance systems, and automated vehicle functions have become the most discussed topics in the field of automotive research. The advantages of automated vehicles and their underlying technology include the potential to improve road safety, reduce or eliminate the effect of human errors, reduce pollutant emissions, the number of accidents, and travel times. Automated vehicles are suitable for avoiding collisions by using the steering and braking system conventionally; furthermore, a higher level of vehicle motion control is available for solving an emergency by forcing the vehicle into an unstable state, for example, drifting and controlling the vehicle reliably in this unstable state [1,2].
In the structure of an automated vehicle, the path-following and path-planning modules—which are closely related to each other—are essential to realizing the tasks listed above. In this paper, a model predictive controller (MPC)-based path-following controller structure is proposed to realize path-following scenarios near the handling limit.
The previous research of the authors includes the aim to increase the speed during path-following tasks. There are numerous path-following control solutions as summarized in [3,4,5,6,7,8]. During the research and experimental testing, the authors have concluded that the two most important features required for increasing the speed of the vehicle during path-following are the knowledge of the path ahead of the vehicle and the inclusion of vehicle dynamics into the control law. These attributes are essential to achieve accurate path tracking at higher speeds. The MPC controller makes the realization of both required features possible. Moreover, the MPC can handle constraints; thus, the authors chose MPC for path-following tasks. Furthermore, a third feature—the consideration of the steering dynamics—was identified as an additional requirement for path tracking which, if possible, is needed to be considered in the control law. The MPC makes the incorporation of this additional feature possible as well by choosing the right vehicle model for state-prediction purposes. The adaptive H controller in [6], the nonlinear sliding mode controller in [7], and the adaptive MPC in [8] consider the lateral and orientation error at the center of gravity of the vehicle, but there is no further information about the path in front of the vehicle considered in the control law, while our reference definition method presented below uses information about a greater path segment during the calculation of control input. Furthermore, integrating the steering dynamics into the prediction model is also an added value over [6,7,8].
In the field of path-tracking research, three main types of MPC methods have been implemented and tested which are the linear parameter-varying (LPV-MPC) [9,10], the linear time-varying (LTV-MPC) [11,12], and the nonlinear (NMPC) [11,13] solutions. In the LPV-MPC method, a linear plant model is applied for state prediction. The model does not change during the operation. However, the values can be recalculated at each time step based on the change in a parameter—for example, the velocity—of the vehicle. The change in the parameters is determined by real-time measurements or state estimation techniques. This method has a low computational cos; however, it is not able to handle the nonlinear behavior of the system. In the LTV-MPC method, the plant model is recalculated at each time step based on the online linearization of the applied nonlinear vehicle model. The linearization is always conducted in the current state of the system. Additional transformation of the system matrices and control input command are required. The parameters of the vehicle can be changed in the model as well. The current state which is the basis of the linearization either can be measured or estimated. In the case of nonlinear MPC, the evolution matrices are calculated based on a nonlinear plant model without linearization. This is the most accurate method, yet it is computationally expensive which can limit its applicability, as discussed in [11].
The vehicle model used for state prediction in the MPC controller needs to be chosen according to the control purpose [14,15]. The model should be able to predict future values of the controlled states for which states the desired values are defined by the reference values. Different types of vehicle models are applied in the path-following MPC controllers. In [11], two different types of MPC controllers are used for the path-tracking task: a nonlinear MPC with a nonlinear solver and a LTV-MPC using successive linearization and quadratic cost function. In both cases, the reference values are the heading angle, the yaw-rate and the lateral distance in the global frame, while the control input is the front steering angle. The difference between the two NMPC controllers used in [16] is the level of complexity of the vehicle models applied for state prediction. In one case, the vehicle model is a four-wheel 10 DOF model, while in the other case, it is a simplified 6 DOF bicycle model. The path-following task is conducted by combined steering and braking; hence the control inputs are the front steering angle and the braking torques for each wheel, and the reference is defined for the following states: longitudinal velocity, heading angle, lateral distance in the global frame, and yaw-rate. In [17], a LTV-MPC is applied, a 6 DOF four-wheel vehicle model is successively linearized, the control input is the front steering angle, and the reference states are the yaw-rate and the lateral distance in the global frame. In [18], a LTV-MPC is applied for the path-following task, the control input is the steering angle, and the reference states are the longitudinal and lateral distance in the global frame, and the heading angle. In [19], different controllers for the path following of over-actuated autonomous electric vehicles are presented, where the reference states are the yaw-rate, the sideslip angle, the heading angle, the lateral distance in the global frame, and the longitudinal velocity. The control inputs are the front steering angle and the driving or braking forces for each wheel. In [20], a LTV-MPC is applied in an integrated longitudinal and lateral control scheme where the reference states are the heading angle, the yaw-rate and the lateral distance in the global frame, while the control input is the front steering angle.
In [11,16,17,18,19,20,21], the lateral distance as a reference state is defined in the global frame; hence, the application of the nonlinear vehicle model or successive linearization of the nonlinear model is necessary for state prediction. In this paper, the authors intend to use a linear prediction model without successive linearization; thus, the lateral distance reference is defined in the vehicle’s own frame by transforming the corresponding section of the path using the vehicle’s spatial position and orientation related to the path. With this type of reference definition, and using a linear vehicle model, the nonlinear terms of the vehicle model can be easily omitted from the controller development. Furthermore, the orientation error is defined in a forward-looking way, by transforming the orientation errors to the vehicle’s ego coordinate system, which is a novel reference definition method and is one of the contributions of this paper.
There is a considerable effect that is mostly neglected during the development of path-following controllers [11,16,17,18,19,20,21] which is the consideration of the actuator dynamics—in this case, the dynamics of the steering system. During the previous research of the authors [22], the inclusion of the steering dynamics in the control law is able to significantly improve the performance of the path-following controller. The actuator dynamics can be modeled by a first-order lag [23]. In [9], the dynamics of the steering system are considered by a first-order lag; however, they are not integrated into the prediction model, applied solely in the vehicle model which is used for testing the controller in a simulation environment. In [12], the dynamics of the steering system are modeled by a first-order lag in the nonlinear prediction model which is linearized at each time step in a LTV-MPC structure. Also, a first-order lag is used as a steering system model in [24]. In [25], the steering actuator dynamics are modeled in different ways in order to achieve a smoother path-tracking performance. Furthermore, the backlash is also a considerable concern during the modeling of the steering systems, which can have a significant impact on the performance of a path-following controller. In the applied experimental vehicle, the backlash did not lead to a problem during the tests; hence, its impact is neglected in this article.

Contribution and Structure of the Paper

In this paper, the authors apply the LPV-MPC method to the path-tracking problem. The stability of the proposed control method is discussed in [26,27]. During the research, the authors intended to apply the proposed LPV-MPC at as high sideslip angles as possible. As expected by the authors, the proposed controller is applicable until the sideslip angles of the tires are in the linear region of the tire characteristics because a linearized vehicle model coupled with a linear tire model is used for state prediction. The phenomenon was confirmed during the experimental tests. The desired path-tracking accuracy can be reached by defining the path-following task optimally, in a novel way, and with the consideration of the steering dynamics in the state prediction. The plant model is calculated at each time step based on the measured states. As all of the states can be measured on the test vehicle, there is no need for using a state estimator. While in articles [9,10,11,12,13,28] the applied methods are LTV-MPC or NLMPC coupled with constraints on the sideslip angles, in this paper, the sideslip angle is not constrained, yet similarly, a high performance is reached by the optimal description of the path-tracking problem and the inclusion of the steering dynamics in the plant model used for state prediction.
In this article, a novel reference definition method is presented which determines both the reference lateral displacement and the reference angular orientation of the vehicle for a finite horizon in front of the vehicle. In the existing works [9,29], the reference trajectory is not defined in a forward-looking way, although if so, then solely the lateral displacement reference is given by different forward-looking methods [10,17].
The path-following performance is aimed to be enhanced by considering the steering system dynamics in the plant model. In this paper, the steering system is modeled both as a first-order and as a second-order system. The steering system models are identified on the test vehicle. In [30], a cascade MPC structure is proposed to reduce the computational requirements of the path-following controller and for a more accurate tracking realization. In this paper, additionally, the proposed cascade MPC structure is also examined; thereby, four different controllers are evaluated: a controller excluding the steering dynamics, a controller using first-order steering system dynamics, another using second-order dynamics, and a fourth one realizing the cascade MPC using second-order steering dynamics, and in which the controller of the steering dynamics is separated from the path-following controller. The performance of the controllers and the effect of the steering models are evaluated and compared in a simulation environment and on a test vehicle.
In summary, the contribution of this paper is twofold: a novel reference definition method is given in a forward-looking way, and, furthermore, the effect of the integration of different steering system models into the plant model of a MPC, and a cascade MPC structure on the path-following are evaluated in both simulation and experimental environments.
The structure of this paper is as follows. Section 2 presents the vehicle model used during the in-simulation development of the controller, and the different types of vehicle models applied in the MPC for state prediction, including the steering dynamics. Furthermore, Section 2 briefly presents the experiment-based identification of the parameters used in the nonlinear tire model. Section 3 describes the reference path-generation method. Section 4 and Section 5 explain the MPC problem formulation including the derivation of the cost function which needs to be minimized by the MPC by solving the quadratic programming (QP) problem, and the cascade MPC formulation, respectively. In Section 6, the simulation and experimental results are examined in detail and a profound comparison is made. Finally, Section 7 summarizes the concluding remarks and further plans.

2. Vehicle Modeling

In this section, the test vehicle setup, the applied vehicle models, and the parameter identification are presented. In this paper, the authors use two different types of vehicle models. One of the models is a four-wheel vehicle model in which nonlinear tire models are used at each wheel. This model was used during the testing and validation process of the MPC in a simulation environment. The other model is a linearized dynamic bicycle model which is applied to the MPC plant model for state prediction.

2.1. Test Vehicle Setup

The used vehicle platform is a BMW M2 Competition series production coupe car on which the necessary modifications were made to prepare it for executing the measurements. The vehicle is powered by a twin-turbocharged 3.0 L straight-six engine which produces 302 kW of performance and 550 Nm of torque. It has rear-wheel drive and a 7-speed dual-clutch automatic transmission. The vehicle was prepared for the tests by equipping it with a steering robot and throttle-by-wire systems.
For the MPC implementation, online data acquisition, and for the control of the actuators, a dSpace MicroAutoBox II 1401 was used. The MPC controller was built in the MATLAB Simulink environment from which C code was generated and uploaded to the MicroAutoBox. As the maximum time requirement of the MPC is less than 0.35 ms, the entire control model runs with a 1 ms time step. The steer-by-wire function is realized by a FER-201 steering robot used in angle control mode, as per the installation shown in Figure 1. The steering angle requested by the MPC is realized by the separated PID controller of the steering robot subsystem. All of the sensors and actuators are connected to the MicroAutoBox via the CAN interface.
The accelerator pedal of the vehicle is removed and its signal is emulated by a digital–analog converter which is built into the MicroAutoBox. The velocity of the vehicle is controlled separately from the lateral motion control by a PI controller. Hence, the transmission is used in automatic mode, the velocity demand is sent to the PI controller, the controlled variable is assigned to the accelerator pedal position, and the feedback variable is assigned to the velocity of the vehicle measured via its CAN bus.
For self-localization, an iMAR dual-antenna GNSS system with a built-in inertial measurement unit (IMU) and with RTK correction was used. All of the required states were measured or calculated from the signals provided by the GNSS system. The signals consist of the X and Y coordinates in UTM coordinate system, the heading angle, the yaw-rate, and the sideslip angle of the vehicle. Furthermore, all of the signal values are provided at the center of gravity (C.G.) of the vehicle, and the sideslip angles of the tires are calculated from the vehicle sideslip angle β provided by the GNSS system. Additional signals are read from the CAN bus of the vehicle and converted to FMS-Standard messages by an FMS Gateway. The CAN signals used during both measurement and system identification are the steering angle, the yaw-rate, the engine torque, the vehicle velocity, and the accelerator pedal position.

2.2. Vehicle Model for Simulation

For testing the controller in a simulation environment, a four-wheel dynamic vehicle model was used. The vehicle model only considers the planar dynamics of the vehicle, while the rolling and pitching dynamics are neglected as they are not relevant to the current problem. Equations (1)–(6), describe the longitudinal, lateral and yaw movement of the vehicle, based on Newton’s second law:
a x = 1 m F x V + V y r
a y = 1 m F y V V x r
r ˙ = 1 I z M z
F x V = F x R L + F x R R + F y F L sin δ F L + F y F R sin δ F R + F x F L cos δ F L + F x F R cos δ F R
F y V = F y R L + F y R R + F x F L sin δ F L + F x F R sin δ F R + F y F L cos δ F L + F y F R cos δ F R
M z = b ( F y R L + F y R R ) + s f ( F x F L sin δ F L + F x F R sin δ F R ) + s r F x R L + F x R R + a F y F L cos δ F L + F y F R cos δ F R
where ax is the longitudinal acceleration, ay is the lateral acceleration, FyFL, FyFR, FyRL and FyRR are the lateral tire forces at the front and the rear wheels, at the left and the right side, respectively, FxFL, FxFR, FxRL and FxRR are the longitudinal tire forces at the front and the rear wheels, at the left and the right side, respectively, where FxRL and FxRR are considered equal, m is the mass of the vehicle, r is the yaw-rate, a and b are the distances from the front and the rear wheel to the center of gravity, respectively. Furthermore, sf and sr are the front and the rear track, respectively, Iz is the moment of inertia around axis z, Vx is the longitudinal velocity, Vy is the lateral velocity in the ego coordinate system, δFL and δFR are the front steering angle at the left and at the right side, respectively, and finally αFL, αFR, αRL and αRR are the front and rear sideslip angles at the left and the right sides, respectively, as shown in Figure 2. The values of δFL and δFR are different, the ratio of the steering system is identified via measurements conducted with the test vehicle. The rear wheels are assumed to be unable to be steered.
The brush tire model [31] is used to calculate the lateral tire forces by Equations (7)–(9), where Cα is the tire cornering stiffness, α is the tire sideslip angle, µ is the friction coefficient and Fz is the vertical tire load. The model includes a ζ derating factor as suggested in [32] to consider the coupling between lateral and longitudinal forces. The calculation of the forces is based on the friction circle. The longitudinal traction force acts at the rear wheels hence the derating factor is only applied to the rear wheels. The variable αsl indicates the boundary of the sideslip angle where the entire tire is fully saturated, in which state the further increase in the sideslip angle will not increase the lateral force. At the front wheels, zero longitudinal force is assumed. In this case, the lateral force can be calculated by Equations (7) and (8), substituting ζ = 1 into the equations (Figure 3).
F y = C α t a n α + C α 2 3 ζ μ F z t a n α t a n α C α 3 27 ζ 2 μ 2 F z 2 t a n 3 α ,     α α s l ζ μ F z s g n α ,     α > α s l
α s l = 3 ζ μ F z C α
ζ = μ R F z R 2 F x 2 μ R F z R
The sideslip angles of the individual wheels are calculated by Equations (11) and (12) at the front and rear wheels, respectively.
v i = v x i v y i v z i = V x V y V z + 0 0 r × P i
P F L = a s f 0 T ,   P F R = a s f 0 T
P R L = b s r 0 T ,   P R R = b s r 0 T
α F L = a r c t a n v y F L v x F L δ F L ,   α F R = a r c t a n v y F R v x F R δ F R
α R L = a r c t a n v y R L v x R L ,   α R R = a r c t a n v y R R v x R R
where vi is the velocity vector (i = FL ˅ FR ˅ RL ˅ RR) of the wheels, calculated by using the [Vx,Vy,Vz]T velocity vector of the vehicle at the C.G., the yaw-rate, and the Pi location vector of the wheels.
The vehicle parameters m and Iz are measured, while the cornering stiffness of the tires is identified by ramp steer tests in [33]. The tire characteristics fitted to the respective test results are shown in Figure 4.

2.3. Vehicle Models Applied by the MPC

The interpretation of the lateral and orientation error is shown in Figure 5. The lateral error e is the distance measured between the center of gravity of the vehicle and the closest point to it on the path.
The orientation error λ calculated at the same path point as the distance error is the difference between the current heading angle φ of the vehicle and the tangent of the path at the closest point to the center of gravity.
In this paper, the authors apply a linearized bicycle model for state prediction. The model (Equation (13)) describes the lateral dynamics of the vehicle where the states are the lateral error, the derivative of the lateral error, the orientation error and the derivative of the orientation error [34].
x ˙ = A x + B u
A = 0 1 0 0 0 2 C α f + 2 C α r m V x 2 C α f + 2 C α r m 2 C α f l f + 2 C α r l r m V x 0 0 0 1 0 2 C α f l f 2 C α r l r I z V x 2 C α f l f 2 C α r l r I z 2 C α f l f 2 2 C α r l r 2 I z V x
B = 0 2 C α f m 0 2 C α f l f I z
The state vector is x = [ e 1   e ˙ 1   e 2   e ˙ 2 ]T, where e1 is the lateral error, e2 is the orientation error, and the control input u is the steering angle. Based on Equation (13), the future states of the vehicle can be predicted. As shown in Figure 4, the linear characteristic of the tires are between 0 and 3.5 degrees of the sideslip angle at the front wheels, and 0 and 2 degrees of the sideslip angle at the rear wheels; hence, the prediction is acceptable until the sideslip angles are in these ranges, respectively. Above these values, the prediction becomes incorrect due to the neglect of the tire nonlinearities. Accordingly, the controller is expected to be applicable approximately up to a 3.5 degrees/2 degrees of front/rear sideslip angle, whose expectation is proved by the experimental results presented in Section 6.
In this article, the dynamics of the steering system are modeled in two different ways: by a first-order lag (1TP) Equation (14) or by a second-order lag (2TP) Equation (16), for which both models can be easily included in the prediction model.
δ ˙ a c t = 1 T s t δ a c t + 1 T s t δ r e f
The first-order steering dynamics Equation (14) can be written as a transfer function (Equation (15)).
δ a c t = 1 T s t · s + 1 δ r e f
δ a c t = b s 2 + s · a s t 1 + a s t 0 δ r e f
where δ a c t is the actual steering angle, δ r e f is the reference steering angle demanded by the controller—both are road wheel angle—and T s t is the time constant of the first-order steering system, while ast1, ast0 and b are the parameters of the second-order steering system. The Tst time constant and the ast1, ast0, b parameters are identified based on measurement results. The identified steering system models are compared with the measured steering system; the result is shown in Figure 6. Because the measured and the identified systems show a high degree of coincidence, Figure 6 only shows the results in a small time window in order to achieve better visibility. As shown in Figure 6, the lag between signals ‘Measured’ and ‘Demand’ is small because of the high torque of the steering robot.
In the case of using the first-order steering dynamics, the dynamic model of vehicle Equation (17) is identical with Equation (13); however, the state vector is supplemented with a fifth state, the actual steering angle δact, yields x = e 1   e ˙ 1   e 2   e ˙ 2   δ a c t T .
x ˙ = A x + B u
A = 0 1 0 0 0 0 2 C α f + 2 C α r m V x 2 C α f + 2 C α r m 2 C α f l f + 2 C α r l r m V x 2 C α f m 0 0 0 1 0 0 2 C α f l f 2 C α r l r I z V x 2 C α f l f 2 C α r l r I z 2 C α f l f 2 2 C α r l r 2 I z V x 2 C α f l f I z 0 0 0 0 1 T s t
B = 0 0 0 0 1 T s t
As seen in Equations (13) and (17), the variable in the vehicle model is the longitudinal velocity Vx. The prediction model is updated in every time step using the current Vx.
In the case of using the second-order steering dynamics, the state-space representation of the vehicle in Equation (13) is expanded from four to six states by incorporating the actual steering angle and the angular velocity of the actual steering angle δ ˙ a c t into the state vector: x = [ e 1   e ˙ 1   e 2   e ˙ 2   δ a c t   δ ˙ a c t ]T. Finally, the vehicle model containing the second-order steering dynamics is defined in (18):
x ˙ = A x + B u
A = 0 1 0 0 0 0 0 2 C α f + 2 C α r m V x 2 C α f + 2 C α r m 2 C α f l f + 2 C α r l r m V x 2 C α f m 0 0 0 0 1 0 0 0 2 C α f l f 2 C α r l r I z V x 2 C α f l f 2 C α r l r I z 2 C α f l f 2 2 C α r l r 2 I z V x 2 C α f l f I z 0 0 0 0 0 0 1 0 0 0 0 a s t 0 a s t 1
B = 0 0 0 0 0 b
The experimental tests are conducted by using both vehicle models; the comparison of the results shows that those models which include steering dynamics are significantly more accurate and stable.

3. Reference Generation

As explained in Section 2, the authors intend to apply a linear prediction model and avoid the application of nonlinear prediction models or successive linearization techniques. Hence, the reference path which needs to be followed is defined by the corresponding states of the prediction model; thus, the reference lateral error e1 and the orientation error e2 values are given in a novel forward-looking way. As a result of defining the reference in this way, the path is defined by the desired lateral position values of the path points and by the orientation angle values. The distances of the lateral position values of the transformed reference path and the angles are considered as an error viewed from the current state of the vehicle in the vehicle’s ego coordinate system. The lateral error and the orientation error are the references for the first and the third elements of the state vector x, respectively.
κ = λ 1 + φ
H = 0 e 1
P r e f , i = H + c o s κ s i n κ s i n κ c o s κ P i
To calculate these error values, the path is transformed from the global coordinate system into the ego coordinate system Equation (19) where κ is the rotation angle, λ1 is the orientation error at the closest point to the center of gravity, H is the offset vector, e1 is the lateral error at the closest point to the center of gravity, Pref,i is the transformed point and Pi is the original path point, and i = 2… Np.
Figure 7 shows the principle of the reference definition where (X,Y) is the global frame, (x,y) is the ego frame, while e1, e2, … eNp are the lateral error references, and λ1, λ2, …. λNp are the orientation error references. The orientation error references are calculated at the same points as the lateral error references. The controller uses Np path points as references for the calculation of the optimal sequence of the steering demand where Np is the prediction horizon of the controller. The desired lateral error and orientation error are calculated at each Np path point. Finally, the reference for each point is a ϕ-vector equation (see Equation (20a)) where ei is the reference lateral error for the ith path point and λi is the reference orientation error for the ith path point. The reference vector for the entire prediction horizon is a stacked matrix Φ (Equation (20b)) with a dimension of 2 × Np.
Defining the reference path in this way, the desired (X,Y) values are transformed into the desired errors which are coherent with the states of the applied prediction model. The presented reference definition method is considered as one of the contributions of this paper, especially the forward-looking definition of angular errors.
ϕ i = e i λ i
Φ = ϕ 1 T ϕ 2 T ϕ N p T T = e 1 λ 1 e 2 λ 2 e N p λ N p   T

4. MPC Formulation

In the applied control structure, the vehicle model and the reference matrix are updated in every time step based on the current state of the vehicle regarding the path. Afterward, the evolution matrices, the reference matrix, and the current vehicle state are coupled in the QP cost function from which the optimal steering demand vector u is calculated. The QP problem is solved by the built-in MATLAB solver.
The evolution matrices Equation (21) of the system are calculated by the widely used method [35] where A is the state matrix, B is the control input matrix, u is the control input—in this case, the steering angle—and x is the vector of the state variables.
x k + 1 x k + 2 x k + N p x ¯ ^ = A A 2 A N p A = x k + B 0 0 A B B 0 A N p 1 B A N p 2 B B B = u k u k + 1 u k + N p 1 u ¯
Both the deviation of the vehicle states from the reference states and the magnitude of the applied control input need to be penalized by the cost function. Thus, an error vector z is created for penalizing the deviation of the states (Equation (22)) where z1 and z2 are the error terms for the deviation of the lateral error and the orientation error, respectively.
z k = z 1 k z 2 k = e 1 , r e f k e 1 k e 2 , r e f k e 2 k = C x + D ϕ = 1 0 0 0 0 0 1 0 e 1 k e ˙ 1 k e 2 k e ˙ 2 k + 1 0 0 1 e 1 , r e f k e 2 , r e f k
In (22), C is the output matrix, D is the selection matrix for the reference, C and D are constructed in correspondence with the state vector xR4, and the reference vector ϕ, respectively, while e1,ref (k) is the reference lateral error and e2,ref (k) is the reference orientation error. In that case, when the enhanced model including the steering dynamics is used, matrix C is changed according to Equation (23). Based on which steering system model is used, the enhanced state vector is xR5 for the first-order steering model (Equation (23a)), and is xR6 for the second-order steering model (Equation (23b)).
C f i r s o r d e r = 1 0 0 0 0 0 0 1 0 0
C s e c o n d o r d e r = 1 0 0 0 0 0 0 0 1 0 0 0
The error vector z is extended for the entire prediction horizon Equation (24),
z k + 1 z k + 2 z k + N p z ¯ ^ = + C 0 0 C 0 0 0 0 C C = x k x k + 1 x k + N p x ¯ ^ + D 0 0 D 0 0 0 0 D D = ϕ k + 1 ϕ k + 2 ϕ k + N p Φ ¯ ^
where C = R 2 N p × 4 N p or C = R 2 N p × 5 N p or C = R 2 N p × 6 N p —according to the applied steering system model—is the output hypermatrix, and D = R 2 N p × 2 N p is the selection hypermatrix for the reference. Both C = and D = are stacked diagonal matrices derived from the C and D matrices.
The cost function is formulated by using the state vector and the error matrix for penalizing the state deviation, and the control input matrix for penalizing the magnitude of the controlled variable. The general form of the cost functions for QP problems is defined as Equation (25) where Q = x R 4 N p × 4 N p or Q = x R 5 N p × 5 N p or Q = x R 6 N p × 6 N p – according to the applied steering system model—and Q = z R 2 N p × 2 N p are weight matrices for the state deviation, and R = R N p × N p is the weight matrix for the controlled variable, while x ¯ ^ T R N p × 4 N p or x ¯ ^ T R N p × 5 N p or x ¯ ^ T R N p × 6 N p —according to the applied steering system model—and z ¯ ^ T R N p × 2 N p are the stacked vectors of the predicted states and errors, respectively, and u ¯ T R N p × N p is the optimal control input vector which is the solution of the QP problem.
J k = 1 2 x ¯ ^ T Q = x x ¯ ^ + z ¯ ^ T Q = z z ¯ ^ + u ¯ T R = u ¯
Q = x = Q x 0 0 0 Q x 0 0 0 Q x
Q = z = Q z 0 0 0 Q z 0 0 0 Q z
R = = R 0 0 0 R 0 0 0 R
where Q = x , Q = z and R = are diagonal matrices Equation (26) created by using matrices Qx, Qz and scalar R (Equation (19)) where Qx is changed according to the applied vehicle model, i.e., according to the dimensions of the state vector x. Using the model without steering dynamics, Qx ∈ R4×4 (Equation (20a))—when x = [ e 1   e ˙ 1   e 2   e ˙ 2 ]T—while using the enhanced model including the first-order steering dynamics, QxR5×5 (Equation (27b))—when x = [ e 1   e ˙ 1   e 2   e ˙ 2   δ a c t ]T—and when using the second-order steering dynamics, QxR6×6 (Equation (27c))—when x = [ e 1   e ˙ 1   e 2   e ˙ 2   δ a c t   δ ˙ a c t ]T.
Q x = q x 1 0 0 0 0 0 0 0 0 0 q x 2 0 0 0 0 0
Q x = q x 1 0 0 0 0 0 0 0 0 0 0 0 q x 2 0 0 0 0 0 0 0 0 0 0 0 0
Q x = q x 1 0 0 0 0 0 0 0 0 0 0 0 0 0 q x 2 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0
In Equation (27), qx1 and qx2 are the weights of the lateral error and the orientation error, respectively. Qz and R are identical for both vehicle models Equation (28) where qz1 and qz2 are the weights of the deviation from the reference lateral error and the orientation error, respectively, and r is the weight of the control input.
Q z = q z 1 0 0 q z 2
R = r
The cost function Equation (29) is calculated by substituting Equations (21) and (22) to Equation (25).
J k = 1 2 u ¯ T H u ¯ + f T u ¯ = 1 2 u ¯ T B = T Q = x B = + B = T C = T Q = z C = B = + R = H u ¯ + x ¯ T A = T Q = x B = + x ¯ T A = T C = T Q = z C = B = + Φ ¯ ^ D = T Q = z C = B = f T u ¯
The QP problem is defined in the following form:
min u 1 2 u ¯ T H u ¯ + f T u ¯
subject to
0.5   r a d u i   0.5 r a d     u i u ¯
Finally, the solution of the QP problem is vector u which contains the optimal control input signals—in this case, the sequence of steering angles. Only the first element of vector u is applied to the vehicle, and the state measurement, the prediction of future states, and the solution of the quadratic programming problem are conducted in every time step. Although u is defined as roadwheel angle (RWA) in radians, the steering wheel angle (SWA) is shown in degrees in the figures below. The conversion from RWA to SWA is conducted based on the ratio of the steering system which is identified on the test vehicle. The constraint of 0.5 rad on the RWA expressed as SWA is 400 deg. Since the MPC is an online optimization process, the entire process needs to be able to run in real-time on the MicroAutoBox; the presented process can run for less than 1 ms as shown in Section 6.

5. Cascade MPC Formulation

The authors implemented a cascade MPC as suggested in [30], in which the steering system dynamics are modeled and controlled separately from the path-following MPC, by a second MPC. In this controller method, the first MPC—i.e., vehicle MPC—calculates the necessary angular velocity of the actual steering angle, and the second MPC—i.e., the steering MPC—is responsible for tracking it using a second-order steering system model for state prediction. In [30], the vehicle MPC uses system model Equation (31) for state prediction, where the state vector is x = [ e 1   e ˙ 1   e 2   e ˙ 2   δ r e f ]T, and the control input is u = δ ˙ r e f .
x ˙ = A x + B u
A = 0 1 0 0 0 0 2 C α f + 2 C α r m V x 2 C α f + 2 C α r m 2 C α f l f + 2 C α r l r m V x 2 C α f m 0 0 0 1 0 0 2 C α f l f 2 C α r l r I z V x 2 C α f l f 2 C α r l r I z 2 C α f l f 2 2 C α r l r 2 I z V x 2 C α f l f I z 0 0 0 0 0
B = 0 0 0 0 1
In the steering MPC, the second-order steering system is modeled by Equation (32), where the state vector is x = [ δ a c t   δ ˙ a c t ]T, and the control input is u = δ r e f .
x ˙ = A x + B u
A = 0 1 a s t 0 a s t 1
B = 0 b
The QP cost function is formulated and solved in both the vehicle MPC and in the steering MPC in the same way, as presented in Section 4. In the vehicle MPC, the applied C matrix is Equation (23b), the Qx matrix is Equation (27b), and the other matrices are identical. In the steering MPC, the reference is given by Equation (33) which is a vector that contains the reference angular velocity values calculated by the vehicle MPC.
Φ = δ ˙ r e f 1 δ ˙ r e f 2 δ ˙ r e f N p   T
In the steering MPC, the error vector needs to be modified (Equation (34)). The error vector is extended for the entire prediction horizon in the same way as in Equation (24). The applied Q = x R 2 N p × 2 N p and Q = z R N p × N p are generated using the Qxst Equation (35) and Qzst Equation (36) matrices. The diagonal matrix R = is generated as in Equation (26c), using rst.
z k = δ ˙ r e f δ ˙ a c t = C x + D ϕ = 0 1 δ a c t δ ˙ a c t + δ ˙ r e f
Q x s t = 0 0 0 q x s t
Q z s t = q z s t
The solution of the two QP problems is two vectors of length Np that contain the optimal reference angular velocity of the steering angle in the vehicle MPC, and the optimal reference steering angle in the steering MPC. The applied constraint on the vector of the optimal angular velocity of the steering angle is −2 rad/s ≤ δ ˙ r e f , i ≤ 2 rad/s,   δ ˙ r e f , i   δ ˙ ¯ r e f and the constraint on the optimal steering angle vector is −0.5 rad ≤ δ r e f , i ≤ 0.5 rad,   δ r e f , i δ ¯ r e f .
The parameters of the test vehicle, the controllers, and the steering models are provided in Table 1.

6. Simulation and Experimental Results

The simulation and the experimental results are conducted on the same reference path, on a flat asphalt surface. The path consists of three main sections, as shown in Figure 8, which are the double lane change, the u-turn, and the slalom segments.
The double lane change, which is a critical driving maneuver [36,37], has a 3.5 m lateral evasion where the entering and leaving sections are generated by using clothoid transition curves. The u-turn is a semicircle with a 30 m radius. The slalom segment is constructed by five arcs with a 20 m radius. At the double lane change section, the curvature of the path is increasing continuously. However, at the u-turn and the slalom sections, no transitional arcs are applied; thus, there are discontinuities in the curvature which makes it harder for the vehicle to follow the path.
Furthermore, the reference path contains two straight line segments at the beginning and at the end of the path. The straight section at the beginning is intended to provide the necessary distance for the vehicle to accelerate to the required speed. The reference velocity of the vehicle is reached in the straight section and kept on this value during the entire path by a PI controller. The straight section at the end is applied to ensure the vehicle stabilizes after the slalom section. The throttle is only released at the final straight section.
The simulation and the experimental tests are conducted using both the vehicle model without steering dynamics and the enhanced vehicle model including the steering dynamics for state prediction. During the tests, the target velocity of the vehicle is increased until the controller is unable to follow the path. The target velocity is started at 30 km/h and increased in 10 km/h steps until the applicability limit of the controller is reached and the controller becomes unable to follow the path. The tuning parameters of the controller are constant during the tests. Furthermore, the same parameters are used in the simulation and during the experimental tests. The prediction horizon is unchanged as well and is identical in every setup; thus, the same identically tuned and parametrized controllers are tested in the simulation and experimental environments.

6.1. Simulation and Experimental Results Excluding Steering Dynamics

In this section, the presented simulation and experimental results are both conducted using the vehicle model which excludes the steering dynamics for state prediction. The results are summarized in Table 2, where eavg and ϕavg are the average lateral and orientation errors, respectively, and emax and ϕmax are the maximal lateral and orientation errors, respectively.
The results of the first test case conducted at 30 km/h are shown in Figure 9 and Figure 10. The simulation and the test results are highly close to each other, the average error values are low, and the maximal values are appropriate as well. For both the simulation and the measurements, the sideslip angle falls within the same interval (≤3.5 degrees) which is the linear section of the tire characteristic. An oscillation phenomenon appears in the steering angle which is much more significant during simulation rather than experimental tests. The presence of the oscillation is assumed to be the result of the neglect of the steering dynamics.
At a speed of 40 km/h, the controller still operates stably and the lateral and orientation errors are still low. The amplitude of the oscillation is increased compared to the tests conducted at 30 km/h which made the travel inconvenient for the passengers. In the slalom section, the sideslip angles reach the nonlinear region of the tire characteristics (≥3.5 degrees) which further increases the oscillation.
The highest speed at which the tests can be performed is 45 km/h as shown in Figure 11 and Figure 12. In the simulation, the controller can drive the vehicle along the entire path; however, during the experimental tests, the amplitude of the oscillation becomes so high that the test is stopped—despite the fact that the controller can follow the path and the error values are low, the results are not applicable. The appearance of the oscillation in the simulation correctly predicts that it will also appear in the experimental tests.
As seen in Table 2, the simulation results of the lateral and orientation errors are an accurate approximation of the measurement results, however, the average and maximal errors are slightly greater.
The appearing oscillation is primarily due to the neglect of the actuator dynamics which are the dynamics of the steering system in this case, and secondly, at higher speeds, due to the prediction inaccuracy of the linear tire model. Tuning the parameters of the controller to be less sensitive for the errors results in a decrease in the oscillation; however, the accuracy of the path following significantly deteriorates as well.

6.2. Simulation and Experimental Results including Steering Dynamics

In this section, the simulation and experimental results of the application of the steering models in the MPC for state prediction are presented, as shown in Table 3.
At 30 km/h (Figure 13 and Figure 14) and at 40 km/h, the simulation results approximate the measurement results accurately; however, the average lateral error is greater during the measurements than in the simulation. The oscillation is entirely missing as a result of the inclusion of the steering dynamics.
At 50 km/h and at 55 km/h (Figure 15 and Figure 16), the controller still operates stably and accurately, proven by the simulation results being close to the measurement results. The consideration of the steering dynamics enables the controller to drive the vehicle along the path at enhanced speeds, while the oscillation appears at first only at 55 km/h. At this speed, the sideslip angles reach and exceed the 3.5 degrees limit, which is the applicability limit of the applied linear tire models. Hence, the appearing oscillation is the result of invalid state prediction caused by exceeding the limit of the applied linear tire model in the prediction model. The application of the second-order steering model does not result in a performance improvement, which is due to the high torque of the steering robot. At 50 km/h, the cascade MPC provides acceptable performance, but at 55 km/h, high errors appear.
At 60 km/h (Figure 17 and Figure 18), the sideslip angles of the tires reach the limit of applicability; hence, all of the applied controllers lose control over the vehicle. The vehicle can perform the double lane change and the u-turn sections, using the first-order and the second-order steering models; however, the controller loses control in the slalom section, in both simulation and experimental tests. During the experimental tests, the measurements are plotted until the u-turn section, because the cascade MPC loses control here.
Please note that at 60 km/h, at the ending section of the tests, the lateral and orientation errors are high. Furthermore, the simulation and the experimental test are not aborted at exactly the same path point.
These have a considerable effect on the calculated average errors; hence, the simulation and the test results at 60 km/h do not show as high a degree of coincidence as at other speeds.
The controllers lose control in the slalom section due to the change in the curvature being high there, which results in a large steering angle along with a high sideslip angle. Moreover, the vehicle reaches its driving limit due to the high curvatures of the slalom section—even with a human driver. Furthermore, until the slalom section, the controllers using the first-order and the second-order steering models follow the path highly accurately despite the instability. The poor performance of the cascade MPC is the result of the exclusion of the steering dynamics from the vehicle MPC’s plant model.
Regarding the simulation results, overall, they can accurately represent the expected behavior of the vehicle. In the 1TP test cases, the average lateral errors are smaller during the tests than in the simulations, but apart from that, the errors were slightly greater in the experimental tests than in the simulations; however, the differences remain small. Applying the same controller parameters and using the vehicle model, which is parametrized based on measurements, the simulations give accurate results, which proves that the applied vehicle model is correct and is suitable for in-simulation controller development.
Based on the simulation and the experimental results, the authors experienced that the dynamic model of the vehicle and the steering system should be integrated into the same MPC, for better performance.
The lateral acceleration during the experimental test conducted at 55 km/h using the 1TP steering model is shown in Figure 19. The maximal lateral acceleration is about 9 m/s2 at the slalom section; here, the signal noise is generated by the high sideslip of the tires. In the double lane change section, the lateral acceleration reaches about 7.5 m/s2, where the controller can still drive the vehicle stably. The unstable behavior starts when the sideslip reaches 3.5 degrees, as shown in Figure 16.
The computational requirements are examined solely in those cases when the controller is run on the MicroAutoBox II rapid prototyping unit. The values of the turnaround time provided by the MicroAutoBox II are shown in Table 4, while Figure 20 shows the turnaround time values for a measurement in which no steering dynamics are considered. The turnaround time values show the time which is needed to run the entire control model—including the state measurement, the prediction of the future states, and the solution of the QP problem. By increasing the dimension of the x state vector of the plant model, the computational requirement is increased but remains under 1 ms which is sufficient for running the controller with a 1 ms time step, which is the desired target value in the field of controller development. The results show that the proposed LPV-MPC controller has a low computational requirement compared to other methods, e.g., a NLMPC described in [14] where the computational time is 5–35 ms, or LTV-MPC solutions, e.g., in [15], where 100–600 ms is needed for running the controller, depending on the applied vehicle model, or in the other LTV-MPC [18], where the execution time is about 2 ms.

7. Conclusions and Future Work

In this paper, an MPC approach for automated vehicle path following is presented. A vehicle model for state prediction and a novel method for reference state generation is proposed where the reference states are defined by the desired lateral error and the orientation error regarding the current state of the vehicle.
Regarding the applied vehicle model, when the steering dynamics are neglected at the state prediction, the lateral error is increased at each test case and the controller starts to oscillate at around 40 km/h, and for higher speeds, it is unable to follow the path. When the steering dynamics are considered for the state prediction, the limit of the controller is increased to up to 55 km/h—for this test vehicle. Consequently, with the inclusion of the model of the steering system in the prediction model, the performance of the controller is significantly increased.
In this article, four different models are applied for state prediction; the best performance is achieved when the first-order steering model is coupled with the vehicle model in a single MPC. There are no significant differences when applying the first-order and the second-order steering models; the application of the first-order system provided a slightly more accurate path-following. However, the modeled steering system has very fast dynamics, and a small time constant, which is due to the high torque of the steering robot. A cascade MPC structure is also examined, where the steering dynamics is considered separately from the vehicle dynamics in a second MPC. This solution provided better performance than when the steering dynamics were neglected and solely the vehicle dynamics were considered for state prediction. However, according to our experiments, the best performance can be reached when the dynamics of the vehicle and the steering system are integrated into one model, applying one MPC. The performance degradation of the cascade MPC is due to the incapability of the vehicle MPC for taking into account the steering dynamics during the state prediction. Based on the conducted tests, the authors suggest integrating the dynamics of the vehicle and the steering system into one MPC for the best path-following performance; however, this results in a slightly higher computational demand.
As future research opportunities, from a modeling point of view, the application of a more detailed steering system model would be able to further increase the performance of the controller, especially if the steering actuator does not have as high torque as the applied one. The controller uses a linear vehicle and tire model for state prediction, which leads to inaccurate state prediction when the vehicle operates at higher lateral accelerations. To overcome this issue the accuracy of the state prediction needs to be enhanced, which could be reached by applying a successive linearization method in an LTV-MPC structure, or by using NLMPC. The application of the nonlinear vehicle and tire models in a LTV-MPC or NLMPC structure coupled with a more detailed model of the steering system would be able to increase the application limit of the controller. Furthermore, a LTV-MPC is also under development by the authors to be able to handle the vehicle when the tires operate in the nonlinear region. The consideration of the backlash of the steering system by the path-following controller is also a potential research field. As the vehicle is driven in a more dynamic maneuver, e.g., during higher lateral accelerations or at higher speeds, the effect of backlash becomes more important, which needs to be considered in the future. Moreover, a potential research opportunity is the consideration of the actuator fault as discussed in [6], and making the controller more adaptive, e.g., changing the value of the prediction horizon, the control horizon, and the controller gains depending on the velocity of the vehicle as presented in [8]. The online estimation of the tire cornering stiffness [8], the friction coefficient [8] and other vehicle parameters can also improve the performance of the controller.

Author Contributions

Conceptualization, Á.D. and V.T.; formal analysis, Á.D. and V.T.; investigation, Á.D.; methodology, Á.D.; project administration, V.T.; resources, V.T.; software, Á.D.; supervision, V.T.; validation, Á.D.; writing—review and editing, Á.D. and V.T. All authors have read and agreed to the published version of the manuscript.

Funding

The research was supported by the Ministry of Innovation and Technology NRDI Office within the framework of the Autonomous Systems National Laboratory Program. (RRF-2.3.1-21-2022-00002).

Institutional Review Board Statement

Not applicable.

Informed Consent Statement

Not applicable.

Data Availability Statement

Not applicable.

Conflicts of Interest

The authors declare no conflict of interest.

References

  1. Gray, A.; Gao, Y.; Lin, T.; Hendrick, J.K.; Tseng, H.E.; Borelli, F. Predictive Control for Agile Semi-Autonomous Ground Vehicles using Motion Primitives. In Proceedings of the 2012 American Control Conference (ACC), Montreal, QC, Canada, 27–29 June 2012. [Google Scholar] [CrossRef]
  2. Orgován, L.; Bécsi, T.; Aradi, S. Autonomous Drifting Using Reinforcement Learning. Period. Polytech. Transp. Eng. 2021, 49, 292–300. [Google Scholar] [CrossRef]
  3. Lu, Z.; Shyrokau, B.; Boulkroune, B.; van Aalst, S.; Happee, R. Performance benchmark of state-of-the-art lateral path-following controllers. In Proceedings of the 2018 IEEE 15th International Workshop on Advanced Motion Control (AMC), Tokyo, Japan, 9–11 March 2018; pp. 541–546. [Google Scholar] [CrossRef] [Green Version]
  4. Viana, Í.B.; Kanchwala, H.; Ahiska, K.; Aouf, N. A Comparison of Trajectory Planning and Control Frameworks for Cooperative Autonomous Driving. J. Dyn. Syst. Meas. Control. 2021, 143, 071002. [Google Scholar] [CrossRef]
  5. Viana, Í.B.; Kanchwala, H.; Aouf, N. Cooperative Trajectory Planning for Autonomous Driving Using Nonlinear Model Predictive Control. In Proceedings of the 2019 IEEE International Conference on Connected Vehicles and Expo (ICCVE), Graz, Austria, 4–8 November 2019; pp. 1–6. [Google Scholar] [CrossRef]
  6. Wang, H.; Zhou, F.; Li, Q.; Song, W. Reliable adaptive H-infinity path following control for autonomous ground vehicles in finite frequency domain. J. Frankl. Inst. 2020, 357, 9599–9613. [Google Scholar] [CrossRef]
  7. Matveev, A.S.; Hoy, M.; Katupitiya, J.; Savkin, A.V. Nonlinear sliding mode control of an unmanned agricultural tractor in the presence of sliding and control saturation. Robot. Auton. Syst. 2013, 61, 973–987. [Google Scholar] [CrossRef]
  8. Lin, F.; Chen, Y.; Zhao, Y.; Wang, S. Path tracking of autonomous vehicle based on adaptive model predictive control. International. J. Adv. Robot. Syst. 2019, 16, 1729881419880089. [Google Scholar] [CrossRef] [Green Version]
  9. Kianfar, R.; Falcone, P.; Frederikson, J. A Distributed Model Predictive Control Approach to Active Steering Control of String Stable Cooperative Vehicle Platoon. IFAC Proc. Vol. 2013, 46, 750–755. [Google Scholar] [CrossRef]
  10. Wu, N.; Huang, W.; Song, Z.; Wu, X.; Zhang, Q.; Yao, S. Adaptive dynamic preview control for autonomous vehicle trajectory following with DDP based path planner. In Proceedings of the 2015 IEEE Intelligent Vehicles Symposium (IV), Seoul, Republic of Korea, 28 June–1 July 2015; pp. 1012–1017. [Google Scholar]
  11. Falcone, P.; Borelli, F.; Asgari, J.; Tseng, H.E.; Hrovat, D. Predictive Active Steering Control for Autonomous Vehicle Systems. IEEE Trans. Control. Syst. Technol. 2007, 15, 566–580. [Google Scholar] [CrossRef]
  12. Katriniok, A.; Maschuw, J.P.; Christen, F.; Eckstein, L.; Abel, D. Optimal vehicle dynamics control for combined longitudinal and lateral autonomous vehicle guidance. In Proceedings of the 2013 European Control Conference (ECC), Zurich, Switzerland, 17–19 July 2013; pp. 974–979. [Google Scholar]
  13. Borrelli, F.; Falcone, P.; Keviczky, T.; Asgari, J.; Hrovat, D. MPC-based approach to active steering for autonomous vehicle systems. Int. J. Veh. Auton. Syst. 2005, 3, 265–291. [Google Scholar] [CrossRef]
  14. Chowdhri, N.; Ferranti, L.; Iribarren, F.S.; Shyrokau, B. Integrated nonlinear model predictive control for automated driving. Control. Eng. Pract. 2021, 106, 104654. [Google Scholar] [CrossRef]
  15. Kanchwala, H.; Bezerra, V.I.; Aouf, N. Cooperative path-planning and tracking controller evaluation using vehicle models of varying complexities. Proc. Inst. Mech. Eng. Part C J. Mech. Eng. Sci. 2020, 235, 2877–2896. [Google Scholar] [CrossRef]
  16. Falcone, P.; Tseng, H.E.; Borrelli, F.; Asgari, J. MPC-based yaw and lateral stabilisation via active front steering and braking. Veh. Syst. Dyn. 2008, 46, 611–628. [Google Scholar] [CrossRef]
  17. Xu, Y.; Tang, W.; Chen, B.; Qiu, L.; Yang, R. A Model Predictive Control with Preview-Follower Theory Algorithm for Trajectory Tracking Control in Autonomous Vehicles. Symmetry 2021, 13, 381. [Google Scholar] [CrossRef]
  18. Ducajú, J.M.S.; Llobregat, J.J.S.; Cuenca, Á.; Tomizuka, M. Autonomous Ground Vehicle Lane-Keeping LPV Model-Based Control: Dual-Rate State Estimation and Comparison of Different Real-Time Control Strategies. Sensors 2021, 21, 1531. [Google Scholar] [CrossRef]
  19. Zhang, W.; Wang, Z.; Drugge, L.; Nybacka, M. Evaluating Model Predictive Path Following and Yaw Stability Controllers for Over-Actuated Autonomous Electric Vehicles. IEEE Trans. Veh. Technol. 2020, 69, 12807–12821. [Google Scholar] [CrossRef]
  20. Wei, S.; Zou, Y.; Zhang, X.; Zhang, T.; Li, X. An Integrated Longitudinal and Lateral Vehicle Following Control System with Radar and Vehicle-to-Vehicle Communication. IEEE Trans. Veh. Technol. 2019, 68, 1116–1127. [Google Scholar] [CrossRef]
  21. Wischnewski, A.; Euler, M.; Gümüs, S. Tube model predictive control for an autonomous race car. Veh. Syst. Dyn. 2021, 60, 3151–3173. [Google Scholar] [CrossRef]
  22. Domina, Á.; Tihanyi, V. Modelling the dynamic behavior of the steering system for low speed autonomous path tracking. In Proceedings of the 2019 IEEE Intelligent Vehicles Symposium (IV), Paris, France, 9–12 June 2019. [Google Scholar]
  23. Bárdos, Á.; Szimandl, B.; Németh, H. Controller structure for high response engine exhaust throttles. Int. J. Heavy Veh. Syst. 2020, 27, 325–339. [Google Scholar] [CrossRef]
  24. Xu, S.; Peng, H.; Tang, Y. Preview Path Tracking Control with Delay Compensation for Autonomous Vehicles. IEEE Trans. Intell. Transp. Syst. 2021, 22, 2979–2989. [Google Scholar] [CrossRef]
  25. Kim, E.; Kim, J.; Sunwoo, M. Model predictive control strategy for smooth path tracking of autonomous vehicles with steering actuator dynamics. Int. J. Automot. Technol. 2014, 15, 1155–1164. [Google Scholar] [CrossRef]
  26. Falcone, P.; Borrelli, F.; Tseng, H.E.; Asgari, J.; Hrovat, D. Linear time-varying model predictive control and its application to active steering systems: Stability analysis and experimental validation. Int. J. Robust Nonlinear Control. 2007, 18, 862–875. [Google Scholar] [CrossRef]
  27. Cisneros, P.S.G. Quasi-Linear Model Predictive Control: Stability, Modelling and Implementation. Ph.D. Thesis, Technical University of Hamburg, Hamburg, Germany, 2021. [Google Scholar]
  28. Kanchwala, H.; Viana, Í.B.; Ceccoti, M.; Aouf, N. Model predictive tracking controller for a high fidelity vehicle dynamics model. In Proceedings of the 2019 IEEE Intelligent Transportation Systems Conference (ITSC), Auckland, New Zealand, 27–30 October 2019; pp. 1496–1503. [Google Scholar] [CrossRef]
  29. Ni, L.; Gupta, A.; Falcone, P.; Johannesson, L. Vehicle Lateral Motion Control with Performance and Safety Guarantees. IFAC-Pap. 2016, 49, 285–290. [Google Scholar] [CrossRef]
  30. Nam, H.; Choi, W.; Ahn, C. Model Predictive Control for Evasive Steering of an Autonomous Vehicle. Int. J. Automot. Technol. 2019, 20, 1033–1042. [Google Scholar] [CrossRef]
  31. Hadekel, R. The Mechanical Characteristics of Pneumatic Tyres; No Ati 92172, S & T MEMO NO 10/52; Clearinghouse for Federal Scientific and Technical Information; National Association of Housing and Redevelopment Officials: Washington, DC, USA, 1952. [Google Scholar]
  32. Hindiyeh, R.Y. Dynamics and Control of Drifting in Automobiles. Ph.D. Thesis, Stanford University, Stanford, CA, USA, 2013. [Google Scholar]
  33. Bárdos, Á.; Domina, Á.; Tihanyi, V.; Szalay, Z.; Palkovics, L. Implementation and experimental evaluation of a MIMO drifting controller on a test vehicle. In Proceedings of the 2020 IEEE Intelligent Vehicles Symposium (IV), Las Vegas, NV, USA, 19 October–13 November 2020; pp. 1472–1478. [Google Scholar] [CrossRef]
  34. Rajamani, R. Vehicle dynamics and control. In Mechanical Engineering Series, 2nd ed.; Springer: Boston, MA, USA, 2012. [Google Scholar]
  35. Varga, B.; Tettamanti, T.; Kulcsár, B. Optimally combined headway and timetable reliable public transport system. Transp. Res. Part C Emerg. Technol. 2018, 92, 1–26. [Google Scholar] [CrossRef]
  36. Rákos, O.; Aradi, S.; Bécsi, T. Lane Change Prediction Using Gaussian Classification, Support Vector Classification and Neural Network Classifiers. Period. Polytech. Transp. Eng. 2020, 48, 327–333. [Google Scholar] [CrossRef]
  37. Fadhil, S.A.; Al-Bayatti, A.H. Developing a New Driver Assistance System for Overtaking on Two-Lane Roads using Predictive Models. Period. Polytech. Transp. Eng. 2022, 50, 400–413. [Google Scholar] [CrossRef]
Figure 1. Steering robot installed in the test vehicle.
Figure 1. Steering robot installed in the test vehicle.
Sensors 23 06862 g001
Figure 2. Four-wheel vehicle model with applied symbols.
Figure 2. Four-wheel vehicle model with applied symbols.
Sensors 23 06862 g002
Figure 3. Lateral force characteristics of the brush tire model as a function of longitudinal force and sideslip angle.
Figure 3. Lateral force characteristics of the brush tire model as a function of longitudinal force and sideslip angle.
Sensors 23 06862 g003
Figure 4. Front and rear tire characteristics [33].
Figure 4. Front and rear tire characteristics [33].
Sensors 23 06862 g004
Figure 5. Lateral and orientation error.
Figure 5. Lateral and orientation error.
Sensors 23 06862 g005
Figure 6. Reference tracking of the steering robot, the identified first-order and second-order systems.
Figure 6. Reference tracking of the steering robot, the identified first-order and second-order systems.
Sensors 23 06862 g006
Figure 7. Reference lateral error and orientation error in the ego frame.
Figure 7. Reference lateral error and orientation error in the ego frame.
Sensors 23 06862 g007
Figure 8. Reference path with the three main sections.
Figure 8. Reference path with the three main sections.
Sensors 23 06862 g008
Figure 9. Simulation results at 30 km/h—without steering dynamics.
Figure 9. Simulation results at 30 km/h—without steering dynamics.
Sensors 23 06862 g009
Figure 10. Measurement results at 30 km/h—without steering dynamics.
Figure 10. Measurement results at 30 km/h—without steering dynamics.
Sensors 23 06862 g010
Figure 11. Simulation results at 45 km/h—without steering dynamics.
Figure 11. Simulation results at 45 km/h—without steering dynamics.
Sensors 23 06862 g011
Figure 12. Measurement results at 45 km/h—without steering dynamics.
Figure 12. Measurement results at 45 km/h—without steering dynamics.
Sensors 23 06862 g012
Figure 13. Simulation results at 30 km/h—including steering dynamics.
Figure 13. Simulation results at 30 km/h—including steering dynamics.
Sensors 23 06862 g013
Figure 14. Measurement results at 30 km/h—including steering dynamics.
Figure 14. Measurement results at 30 km/h—including steering dynamics.
Sensors 23 06862 g014
Figure 15. Simulation results at 55 km/h—including steering dynamics.
Figure 15. Simulation results at 55 km/h—including steering dynamics.
Sensors 23 06862 g015
Figure 16. Measurement results at 55 km/h—including steering dynamics.
Figure 16. Measurement results at 55 km/h—including steering dynamics.
Sensors 23 06862 g016
Figure 17. Simulation results at 60 km/h—including steering dynamics.
Figure 17. Simulation results at 60 km/h—including steering dynamics.
Sensors 23 06862 g017
Figure 18. Measurement results at 60 km/h—including steering dynamics.
Figure 18. Measurement results at 60 km/h—including steering dynamics.
Sensors 23 06862 g018
Figure 19. Lateral acceleration at 55 km/h, 1TP steering model.
Figure 19. Lateral acceleration at 55 km/h, 1TP steering model.
Sensors 23 06862 g019
Figure 20. The time requirement of the control software on the MicroAutoBox II during the “no steering dynamics” test case.
Figure 20. The time requirement of the control software on the MicroAutoBox II during the “no steering dynamics” test case.
Sensors 23 06862 g020
Table 1. Parameter values of the vehicle, the controller, and the steering models.
Table 1. Parameter values of the vehicle, the controller, and the steering models.
NameValueSign and Dimension
Vehicle parameters
mass of the vehicle1810m (kg)
vehicle moment of inertia around the z-axis2500Iz (kgm2)
cornering stiffness of the front tires150,000Cαf (N/rad)
cornering stiffness of the rear tires250,000Cαr (N/rad)
friction coefficient (lateral)1μ (-)
distance between the center of gravity and the front axle1.35a (m)
distance between the center of gravity and the rear axle1.37b (m)
Controller parameters
prediction horizon10Np (pcs)
control horizon10Nc (pcs)
weight of lateral error0.85qx1 (-)
weight of orientation error1.1qx2 (-)
weight of the deviation from the lateral reference0.85qz1 (-)
weight of the deviation from the orientation reference1.1qz2 (-)
weight of steering MPC error0.5qxst (-)
weight of the deviation from the steering angular velocity reference0.5qzst (-)
weight of the control input0.7r (-)
weight of control input in the steering MPC0.8rst (-)
Steering model parameters
first-order model: Tst0.012(s)
second-order model: ast1248.06(-)
second-order model: ast021,915.56(-)
second-order model: b21,851.67(-)
Table 2. Lateral and orientation error results—excluding steering dynamics.
Table 2. Lateral and orientation error results—excluding steering dynamics.
Speed (km/h)eavg (m)emax (m)ϕavg (deg)ϕmax (deg)
Simulation300.0780.1341.4374.183
400.0830.1601.2994.110
450.1610.5481.38213.486
Measurement300.100.201.664.97
400.110.231.465.36
450.152.841.8122.74
Table 3. Lateral and orientation error results—including first-order, second-order steering dynamics and cascade MPC.
Table 3. Lateral and orientation error results—including first-order, second-order steering dynamics and cascade MPC.
Speed (km/h) eavg (m)emax (m)ϕavg (deg)ϕmax (deg)
30 km/hSimulation—1TP0.0260.0541.5592.869
Measurement—1TP0.0160.0991.9234.203
Simulation—2TP0.0270.0551.4262.817
Measurement—2TP0.0250.1232.1034.343
Simulation—cascade0.0130.0441.3173.212
Measurement—cascade0.0310.0792.1374.147
40 km/hSimulation—1TP0.0250.0521.4542.664
Measurement—1TP0.0130.0881.7834.194
Simulation—2TP0.0220.0451.1902.426
Measurement—2TP0.0150.0971.9314.121
Simulation—cascade0.0220.0591.3633.567
Measurement—cascade0.0410.0911.9454.322
50 km/hSimulation—1TP0.0240.0501.3082.524
Measurement—1TP0.0110.0751.6733.764
Simulation—2TP0.0130.0330.8281.911
Measurement—2TP0.0160.0911.7713.880
Simulation—cascade0.0400.1261.0944.620
Measurement—cascade0.0570.1491.8774.811
55 km/hSimulation—1TP0.0280.0581.2072.506
Measurement—1TP0.0210.1321.5874.096
Simulation—2TP0.0060.0300.5692.446
Measurement—2TP0.0290.1951.6664.466
Simulation—cascade0.0530.3031.2246.534
Measurement—cascade0.0640.2181.7935.223
60 km/hSimulation—1TP0.0360.3321.1644.984
Measurement—1TP0.0410.5771.5017.844
Simulation—2TP0.0420.1950.8905.474
Measurement—2TP0.0370.3381.5826.761
Simulation—cascade0.0920.4481.2868.704
Measurement—cascade0.0590.2041.3864.288
Table 4. Turnaround time of the control model.
Table 4. Turnaround time of the control model.
Minimal (ms)Average (ms)Maximal (ms)
No steering dynamics0.19400.20590.2250
1TP steering model0.29190.30910.3328
2TP steering model0.29660.30950.3339
Cascade MPC0.29180.30580.3229
Disclaimer/Publisher’s Note: The statements, opinions and data contained in all publications are solely those of the individual author(s) and contributor(s) and not of MDPI and/or the editor(s). MDPI and/or the editor(s) disclaim responsibility for any injury to people or property resulting from any ideas, methods, instructions or products referred to in the content.

Share and Cite

MDPI and ACS Style

Domina, Á.; Tihanyi, V. Model Predictive Controller Approach for Automated Vehicle’s Path Tracking. Sensors 2023, 23, 6862. https://doi.org/10.3390/s23156862

AMA Style

Domina Á, Tihanyi V. Model Predictive Controller Approach for Automated Vehicle’s Path Tracking. Sensors. 2023; 23(15):6862. https://doi.org/10.3390/s23156862

Chicago/Turabian Style

Domina, Ádám, and Viktor Tihanyi. 2023. "Model Predictive Controller Approach for Automated Vehicle’s Path Tracking" Sensors 23, no. 15: 6862. https://doi.org/10.3390/s23156862

Note that from the first issue of 2016, this journal uses article numbers instead of page numbers. See further details here.

Article Metrics

Back to TopTop