Next Article in Journal
Performance Analysis of Sparse Matrix-Vector Multiplication (SpMV) on Graphics Processing Units (GPUs)
Next Article in Special Issue
A Low-Cost Platform for Modeling and Controlling the Yaw Dynamics of an Agricultural Tractor to Gain Autonomy
Previous Article in Journal
Research on Optimization of VR Welding Course Development with ANP and Satisfaction Evaluation
Previous Article in Special Issue
Integrating Driving Hardware-in-the-Loop Simulator with Large-Scale VANET Simulator for Evaluation of Cooperative Eco-Driving System
 
 
Font Type:
Arial Georgia Verdana
Font Size:
Aa Aa Aa
Line Spacing:
Column Width:
Background:
Article

Lateral-Acceleration-Based Vehicle-Models-Blending for Automated Driving Controllers

1
TECNALIA, Basque Research and Technology Alliance (BRTA), 48160 Derio, Spain
2
Department of Automatic Control and Systems Engineering, University of the Basque Country (UPV/EHU), 48013 Bilbao, Spain
*
Author to whom correspondence should be addressed.
Electronics 2020, 9(10), 1674; https://doi.org/10.3390/electronics9101674
Submission received: 4 September 2020 / Revised: 26 September 2020 / Accepted: 8 October 2020 / Published: 13 October 2020
(This article belongs to the Special Issue Autonomous Vehicles Technology)

Abstract

:
Model-based trajectory tracking has become a widely used technique for automated driving system applications. A critical design decision is the proper selection of a vehicle model that achieves the best trade-off between real-time capability and robustness. Blending different types of vehicle models is a recent practice to increase the operating range of model-based trajectory tracking control applications. However, current approaches focus on the use of longitudinal speed as the blending parameter, with a formal procedure to tune and select its parameters still lacking. This work presents a novel approach based on lateral accelerations, along with a formal procedure and criteria to tune and select blending parameters, for its use on model-based predictive controllers for autonomous driving. An electric passenger bus traveling at different speeds over urban routes is proposed as a case study. Results demonstrate that the lateral acceleration, which is proportional to the lateral forces that differentiate kinematic and dynamic models, is a more appropriate model-switching enabler than the currently used longitudinal velocity. Moreover, the advanced procedure to define blending parameters is shown to be effective. Finally, a smooth blending method offers better tracking results versus sudden model switching ones and non-blending techniques.

1. Introduction

Trajectory tracking is a crucial task in high driving automation developments. Thus, proper control methods must be designed to safely follow the desired reference path and speed. Model Predictive Control (MPC) is one of the most popular advanced model-based control techniques for this purpose. MPC approaches use the vehicle and tire models to predict the future behavior of the vehicle and compute the optimum control sequence to be applied. Moreover, this latter calculation is carried out considering explicitly the physical constraints of the system and its actuators [1].
A critical design decision in MPC-based methods is the selection of a proper model to predict the behavior of the vehicle, as the controller performance will depend heavily on its accuracy and real-time capability. However, this selection is not a trivial task, as covering a broad range of speeds, even the limits of handling, while maintaining real-time capabilities, represents a current engineering challenge [2].
In the literature, five vehicle-modeling techniques can be found: point-mass, geometric, kinematic, dynamic, and multi-body vehicle models [3,4]. The point-mass modeling considers the vehicle as a particle and it is commonly used in motion planning [5,6]. Even though it considers accelerations, it ignores the turning capacity of the vehicle [4]. The geometric modeling considers the basic geometry of the vehicle and uses its geometric relationships for path tracking [7,8]. Although it offers good robustness in most low-speed maneuvers, it ignores the velocity and forces on the vehicle, which causes poor tracking performance at high speeds and transitional maneuvers [9]. The kinematic modeling is a simplified representation that, besides geometry, considers the orientation, velocity, and acceleration of the vehicle [10]. It provides appropriate performance at low speed (less than 5 m/s) when tire deformations are small and slips angles on the wheels can be neglected [11]. Experimental validations have shown a good performance of model-based controllers at low speeds [12,13]. However, when the lateral forces on tires increase (e.g., while turning at high speeds), its accuracy is compromised [14,15]. The dynamic modeling is a more complex vehicle representation that, besides geometry and kinematics, considers the internal forces and the inertia of the vehicle, providing accurate results in high-speed applications and extreme handling maneuvers [16,17,18]. Its implementation requires a tire model to estimate the longitudinal and lateral tire forces. For this purpose, a linear tire model is typically used, as it represents a good trade-off between computational efficiency and accuracy [19,20,21]. Finally, multi-body modeling is the most accurate representation of vehicle dynamics which is mainly employed as a virtual test platform for driving automation developments. Its high complexity and low computational efficiency make it difficult to implement this method today for real-time applications, therefore it is barely used for motion planning [22]. A comparison of these models in the context of this work is summarized in Table 1.
In MPC designs, kinematic and dynamic models are commonly used, as they present the best accuracy vs. computational cost ratio. Linear MPC approaches have been used to modify dynamically trajectory planners in the case of unexpected situations [23]. However, as seen in Table 1, each model presents strengths in different driving scenarios. Hence, in order to improve trajectory tracking and increase the speed range, recent works have proposed to combine these approaches [24]. This way, some authors have integrated both vehicle models in parallel to estimate more accurately relevant vehicle dynamics behavior, such as the side-slip angle [25] or the vehicle’s position [26,27]. As the previous technique requires computing both models in parallel and increasing the computational effort, in recent years, the so-called model-blending approach has been proposed by some authors [28,29]. In this latter method, a model-switching strategy allows for selecting the most appropriate model depending on the driving scenario, allowing for increasing the validity range of the MPC-based vehicle control approach.
In the aforementioned works, to perform the model-blending technique, two aspects are usually considered: (1) the switching condition and (2) the switching method. The switching condition is the criteria used to select the best model for each driving circumstance. This criterion has to be defined using a variable that allows for optimizing the operative range of each model so that the model-blending effectively improves trajectory tracking. In [28,29], the longitudinal speed is used as the switching condition, selecting the kinematic model to compute MPC predictions when the vehicle moves at low speed while using the dynamic model when moving at high-speed. However, as model validity is limited by the tire model saturation, it seems more appropriate to use another variable to perform the switching which is directly related to the tires’ forces, such as lateral acceleration. Regarding the switching mode, previous works have presented two different methods—firstly, a sudden switch strategy that instantly changes between kinematic and dynamic models [28]; secondly, a progressive switching strategy that performs this change more smoothly using a linear approach [29]. Nevertheless, there is not a recommended procedure to blend models, besides the trial-and-error method.
In this work, a novel vehicle model blending procedure based on lateral acceleration for MPC is proposed. A coupled longitudinal and lateral vehicle dynamics is considered in the MPC formulations for trajectory tracking. The cornering stiffness is constantly estimated for a linear tire–road interaction. Lateral motion is constrained avoiding lane departures. The proposed approach presents three main contributions: (1) the lateral acceleration is selected as the switching condition instead of the longitudinal velocity, as the former is directly associated with the lateral forces on the tires and it defines a more consistent validity application range for each model; (2) a procedure proposal is presented to find the proper lateral acceleration switching value that allows for getting the best performance in terms of path tracking error; and (3) a thorough comparison of the proposed approach is carried out with the kinematic and dynamic vehicle models, as well as the longitudinal velocity as switching condition.
The structure of the paper is as follows: Section 2 presents the vehicle modeling and the combination method for kinematic and dynamic models; Section 3 defines the proposed model blending procedure tuning to achieve the best path-tracking in vehicle model blending; Section 4 details the case study and the MPC-based control architecture used to evaluate the model-blending approaches; Section 5 shows the results of the simulation experiments using a passenger bus in a realistic urban environment, with a detailed analysis and comparisons between switching methods; Section 6 closes with the conclusions and future works.

2. Vehicle Modeling

As previously stated, vehicle motion control based on MPC highly relies on accurate models. In addition, these need to be as simple as possible, so that the proposed trajectory tracking MPCs can be implemented in real-time platforms.
The single-track vehicle model is a well-known simplification broadly used in vehicle control approaches [11,30], where the front and rear wheels are defined as single wheels at each axle. The notation employed is depicted in Figure 1.
Based on this approach, kinematic and dynamic vehicle models are calculated. The equations of motion required for developing the trajectory-tracking control are detailed in Section 2.1 and Section 2.2.

2.1. Kinematic Vehicle Model

Geometric relationships can be used to describe the motion of a vehicle under the assumption that lateral forces on tires do not considerably affect this estimation [11]. According to [31], the kinematic single-track vehicle model is even capable of generating feasible trajectories if the lateral acceleration ( v y ˙ ) does not exceed 0.5 g. The motion equations are given by Equation (1a–c):
(1a) v x ˙ = F x / m (1b) v y ˙ = ( F x tan δ / m + v x Δ δ / cos 2 δ ) l r / ( l f + l r ) (1c) r ˙ = ( F x tan δ / m + v x Δ δ / cos 2 δ ) / ( l f + l r )
where m is the total mass of the vehicle, δ is the front wheel steering angle, Δ δ is the front wheel steering rate, and l f and l r are the distances from the center of gravity of the vehicle (CG) to the front and rear axles, respectively. The longitudinal velocity ( v x ), lateral velocity ( v y ), and yaw rate (r) are calculated with respect to the reference system attached to the CG. v y can be approximated to v y = l r r considering r = v x tan δ / ( l f + l r ) [29]. The longitudinal force ( F x ) acting on the vehicle is described as in Equation (2):
F x = T d P / r e f f R x F a e r o
where T d is the maximum acceleration and braking torque, P is the throttle and brake pedals’ positions and r e f f is the effective tire radius. The force due to rolling resistance for radial-ply truck tires ( R x ) is empirically described by [32] as in Equation (3):
R x = ( 6 e 3 tanh v x + 0.23 e 6 v x 2 ) m g
where tanh v x is included to avoid numerical inconsistencies in MPC formulation when v x 0 , g is the gravity acceleration and v x is defined here in km/h.
Finally, the equivalent longitudinal aerodynamic drag force ( F a e r o ) is defined by [11] as in Equation (4):
F a e r o = 0.5 ρ C d A f v x 2
where ρ is the air density, C d is the drag coefficient, and A f is the frontal area.

2.2. Dynamic Vehicle Model

As the lateral force on the tires increases, the slip angles at the wheels are no longer considered negligible and a dynamic approach becomes necessary [11]. The motion equations in this approach are given by Equation (5a–c):
(5a) v x ˙ = ( F x F y f sin δ + m v y r ) / m (5b) v y ˙ = ( F y f cos δ + F y r m v x r ) / m (5c) r ˙ = ( l f F y f cos δ l r F y r ) / I z
where I z is the yaw axis inertia. The external lateral forces on the front ( F y f ) and rear ( F y r ) axles are in Equation (6a,b):
(6a) F y f = C α f α f (6b) F y r = C α r α r
where C α f and C α r are the cornering stiffness on the front and rear axles, respectively; and α f and α r are the slip angles associated with those axles, defined as
(7a) α f = δ tan 1 ( ( l f r + v y ) / v x ) (7b) α r = tan 1 ( ( l r r v y ) / v x )
The estimation of C α f and C α r is a complex task in a real scenario, as these coefficients represent the interactions between tires and road surface, which may not be linear. Hence, in this work, a procedure to identify these parameters in real time is described in Section 4.2.

2.3. Blended Model for MPC Control

If the operating range of the MPC-based approach is to be increased, blending the aforementioned models is required. Thus, when lateral tire forces can be neglected, the kinematic model provides appropriate and fast results, while the dynamic model is used when tire slip is significant. This way, the set of nonlinear equations used for the longitudinal and lateral MPC is given by Equation (8a–g):
(8a) X ˙ = v x cos ψ v y sin ψ (8b) Y ˙ = v x sin ψ + v y cos ψ (8c) ψ ˙ = r (8d) δ ˙ = Δ δ (8e) v x ˙ = ( 1 λ ) v x ˙ k i n + λ v x ˙ d y n (8f) v y ˙ = ( 1 λ ) v y ˙ k i n + λ v y ˙ d y n (8g) r ˙ = ( 1 λ ) r ˙ k i n + λ r ˙ d y n
where [ X , Y , ψ , δ , v x , v y , r ] T are the states related to the CG. The positions (X,Y) and orientation angle ( ψ ) of the vehicle are considered in global coordinates, while the rest of the variables have been previously defined.
The control parameters [ Δ δ , P ] T are the front wheel angle rate and pedal positions, respectively. The use of incremental variables as Δ δ (used in Equation (1b,c)) allows for including an integrative effect in the MPC controller, which is normalized for actuation stage consistency as detailed in Section 4.6.
The superscripts ( . ) k i n and ( . ) d y n specify the relation of v x , v y and r with the kinematic and dynamic models defined in previous subsections. The parameter λ is selected to switch or blend the two proposed vehicle models. If λ = 0 , then a full kinematic model is applied. On the contrary, if λ = 1 , then a fully dynamic model is engaged. An intermediate value of λ defines a model blended circumstance.
The different strategies selected for model blending are detailed in depth in Section 4.3.

3. Tuning Procedure for Model Blending

As detailed in the Introduction, the blending of vehicle models is based on two aspects: (1) the switching condition, and (2) the switching method.
The switching condition is based on a physical measure usually available on the vehicle’s acquisition, v x being the most used [28]. However, this value is typically defined by the designer by a rule of thumb based on several tests. A clear reference for this value is defined by [11] as 5 m/s, this being the recommended limit to employ the kinematic vehicle model. Nonetheless, this limit does not apply to all cases. For instance, in straight-line motion, lateral forces can be neglected, and the kinematic vehicle model could be considered valid in this condition even after 5 m/s.
The switching method is defined as how the switching condition occurs. As analyzed in Section 1, two main approaches have been proposed: a sudden or step change and a progressive one, in which a linear blending is proposed. According to [29], a progressive transition between models offers a better response in the vehicle motion control in contrast to sudden switching conditions. However, the obtainment of v x values for this progressive blending is a complex task, as more than one reference for the switching condition is necessary and no more than trial-and-error methods are defined to achieve it.
In this work, a novel approach is proposed. The lateral acceleration v y ˙ is considered as the switching condition parameter as it can be directly related to the current lateral forces on tires in any condition. The use of this variable is more consistent with the theoretical assumptions referred by [11] for the kinematic and dynamic vehicle models.
Based on this switching condition, the procedure proposed in Table 2 selects the best switching value of v y ˙ for model blending in step and linear methods. The lateral ( e y ) and angular ( e ψ = ψ ψ r ) errors are considered as key metrics.
This procedure will be applied for the case study proposed in the next section, and the results will be detailed in Section 5.1.

4. Case Study: An Urban Passenger Bus

In this section, the proposed vehicle model blending procedure is applied to a particular case study based on a trajectory tracking MPC for a passenger bus in an urban environment. The overall control architecture of the proposed case study, including the test vehicle and the MPC controller, is depicted in Figure 2.

4.1. Test Vehicle

The vehicle model employed is an electric passenger bus conceived for urban environments as depicted in Figure 3.
The test vehicle has been modeled in Dynacar [33] considering a multi-body formulation. A steering-knuckle-type suspension at the front axle and a rigid-axle-type suspension at the rear axle is linked to the chassis. Two wheels on the front and four wheels at the rear are linked to suspensions. The Pacejka tire model of a standard tire defined in [34] has been employed. Vehicle parameters are depicted in Table 3. Where T m , T b and T r are the motor, braking, and regenerative brake torques, N t and N δ are the transmission and the front-wheel-angle/steering-wheel-angle ratio, I t and I d are the transmission and drive-line inertia, respectively.

4.2. Cornering Stiffness Identification

The dynamic model detailed in Section 2.2 requires the knowledge of the cornering stiffness coefficients that characterize the tire and road interaction. As the identification of these parameters is complex, an approach based on the direct method described by [35] is proposed.
One advantage of this method is the capacity to use the dynamic vehicle model employed for trajectory-tracking, as a simplified lateral tire model [11]. The C α f and C α r values depend on vehicle parameters as m, I z , l f and l r , and real-time measures of δ , v x , v y and r as described in Equation (9).
C α f C α r = 2 α f 2 α r 2 l f α f 2 l r α r 1 m ( v y ˙ + v x r ) I z r ˙
where α f and α r are defined previously in Equation (7a,b).
After the estimation of cornering stiffnesses, two separate one-dimensional Kalman filters reduce peak values from numerical inconsistencies in both C α f and C α r . The filters are evaluated in the discrete-time domain, no control input is considered, and gain matrices related to states and measurement are constants valued as 1 [35,36]. The process and measurement noise covariances are settled to 0.01 N/rad and 1 N/rad, respectively. In this work, the Kalman Filter block from MATLAB/Simulink was employed for this purpose.
In contrast to [35], the use of a linear Kalman filter avoids the definition of a threshold limit for α f and α r , as the slip angles would approach to zero when the vehicle is driving straight or during transient steering maneuvers, affecting the cornering stiffness calculation. These results are explained in Section 5.3.

4.3. Switching Model

As previously stated, both the kinematic and dynamic models defined in Section 2 will be implemented in the MPC. Two different types of blending methods based on v y ˙ are proposed in this work for comparison purposes. Firstly, a step switch which causes a sudden change between kinematic and dynamic models. Secondly, a linear switch which executes a progressive change between models. The switching parameter λ defined in Equation (a–g) is defined by Equation (10):
λ = min [ max [ | v y ˙ | v y ˙ m i n v y ˙ m a x v y ˙ m i n , 0 ] , 1 ]
where v y ˙ m i n and v y ˙ m a x are the minimum and maximum acceleration thresholds defined by the switching designer (see Section 5.1 for more details). On the one hand, for the step method, v y ˙ m i n = v y ˙ m a x is employed, where the change between kin and dyn models is performed when the sign from the estimation ( | v y ˙ | v y ˙ m i n ) / 0 results in , therefore switching λ between 0 1 , respectively. On the other hand, for the linear method, v y ˙ m i n < v y ˙ m a x is applied.
Additionally, a third switching strategy, called speed is considered for comparison purposes. This strategy, as proposed by [11], suddenly switches between the kinematic and dynamic models at 5 m/s and will be considered as a benchmarking strategy. Therefore, Equation (10) is also employed using v x as switching condition instead of v y ˙ .

4.4. Trajectory Planner

The planned trajectory considers a realistic urban scenario with a total travel distance of approximately 680 m. It contains a couple of roundabouts with maximum curvatures (k) of around 0.08 m 1 connected through an avenue with smoother paths. The motion planner is based on parametric Bézier curves [37], considering the center-path of the road’s right-lane. The starting vehicle’s position and orientation, including the curvature segments, are depicted in Figure 4.
Considering the MPC’s predictions ( [ X , Y ] ), new positions and orientations are estimated repeatedly at each iteration as new references for trajectory tracking ( [ X , Y , ψ , v x ] ). Additionally, the center-lane path’s border positions are continuously considered ( [ X L , X R , Y L , Y R ] ), using them as path constraints to avoid lane departures.
As this investigation is focused on the kinematic and dynamic models transitional effects over vehicle motion control, the round-about on the right side in Figure 4 is planned using non-smooth curvatures provoking high lateral accelerations, which will help to analyze the model blending efficacy in extreme handling maneuvers.

4.5. Model Predictive Control

The developed MPC approach performs the longitudinal and lateral vehicle motion control of the trajectory defined in Section 4.4. It makes use of the blended model defined in Section 2.3, requiring an appropriate switching method for model change (i.e., the ones proposed in Section 4.3).
As the vehicle models are nonlinear, the proposed approach is a nonlinear MPC, which also includes a set of state and control constraints, designed to guarantee a safe execution of the dynamic driving task. The problem formulation is solved at each time step with a prediction horizon defined as i , i + 1 , . . . , i + N is presented in Equation (11a,d):
min s ( · ) , u ( · ) 1 2 i = 0 N 1 s i s i r e f Q 2 + u i R 2 s . t .
(11b) s i + 1 = f d ( s i , u i , λ i ) , i = 0 , . . . , N 1 (11c) s ̲ s i s ¯ , i = 0 , . . . , N 1 (11d) u ̲ u i u ¯ , i = 0 , . . . , N 1
where the Q = diag( q X , q Y , q ψ , q v x ) and R = diag( q Δ δ , q P ) are the weight matrices associated with the state tracking and control inputs, respectively (Equation (11a)).
The s i + 1 = f d ( s i , u i , λ i ) represents the blended model defined in Section 2.3. The states s i = [ X , Y , ψ , v x ] i T are minimized according to the driving route geometry, orientation, and velocity references ( s i r e f ). The control parameters u i = [ Δ δ , P ] i T are minimized to values as close to zero as possible to avoid sudden changes in control parameters. The switching parameter ( λ ) plays an important role in the formulation (Equation (11b)). The weights are set to q X = q Y = q ψ = q v x = 1 and q Δ δ = q P = 10.
Constraints (Equation (11c,d)) are defined for both the states s i = [ X , Y , δ , v x ] i T as [X L , R , Y L , R , ±0.68 rad, v x r e f ]; and control parameters u i = [ Δ δ , P ] i T as ± [0.5 rad/s, 1]. Keeping the vehicle on the planned path to avoid undesired lane departures is considered through additional soft constraints [X L , R , Y L , R ] as depicted in Figure 5. An additional distance ( d w = 0.2 m) is taken into account to avoid unfeasible solutions when results from | X i L X i R | or | Y i L Y i R | are near to zero.
The path borders are obtained from the planned trajectory considering a continuous lane-width along the route, permitting a maximum lateral displacement from the center-lane path of 0.725 m. The constraint values for path borders are processed in real-time as described in Equation (12a–d):
(12a) X i ̲ = min ( [ X i L , X i R , X i r e f d w ] ) (12b) X i ¯ = max ( [ X i L , X i R , X i r e f + d w ] ) (12c) Y i ̲ = min ( [ Y i L , Y i R , Y i r e f d w ] ) (12d) Y i ¯ = max ( [ Y i L , Y i R , Y i r e f + d w ] )
Minimizing Equation 11a allows for calculating the optimum value of u = [ Δ δ , P ] i T for the current time step. For that purpose, the nonlinear MPC is solved with the automatic code generator of the open-source ACADO toolkit [38], using QPOASES as the set solver, the sequential programming technique, and the direct multiple-shooting method for discretization. The prediction horizon is 5 s of look-ahead time considering a fixed time step among predictions of 0.5 s.

4.6. Actuation Stage

The control variable Δ δ calculated by the MPC is integrated at this stage to obtain a δ normalized between [−1, 1] considering a maximum value of δ = 0.68 rad. The control variable P is constrained between [−1, 1] in the MPC formulation and represents the maximum brake and throttle pedal positions, respectively. Actuation delays of 150 ms for accelerator and 80 ms for both steering wheel and brake pedal were approximated by second-order transfer functions. In addition, rate limitations are applied mimicking a real actuation behavior [13,39].

5. Results and Discussion

The performance evaluation of vehicle models and switching methods employed are detailed in this section. The elements in the control architecture defined in Figure 2 and detailed in Section 4 are implemented in a MATLAB/Simulink setup which is used to perform a simulation-based analysis.
Considering the tuning procedure defined in Section 3, the parameters to perform the three switching methods introduced in Section 4.3 (step, linear and speed) are defined and evaluated first. In addition, pure kinematic (kin) and dynamic (dyn) methods are considered for comparison.
Three complete laps are simulated in the defined scenario (Figure 4), the results being recorded and evaluated. Eight values for v x r e f are defined from 1.1 m/s to 8.8 m/s, equally spaced at 1.1 m/s for each simulation test. This will allow for studying the influence of v x and the lateral acceleration ( a y ) in the lateral motion control for the defined route.

5.1. Tuning Procedure for Model Blending

In this section, the procedure defined in Section 3 is applied to select the best switching value for v y ˙ for model blending in the step and linear methods. Note that the speed method is based on the v x as proposed in [11]. In the latter case, a step method is applied, in which a kinematic model is used below 5 m/s, and a dynamic model at higher speeds.
The results of the step-by-step procedure are detailed next.
Steps 1 to 5: Once the planned route for trajectory-tracking of Section 4.4 is defined, the vehicle motion control is executed using kin and dyn vehicle models at several v x r e f as described previously. The median is estimated for the absolute values | e y | and | e ψ | considering kin ( . ) k i n and dyn ( . ) d y n models in a grid of v x r e f vs a y . In practice, the median provides a better estimation in contrast to mean values for the cut-off definition pointed in Steps 6a–c. Results are processed through a two-dimensional convolution [40] creating surface plots as depicted in Figure 6.
The e y k i n and e y d y n results are depicted in Figure 6a, in blue and red, respectively. The influence of a y is remarkable along several v x r e f tested, having a clear limit from kin and dyn surface intersections. These surface intersections help to prove the initial hypothesis which presents a y as a more appropriate switching condition than v x .
The e ψ k i n and e ψ d y n results are depicted in Figure 6b, in blue and red, respectively. There is no clear influence of a y or v x on the improvement of the path-tracking performance in terms of e ψ , as kin and dyn models seem to have similar behavior. These findings motivate the idea of selecting e y over e ψ as the basis for a switching strategy.
Steps 6a–c (stepblending): A linear regression is calculated from e y k i n , d y n vs a y as showed in Figure 7a (i.e., considering all the values of e y k i n , d y n , associated with a certain a y and all related v x r e f values). The intersection of L R k i n and L R d y n is approximately in 1.5 m/s 2 , this being a useful cut-off value to define the switching condition to a y . This value allows for obtaining the lowest e y values for kin and dyn models. As stated previously, if the same procedure is applied to e ψ k i n , d y n (Figure 7b), no relevant results can be extracted, as both models have similar performance.
Steps 7a–d (linearblending): The a y becomes relevant around 1 m/s 2 as depicted in Figure 6a. This is the lowest a y value that can be extracted from the surface intersection, which is useful for defining the initial condition of a progressive switching between models. In addition, the step switching (defined at 1.5 m/s 2 ) is considered as the point of symmetry to this initial condition. Therefore, the linear switching is determined from 1 m/s 2 to 2 m/s 2 being centered around the step switching condition. The switching methods for model blending based on λ ∈ [0, 1] are presented in Figure 8a.

5.2. Trajectory-Tracking Response Analysis

Results for three-of-eight simulation tests at constant v x r e f have been selected for discussion simplicity (2.2 m/s, 5.5 m/s, and 8.8 m/s). The linear method has been chosen for Figure 8b–d as it presents the best performance compared to other methods. The route values (black line) are located at zero values on z-axis as a reference, and the z-axis limits correspond to minimum and maximum estimation values of v x , a y , and e y , respectively.
Figure 8b shows the v x of the bus for the linear method. Although the v x r e f is set as constant, note that the MPC regulates the final speed to avoid lane-departures (e.g., v x r e f = 8.8 m/s) as defined in Section 4.5. Hence, this is considered as a proper performance.
Figure 8c shows the a y of the bus. Larger values are obtained while turning as the v x r e f increases. Important transitions are observed mostly on the roundabout at the right-side due to non-smooth planned curvatures. This transitional behavior is observed in a y results independently of the tested v x r e f , a phenomenon that is not acquired previously in v x results.
Figure 8d shows the e y of the bus, which is calculated by considering the road’s center-lane and the current position at each time step. The transitional effects described in a y seem to affect the e y response, and, therefore, the path tracking.
The former results demonstrate that the MPC with the linear method provides an appropriate trajectory tracking.

5.3. Cornering Stiffness Estimation Analysis

Results for three-of-eight simulation tests at constant v x r e f have been selected for discussion simplicity (1.1 m/s, 4.4 m/s and 8.8 m/s). The dyn method has been chosen for Figure 8e–f as it uses the cornering stiffness estimation in the whole range of v x r e f . The route values (black line) is located at zero values on z-axis as a reference, and the z-axis limits correspond to minimum and maximum estimation values of both C α f and C α f , respectively.
Results for C α f and C α f for the dyn method are presented in Figure 8e–f, respectively. These values are obtained at continuous turning maneuvers both at the front and rear axles. As expected, the estimations behave bumpily when steer angles are near zero, since they imply the inverse of a near-zero matrix (see Section 4.2). In practical terms, this results in larger variations of slip angles that are later attenuated by the linear Kalman filter. Consequently, the dyn method deteriorates the path-tracking at straight driving even if the vehicle is driving at high speed. This supports the main rationale to switch to kin method in this driving condition, even for v x > 5 m/s, which is successfully achieved by the proposed a y -based blending approach as opposed to the suggestion made by the existing v y -based approach.

5.4. Lateral and Angular Error Analysis

Figure 9a,b shows the statistical distribution of e y and e ψ for five study conditions related to the five analyzed methods, allowing comparison for their trajectory-tracking performance. The boxes span (blue boxes) cover from 2% to 98% of the data, the whiskers span (black lines) cover from 1% to 99% of the data, the median (red horizontal lines) and mean ( μ , red plus signs) values as statistical metrics assessment.
In Figure 9a, it can be seen that, for this low speed test track, the kinematic model (kin) clearly outperforms the dynamic model (dyn) as expected. However, blending these two models can produce better results than either one of them individually. Note that this particular track has the most low speed turns towards the left, whereas right-hand turns are mostly high speed. This allows for exemplifying the limitations of the speed method. Its positive e y distribution resembles the kinematic model behavior, while the negative side is much closer to the dynamic model. Since they can be correlated to the left and right-hand turns and thus the predominantly high and predominantly low speeds, it becomes clear that blending based on the speed uses either model in some cases where the other one behaves better (i.e., on the high speed turns, it uses the dynamic approximation even if the lateral forces are low and the kinematic model behaves better).
On the other hand, the hereby introduced switching strategies (linear and step), based on lateral acceleration, provide better behavior than the use of either kinematic or dynamic models, or even the aforementioned blending approach based on the speed (speed). This is achieved by actually switching when the lateral forces are significant, thus properly using the best approach in every condition to reduce errors (see Figure 6), rather than just avoiding singularities (which is the main motivation for the speed based blending). Since most of the track has low lateral acceleration, most of the error distribution for both a y -based methods (linear and step) resembles the kinematic model behavior (see the blue boxes in Figure 9a, associated with the 2%–98% data interval). However, the black whiskers do show a significant improvement in reducing the lateral error corresponding to those cases with either high lateral acceleration and low speed or those of high speed and low lateral acceleration, thus proving the advantage of introducing the lateral acceleration as the blending parameter in place of the currently accepted vehicle velocity.
Furthermore, it is noted that the linear blending is slightly better than the step in terms of the maximum dispersion (black whiskers), though the actual advantage of this technique relates to the computational cost, as will become evident in the discussion below.
Figure 9b shows that the e ψ behaves very similarly regardless of the implementation of either of the analyzed methods, which fit the results shown in Section 5.1 and endorse the decision of considering e y surfaces for the blending procedure.

5.5. Computational Cost Analysis

To demonstrate the real-time capability of the presented approach, computational cost analysis has been carried out. The required time to calculate each control cycle of the proposed MPC controllers with the different blending methods has been evaluated. All controllers were execute at a 10 ms period on a LATITUDE E5570 provided with an Intel Core i7-6600U, CPU 2.60GHz (Santa Clara, California, USA). The results are depicted in Figure 9c, in which the statistical distribution of the solving time is depicted, following the same representation applied to Figure 9a–b. It can be seen where the worst-case scenario is for the step and dyn approaches, with mean values of 0.04 ms and maximums of nearly 0.08 ms. On the contrary, the linear method offers the best time efficiency with a mean value of 0.03 ms and a maximum solving time of 0.07 ms. Hence, results demonstrate that computational cost can be reduced by the use of blended models.
Note that all the referred approaches are based on a nonlinear MPC. In this case study, the previously calculated state and input values are used as a seed for the next iteration. Hence, when sudden or abrupt changes are required, the number of iterations required to solve the MPC problem increases significantly as depicted in Figure 9d. For instance, this happens when a sudden transition from a kinematic to a dynamic model is carried out in the step method. In this sense, the linear method reduces the required computational cost by lowering the number of iterations required to solve the optimization problem in the blending procedure to even slightly better values than the simple kinematic model.

6. Conclusions

The performance of MPC-based tracking controllers in automated vehicles is highly dependent on the selection of the model, either kinematic or dynamic. The kinematic enables accuracy at low a y , e.g., driving straight. However, the dynamic provides better overall results when a y becomes representative, e.g., turning or steering transient maneuvers. To cover a wide operational range, switching or blending from one model to the other has been proposed in the literature. In particular, proposed approaches’ use of the longitudinal velocity as the switching condition, which does not offer the best performance. Moreover, there is a lack of works related to the proper tuning of model-blending.
In this study, the use of the a y as opposed to the v x is proposed as the switching condition to blend vehicle models within an MPC-based trajectory tracking control. As tire forces are the critical factor for the validity of the kinematic/dynamic models, the a y is considered as a variable with direct relation to these forces, allowing for increasing the overall performance of the blended approach. Additionally, a formal step-by-step tuning approach is proposed and detailed for two methods: linear and step.
The presented method is tested in a case study with an electric passenger bus in a virtual urban scenario. Results show that the proposed blending approaches based on a y provide a relative improvement of 15% in terms of e y , in contrast to the method based on v x proposed in the literature. Additionally, it allows for reducing the maximum computational cost in 12% if a linear blending approach is used. Moreover, the validity of the tuning procedure is demonstrated.
Future works will assess the concepts presented in this research on both Hardware-in-the-Loop tests verification and real test platform validations, including the implementation issues related to parameters and variable estimations.

Author Contributions

Conceptualization, J.A.M.-P., and S.D.; methodology, J.A.M.-P., and S.D.; software, J.A.M.-P.; formal analysis, J.A.M.-P., and S.D., investigation J.A.M.-P. and S.D.; writing—original draft preparation, J.A.M.-P.; writing—review and editing, J.A.M.-P., M.M., S.D., A.Z., and J.P.; supervision, A.Z., and J.P. All authors have read and agreed to the published version of the manuscript.

Funding

This research was funded by AUTODRIVE within the Electronic Components and Systems for European Leadership Joint Undertaking (ECSEL JU) in collaboration with the European Union’s H2020 Framework Program (H2020/2014-2020) and National Authorities, under Grant No. 737469.

Conflicts of Interest

The authors declare no conflict of interest.

References

  1. Dixit, S.; Fallah, S.; Montanaro, U.; Dianati, M.; Stevens, A.; Mccullough, F.; Mouzakitis, A. Trajectory planning and tracking for autonomous overtaking: State-of-the-art and future prospects. Annu. Rev. Control 2018, 45, 76–86. [Google Scholar] [CrossRef]
  2. Eskandarian, A.; Wu, C.; Sun, C. Research Advances and Challenges of Autonomous and Connected Ground Vehicles. IEEE Trans. ITS 2019, 1–29. [Google Scholar] [CrossRef]
  3. Sorniotti, A.; Barber, P.; De Pinto, S. Path tracking for automated driving: A tutorial on control system formulations and ongoing research. In Automated Driving; Springer: Cham, Switerland, 2017; pp. 71–140. [Google Scholar]
  4. Althoff, M. CommonRoad: Vehicle Models; Technische niversität München: Garching, Germany, 2017; pp. 1–25. [Google Scholar]
  5. Tomas-Gabarron, J.B.; Egea-Lopez, E.; Garcia-Haro, J. Vehicular trajectory optimization for cooperative collision avoidance at high speeds. IEEE Trans. ITS 2013, 14, 1930–1941. [Google Scholar] [CrossRef]
  6. González, D.; Pérez, J.; Milanés, V.; Nashashibi, F. A Review of Motion Planning Techniques for Automated Vehicles. IEEE trans. Intell. Transp. Syst. 2016, 17, 1135–1145. [Google Scholar] [CrossRef]
  7. Snider, J.M. Automatic Steering Methods for Autonomous Automobile Path Tracking; Tech. Rep. CMU-RITR-09-08; Robotics Institute: Pittsburgh, PA, USA, 2009. [Google Scholar]
  8. Thrun, S.; Montemerlo, M.; Dahlkamp, H.; Stavens, D.; Aron, A.; Diebel, J.; Fong, P.; Gale, J.; Halpenny, M.; Hoffmann, G.; et al. Stanley: The robot that won the DARPA Grand Challenge. J. Field Robot. 2006, 23, 661–692. [Google Scholar] [CrossRef]
  9. Amer, N.H.; Zamzuri, H.; Hudha, K.; Kadir, Z.A. Modelling and control strategies in path tracking control for autonomous ground vehicles: A review of state of the art and challenges. J. Intell. Robot. Syst. 2017, 86, 225–254. [Google Scholar] [CrossRef]
  10. Jazar, R.N. Vehicle Dynamics: Theory and Application; Springer: Cham, Switerland, 2017. [Google Scholar]
  11. Rajamani, R. Vehicle Dynamics and Control; Springer S&B Media: Boston, MA, USA, 2011. [Google Scholar]
  12. Matute, J.A.; Marcano, M.; Diaz, S.; Perez, J. Experimental Validation of a Kinematic Bicycle Model Predictive Control with Lateral Acceleration Consideration. IFAC-PapersOnLine 2019, 52, 289–294. [Google Scholar] [CrossRef]
  13. Matute-Peaspan, J.A.; Zubizarreta-Pico, A.; Diaz-Briceno, S.E. A Vehicle Simulation Model and Automated Driving Features Validation for Low-Speed High Automation Applications. IEEE trans. Intell. Transp. Syst. 2020, 1–10. [Google Scholar] [CrossRef]
  14. Gao, Y.; Gray, A.; Tseng, H.E.; Borrelli, F. A tube-based robust nonlinear predictive control approach to semiautonomous ground vehicles. Veh. Syst. Dyn. 2014, 52, 802–823. [Google Scholar] [CrossRef]
  15. Schildbach, G.; Borrelli, F. Scenario model predictive control for lane change assistance on highways. In Proceedings of the 2015 IEEE Intelligent Vehicles Symposium (IV), Seoul, Korea, 28 June–1 July 2015; pp. 611–616. [Google Scholar]
  16. Liniger, A.; Domahidi, A.; Morari, M. Optimization-based autonomous racing of 1:43 scale RC cars. Optim. Control Appl. Methods 2015, 36, 628–647. [Google Scholar]
  17. Levinson, J.; Askeland, J.; Becker, J.; Dolson, J.; Held, D.; Kammel, S.; Kolter, J.Z.; Langer, D.; Pink, O.; Pratt, V.; et al. Towards fully autonomous driving: Systems and algorithms. In Proceedings of the 2011 IEEE Intelligent Vehicles Symposium (IV), Baden-Baden, Germany, 5–9 June 2011; pp. 163–168. [Google Scholar]
  18. Beal, C.E.; Gerdes, J.C. Model predictive control for vehicle stabilization at the limits of handling. IEEE Trans. CST 2012, 21, 1258–1269. [Google Scholar] [CrossRef]
  19. Tagne, G.; Talj, R.; Charara, A. Design and comparison of robust nonlinear controllers for the lateral dynamics of intelligent vehicles. IEEE Trans. ITS 2015, 17, 796–809. [Google Scholar] [CrossRef]
  20. Kritayakirana, K.; Gerdes, J.C. Autonomous vehicle control at the limits of handling. Int. J. Veh. Auton. Syst. 2012, 10, 271–296. [Google Scholar] [CrossRef]
  21. Besselmann, T.; Morari, M. Autonomous vehicle steering using explicit LPV-MPC. In Proceedings of the 2009 European Control Conference (2009 ECC), Budapest, Hungary, 23–26 August 2009; pp. 2628–2633. [Google Scholar]
  22. Bertolazzi, E.; Biral, F.; Da Lio, M. Real-time motion planning for multibody systems. MSD 2007, 17, 119–139. [Google Scholar] [CrossRef]
  23. Lattarulo, R.; He, D.; Pérez, J. A Linear Model Predictive Planning Approach for Overtaking Manoeuvres Under Possible Collision Circumstances. In Proceedings of the 2018 IEEE Intelligent Vehicles Symposium (IV), Changshu, China, 26–30 June 2018; pp. 1340–1345. [Google Scholar]
  24. Rupp, A.; Stolz, M. Survey on control schemes for automated driving on highways. In Automated Driving; Springer: Cham, Switerland, 2017; pp. 43–69. [Google Scholar]
  25. Kim, C.i.; Kim, M.s.; Lee, K.s.; Jang, H.S.; Park, T.S. Development of a full speed range path-following system for the autonomous vehicle. In Proceedings of the 2015 15th International Conference on Control, Automation and Systems (ICCAS), Busan, Korea, 13–16 October 2015; pp. 710–715. [Google Scholar]
  26. Jo, K.; Chu, K.; Lee, K.; Sunwoo, M. Integration of multiple vehicle models with an IMM filter for vehicle localization. In Proceedings of the 2010 IEEE Intelligent Vehicles Symposium, La Jolla, CA, USA, 21–24 June 2010; pp. 746–751. [Google Scholar]
  27. Kang, C.M.; Lee, S.H.; Chung, C.C. Vehicle lateral motion estimation with its dynamic and kinematic models based interacting multiple model filter. In Proceedings of the 2016 IEEE 55th Conference on Decision and Control (CDC), Las Vegas, NV, USA, 12–14 December 2016; pp. 2449–2454. [Google Scholar]
  28. Ritschel, R.; Schrödel, F.; Hädrich, J.; Jäkel, J. Nonlinear model predictive path-following control for highly automated driving. IFAC-PapersOnLine 2019, 52, 350–355. [Google Scholar] [CrossRef]
  29. Kabzan, J.; Valls, M.d.l.I.; Reijgwart, V.; Hendrikx, H.F.C.; Ehmke, C.; Prajapat, M.; Bühler, A.; Gosala, N.; Gupta, M.; Sivanesan, R.; et al. Amz driverless: The full autonomous racing system. arXiv 2019, arXiv:1905.05150. [Google Scholar]
  30. Carvalho, A.; Lefévre, S.; Schildbach, G.; Kong, J.; Borrelli, F. Automated driving: The role of forecasts and uncertainty—A control perspective. Eur. J. Control 2015, 24, 14–32. [Google Scholar] [CrossRef] [Green Version]
  31. Polack, P.; Altché, F.; d’Andréa Novel, B.; de La Fortelle, A. The kinematic bicycle model: A consistent model for planning feasible trajectories for autonomous vehicles? In Proceedings of the 2017 IEEE Intelligent Vehicles Symposium (IV), Los Angeles, CA, USA, 11–14 June 2017; pp. 812–818. [Google Scholar]
  32. Wong, J.Y. Theory of Ground Vehicles; John Wiley & Sons: Hoboken, NJ, USA, 2008. [Google Scholar]
  33. Pena, A.; Iglesias, I.; Valera, J.; Martin, A. Development and validation of Dynacar RT software, a new integrated solution for design of electric and hybrid vehicles. EVS26 Los Angeles 2012, 26, 1–7. [Google Scholar]
  34. Pacejka, H. Tire and Vehicle Dynamics; Elsevier: Amsterdam, The Netherlands, 2005. [Google Scholar]
  35. Sierra, C.; Tseng, E.; Jain, A.; Peng, H. Cornering stiffness estimation based on vehicle lateral dynamics. Veh. Syst. Dyn. 2006, 44, 24–38. [Google Scholar] [CrossRef]
  36. Welch, G.; Bishop, G. An Introduction to the Kalman Filter (TR95-041); Department of Computer Science, University of North Carolina at Chapel Hill: Chapel Hill, NC, USA, 2006; 27599-3175. [Google Scholar]
  37. Lattarulo, R.; González, L.; Martí, E.; Matute, J.; Marcano, M.; Pérez, J. Urban motion planning framework based on n-bézier curves considering comfort and safety. J. Adv. Transp. 2018. [Google Scholar] [CrossRef]
  38. Houska, B.; Ferreau, H.J.; Diehl, M. ACADO toolkit—An open-source framework for automatic control and dynamic optimization. Optim. Control Appl. Methods 2011, 32, 298–312. [Google Scholar] [CrossRef]
  39. Marcano, M.; Matute, J.A.; Lattarulo, R.; Martí, E.; Pérez, J. Low speed longitudinal control algorithms for automated vehicles in simulation and real platforms. Complexity 2018, 2018. [Google Scholar] [CrossRef]
  40. Marques, O. Practical Image and Video Processing Using MATLAB; John Wiley & Sons: Hoboken, NJ, USA, 2011. [Google Scholar]
Figure 1. Vehicle modeling notation.
Figure 1. Vehicle modeling notation.
Electronics 09 01674 g001
Figure 2. Control architecture.
Figure 2. Control architecture.
Electronics 09 01674 g002
Figure 3. Test vehicle.
Figure 3. Test vehicle.
Electronics 09 01674 g003
Figure 4. Planned trajectory considering the vehicle’s maximum turning.
Figure 4. Planned trajectory considering the vehicle’s maximum turning.
Electronics 09 01674 g004
Figure 5. Path borders as constraints.
Figure 5. Path borders as constraints.
Electronics 09 01674 g005
Figure 6. (a) e y and (b) e ψ for kin and dyn considering v x r e f and a y .
Figure 6. (a) e y and (b) e ψ for kin and dyn considering v x r e f and a y .
Electronics 09 01674 g006
Figure 7. Linear regression in (a) e y finding the a y “cut-off” and (b) e ψ .
Figure 7. Linear regression in (a) e y finding the a y “cut-off” and (b) e ψ .
Electronics 09 01674 g007
Figure 8. Results for: (a) switching methods for model blending; (b) v x ; (c) a y and (d) e y for linear method; (e) C α f and (f) C α r for the dyn method.
Figure 8. Results for: (a) switching methods for model blending; (b) v x ; (c) a y and (d) e y for linear method; (e) C α f and (f) C α r for the dyn method.
Electronics 09 01674 g008
Figure 9. Results for: (a) e y , (b) e ψ , and (c) solving time statistics; (d) iterations number vs. λ for different methods.
Figure 9. Results for: (a) e y , (b) e ψ , and (c) solving time statistics; (d) iterations number vs. λ for different methods.
Electronics 09 01674 g009
Table 1. Comparison of vehicle models in terms of performance and applications.
Table 1. Comparison of vehicle models in terms of performance and applications.
ModelStrength(s)Weakness(es)Applications
Point-Mass- Simplest model- Ignores minimum turning- Motion planning
- Easiest implementation
Geometric- Considers minimum turn- Ignores internal forces- Motion planning/tracking
- Robust in most maneuvers- Ignores vehicle acceleration- Low speeds
- Not suitable for high speeds- Constant speed/curvature
Kinematic- Simple motion description- No wheel’s slip/skid- Motion planning/tracking
- Considers chassis slip- Speed range is limited- Low speeds (<5 m/s)
- Varying speed/curvature
Dynamic- Accurate motion estimate- Tire forces calculus- Motion planning/tracking
- Handling dynamics- Less numerical efficiency- High speeds (>5 m/s)
- Stability at handling limit- ∞ linear tire model (V x 0)- Varying speed/curvature
- Chassis slip angles < 5 deg
Multi-body- Best accuracy- Low numerical efficiency- Motion planning
- All suspension forces- Complex implementation- Virtual test platform
Table 2. Tuning procedure for model blending.
Table 2. Tuning procedure for model blending.
StepsProcedure
1.Plan a route for trajectory-tracking at constants v x r e f
2.Execute motion control using kinematic vehicle model
3.Execute motion control using dynamic vehicle model
4.Average e y k i n , d y n values in a grid of v x r e f vs v y ˙
5.Create surface plots from 4
6.For step switching method:
 6.a.Make Linear Regressions (LR) of e y k i n , d y n vs v y ˙
 6.b.Intersect LRs to find a v y ˙
 6.c.The step switch is defined by 6b
7.For linear switching method:
 7.a.Identify lowest v y ˙ in surfaces intersection from 5
 7.b.Estimate difference between 6b and 7a
 7.c.Use 6b as point symmetry distance to 7a
 7.d.The linear switch is defined by 7c
Table 3. Parameters of the Passenger Bus Model.
Table 3. Parameters of the Passenger Bus Model.
ParameterValueUnitParameterValueUnit
l f 3.55mm16,600kg
l r 2.22m I z 115,063kg-m 2
A f 7.34m 2 C d 0.65-
ρ 1.21kg/m 3 g9.81m/s 2
T m 3600N-m N t 1:5.93-
T b 12,000N-m N δ 31:1-
T r 35N-m I t 17kg-m 2
r e f f 0.45m I d 100kg-m 2

Share and Cite

MDPI and ACS Style

Matute-Peaspan, J.A.; Marcano, M.; Diaz, S.; Zubizarreta, A.; Perez, J. Lateral-Acceleration-Based Vehicle-Models-Blending for Automated Driving Controllers. Electronics 2020, 9, 1674. https://doi.org/10.3390/electronics9101674

AMA Style

Matute-Peaspan JA, Marcano M, Diaz S, Zubizarreta A, Perez J. Lateral-Acceleration-Based Vehicle-Models-Blending for Automated Driving Controllers. Electronics. 2020; 9(10):1674. https://doi.org/10.3390/electronics9101674

Chicago/Turabian Style

Matute-Peaspan, Jose A., Mauricio Marcano, Sergio Diaz, Asier Zubizarreta, and Joshue Perez. 2020. "Lateral-Acceleration-Based Vehicle-Models-Blending for Automated Driving Controllers" Electronics 9, no. 10: 1674. https://doi.org/10.3390/electronics9101674

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