Next Article in Journal
Bitcoin and Fiat Currency Interactions: Surprising Results from Asian Giants
Previous Article in Journal
Matching-Type Image-Labelings of Trees
 
 
Font Type:
Arial Georgia Verdana
Font Size:
Aa Aa Aa
Line Spacing:
Column Width:
Background:
Article

MPC Tracking Controller Parameters Impacts in Roundabouts

Department of Automotive Technologies, Budapest University of Technology and Economics, 1111 Budapest, Stoczek J. u. 6., Hungary
*
Authors to whom correspondence should be addressed.
Mathematics 2021, 9(12), 1394; https://doi.org/10.3390/math9121394
Submission received: 30 April 2021 / Revised: 8 June 2021 / Accepted: 11 June 2021 / Published: 16 June 2021
(This article belongs to the Section Dynamical Systems)

Abstract

:
The work is proposed to design a controller of the form known as the roundabout scenario trajectory tracking problem. The road condition is a four-leg, single-lane roundabout; the reference path is given. Due to the decision choice of exits, the MPC tracking controller is used to test the effect of weight parameter and target speed on the performance of the tracking controller. Two sets of test cases are proposed to make the experimental comparison, see the relationship between the control parameters and road conditions (different curvature path), and also see how the weight parameters Q and R and sample time affect the tracking performance. Our work, MPC controller utilization in a roundabout, plays an essential role with the increasing autonomy of vehicles.

1. Introduction and Motivation

Self-driving vehicles are now receiving more and more attention and research from academic and industrial communities and are maturing in various research directions. Many test conditions are most intensively studied in the highway scenario, while the work on roundabouts needs more time and effort to be further studied.
Linear model predictive control (LMPC) has been widely used in the industry and developed well. Due to tight performance specification demands in the academic and industry researching process, nonlinear model predictive control (NMPC) [1,2,3] plays a significant role. For example, NMPC is the main model that used in tracking ability testing [4]. Proposed dealing with fuzzy adaptive weight variables to fit the autonomous path tracking cost function with a refined model predictive control (MPC) controller. Considering the vehicle dynamic problem, the authors mainly focused on the tracking accuracy and driving comfort. The result was verified as a comparison study with classical MPC controller and pure-pursuit controller and showed a better tracking performance. Research work in [5] built an MPC simultaneous controller to reach the trajectory planning and tracking purpose. The novel idea of the optimization problem is to use an initial and intermediate two sets of variables to define the MPC control sequence and basic information of lane-change trajectories, including velocity. Unconstrained and constrained conditions with lane change to the left and right directions are all discussed intensely in the paper. An MPC controller was used to track piecewise clothoid trajectory in work [6]. In this method, the authors considered the ego car constraints, the yaw rate conditions, and the predefined boundary constraints. The proposed idea is based on the robust control invariant (RCI) system to ensure the boundaries and constraints are fully satisfied. Demonstrating the good tracking ability of NMPC, the authors presented their work as [1], which utilized lateral driving behavior with an NMPC controller. This method was transformed through a linear time-varying (LTV) MPC to control different constraints and vehicle conditions. Two different study cases verified the validity of the NMPC controller’s tracking ability and accuracy. The work in [7] calculated the ego car velocity and steering demand with a built nonlinear MPC controller framework. Using the genetic algorithms (GA) as an optimization solver, it met the flexible MPC structure requirement, and the proposed method provided the tracking accuracy based on different road conditions.
Different researchers have also studied MPC with different methods and purposes. A studied MPC controller dealt with changing the horizon parameter and illustrated the key point of selecting vehicle model and optimization solver [8]. Brake and steering behavior was tested with a designed MPC controller, changing over time as the ego car front-steering angle controller followed the predefined path [9]. The paper [10] studied steering behavior with the road surface conditions, used tire parameters as variables, and estimated the initial tire-force curve slope by the NMPC control method. In this case, the nonlinear tire curve was fully adapted by the proposed NMPC controller, leading the vehicle into a stable and well-adapted driving level. To avoid the computational difficulties, a single dimension artificial potential fields approach (SDAPF) was used to obtain the environments and build a convex quadratic programming (CQP)-based MPC controller [11]. Highway lane-merge action is also an important module in autonomous vehicle simulation and testing. Researchers developed a cooperative nonlinear MPC method implementing the lane merge scenario via ACADO code. The proposal of performance-cost function and the receding horizon was also validated in the numerical results of the paper [12].
There are few research-built MPC scheme applied to the roundabout road scenario. Our goal is building a MPC system both related to the global planner and local planner, applied to the whole roundabout scenario. In this case, the controller parameter tuning is an important issue.
Hypothesis 1.
A steady state of trajectory controller can be built and run out, fitting in the curvature and changing roundabout scenario cases.
Investigation novelty:
  • The ability of the MPC-optimization method for path tracking in the given roundabout environment is proven.
  • The relationship between MPC controller parameters and tracking performance based on roundabout road features is analyzed.
In this paper, our research is based on the roundabout global planner, which has been built to test the vehicle trajectory-tracking performance. We built an MPC tracking controller that can fit the roundabout scenario and track the continuous large curvature path smoothly. Roundabout road condition is a special case in urban scenarios. The key point of this paper is building the MPC model, which can connect to the roundabout global planner, and discussing the parameters of controller impacts on the tracking performance in a roundabout path. The optimization problem is set as a convex problem and is to be solved at each sample by an efficient quadratic programming (QP) method, the slack variable designed as a solver to the inequality constraints. Our work provides further analysis and development of applied mathematics to autonomous driving.
The remaining sections of this article are organized as follows: Section 2 describes the related work of the MPC design methodology and fundamental theory. This section gives a comprehensive and straightforward overview of MPC system from [13,14,15,16,17,18,19,20,21]. The MPC system-cost function and scenario constraints are described in Section 3. Section 4 presents the performance analysis of the proposed MPC parameters changing under various scenarios and discussion on the choice of MPC parameters for each roundabout scenario. Section 5 concludes the work with future direction.

2. Related Works

2.1. Vehicle Kinematics Model

Since the vehicle is not considered to be driven at high speed, the state, control, and reference vectors, respectively, are denoted as
[ X ˙ Y ˙ φ ˙ ] = [ c o s φ s i n φ t a n δ f / l ] v
The state of the model is ξ = [ X , Y , φ ] T , and the control quantity of the model is the steering angle of the front wheel, u = [ v , δ f ] T .

2.2. Model Predictive Control Fundamental Theory

Control system is the fundamental work for MPC. Special attention is given to the observer design in work [22]. The system model (1) obtained by kinematic modeling is a nonlinear system that cannot be directly used for linear time-varying model predictive control. The linearization of the nonlinear system needs to be performed first. As a widely used linearization method, Taylor series expansion can approximate the value at the operating point of the nonlinear system very well using polynomials.
Figure 1 illustrates the reference trajectory system and MPC trajectory tracking system relationship. The state ξ r e f is obtained from roundabout reference trajectory module as the waypoints X r e f , Y r e f , and the MPC system control inputs are the reference velocity V r e f . Assume that the state ξ r e f and control quantities u r e f at any given moment satisfy the following equations; k is the sampling instant,
ξ ˙ r e f ( k + 1 ) = f ( ξ r e f ( k ) , u r e f )
The above reference equation performs a Taylor expansion at the point ( ξ r e f , u r e f ) , ignoring the higher-order terms and retaining only the first-order terms
ξ ˙ = f ( ξ r e f , u r e f ) + J f ( ξ ) ( ξ ξ r e f ) + J f ( u ) ( u u r e f )
J f ( ξ ) and J f ( u ) are the Jacobi matrices of f concerning ξ and u , respectively. The equation after linearization is obtained as
ξ ˜ ˙ = A ( t ) ξ ˜ ( t ) + B ( t ) u ˜ ( t )
where ξ ˜ ( t ) = ξ ξ r e f , u ˜ ( t ) = u u r e f , A ( t ) = J f ( ξ ) , B ( t ) = J f ( u )
[ x ˙ x ˙ r e f y ˙ y ˙ r e f φ ˙ φ ˙ r e f ] = [ 0 0 v s i n φ 0 0 v c o s φ 0 0 0 ] [ x x r e f y y r e f φ φ r e f ] + [ c o s φ 0 s i n φ tan δ r l 0 v l cos 2 δ r ] [ v v r e f δ f δ r e f ]
After discretization, the system state can be represented as
A k , t = I + T A ( t ) B k , t = T B ( t )
I is the unit matrix and T is the discrete step length; k is the sampling instant. The results of the discretization using Euler’s method are
ξ ˜ ˙ ( k + 1 ) = A k , t ξ ˜ ( k ) + B k , t u ˜ ( k )
A k , t = I + T A ( t ) = [ 1 0 v s i n φ T 0 1 v c o s φ T 0 0 1 ] ,
B k , t = T B ( t ) = [ c o s φ T 0 c o s φ T 0 t a n δ f T l v T l c o s 2 δ f ]
And the observation equation represents as
η ( k ) = C k , t ,   ξ ˜ ( k )
C k , t = [ 1 0 0 0 1 0 0 0 1 ]
In the next process of designing the objective function, replacing the control with the control increment and adding the relaxation factor can directly restrict the control increment and prevent the situation that there is no feasible solution during the execution.
Setting new state variables as ξ ˜ ( k | t ) = [ ξ ˜ ( k | t ) u ( k 1 | t ) ] , the control variable from the previous moment is added to the state variable, and the control increment is used as the new control variable. According to the relationship between the control volume and the control increment, it is obtained that
ξ ^ ( k + 1 | t ) = A ˜ k , t , ξ ^ ( k | t ) + B ˜ k , t Δ u ( k | t ) η ( k | t ) = C ˜ k , t , ξ ^ ( k | t )
As given the system state quantity ξ ^ ( k | t ) and the control increment Δ u ( k | t ) at the moment t, the output quantity η ( k + 1 | t ) of the system (12) at the next moment can be calculated by equation, and the system output quantity in the prediction time domain can be obtained by continuously iterating the calculation, as
A k , t = A t , k = t , t + P B k , t = B t , k = t , t + P C k , t = C t , k = t , t + P
The output in P step represents in the following way:
η ( t + P | t ) = C ˜ t A ˜ p ξ ( t | t ) + C ˜ t A ˜ t B ˜ t Δ u ( t | t ) + + C ˜ t A ˜ t B ˜ t Δ u ( t + N | t )
The above calculation process between state, control, and output quantities in the predicted time domain can be organized as follows:
Y ( t ) = Ψ t ξ ^ ( t | t ) + Θ t Δ U ( t )
and the system predicts the output and input sequences as
Y ( t ) = [ η ( t + 1 | t ) η ( t + 2 | t ) η ( t + N | t ) η ( t + P | t ) ] ,
Δ U ( t ) = [ Δ u ( t | t ) Δ u ( t + 1 | t ) Δ u ( t + N | t ) ]
in this case, the prediction matrices can be expressed, respectively, as
Ψ t = [ c ˜ f A ˜ t c ˜ r A ˜ 2 c ˜ r A ˜ v c ˜ r A ˜ v ] ,
Θ t = ( c ˜ f , 0 0 0 C ˜ r A ˜ B ˜ t C ˜ r B ˜ t 0 C ˜ r A ˜ 1 B ˜ t C ˜ r A r B ˜ t C ˜ r B ˜ t C ˜ r A ˜ R 1 B ˜ t C ˜ r A ˜ t B ˜ t C ˜ r A ˜ R N 1 B ˜ t )

3. Model Predictive Control System

The essential point of MPC controller is to control the input by designing and solving the cost function. Minimizing the error between the future system output and the reference output obtains a stable vehicle state tracking system. As shown in Figure 2, the main steps of the model predictive control system are built. In this section, model calculation and optimization are the key content.

3.1. Objective Function

For the path tracking controller, the goal in this section is to follow the reference path quickly and stably, so the objective function is designed as follows:
J ( ξ ( t ) , u ( t 1 ) , Δ U ( t ) ) = i = 1 P η ( t + i | t ) η ref ( t + i | t ) 2 + i = 0 N 1 Δ u ( t + i | t ) 2 + ρ ε 2
The role of i = 1 P η ( t + i | t ) η ref ( t + i | t ) 2 is used to be the deviation between the state output of the predicted system and the reference system reference in the prediction horizon, reflecting the system’s tracking ability to the reference trajectory. i = 0 N 1 Δ u ( t + i | t ) 2 reflects the constraints on the control quantity, i.e., the smoothness of the control. By adjusting the weight matrices Q and R, the system can quickly and stably follow the reference trajectory. The slack variable is mainly to avoid the situation that there is no feasible set.

3.2. QP (Quadratic Programming) Standard Form Transformation

To solve the objective function and constraints upward, some corresponding matrices transform are needed, and let those functions turn to quadratic programming problem, which is easier to calculate.
m i n x 1 2 x T H x + f T x
s u c h   t h a t { A x b A e q x = b e q l b x u b
H is the positive definite Hessian matrix; A , b are the inequality constraint matrices of the control variables; A e q and b e q are the equation constraint matrices of the control variables; l b , u b are the upper and lower constraints of the control variables, respectively.
Define the deviation of the output quantity in the predicted horizon with
E ( t ) = Ψ t ξ ^ ( t | t ) Y r ( t )
where the reference value Y r e f ( t ) = [ η r e f ( t + 1 | t ) , η r e f ( t + P | t ) ] . Substituting (23) into (20), the function is transformed as
J ( ξ ^ ( t ) ) , u ( t 1 ) , Δ U ( t ) ) = [ Δ U ( t ) T , ε ] H t [ Δ U ( t ) T , ε ] T + G t [ Δ U ( t ) T , ε ] T + P t
where
H t = [ Θ t T Q e Θ t + R e 0 0 ρ ]
G t = [ 2 E ( t ) T Q e Θ t 0 ]
P t = E ( t ) T Q e E ( t )
Q e and R e are expanded forms of the weight matrices Q and R , respectively.
Q e = [ Q P × P 0 P × P 0 P × P 0 P × P Q 0 P × P 0 P × P 0 P × P 0 P × P Q ] P × P
R e = [ R u × u 0 u × u 0 u × u 0 u × u R 0 u × u 0 u × u 0 u × u 0 u × u R ] u × u
The final form of the objective function is described in the following way:
J ( ξ ^ ( t ) , u ( t 1 ) , Δ U ( t ) ) = Δ U ^ ( t ) H t Δ U ˜ ( t ) T + G t Δ U ˜ ( t ) T
where
Δ U ˜ ( t ) = [ Δ U ( t ) T , ε ] T

3.3. Constraints Setting

The constraints adopted MPC controller are mainly set in three aspects, respectively:
  • Control constraints
u m i n ( t + k ) u ( t + k ) u m a x ( t + k ) , k = 0 , 1 , , N
  • Control incremental constraints
Δ u m i n ( t + k ) Δ u ( t + k ) Δ u m a x ( t + k ) , k = 0 , 1 , , N
  • Output constraints
y m i n ( t + k ) y ( t + k ) y m a x ( t + k ) , k = 0 , 1 , , N
The above three constraints need to be transformed according to the standard form. The relationship between the control quantity and the control increment can be described as (35)
u ( t + k ) = u ( t + k 1 ) + Δ u ( t + k )
In the prediction horizon, we can obtain the Equation (36), and 1 N is the N-dimensional column vectors with elements of 1, L N is the N-dimensional all-one lower triangular matrix, I u is the unit matrix with the same dimension as the control variable dimension, and is the Kronecker product.
[ u t | t u t + 1 | t u t + N | t ] = [ u t 1 u t 1 u t 1 ] + [ Δ u t | t Δ u t | t + Δ u t + 1 | t Δ u t | t + Δ u t + 1 | t + + Δ u t + N | t ] = 1 N u t 1 + L N I u Δ U ( t )
Finally, the constraint (32) can be transformed as:
U m i n A Δ U t + U t 1 U m a x A = L N I u U t 1 = 1 N u t 1
constraint (34) can be illustrated as:
Y m i n Ψ t ξ ( t | t ) + Θ t Δ U ( t ) Y m a x
Calculate the Kronecker product of matrices A and B, and combine with the optimization formulation we mentioned at (30),
A c o n s Δ U ˜ t b c o n s A c o n s = [ A 0 u × N , u × N A 0 u × N , u × N Θ t Θ t 0 u × N , u × N ] , B c o n s = [ U m a x U t 1 U m i n + U t 1 Y m a x Ψ t ξ ( t | t ) Y m i n + Ψ t ξ ( t | t ) ]
Equation (39) can be the constraints (33), and M is the upper bound of the slack variable ε.
l b Δ U ˜ t u b l b = [ Δ U m i n ; 0 ] , u b = [ Δ U m a x ; M ]

3.4. Geometric Constraints for Vehicles and Structured Roads

Based on the real vehicle steering demand and the roundabout road constraints, the system needs to follow three constraints:
To restrict the lateral stability of the vehicle, predefine the turning angle as ±0.25 rad , the front-wheel steering angle constraint is
0.25 δ f 0.25
Considering the ego car safety and comfort, the lateral acceleration set in the range of [−1,1],
1   m / s 2 < v ˙ l a < 1   m / s 2
To assure vehicles are driving inside the road, the feasible domain boundary in the road coordinate system is predefined in constraints setting at a half-car width away from the edge of the road.
( S L m i n W c 2 ) S L ( S L m i n + W c 2 )
S L m a x / S L m i n are the maximum and minimum offsets of the road edges, and W c set as the vehicle width.

4. Experimental Results

In this section, the model predictive controller performance is validated through coding in MATLAB 2017b, and the quadratic programming problem is run by MATLAB quadprog solver. Two road conditions are carried out and used to determine N p and N c parameter values after many tests. Taking the initial control parameters N p = 60, N c = 30, and T = 0.027 s, the target speed takes 50 km/h. This work sets a simple PI controller to drive the longitudinal speed.
Case 1 tests the MPC performance while changing the weight parameters Q and R; Case 2 makes the MPC performance comparison of only changing the target speed and tuning the sample time corresponding to the different speed.

4.1. Case 1. Fourth-Leg Enter, Second-Leg Exit

Case 1 tracks the path through the fourth-leg enter area and second-leg exit area and tests the MPC performance while changing the weight parameters Q and R, as shown in Table 1. Changing three sets of weight parameters alters the tracking performance. Figure 3 shows the tracking route used to change the weight parameter Q and the weight parameter R.
The tracking controller performs well when the ego vehicle is going along the straight road and stable curvature curve area. The tracking performance is altered mainly in the two merging zones of the roundabout. Both Figure 4a,b emphasize their tracking differences on the lateral axis when the ego car is approaching the roundabout merging zones. When changing the parameter R, the blue line (Q = 40, R = 0.8) in Figure 4a is the most stable line and is also closer to the reference trajectory. Figure 4b demonstrates that the pink line, Q = 80, R = 0.8, is the most stable tracking route even in the merging zones. The specific tracking error on longitudinal and later directions are shown in Figure 5a,b.
Figure 5a,b are the steady-state errors in longitudinal direction, lateral position, and yaw angle. The idea of the steady-state errors is consistent with the literature [21].
Since the value of errors were positive, the ego car started measurement of yaw angle at the beginning of the simulation, while the longitudinal axis of the actual vehicle was pointing to the right.
At the end of the following path, the ego car was actually on a straight path, as demonstrated clearly by the shape of the lateral position plotting and zero steering angle. Furthermore, the measured yaw angle can be seen as the orientation error, both illustrated in Figure 5a,b.
Figure 6a,b show the vehicle tracking heading performance and the longitudinal velocity. The yaw rate changes rapidly when passing through the curve area.

4.2. Case 2. Fourth-Leg Enter, Third-Leg Exit

Case 2 tracks the path through the fourth-leg enter area and third-leg exit area and tests the MPC performance while changing the target speed and sample time T. Figure 7 shows the Case 2 tracking route used to change the target speed and sample time. Two scenario sets are tested in Case 2. As Table 2 shows, tests 1–4 change the vehicle target speed without tuning the sample time, and tests 5–8 adjust the vehicle target speed and the sample time to reach the trajectory tracking purpose.
Figure 8a,b show the tracking route after changing the weight parameter Q and the weight parameter R.
The tracking controller did not perform well in the case of only changing the speed-related parameters. The tracking performance was altered from the first merging zone of the roundabout. The yellow line (target speed 50 km/h) reached the destination first, but the tracking error was significant. Even after changing the target speed, the controller did not reach the destination as planned. When the target speed decreased, the pink line test set (target speed 35 km/h) did not reach the final destination. However, after tuning the sample time T, the test sets all cleared the final goal successfully, as shown in Figure 8b. The specific tracking error on longitudinal and later directions are shown in Figure 9a,b.
Figure 10a,b are the vehicle tracking heading performance and the longitudinal velocity. The yaw rate changes rapidly when passing through the curve area.

5. Conclusions and Future Works

In this work, an MPC controller is designed for path tracking purposes, and it is validated that the proposed MPC controller can fully track the given path in roundabouts. Case 1 and Case 2 used the same set of control horizons parameters; however, the case 2 tracking performance was not as advantageous as the Case 1 road condition. Prediction horizon and control horizon parameters need to be tuned according to the reference path curvature. Weight parameters Q, R did affect the tracking performance significantly when changing the target speed. Sample time T did not greatly affect the tracking performance.
In this work, we present a novel combination of MPC scheme and roundabout condition considering the effects of road constraints. Accounting for the effect of path curvature, a single-track vehicle model is derived. In the future, our research would like to enable collision avoidance and improve the prediction accuracy in the short-term.
Managing a MPC system from Matlab coding for real practice is also a future challenge for us. Simulations carried out in the MATLAB/CarSim environment validated the effectiveness and real-time ability of the proposed scheme. In the case of our study, it seems programming the algorithm in Matlab and then simulating the MPC system for verification is a method for practice. Setting up the compilation environment for C/C++ is achieved by creating an S-function file in Matlab. Once the requirements are met, it can be combined with software such as Carsim and connected to the automation hardware controller module for real vehicle tests. If the simulation results verify the positive real-time performance of the designed control system in engineering applications, the robustness in trajectory tracking performance and the effectiveness in lateral stability can be verified as well; then, a real-world test with a real vehicle should be carried out in the near future. In this case, the calculated output is sent to the simulator, which, in practice, would be sending signals to the steering wheel and pedals. There are also predicted track points as output to the simulator. In the near future, the work should continue to contribute to applied mathematics and autonomous vehicle aspects.

Author Contributions

Conceptualization, H.C.; software, H.C.; formal analysis, H.C.; investigation, H.C.; writing—original draft preparation, H.C.; writing—review and editing, H.C. and M.Z.; supervision, M.Z.; project administration, M.Z. All authors have read and agreed to the published version of the manuscript.

Funding

This research received no external funding.

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. Ming, T.; Deng, W.; Zhang, S.; Zhu, B. MPC-Based Trajectory Tracking Control for Intelligent Vehicles. In Proceedings of the SAE 2016 World Congress & Exhibition—Society of Automotive Engineers, Detroit, MI, USA, 12–14 April 2016; SAE Technical Paper Series. SAE International: Miami, FL, USA, 2016. [Google Scholar]
  2. Henson, M.A. Nonlinear model predictive control: Current status and future directions. Comput. Chem. Eng. 1998, 23, 187–202. [Google Scholar] [CrossRef]
  3. Allgöwer, F.; Findeisen, R.; Nagy, Z. Nonlinear Model Predictive Control: From Theory to Application. J. Chin. Inst. Chem. Eng. 2004, 35, 299–315. [Google Scholar]
  4. Wang, H.; Liu, B.; Ping, X.; An, Q. Path Tracking Control for Autonomous Vehicles Based on an Improved MPC. IEEE Access 2019, 7, 161064–161073. [Google Scholar] [CrossRef]
  5. Guo, H.; Shen, C.; Zhang, H.; Chen, H.; Jia, R. Simultaneous Trajectory Planning and Tracking Using an MPC Method for Cyber-Physical Systems: A Case Study of Obstacle Avoidance for an Intelligent Vehicle. IEEE Trans. Ind. Inform. 2018, 14, 4273–4283. [Google Scholar] [CrossRef]
  6. Di Cairano, S.; Kalabic, U.; Berntorp, K. Vehicle tracking control on piecewise-clothoidal trajectories by MPC with guaranteed error bounds. In Proceedings of the 2016 IEEE 55th Conference on Decision and Control (CDC), Las Vegas, NV, USA, 12–14 December 2016; pp. 709–714. [Google Scholar] [CrossRef]
  7. Du, X.; Htet, K.K.K.; Tan, K.K. Development of a Genetic-Algorithm-Based Nonlinear Model Predictive Control Scheme on Velocity and Steering of Autonomous Vehicles. IEEE Trans. Ind. Electron. 2016, 63, 6970–6977. [Google Scholar] [CrossRef]
  8. Quirynen, R.; Berntorp, K.; Di Cairano, S. Embedded Optimization Algorithms for Steering in Autonomous Vehicles based on Nonlinear Model Predictive Control. In Proceedings of the 2018 Annual American Control Conference (ACC), Milwaukee, WI, USA, 27–29 June 2018; pp. 3251–3256. [Google Scholar]
  9. Falcone, P.; Borrelli, F.; Asgari, J.; Tseng, H.E.; Hrovat, D. A model predictive control approach for combined braking and steering in autonomous vehicles. In Proceedings of the 2007 Mediterranean Conference on Control & Automation, Athens, Greece, 27–29 June 2007; pp. 1–6. [Google Scholar] [CrossRef]
  10. Berntorp, K.; Quirynen, R.; Di Cairano, S. Steering of Autonomous Vehicles Based on Friction-Adaptive Nonlinear Model-Predictive Control. In Proceedings of the 2019 American Control Conference (ACC), Philadelphia, PA, USA, 10–12 July 2019; pp. 965–970. [Google Scholar] [CrossRef]
  11. Jiang, H.; Wang, Z.; Chen, Q.; Zhu, J. Obstacle avoidance of autonomous vehicles with CQP-based model predictive control. In Proceedings of the 2016 IEEE International Conference on Systems, Man, and Cybernetics (SMC), Budapest, Hungary, 9–12 October 2017; pp. 001668–001673. [Google Scholar] [CrossRef]
  12. Hussain, S.A.; Jahromi, B.S.; Cetin, S. Cooperative Highway Lane Merge of Connected Vehicles Using Nonlinear Model Predictive Optimal Controller. Vehicles 2020, 2, 249–266. [Google Scholar] [CrossRef] [Green Version]
  13. Mathworks. Model Predictive Control Toolbox. Available online: https://www.mathworks.com/help/mpc/ug/choosing-sample-time-and-horizons.html (accessed on 15 June 2021).
  14. Zak, S.H. An Introduction to Model-Based Predictive Control (MPC). Available online: https://engineering.purdue.edu/~zak/ECE680/MPC_handout.pdf (accessed on 15 June 2021).
  15. Wikipedia. Model Predictive Control. Available online: https://en.wikipedia.org/wiki/Model_predictive_control (accessed on 15 June 2021).
  16. Németh, B.; Gáspár, P.; Hegedűs, T. Optimal Control of Overtaking Maneuver for Intelligent Vehicles. J. Adv. Transp. 2018, 2018, 1–11. [Google Scholar] [CrossRef]
  17. Lin, F.; Chen, Y.; Zhao, Y.; Wang, S. Path tracking of autonomous vehicle based on adaptive model predictive control. Int. J. Adv. Robot. Syst. 2019, 16. [Google Scholar] [CrossRef]
  18. Kalman, R.E. When is a Linear Control System Optimal? J. Basic Eng. 1964, 86, 51–60. [Google Scholar] [CrossRef]
  19. Mizushima, Y.; Okawa, I.; Nonaka, K. Model Predictive Control for Autonomous Vehicles with Speed Profile Shaping. IFAC-PapersOnLine 2019, 52, 31–36. [Google Scholar] [CrossRef]
  20. Babu, M.; Oza, Y.; Singh, A.K.; Krishna, K.M.; Medasani, S. Model Predictive Control for Autonomous Driving Based on Time Scaled Collision Cone. In Proceedings of the 2018 European Control Conference (ECC), Limassol, Cyprus, 12–15 June 2018; pp. 641–648. [Google Scholar] [CrossRef] [Green Version]
  21. Falcone, P.; Borrelli, 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]
  22. Mercorelli, P. Trajectory tracking using MPC and a velocity observer for flat actuator systems in automotive applications. In Proceedings of the 2008 IEEE International Symposium on Industrial Electronics, Cambridge, UK, 30 June–2 June 2008; pp. 1138–1143. [Google Scholar]
Figure 1. Model predictive control trajectory tracking system scheme.
Figure 1. Model predictive control trajectory tracking system scheme.
Mathematics 09 01394 g001
Figure 2. The flowchart of MPC tracking system steps.
Figure 2. The flowchart of MPC tracking system steps.
Mathematics 09 01394 g002
Figure 3. Fourthleg enter, second-leg exit MPC tracking route.
Figure 3. Fourthleg enter, second-leg exit MPC tracking route.
Mathematics 09 01394 g003
Figure 4. (a) Shows the tracking difference with reference path after changing the weighting parameter R; Q = 40, R = 0.8 achieves the best performance. (b) Compares yaw angle after changing the weighting parameter Q; those performances look similar, but the pink line (Q = 80, R = 0.8) is still closer to the red reference line.
Figure 4. (a) Shows the tracking difference with reference path after changing the weighting parameter R; Q = 40, R = 0.8 achieves the best performance. (b) Compares yaw angle after changing the weighting parameter Q; those performances look similar, but the pink line (Q = 80, R = 0.8) is still closer to the red reference line.
Mathematics 09 01394 g004
Figure 5. (a) Shows the comparison of trajectory errors after changing the weighting parameter R; Q = 40, R = 0.8 still achieves the best performance. (b) Compares trajectory errors after changing the weighting parameter Q; Q = 500, R = 0.8 still achieves the best performance.
Figure 5. (a) Shows the comparison of trajectory errors after changing the weighting parameter R; Q = 40, R = 0.8 still achieves the best performance. (b) Compares trajectory errors after changing the weighting parameter Q; Q = 500, R = 0.8 still achieves the best performance.
Mathematics 09 01394 g005
Figure 6. (a) Shows the comparison of yaw rate after changing the weighting parameter R; Q = 40, R = 0.8 still achieves the best performance. (b) Shows the comparison of yaw rate after changing the weighting parameter Q; Q = 50, R = 0.8 still achieves the best performance.
Figure 6. (a) Shows the comparison of yaw rate after changing the weighting parameter R; Q = 40, R = 0.8 still achieves the best performance. (b) Shows the comparison of yaw rate after changing the weighting parameter Q; Q = 50, R = 0.8 still achieves the best performance.
Mathematics 09 01394 g006
Figure 7. Fourth-leg enter, third-leg exit MPC tracking route.
Figure 7. Fourth-leg enter, third-leg exit MPC tracking route.
Mathematics 09 01394 g007
Figure 8. (a) Shows the tracking difference with the reference path after changing the target speed. (b) Shows the tracking difference with reference path after changing the target speed and the sample time T tuning condition.
Figure 8. (a) Shows the tracking difference with the reference path after changing the target speed. (b) Shows the tracking difference with reference path after changing the target speed and the sample time T tuning condition.
Mathematics 09 01394 g008
Figure 9. (a) Shows the comparison of trajectory errors after changing the target speed. (b) Compares trajectory errors after changing the target speed and the sample time T tuning condition.
Figure 9. (a) Shows the comparison of trajectory errors after changing the target speed. (b) Compares trajectory errors after changing the target speed and the sample time T tuning condition.
Mathematics 09 01394 g009
Figure 10. (a) Shows the comparison of yaw rate after changing the target speed. (b) Compares yaw rate after changing the target speed and the sample time T tuning condition.
Figure 10. (a) Shows the comparison of yaw rate after changing the target speed. (b) Compares yaw rate after changing the target speed and the sample time T tuning condition.
Mathematics 09 01394 g010
Table 1. Fourth-leg enter, second-leg exit MPC tracking changing parameters.
Table 1. Fourth-leg enter, second-leg exit MPC tracking changing parameters.
Case 1 Parameters
No. of Test CasesTest DescriptionNpNcT (s)QRTarget Speed (km/h)
1Scenario 1 change R weighting parameter60300.027400.850
260300.027408050
360300.02740800050
4Scenario 1 change Q weighting parameter60300.027800.850
560300.0275000.850
660300.0270.50.850
Table 2. Fourth-leg enter, third-leg exit MPC tracking changing parameters.
Table 2. Fourth-leg enter, third-leg exit MPC tracking changing parameters.
Case 2 Parameters
No. of Test CasesTest DescriptionNpNcT (s)QRTarget Speed (km/h)
1Scenario 2 change target speed, no change on sample time T60300.027100150
260300.027100145
360300.027100140
460300.027100135
5Scenario 2 change target speed and sample time T60300.0155100150
660300.0173100145
760300.0195100140
860300.0223100135
Publisher’s Note: MDPI stays neutral with regard to jurisdictional claims in published maps and institutional affiliations.

Share and Cite

MDPI and ACS Style

Cao, H.; Zoldy, M. MPC Tracking Controller Parameters Impacts in Roundabouts. Mathematics 2021, 9, 1394. https://doi.org/10.3390/math9121394

AMA Style

Cao H, Zoldy M. MPC Tracking Controller Parameters Impacts in Roundabouts. Mathematics. 2021; 9(12):1394. https://doi.org/10.3390/math9121394

Chicago/Turabian Style

Cao, Hang, and Mate Zoldy. 2021. "MPC Tracking Controller Parameters Impacts in Roundabouts" Mathematics 9, no. 12: 1394. https://doi.org/10.3390/math9121394

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