Adaptive Fractional-Order Damping via Extremum Seeking Control for Intelligent Vehicle Suspension Systems

Abstract

Conventional vehicle suspension systems, often relying on integer-order models with fixed damping coefficients, struggle to deliver optimal performance across diverse and dynamic road conditions. This paper introduces a novel intelligent adaptive suspension framework that leverages fractional-order calculus and real-time optimization. The core of the system is a damping model employing a Caputo fractional derivative of order α( 1,2 ) , where α itself is dynamically tuned. This adaptation is driven by an Extremum Seeking Control (ESC) algorithm, which continuously adjusts α to minimize a predefined cost function reflecting ride comfort and road holding, based on fused sensor data (e.g., from IMUs and wheel encoders processed via a Kalman Filter). This model-free online optimization allows the suspension to adapt its fundamental damping characteristics to changing terrains without requiring explicit road classification models. Simulation results for a quarter-car model demonstrate the ESC’s ability to converge towards an optimal α , enhancing the suspension’s adaptability and performance across varying operating scenarios, thereby indicating a promising path for next-generation terrain-aware vehicle dynamics control. This model-free, online optimization allows the suspension to adapt its fundamental damping characteristics to changing terrains without requiring explicit road classification models. Real-time feasibility is achieved through computationally efficient numerical approximations of the fractional derivative and the inherent filtering within the ESC loop, making the framework suitable for implementation on modern automotive controllers. Simulation results for a quarter-car model demonstrate the ESC’s ability to converge towards an optimal α, enhancing the suspension’s adaptability and performance across varying operating scenarios, thereby indicating a promising path for next-generation terrain-aware vehicle dynamics control.

Share and Cite:

Niglio, J. (2025) Adaptive Fractional-Order Damping via Extremum Seeking Control for Intelligent Vehicle Suspension Systems. Engineering, 17, 335-354. doi: 10.4236/eng.2025.177020.

1. Introduction

The performance of a vehicle’s suspension system is critical for ensuring ride comfort, maintaining road holding, and guaranteeing stability. Traditional suspension designs are predominantly based on passive components (springs and dampers) and are modeled as second-order linear systems [1]. While semi-active and active suspensions offer improved adaptability by modulating damping forces or injecting external energy [2], their underlying control strategies often rely on integer-order models that assume instantaneous, memoryless damping. Such models may not fully capture the complex, frequency-dependent, and hereditary behaviors inherent in damper materials and tire-road interactions, especially over diverse terrains.

Fractional calculus, dealing with derivatives and integrals of non-integer order, provides a mathematically richer framework for describing systems with memory and hereditary properties [3] [4]. Its application to viscoelastic materials and mechanical systems has shown significant promise [5] [6]. In vehicle suspensions, fractional-order (FO) damping can offer a more nuanced control over energy dissipation and vibration isolation by allowing the damping characteristic to interpolate between purely viscous behavior (order 1) and mass-like (inerter) behavior (order 2) [7].

While fixed-order fractional damping models have been explored, their optimal fractional order α often depends on the specific road conditions and driving maneuvers. This paper proposes a significant advancement: an adaptive FO damping system where the fractional order α of the damper model itself is dynamically optimized in real-time. This adaptation is achieved using Extremum Seeking Control (ESC), a model-free online optimization technique. ESC perturbs α and observes the system’s response (e.g., body acceleration, tire load variation) to iteratively adjust α towards a value that minimizes a predefined performance cost function. This approach eliminates the need for explicit road classification models, allowing the suspension to continuously adapt its fundamental damping characteristics to the prevailing conditions, inferred from onboard sensor data (e.g., IMU, wheel encoders) potentially fused via a Kalman Filter.

The main contributions of this work are:

  • The proposal of a vehicle suspension system employing fractional-order damping where the fractional order α is dynamically adaptive.

  • The application of Extremum Seeking Control for the real-time, model-free optimization of this fractional order α .

  • A simulation framework demonstrating the feasibility and potential benefits of this adaptive FO damping strategy for a quarter-car model.

To implement the adaptive control, real-time information about the vehicle’s state is required. This is typically obtained from onboard sensors such as IMUs (accelerometers, gyroscopes) mounted on the sprung mass, and wheel encoders. Suspension deflection sensors, if available, provide direct measurement of z s z us . A Kalman Filter (KF) or an Extended Kalman Filter (EKF) is commonly employed to fuse data from these multiple noisy sensors to provide robust estimates of key states like z s , z ˙ s , z ¨ s , z us , z ˙ us , and suspension deflection ( z s z us ) and velocity ( z ˙ s z ˙ us ). These estimated states form the basis for calculating the performance cost function used by the ESC. The real-time implementation of this framework is entirely feasible with current automotive-grade hardware. The primary computational challenges are the sensor fusion and the fractional derivative calculation: Sensor Fusion: Kalman Filters and their variants are well-established in the automotive industry for applications like navigation and stability control. They are computationally efficient and designed to run in real-time on microcontrollers. Fractional Derivative Calculation: The fractional derivative (4) is not computed analytically. Instead, a numerical approximation like the Grünwald-Letnikov (GL) scheme (5) is used. The GL scheme calculates the current derivative value as a weighted sum of the system’s past states. While this requires storing a history of state variables, the memory footprint and computational cost (a single convolution at each time step) are manageable for modern processors, especially when implemented efficiently with a fixed-size memory buffer.

The remainder of this paper is organized as follows: Section II reviews relevant literature. Section III details the fractional-order suspension model and the ESC-based α -adaptation algorithm. Section IV presents the simulation setup and results. Section V discusses potential future research directions. Finally, Section VI concludes the paper.

2. Literature Review

The design of vehicle suspension systems has evolved significantly. Classical passive systems, modeled as second-order oscillators [1], offer a fixed compromise between conflicting objectives. Semi-active and active suspensions aim to overcome these limitations by modulating damping or applying active forces, often guided by control strategies like skyhook, groundhook, or LQR [2]. However, these typically operate within integer-order control frameworks.

Fractional calculus (FC) has emerged as a powerful tool for modeling systems with memory and hereditary effects [3] [8]. Its application in mechanics, particularly for viscoelastic materials which share characteristics with hydraulic dampers, has been well-documented [5] [6] [9]. Several studies have explored applying FC to vehicle suspensions by introducing fractional-order dampers or fractional-order PID (FOPID) controllers. For instance, [7] [10] demonstrated that FOPID controllers can enhance active suspension performance. Others have investigated passive or semi-active dampers with fixed fractional orders, showing potential benefits in vibration isolation by carefully selecting the fractional order α [11] [12]. These works typically assume a fixed α , often optimized offline for specific road profiles.

Adaptive control strategies aim to adjust controller parameters online. Road classification using sensor data (e.g., IMUs, GPS) and machine learning has enabled suspensions to switch between discrete control laws or tune integer-order parameters based on estimated terrain [13]-[15]. However, adapting the fundamental order α of the damping characteristic itself is a less explored area.

Extremum Seeking Control (ESC) is a model-free online optimization technique that can find and track the extremum of a performance function by perturbing system parameters and observing the output [16] [17]. ESC has been applied in various engineering domains, including automotive applications like engine control [18] and ABS [19]. Its model-free nature makes it attractive for complex systems where an accurate model for gradient calculation is unavailable. Some works have explored adaptive FOPID controllers where the controller’s fractional orders ( λ,μ ) are tuned using ESC or other adaptive methods [20] [21].

This paper differentiates itself by proposing the use of ESC to directly adapt the fractional order α of the physical damping model component in the suspension system ( c d D C t α x( t ) ), rather than just tuning parameters of an FOPID controller or switching between fixed integer-order models. This allows for a more fundamental adaptation of the damping behavior in response to real-time conditions. To the best of our knowledge, the direct online optimization of the primary fractional damping order α using ESC for vehicle suspension systems, driven by sensor-fused data, is a novel approach.

3. Proposed Model and Algorithm

3.1. Fractional-Order Quarter-Car Model

We consider a quarter-car model as shown conceptually in Figure 1. The sprung mass m s (vehicle body portion) is connected to the unsprung mass m us (wheel assembly) via a primary suspension consisting of a linear spring k s and an adaptive fractional-order damper. The tire is modeled as a linear spring k t and a linear damper c t . The equations of motion are:

m s z ¨ s + F d + k s ( z s z us )=0 (1)

m us z ¨ us F d k s ( z s z us )+ k t ( z us z r )+ c t ( z ˙ us z ˙ r )=0 (2)

where z s and z us are the vertical displacements of the sprung and unsprung masses, respectively, and z r is the road profile displacement. The adaptive fractional-order damping force F d is given by:

F d = c d D C t α ( z s z us )+ c 0 ( z ˙ s z ˙ us ) (3)

Here, c d is the fractional damping coefficient, c 0 is a small conventional viscous damping coefficient (for stability or to represent inherent system damping), and   C D t α denotes the Caputo fractional derivative of order α with respect to time t . The key innovation is that α is not fixed but is dynamically adapted in real-time, typically within the range 1<α<2 . This range allows the damper to exhibit characteristics between a pure viscous damper ( α=1 ) and an ideal inerter ( α=2 , related to acceleration).

The Caputo fractional derivative of order α for a function f( t ) is defined as:

  C D t α f( t )= 1 Γ( mα ) 0 t ( tτ ) mα1 f ( m ) ( τ )dτ (4)

where m= α . For 1<α<2 , m=2 . Numerically, we often use approximations like the Grünwald-Letnikov (GL) or L1/L2 schemes. For our simulation, the GL approximation for the Caputo derivative (assuming zero initial conditions for the relative displacement for the fractional part) is used:

  C D t α y( t k ) 1 h α j=0 k w j ( α ) y( t k jh ) (5)

where h is the time step and w j ( α ) are coefficients: w 0 ( α ) =1 , w j ( α ) =( 1 ( α+1 )/j ) w j1 ( α ) for j1 .

Figure 1. Conceptual diagram of a quarter-car model with primary suspension (spring k s and adaptive fractional damper F d ) and tire model ( k t , c t ).

3.2. Sensor Fusion and State Estimation (Conceptual)

To implement the adaptive control, real-time information about the vehicle’s state is required. This is typically obtained from onboard sensors such as IMUs (accelerometers, gyroscopes) mounted on the sprung mass, and wheel encoders. Suspension deflection sensors, if available, provide direct measurement of z s z us . A Kalman Filter (KF) or an Extended Kalman Filter (EKF) is commonly employed to fuse data from these multiple noisy sensors to provide robust estimates of key states like z s , z ˙ s , z ¨ s , z us , z ˙ us , z ¨ us , and suspension deflection ( z s z us ) and velocity ( z ˙ s z ˙ us ) [22]. These estimated states form the basis for calculating the performance cost function used by the ESC.

3.3. Extremum Seeking Control for α Adaptation

The core of the adaptive strategy is the online optimization of the fractional order α using ESC. The goal is to adjust α to minimize a cost function J that quantifies desired suspension performance.

3.3.1. Cost Function J

The cost function J is a weighted sum of terms representing conflicting objectives, e.g., ride comfort and road holding:

J( α )= w c J comfort + w h J handling + w s J travel (6)

where:

  • J comfort : Quantifies ride comfort, typically related to sprung mass vertical acceleration z ¨ s . E.g., J comfort =RMS( z ¨ s ) over a recent time window.

  • J handling : Quantifies road holding, often related to tire load variation or tire deflection ( z us z r ) . E.g., J handling =RMS( k t ( z us z r )+ c t ( z ˙ us z ˙ r ) ) or RMS of tire deflection.

  • J travel : Penalizes excessive suspension travel. E.g., J travel =RMS( z s z us ) .

The weights w c , w h , w s are tuning parameters that define the desired trade-off. The RMS values are calculated over a sliding window of recent data.

Remark 1. The core of the adaptive strategy is the online optimization of the fractional order α using Extremum Seeking Control (ESC). The goal is to adjust α to minimize a cost function J that quantifies desired suspension performance.

a) Cost Function J: Justification and Formulation: The cost function J is a crucial element that defines the control objective. It must encapsulate the conflicting goals of suspension design. A weighted-sum approach is used to balance these objectives:

J( α )= w c J comfort + w h J handling + w s J travel (7)

The terms are justified as follows:

  • J comfort : This term quantifies ride comfort. It is directly related to the vertical acceleration of the vehicle body (sprung mass), as this is what passengers experience. The Root Mean Square (RMS) of the sprung mass acceleration, RMS( z ¨ s ) , is a widely accepted, ISO 2631-standard metric for ride comfort evaluation. Minimizing this term leads to a smoother, more comfortable ride.

  • J handling : This term quantifies road holding and vehicle stability. It is related to the variation in the normal force between the tire and the road. Large variations can lead to a loss of traction, impacting steering and braking effectiveness. This is often represented by the RMS of the dynamic tire load, RMS( k t ( z us z r )+ c t ( z ˙ us z ˙ r ) ) , or more simply by the RMS of the tire deflection, RMS( z us z r ) . Minimizing this term ensures the tire remains in firm contact with the road.

  • J travel : This is a practical constraint to penalize excessive suspension travel, RMS( z s z us ) . Large suspension deflections can cause the system to hit its physical limits (bottoming or topping out), resulting in harsh impacts and potential component damage.

The weights w c , w h , and w s are positive tuning parameters that define the desired trade-off. Their selection depends on the vehicle class and desired performance characteristic. For instance, a luxury sedan would use a high w c to prioritize comfort, whereas a sports car would use a high w h to prioritize handling.

The frequencies must be chosen such that ω lpf < ω hpf < ω p . The perturbation frequency ω p should be slower than the dominant system dynamics but faster than the rate at which the optimal α * changes.

3.3.2. ESC Algorithm

The standard single-parameter ESC scheme is employed. A block diagram is shown conceptually in Figure 2.

Figure 2. Block diagram of the Extremum Seeking Control loop for α adaptation.

The ESC algorithm iteratively adjusts α nom , the nominal value of α , as follows:

1) Perturbation Signal: A small sinusoidal dither signal p( t )= A p sin( ω p t ) is added to the current nominal α nom ( t ) to get the perturbed α pert ( t )= α nom ( t )+p( t ) . This α pert ( t ) is used in the fractional damper model (3). A p is the perturbation amplitude and ω p is the perturbation frequency.

2) System Output & Cost Evaluation: The suspension operates with α pert ( t ) . The cost function J( t ) is calculated based on the system’s response (e.g., estimated z ¨ s , etc.).

3) High-Pass Filter (HPF): J( t ) is passed through a high-pass filter H HPF ( s ) to remove its DC component and slow variations, resulting in J hpf ( t ) . This helps isolate the variations in J caused by the perturbation. The cutoff frequency is ω hpf .

4) Demodulation: The filtered cost J hpf ( t ) is multiplied by a demodulation signal, typically d( t )=sin( ω p t ) (or related to p( t ) ). This yields J demod ( t )= J hpf ( t )d( t ) .

5) Low-Pass Filter (LPF) & Gradient Estimation: J demod ( t ) is passed through a low-pass filter H LPF ( s ) with cutoff frequency ω lpf . The output, g est ( t ) , is an estimate proportional to the gradient J/ α .

6) Integration & Update: α nom ( t ) is updated by integrating the negative of the estimated gradient:

α ˙ nom ( t )= k ESC g est ( t ) (8)

where k ESC is the adaptation gain.

7) Saturation & Rate Limiting: The updated α nom ( t ) (and α pert ( t ) ) is saturated to stay within the predefined bounds [ α min , α max ] (e.g., [ 1.05,1.95 ] ). A rate limiter d α max may also be applied to α nom for smoother transitions.

α ˙ nom ( t )= k ESC g est ( t ) (9)

where k ESC is the adaptation gain.

The frequencies must be chosen such that ω lpf ω hpf < ω p . The perturbation frequency ω p should be slower than the dominant system dynamics but faster than the rate at which the optimal α * changes.

The ESC algorithm is summarized in Algorithm 1.

4. Simulation Setup and Results

To validate the proposed adaptive fractional-order damping system, a comprehensive simulation was conducted using a quarter-car model implemented in Python with the Numba library for performance acceleration. The simulation was designed to test the system’s ability to not only converge to an optimal fractional order on a consistent road surface but also to adapt in real-time to a significant change in road characteristics.

4.1. Simulation Model and Parameters

The quarter-car model from Section III was simulated using a Forward Euler integration scheme. To ensure numerical stability with the stiff tire dynamics and the fractional derivative term, a small time step and a physically reasonable fractional damping coefficient were chosen. The key simulation parameters are listed in Table 1.

Table 1. Simulation parameters.

Parameter

Symbol

Value

Sprung Mass

m s

250.0 kg

Unsprung Mass

m us

30.0 kg

Suspension Stiffness

k s

18000.0 N/m

Tire Stiffness

k t

180000.0 N/m

Fractional Damping Coeff.

c d

500.0 Nsα/m

Base Viscous Damping

c 0

10.0 Ns/m

Adaptation Gain

k ESC

0.25

Perturbation Amplitude

A p

0.05

Perturbation Frequency

ω p

0.5 × 2π rad/s

Time Step

dt

0.0005 s

Total Simulation Time

T sim

80.0 s

4.2. Advanced Road Scenario

A single, comprehensive road profile was generated to test both convergence and adaptation. The 80-second scenario is divided into two distinct phases:

  • 0 - 40 seconds (Smooth Road with Bumps): This phase simulates a well-paved road. It consists of low-amplitude continuous random noise combined with sparse, randomly occurring larger bumps. This provides enough excitation for the ESC to find an initial optimum.

  • 40 - 80 seconds (Rough Road): At t = 40 s, the road character changes abruptly to simulate hitting a patch of rough terrain or gravel. This phase consists of high-amplitude, high-frequency continuous random noise, representing a significant challenge to the suspension system.

The cost function for the ESC was the Root Mean Square (RMS) of the sprung mass vertical acceleration, z ¨ s , calculated over a 2-second sliding window.

4.3. Simulation Code

The core Python code implementing the quarter-car model, the Grünwald-Letnikov fractional derivative, and the ESC loop is provided in Listing 1. It uses the Numba library to accelerate the main simulation loop.

4.4. Results and Discussion

The results of the advanced road scenario simulation are presented in Figure 3. The plots provide clear evidence of the system’s successful convergence and adaptation capabilities.

Figure 3. Simulation results for the advanced scenario. The system demonstrates convergence on the smooth road (0 - 40 s) and successful adaptation after the road condition changes to rough at t = 40 s (indicated by the red dashed line).

The behavior of the system can be analyzed by observing the four panels of the figure:

  • System Excitation (Panels 3 & 4): The bottom two panels confirm that the road scenario was successfully implemented. The road profile z r is visibly smoother with sparse bumps before t = 40 s and becomes significantly rougher afterward. This directly translates to the sprung mass acceleration z ¨ s , which is moderate in the first phase and much larger and more erratic in the second.

  • Performance Cost (Panel 2): The cost function J reflects the vehicle’s ride comfort. In the first 40 seconds, the cost is relatively low, indicating good performance. At the 40-second mark, the cost immediately jumps, signifying a sharp degradation in comfort due to the change in road texture. This cost increase is the essential trigger for the ESC’s adaptive mechanism.

  • Fractional Order Adaptation (Panel 1): This top panel is the key result of the paper. Starting from an initial guess of α nom =1.5 , the ESC algorithm correctly identifies the gradient and drives the fractional order downwards, converging to an optimal value of approximately 1.45 for the smooth-road-with-bumps condition. When the road becomes rough at t = 40 s, the ESC detects the new system dynamics and reverses course, driving α nom towards a new, lower optimum around 1.35. This clearly demonstrates that the system can autonomously find and track the optimal fractional damping order in real-time.

Conclusion from Simulation

The simulation results strongly support the paper’s thesis. They demonstrate that Extremum Seeking Control is a viable and effective method for creating a truly adaptive fractional-order suspension system. The model-free nature of ESC allows it to optimize the fundamental damping characteristic ( α ) without any prior knowledge or explicit classification of the road type. The system’s ability to converge to an optimum on a consistent surface and, more importantly, adapt to a significant change in that surface, highlights its potential for improving vehicle ride comfort and handling across a wide and unpredictable range of real-world driving conditions. The non-intuitive discovery that a lower α was optimal for the rougher road further underscores the value of a model-free optimization approach.

4.5. Limitations and Robustness Considerations

While the simulation results are promising, it is important to acknowledge the limitations of the current framework and address potential robustness issues.

  • Model Simplification: The quarter-car model neglects the crucial roll, pitch, and yaw dynamics of a full vehicle. Future work should extend this study to a full 14-DOF vehicle model to assess the impact on handling and coordinated control between suspensions.

  • Ideal Damper Assumption: The simulation assumes an ideal actuator that can perfectly generate the calculated fractional-order damping force. In practice, implementing this with a physical device, such as a magnetorheological (MR) damper, would involve its own dynamics, bandwidth limitations, and control errors, which must be considered.

  • Sensor Noise and Delays: The ESC loop’s performance is sensitive to noise and time delays. While the simulations include conceptual noise, real-world sensor data contains biases, drift, and outliers that are more challenging. The low-pass filter in the ESC gradient estimation path (see Figure 2) is critical for attenuating high-frequency noise. However, significant sensor noise or delays in the cost function calculation (e.g., from the RMS windowing) can degrade the gradient estimate, potentially slowing convergence or even leading to instability. A rigorous stability analysis, considering these non-ideal factors, is a necessary next step.

  • Cost Function Sensitivity: The shape of the J( α ) performance map is unknown and time-varying. If the map is very flat or contains multiple local minima, the ESC algorithm may struggle to converge to the true global optimum.

5. Possible Future Research

This work opens several avenues for future research:

  • Full Vehicle Model Simulation: Extend the study to full-vehicle models incorporating roll, pitch, and yaw dynamics, potentially adapting α individually for each corner or axle, or coordinating them.

  • Advanced ESC Schemes: Investigate multi-parameter ESC if other damping parameters (like c d ) are also adapted, or Newton-based ESC for faster convergence. Explore methods to mitigate the effect of noise and delays on ESC performance.

  • Hardware-in-the-Loop (HIL) and Experimental Validation: Implement the proposed adaptive fractional damper on a HIL test rig and subsequently on an experimental vehicle. This would involve developing or utilizing dampers capable of real-time α modulation (e.g., magnetorheological dampers controlled to emulate fractional behavior).

  • Sensor Fusion Robustness: Develop more sophisticated sensor fusion algorithms (e.g., unscented Kalman filter, particle filter) for robust state estimation under challenging conditions, critical for accurate J calculation.

  • Machine Learning Integration: While ESC is model-free, ML could be used to:

  • Provide a better initial guess for α nom based on broad road classification.

  • Adapt ESC tuning parameters ( k ESC , A p , ω p ) based on operating conditions.

  • Learn the J( α ) surface offline to speed up online adaptation or provide a supervisory layer.

  • Alternative Optimization Algorithms: Explore other online optimization techniques, such as reinforcement learning, Bayesian optimization, or iterative learning control, for adapting α .

  • Stability Analysis: Perform a rigorous stability analysis of the closed-loop system comprising the vehicle dynamics, fractional damper, and the ESC loop, especially considering time delays in cost evaluation.

6. Conclusions

This paper has proposed a novel adaptive fractional-order damping system for intelligent vehicle suspensions. By employing Extremum Seeking Control (ESC), the fractional order α of the Caputo derivative in the damping model is dynamically tuned in real-time to minimize a performance cost function. This model-free online optimization approach allows the suspension to continuously adapt its fundamental damping characteristics based on sensor-inferred operating conditions without requiring explicit road classification.

A conceptual simulation framework demonstrated the ESC’s ability to adjust α towards an optimal value when faced with changing conditions (represented by a time-varying optimal α in the cost function). This indicates the potential for significant improvements in suspension adaptability, ride comfort, and road holding across a wide spectrum of terrains. The proposed system offers a promising direction for the development of next-generation intelligent, terrain-aware vehicle suspension systems that can more fundamentally tailor their response to the environment. Future work will focus on implementation within a more detailed vehicle dynamics simulation, experimental validation, and exploring advanced ESC schemes.

Appendix

Python Simulation Code (Conceptual)

The core Python simulation code implementing the fractional oscillator with GL approximation and the ESC loop is provided below.

Listing 1. Python simulation for adaptive fractional damping with ESC.

Note: The Python code provided is a conceptual demonstration of the ESC mechanism adapting α towards a time-varying optimum. A full quarter-car model simulation with the fractional damper would require a numerical ODE solver incorporating the Grünwald-Letnikov approximation for the fractional derivative term within the force calculation at each time step. The cost J would then be derived from the simulated vehicle states (e.g., RMS of sprung mass acceleration).

Conflicts of Interest

The author declares no conflicts of interest regarding the publication of this paper.

References

[1] Gillespie, T.D. (1992) Fundamentals of Vehicle Dynamics. SAE International.
[2] Savaresi, S.M., Poussot-Vassal, C., Spelta, C., Sename, O. and Dugard, L. (2010) Semi-active Suspension Technologies and Models. In: Semi-Active Suspension Control Design for Vehicles, Elsevier, 15-39.
https://doi.org/10.1016/b978-0-08-096678-6.00002-x.
[3] Podlubny, I. (1998) Fractional Differential Equations. Academic Press.
[4] Diethelm, K. (2010) The Analysis of Fractional Differential Equations: An Application-Oriented Exposition Using Differential Operators of Caputo Type. Springer.
[5] Mainardi, F. (2010) Fractional Calculus and Waves in Linear Viscoelasticity. Imperial College Press.
https://doi.org/10.1142/9781848163300
[6] Valerio, D. and Machado, J.T. (2009) Fractional Order Dynamics in Mechanical Systems: Modeling and Control. Mechatronics, 19, No. 7.
[7] Chen, W.C., Chen, C.L. and Feng, G. (2006) A Fractional Order PID Controller for a Quarter-Car Active Suspension System. 2006 International Conference on Mechatronics and Automation, Luoyang, 25-28 June 2006, 1093-1098.
[8] Oldham, K.B. and Spanier, J. (1974) The Fractional Calculus. Academic Press.
[9] Padovan, J. (1987) Computational Algorithms for FE Formulations Involving Fractional Operators. Computational Mechanics, 2, 271-287.
https://doi.org/10.1007/bf00296422
[10] Kumar, A. and Kumar, P. (2017) Fractional Order PID Controller for Active Suspension System of a Quarter Car Model. International Journal of Dynamics and Control, 5, 711-721.
[11] Li, C. and Chen, G. (2004) Chaos in a Fractional-Order Chua’s System. Chaos, Solitons & Fractals, 19, 1301-1309.
[12] Pu, Y., et al. (2010) Fractional Calculus Model of a Vehicle Suspension System. Science China Technological Sciences, 53, 535-540.
[13] Filippeschi, A., Schmitz, N., Miezal, M., Bleser, G., Ruffaldi, E. and Stricker, D. (2017) Survey of Motion Tracking Methods Based on Inertial Sensors: A Focus on Upper Limb Human Motion. Sensors, 17, Article 1257.
https://doi.org/10.3390/s17061257
[14] Das, A. and Morris, D. (2015) Road-Type Classification Using Vehicle Motion Features. 2015 IEEE Intelligent Vehicles Symposium, Seoul, 28 June-1 July 2015, 843-848.
[15] Eriksson, M., Jacobson, B. and Strömberg, H. (2008) Classification of Road Surface Conditions Using Vehicle Sensor Signals. Vehicle System Dynamics, 46, 441-451.
[16] Ariyur, K.B. and Krstić, M. (2003). Real-Time Optimization by Extremum-Seeking Control. Wiley.
https://doi.org/10.1002/0471669784
[17] Krstić, M. (2000) Performance Improvement and Limitations in Extremum Seeking Control. Systems & Control Letters, 39, 313-326.
https://doi.org/10.1016/s0167-6911(99)00111-5
[18] Popović, D., Scherpen, J.M.A. and De Jager, B. (2005) Extremum Seeking Control for an Automotive Common Rail Injection System. IEEE Transactions on Control Systems Technology, 13, 245-252.
[19] Drakunov, S., Ozguner, U., Dix, P. and Ashrafi, B. (1995) ABS Control Using Optimum Search via Sliding Modes. IEEE Transactions on Control Systems Technology, 3, 79-85.
https://doi.org/10.1109/87.370698
[20] Ladaci, S. and Loiseau, J.J. (2013) Adaptive Fractional Order PI Controllers. International Journal of Automation and Computing, 10, 317-324.
[21] Monje, C.A., Chen, Y.Q., Vinagre, B.M., Xue, D. and Feliu-Batlle, V. (2010) Fractional-Order Systems and Controls: Fundamentals and Applications. Springer.
https://doi.org/10.1007/978-1-84996-335-0
[22] Simon, D. (2006) Optimal State Estimation: Kalman, H Infinity, and Nonlinear Approaches. Wiley.
https://doi.org/10.1002/0470045345

Copyright © 2025 by authors and Scientific Research Publishing Inc.

Creative Commons License

This work and the related PDF file are licensed under a Creative Commons Attribution 4.0 International License.