Next Article in Journal
A Semantic Behavioral Sequence-Based Approach to Trajectory Privacy Protection
Previous Article in Journal
Symmetry in Explainable AI: A Morphometric Deep Learning Analysis for Skin Lesion Classification
Previous Article in Special Issue
A Fuzzy Logic-Based eHealth Mobile App for Activity Detection and Behavioral Analysis in Remote Monitoring of Elderly People: A Pilot Study
 
 
Font Type:
Arial Georgia Verdana
Font Size:
Aa Aa Aa
Line Spacing:
Column Width:
Background:
Article

A Skill-Inspired Adaptive Fuzzy Control Framework for Symmetric Gait Tracking with Sparse Sensor Fusion in Lower-Limb Exoskeletons

1
The IBISC Laboratory, UEVE, University of Paris-Saclay, 91000 Evry, France
2
School of Future Technology, South China University of Technology, Guangzhou 511442, China
*
Author to whom correspondence should be addressed.
Symmetry 2025, 17(8), 1265; https://doi.org/10.3390/sym17081265
Submission received: 1 July 2025 / Revised: 24 July 2025 / Accepted: 1 August 2025 / Published: 7 August 2025
(This article belongs to the Special Issue Symmetry/Asymmetry in Fuzzy Control)

Abstract

This paper presents a real-time framework for bilateral gait reconstruction and adaptive joint control using sparse inertial sensing. The system estimates full lower-limb motion from a single-side inertial measurement unit (IMU) by applying a pipeline that includes signal smoothing, temporal alignment via Dynamic Time Warping (DTW), and motion modeling using Gaussian Mixture Models with Regression (GMM-GMR). Contralateral leg trajectories are inferred using both ideal and adaptive symmetry-based models to capture inter-limb variations. The reconstructed motion serves as reference input for joint-level control. A classical Proportional–Integral–Derivative (PID) controller is first evaluated, demonstrating satisfactory results under simplified dynamics but notable performance loss when virtual stiffness and gravity compensation are introduced. To address this, an adaptive fuzzy PID controller is implemented, which dynamically adjusts control gains based on real-time tracking error through a fuzzy inference system. This approach enhances control stability and motion fidelity under varying conditions. The combined estimation and control framework enables accurate bilateral gait tracking and smooth joint control using minimal sensing, offering a practical solution for wearable robotic systems such as exoskeletons or smart prosthetics.

1. Introduction

Wearable robotic systems, especially lower-limb exoskeletons, have attracted significant attention for their ability to support human locomotion, assist rehabilitation, and improve mobility for individuals with impairments [1,2,3,4]. To be effective, these systems require not only accurate motion generation but also control strategies [5,6] that can adapt to the variability of human gait and the complexities of physical human–robot interaction [7,8,9].
Recent advances in data-driven modeling [10] have enabled the use of human movement patterns for robotic control. Among these, Dynamic Time Warping (DTW) is widely used to temporally align gait cycles of varying lengths, facilitating consistent phase matching across trials [11,12,13,14]. However, DTW alone does not create generalized models suitable for motion synthesis. To overcome this, Gaussian Mixture Models (GMM) combined with Gaussian Mixture Regression (GMR) have been employed to generate smooth, probabilistic representations of human joint trajectories [15,16,17].
After generating reference trajectories, an effective control strategy [18] is required to track them in real time. Classical Proportional–Integral–Derivative (PID) controllers remain common in exoskeleton systems due to their simplicity and low computational requirements [19,20]. However, PID controllers often perform poorly in the presence of non-linearities such as joint elasticity, friction, and gravitational disturbances [20,21]. To address these challenges, fuzzy logic controllers [22] have been proposed as adaptive alternatives capable of tuning gains in response to real-time tracking errors [7,8,9,23].
This paper presents an integrated framework that combines trajectory reconstruction, symmetry-aware motion prediction, and adaptive joint control for lower-limb exoskeletons. The proposed method reconstructs bilateral gait motion from sparse unilateral sensor input using a sequence of signal filtering, DTW alignment, and GMM-GMR modeling. A key contribution is the use of a technique that refines contralateral leg predictions using phase shifts, amplitude scaling, and offset correction, capturing real-world gait asymmetries often ignored in idealized models. Additionally, we introduce an adaptive fuzzy PID controller that dynamically adjusts control gains based on instantaneous error and error rate. This controller improves tracking fidelity under nonlinear conditions, including simulated joint stiffness and gravity effects. While many existing systems rely on dense sensor networks, our approach uses sparse sensor fusion—integrating data from IMUs, flex sensors, and pressure sensors—processed in parallel to achieve real-time gait estimation with reduced hardware complexity.
The framework is evaluated through simulation using real gait datasets. We assess trajectory accuracy and control robustness across walking, running, and stair climbing tasks, demonstrating the system’s generalization across diverse locomotion modes.

2. Materials and Methods

2.1. Sensor Setup and Dataset

The proposed system integrates wearable sensing, trajectory reconstruction, and exoskeleton control in a modular pipeline. As shown in Figure 1, the full setup consists of three stages: human motion data acquisition, signal preprocessing, and robotic control execution. During the acquisition stage, motion data are collected from the user’s left leg using a sparse sensor configuration. Two inertial measurement units (IMUs; Xsens DOT, Movella Inc., Enschede, The Netherlands) were placed near the hip and knee joints to capture joint-level kinematics. These IMUs provide angular velocity and orientation data, which are used to reconstruct the trajectories of the hip and knee joints in the sagittal plane.
Smart shoes (Qihang Tech, Weihai, China) were equipped with embedded pressure and flex sensors to monitor foot-ground contact and foot arch deformation during dynamic locomotion. In detail, smart shoes are equipped with the following:
  • One IMU positioned on the foot to reconstruct the foot’s angular motion and orientation during stance and swing phases.
  • Pressure sensors embedded under the sole to monitor foot-ground contact and estimate the center of pressure (COP), which can be used to approximate the center of gravity (COG) trajectory.
  • Flex (bending) sensors placed along the shoe upper to detect curvature and deformation of the foot arch during dynamic locomotion.
All sensor signals are transmitted wirelessly via Bluetooth to a central computer for real-time processing.
The system employs a parallel sensing fusion strategy, in which each sensor modality—IMU, pressure, and flex—independently contributes specific biomechanical features. IMUs provide joint kinematics and segment orientations; pressure sensors detect gait events and loading patterns; and flex sensors capture arch deformation related to foot curvature. These signals are not fused at the feature or decision level. Instead, each stream is processed in parallel and integrated only during the control and reconstruction stages. This modular design simplifies implementation, reduces latency, and enhances system interpretability, making it suitable for real-time wearable robotics applications.
Subjects performed locomotion tasks including level-ground walking, stair climbing, and running at self-selected speeds in a controlled indoor environment. IMU data were recorded at 100 Hz, capturing multiple complete gait cycles for each motion type. The data were stored in CSV format with timestamped joint angle estimates derived from the IMU signals. Only the left leg was instrumented, and its motion was used to estimate the contralateral limb motion using symmetry-based reconstruction models [4,24].
After acquisition, the raw signals were smoothed, segmented into gait cycles, and time-normalized to ensure consistency across trials. The resulting processed left-leg trajectories served as input for both motion modeling and the control strategy. All data processing and control algorithms were implemented using MATLAB R2024a (MathWorks Inc., Natick, MA, USA).

2.2. Signal Preprocessing

Raw joint angle signals captured from inertial measurement units (IMUs) often contain high-frequency noise, motion artifacts, and low-frequency drift. These disturbances result from sensor limitations, soft tissue oscillations, and mechanical impacts during locomotion. To mitigate these effects while preserving the biomechanical integrity of the signals, a locally weighted scatterplot smoothing (LOESS) filter was applied [12,24].
LOESS is a non-parametric regression technique that fits a low-order polynomial to localized segments of the data using weighted least squares. This approach enables adaptive smoothing by assigning greater weight to points near the current time t, thereby maintaining sharp motion transitions (e.g., heel strikes or peak flexion) while suppressing transient noise [12].
The smoothed value x ^ ( t ) at time t is computed as follows:
x ^ ( t ) = i = 1 N w i ( t ) x i
where x i are the original data samples, and w i ( t ) are weights determined by their temporal distance from t. The weights follow a tricube kernel function:
w i ( t ) = 1 t t i h 3 3 if | t t i | < h 0 otherwise
Here, h defines the smoothing span or window width, and t i represents the timestamps of neighboring samples. In practice, for signals recorded at 100 Hz, a span of 20–50 samples (equivalent to 0.2–0.5 s of data) was found to provide a good balance between denoising and preserving important gait features such as joint peaks and reversals. This span was tuned empirically for each joint signal. The LOESS filter was applied independently to each joint angle across the dataset. This preprocessing step significantly reduced artifacts and jitter, enabling consistent gait cycle segmentation and supporting accurate downstream motion modeling [4,24].

2.3. Trajectory Alignment and Modeling

Human gait is inherently variable due to natural differences in timing, stride length, and joint motion. To build reliable models for gait reconstruction, this variability must be normalized. We addressed this using a two-step method: (1) Dynamic Time Warping (DTW) for temporal alignment; (2) Gaussian Mixture Modeling and Regression (GMM-GMR) for probabilistic trajectory modeling.
1. Dynamic Time Warping (DTW)
DTW is a dynamic programming technique that aligns two time-series signals with different lengths or timing. It finds the optimal non-linear mapping between two sequences by minimizing the cumulative distance between them. This is crucial for comparing gait cycles that may differ slightly in duration or phase.
Given two sequences X = { x 1 , , x N } and Y = { y 1 , , y M } , the alignment cost is defined recursively as follows:
D ( i , j ) = x i y j 2 + min D ( i 1 , j ) , D ( i , j 1 ) , D ( i 1 , j 1 )
The resulting cost matrix D holds the optimal alignment path from the final point D ( N , M ) back to the start D ( 1 , 1 ) . Above all, the DTW Algorithm for gait alignment is shown in Table 1.
This algorithm was applied pairwise to each joint trajectory across multiple gait cycles. After DTW alignment, all cycles were normalized in time and prepared for statistical modeling. For instance, let X = [ 1 , 3 , 4 ] and Y = [ 1 , 2 , 4 ] . The local cost at position D ( 2 , 2 ) compares x 2 = 3 and y 2 = 2 , giving 3 2 2 = 1 . If the minimum of the three neighboring values is, say, D ( 1 , 1 ) = 0 , then D ( 2 , 2 ) = 1 + 0 = 1 . This process continues until the final cost at D ( 3 , 3 ) accumulates the minimum alignment cost between sequences, which in this case is 1.
2. Trajectory Modeling with GMM-GMR
After alignment, we applied Gaussian Mixture Models (GMM) to statistically model the time-aligned joint trajectories. Each data point is represented as ξ n = [ t n , θ n ] , where t n is the normalized time and θ n is the corresponding joint angle.
GMM expresses the joint distribution as a sum of Gaussian components:
p ( ξ ) = k = 1 K π k N ( ξ μ k , Σ k )
To reconstruct the expected angle at time t, Gaussian Mixture Regression (GMR) is used:
θ ^ ( t ) = k = 1 K h k ( t ) μ k θ + Σ k θ t ( Σ k t t ) 1 ( t μ k t )
where
  • h k ( t ) is the activation weight of the k-th Gaussian at time t,
  • μ k t , μ k θ are mean time and angle for component k,
  • Σ k t t and Σ k θ t are time and cross-covariance matrices.
This enables smooth and probabilistic reconstruction of the joint angle trajectory, capturing both mean behavior and variability across cycles.
The DTW + GMM-GMR pipeline allowed us to align and model hip and knee trajectories for walking, running, and stair climbing. These models were used to reconstruct full bilateral motion from unilateral input, and to generate reference trajectories for exoskeleton control. The use of DTW ensured time consistency across samples, while GMM-GMR provided a robust statistical basis for smooth trajectory generation, even from sparse sensor input.

2.4. Contralateral Trajectory Reconstruction

To reduce sensing complexity and enable lightweight deployment, the right-leg joint trajectories were reconstructed from left-leg motion using symmetry-based transformations. This leverages the approximate bilateral symmetry of human gait in the sagittal plane, particularly during steady walking and running [1,4,13,24]. By relying on sparse IMU input from only one side of the body, the system can generate full bilateral motion profiles suitable for exoskeleton control.
The reconstruction process integrates three main stages: time normalization using Dynamic Time Warping (DTW), probabilistic modeling using Gaussian Mixture Models with Regression (GMM-GMR), and contralateral estimation using both ideal and adaptive symmetry transformations. Each stage builds upon the previous to provide continuous, biologically plausible trajectories from unilateral IMU data.
Ideal Symmetry Transformation. As a baseline, the right joint angle is estimated by time-shifting and sign-inverting the left-leg signal:
θ right ( t ) = θ left ( t + ϕ )
where ϕ represents the phase delay between limbs, typically half the gait cycle ( ϕ = T / 2 ) for symmetric locomotion. This assumes idealized, mirrored motion between the left and right sides [1,11,12].
Adaptive Symmetry Refinement. To address real-world gait asymmetries caused by user variability, transitions between activities, or uneven ground, we introduce a tunable model:
θ right ( t ) = α · θ left ( t + ϕ ) + δ
Here, α adjusts for amplitude differences, ϕ allows phase misalignment, and δ corrects constant offsets. These parameters were optimized using recorded bilateral gait data by minimizing the squared prediction error:
L ( α , ϕ , δ ) = t = 1 N θ right , true ( t ) + α · θ left ( t + ϕ ) δ 2
This optimization was solved using a constrained nonlinear solver with physiologically valid bounds. The learned model produced significantly more accurate right-leg reconstructions across different motion types. For example, stair climbing exhibited reduced gain values ( α < 1 ), while running produced consistent phase shifts ( ϕ T / 2 ) and negligible offset ( δ 0 ).
This method combines time-aligned modeling and adaptive symmetry to reconstruct bilateral trajectories from unilateral IMU signals alone—without requiring dense sensing or complex hardware. The procedures are shown in Figure 2. While effective across tasks, the adaptive parameters were tuned offline and may vary by user. Future work may incorporate online learning [25,26] or subject-specific calibration for improved generalization.

2.5. Exoskeleton Modeling and Control

Accurate control of wearable robotic systems requires both a faithful dynamic model of the system and an effective control strategy that can accommodate the complexities of human–robot interaction. In this section, we describe the complete modeling of a 4-degree-of-freedom (DOF) sagittal-plane lower-limb exoskeleton [27] and the layered control architecture built upon it, which progresses from classical PID control to virtual compensation strategies and finally to adaptive fuzzy control [28].

Dynamic Modeling of the 4-DOF Exoskeleton

The modeled system consists of two legs, each with actuated hip and knee joints, yielding a total of four degrees of freedom: θ = [ θ L H , θ L K , θ R H , θ R K ] T . The system dynamics are expressed using the Euler–Lagrange formulation:
τ = M ( θ ) θ ¨ + C ( θ , θ ˙ ) θ ˙ + G ( θ ) + τ spring
where
-
M ( θ ) is the configuration-dependent mass-inertia matrix,
-
C ( θ , θ ˙ ) captures Coriolis and centrifugal forces,
-
G ( θ ) models gravity-induced joint torques,
-
τ spring represents the passive joint stiffness.
This structure enables simulation of realistic physical conditions, including compliance, gravitational loading, and inter-joint coupling effects [19,20,21].

2.6. Control Framework

Joint-level trajectory tracking was implemented using IMU-reconstructed reference angles for hip and knee joints, as shown in Figure 3. To assess control performance under dynamic conditions, we evaluated three strategies: classical PID control, virtual compensation for biomechanical dynamics, and adaptive fuzzy PID control.

2.6.1. PID-Based Joint Control

As a baseline, a conventional PID controller was implemented for each joint:
τ i ( t ) = K p , i e i ( t ) + K i , i e i ( t ) d t + K d , i d e i ( t ) d t
where e i ( t ) = θ i , ref ( t ) θ i ( t ) is the position error between the reconstructed reference trajectory and the measured joint angle.
Initial gains were selected using the Ziegler–Nichols method [19], where the proportional gain is tuned to induce sustained oscillation, and the ultimate gain K u and oscillation period T u are used to derive:
K p = 0.6 K u , K i = 2 K p T u , K d = K p T u 8
These gains were refined manually to stabilize tracking performance during gait transitions.
While PID control performs well in linear settings, its effectiveness degrades when faced with nonlinear joint dynamics introduced by virtual spring compliance and gravitational torques, both of which depend on joint position and gait phase [20,21].

2.6.2. Virtual Spring and Gravity Compensation

To improve control under realistic joint dynamics, passive torque terms were added to model elasticity and gravitational effects. The spring-like restoring torque is computed as follows:
τ spring , i = k i ( θ i θ i , ref )
where k i is the joint stiffness constant. Gravitational torque is calculated as follows:
τ gravity , i = m i g l i sin ( θ i )
with m i , l i , and g representing segment mass, length to center of mass, and gravity respectively.
The total commanded torque, as shown in Table 2, becomes:
τ i ( t ) = τ PID , i + τ spring , i + τ gravity , i
This compensation improves control fidelity, particularly during stance initiation and swing recovery phases.

2.6.3. Adaptive Fuzzy PID Controller

To overcome the limitations of fixed-gain PID control, an adaptive fuzzy PID structure [29] was implemented, based on the comparison of different controllers shown in Table 3. The fuzzy controller adjusts PID gains online using tracking error e ( t ) and error rate e ˙ ( t ) as input to a rule-based inference engine.
Fuzzy rules are of the form:
IF  e ( t ) is Large AND e ˙ ( t ) is Positive, THEN Decrease K p , Increase K d
Gain adjustments follow:
K p new = K p + Δ K p ( e , e ˙ ) K i new = K i + Δ K i ( e , e ˙ ) K d new = K d + Δ K d ( e , e ˙ )
Triangular membership functions were defined for both inputs and outputs, as shown in Figure 4, with a 7 × 7 rule matrix designed to preserve stability. The system was executed in Simulink with a 1 ms sampling rate. This architecture improved adaptability under dynamic gait transitions and unsteady loading [7,8,9].
The fuzzy rule base was designed heuristically for average gait behavior. However, inter-subject variability or atypical motion may require retuning. Future work may incorporate learning based or self-tuning fuzzy logic systems for better generalization to diverse users or environmental contexts.

2.6.4. Validation Metrics and Evaluation Formulation

To comprehensively evaluate the performance of the proposed control strategies across the four exoskeleton joints (bilateral hip and knee), several quantitative metrics are adopted. These metrics assess tracking accuracy, smoothness of motion, and energy efficiency—critical aspects for ensuring safety and usability in wearable assistive systems [7,8,20,21].
(1)
Root Mean Square (RMS) Tracking Error.
The RMS error provides a global measure of trajectory fidelity over a gait cycle. It reflects how closely the actual joint motion follows the reference trajectory:
RMS = 1 N i = 1 N θ ref , i θ act , i 2
where θ ref , i and θ act , i are the reference and actual joint angles at the i th time sample, and N is the total number of samples per cycle.
(2)
Maximum Error.
This metric captures the worst-case deviation and is critical for identifying potential instability or delay in response:
e max = max t θ ref ( t ) θ act ( t )
The maximum error defined is particularly useful in detecting overshoot or lag during rapid gait transitions [11,21].
(3)
Control Effort.
To assess actuator workload and energy usage, we compute the control effort as the time-integrated product of joint torque and angular velocity:
E = 0 T τ ( t ) · θ ˙ ( t ) d t
The control effort defined indicates system efficiency and is critical in battery-powered exoskeletons where energy optimization is essential [7,8].
(4)
Jerk Index.
Jerk, the third derivative of position with respect to time, measures motion smoothness. High jerk can cause user discomfort or biomechanical incompatibility. The jerk index is defined as follows:
J = 0 T d 3 θ ( t ) d t 3 2 d t
Lower values imply smoother joint motion, enhancing comfort and reducing mechanical stress [7,20].
These evaluation metrics were applied consistently to all four sagittal joints (left/right hip and knee) during simulation experiments. Performance was compared across the PID and fuzzy PID controllers, under both ideal and nonlinear conditions (e.g., elastic elements, gravity disturbances), providing a robust analysis of controller adaptability and system responsiveness.

2.7. Trajectory Reconstruction Results

The proposed reconstruction pipeline was evaluated across the locomotion modes in normal walking. For each mode, the pipeline followed two main steps: (1) Gait cycles were temporally aligned using Dynamic Time Warping (DTW); (2) Gaussian Mixture Modeling with Regression (GMM-GMR) was applied to learn a smoothed motion profile. Right-leg trajectories were then estimated using both ideal and adaptive symmetry models [7,11,12,15,17,23].
Figure 5 shows noticeable variability in raw gait cycles due to inconsistent step timing. DTW effectively normalizes this timing, revealing consistent stride structure across repetitions, essential for modeling. Similar improvements are seen in Figure 6. Temporal misalignments in raw hip signals are smoothed post-alignment, enabling accurate downstream modeling.
As seen in Figure 7, the adaptive symmetry model closely tracks the GMM-inferred motion, outperforming the ideal symmetry model, which introduces phase and amplitude offsets in the right knee prediction. The adaptive model again provides superior results (Figure 8), reducing overshoot and misalignment, demonstrating its effectiveness for estimating contralateral hip dynamics during walking.
Summary:
  • DTW normalization is essential for consistent GMM modeling.
  • Adaptive symmetry modeling significantly improves contralateral motion estimation.
  • The method generalizes well from cyclic motions (walking, running) to asymmetric tasks (stair climbing).
Dynamic Time Warping (DTW) was chosen for its ability to temporally align gait cycles with non-uniform timing, a key challenge in human locomotion data. Unlike linear interpolation or time-normalized averaging—which assume consistent stride durations—DTW allows flexible non-linear alignment of key gait events (e.g., heel-strike, toe-off) without distorting kinematic patterns. Other alternatives, such as Principal Component Analysis (PCA)-based time normalization or Uniform Temporal Scaling, offer computational speed but lose cycle-specific variation critical for personalized modeling. DTW preserves temporal dynamics while maintaining feature correspondence across cycles, making it more suitable for accurate Gaussian Mixture Modeling in variable gait data.

2.8. PID Control Performance

The reconstructed joint trajectories—generated through DTW alignment, GMM-GMR modeling, and adaptive symmetry transformation—were used as reference inputs for joint-level control using a classical Proportional–Integral–Derivative (PID) controller. The system was evaluated under ideal linear conditions, with no additional spring compliance or gravitational loads, simulating a best-case actuation scenario.
Figure 9 presents representative tracking results for the left and right hip and knee joints. Reference trajectories are shown as dashed lines, while solid lines indicate actual joint responses. The performance of the tracking was evaluated for three types of motions: walking, running, and climbing stairs. The following observations summarize the controller’s behavior. Accurate tracking with minimal overshoot or delay. The controller handled the periodic, low-speed motion with smooth transitions and negligible steady-state error.
Overall, the results show that classical PID control performs adequately when applied to an exoskeleton model governed by approximately linear dynamics. Under these conditions, the static gain structure of PID is sufficient to achieve stable tracking with low steady-state error [8,9,19]. Its simplicity, fast response, and ease of implementation have made it a longstanding baseline in robotic control [7,13,20]. However, this performance assumes ideal actuation and neglects realistic factors such as joint elasticity, load disturbances, and unmodeled dynamics [3,21,32]. As these nonlinearities are introduced in the following sections, PID’s limitations become increasingly evident, motivating the transition to more adaptive control strategies.

2.9. Effect of Spring and Gravity Compensation on PID Performance

To simulate more realistic actuation dynamics, virtual joint stiffness and gravity effects were introduced into the exoskeleton model. Joint compliance was modeled using linear torsional springs, and segment-wise gravitational torque was incorporated based on limb orientation and mass [3,21]. The original PID controller, tuned under idealized dynamics, was retained without modification to assess its robustness under these altered conditions.
Figure 10 illustrates the impact of these added nonlinearities on joint tracking for a walking cycle. While reference trajectories remain unchanged, the simulated joint responses deviate significantly, especially in the knee joints. Amplitude attenuation, high-frequency oscillations, and phase lag are apparent, indicating deteriorated tracking performance.
The following observations highlight specific failure modes during walking:
  • Left and Right Hip: Spring-induced oscillations degrade early-cycle stability. Phase lag appears post toe-off, with the system underreacting to flexion demands during swing.
  • Left Knee: High overshoot and instability are observed, likely due to resonance between the spring dynamics and PID gains. The controller fails to suppress abrupt transitions near peak flexion.
  • Right Knee: Motion becomes highly discontinuous, indicating loss of closed-loop stability. Gravity-induced drift and compliance mismatch lead to poor synchronization with the contralateral leg.
These results emphasize that classical PID controllers, while simple and effective under linear assumptions, are inadequate for managing the time-varying dynamics introduced by compliance and gravitational forces. Their static gain structure cannot compensate for joint-dependent variability or disturbance-induced coupling [9,19,21]. In wearable robotic systems where elastic actuators and uneven load conditions are common, more adaptive strategies such as fuzzy-PID control are required to ensure stable and reliable motion tracking [7,20,23,32].

2.10. Adaptive Fuzzy PID Controller

To overcome the limitations of classical PID under nonlinear joint dynamics, an adaptive fuzzy PID controller was developed. This controller extends a standard PID structure by integrating a Mamdani-type fuzzy inference system (FIS), enabling dynamic tuning of K p , K i , and K d gains based on real-time tracking behavior [7,20,23,32,33].
As shown in Figure 11, the FIS receives two inputs: the tracking error e ( t ) and its derivative e ˙ ( t ) , both normalized to the range [ 3 , 3 ] . Each input is described by three triangular membership functions (MFs): Negative, Zero, and Positive. The FIS outputs three incremental adjustments: Δ K p , Δ K i , and Δ K d , each mapped over the range [ 1 , 1 ] using five triangular MFs (from strong decrease to strong increase).
The rule base contains nine core fuzzy rules designed to reflect intuitive control logic. For example:
  • Rule 1: If Error is Negative and DeltaError is Negative, then Δ K p is Strong Increase, Δ K i is Neutral, and Δ K d is Increase. This boosts responsiveness while maintaining damping.
  • Rule 5: If both Error and DeltaError are Zero, then no gain changes occur—preserving current control behavior in steady state.
  • Rule 9: If Error is Positive and DeltaError is Positive, then Δ K p is Strong Decrease, Δ K i is Slight Decrease, and Δ K d is Increase. This reduces overshoot and improves damping.
The fuzzy system uses a min–max composition, Mamdani inference method, and centroid defuzzification. All gain updates are applied incrementally to baseline PID values, enabling adaptive behavior throughout the gait cycle [23,32].
The fuzzy PID controller was evaluated using walking trials under nonlinear joint conditions (spring compliance and gravity torque). Figure 12 and Figure 13 illustrate tracking results for ideal and non-ideal symmetry assumptions.
Observations (Ideal Symmetry):
  • The controller enables precise tracking across all joints.
  • Spring-induced oscillations are effectively attenuated.
  • The system maintains phase alignment and amplitude fidelity.
Observations (Non-Ideal Symmetry):
  • Slight increases in phase lag are observable, especially at the right knee.
  • The controller compensates well for asymmetries, avoiding large deviations.
  • Joint transitions remain smooth and natural despite variability.
Overall, this adaptive control strategy improves stability and tracking fidelity in the presence of real-world nonlinearities. It enables real-time adaptation to changing joint dynamics, which is particularly advantageous for wearable robotic systems [7,20,23,32,33].
While classical PID controllers are simple and widely used, they lack adaptability under time-varying dynamics. Alternative approaches such as Gain Scheduling, Model Predictive Control (MPC), and Adaptive Neural Controllers have been explored for exoskeletons. Gain scheduling requires predefined operating points and extensive tuning; MPC offers optimal control but is computationally intensive and less practical for embedded real-time systems. Neural controllers can adapt to nonlinearities but require large datasets and may lack interpretability. Fuzzy PID, by contrast, combines rule-based adaptability with low computational overhead, enabling real-time tuning of gains based on error dynamics. Its interpretability, fast response, and robustness make it a superior choice for wearable robotics where safety and transparency are essential [7,20,23,32].

2.11. Validation and Quantitative Evaluation

To rigorously assess the performance of the proposed control framework, walking experiments were conducted comparing a classical PID controller and the proposed adaptive fuzzy PID controller. The root mean square (RMS) error between actual and reference joint trajectories was used to quantify tracking performance across the left and right hip and knee joints. For comparison, the PID controller was evaluated both in an ideal (simulation-based) scenario and under real-world limitations [7,20,32].
Observations: Table 4 highlights the joint-level tracking accuracy across controllers. In simulation (ideal conditions), the PID controller achieves low RMS errors. However, when deployed under real-world limitations, its performance degrades significantly. For instance, the right knee error rises from 0.042 to 0.742 rad—a more than 17-fold increase.
In contrast, the adaptive fuzzy PID controller maintains consistently low errors in all joints, even under uncertainty. Relative to the PID under limitations, the RMS error was reduced:
  • Left hip: 90.6% (from 0.149 to 0.014 rad)
  • Right hip: 88.4% (from 0.112 to 0.013 rad)
  • Left knee: 80.6% (from 0.727 to 0.141 rad)
  • Right knee: 91.9% (from 0.742 to 0.060 rad)
These results show that while PID may perform adequately in linear, controlled conditions, it lacks the robustness needed to handle variability. The adaptive fuzzy PID, by contrast, responds to joint-specific deviations in real time, offering reliable and accurate performance across all lower-limb joints [7,32].
Table 5 compares the overall control effort and motion smoothness for both controllers. The adaptive fuzzy PID reduced the control effort by 38.8%, indicating less torque demand to achieve accurate tracking. This reduction directly contributes to energy efficiency, reduced actuator strain, and longer operational endurance—all critical in wearable robotic systems.
Additionally, the jerk index was reduced by 41.2%, indicating that the adaptive fuzzy controller produces smoother joint trajectories with fewer abrupt changes in acceleration. This smoother motion not only improves user comfort but also reflects better dynamic stability of the controlled limb. These improvements are also supported by the integration of a virtual spring component in the control architecture. This spring introduces passive compliance that emulates biological elasticity, allowing the system to absorb minor deviations and offload some of the control burden from the actuators. The result is more natural, energy-efficient motion with improved stability [23,33].

3. Discussion

This study presented a simulation-based framework that integrates sparse sensing and symmetry modeling for adaptive gait trajectory reconstruction and exoskeleton control. While the proposed approach demonstrated promising results in terms of tracking fidelity, robustness, and control efficiency, several ongoing developments aim to further bridge the gap between simulation and real-world deployment. A key direction is the hardware implementation and real-world validation of the proposed methods. A physical lower-limb exoskeleton system has already been constructed, integrating the same sparse IMU, flex, and pressure sensor setup described in this paper. Initial bench testing has been completed, and work is currently underway to deploy the adaptive fuzzy PID controller and energy-tank-based impedance modulation strategies on the embedded platform. These efforts will culminate in human-in-the-loop experiments that evaluate control responsiveness, trajectory accuracy, and safety under walking, stair climbing, and running conditions.
Another extension involves enhancing the sensor fusion architecture to improve estimation of the center of pressure (COP) and center of gravity (COG). Specifically, pressure and flex sensors will be leveraged to extract foot-ground contact and arch curvature information, providing richer feedback for real-time stability monitoring and energy-aware control, particularly during locomotion transitions and when traversing uneven terrain. Moreover, the current fuzzy controller operates with a predefined rule base, which, while effective, may lack adaptability for highly personalized gait dynamics. To address this limitation, future versions may adopt online learning techniques such as neuro-fuzzy adaptation or reinforcement learning [32,34]. These techniques would enable subject-specific tuning based on historical gait data and dynamic sensor patterns, thereby enhancing personalization and long-term performance.
To further improve motion planning, model predictive control (MPC) is under consideration as a complementary strategy. MPC can offer anticipatory control capabilities, particularly beneficial in scenarios involving multi-step planning or rapidly changing environments [30]. Its predictive nature could complement the adaptive fuzzy controller by providing higher-level trajectory modulation.
Finally, while the current system is limited to sagittal-plane motion, an important direction is the expansion toward 3D gait modeling and lateral control. This would involve the integration of lateral joint dynamics and quaternion-based orientation estimation for full-body motion reconstruction [35]. Such an extension would greatly enhance the system’s applicability to real-world ambulatory scenarios, including complex maneuvers such as turning, side-stepping, or adapting to inclined surfaces. In summary, while the current work establishes a strong foundation for adaptive gait tracking and control using minimal sensors, ongoing and future developments are expected to significantly advance its practical utility in wearable robotic systems.

4. Conclusions

This paper presented an integrated framework that combines gait trajectory reconstruction using unilateral IMU data with adaptive fuzzy PID control for lower-limb exoskeletons. Through a structured pipeline involving signal filtering, dynamic time warping, statistical modeling, and symmetry-based extrapolation, we reconstructed full-joint trajectories for walking, running, and stair climbing using data from a single leg. We evaluated classical PID control and found that it performs well under linear, idealized conditions. However, its effectiveness diminishes when nonlinearities such as joint stiffness and gravitational loading are introduced. To address these challenges, we incorporated a virtual spring–damper model and implemented an adaptive fuzzy PID controller capable of adjusting gains in real time based on error dynamics.
The results demonstrated that the adaptive fuzzy control strategy significantly improves tracking accuracy, motion smoothness, and energy efficiency under more realistic joint dynamics. The overall control architecture remains lightweight, modular, and scalable, making it well-suited for deployment in wearable robotic systems aimed at rehabilitation or mobility support. This work lays a foundation for future extensions involving predictive control, online adaptation, and real-world implementation in diverse locomotion environments.

Author Contributions

Conceptualization, H.S. and S.A.; Methodology, L.B. and A.I.; Validation, L.B. and H.L.; Formal analysis, L.B. and H.L.; Investigation, L.B. and A.I.; Data curation, A.I.; Writing—original draft, L.B., A.I. and H.L.; Writing—review and editing, W.Q. and H.S.; Supervision, W.Q., H.S. and S.A. All authors have read and agreed to the published version of the manuscript.

Funding

This research received no external funding.

Data Availability Statement

The raw data supporting the conclusions of this article will be made available by the authors on request.

Conflicts of Interest

The authors declare no conflicts of interest.

References

  1. Chacon-Murguia, M.I.; Sandoval-Rodriguez, R.; Arias-Enriquez, O. Human gait feature extraction including a kinematic analysis toward robotic power assistance. Int. J. Adv. Robot. Syst. 2012, 9, 68. [Google Scholar] [CrossRef]
  2. Viteckova, S.; Kutilek, P.; Jirina, M. Wearable lower limb robotics: A review. Biocybern. Biomed. Eng. 2013, 33, 96–105. [Google Scholar] [CrossRef]
  3. Tejima, N. Rehabilitation robotics: A review. Adv. Robot. 2001, 14, 551–564. [Google Scholar] [CrossRef]
  4. Hu, B.; Rouse, E.; Hargrove, L. Benchmark datasets for bilateral lower-limb neuromechanical signals from wearable sensors during unassisted locomotion in able-bodied individuals. Front. Robot. AI 2018, 5, 14. [Google Scholar] [CrossRef]
  5. Jleilaty, S.; Ammounah, A.; Abdulmalek, G.; Nouveliere, L.; Su, H.; Alfayad, S. Distributed real-time control architecture for electrohydraulic humanoid robots. Robot. Intell. Autom. 2024, 44, 607–620. [Google Scholar] [CrossRef]
  6. Sharma, R.; Gaur, P.; Bhatt, S.; Joshi, D. Optimal fuzzy logic-based control strategy for lower limb rehabilitation exoskeleton. Appl. Soft Comput. 2021, 105, 107226. [Google Scholar] [CrossRef]
  7. Zhong, B.; Cao, J.; Guo, K.; McDaid, A.; Peng, Y.; Miao, Q.; Xie, S.; Zhang, M. Fuzzy logic compliance adaptation for an assist-as-needed controller on the Gait Rehabilitation Exoskeleton (GAREX). Robot. Auton. Syst. 2020, 133, 103642. [Google Scholar] [CrossRef]
  8. Toan, N.V.; Khoi, P.B. Fuzzy-based-admittance controller for safe natural human–robot interaction. Adv. Robot. 2019, 33, 815–823. [Google Scholar] [CrossRef]
  9. Zawawi, M.Z.F.B.M.; Elamvazuthi, I.; Aziz, A.B.A.; Daud, S.A. Comparison of PID and fuzzy logic controller for DC servo motor in the development of lower extremity exoskeleton for rehabilitation. In Proceedings of the 2017 IEEE 3rd International Symposium in Robotics and Manufacturing Automation (ROMA), Kuala Lumpur, Malaysia, 19–21 September 2017; pp. 1–6. [Google Scholar]
  10. Xu, Y.; Su, H.; Ma, G.; Liu, X. A novel dual-modal emotion recognition algorithm with fusing hybrid features of audio signal and speech context. Complex Intell. Syst. 2023, 9, 951–963. [Google Scholar] [CrossRef]
  11. Gaspar, M.; Welke, B.; Seehaus, F.; Hurschler, C.; Schwarze, M. Dynamic Time Warping compared to established methods for validation of musculoskeletal models. J. Biomech. 2017, 55, 156–161. [Google Scholar] [CrossRef]
  12. Avola, D.; Cinque, L.; De Marsico, M.; Fagioli, A.; Foresti, G.L.; Mancini, M.; Mecca, A. Signal enhancement and efficient DTW-based comparison for wearable gait recognition. Comput. Secur. 2024, 137, 103643. [Google Scholar] [CrossRef]
  13. Huang, L.; Zheng, J.; Hu, H. A gait phase detection method in complex environment based on DTW-mean templates. IEEE Sens. J. 2021, 21, 15114–15123. [Google Scholar] [CrossRef]
  14. Wang, X.; Kyrarini, M.; Ristić-Durrant, D.; Spranger, M.; Gräser, A. Monitoring of gait performance using dynamic time warping on IMU-sensor data. In Proceedings of the 2016 IEEE International Symposium on Medical Measurements and Applications (MeMeA), Benevento, Italy, 15–18 May 2016; pp. 1–6. [Google Scholar]
  15. Ti, B.; Gao, Y.; Li, Q.; Zhao, J. Dynamic movement primitives for movement generation using GMM-GMR analytical method. In Proceedings of the IEEE 2nd International Conference on Information and Computer Technologies (ICICT), Kahului, HI, USA, 14–17 March 2019. [Google Scholar]
  16. Wiest, J.; Höffken, M.; Kreßel, U.; Dietmayer, K. Probabilistic trajectory prediction with Gaussian mixture models. In Proceedings of the 2012 IEEE Intelligent Vehicles Symposium, Madrid, Spain, 3–7 June 2012; pp. 141–146. [Google Scholar]
  17. Maeda, G.J.; Neumann, G.; Ewerton, M.; Lioutikov, R.; Kroemer, O.; Peters, J. Probabilistic movement primitives for coordination of multiple human–robot collaborative tasks. Auton. Robot. 2017, 41, 593–612. [Google Scholar] [CrossRef]
  18. Li, Q.; Cicirelli, F.; Vinci, A.; Guerrieri, A.; Qi, W.; Fortino, G. Quadruped Robots: Bridging Mechanical Design, Control, and Applications. Robotics 2025, 14, 57. [Google Scholar] [CrossRef]
  19. Andersson, R.; Cronhjort, M.; Chilo, J. Wireless PID-Based Control for a Single-Legged Rehabilitation Exoskeleton. Machines 2024, 12, 745. [Google Scholar] [CrossRef]
  20. Belkadi, A.; Oulhadj, H.; Touati, Y.; Khan, S.A.; Daachi, B. On the robust PID adaptive controller for exoskeletons: A particle swarm optimization based approach. Appl. Soft Comput. 2017, 60, 87–100. [Google Scholar] [CrossRef]
  21. Yamazaki, T.; Sakaino, S.; Tsuji, T. Estimation and kinetic modeling of human arm using wearable robot arm. Electr. Eng. Jpn. 2017, 199, 57–67. [Google Scholar] [CrossRef]
  22. Su, H.; Ovur, S.E.; Xu, Z.; Alfayad, S. Exploring the potential of fuzzy sets in cyborg enhancement: A comprehensive review. IEEE Trans. Fuzzy Syst. 2024, 33, 810–827. [Google Scholar] [CrossRef]
  23. Ferdaus, M.M.; Pratama, M.; Anavatti, S.G.; Garratt, M.A.; Pan, Y. Generic evolving self-organizing neuro-fuzzy control of bio-inspired unmanned aerial vehicles. IEEE Trans. Fuzzy Syst. 2019, 28, 1542–1556. [Google Scholar] [CrossRef]
  24. Fusca, M.; Negrini, F.; Perego, P.; Magoni, L.; Molteni, F.; Andreoni, G. Validation of a wearable IMU system for gait analysis: Protocol and application to a new system. Appl. Sci. 2018, 8, 1167. [Google Scholar] [CrossRef]
  25. Chen, J.; Wu, Y.; Qiao, H. Memory, attention, and muscle synergies based reinforcement and transfer learning for musculoskeletal robots under imperfect observation. IEEE/ASME Trans. Mechatron. 2024, 30, 1853–1864. [Google Scholar] [CrossRef]
  26. Chen, J.; Wu, Y.; Yao, C.; Huang, X. Robust motion learning for musculoskeletal robots based on a recurrent neural network and muscle synergies. IEEE Trans. Autom. Sci. Eng. 2024, 22, 2405–2420. [Google Scholar] [CrossRef]
  27. Su, H.; Li, Z.; Li, G.; Yang, C. EMG-Based neural network control of an upper-limb power-assist exoskeleton robot. In International Symposium on Neural Networks; Springer: Berlin/Heidelberg, Germany, 2013; pp. 204–211. [Google Scholar]
  28. Amiri, M.S.; Ramli, R. Fuzzy Adaptive Controller of a Wearable Assistive Upper Limb Exoskeleton Using a Disturbance Observer. IEEE Trans. Hum.-Mach. Syst. 2025, 55, 197–206. [Google Scholar] [CrossRef]
  29. Hsu, H.H.; Lee, W.K.; Lee, P.L. Designing an EEG Signal-Driven Dual-Path Fuzzy Neural Network-Controlled Pneumatic Exoskeleton for Upper Limb Rehabilitation. Int. J. Fuzzy Syst. 2025, 1–19. [Google Scholar] [CrossRef]
  30. Incremona, G.P.; Cucuzzella, M.; Magni, L.; Ferrara, A. MPC with sliding mode control for the energy management system of microgrids. Ifac-Papersonline 2017, 50, 7397–7402. [Google Scholar] [CrossRef]
  31. Mondal, A.; Ganguli, S. Controller Design for Industrial Applications; John Wiley & Sons: Hoboken, NJ, USA, 2025. [Google Scholar]
  32. Sun, Z.; Li, F.; Duan, X.; Jin, L.; Lian, Y.; Liu, S.; Liu, K. A novel adaptive iterative learning control approach and human-in-the-loop control pattern for lower limb rehabilitation robot in disturbances environment. Auton. Robot. 2021, 45, 595–610. [Google Scholar] [CrossRef]
  33. Li, Z.; Li, X.; Li, Q.; Su, H.; Kan, Z.; He, W. Human-in-the-loop control of soft exosuits using impedance learning on different terrains. IEEE Trans. Robot. 2022, 38, 2979–2993. [Google Scholar] [CrossRef]
  34. Aly, A.A.; The Vu, M.; El-Sousy, F.F.; Alotaibi, A.; Mousa, G.; Le, D.N.; Mobayen, S. Fuzzy-based fixed-time nonsingular tracker of exoskeleton robots for disabilities using sliding mode state observer. Mathematics 2022, 10, 3147. [Google Scholar] [CrossRef]
  35. Kim, H.; Lee, D.H. Stable whole-body control of exoskeletons using 3D motion reconstruction. Robot. Auton. Syst. 2019, 119, 21–33. [Google Scholar]
Figure 1. System architecture integrating wearable sensing, signal preprocessing, and exoskeleton control. The pipeline consists of acquisition from body- and foot-mounted sensors, followed by time-aligned trajectory modeling and joint-level control.
Figure 1. System architecture integrating wearable sensing, signal preprocessing, and exoskeleton control. The pipeline consists of acquisition from body- and foot-mounted sensors, followed by time-aligned trajectory modeling and joint-level control.
Symmetry 17 01265 g001
Figure 2. Overview of the trajectory reconstruction pipeline using unilateral IMU input. Raw left-leg signals are filtered and time-aligned using Dynamic Time Warping (DTW), modeled via GMM-GMR, and transformed using symmetry-based estimation to reconstruct right-leg trajectories. The output serves as input for bilateral exoskeleton control.
Figure 2. Overview of the trajectory reconstruction pipeline using unilateral IMU input. Raw left-leg signals are filtered and time-aligned using Dynamic Time Warping (DTW), modeled via GMM-GMR, and transformed using symmetry-based estimation to reconstruct right-leg trajectories. The output serves as input for bilateral exoskeleton control.
Symmetry 17 01265 g002
Figure 3. Block diagram of the classical PID control.
Figure 3. Block diagram of the classical PID control.
Symmetry 17 01265 g003
Figure 4. Structure of the adaptive fuzzy PID controller with real-time gain tuning.
Figure 4. Structure of the adaptive fuzzy PID controller with real-time gain tuning.
Symmetry 17 01265 g004
Figure 5. Knee joint: Raw left-knee trajectories (left) and DTW-aligned signals (right) showing temporal normalization across trials.
Figure 5. Knee joint: Raw left-knee trajectories (left) and DTW-aligned signals (right) showing temporal normalization across trials.
Symmetry 17 01265 g005
Figure 6. Hip joint: Raw left-hip joint angles (left) and aligned trajectories (right) after DTW.
Figure 6. Hip joint: Raw left-hip joint angles (left) and aligned trajectories (right) after DTW.
Symmetry 17 01265 g006
Figure 7. Knee joint: GMM-GMR output (green), right-knee prediction via ideal (orange dashed) and adaptive symmetry (red solid).
Figure 7. Knee joint: GMM-GMR output (green), right-knee prediction via ideal (orange dashed) and adaptive symmetry (red solid).
Symmetry 17 01265 g007
Figure 8. Hip joint: Right-hip motion estimated using both symmetry models.
Figure 8. Hip joint: Right-hip motion estimated using both symmetry models.
Symmetry 17 01265 g008
Figure 9. Joint angle tracking performance using classical PID controller under linear system dynamics. Reference trajectories (dashed), joint responses (solid).
Figure 9. Joint angle tracking performance using classical PID controller under linear system dynamics. Reference trajectories (dashed), joint responses (solid).
Symmetry 17 01265 g009
Figure 10. PID tracking performance under spring and gravity dynamics for walking. Desired trajectories (blue); simulated joint responses (red).
Figure 10. PID tracking performance under spring and gravity dynamics for walking. Desired trajectories (blue); simulated joint responses (red).
Symmetry 17 01265 g010
Figure 11. Fuzzy PID architecture. Error and error rate inputs are mapped to triangular MFs and processed through a Mamdani inference engine to tune Δ K p , Δ K i , and Δ K d in real time.
Figure 11. Fuzzy PID architecture. Error and error rate inputs are mapped to triangular MFs and processed through a Mamdani inference engine to tune Δ K p , Δ K i , and Δ K d in real time.
Symmetry 17 01265 g011
Figure 12. Tracking performance using fuzzy PID under nonlinear dynamics with ideal symmetry. All joints follow reference trajectories closely with minimal steady-state error and smooth transitions.
Figure 12. Tracking performance using fuzzy PID under nonlinear dynamics with ideal symmetry. All joints follow reference trajectories closely with minimal steady-state error and smooth transitions.
Symmetry 17 01265 g012
Figure 13. Tracking performance using fuzzy PID under nonlinear dynamics with non-ideal symmetry. The controller maintains stable and smooth output despite asymmetry in reference trajectories.
Figure 13. Tracking performance using fuzzy PID under nonlinear dynamics with non-ideal symmetry. The controller maintains stable and smooth output despite asymmetry in reference trajectories.
Symmetry 17 01265 g013
Table 1. Pseudocode for DTW-based trajectory alignment.
Table 1. Pseudocode for DTW-based trajectory alignment.
Inputs:
  •    X = { x 1 , , x N } : Reference trajectory
  •    Y = { y 1 , , y M } : Target trajectory to be aligned
Output: Aligned trajectory Y , optimal warping path P *
Procedure:
  •   Compute local cost: C ( i , j ) = x i y j 2
  •   Initialize cumulative matrix:
    D ( 1 , 1 ) = C ( 1 , 1 )
    D ( i , 1 ) = D ( i 1 , 1 ) + C ( i , 1 ) , D ( 1 , j ) = D ( 1 , j 1 ) + C ( 1 , j )
  •   For all i = 2 to N, and j = 2 to M:
    D ( i , j ) = C ( i , j ) + min D ( i 1 , j ) , D ( i , j 1 ) , D ( i 1 , j 1 )
  •   Backtrack from D ( N , M ) to D ( 1 , 1 ) to extract optimal warping path P *
  •   Warp Y along P * to obtain aligned Y
Return: Warped trajectory Y , path P *
Table 2. Torque computation using PID control with virtual spring and gravity compensation.
Table 2. Torque computation using PID control with virtual spring and gravity compensation.
Procedure: Virtual Torque Computation
  •   Input:  θ i , θ ˙ i , θ i , ref , k i , m i , l i , g
  •   1. Compute error: e i = θ i , ref θ i
  •   2. Compute PID torque: τ PID , i
  •   3. Compute spring torque: τ spring , i = k i · e i
  •   4. Compute gravity torque: τ gravity , i = m i g l i sin ( θ i )
  •   5. Total output: τ i = τ PID , i + τ spring , i + τ gravity , i
Table 3. Qualitative comparison of adaptive controllers for wearable robotics.
Table 3. Qualitative comparison of adaptive controllers for wearable robotics.
MethodAdvantagesLimitations
Fuzzy PIDReal-time tuning, interpretable, low-cost [7,8]Manual tuning, limited personalization
MPCOptimal control with constraints [30]Requires accurate models, high computational load
SMCRobust to disturbances [31]Chattering, less smooth
RLLearns from data, adapts over time [32]Needs large datasets, low interpretability
Table 4. RMS Tracking Errors (in radians) for Each Joint Across Controllers.
Table 4. RMS Tracking Errors (in radians) for Each Joint Across Controllers.
JointPID (Ideal)PID LimitationsAdaptive Fuzzy PID
Left Hip0.0190.1490.014
Right Hip0.0120.1120.013
Left Knee0.1270.7270.141
Right Knee0.0420.7420.060
Table 5. Control Effort and Motion Smoothness Comparison.
Table 5. Control Effort and Motion Smoothness Comparison.
MetricPID ControllerAdaptive Fuzzy PID Controller
Control Effort [ | τ θ ˙ | ]23.714.5
Jerk Index [ θ 2 d t ]91.653.8
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

Bencharif, L.; Ibset, A.; Liu, H.; Qi, W.; Su, H.; Alfayad, S. A Skill-Inspired Adaptive Fuzzy Control Framework for Symmetric Gait Tracking with Sparse Sensor Fusion in Lower-Limb Exoskeletons. Symmetry 2025, 17, 1265. https://doi.org/10.3390/sym17081265

AMA Style

Bencharif L, Ibset A, Liu H, Qi W, Su H, Alfayad S. A Skill-Inspired Adaptive Fuzzy Control Framework for Symmetric Gait Tracking with Sparse Sensor Fusion in Lower-Limb Exoskeletons. Symmetry. 2025; 17(8):1265. https://doi.org/10.3390/sym17081265

Chicago/Turabian Style

Bencharif, Loqmane, Abderahim Ibset, Hanbing Liu, Wen Qi, Hang Su, and Samer Alfayad. 2025. "A Skill-Inspired Adaptive Fuzzy Control Framework for Symmetric Gait Tracking with Sparse Sensor Fusion in Lower-Limb Exoskeletons" Symmetry 17, no. 8: 1265. https://doi.org/10.3390/sym17081265

APA Style

Bencharif, L., Ibset, A., Liu, H., Qi, W., Su, H., & Alfayad, S. (2025). A Skill-Inspired Adaptive Fuzzy Control Framework for Symmetric Gait Tracking with Sparse Sensor Fusion in Lower-Limb Exoskeletons. Symmetry, 17(8), 1265. https://doi.org/10.3390/sym17081265

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