Next Article in Journal
A Self-Supervised Point Cloud Completion Method for Digital Twin Smart Factory Scenario Construction
Previous Article in Journal
Development of Water Quality Analysis for Anomaly Detection and Correlation with Case Studies in Water Supply Systems
Previous Article in Special Issue
A Novel Approach for Self-Driving Vehicle Longitudinal and Lateral Path-Following Control Using the Road Geometry Perception
 
 
Font Type:
Arial Georgia Verdana
Font Size:
Aa Aa Aa
Line Spacing:
Column Width:
Background:
Article

Learning-Based MPC Leveraging SINDy for Vehicle Dynamics Estimation

by
Francesco Paparazzo
*,
Andrea Castoldi
,
Mohammed Irshadh Ismaaeel Sathyamangalam Imran
,
Stefano Arrigoni
and
Francesco Braghin
Department of Mechanical Engineering, Politecnico di Milano, Via La Masa 1, 20156 Milano, Italy
*
Author to whom correspondence should be addressed.
Electronics 2025, 14(10), 1935; https://doi.org/10.3390/electronics14101935
Submission received: 4 April 2025 / Revised: 5 May 2025 / Accepted: 7 May 2025 / Published: 9 May 2025
(This article belongs to the Special Issue Feature Papers in Electrical and Autonomous Vehicles)

Abstract

:
Self-driving technology aims to minimize human error and improve safety, efficiency, and mobility through advanced autonomous driving algorithms. Among these, Model Predictive Control (MPC) is highly valued for its optimization capabilities and ability to manage constraints. However, its effectiveness depends on an accurate system model, as modeling errors and disturbances can degrade performance, making uncertainty management crucial. Learning-based MPC addresses this challenge by adapting the predictive model to changing and unmodeled conditions. However, existing approaches often involve trade-offs: robust methods tend to be overly conservative, stochastic methods struggle with real-time feasibility, and deep learning lacks interpretability. Sparse regression techniques provide an alternative by identifying compact models that retain essential dynamics while eliminating unnecessary complexity. In this context, the Sparse Identification of Nonlinear Dynamics (SINDy) algorithm is particularly appealing, as it derives governing equations directly from data, balancing accuracy and computational efficiency. This work investigates the use of SINDy for learning and adapting vehicle dynamics models within an MPC framework. The methodology consists of three key phases. First, in offline identification, SINDy estimates the parameters of a three-degree-of-freedom single-track model using simulation data, capturing tire nonlinearities to create a fully tunable vehicle model. This is then validated in a high-fidelity CarMaker simulation to assess its accuracy in complex scenarios. Finally, in the online phase, MPC starts with an incorrect predictive model, which SINDy continuously updates in real time, improving performance by reducing lap time and ensuring a smoother trajectory. Additionally, a constrained version of SINDy is implemented to avoid obtaining physically meaningless parameters while aiming for an accurate approximation of the effects of unmodeled states. Simulation results demonstrate that the proposed framework enables an adaptive and efficient representation of vehicle dynamics, with potential applications to other control strategies and dynamical systems.

1. Introduction

MPC, also known as Receding Horizon Control (RHC), is an optimization-based control strategy that predicts system behavior over a finite horizon and applies a receding horizon approach to improve performance while effectively handling constraints and disturbances [1]. A key advantage of MPC is its feedback-based nature, which compensates for disturbances and modeling errors, while its predictive capability allows it to anticipate future behavior, making it well suited for nonlinear systems such as autonomous vehicles [2]. However, MPC’s computational complexity and sensitivity to model accuracy present challenges, often necessitating robust or adaptive formulations. Uncertainty affects cost functions, constraints, and system dynamics. Learning-based MPC integrates machine learning to refine predictive models, enhancing adaptation to nonlinearities and uncertainties through real-time or offline updates. Some approaches also optimize constraints and cost functions to improve closed-loop performance [3].
This work focuses on learning system dynamics. Robust MPC ensures constraint satisfaction under uncertainty by decomposing system dynamics into a nominal model and an additive uncertainty term [3]. Robust methods can be categorized as parametric or non-parametric. Parametric approaches confine uncertainties within feasible sets, iteratively refining them using system observations to ensure recursive feasibility and stability. Non-parametric approaches estimate system behavior directly from data without assuming a predefined uncertainty set, relying on gradient constraints to approximate the uncertain function. While effective for nonlinear systems, these methods are computationally demanding. Several robust learning techniques exist. Set Membership Estimation (SME) iteratively refines feasible parameter sets to maintain constraint satisfaction [4], with applications in adaptive MPC for real-time parameter refinement [5]. Robust adaptive Nonlinear Model Predictive Control (NMPC) integrates Least Squares minimization, leveraging kernel-based estimators for improved accuracy [6]. Kinky Inference, a non-parametric method, provides deterministic error bounds in system modeling [7]. Stochastic MPC explicitly accounts for uncertainty by incorporating probability distributions to construct confidence sets [3].
Gaussian Process (GP) regression is widely used in stochastic learning-based MPC to model system dynamics under additive Gaussian noise [8]. Applications include improved trajectory tracking in autonomous racing [9,10] and real-time adaptation in mobile robotics [11]. Sparse GP approximations and dynamic data selection mitigate computational burdens [12]. GP-based models also enhance path tracking under uncertainty [13] and improve constraint handling in aggressive maneuvers [14,15].
Bayesian Linear Regression (BLR) is another probabilistic learning approach for adaptive control, incorporating prior knowledge and updating with new data. Weighted Bayesian Linear Regression (wBLR) enhances learning-based MPC by balancing short-term adaptation with long-term knowledge retention, outperforming Gaussian Processes in predictive accuracy and computational efficiency [16].
Deep learning has been applied to MPC for capturing complex system dynamics. Neural networks enhance predictive accuracy through methods such as Extreme Learning Machines for error estimation [17] and Adaptive Neuro-Fuzzy Inference Systems for improved prediction accuracy [18]. Neural networks have been used in autonomous racing, outperforming physics-based models [19], as well as in MPC for learning drift dynamics [20] and improving trajectory tracking [21].
Least Squares (LS) estimation is widely employed in adaptive MPC for real-time parameter updates. Recursive Least Squares (RLS) enables adaptive control, improving vehicle stability and trajectory tracking under varying road conditions [22]. In autonomous racing, LS-based adaptive MPC iteratively optimizes performance [23,24]. Dynamic Mode Decomposition with Control (DMDc) has been applied to aircraft control, extracting linear models from data using LS regression [25]. Auto-Regressive with Exogenous Input (ARX) models, updated through RLS, support adaptive MPC in process control and real-time hybrid simulations [26,27].
However, as explained in Table 1, robust methods are often overly conservative, as they require bounding uncertainties within sets that include highly unlikely realizations. Stochastic approaches tend to be computationally intractable, particularly for nonlinear dynamics, where propagating Gaussian distributions becomes challenging. Deep learning methods, meanwhile, often lack generality and interpretability—critical properties for vehicle control.
This work focuses on implementing a sparse learning approach in a vehicle application, driven by a clear purpose. Unlike other learning methods, sparse optimization provides an interpretable and generalizable solution by approximating vehicle dynamics with a minimal set of physically meaningful functions. This approach is not only intended to enhance vehicle control but also to offer deeper insights into its true dynamics, which may be too complex to model using first-principles methods. By seeking the most accurate representation with the fewest possible functions, sparse optimization strikes a balance between precision and computational efficiency, making it a promising tool for autonomous vehicle applications, enabling online implementation. To summarize, the main objectives of this work are the following:
  • To investigate the effectiveness of the SINDy algorithm in identifying a parsimonious yet accurate and physically consistent vehicle dynamics model from simulation data.
  • To integrate the identified model within an MPC framework and assess its performance in both offline and online settings.
  • To evaluate the proposed approach in different scenarios, ranging from a simplified 3-degree-of-freedom (DOF) vehicle model to a high-fidelity CarMaker simulation.

2. Sparse Identification of Nonlinear Dynamics (SINDy)

The SINDy algorithm is employed in this work to derive a predictive model for NMPC. SINDy is chosen for its sparse formulation, which ensures interpretability while maintaining generality. As noted in [28], many model discovery techniques require large datasets to accurately identify the governing dynamical equations. These methods often struggle to generalize beyond the training dataset, limiting their practical applicability. Machine learning approaches, such as neural networks, typically produce black-box models that obscure physical insights and make it difficult to enforce known constraints. In contrast, SINDy provides a framework for sparse and parsimonious modeling, enabling the identification of interpretable models even with limited data. The algorithm exploits the fact that most physical systems are governed by only a few dominant terms. By applying sparse regression techniques, SINDy extracts the most relevant terms while discarding unnecessary ones, making it both computationally efficient and interpretable. As described in [29], to extract the dynamical equation f of a system from the data acquired, the vector of the time history of the state x ( t ) is collected and the corresponding derivative x . ( t ) is either measured or computed numerically. These are then arranged into two matrices, (1) and (2), where n represents the state dimension and m the number of sampling instants.
X = x T ( t 1 ) x T ( t 2 ) x T ( t m ) = x 1 ( t 1 ) x 2 ( t 1 ) x n ( t 1 ) x 1 ( t 2 ) x 2 ( t 2 ) x n ( t 2 ) x 1 ( t m ) x 2 ( t m ) x n ( t m )
X ˙ = x ˙ T ( t 1 ) x ˙ T ( t 2 ) x ˙ T ( t m ) = x ˙ 1 ( t 1 ) x ˙ 2 ( t 1 ) x ˙ n ( t 1 ) x ˙ 1 ( t 2 ) x ˙ 2 ( t 2 ) x ˙ n ( t 2 ) x ˙ 1 ( t m ) x ˙ 2 ( t m ) x ˙ n ( t m )
Additionally, the control vector U is defined as in (3):
U = u T ( t 1 ) u T ( t 2 ) u T ( t m ) = u 1 ( t 1 ) u 2 ( t 1 ) u d ( t 1 ) u 1 ( t 2 ) u 2 ( t 2 ) u d ( t 2 ) u 1 ( t m ) u 2 ( t m ) u d ( t m )
where d represents the input dimension and m the number of sampling instants. The input is considered to identify nonlinear functions where the system dynamics can be represented by (4).
d d t x = f ( x , u ) , x ( 0 ) = x 0 ,
The library of functions Θ ( X , U ) is then constructed consisting of candidate nonlinear functions given by (5), where x y represent the vectors of all product combinations of the components in X and U.
Θ ( X , U ) = 1 T X T U T ( X X ) T ( X U ) T sin ( U ) T sin ( X U ) T
Each column of (5) represents a candidate function for the dynamical Equation (4), with only a few of these nonlinear functions being active in each row of the library function matrix. Sparse regression is used to determine the sparse vector coefficients Φ = [ ϕ 1 ϕ 2 ϕ n ] that indicate the nonlinear functions that will actually be used, converging to (6).
X ˙ = Φ Θ T ( X , U ) .
In order to solve the sparse regression problem (7), where X . k represent the kth row of X . and ϕ k the kth row of Φ , two different optimization techniques can be used to identify a sparse Φ : LASSO or sequential threshold Least Squares.
ϕ k = argmin ϕ ^ k 1 2 X ˙ k ϕ ^ k θ T ( X , U ) 2 2 + λ ϕ ^ k 1
The · 1 term is used to sparsify the coefficient vector ϕ k , leveraging the parameter λ to identify the Pareto optimal model that ensures accuracy while balancing model complexity. A broad exploration of λ is conducted to determine the approximate threshold where terms are removed and the error begins to rise. SINDy has been applied in various nonlinear dynamical systems, including the Lotka–Volterra predator–prey model, the chaotic Lorenz system, the F8 Crusader aircraft model, and the HIV/immune response model [30]. Its adaptability extends to high-dimensional systems through the use of principal components and delay coordinates, ensuring practical feasibility in real-world applications. Additionally, SINDy has been enhanced to handle constraints, noise, and outliers, making it robust for applications in fields such as adaptive flight control and rapid system identification.
A significant extension of SINDy is Constrained-SINDy, introduced in [31], which integrates physical constraints directly into the regression process, as shown in (8). This ensures that the identified models not only fit the data but also respect fundamental physical principles, such as energy conservation and known symmetries. By incorporating linear equality constraints, the method improves the accuracy and stability of identified equations, proving especially useful in fluid dynamics.
min Φ Θ ( X ) Φ X ˙ 2 2 , subject to C ϕ = q ,
Another key development is Weak-SINDy (WSINDy), introduced by [32,33], which enhances robustness against noise and extends the algorithm’s applicability to partial differential equations. Unlike traditional methods that rely on point-wise derivative approximations, WSINDy formulates the identification problem using integral equations, minimizing noise amplification and improving numerical stability. This approach has been further refined with WENDy, introduced in [34], which specializes in parameter estimation within known differential equation models.
SINDy-PI, proposed in [30], addresses cases where governing equations are not easily expressible in explicit form. Traditional SINDy assumes explicit dynamical equations, but SINDy-PI allows for implicit relationships between state variables and their derivatives. This is particularly useful in applications such as fluid dynamics and systems governed by conservation laws. By systematically testing and selecting candidate terms, SINDy-PI enhances stability and noise resilience.
Recent advancements, such as SINDy-RL, introduced in [35], integrate reinforcement learning to optimize control policies with minimal data. This approach reduces the sample complexity of reinforcement learning while maintaining interpretability. Another advancement, ADAM-SINDy, introduced in [36], eliminates the need for predefined nonlinear terms by dynamically estimating system parameters using adaptive optimization techniques. Despite its advantages, SINDy faces challenges in handling non-smooth dynamics and missing state variables, requiring careful preprocessing, as discussed in [35].
The integration of SINDy with MPC offers a powerful data-driven control strategy. SINDy models can be used within MPC frameworks to enhance computational efficiency while retaining essential nonlinear behaviors. Offline implementations of SINDy-MPC involve identifying a sparse model before deployment, ensuring efficient real-time control. In online applications, SINDy dynamically updates the model as new data become available, adapting the control strategy in real time.
A notable online adaptation method is Abrupt-SINDy, proposed in [37], which rapidly updates models in response to sudden system changes. In the aerospace domain, SINDy-MPC has been applied to ducted fan aerial vehicles, as demonstrated in [38], where the adaptive model improves trajectory tracking under uncertain conditions. Error-Triggered Adaptive SINDy (ETASI), introduced in [39], updates the model only when prediction errors exceed a threshold, reducing computational cost while maintaining accuracy.
In aircraft dynamics, SINDyC, discussed in [40], provides a data-efficient method for modeling unknown aerodynamic behaviors using minimal flight data. Similarly, SINDy has been applied to industrial robotics, as shown in [41], where it enhances torque prediction and control stability in a 6-DOF industrial robot. In marine vehicle dynamics, the HLAR framework, proposed in [42], integrates SINDy with hydrodynamic dictionary libraries to improve real-time control performance. SINDy has also been employed in soft robotics, as demonstrated in [43], where it is combined with a Super-Twisting Sliding Mode Controller (STSMC) to achieve precise trajectory tracking.
In this work, WSINDy is not implemented due to its slower performance compared to the basic version, and noise handling is beyond the scope of this paper. Similarly, SINDy-PI is excluded as it introduces unnecessary complexity and lower efficiency in generating an effective vehicle model, as shown in the following sections. Instead, the constrained version of SINDy is used when testing on a highly realistic vehicle model to ensure physically meaningful parameters when approximating the effects of unmodeled states.

3. Control and Simulation Framework

This work proposes a learning-based MPC that leverages SINDy to develop an adaptive predictive model representing the dynamics of a vehicle. The MPC is used to control an autonomous vehicle around a track, where the predictive model is initially discovered and subsequently refined by SINDy. SINDy provides a physics-informed method to identify the vehicle dynamics, considering only terms that represent known physical functions in the related library matrix.
The following section presents and analyzes the complete framework, starting with the different scenarios involved, followed by the MPC formulation, the SINDy formulation, and finally, the overall setup. The goal of the paper is to estimate the parameters of a 3-DOF dynamic bicycle model using SINDy, with the aim of developing a fully tunable model.

3.1. Simulation Scenarios

The complete framework developed in this work is tested in different scenarios to assess its limitations and capabilities. Two different setups are developed based on their complexity, specifically in terms of the simulation vehicle model. Testing on a 3-DOF vehicle helps to evaluate the learning algorithm’s speed and its ability to accurately approximate the highly nonlinear wheel force model. The next step involves testing on a more complex and realistic vehicle model to evaluate SINDy’s performance in capturing the effects of unmodeled degrees of freedom.
It is important to note that the sparse regression approach allows for aggressive maneuvers near road limits, as demonstrated in simulations, which makes real-world validation inherently risky. Furthermore, the lack of a well-defined ground truth complicates the identification of true vehicle parameters; as a result, the analysis will be carried out exclusively in a simulation environment.
  • Dynamic bicycle model
  • A single-track dynamic bicycle model is selected to simulate the vehicle behavior in MATLAB 2023b. As stated in [44,45], the dynamic bicycle model is a widely used representation to describe vehicle motion, accounting for inertial effects, yaw dynamics, and lateral tire forces. According to [46], the following parameters are considered: l f and l r denote the distances from the center of mass to the front and rear wheels, respectively. The vehicle’s heading angle is represented by ψ , while ω indicates the yaw rate. The longitudinal and lateral tire forces are denoted by F l and F c , respectively, where the subscripts ( · ) f and ( · ) r correspond to the front and rear wheels. The steering angle is represented by δ , while α f and α r define the slip angles of the front and rear wheels, respectively. These parameters, as introduced in [46], provide the foundation for modeling vehicle dynamics. The system’s dynamics are formulated in state-space notation as x ˙ ( t ) = f ( x ( t ) , u ( t ) ) , with the state vector x ( t ) R 8 and the input vector u ( t ) R 2 . These equations are expressed in a local reference frame defined by the curvilinear coordinate s that represents the vehicle’s position along the road centerline, and the lateral deviation from the centerline y, as in (9). The orientation error ξ is defined as the difference between the vehicle’s heading angle and the tangent angle of the road centerline in the global coordinate system, given by ξ = ψ ϑ c . The vehicle’s velocity components in the local reference frame are v x , v y , and ω . The steering angle at the front wheels, δ , and the torque applied to the rear axle, T r , are obtained by integrating the inputs u 1 and u 2 , such that δ ˙ = u 1 and T ˙ r = u 2 . The longitudinal force F r l at the rear axle is equal to T r divided by the wheel radius, while the lateral forces are a function of the lateral slip angles, assumed to be known and calculated following (10). These forces are involved in describing the dynamics of the v ˙ x , v ˙ y , and ω ˙ states and will be approximated by the SINDy algorithm.
    s ˙ = V x cos ( ξ ) V y sin ( ξ ) 1 y c s y ˙ = V x sin ( ξ ) + V y cos ( ξ ) ξ ˙ = ω y c s s ˙ v ˙ x = ω v y + F r l M F f c sin ( δ ) M F r e s M v ˙ y = ω v x + F r c M + F f c cos ( δ ) M ω ˙ = 1 J z ( F r c l r + F f c l f cos ( δ ) ) δ ˙ = u 1 T ˙ r = u 2
    α f = arctan ( v y + ω l f ) cos ( δ ) v x sin ( δ ) v x tanh ( κ v x ) v x cos ( δ ) + ( v y + ω l f ) sin ( δ ) v x + ϵ 0 α r = arctan v y ω l r v x tanh ( κ v x ) v x 2 + ϵ 0
    The Magic Formula Tire Model [47] has been employed due to its ability to provide a highly accurate mathematical representation of tire forces while accounting for nonlinear effects. This model expresses lateral force, longitudinal force, and aligning torque as nonlinear functions of slip ratio and slip angle, with B ,   C ,   D , and E serving as tuning parameters that govern the stiffness, shape, peak values, and asymmetry of the force–slip curve. In the dynamic bicycle model used in this work, only the lateral forces F f c and F r c need to be evaluated, as given in (11):
    F f , r c ( α f , r ) = D sin C arctan B α f , r E B α f , r arctan ( B α f , r )
    The values used in the 3-DOF dynamic bicycle model are summarized in Table 2, along with the parameters of the Magic Formula Tire Model.
  • CarMaker
  • A more advanced benchmark was then developed using the CarMaker [48] simulation software (13.1.1 version) with a high-fidelity vehicle model. The Tesla Model S in CarMaker is a detailed multibody system that accurately replicates the vehicle’s dynamics, including its electric all-wheel-drive system, regenerative braking, and advanced driver assistance features. This model enables realistic testing of autonomous driving scenarios in virtual environments. To assess the algorithm’s effectiveness, three test tracks are used, as shown in Figure 1.
    In particular, in Figure 1 track (1a) is taken from [49], track (1b) is the Monza Formula 1 circuit imported in CarMaker, and track (1c) is taken from [15]. The selection of these three tracks is motivated by several factors. The first track offers a relatively simple level of complexity, allowing the algorithm to be trained on a reasonably sized dataset before being tested on more challenging circuits, such as the third one. Both tracks are also commonly used in the literature in studies relevant to this work. The Monza circuit, on the other hand, is included to provide validation within CarMaker for a highly realistic application scenario.

3.2. NonLinear Model Predictive Controller

The Nonlinear Model Predictive Controller (NMPC) used in this work is derived from [49]. The formulated NMPC is solved using the open-source acados solver [50], where the nonlinear program (NLP) is approximately solved using the real-time iteration (RTI) scheme with a sequential quadratic programming (SQP) method.
The previously formulated vehicle dynamic model is treated as an equality constraint in the MPC formulation. In this model, the lateral tire forces are approximated by a sum of nonlinear odd functions dependent on the lateral slip angles. This approach, along with the model identified by SINDy, will be further detailed in the next section.
In the NMPC formulation, the following hard constraints are considered:
  • Track boundary constraint, y m a x _ h a r d .
  • Maximum steering rate, δ ˙ m a x .
  • Maximum torque rate, T ˙ m a x .
Additionally, soft constraints are introduced to avoid discontinuities in the formulation and to ensure smoother vehicle behavior:
  • Track boundary constraint, y m a x _ s o f t .
  • Maximum steering angle, δ m a x .
  • Maximum torque, T m a x .
  • Maximum lateral acceleration, a m a x , constrained as follows:
    a = v ¨ y + v x · ω
  • Maximum longitudinal acceleration, a m a x , constrained as follows:
    a = v ¨ x v y · ω
To leverage efficient algorithms for solving the problem, a quadratic objective function is formulated in (15), while the track progress of the vehicle is defined as in (14), where s 0 represents the vehicle’s current track progress, and k is the step in the prediction horizon, which consists of N steps:
s k , ref = s 0 + s N , ref N k , k = 0 , , N ,
min x 0 , , x N , u 0 , , u N 1 k = 0 N 1 x k x k , ref Q 2 + u k R 2 + x N x N , ref Q N 2
where x = [ v x , v y , ω , ξ , s , y , δ , T ] T and u = [ δ ˙ , T ˙ ] T represent the vehicle’s states and control inputs, respectively. The weighting matrices Q ,   R ,   Q N   >   0 are positive definite. The resulting cost function and constraints define the NLP, which is imported into acados and solved using the RTI scheme within an SQP framework. The resulting quadratic programs (QPs) are then solved using the high-performance interior-point method (HPIPM).

3.3. Sparse Approximation of Vehicle Model

The core of this work is the SINDy algorithm, which not only enables the identification of a dynamic bicycle model from observed data but also provides a fully tunable model in terms of its parameters.
Initially, SINDy was applied offline to approximate the Pacejka tire forces as a sum of odd polynomial functions of the slip angles, which are assumed to be known (as functions of the state) and computed according to (10). This approach is justified by the symmetry of Pacejka’s Magic Formula for lateral forces with respect to the origin, as illustrated in Figure 2.
The approximation of Pacejka’s Magic Formula proves to be highly accurate, particularly for limited slip angle values. To preserve generality, a range of ± 30 is considered; within this range, the approximation error remains below 6%. If the slip angle range is further restricted to ± 20 , which broadly encompasses the majority of maneuvers expected from an autonomous vehicle, the error drops to approximately 1%. Subsequently, the functions to be used in the SINDy library for approximating the vehicle dynamics are selected. The objective is to transform the previously defined dynamic bicycle model in (9) into a sum of nonlinear functions suitable for implementation in SINDy.
First, the tire force expressions are replaced with the previously identified odd polynomial functions. Then, the equations governing the dynamic behavior of the model, which define its degrees of freedom, are reformulated as a sum of functions, while the first three equations, representing the model’s geometric constraints, remain fixed. Finally, the complete model is represented in (16), where the accelerations identified by SINDy are v ˙ x , v ˙ y , and ω ˙ , expressed as a sum of state, input, and slip angle functions, multiplied by their associated weights c 1 , , c 25 , thus resulting in a fully tunable 3-degree-of-freedom dynamic vehicle model.
s ˙ = V x cos ( ξ ) V y sin ( ξ ) 1 y c s y ˙ = V x sin ( ξ ) + V y cos ( ξ ) ξ ˙ = ω y c s s ˙ v ˙ x = c 1 ω v y + c 2 T r + ( c 3 α f + c 4 α f 3 + c 5 α f 5 + c 6 α f 7 ) sin ( δ ) + c 7 v x + c 8 v x 2 , v ˙ y = c 9 ω v x + ( c 10 α f + c 11 α f 3 + c 12 α f 5 + c 13 α f 7 ) cos ( δ ) + c 14 α r + c 15 α r 3 + c 16 α r 5 + c 17 α r 7 ω ˙ = ( c 18 α f + c 19 α f 3 + c 20 α f 5 + c 21 α f 7 ) cos ( δ ) + c 22 α r + c 23 α r 3 + c 24 α r 5 + c 25 α r 7 δ ˙ = u 1 T ˙ r = u 2
In particular, recalling the SINDy general formulation in (6), the sparse learning algorithm aims to solve the following problem (17):
X ˙ = Θ ( X , U ) Φ X ˙ = v ˙ x , v ˙ y , ω ˙ X = v x , v y , ω , α f , α r U = δ , T r Φ = c 1 c 9 c 18 c 8 c 17 c 25
Two additional key parameters need to be properly tuned to ensure accurate model identification: the sparsity promoter parameter λ and the number of iterations N SIN Dy used in the algorithm. While the number of iterations remains the same across different approaches, N SIN Dy = 10 , the values of λ vary. Furthermore, normalization is particularly useful in cases where the identified weights have significantly different orders of magnitude. In such cases, the sparsity promoter parameter must be smaller than the smallest expected nonzero weight.
A constrained version of the algorithm is implemented to limit the variation of the weights discovered by SINDy in an online scenario, while attempting to approximate the effect of unmodeled states. To find the coefficients of the library functions, acados solves a simple NLP consisting of the Least Squares constrained minimization problem in (8).
The problem variables consist of the weights of the library functions, while the problem parameters include the derivative vector and the library matrix. These parameters are treated as variables because they change as the simulation progresses, incorporating newly available data. Each time the algorithm runs, these parameters update dynamically without requiring the entire problem to be recomputed. With this formulation, a computational time of around 50 ms with N SIN Dy = 10 has been achieved. By leveraging the capacity of acados to generate the corresponding S-Function, the overall setup is implemented in Simulink.
Finally, the overall software in the loop (SiL) simulation setup is highlighted in Figure 3, where the connections between the different entities used in the simulation scenario are outlined. In summary, vehicle states from CarMaker are passed to MATLAB/Simulink, where Constrained-SINDy identifies the dynamics parameters and refines the acados MPC model. acados MPC then generates control inputs, such as the steering angle and torque. The torque is translated into gas and brake pedal inputs, while the steering input is applied directly to the steering system. Finally, the updated inputs control the simulated Tesla Model S in CarMaker.
In particular, the working principle of constrained-SINDy is highlighted in Figure 4. The machine learning algorithm aims to reconstruct the longitudinal, lateral, and yaw accelerations based on the vehicle’s inputs and states. A different sparsity-promoting parameter, λ , is used for each of the three acceleration components. Once the optimal coefficients for the bicycle model are identified, they are provided as parameters to the acados predictive model, which uses the same SINDy library functions. This results in a fully tunable three-degree-of-freedom vehicle model, enabling an optimized trade-off between model accuracy and simplicity.

4. Results

Initially, the tested vehicle is a 3-DOF single-track bicycle model. This same model is also used as the predictive model within the NMPC framework, with one key exception: the formulation of the tire forces. In the simulation model, the tire forces are computed using the Pacejka formulation, as described previously. However, in the predictive model, they are represented differently, as a sum of odd polynomial functions.

4.1. 3-DOF: Offline Testing

The single-track dynamic model, previously introduced and detailed in (9), serves as the base for the simulation that operates on the track shown in Figure 1a.
To systematically evaluate the effectiveness of the proposed algorithm, SINDy is applied to extract the weights of the functions composing the library matrix. The input to SINDy consists of both the state vector and its derivative. However, the state vector is augmented to explicitly include the lateral slip angle for both the front and rear tires. The slip angles are assumed to be available, and their values are determined using the formulation provided in (10). The augmentation of the state vector allows SINDy to include the slip angles in the formulation of the library matrix, providing a more comprehensive representation of the system and improving the accuracy of the identified model.
The results obtained from the application of SINDy are presented in Figure 5 and Figure 6. The sparse regression algorithm successfully reconstructs and approximates the simulated vehicle’s dynamics with a high degree of accuracy. As illustrated in the graph in Figure 5, the state variables v ˙ x , v ˙ y , and ω ˙ are effectively identified and reproduced by SINDy. This validation confirms that the learned model captures the essential characteristics of the vehicle’s dynamic behavior.
To evaluate the accuracy of the SINDy-based identification process, an error analysis is conducted using the coefficient of determination R 2 . This metric quantifies how well the identified model captures the variance in the observed data, with values closer to 1 indicating higher accuracy. The R 2 value is computed as in (18), where z true represents the actual system outputs, z pred denotes the predicted outputs, and z ¯ true is the mean of the true outputs.
R 2 = 1 ( z true z pred ) 2 ( z true z ¯ true ) 2
Figure 6 presents the R 2 graph, constructed using the test dataset, illustrating the accuracy of the identified model in capturing the system dynamics. The high R 2 values observed in Figure 6 further support this, indicating that the identified equations effectively describe the system behavior. Lower values, if present, would suggest discrepancies due to model simplifications, data noise, or an insufficiently rich library of candidate functions.
Table 3 reports the percentage error of the SINDy identification along with the corresponding R 2 values for all relevant states.
Moreover, the shape of the tire forces can also be reconstructed with the discovered weights, as shown in Figure 7. Since the wheel forces appear in the differential equations of all three accelerations, it is possible to estimate them from each of the three equations reconstructed by SINDy. The approximation of the highly nonlinear tire forces is highly accurate within the vehicle’s operational range, demonstrating SINDy’s ability not only to estimate parameters but also to obtain a precise and fully tunable dynamic model that ensures high performance.
To further assess the generalization capability of the identified model, the simulation is performed on a different test track, shown in Figure 1c. The choice of a distinct track is deliberate, as it allows for evaluating whether a physics-informed identification algorithm, such as SINDy, can extract a generalized vehicle model that is not overfitted to a specific training dataset. As shown in Figure 8, the NMPC controller with the identified model successfully completes a lap on this complex track, effectively handling high slip angles.

4.2. Three Degrees of Freedom: Online Testing

At this stage, after successfully testing the offline SINDy framework on the 3-DOF vehicle, the focus shifts to evaluating its performance in an online setting. The simulation is carried out on the track shown in Figure 1a. To investigate the real-time adaptability of SINDy, a crucial modification is introduced. Specifically, the dynamic bicycle model used in the simulation undergoes a set of parameter alterations. The parameters defining the single-track bicycle model, as well as those characterizing the Pacejka tire model, are randomly perturbed by up to 20%, in a simulation scenario similar to the one performed by [15]. This controlled modification introduces an element of unpredictability, simulating real-world conditions where vehicle parameters might change due to variations in road conditions, tire wear, or load distribution. Before the start of the third lap, SINDy activates, allowing the algorithm to adjust the predictive model in real time. The newly computed weights capture the altered dynamics, refining the approximation of the single-track bicycle model as it responds to the evolving conditions.
The results of this adaptation process are illustrated in Figure 9. A clear distinction can be observed between the trajectories taken during the second and third laps. Prior to SINDy’s activation, the vehicle struggles to maintain optimal control, nearly reaching the track boundaries at the penultimate turn. However, after SINDy is executed, a significant improvement in trajectory control is achieved. The vehicle follows a more stable path, effectively navigating the track with greater precision. Additionally, this improved control also leads to enhanced performance, as evidenced by a reduction in lap time. The vehicle completes the lap 1 s faster than before, demonstrating that the updated predictive model enhances both safety and performance. Over a 24 s lap, this corresponds to an improvement of approximately 4 % .
At this stage, the testing scenario is further refined to introduce greater complexity. Instead of using a simplified vehicle model, the CarMaker software is employed to simulate a high-fidelity representation of the system. The chosen vehicle is a Tesla Model S, ensuring that the analysis is conducted with a realistic and detailed model. Additionally, the tracks on which the vehicle operates are fully modeled within the CarMaker environment, providing a more comprehensive and representative testing platform. When working with a high-fidelity simulation scenario, additional effects can emerge and significantly influence vehicle dynamics. Among these, the longitudinal dynamics are particularly impacted by the presence of resistive forces, such as rolling resistance and aerodynamic drag, that normally are modeled as additional inputs. As discussed in Section 3, these contributions are incorporated into the system identification process by augmenting the SINDy library with two additional functions related to the longitudinal acceleration state, a x . Specifically, the function v x is assumed to be proportional to rolling resistance, while the function v x 2 is associated with aerodynamic drag. This modification aims to enhance the accuracy of the identified dynamic equations for a x .
Two testing scenarios assess the framework’s performance in this complex environment. The first validates the offline identification of a high-fidelity vehicle model, evaluating its ability to reconstruct dynamics with greater detail than the previous 3-DOF bicycle model. The second scenario tests online adaptation using Constrained-SINDy, enabling real-time refinement while enforcing physically meaningful constraints. This ensures accurate and robust identification, preventing non-physical terms and maintaining reliability in dynamic conditions.

4.3. CarMaker: Offline Testing

To execute the offline approach, the simulation is performed on the track shown in Figure 1a, implemented in the CarMaker environment. The vehicle is initially controlled by the IPG Driver module to follow a predefined trajectory. Relevant state variables and their derivatives are collected to ensure a comprehensive dataset for analysis. Additionally, the state vector is augmented with the front and rear lateral slip angles, which are assumed to be known and computed using Equation (10).
The results obtained from the application of SINDy are presented in Figure 10 and Figure 11. The sparse regression algorithm successfully identifies a model with a maximum error of 6% in a x , 10% in a y , and 38% in ω ˙ . The error in the identification of angular acceleration can be attributed to the fact that the corresponding expression depends almost exclusively on the forces on the wheels, which makes it highly nonlinear. However, the R 2 value serves as a more reliable indicator of accuracy, as the identification of angular acceleration is mainly influenced by wheel forces. Despite the nonlinear nature of this dependency, the approximation remains sufficiently accurate, allowing for good overall performance.
The reconstruction of the model parameters is achieved through the expressions for lateral and longitudinal accelerations. These error values demonstrate the effectiveness of the approach in capturing the essential vehicle dynamics while maintaining a reduced model complexity. As shown in Figure 10, the state variables v x ˙ , v y ˙ , and ω ˙ are effectively identified and reproduced by SINDy. This validation confirms that the learned model accurately captures the key characteristics of the vehicle’s dynamic behavior.
As accomplished before, an error analysis is conducted to assess the reliability and accuracy of the SINDy-based identification process. The results are presented in Figure 11, which displays the R 2 graph constructed using the test dataset. Table 4 summarizes the percentage error of the SINDy identification along with the corresponding R 2 values for all relevant states.
Additionally, beyond simply reconstructing the vehicle’s equations of motion, the extracted weights provide valuable insights into the physical parameters of the system. For instance, the mass of the vehicle can be directly inferred from the weight associated with the input torque T. The percentage error on the discovered mass is 1.7%. Moreover, the shape of the tire forces can also be reconstructed with the discovered weights, as shown in Figure 12. The approximation of the curves is less accurate, likely due to the higher complexity of the simulated vehicle. The identified model must approximate highly complex dynamics, with unmodeled effects contributing to the mismatch. Additionally, the discrepancy may arise from the highly nonlinear tire forces encountered during the simulation. In this case, the lateral tire force reaches its peak at approximately 4 of slip angle, requiring the SINDy equation to account for a wider nonlinear range.
To further assess the generalization capability of the identified model, a simulation is performed on a different test track (Figure 1b). As depicted in Figure 13, the NMPC controller, utilizing the identified model, successfully navigates a full lap on this complex track.

4.4. CarMaker: Online Testing

The final scenario tested involves the online identification capability of SINDy. The objective is to assess SINDy’s ability to adaptively identify the vehicle model in real time and improve its predictive accuracy under changing conditions. To create a challenging identification scenario, the predictive model previously identified on the complex track is intentionally altered. Specifically, its weights are modified by approximately 20%. This change significantly impacts vehicle control performance, to the extent that the reference velocity must be drastically reduced to maintain stability. As a result, the simulated complex vehicle mostly operates in the linear tire force region, which significantly limits the ability to capture and identify nonlinear behaviors.
To enhance robustness in the identified model parameters, Constrained-SINDy is implemented. In this approach, constraints are applied to limit the variation of the discovered weights, ensuring that the model does not deviate excessively from values of the coefficients that have physical meaning. Given that the offline-identified model demonstrated good performance and low identification error, particularly in the states a x and a y , it is chosen as the reference model for formulating constraints on the weight adjustments. The constraint strategy allows for a maximum variation of ±20% on the weights, with the exception of those related to friction forces, for which the upper bound is set to zero. This restriction ensures that the model does not identify overly incorrect terms that could compromise the testing process.
The simulation is executed using Constrained-SINDy to update the vehicle model. The vehicle is initially subjected to two laps with a fixed predictive model, meaning that no adaptive learning takes place during these first laps. Before the start of the third lap, Constrained-SINDy is activated, allowing the algorithm to adjust the predictive model in real time. The newly computed weights capture the altered dynamics, refining the approximation of the single-track bicycle model as it responds to the evolving conditions. The results clearly indicate an improvement in the controller’s tracking performance, as shown in Figure 14. The first two laps are performed to have the same initial conditions on the second and third lap.
Before SINDy is applied, the vehicle exhibits unstable behavior, particularly during cornering. At curve exits, the vehicle approaches the track boundaries, resulting in an unsafe and inefficient trajectory. However, once Constrained-SINDy updates the predictive model, the vehicle maintains a more controlled and precise path through the turns, demonstrating improved stability and responsiveness. When the reference speed is kept constant, the vehicle follows a smoother trajectory; specifically, the lap time is reduced from 43.85 s to 42.05 s, corresponding to an overall improvement of 4.3 % . However, the vehicle is able to navigate the track at a higher reference velocity, particularly increasing from 13 m / s to 15 m / s with the updated model. The difference between the two laps can also be seen in Figure 15 and Figure 16, where the vehicle states are depicted. This result highlights the benefits of real-time model adaptation, showing that by refining the predictive model during operation, the vehicle can achieve both better stability and enhanced performance.

5. Conclusions and Future Developments

This work investigated the integration of the SINDy algorithm into an MPC framework for autonomous vehicle systems. Unlike traditional MPC approaches that rely on fixed, physics-based models, SINDy offers a data-driven alternative capable of identifying governing equations directly from data, while maintaining interpretability and physical structure.
Based on a review of related work, the proposed method offers advantages in terms of computational efficiency and scalability for real-time applications when compared to stochastic MPC approaches, which are often limited in this regard. In addition, while deep learning methods typically yield black-box models with limited interpretability, the SINDy-based framework preserves transparency and tunability—desirable properties in safety-critical applications such as automated driving. This study also introduced a constrained version of SINDy to promote physically meaningful parameter updates in the presence of unmodeled dynamics.
In the first scenario, SINDy is applied to identify a 3-degree-of-freedom (3-DOF) vehicle model from simulation data. The offline phase consists of collecting data and constructing the state vector, the corresponding derivative vector, and the library matrix. Sparse regression is then used to identify the governing equations, effectively approximating the Pacejka tire force formulation. The identified model is subsequently tested within the MPC framework on a different and more challenging track. In the online phase, the predictive model is continuously updated within MPC, allowing real-time refinement. The results show improved trajectory tracking performance and reduced lap times.
In the second scenario, a high-fidelity vehicle model is simulated in CarMaker. SINDy is used to approximate its dynamics using a simplified 3-DOF representation. As in the first case, the offline phase involves applying SINDy to generate a reduced-order model from simulation data, which is then tested on a separate challenging track. During the online phase, a constrained version of SINDy is employed to regulate parameter updates, maintaining consistency and preventing unphysical variations. The results confirm an improvement in the quality of control inputs and a further reduction in lap times.
Throughout the study, it became evident that selectively updating the model based on informational advantage could further enhance efficiency by avoiding unnecessary or noisy updates. Future work will focus on developing intelligent data substitution mechanisms and robust noise-handling strategies, such as Weak-SINDy or advanced filtering techniques. Additionally, introducing structured uncertainty bounds within the identification process is expected to improve the robustness of the Constrained-SINDy approach, enabling the derivation of valid parameter intervals and laying the groundwork for a set-membership-based framework.
Overall, the proposed methodology enhances the adaptability and performance of learning-based MPC systems, offering a promising direction for real-time control in autonomous vehicle applications.

Author Contributions

Conceptualization, A.C. and F.P.; methodology, S.A. and F.P.; software, M.I.I.S.I. and A.C.; validation, A.C., F.P., M.I.I.S.I. and S.A.; formal analysis, F.P. and A.C.; investigation, A.C., F.P. and M.I.I.S.I.; resources, A.C., F.P., M.I.I.S.I. and S.A.; data curation, A.C. and F.P.; writing—original draft preparation, A.C. and F.P.; writing—review and editing, S.A., M.I.I.S.I. and F.P.; visualization, F.P. and M.I.I.S.I.; supervision, F.B. and S.A.; project administration, F.B. All authors have read and agreed to the published version of the manuscript.

Funding

This research received no external funding.

Data Availability Statement

The original contributions presented in the study are included in the article; further inquiries can be directed to the corresponding authors.

Acknowledgments

We would like to express our gratitude to IPG for providing us with the necessary software license for Carmaker used in this study.

Conflicts of Interest

The authors declare no conflicts of interest.

Abbreviations

The following abbreviations are used in this manuscript:
MPCModel Predictive Control
SINDySparse Identification of Nonlinear Dynamics
RHCReceding Horizon Control
SMESet Membership Estimation
GPGaussian Process
BLRBayesian Linear Regression
LSLeast Squares
ARXAuto-Regressive with Exogenous Input
DMDcDynamic Mode Decomposition with Control
LASSOLeast Absolute Shrinkage and Selection Operator
3-DOFThree Degrees of Freedom
NLPNonlinear Programming
SQPSequential Quadratic Programming
RTIReal-Time Iteration
SILSoftware In the Loop

References

  1. Yu, S.; Hirche, M.; Huang, Y.; Chen, H.; Allgöwer, F. Model predictive control for autonomous ground vehicles: A review. Auton. Intell. Syst. 2021, 1, 4. [Google Scholar] [CrossRef]
  2. Sathyamangalam Imran, M.I.I.; Awasthi, S.S.; Khayyat, M.; Arrigoni, S.; Braghin, F. A Rule-Defined Adaptive MPC Based Motion Planner for Autonomous Driving Applications. In Proceedings of the 16th International Symposium on Advanced Vehicle Control; Mastinu, G., Braghin, F., Cheli, F., Corno, M., Savaresi, S.M., Eds.; Springer: Cham, Switzerland, 2024; pp. 540–549. [Google Scholar]
  3. Hewing, L.; Wabersich, K.P.; Menner, M.; Zeilinger, M.N. Learning-Based Model Predictive Control: Toward Safe Learning in Control. Annu. Rev. Control. Robot. Auton. Syst. 2020, 3, 269–296. [Google Scholar] [CrossRef]
  4. Lu, X.; Cannon, M.; Koksal-Rivet, D. Robust adaptive model predictive control: Performance and parameter estimation. Int. J. Robust Nonlinear Control 2021, 31, 8703–8724. [Google Scholar] [CrossRef]
  5. Köhler, J.; Kötting, P.; Soloperto, R.; Allgöwer, F.; Müller, M.A. A Robust Adaptive Model Predictive Control Framework for Nonlinear Uncertain Systems. Int. J. Robust Nonlinear Control 2021, 31, 8134–8159. [Google Scholar] [CrossRef]
  6. Aswani, A.; González, H.; Sastry, S.S.; Tomlin, C.J. Provably Safe and Robust Learning-Based Model Predictive Control. Automatica 2013, 49, 1216–1226. [Google Scholar] [CrossRef]
  7. Manzano, J.M.; Limon, D.; noz de la Peña, D.M.; Calliess, J.P. Robust learning-based MPC for nonlinear constrained systems. Automatica 2020, 117, 108948. [Google Scholar] [CrossRef]
  8. Sigaud, O.; Salan, C.; Padois, V. On-line regression algorithms for learning mechanical models of robots: A survey. Robot. Auton. Syst. 2011, 59, 1115–1129. [Google Scholar] [CrossRef]
  9. Picotti, E.; Mion, E.; Libera, A.D.; Pavlovic, J.; Censi, A.; Frazzoli, E.; Beghi, A.; Bruschetta, M. A Learning-Based Nonlinear Model Predictive Controller for a Real Go-Kart Based on Black-Box Dynamics Modeling Through Gaussian Processes. IEEE Trans. Control Syst. Technol. 2023, 31, 2034–2047. [Google Scholar] [CrossRef]
  10. ao Pinho, J.; Costa, G.; Lima, P.U.; Botto, M.A. Learning-Based Model Predictive Control for Autonomous Racing. World Electr. Veh. J. 2023, 14, 163. [Google Scholar] [CrossRef]
  11. Ostafew, C.J.; Schoellig, A.P.; Barfoot, T.D. Learning-Based Nonlinear Model Predictive Control to Improve Vision-Based Mobile Robot Path-Tracking in Challenging Outdoor Environments. In Proceedings of the 2014 IEEE International Conference on Robotics and Automation (ICRA), Hong Kong, China, 31 May–7 June 2014; p. 6822. [Google Scholar]
  12. Kabzan, J.; Hewing, L.; Liniger, A.; Zeilinger, M.N. Learning-Based Model Predictive Control for Autonomous Racing. IEEE Robot. Autom. Lett. 2019, 4, 3363–3370. [Google Scholar] [CrossRef]
  13. Ostafew, C.J.; Schoellig, A.P.; Barfoot, T.D. Robust Constrained Learning-based NMPC enabling reliable mobile robot path tracking. Int. J. Robot. Res. 2016, 35, 1547–1563. [Google Scholar] [CrossRef]
  14. Arab, A.; Yi, J. Safety-Guaranteed Learning-Predictive Control for Aggressive Autonomous Vehicle Maneuvers. In Proceedings of the 2020 IEEE/ASME International Conference on Advanced Intelligent Mechatronics (AIM), Boston, MA, USA, 6–9 July 2020; pp. 1539–1544. [Google Scholar] [CrossRef]
  15. Hewing, L.; Liniger, A.; Zeilinger, M.N. Cautious NMPC with Gaussian Process Dynamics for Autonomous Miniature Race Cars. In Proceedings of the European Control Conference (ECC), Limassol, Cyprus, 12–15 June 2018; pp. 1345–1351. [Google Scholar] [CrossRef]
  16. McKinnon, C.D.; Schoellig, A.P. Learn Fast, Forget Slow: Safe Predictive Learning Control for Systems with Unknown and Changing Dynamics Performing Repetitive Tasks. IEEE Robot. Autom. Lett. 2019, 4, 2180–2187. [Google Scholar] [CrossRef]
  17. Tian, H.; Hu, J.; Zhai, J.; Wei, C.; Ni, J.; Jiang, C. Learning-Based Predictive Error Estimation and Compensator Design for Autonomous Vehicle Path Tracking. In Proceedings of the 2020 IEEE International Conference on Vehicular Electronics and Safety (ICVES), Kristiansand, Norway, 9–13 November 2020; pp. 1–6. [Google Scholar] [CrossRef]
  18. Alcala, E.; Sename, O.; Puig, V.; Quevedo, J. TS-MPC for Autonomous Vehicle using a Learning Approach. IFAC-PapersOnLine 2020, 53, 15110–15115. [Google Scholar] [CrossRef]
  19. Spielberg, N.A.; Brown, M.; Kapania, N.R.; Kegelman, J.C.; Gerdes, J.C. Neural Network Vehicle Models for High-Performance Automated Driving. Sci. Robot. 2019, 4, eaaw1975. [Google Scholar] [CrossRef]
  20. Acosta, M.; Kanarachos, S. Teaching a vehicle to autonomously drift: A data-based approach using Neural Networks. Knowl.-Based Syst. 2018, 153, 12–28. [Google Scholar] [CrossRef]
  21. Kang, E.; Qiao, H.; Gao, J.; Yang, W. Neural network-based model predictive tracking control of an uncertain robotic manipulator with input constraints. ISA Trans. 2021, 109, 89–101. [Google Scholar] [CrossRef]
  22. Ercan, Z.; Gokasan, M.; Borrelli, F. An Adaptive and Predictive Controller Design for Lateral Control of an Autonomous Vehicle. In Proceedings of the 2017 IEEE International Conference on Vehicular Electronics and Safety (ICVES), Vienna, Austria, 27–28 June 2017; pp. 232–237. [Google Scholar] [CrossRef]
  23. Rosolia, U.; Carvalho, A.; Borrelli, F. Autonomous Racing using Learning Model Predictive Control. In Proceedings of the 2017 American Control Conference (ACC), Seattle, WA, USA, 24–26 May 2017; pp. 5115–5120. [Google Scholar] [CrossRef]
  24. Brunner, M.; Rosolia, U.; Gonzales, J.; Borrelli, F. Repetitive learning model predictive control: An autonomous racing example. In Proceedings of the 2017 IEEE 56th Annual Conference on Decision and Control (CDC), Melbourne, VIC, Australia, 12–15 December 2017. [Google Scholar]
  25. Oznurlu, C.; Bayri, B.; Ugur, O. Data-Driven Model Discovery and Control: Real-Time Implementation to Highly Maneuverable Aircraft Lateral-Directional Dynamics. In Proceedings of the 10th International Conference on Recent Advances in Air and Space Technologies, RAST 2023, Istanbul, Turkiye, 7–9 June 2023. [Google Scholar] [CrossRef]
  26. Aliskan, I. Adaptive Model Predictive Control for Wiener Nonlinear Systems. Iran. J. Sci. Technol.-Trans. Electr. Eng. 2019, 43, 361–377. [Google Scholar] [CrossRef]
  27. Tsokanas, N.; Pastorino, R.; Stojadinović, B. Adaptive model predictive control for actuation dynamics compensation in real-time hybrid simulation. Mech. Mach. Theory 2022, 172, 104817. [Google Scholar] [CrossRef]
  28. Kaiser, E.; Kutz, J.N.; Brunton, S.L. Sparse identification of nonlinear dynamics for model predictive control in the low-data limit. Proc. R. Soc. A Math. Phys. Eng. Sci. 2018, 474, 20180335. [Google Scholar] [CrossRef]
  29. Brunton, S.L.; Proctor, J.L.; Kutz, J.N. Discovering governing equations from data by sparse identification of nonlinear dynamical systems. Proc. Natl. Acad. Sci. USA 2016, 113, 3932–3937. [Google Scholar] [CrossRef]
  30. Kaheman, K.; Kutz, J.N.; Brunton, S.L. SINDy-PI: A Robust Algorithm for Parallel Implicit Sparse Identification of Nonlinear Dynamics. Proc. R. Soc. A Math. Phys. Eng. Sci. 2020, 476, 20200279. [Google Scholar] [CrossRef]
  31. Loiseau, J.C.; Brunton, S.L. Constrained sparse Galerkin regression. J. Fluid Mech. 2018, 838, 42–67. [Google Scholar] [CrossRef]
  32. Messenger, D.A.; Bortz, D.M. Weak SINDy: Galerkin-based data-driven model selection. Multiscale Model. Simul. 2021, 19, 1474–1497. [Google Scholar] [CrossRef]
  33. Messenger, D.A.; Bortz, D.M. Weak SINDy for partial differential equations. J. Comput. Phys. 2021, 443, 110525. [Google Scholar] [CrossRef]
  34. Bortz, D.M.; Messenger, D.A.; Dukic, V. Direct Estimation of Parameters in ODE Models Using WENDy: Weak-form Estimation of Nonlinear Dynamics. Bull. Math. Biol. 2023, 85, 110. [Google Scholar] [CrossRef]
  35. Zolman, N.; Fasel, U.; Kutz, J.N.; Brunton, S.L. SINDy-RL: Interpretable and Efficient Model-Based Reinforcement Learning. arXiv 2024, arXiv:2403.09110. [Google Scholar]
  36. Viknesh, S.; Tatari, Y.; Arzani, A. ADAM-SINDy: An Efficient Optimization Framework for Parameterized Nonlinear Dynamical System Identification. arXiv 2024, arXiv:2410.16528. [Google Scholar]
  37. Quade, M.; Abel, M.; Kutz, J.N.; Brunton, S.L. Sparse Identification of Nonlinear Dynamics for Rapid Model Recovery. Chaos Interdiscip. J. Nonlinear Sci. 2018, 28, 063116. [Google Scholar] [CrossRef]
  38. Manzoor, T.; Pei, H.; Sun, Z.; Cheng, Z. Model Predictive Control Technique for Ducted Fan Aerial Vehicles Using Physics-Informed Machine Learning. Drones 2023, 7, 4. [Google Scholar] [CrossRef]
  39. Huang, K.; Tao, Z.; Liu, Y.; Wu, D.; Yang, C.; Gui, W. Error-Triggered Adaptive Sparse Identification for Predictive Control and Its Application to Multiple Operating Conditions Processes. IEEE Trans. Neural Netw. Learn. Syst. 2024, 35, 2942–2955. [Google Scholar] [CrossRef]
  40. Cao, R.; Lu, Y.P.; He, Z. System identification method based on interpretable machine learning for unknown aircraft dynamics. Aerosp. Sci. Technol. 2022, 126, 107593. [Google Scholar] [CrossRef]
  41. Omar, M.; Wang, K.; Kun, D.; Li, R.; Asker, A. Robust data-driven dynamic model discovery of industrial robots with spatial manipulation capability using simple trajectory. Nonlinear Dyn. 2024, 112, 9155–9177. [Google Scholar] [CrossRef]
  42. Liu, A.; Xue, Y.; Qin, H.; Zhu, Z. Physics-informed identification of marine vehicle dynamics using hydrodynamic dictionary library-inspired adaptive regression. Ocean. Eng. 2024, 296, 117013. [Google Scholar] [CrossRef]
  43. Papageorgiou, D.; Sigurdardóttir, G.T.; Falotico, E.; Tolu, S. Sliding-mode control of a soft robot based on data-driven sparse identification. Control Eng. Pract. 2024, 144, 105836. [Google Scholar] [CrossRef]
  44. Kong, J.; Pfeiffer, M.; Schildbach, G.; Borrelli, F. Kinematic and dynamic vehicle models for autonomous driving control design. In Proceedings of the IEEE Intelligent Vehicles Symposium, Seoul, Republic of Korea, 28 June–1 July 2015; pp. 1094–1099. [Google Scholar] [CrossRef]
  45. Chen, S.; Chen, H.; Negrut, D. Implementation of MPC-Based Path Tracking for Autonomous Vehicles Considering Three Vehicle Dynamics Models with Different Fidelities. Automot. Innov. 2020, 3, 386–399. [Google Scholar] [CrossRef]
  46. Micheli, F.; Bersani, M.; Arrigoni, S.; Braghin, F.; Cheli, F. NMPC Trajectory Planner for Urban Autonomous Driving. Veh. Syst. Dyn. 2023, 61, 1387–1409. [Google Scholar] [CrossRef]
  47. Pacejka, H.B.; Bakker, E. The Magic Formula Tyre Model. Veh. Syst. Dyn. 1992, 21, 1–18. [Google Scholar] [CrossRef]
  48. IPG Automotive GmbH. CarMaker; IPG Automotive: Karlsruhe, Germany, 2024. [Google Scholar]
  49. Kloeser, D.; Schöls, T.; Sartor, T.; Zanelli, A.; Frison, G.; Diehl, M. NMPC for Racing Using a Singularity-Free Path-Parametric Model with Obstacle Avoidance. IFAC-PapersOnLine 2020, 53, 14324–14329. [Google Scholar] [CrossRef]
  50. Verschueren, R.; Frison, G.; Kouzoupis, D.; Frey, J.; van Duijkeren, N.; Zanelli, A.; Novoselnik, B.; Albin, T.; Quirynen, R.; Diehl, M. acados: A modular open-source framework for fast embedded optimal control. arXiv 2019, arXiv:1910.13753. [Google Scholar] [CrossRef]
Figure 1. Tracks employed in the simulations. (a) Track taken from [49], primarly used for training. (b) Track of Monza F1 circuit, used for its high realism. (c) Track taken from [15], primarly used as testing scenario.
Figure 1. Tracks employed in the simulations. (a) Track taken from [49], primarly used for training. (b) Track of Monza F1 circuit, used for its high realism. (c) Track taken from [15], primarly used as testing scenario.
Electronics 14 01935 g001
Figure 2. Approximation of Pacejka’s Magic Formula through offline implementation of SINDy.
Figure 2. Approximation of Pacejka’s Magic Formula through offline implementation of SINDy.
Electronics 14 01935 g002
Figure 3. Overall setup implemented in Simulink and CarMaker.
Figure 3. Overall setup implemented in Simulink and CarMaker.
Electronics 14 01935 g003
Figure 4. Constrained-SINDy implementation in Matlab.
Figure 4. Constrained-SINDy implementation in Matlab.
Electronics 14 01935 g004
Figure 5. SINDy identification of the 3-DOF vehicle dynamics.
Figure 5. SINDy identification of the 3-DOF vehicle dynamics.
Electronics 14 01935 g005
Figure 6. R 2 of the 3-DOF SINDy identifications.
Figure 6. R 2 of the 3-DOF SINDy identifications.
Electronics 14 01935 g006
Figure 7. Lateral tire forces estimation in the 3DOF simulation. (a) Front lateral tire forces identified by SINDy from the different vehicle acceleration equations, against Pacejka’s Magic Formula. (b) Rear Lateral tire forces identified by SINDy from the different vehicle acceleration equations, against Pacejka’s Magic Formula.
Figure 7. Lateral tire forces estimation in the 3DOF simulation. (a) Front lateral tire forces identified by SINDy from the different vehicle acceleration equations, against Pacejka’s Magic Formula. (b) Rear Lateral tire forces identified by SINDy from the different vehicle acceleration equations, against Pacejka’s Magic Formula.
Electronics 14 01935 g007
Figure 8. Three-degree-of-freedom vehicle trajectory in the complex track 3.
Figure 8. Three-degree-of-freedom vehicle trajectory in the complex track 3.
Electronics 14 01935 g008
Figure 9. Trajectories of the 3-DOF vehicle before and after SINDy update.
Figure 9. Trajectories of the 3-DOF vehicle before and after SINDy update.
Electronics 14 01935 g009
Figure 10. SINDy identification of the CarMaker vehicle dynamics.
Figure 10. SINDy identification of the CarMaker vehicle dynamics.
Electronics 14 01935 g010
Figure 11. R 2 graph of the CarMaker identification.
Figure 11. R 2 graph of the CarMaker identification.
Electronics 14 01935 g011
Figure 12. Lateral tire forces estimation in Carmaker simulation. (a) Front Lateral tire forces identified by SINDy from the different vehicle acceleration equations, against CarMaker direct variable access. (b) Rear Lateral tire forces identified by SINDy from the different vehicle acceleration equations, against CarMaker direct variable access.
Figure 12. Lateral tire forces estimation in Carmaker simulation. (a) Front Lateral tire forces identified by SINDy from the different vehicle acceleration equations, against CarMaker direct variable access. (b) Rear Lateral tire forces identified by SINDy from the different vehicle acceleration equations, against CarMaker direct variable access.
Electronics 14 01935 g012
Figure 13. Zoom on the trajectory performed in CarMaker in complex track 2, (a) first turn, (b) second turn, (c) fourth turn, and (d) fifth turn.
Figure 13. Zoom on the trajectory performed in CarMaker in complex track 2, (a) first turn, (b) second turn, (c) fourth turn, and (d) fifth turn.
Electronics 14 01935 g013
Figure 14. Trajectories of the CarMaker vehicle before and after SINDy update.
Figure 14. Trajectories of the CarMaker vehicle before and after SINDy update.
Electronics 14 01935 g014
Figure 15. Velocity states of the CarMaker vehicle in complex track 1, before and after SINDy update.
Figure 15. Velocity states of the CarMaker vehicle in complex track 1, before and after SINDy update.
Electronics 14 01935 g015
Figure 16. Local position states of the CarMaker vehicle in simple track, before and after SINDy update.
Figure 16. Local position states of the CarMaker vehicle in simple track, before and after SINDy update.
Electronics 14 01935 g016
Table 1. Comparison of different approaches for handling uncertainty.
Table 1. Comparison of different approaches for handling uncertainty.
Robust MPCStochastic MPCDeep Learning MPC
Bounded uncertainty.Probabilistic distribution of uncertainty.Strong predictive performance.
Constraints satisfaction.Nonlinearities cause inaccuracies in propagation.Low interpretability and generalization.
Conservative control and reduced performance.Computational burden.High computational cost.
Table 2. List of vehicle parameters used in the model.
Table 2. List of vehicle parameters used in the model.
ParameterValue
M1412 kg
J z 1536.7 kg·m2
R0.325 m
l f 1.015 m
l r 1.895 m
w2 m
κ 2
ϵ 0 0.4
B0.0885 deg−1
C1.4
D8311 N
E−2
Table 3. Error and R 2 values of the 3-DOF estimation of SINDy.
Table 3. Error and R 2 values of the 3-DOF estimation of SINDy.
ErrorR2
v ˙ x 0.16%0.9999
v ˙ y 1.39%0.9998
ω ˙ 1.32%0.9998
Table 4. Error and R 2 values of the CarMaker estimation of SINDy.
Table 4. Error and R 2 values of the CarMaker estimation of SINDy.
ErrorR2
a x 5.73%0.9967
a y 9.49%0.9901
ω ˙ 37.58%0.8585
Disclaimer/Publisher’s Note: The statements, opinions and data contained in all publications are solely those of the individual author(s) and contributor(s) and not of MDPI and/or the editor(s). MDPI and/or the editor(s) disclaim responsibility for any injury to people or property resulting from any ideas, methods, instructions or products referred to in the content.

Share and Cite

MDPI and ACS Style

Paparazzo, F.; Castoldi, A.; Sathyamangalam Imran, M.I.I.; Arrigoni, S.; Braghin, F. Learning-Based MPC Leveraging SINDy for Vehicle Dynamics Estimation. Electronics 2025, 14, 1935. https://doi.org/10.3390/electronics14101935

AMA Style

Paparazzo F, Castoldi A, Sathyamangalam Imran MII, Arrigoni S, Braghin F. Learning-Based MPC Leveraging SINDy for Vehicle Dynamics Estimation. Electronics. 2025; 14(10):1935. https://doi.org/10.3390/electronics14101935

Chicago/Turabian Style

Paparazzo, Francesco, Andrea Castoldi, Mohammed Irshadh Ismaaeel Sathyamangalam Imran, Stefano Arrigoni, and Francesco Braghin. 2025. "Learning-Based MPC Leveraging SINDy for Vehicle Dynamics Estimation" Electronics 14, no. 10: 1935. https://doi.org/10.3390/electronics14101935

APA Style

Paparazzo, F., Castoldi, A., Sathyamangalam Imran, M. I. I., Arrigoni, S., & Braghin, F. (2025). Learning-Based MPC Leveraging SINDy for Vehicle Dynamics Estimation. Electronics, 14(10), 1935. https://doi.org/10.3390/electronics14101935

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