中南大学学报(英文版)

J. Cent. South Univ. (2020) 27: 3702-3720

DOI: https://doi.org/10.1007/s11771-020-4561-1

MPC-based path tracking with PID speed control for high-speed autonomous vehicles considering time-optimal travel

CHEN Shu-ping(陈舒平)1, XIONG Guang-ming(熊光明)1, CHEN Hui-yan(陈慧岩)1, NEGRUT Dan2

1. School of Mechanical Engineering, Beijing Institute of Technology, Beijing 100081, China;

2. Department of Mechanical Engineering, University of Wisconsin-Madison, Madison, WI 53706, USA

Central South University Press and Springer-Verlag GmbH Germany, part of Springer Nature 2020

Abstract:

In order to track the desired path as fast as possible, a novel autonomous vehicle path tracking based on model predictive control (MPC) and PID speed control was proposed for high-speed automated vehicles considering the constraints of vehicle physical limits, in which a forward-backward integration scheme was introduced to generate a time-optimal speed profile subject to the tire-road friction limit. Moreover, this scheme was further extended along one moving prediction window. In the MPC controller, the prediction model was an 8-degree-of-freedom (DOF) vehicle model, while the plant was a 14-DOF vehicle model. For lateral control, a sequence of optimal wheel steering angles was generated from the MPC controller; for longitudinal control, the total wheel torque was generated from the PID speed controller embedded in the MPC framework. The proposed controller was implemented in MATLAB considering arbitrary curves of continuously varying curvature as the reference trajectory. The simulation test results show that the tracking errors are small for vehicle lateral and longitudinal positions and the tracking performances for trajectory and speed are good using the proposed controller. Additionally, the case of extended implementation in one moving prediction window requires shorter travel time than the case implemented along the entire path.

Key words:

model predictive control; path tracking; minimum-time speed profile; vehicle dynamics; arbitrary path

Cite this article as:

CHEN Shu-ping, XIONG Guang-ming, CHEN Hui-yan, NEGRUT Dan. MPC-based path tracking with PID speed control for high-speed autonomous vehicles considering time-optimal travel [J]. Journal of Central South University, 2020, 27(12): 3702-3720.

DOI:https://dx.doi.org/https://doi.org/10.1007/s11771-020-4561-1

1 Introduction

With the rapid development of software and hardware on sensors, computers and control technology, autonomous vehicles have received significant progress during last decades. The time of daily commuters’ traversal and the improvement of traffic safety will be the benefit from automated driving [1, 2]. The motion control of self-driving vehicles can be divided into path planning and path tracking, in which the path planning generates the desired path (desired position and heading) using data from the perception system, while the path tracking controller calculates the steering maneuvers to guide the vehicle following the reference path [3, 4].

In the literature concerning path planning, many researches have been dedicated to feasible and efficient methods for path planning. Early researches used graph search-based planners to generate the shortest path on discretized environment graphs for real-time implementation, such as Dijkstras algorithm [5], A-Star (A*) algorithm and its variants [6, 7] and the state lattices algorithm [8]; Interpolating curve planners including polynomial curves, spline curves, Clothoid curves and Bezier curves have been also utilized for online path planning. Both planners have advantages of low computational burden, but cannot easily consider the constraints of vehicle dynamics during path planning [1]. Sampling-based planners which are also proper approaches to generate trajectories for both non-holonomic and holonomic systems, have attracted intense interest in recent years, for example, the probabilistic road maps (PRM) [9] and the rapidly-exploring random trees (RRT) [10]. Additionally, trajectory optimization based method has also become increasingly popular in path planners due to its core idea of formulating path planning as an optimization problem considering desired vehicle performance and constraints [11]. A thorough comparison of benefits and drawbacks among those planning techniques applied in autonomous driving scenarios was presented in Ref. [12]. Traditionally, a complete trajectory from a start point to a target one can be solved using trajectory optimization-based methods. However, it is difficult to predict the driving environment due to the dynamic and stochastic characteristics. Therefore, model predictive control approaches are popularized for online path planning recently, which deal with the sequence finite horizon optimization problems in a receding manner and consider updating the environmental and vehicle states during the planning process [1, 13, 14].

The path tracking aims to navigate the vehicle along the desired position and orientation using automated steering maneuvers. To this end, various controller in the literature have been designed with PID control [15, 16], optimal control [17, 18], backstepping and sliding mode control [19, 20], etc. However, the constraints of actuators and vehicle states were not taken into consideration. MPC-based controller, characterized by its optimization in a receding horizon manner, is capable of dealing with this problem while considering the input and output constraints [21]. Numerous research studies indicate that the MPC algorithm is good at dealing with trajectory tracking problems with safety and actuator constraints [22, 23]. Some studies utilized the MPC-based controller for path tracking considering the vehicle stability and environment constraints [24], or considering the yaw stability constraint for obstacle avoidance[25]; Some studies converted the nonlinear model predictive control (NMPC) into linear model predictive control (LMPC) to formulate the path tracking control problem in order to reduce the computational burden [26]. Moreover, a dual-envelop-oriented trajectory tracking method and a LMPC algorithm considering the constraints of road boundaries and actuator saturation were employed in Ref. [27] to design the path following controller with varied sample time and varied prediction horizon. A cascaded kinematic MPC-PID controller with vehicle sideslip angle compensation was introduced in Ref. [28] to tackle the path tracking problem for high-speed autonomous vehicles, in which compared with classic MPC controller, the desired yaw rate rather than steering angle was generated as the reference to be followed. However, most of the studies assumed the speed was constant so that the longitudinal and lateral control can be dealt with in a decoupled way [29]. The automobile is a complex system with strong coupling effects among different motion directions. Therefore, it is important to consider a combined longitudinal and lateral controller and a time-varied longitudinal velocity for path tracking to improve the performance [30].

To track the desired trajectory as fast as possible, it is important to investigate the minimum-time (i.e., time-optimal) trajectory generation for self-driving vehicles, which is actually an aspect of path planning. Efforts on the minimum-time trajectory solutions date back to 1696 when Johann Bernoulli introduced the Brachistochrone curve problem. Despite little concern with this ancient problem nowadays, calculating faster trajectory is of significant benefits to winning competitions, intercepting enemies and aiding those in need more quickly, etc. Additionally, many researches have been devoted to solving minimum-time problems in the field of robots as well owing to their high-performance achievement and maximized production [31, 32].

As a matter of fact, the minimum-time trajectory generation belongs to optimal control problem. Therefore, many methods developed for optimal control are utilized to solve minimum-time problem, one of which arising from initial solutions to the Brachistochrone problem is the calculus of variations serving as the basis for many other approaches. Nonlinear programming (NP) as an alternative approach is also utilized to handle trajectory generation problems, evolving from which the pseudospectral approach uses Legendre or similar polynomials as functions to solve the time-optimal problem. But the above approaches are hindered by the constraints of exact path tracking and calculating speed [31]. Other methods, such as Dijkstras algorithms, A*, PRM and RRT that mentioned before, are useful to produce collision-free trajectories in the environment of many static obstacles without considering vehicle dynamics. Those trajectories then need to be evaluated and compared to find the one with minimum-time traversal [31].

For minimum-time trajectory generation over a predefined path, the problem can be transformed into generating a time-optimal longitudinal speed profile considering vehicle dynamics. In Ref. [31], valid speed regions were determined using vehicle dynamics based on a transformation method introduced by BOBROW et al [33], in which the prespecified trajectory was reparameterized using the distance travelled along the path and the goal was then converted to generate feasible speed profile along the newly parameterized path within the maximum longitudinal velocity regions. Recent research observed that the velocity profile was convex for a six-degree-of-freedom robotic manipulator using this transformation. Therefore, the time-optimal problem can be dealt with many convex optimization tools, which significantly improved the flexibility and efficiency of this formulation and provided guarantees on basic optimality [34, 35]. In addition to convex formulations, alternative methods have also been investigated, for instance, differentially flat formulations which allow considering a broader type of vehicle models, but lose the advantages leveraged from convex optimization [36].

For high-speed autonomous vehicles, e.g., a self-driving racing car, the problem of minimum lap time trajectory generation is usually tackled with numerical optimization in the literature. Several publications indicated that realistic results were produced using numerical techniques in the process of optimization due to the capability of incorporating accurate and high order dynamic models, which were actually comparable to the results measured from expert race drivers [37, 38]. However, numerical optimization methods are not proper for real-time implementation, because they require intensive computational expense and cannot be easily used in unpredictable environmental situation. Early researches presented a solution for minimum-time trajectory in vehicle lane change maneuver using coupled differential equations and Pontryagin’s minimum principle [39]; Motivated by intense interest in the minimum-time problem from professional racing teams, a planning method generating the optimized path and longitudinal velocity profile simultaneously was proposed in Ref. [40] using NP solution method based on nonlinear vehicle dynamics model; Then, the physical effect of tire thermodynamics was considered in Ref. [41] utilizing more robust NP approach, e.g., sequential quadratic programming (SQP), to further extend the results in Ref. [40]; More recently, a gradient descent approach was proposed in Ref. [42] to calculate time-optimal racing lines composed of certain number of clothoid segments; The MPC algorithm was also formulated to solve minimum-time trajectory problems using linearized vehicle dynamics model at each sampling and the objective of time-optimal traversal was approximated by maximizing the distance travelled along the trajectory [43, 44]; However, one obvious disadvantage of the MPC method is that the minimum time optimization problems need to be reconstructed and solved during each step, which is still computationally intensive. Therefore, it is beneficial to develop a real-time trajectory generation algorithm for high-speed autonomous vehicles considering minimum lap time.

To this end, the computational burden shown in Ref. [45] was significantly reduced by a combined use of the curvilinear frame, nonstiff vehicle dynamics and the computer-generated analytical derivatives; In Ref. [46], the problem of combined longitudinal and lateral optimal control was transformed into two sequential subproblems, in which the time-optimal speed profile was determined using a forward-backward integration scheme for a given fixed reference path, then the vehicle’s trajectory was optimized and updated given the fixed longitudinal velocity and this two-step algorithm was repeated until the calculated time attained a minimum value; Using complex vehicle dynamics model to prevent rollover and excessive sideslip, a real-time path planning method was presented in Ref. [47] for high-speed automated ground vehicles to avoid hazard situations on rough terrain, in which the computational cost was reduced by choosing avoidance maneuver from offline precalculated database; A hierarchical model predictive controller was proposed in Ref. [48] for trajectory generation and tracking via active front steering, which omitted the computational delay to react more quickly to the environment changes. A preview steering control algorithm was presented in Ref. [49] for path tracking, in which less computational load was required to achieve tracking accuracy and smoothness compared with the MPC method. Given the vehicle dynamic characteristics, an approach of generating minimum-time velocity profile was proposed in Ref. [50] to investigate the time-optimal solution for high-speed autonomous vehicles, which used a separation of geometric problems from the dynamic optimization problems [51] and implemented the optimal speed profile generation in a receding horizon manner; Based on the path-velocity decomposition approach [52] and the iterative steering technique [53], the problem of minimum-time longitudinal velocity planning was addressed in Ref. [54] for a robot vehicle navigating on a prespecified path of given length, in which the algebraic solution demonstrated that the minimum-time speed planning problem can be converted to the problem of calculating real roots of a quartic equation and consequently facilitated the real-time implementation. A fast and direct solution for time-optimal velocity planning problem was proposed in Ref. [55] for a wheeled automated vehicle concerning high curvature and speed, based on a curvilinear discretization which was suitable for real-time application and consideration of the velocity limit, maximum longitudinal and centripetal accelerations.

In this paper, a novel trajectory tracking and speed control strategy is proposed using MPC-based controller and PID speed control embedded in the model predictive control framework. Furthermore, the problem of generating time-optimal speed profile for a given predefined trajectory is addressed using a forward-backward integration approach introduced in Ref. [46]. Given the road points, the curvature along the reference path was approximated and a refined trajectory was generated, based on which a minimum-time speed profile was then designed. The forward-backward integration scheme was further extended to generate a sequence of time-optimal longitudinal velocity profiles in one moving prediction window. The speed profile and control framework were formulated in the curvilinear frame to explicitly acquire the vehicle position at each sampling instant while maintain consideration of the time-varying longitudinal velocity. In the lateral controller design, a sequence of optimal steering angles is generated using MPC algorithm, while the total wheel torque is generated using PID controller for the longitudinal control. Moreover, the proposed MPC-based controller is implemented considering the desired trajectory as the arbitrary curves of continuously varying curvature. The main contributions of this paper are given as:

1) A novel MPC-based path tracking with PID speed control strategy considering a time-varied speed and the coupling of lateral and longitudinal vehicle dynamics is proposed to simultaneously track the reference path and speed, which utilizes LMPC algorithm to reduce the computation load and therefore facilitates the real-time performance.

2) With respect to the time-optimal velocity profile, the forward-backward integration algorithm introduced in Ref. [46] is further extended to implement the speed profile generation and tracking control in one moving prediction windows, which allows the algorithm to update the reference speed profile according to the changes from local path planning in the case of obstacle avoidance.

3) A double-track 8-DOF model considering roll dynamics is employed as the prediction model and a 14-DOF model with high-fidelity is utilized as the plant to formulate the MPC algorithm, which can be future considered for the investigation on path tracking considering lateral and roll stability for high-speed automated vehicles.

The rest of this paper is organized as follows: In Section 2, the development of vehicle dynamics models is described; In Section 3, the method of generating approximated curvature and refined reference trajectory based on given road points was presented and a scheme of minimum-time speed profile generation given a fixed path was also introduced; In Section 4, the lateral control and the longitudinal control were specified; In Section 5, the proposed controller for combined longitudinal and lateral control was implemented in MATLAB considering the desired trajectory to be arbitrary curves of continuously varying curvature; In Section 6, the paper was wrapped up and the future work was outlined.

2 Vehicle models for control synthesis

A brief introduction for the development of vehicle dynamics models is presented in this section before specifying the combined lateral and longitudinal controller design. These models are also specified in our previous work in Ref.[56].

2.1 Tire model

The forces affecting the behavior of a vehicle mainly result from tires except for aerodynamics and gravity. In physical world, the vehicle tire exhibits strong nonlinear and coupling performance which makes it difficult to be modeled. However, if the tire slip angle and longitudinal slip ratio are bounded within small region, the tire model can be regarded as a linearized model to generate lateral and longitudinal forces [25, 56, 57].

2.2 8-DOF vehicle model

An 8-DOF vehicle model with lateral, longitudinal, yaw and roll DOFs and 4 DOFs for each wheel rotational dynamics is employed as the prediction model [56, 58]. The 8-DOF vehicle dynamics model is shown in Figure 1.

Figure 1 8-DOF vehicle model [56, 58]

The equations for the 8-DOF model according to Newton’s laws are given as[56, 58]:

 (1)

  (2)

                (3)

             (4)

where,

                         (5)

In above equations, u denotes the longitudinal velocity; v denotes the lateral velocity; ωx is the roll angular velocity; ωz is the yaw angular velocity; f is the roll angle; Jz is the yaw inertial; Jx is the roll inertial; Jxz is the product of roll and yaw inertial; mt denotes the vehicle mass, while ms denotes sprung mass; Fxgij and Fygij represent the longitudinal and lateral forces at the tire contact patch, where the subscripts ij denotes front right(rf), front left(lf), rear right(rr) and rear left(lr), respectively; a is the distance from vehicle center of mass (C.M.) to front wheel center; b is the distance from vehicle C.M. to rear axle; muf, mur denote front, rear unsprung mass; cf and cr denote front and rear track width, respectively; hrcf and hrcr denote the front and rear roll center distance below sprung mass, respectively; kff and kfr denote the equivalent roll stiffness of the front and rear suspension, respectively; bff and bfr denote the equivalent roll damping coefficient of the front and rear suspension, respectively; g denotes gravity acceleration [56].

In the case that the vehicle is front wheel driven, the equations of front right and rear right wheel rotational dynamics are given as [56, 59]:

                  (6)

                      (7)

where Tdrf and Tbrf are the driving and braking torque passed to the right front wheel; Tbrr is the braking wheel torque passed to the right rear wheel; rrf and rrr denote the effective rolling radius of front and rear tires, respectively. ωrf and ωrr denote the angular velocity of the front and rear wheels [56, 59].

2.3 14-DOF vehicle model

Due to the consideration of the suspension DOF at each corner of a vehicle, the 14-DOF model can simulate the pitch and heave motions, in addition to the same DOFs of a double-track 8-DOF model, which gives it an edge to better model the coupling effects among longitudinal, lateral, roll as well as the yaw motion. Moreover, the 14-DOF model can even predict the phenomenon of wheel lift-off and therefore it is proper to be utilized in rollover prediction or prevention control strategy [56, 58].

The schematic of a 14-DOF model is shown in Figure 2. u, v and w denote forward speed, lateral and vertical velocity of the sprung mass, respectively. ψ, f and q are the yaw angle, roll angle and pitch angle, respectively. ωz, ωx and ωy are the yaw angular, roll angular and pitch angular velocities, respectively. Mxij, Myij and Mzij are the moments passed to the sprung mass with respect to ωx, ωy and ωz directions, respectively. The forces passed to the sprung mass with respect to the longitudinal, lateral and vertical directions of body-fixed coordinate frame 1 are Fxsij, Fysij and Fzsij, respectively [56, 58].

The equation for the sprung mass of the 14-DOF model can be given as below using Newton’s laws [56, 58]:

          (8)

       (9)

 (10)

    (11)

  (12)

  (13)

where the cardan angles q, ψ, f are derived by integrating the following equations [56, 58]:

;

;

             (14)

More description about the 14-DOF model can be referred in Refs. [56, 58].

2.4 Spatial-dependent vehicle model

When using a spatial-based vehicle model, the vehicle position will be known explicitly at each optimization step and the solver is retained to consider a time-varied speed [60].

Figure 3 depicts a spatial bicycle model in curvilinear coordinate frame. The arc-length travelled along the path is denoted by s. Defining the vehicle states , and the errors of heading angle and lateral position are eψ and ey, the following equations can be obtained from Figure 3 [56, 60]:

                          (15)

                     (16)

where the speed along the direction of the reference path is vs; the curvature radius is ρ; the reference path heading angle is ψs, and its time derivative is . Then the vehicle’s velocity along the path is given as [56, 60]:

         (17)

Figure 2 14-DOF vehicle model and coordinate frames[56, 58]

Considering that the derivative of can be obtained as follows ((·)′ represents the derivative with respect to s) [56, 60]:

                   (18)

Herein, we utilize a spatial-based 8-DOF model to predict the vehicle state [56].

Figure 3 Curvilinear coordinate system [56, 60]

3 Speed profile generation given fixed reference path

3.1 Reference path generation given road points

The state of vehicle reference position is determined by road curvature. Hence, curvature is the only controlling variable for path planners. In other words, the local path can be planned by determining the curvature [61]. After comparing geometric, kinematic and dynamic path tracking controllers, it concluded that they all require at least curvature-continuous path reference [62].

                    (19)

                     (20)

                        (21)

where x, y, ψ and k specify the position, heading and curvature (implies its steering angle) in terms of arc length s, respectively.

The curvature function of a reference path at point s is given by [63]

                         (22)

where s is the arc length of the track; x′ and y′ are the spatial derivatives at point s.

The curvature can be approximated using finite differences of the sample waypoints as [64]:

                          (23)

where

                      (24)

Hence, the reference trajectory and heading angle can be generated by integration from the curvature profile with given points.

3.2 Minimum-time speed profile generation given fixed path

The speed profile design is to plan a longitudinal velocity by seeking a minimum-time motion and exploring the dynamic capabilities of a vehicle to travel on a given path. After generating a refined reference trajectory, the minimum-time speed profile can be determined, subject to tire-road friction constraints. Although the task of time- optimal velocity planning has been formulated as a convex optimization problem in recent years, a forward-backward integration algorithm was proposed in Ref. [46] to generate a minimum-time longitudinal velocity profile given a prescribed path (referred as a “three pass” method in Ref. [65] and originally inspired by the research in Ref. [50]). Because this algorithm requires less computations and logical operations and the speed profile is generated in curvilinear coordinates, its real-time implementation should be significantly facilitated. The process of minimum-time speed profile generation is provided as follows:

Firstly, the minimum-time speed profile is determined within the boundary of available tire-road friction according to the reference trajectory described by the arc length s and curvature k. Considering the left and right tires of the axle as one lumped tire, the available longitudinal force Fx and lateral force Fy for front and rear axles are constrained by the friction circle [46]

                       (25)

                        (26)

where μ denotes tire-road friction coefficient and Fz denotes the available normal force. Given zero longitudinal force, the maximum allowable vehicle longitudinal velocity is written by [46]:

                          (27)

The above equation is obtained by setting and Fzf=mgb/(a+b).

Furthermore, the velocity is determined by the road environment, and the most important factor is the curvature. Considering the linear tire model and small lateral acceleration, according to the computed road curvature, the reference longitudinal velocity is calculated by [30]

                         (28)

Then, a forward integration follows as the second step, in which the speed at the given point is determined based on the speed at the previous point and the available longitudinal force Fx, max [46].

         (29)

A key point of the second step is to compare the value of Ux(s) with that from Eq. (28), and the minimum value is taken [46].

After the forward integration step, a backward integration step occurs as the third step, in which the force Fx, max for deceleration is limited by lateral forces on all tires [46]:

         (30)

Again, Ux(s) should be compared with the value solved from Eq. (29), and the minimum value is taken, resulting in a reference speed profile. The method presented in Ref. [65] determined the lateral and normaltire forces at every point along the reference trajectory considering weight transfer, road bank, and grade. The lap time is given as [46]:

                             (31)

This indicates that to minimize the traversal time needs to simultaneously maximize the vehicle speed Ux and minimize the total length L.

Since L is known for a given fixed trajectory, to minimize the travel time needs to find the maximum longitudinal velocity at each point along the path, subject to the constraint of tire-road friction.

4 Combined lateral and longitudinal controller design

MPC algorithm is capable of dealing with path tracking problem considering multiple constraints of input physical limits and state output admissible. With these advantages in mind and relied on our previous work [56], we provide a novel trajectory tracking controller to implement the combined longitudinal and lateral control. The proposed controller based on MPC framework is given in Figure 4.

4.1 Lateral dynamics control

The computation cost will be increased rapidly as the system state dimensions increase for multi-DOF vehicle dynamics models. Considering a real-time demand for implementation, we use the linear model predictive control to formulate the lateral controller.

4.1.1 Vehicle model linearization

Setting control input u=δ and the state variable , the vehicle model can be written in general as [56]:

                             (32)

The equations with respect to operating point can bewritten as:

                           (33)

According to the Taylor series expansion and ignoring higher order terms, the equation is obtained as below [21,56]:

                   (34)

Subtracting Eq. (33) from Eq. (34) results in

                            (35)

Figure 4 Framework of combined controller for path tracking and speed control [56]

where , , , .

The equation should be discretized as follows for the model to be used in the MPC controller [21, 56]:

            (36)

where Ad=I+TA, Bd=TB, and T is the sampling time.

4.1.2 State prediction

Defining the new state variable , the output state variable η(k) and the control input increment △u(k)=u(k)- u(k-1), a new form of the model is written as [21, 56]:

          (37)

where , (m, n and p denote the dimensions of control input, state variable and output, respectively).

The model output in a compact matrix form over the prediction horizon Np is written as [56]:

            (38)

where,

;

;

;

;

;

.

4.1.3 Cost function definition

Considering the soft constraints concept [66], the cost function for the MPC-based path tracking is written as [56]:

             (39)

Considering Eq. (38), the cost function can be derived as [21, 56]:

 (40)

Then, the cost function is transformed into a standard quadratic form to solve the optimization [56].

         (41)

where, and et is the tracking error in the predictive horizon.

4.1.4 Constraint analysis

The following constraints should be considered in the model predictive path tracking control.

1) The control input limits are

             (42)

2) The control increment limits are

         (43)

3) The vehicle state output limits are

             (44)

where in Eqs. (42) and (43) and k=1, …, Np in Eq. (44) [56].

After solving the optimal problem, a sequence of control increments can be obtained as:

            (45)

The first element of the sequence is applied as the actual control input given as:

                       (46)

4.2 Longitudinal dynamics control

Among various controllers, PID control is one of the most widely used industrial controllers due to its generalization to most control systems. In this section, the PID controller is employed for vehicle longitudinal control, which is embedded in the solution of MPC-based path tracking control framework [56].

The tracking error equations for longitudinal velocity can be given as

                             (47)

                             (48)

                       (49)

where eu denotes the error between reference speed ud and the plant speed u; the denotes the longitudinal acceleration error between the reference value and the plant value ; the denotes the longitudinal displacement error; Ts denotes the sampling time and for the arc length dependent model.

When the longitudinal velocity of the plant is smaller than the reference value, a driving torque is applied to the wheel; when the plant speed is greater than the reference value, a braking torque is applied.

5 Simulation results and discussion

5.1 Vehicle model parameters

The parameters for the developed vehicle models are listed in Table 1.

Table 1 Parameters for vehicle dynamics modeling

5.2 Trajectory tracking and speed control along entire trajectory

Assuming that the road points along the reference path are given, the road curvature can be approximated and a refined reference trajectory can be generated, based on which a time-optimal velocity profile is determined using the forward- backward integration approach. Furthermore, the proposed controller considering minimum-time traversal is extended and implemented in one moving prediction window along the reference trajectory.

5.2.1 Reference trajectory and curvature definition

Given the points along the prescribed path, i.e., arbitrary curves of continuously varying curvature, a refined reference path of continuously varying curvature is generated according to Eq. (19), Eq. (20) and Eq. (21). The position (x(s), y(s)), heading angle ψ(s) and curvature κ(s) in curvilinear coordinate systems are obtained according to Eq. (22), Eq. (23) and Eq. (24), the reference path and curvature are given in Figure 5.

Figure 5 References:

5.2.2 Time-optimal speed profile generation

Based on the curvature of the reference trajectory, the minimum-time speed profile can be obtained using the forward-backward integration scheme introduced in Section 3.2 in order to track the desired path as fast as possible. The process of generating a reference speed profile is shown in Figure 6, in which the profile determined by the first step is shown as “Fx=0”; by the second step is shown as “Integrate forward”; by the third step is shown as “Integrate backward”, which is the final time-optimal longitudinal velocity profile shown as the red solid line in Figure 6.

Figure 6 Computation process of time-optimal speed profile generation

5.2.3 Trajectory tracking with speed control considering time-optimal travel

For the constraints, the road wheel steering angle is limited in -10°≤α≤10°; the control increment is limited in -4.25°≤Δα≤4.25°; the lateral position boundary is -100 m ≤y≤10 m; the heading angle boundary is -6 rad≤ψ≤3 rad; the longitudinal position constraint is given as -40 m≤x≤60 m. The tracking performances of the proposed combined longitudinal and lateral control are shown in Figures 7 to 9.

1) Tracking performances of “y”, “x”, trajectory and longitudinal speed are shown in Figure 7.

2) Tracking errors of vehicle lateral position and vehicle longitudinal position are shown in Figure 8.

3) The control inputs including steering angle and wheel torque results are shown in Figure 9.

According to the simulation results, the tracking errors for the longitudinal position and lateral position are small and the automated vehicle tracks the reference trajectory and speed well using the proposed controller considering the reference path to be arbitrary curves of continuously varied curvature.

Figure 10 shows how the receding horizon works for the path tracking and the generation of minimum-time longitudinal velocity profile. The speed profile is generated along the entire path serving as the reference for the PID speed controller. The prediction horizon (PHi) is the distance from current position up to the point which the ith optimization step is performed; the control horizon (CHi) is a fraction of PHi which indicates optimal control input sequences; the execution horizon (EHi) is a fraction of CHi which indicates the distance that the planned optimization will actually be executed, the optimization is performed again up to the new planning horizon PHi+1 until the vehicle arrives the target point.

5.3 Trajectory tracking and speed control in one moving prediction window

When an obstacle occurs in the environment,the local path and speed planning are usually needed to consider the change for obstacle avoidance. If the reference speed profile is generated along the entire path, it cannot include the local change and update the reference speed. Therefore, in this section, the entire reference path is given and divided into numbers of prediction windows and the time-optimal speed profile is generated in each window in a receding horizon manner until the path tracking and speed control arrives at the end.

Figure 7 Trajectory tracking and speed control along the entire path:

Figure 8 Trajectory tracking for the method of tracking control along the entire path:

Figure 9 Control inputs:

Figure 10 Optimization with receding horizon along entire path [50]

5.3.1 Method of tracking control in one moving prediction window

Herein, with the predefined tracking objectives along the entire trajectory including the vehicle longitudinal position x, lateral position y, heading angle ψ and road curvature κ, the forward-backward integration scheme mentioned in Section 3.2 is further extended to consider the speed profile generation in one moving prediction window. The entire path is divided into numbers of PHα horizons(representing one window for longitudinal velocity profile generation) and a minimum-time speed profile is generated in this window. The procedures of path tracking and speed control in one moving prediction window are specified in the flowchart shown in Figure 11.

Figure 11 Flowchart of tracking control method in one moving prediction window

Moreover, to compare with the method of optimization with receding horizon along the entire path, Figure 12 shows how the extended scheme for generating minimum-time speed profile and how the receding horizon works for path tracking and speed control along one moving prediction window, in which the definitions of PH, CH and EH are the same as those described in Figure 10.

Figure 12 Tracking control in one moving prediction window

5.3.2 Trajectory tracking with speed control considering time-optimal travel

For the constraints, the road wheel steering angle is limited in -20°≤α≤20°, the control increment is limited in -8.5°≤Δα≤8.5°; The simulation results are shown in Figures 13 and 14.

1) Tracking performances of “y”, “x”, the trajectory and the longitudinal speed are given in Figure 13.

2) Tracking errors of the vehicle lateral position and longitudinal position are shown in Figure 14.

Based on the simulation results, when considering tracking control in one moving prediction window, the desired trajectory and the speed are also well tracked using the proposed coupled lateral and longitudinal controller. On the other hand, the forward-backward integration approach introduced in Ref. [46] was used to generate the velocity profile along the entire reference path (Case A), which was further extended for implementation in one moving prediction window (Case B). With respect to the lap time for two cases, the travel time of accomplishing the path tracking for Case A is 26.26 s and compared with Case A, Case B shortened the travel time of path tracking control owing to the fact that Case B allows minimum-time speed profile design in one moving prediction window and the optimal longitudinal velocity is higher than Case A.

Figure 13 Trajectory tracking and speed control in one moving prediction window:

Figure 14 Trajectory tracking errors for the method of tracking control in one moving prediction window:

6 Conclusions

In this paper, an introduction of the methods for path planning, path tracking and time-optimal problem was firstly presented to point out advantages of MPC-based trajectory tracking considering a minimum-time traversal. Based on a refined path and curvature, a forward-backward integration strategy was used to design the minimum-time longitudinal velocity profile, subject to the tire-road friction limit. Furthermore, this algorithm was extended to consider generating longitudinal velocity profile in one moving prediction window. Then, a novel trajectory tracking and PID speed control based on MPC framework was proposed to handle the combined longitudinal and lateral control. Additionally, to investigate the tracking performance of the proposed controller, the arbitrary curves of continuously varying curvature was considered as the reference trajectory. Based on the simulation results, the following conclusions can be drawn from the research:

1) The proposed controller demonstrates good tracking performance using combined longitudinal and lateral control based on LMPC framework for both the case along the entire trajectory and the case along one moving prediction window. Small tracking errors between the references and the plant are reported.

2) The time-optimal speed profile is generated using the proposed forward-backward integration strategy based on a refined reference trajectory and curvature which can be calculated with the given points along the fixed path of continuously varying curvature. Moreover, the minimum-time speed profile is further extended to be generated in one moving window, which allows to consider updating the reference speed according to the changes from local path planning.

3) With respect to the travel time, the Case B of extended implementation in one moving prediction window requires shorter time than Case A of time-optimal velocity profile generation along the entire path because the optimal speed profile solved in Case B is higher than that in Case A.

Although the proposed controller is capable of considering the coupling effects between lateral and longitudinal vehicle dynamics and time-varied speed control in the formulation of LMPC algorithm, which decreases the computational burden and improves the tracking performance, each method has its own pros and cons. When implemented in one moving window, the trajectory tracking errors become larger as the designed time-optimal longitudinal velocity is increased and the handling stability should be therefore considered for high-speed automated vehicles on curved road. Moreover, the weighting matrices in the cost function and the parameters in the PID control may need to be tuned according to different driving scenarios.

In the future work, the constraints of vehicle lateral and roll stability will be considered in the combined lateral and longitudinal control to guarantee handling stability for high-speed automated vehicles. Moreover, the uncertainties will be also considered and formulated in the LMPC algorithm.

Acknowledgments

This paper is funded by International Graduate Exchange Program of Beijing Institute of Technology. The authors also gratefully thank the reviewers for their valuable suggestions.

Contributors

CHEN Shu-ping wrote the original draft of the manuscript and conducted the creation of the models and simulation analysis. XIONG Guang-ming reviewed and edited the draft of the manuscript. CHEN Hui-yan supervised and leaded the research activity. NEGRUT Dan provided the concept and goals of the manuscript.

Conflict of interest

CHEN Shu-ping, XIONG Guang-ming, CHEN Hui-yan and NEGRUT Dan declare that they have no conflict of interest.

References

[1] LIU Chang, LEE S, VARNHAGEN S, TSENG H E. Path planning for autonomous vehicles using model predictive control [C]// IEEE Intelligent Vehicles Symposium. IEEE, 2017: 174-179. DOI: 10.1109/IVS.2017.7995716.

[2] YURTSEVER E, LAMBERT J, CARBALLO A, TAKEDA K. A survey of autonomous driving: Common practices and emerging technologies [J]. IEEE Access, 2020, 8: 58443-58469. DOI: 10.1109/ACCESS.2020.2983149.

[3] BROWN M, FUNKE J, ERLIEN S, GERDES J C. Safe driving envelopes for path tracking in autonomous vehicles [J]. Control Engineering Practice, 2017, 61: 307-316. DOI: 10.1016/j.conengprac.2016.04.013.

[4] CUI Qing-jia, DING Rong-jun, WEI Chong-feng, ZHOU Bing. Path-tracking and lateral stabilisation for autonomous vehicles by using the steering angle envelope [J]. Vehicle System Dynamics, 2020: 1-25. DOI: 10.1080/00423114. 2020.1776344.

[5] HWANG J Y, KIM J S, LIM S S, PARK K H. A fast path planning by path graph optimization [J]. IEEE Transactions on Systems, Man, and Cybernetics, 2003, 33(1): 121-128. DOI: 10.1109/TSMCA.2003.812599.

[6] LIKHACHEV M, FERGUSON D, GORDON G, STENTZ A, THRUN S. Anytime search in dynamic graphs [J]. Artificial Intelligence, 2008, 172: 1613-1643. DOI: 10.1016/j.artint. 2007.11.009.

[7] DOLGOV D, THRUN S, MONTEMERLO M, DIEBEL J. Path planning for autonomous vehicles in unknown semi-structured environments [J]. International Journal of Robotics Research, 2010, 29(5): 485-501. DOI: 10.1177/ 0278364909359210.

[8] PIVTORAIKO M, KNEPPER R A, KELLY A. Differentially constrained mobile robot motion planning in state lattices [J]. Journal of Field Robotics, 2009, 26(3): 308-333. DOI: 10.1002/rob.20285.

[9] KAVRAKI L E, KOLOUNTZAKIS M N, LATOMBE J C. Analysis of probabilistic roadmaps for path planning [J]. IEEE Transactions on Robotics and Automation, 1998, 14(1): 166-171. DOI: 10.1109/70.660866.

[10] LAVALLE S M, KUFFNER J J. Randomized kinodynamic planning [J]. The International Journal of Robotics Research, 2001, 20(5): 378-400. DOI: 10.1177/02783640122067453.

[11] ZIEGLER J, BENDER P, DANG T, STILLER C. Trajectory planning for bertha-a local, continuous method [C]// 2014 IEEE Intelligent Vehicles Symposium Proceedings. IEEE, 2014: 450-457. DOI: 10.1109/IVS.2014.6856581.

[12] GONZALEZ D, PEREZ J, MILANES V, NASHASHIBI F. A review of motion planning techniques for automated vehicles [J]. IEEE Transactions on Intelligent Transportation Systems, 2016, 17(4): 1135-1145. DOI: 10.1109/TITS.2015. 2498841.

[13] HUANG Yan-jun, WANG Hong, KHAJEPOUR A, DING Hai-tao, YUAN Kang, QIN Ye-chen. A novel local motion planning framework for autonomous vehicles based on resistance network and model predictive control [J]. IEEE Transactions on Vehicular Technology, 2020, 69(1): 55-66. DOI: 10.1109/TVT.2019.2945934.

[14] BEAL C E, GERDES J C. Model predictive control for vehicle stabilization at the limits of handling [J]. IEEE Transactions on Control Systems Technology, 2013, 21(4): 1258-1269. DOI: 10.1109/TCST.2012.2200826.

[15] MARINO R, SCALZI S, NETTO M. Nested PID steering control for lane keeping in autonomous vehicles [J]. Control Engineering Practice, 2011, 19: 1459-1467. DOI: 10.1016/ j.conengprac.2011.08.005.

[16] WANG Shu-ti, YIN Xun-he, LI Peng, ZHANG Ming-zhi, WANG Xin. Trajectory tracking control for mobile robots using reinforcement learning and PID [J]. Iranian Journal of Science and Technology, Transactions of Electrical Engineering, 2020, 44(3): 1059-1068. DOI: 10.1007/ s40998-019-00286-4.

[17] HU Chuan, WANG Rong-rong, YAN Feng-jun, CHEN Nan. Output constraint control on path following of four-wheel independently actuated autonomous ground vehicles [J]. IEEE Transactions on Vehicular Technology, 2016, 65(6): 4033-4043. DOI: 10.1109/TVT.2015.2472975.

[18] LEE K, JEON S, KIM H, KUM D. Optimal path tracking control of autonomous vehicle: Adaptive full-state linear quadratic Gaussian (LQG) control [J]. IEEE Access, 2019, 7: 109120-109133. DOI: 10.1109/ACCESS.2019.2933895.

[19] KANG C M, KIM W, CHUNG C C. Observer-based backstepping control method using reduced lateral dynamics for autonomous lane-keeping system [J]. ISA Transactions, 2018, 83: 214-226. DOI: 10.1016/j.isatra.2018.09.016.

[20] NOROUZI A, MASOUMI M, BARARI A, SANI S F. Lateral control of an autonomous vehicle using integrated backstepping and sliding mode controller [J]. Proceedings of the Institution of Mechanical Engineers, Part K: Journal of Multi-body Dynamics, 2019, 233(1): 141-151. DOI: 10.1177/1464419318797051.

[21] GONG Jian-wei, XU Wei, JIANG Yan, LIU Kai, GUO Hong-fen, SUN Yin-jian. Multi-constrained model predictive control for autonomous ground vehicle trajectory tracking [J]. Journal of Beijing Institute of Technology, 2015, 24(4): 441-448. DOI: 10.15918/j.jbit1004-0579.201524.0403.

[22] LIU Kai, GONG Jian-wei, KURT A, CHEN Hui-yan, OZGUNER U. Dynamic modeling and control of high-speed automated vehicles for lane change maneuver [J]. IEEE Transactions on Intelligent Vehicles, 2018, 3(3): 329-339. DOI: 10.1109/tiv.2018.2843177.

[23] NAM H, CHOI W, AHN C. Model predictive control for evasive steering of an autonomous vehicle [J]. International Journal of Automotive Technology, 2019, 20(5): 1033-1042. DOI: 10.1007/s12239-019-0097-5.

[24] LIU Kai, GONG Jian-wei, CHEN Shu-ping, ZHANG Yu, CHEN Hui-yan. Dynamic modeling analysis of optimal motion planning and control for high-speed self-driving vehicles [J]. Journal of Mechanical Engineering, 2018, 54(14): 141-151. DOI: 10.3901/JME.2018. 14.141. (in Chinese)

[25] FALCONE P, TSENG H E, BORRELLI F, ASGARI J, HROVAT D. MPC-based yaw and lateral stabilisation via active front steering and braking [J]. Vehicle System Dynamics, 2008, 46(Supplement): 611-628. DOI: 10.1080/00423110802018297.

[26] MING Ting-you, DENG Wei-wen, ZHANG Su-min, ZHU Bing. MPC-based trajectory tracking control for intelligent vehicles [J]. SAE Technical Papers, 2016: 2016-01-0452. DOI: 10.4271/2016-01-0452.

[27] GUO Hong-yan, LIU Jun, CAO Dong-pu, CHEN Hong, YU Ru, LV Chen. Dual-envelop-oriented moving horizon path tracking control for fully automated vehicles [J]. Mechatronics, 2018, 50: 422-433. DOI: 10.1016/ j.mechatronics.2017.02.001.

[28] TANG Lu-qi, YAN Fu-wu, ZOU Bin, WANG Ke-wei, LV Chen. An improved kinematic model predictive control for high-speed path tracking of autonomous vehicles [J]. IEEE Access, 2020, 8: 51400-51413. DOI: 10.1109/ ACCESS. 2020.2980188.

[29] ATTIA R, ORJUELA R, BASSET M. Combined longitudinal and lateral control for automated vehicle guidance [J]. Vehicle System Dynamics, 2014, 52(2): 261-279. DOI: 10.1080/00423114.2013.874563.

[30] LIN Fen, ZHANG Yao-wen, ZHAO You-qun, YIN Guo-dong, ZHANG Hui-qi, WANG Kai-zheng. Trajectory tracking of autonomous vehicle with the fusion of DYC and longitudinal–lateral control [J]. Chinese Journal of Mechanical Engineering, 2019, 32: 1-16. DOI: 10.1186/s10033-019-0327-9.

[31] LIPP T, BOYD S. Minimum-time speed optimisation over a fixed path [J]. International Journal of Control, 2014, 87(6): 1297-1311. DOI: 10.1080/00207179.2013.875224.

[32] ALCALA E, PUIG V, QUEVEDO J, ROSOLIA U. Autonomous racing using linear parameter varying-model predictive control (LPV-MPC) [J]. Control Engineering Practice, 2020, 95: 104270. DOI: 10.1016/j.conengprac. 2019.104270.

[33] BOBROW J E, DUBOWSKY S, GIBSON J S. Time-optimal control of robotic manipulators along specified paths [J]. The International Journal of Robotics Research, 1985, 4(3): 3-17. DOI: 10.1177/027836498500400301.

[34] VERSCHEURE D, DEMEULENAERE B, SWEVERS J, SCHUTTER J D, DIEHL M. Time-optimal path tracking for robots: A convex optimization approach [J]. IEEE Transactions on Automatic Control, 2009, 54(10): 2318-2327. DOI: 10.1109/TAC.2009.2028959.

[35] DINH Q T, DIEHL M. An application of sequential convex programming to time optimal trajectory planning for a car motion [C]// Proceedings of the IEEE Conference on Decision and Control. IEEE, 2009: 4366-4371. DOI: 10.1109/CDC.2009.5399823.

[36] FAULWASSER T, HAGENMEYER V, FINDEISEN R. Optimal exact path-following for constrained differentially flat systems[C]// Proceedings of the 18th IFAC World Congress. Elsevier, 2011: 9875–9880. DOI: 10.3182/ 20110828-6-IT-1002.03132.

[37] CASANOVA D, SHARP R S, SYMONDS P. Minimum time manoeuvring: The significance of yaw inertia [J]. Vehicle System Dynamics, 2000, 34: 77–115. DOI: 10.1076/ 0042-3114(200008)34:2;1-G;FT077.

[38] VELENIS E, TSIOTRAS P. Minimum time vs maximum exit velocity path optimization during cornering [C]// IEEE International Symposium on Industrial Electronics. IEEE, 2005: 355-360. DOI: 10.1109/ISIE.2005.1528936.

[39] HENDRIKX J P M, MEIJLINK T J J, KRIENS R F C. Application of optimal control theory to inverse simulation of car handling [J]. Vehicle System Dynamics, 1996, 26: 449-461. DOI: 10.1080/00423119608969319.

[40] CASANOVA D. On minimum time vehicle manoeuvring: The theoretical optimal lap [D]. Cranfield: Cranfield University, 2000.

[41] KELLY D P. Lap time simulation with transient vehicle and tyre dynamics [D]. Cranfield: Cranfield University, 2008.

[42] THEODOSIS P A, GERDES J C. Generating a racing line for an autonomous racecar using professional driving techniques [C]// ASME 2011 Dynamic Systems and Control Conference and Bath/ASME Symposium on Fluid Power and Motion Control, ASME, 2012: 853-860. DOI: 10.1115/DSCC2011-6097.

[43] GERDTS M, KARRENBERG S, MULLER-BEβLER B, STOCK G. Generating locally optimal trajectories for an automatically driven car [J]. Optimization and Engineering, 2009, 10: 439-463. DOI: 10.1007/s11081-008-9047-1.

[44] TIMINGS J P, COLE D J. Minimum maneuver time calculation using convex optimization [J]. Journal of Dynamic Systems, Measurement and Control-Transactions of the ASME, 2013, 135(3): 031015. DOI: 10.1115/ 1.4023400.

[45] PERANTONI G, LIMEBEER D J N. Optimal control for a Formula One car with variable parameters [J]. Vehicle System Dynamics, 2014, 52(5): 653-678. DOI: 10.1080/ 00423114.2014.889315.

[46] KAPANIA N R, SUBOSITS J, GERDES J C. A sequential two-step algorithm for fast generation of vehicle racing trajectories [J]. Journal of Dynamic Systems, Measurement, and Control-Transactions of the ASME, 2016, 138(9): 091005. DOI: 10.1115/1.4033311.

[47] SPENKO M, KURODA Y, DUBOWSKY S, IAGNEMMA K. Hazard avoidance for high-speed mobile robots in rough terrain [J]. Journal of Field Robotics, 2006, 23(5): 311-331. DOI: 10.1002/rob.20118.

[48] HELLEWELL J S, POPOV A A, BURNETT G E. Hierarchical control for trajectory generation and tracking via active front steering [J]. Journal of Dynamic Systems, Measurement, and Control, 2020, 142: 011002. DOI: 10.1115/1.4044620.

[49] XU Shao-bing, PENG Huei. Design, analysis, and experiments of preview path tracking control for autonomous vehicles [J]. IEEE Transactions on Intelligent Transportation Systems, 2020, 21(1): 48-58. DOI: 10.1109/TITS.2019.2892926.

[50] VELENIS E, TSIOTRAS P. Minimum-time travel for a vehicle with acceleration limits: Theoretical analysis and receding-horizon implementation [J]. Journal of Optimization Theory and Applications, 2008, 138: 275-296. DOI: 10.1007/s10957-008-9381-7.

[51] LEPETIC M, KLANCAR G, SKRJANC I, MATKO D, POTOCNIK B. Time optimal path planning considering acceleration limits [J]. Robotics and Autonomous Systems, 2003, 45: 199-210. DOI: 10.1016/j.robot.2003.09.007.

[52] KANT K, ZUCKER SW. Toward efficient trajectory planning: The path-velocity decomposition [J]. The International Journal of Robotics Research, 1986, 5(3): 72-89. DOI: 10.1177/027836498600500304.

[53] BIANCO C G L, PIAZZI A, ROMANO M. Smooth motion generation for unicycle mobile robots via dynamic path inversion [J]. IEEE Transactions on Robotics, 2004, 20(5): 884-891. DOI: 10.1109/TRO.2004.832827.

[54] LINI G, PIAZZI A, CONSOLINI L. Algebraic solution to minimum-time velocity planning [J]. International Journal of Control, Automation and Systems, 2013, 11(4): 805-814. DOI: 10.1007/s12555-011-0065-y.

[55] CONSOLINI L, LOCATELLI M, MINARI A, PIAZZI A. An optimal complexity algorithm for minimum-time velocity planning [J]. Systems and Control Letters, 2017, 103: 50-57. DOI: 10.1016/j.sysconle.2017.02.001.

[56] CHEN Shu-ping, CHEN Hui-yan. MPC-based path tracking with PID speed control for autonomous vehicles [C]// IOP Conference Series: Materials Science and Engineering. IOP, 2020: 012034. DOI: 10.1088/1757-899X/892/1/012034.

[57] BORRELLI F, FALCONE P, KEVICZKY T, ASGARI J, HROVAT D. MPC-based approach to active steering for autonomous vehicle systems [J]. International Journal of Vehicle Autonomous Systems, 2005, 3: 265–291. DOI: 10.1504/IJVAS.2005.008237.

[58] SHIM T, GHIKE C. Understanding the limitations of different vehicle models for roll dynamics studies [J]. Vehicle System Dynamics, 2007, 45(3): 191-216. DOI: 10.1080/00423110600882449.

[59] HE Jun-jie, CROLLA D A, LEVESLEY M C, MANNING W J. Integrated active steering and variable torque distribution control for improving vehicle handling and stability [J]. SAE Technical Papers, 2004: 2004-01-1071. DOI: 10.4271/2004-01-1071.

[60] GAO Yi-qi, GRAY A, FRASCH J V, LIN T, TSENG E H, HEDRICK J K, BORRELLI F. Spatial predictive control for agile semi-autonomous ground vehicles [C]// Proceedings of the 11th International Symposium on Advanced Vehicle Control, 2012. https://borrelli.me.berkeley.edu/pdfpub/pub- 1054.pdf.

[61] ZHANG Chao-yong, CHU Duan-feng, LIU Shi-dong, DENG Ze-jian, WU Chao-zhong. Trajectory planning and tracking for autonomous vehicle based on state lattice and model predictive control [J]. IEEE Intelligent Transportation Systems Magazine, 2019, 11(2): 29-40. DOI: 10.1109/ MITS.2019.2903536.

[62] GU Tian-yu, SNIDER J, DOLAN J M, LEE J W. Focused trajectory planning for autonomous on-road driving [C]// IEEE Intelligent Vehicles Symposium. IEEE, 2013: 547-552. DOI: 10.1109/IVS.2013.6629524.

[63] CAPORALE D, SETTIMI A, MASSA F, AMEROTTI F, CORTI A, FAGIOLINI A, GUIGGIANI M, BICCHI A, PALLOTTINO L. Towards the design of robotic drivers for full-scale self-driving racing cars [C]// IEEE International Conference on Robotics and Automation (ICRA). IEEE, 2019: 5643-5649. DOI: 10.1109/ICRA.2019.8793882.

[64] MENG Yu, WU Yang-ming, GU Qing, LIU Li. A decoupled trajectory planning framework based on the integration of lattice searching and convex optimization [J]. IEEE Access, 2019, 7: 130530-130551. DOI: 10.1109/ACCESS.2019. 2940271.

[65] SUBOSITS J, GERDES J C. Autonomous vehicle control for emergency maneuvers: The effect of topography[C]// 2015 American Control Conference. IEEE, 2015: 1405-1410. DOI: 10.1109/ACC.2015.7170930.

[66] LI Sheng-bo, WANG Jian-qiang, LI Ke-qiang. Stabilization of linear predictive control systems with softening constraints [J]. Journal of Tsinghua University (Science & Technology), 2010, 50(11): 1848-1852. DOI: 10.16511/ j.cnki.qhdxxb.2010.11.029. (in Chinese)

(Edited by HE Yun-bin)

中文导读

基于MPC的考虑时间最优速度的高速无人驾驶车辆路径跟踪和PID速度控制

摘要:为了尽可能快地跟踪期望路径,提出一种新的基于模型预测控制(MPC)和PID速度控制方法,考虑高速无人驾驶车辆的物理约束,通过前向后向积分策略生成轮胎路面附着极限内的时间最优速度曲线,并将该方法进一步扩展应用于单个滚动预测窗口中。在MPC算法框架的设计中,以8自由度车辆模型作为预测模型,以高置信度的14自由度车辆模型作为被控对象,对于横向控制,通过MPC控制器生成最优的前轮转角,对于纵向控制,通过嵌入模型预测控制优化求解中的PID控制器生成总的车辆驱动/制动力矩。以任意连续变化曲率的路径为参考轨迹,在MATLAB中实现所提出的控制器,仿真结果表明车辆的横向位置和纵向位置的跟踪误差较小,通过车轮转角、车轮驱动/制动力矩的联合控制,车辆的轨迹跟踪和速度跟踪性能良好。另外,将最优速度曲线生成方法进一步扩展应用于单个滚动预测窗口中,其所需路径跟踪的时间比在整个路径上应用该策略时需要的时间短。

关键词:模型预测控制;路径跟踪;时间最短速度曲线;车辆动力学;任意路径

Foundation item: Project(20180608005600843855-19) supported by the International Graduate Exchange Program of Beijing Institute of Technology, China

Received date: 2020-05-13; Accepted date: 2020-09-09

Corresponding author: XIONG Guang-ming, PhD, Associate Professor; Tel: +86-10-68918652; E-mail: xiongguangming@bit.edu.cn; ORCID: https://orcid.org/0000-0002-0914-1112

Abstract: In order to track the desired path as fast as possible, a novel autonomous vehicle path tracking based on model predictive control (MPC) and PID speed control was proposed for high-speed automated vehicles considering the constraints of vehicle physical limits, in which a forward-backward integration scheme was introduced to generate a time-optimal speed profile subject to the tire-road friction limit. Moreover, this scheme was further extended along one moving prediction window. In the MPC controller, the prediction model was an 8-degree-of-freedom (DOF) vehicle model, while the plant was a 14-DOF vehicle model. For lateral control, a sequence of optimal wheel steering angles was generated from the MPC controller; for longitudinal control, the total wheel torque was generated from the PID speed controller embedded in the MPC framework. The proposed controller was implemented in MATLAB considering arbitrary curves of continuously varying curvature as the reference trajectory. The simulation test results show that the tracking errors are small for vehicle lateral and longitudinal positions and the tracking performances for trajectory and speed are good using the proposed controller. Additionally, the case of extended implementation in one moving prediction window requires shorter travel time than the case implemented along the entire path.

[1] LIU Chang, LEE S, VARNHAGEN S, TSENG H E. Path planning for autonomous vehicles using model predictive control [C]// IEEE Intelligent Vehicles Symposium. IEEE, 2017: 174-179. DOI: 10.1109/IVS.2017.7995716.

[2] YURTSEVER E, LAMBERT J, CARBALLO A, TAKEDA K. A survey of autonomous driving: Common practices and emerging technologies [J]. IEEE Access, 2020, 8: 58443-58469. DOI: 10.1109/ACCESS.2020.2983149.

[3] BROWN M, FUNKE J, ERLIEN S, GERDES J C. Safe driving envelopes for path tracking in autonomous vehicles [J]. Control Engineering Practice, 2017, 61: 307-316. DOI: 10.1016/j.conengprac.2016.04.013.

[4] CUI Qing-jia, DING Rong-jun, WEI Chong-feng, ZHOU Bing. Path-tracking and lateral stabilisation for autonomous vehicles by using the steering angle envelope [J]. Vehicle System Dynamics, 2020: 1-25. DOI: 10.1080/00423114. 2020.1776344.

[5] HWANG J Y, KIM J S, LIM S S, PARK K H. A fast path planning by path graph optimization [J]. IEEE Transactions on Systems, Man, and Cybernetics, 2003, 33(1): 121-128. DOI: 10.1109/TSMCA.2003.812599.

[6] LIKHACHEV M, FERGUSON D, GORDON G, STENTZ A, THRUN S. Anytime search in dynamic graphs [J]. Artificial Intelligence, 2008, 172: 1613-1643. DOI: 10.1016/j.artint. 2007.11.009.

[7] DOLGOV D, THRUN S, MONTEMERLO M, DIEBEL J. Path planning for autonomous vehicles in unknown semi-structured environments [J]. International Journal of Robotics Research, 2010, 29(5): 485-501. DOI: 10.1177/ 0278364909359210.

[8] PIVTORAIKO M, KNEPPER R A, KELLY A. Differentially constrained mobile robot motion planning in state lattices [J]. Journal of Field Robotics, 2009, 26(3): 308-333. DOI: 10.1002/rob.20285.

[9] KAVRAKI L E, KOLOUNTZAKIS M N, LATOMBE J C. Analysis of probabilistic roadmaps for path planning [J]. IEEE Transactions on Robotics and Automation, 1998, 14(1): 166-171. DOI: 10.1109/70.660866.

[10] LAVALLE S M, KUFFNER J J. Randomized kinodynamic planning [J]. The International Journal of Robotics Research, 2001, 20(5): 378-400. DOI: 10.1177/02783640122067453.

[11] ZIEGLER J, BENDER P, DANG T, STILLER C. Trajectory planning for bertha-a local, continuous method [C]// 2014 IEEE Intelligent Vehicles Symposium Proceedings. IEEE, 2014: 450-457. DOI: 10.1109/IVS.2014.6856581.

[12] GONZALEZ D, PEREZ J, MILANES V, NASHASHIBI F. A review of motion planning techniques for automated vehicles [J]. IEEE Transactions on Intelligent Transportation Systems, 2016, 17(4): 1135-1145. DOI: 10.1109/TITS.2015. 2498841.

[13] HUANG Yan-jun, WANG Hong, KHAJEPOUR A, DING Hai-tao, YUAN Kang, QIN Ye-chen. A novel local motion planning framework for autonomous vehicles based on resistance network and model predictive control [J]. IEEE Transactions on Vehicular Technology, 2020, 69(1): 55-66. DOI: 10.1109/TVT.2019.2945934.

[14] BEAL C E, GERDES J C. Model predictive control for vehicle stabilization at the limits of handling [J]. IEEE Transactions on Control Systems Technology, 2013, 21(4): 1258-1269. DOI: 10.1109/TCST.2012.2200826.

[15] MARINO R, SCALZI S, NETTO M. Nested PID steering control for lane keeping in autonomous vehicles [J]. Control Engineering Practice, 2011, 19: 1459-1467. DOI: 10.1016/ j.conengprac.2011.08.005.

[16] WANG Shu-ti, YIN Xun-he, LI Peng, ZHANG Ming-zhi, WANG Xin. Trajectory tracking control for mobile robots using reinforcement learning and PID [J]. Iranian Journal of Science and Technology, Transactions of Electrical Engineering, 2020, 44(3): 1059-1068. DOI: 10.1007/ s40998-019-00286-4.

[17] HU Chuan, WANG Rong-rong, YAN Feng-jun, CHEN Nan. Output constraint control on path following of four-wheel independently actuated autonomous ground vehicles [J]. IEEE Transactions on Vehicular Technology, 2016, 65(6): 4033-4043. DOI: 10.1109/TVT.2015.2472975.

[18] LEE K, JEON S, KIM H, KUM D. Optimal path tracking control of autonomous vehicle: Adaptive full-state linear quadratic Gaussian (LQG) control [J]. IEEE Access, 2019, 7: 109120-109133. DOI: 10.1109/ACCESS.2019.2933895.

[19] KANG C M, KIM W, CHUNG C C. Observer-based backstepping control method using reduced lateral dynamics for autonomous lane-keeping system [J]. ISA Transactions, 2018, 83: 214-226. DOI: 10.1016/j.isatra.2018.09.016.

[20] NOROUZI A, MASOUMI M, BARARI A, SANI S F. Lateral control of an autonomous vehicle using integrated backstepping and sliding mode controller [J]. Proceedings of the Institution of Mechanical Engineers, Part K: Journal of Multi-body Dynamics, 2019, 233(1): 141-151. DOI: 10.1177/1464419318797051.

[21] GONG Jian-wei, XU Wei, JIANG Yan, LIU Kai, GUO Hong-fen, SUN Yin-jian. Multi-constrained model predictive control for autonomous ground vehicle trajectory tracking [J]. Journal of Beijing Institute of Technology, 2015, 24(4): 441-448. DOI: 10.15918/j.jbit1004-0579.201524.0403.

[22] LIU Kai, GONG Jian-wei, KURT A, CHEN Hui-yan, OZGUNER U. Dynamic modeling and control of high-speed automated vehicles for lane change maneuver [J]. IEEE Transactions on Intelligent Vehicles, 2018, 3(3): 329-339. DOI: 10.1109/tiv.2018.2843177.

[23] NAM H, CHOI W, AHN C. Model predictive control for evasive steering of an autonomous vehicle [J]. International Journal of Automotive Technology, 2019, 20(5): 1033-1042. DOI: 10.1007/s12239-019-0097-5.

[24] LIU Kai, GONG Jian-wei, CHEN Shu-ping, ZHANG Yu, CHEN Hui-yan. Dynamic modeling analysis of optimal motion planning and control for high-speed self-driving vehicles [J]. Journal of Mechanical Engineering, 2018, 54(14): 141-151. DOI: 10.3901/JME.2018. 14.141. (in Chinese)

[25] FALCONE P, TSENG H E, BORRELLI F, ASGARI J, HROVAT D. MPC-based yaw and lateral stabilisation via active front steering and braking [J]. Vehicle System Dynamics, 2008, 46(Supplement): 611-628. DOI: 10.1080/00423110802018297.

[26] MING Ting-you, DENG Wei-wen, ZHANG Su-min, ZHU Bing. MPC-based trajectory tracking control for intelligent vehicles [J]. SAE Technical Papers, 2016: 2016-01-0452. DOI: 10.4271/2016-01-0452.

[27] GUO Hong-yan, LIU Jun, CAO Dong-pu, CHEN Hong, YU Ru, LV Chen. Dual-envelop-oriented moving horizon path tracking control for fully automated vehicles [J]. Mechatronics, 2018, 50: 422-433. DOI: 10.1016/ j.mechatronics.2017.02.001.

[28] TANG Lu-qi, YAN Fu-wu, ZOU Bin, WANG Ke-wei, LV Chen. An improved kinematic model predictive control for high-speed path tracking of autonomous vehicles [J]. IEEE Access, 2020, 8: 51400-51413. DOI: 10.1109/ ACCESS. 2020.2980188.

[29] ATTIA R, ORJUELA R, BASSET M. Combined longitudinal and lateral control for automated vehicle guidance [J]. Vehicle System Dynamics, 2014, 52(2): 261-279. DOI: 10.1080/00423114.2013.874563.

[30] LIN Fen, ZHANG Yao-wen, ZHAO You-qun, YIN Guo-dong, ZHANG Hui-qi, WANG Kai-zheng. Trajectory tracking of autonomous vehicle with the fusion of DYC and longitudinal–lateral control [J]. Chinese Journal of Mechanical Engineering, 2019, 32: 1-16. DOI: 10.1186/s10033-019-0327-9.

[31] LIPP T, BOYD S. Minimum-time speed optimisation over a fixed path [J]. International Journal of Control, 2014, 87(6): 1297-1311. DOI: 10.1080/00207179.2013.875224.

[32] ALCALA E, PUIG V, QUEVEDO J, ROSOLIA U. Autonomous racing using linear parameter varying-model predictive control (LPV-MPC) [J]. Control Engineering Practice, 2020, 95: 104270. DOI: 10.1016/j.conengprac. 2019.104270.

[33] BOBROW J E, DUBOWSKY S, GIBSON J S. Time-optimal control of robotic manipulators along specified paths [J]. The International Journal of Robotics Research, 1985, 4(3): 3-17. DOI: 10.1177/027836498500400301.

[34] VERSCHEURE D, DEMEULENAERE B, SWEVERS J, SCHUTTER J D, DIEHL M. Time-optimal path tracking for robots: A convex optimization approach [J]. IEEE Transactions on Automatic Control, 2009, 54(10): 2318-2327. DOI: 10.1109/TAC.2009.2028959.

[35] DINH Q T, DIEHL M. An application of sequential convex programming to time optimal trajectory planning for a car motion [C]// Proceedings of the IEEE Conference on Decision and Control. IEEE, 2009: 4366-4371. DOI: 10.1109/CDC.2009.5399823.

[36] FAULWASSER T, HAGENMEYER V, FINDEISEN R. Optimal exact path-following for constrained differentially flat systems[C]// Proceedings of the 18th IFAC World Congress. Elsevier, 2011: 9875–9880. DOI: 10.3182/ 20110828-6-IT-1002.03132.

[37] CASANOVA D, SHARP R S, SYMONDS P. Minimum time manoeuvring: The significance of yaw inertia [J]. Vehicle System Dynamics, 2000, 34: 77–115. DOI: 10.1076/ 0042-3114(200008)34:2;1-G;FT077.

[38] VELENIS E, TSIOTRAS P. Minimum time vs maximum exit velocity path optimization during cornering [C]// IEEE International Symposium on Industrial Electronics. IEEE, 2005: 355-360. DOI: 10.1109/ISIE.2005.1528936.

[39] HENDRIKX J P M, MEIJLINK T J J, KRIENS R F C. Application of optimal control theory to inverse simulation of car handling [J]. Vehicle System Dynamics, 1996, 26: 449-461. DOI: 10.1080/00423119608969319.

[40] CASANOVA D. On minimum time vehicle manoeuvring: The theoretical optimal lap [D]. Cranfield: Cranfield University, 2000.

[41] KELLY D P. Lap time simulation with transient vehicle and tyre dynamics [D]. Cranfield: Cranfield University, 2008.

[42] THEODOSIS P A, GERDES J C. Generating a racing line for an autonomous racecar using professional driving techniques [C]// ASME 2011 Dynamic Systems and Control Conference and Bath/ASME Symposium on Fluid Power and Motion Control, ASME, 2012: 853-860. DOI: 10.1115/DSCC2011-6097.

[43] GERDTS M, KARRENBERG S, MULLER-BEβLER B, STOCK G. Generating locally optimal trajectories for an automatically driven car [J]. Optimization and Engineering, 2009, 10: 439-463. DOI: 10.1007/s11081-008-9047-1.

[44] TIMINGS J P, COLE D J. Minimum maneuver time calculation using convex optimization [J]. Journal of Dynamic Systems, Measurement and Control-Transactions of the ASME, 2013, 135(3): 031015. DOI: 10.1115/ 1.4023400.

[45] PERANTONI G, LIMEBEER D J N. Optimal control for a Formula One car with variable parameters [J]. Vehicle System Dynamics, 2014, 52(5): 653-678. DOI: 10.1080/ 00423114.2014.889315.

[46] KAPANIA N R, SUBOSITS J, GERDES J C. A sequential two-step algorithm for fast generation of vehicle racing trajectories [J]. Journal of Dynamic Systems, Measurement, and Control-Transactions of the ASME, 2016, 138(9): 091005. DOI: 10.1115/1.4033311.

[47] SPENKO M, KURODA Y, DUBOWSKY S, IAGNEMMA K. Hazard avoidance for high-speed mobile robots in rough terrain [J]. Journal of Field Robotics, 2006, 23(5): 311-331. DOI: 10.1002/rob.20118.

[48] HELLEWELL J S, POPOV A A, BURNETT G E. Hierarchical control for trajectory generation and tracking via active front steering [J]. Journal of Dynamic Systems, Measurement, and Control, 2020, 142: 011002. DOI: 10.1115/1.4044620.

[49] XU Shao-bing, PENG Huei. Design, analysis, and experiments of preview path tracking control for autonomous vehicles [J]. IEEE Transactions on Intelligent Transportation Systems, 2020, 21(1): 48-58. DOI: 10.1109/TITS.2019.2892926.

[50] VELENIS E, TSIOTRAS P. Minimum-time travel for a vehicle with acceleration limits: Theoretical analysis and receding-horizon implementation [J]. Journal of Optimization Theory and Applications, 2008, 138: 275-296. DOI: 10.1007/s10957-008-9381-7.

[51] LEPETIC M, KLANCAR G, SKRJANC I, MATKO D, POTOCNIK B. Time optimal path planning considering acceleration limits [J]. Robotics and Autonomous Systems, 2003, 45: 199-210. DOI: 10.1016/j.robot.2003.09.007.

[52] KANT K, ZUCKER SW. Toward efficient trajectory planning: The path-velocity decomposition [J]. The International Journal of Robotics Research, 1986, 5(3): 72-89. DOI: 10.1177/027836498600500304.

[53] BIANCO C G L, PIAZZI A, ROMANO M. Smooth motion generation for unicycle mobile robots via dynamic path inversion [J]. IEEE Transactions on Robotics, 2004, 20(5): 884-891. DOI: 10.1109/TRO.2004.832827.

[54] LINI G, PIAZZI A, CONSOLINI L. Algebraic solution to minimum-time velocity planning [J]. International Journal of Control, Automation and Systems, 2013, 11(4): 805-814. DOI: 10.1007/s12555-011-0065-y.

[55] CONSOLINI L, LOCATELLI M, MINARI A, PIAZZI A. An optimal complexity algorithm for minimum-time velocity planning [J]. Systems and Control Letters, 2017, 103: 50-57. DOI: 10.1016/j.sysconle.2017.02.001.

[56] CHEN Shu-ping, CHEN Hui-yan. MPC-based path tracking with PID speed control for autonomous vehicles [C]// IOP Conference Series: Materials Science and Engineering. IOP, 2020: 012034. DOI: 10.1088/1757-899X/892/1/012034.

[57] BORRELLI F, FALCONE P, KEVICZKY T, ASGARI J, HROVAT D. MPC-based approach to active steering for autonomous vehicle systems [J]. International Journal of Vehicle Autonomous Systems, 2005, 3: 265–291. DOI: 10.1504/IJVAS.2005.008237.

[58] SHIM T, GHIKE C. Understanding the limitations of different vehicle models for roll dynamics studies [J]. Vehicle System Dynamics, 2007, 45(3): 191-216. DOI: 10.1080/00423110600882449.

[59] HE Jun-jie, CROLLA D A, LEVESLEY M C, MANNING W J. Integrated active steering and variable torque distribution control for improving vehicle handling and stability [J]. SAE Technical Papers, 2004: 2004-01-1071. DOI: 10.4271/2004-01-1071.

[60] GAO Yi-qi, GRAY A, FRASCH J V, LIN T, TSENG E H, HEDRICK J K, BORRELLI F. Spatial predictive control for agile semi-autonomous ground vehicles [C]// Proceedings of the 11th International Symposium on Advanced Vehicle Control, 2012. https://borrelli.me.berkeley.edu/pdfpub/pub- 1054.pdf.

[61] ZHANG Chao-yong, CHU Duan-feng, LIU Shi-dong, DENG Ze-jian, WU Chao-zhong. Trajectory planning and tracking for autonomous vehicle based on state lattice and model predictive control [J]. IEEE Intelligent Transportation Systems Magazine, 2019, 11(2): 29-40. DOI: 10.1109/ MITS.2019.2903536.

[62] GU Tian-yu, SNIDER J, DOLAN J M, LEE J W. Focused trajectory planning for autonomous on-road driving [C]// IEEE Intelligent Vehicles Symposium. IEEE, 2013: 547-552. DOI: 10.1109/IVS.2013.6629524.

[63] CAPORALE D, SETTIMI A, MASSA F, AMEROTTI F, CORTI A, FAGIOLINI A, GUIGGIANI M, BICCHI A, PALLOTTINO L. Towards the design of robotic drivers for full-scale self-driving racing cars [C]// IEEE International Conference on Robotics and Automation (ICRA). IEEE, 2019: 5643-5649. DOI: 10.1109/ICRA.2019.8793882.

[64] MENG Yu, WU Yang-ming, GU Qing, LIU Li. A decoupled trajectory planning framework based on the integration of lattice searching and convex optimization [J]. IEEE Access, 2019, 7: 130530-130551. DOI: 10.1109/ACCESS.2019. 2940271.

[65] SUBOSITS J, GERDES J C. Autonomous vehicle control for emergency maneuvers: The effect of topography[C]// 2015 American Control Conference. IEEE, 2015: 1405-1410. DOI: 10.1109/ACC.2015.7170930.

[66] LI Sheng-bo, WANG Jian-qiang, LI Ke-qiang. Stabilization of linear predictive control systems with softening constraints [J]. Journal of Tsinghua University (Science & Technology), 2010, 50(11): 1848-1852. DOI: 10.16511/ j.cnki.qhdxxb.2010.11.029. (in Chinese)