Next Article in Journal
Towards Wearable Respiration Monitoring: 1D-CRNN-Based Breathing Detection in Smart Textiles
Previous Article in Journal
Mapping Manual Laboratory Tasks to Robot Movements in Digital Pathology Workflow
Previous Article in Special Issue
Traversal by Touch: Tactile-Based Robotic Traversal with Artificial Skin in Complex Environments
 
 
Font Type:
Arial Georgia Verdana
Font Size:
Aa Aa Aa
Line Spacing:
Column Width:
Background:
Article

Online Estimation of Manipulator Dynamics for Computed Torque Control of Robotic Systems

1
Mediterranean Institute of Technology, Southern Mediterranean University, Tunis 1053, Tunisia
2
School of Engineering and Engineering Technology, University of Arkansas at Little Rock, Little Rock, AR 72204, USA
*
Author to whom correspondence should be addressed.
Sensors 2025, 25(22), 6831; https://doi.org/10.3390/s25226831 (registering DOI)
Submission received: 20 September 2025 / Revised: 22 October 2025 / Accepted: 4 November 2025 / Published: 8 November 2025
(This article belongs to the Special Issue Intelligent Robots: Control and Sensing)

Highlights

What are the main findings?
  • This study presents a novel framework for the modeling and control of robotic systems based on data gathered from real-time sensors.
  • We developed and tested a scheme to estimate robot dynamics online from the trajectory data gathered during robot movements.
What is the implication of the main finding?
  • The proposed approach sidesteps the need for complete a priori knowledge of system parameters.
  • Using this approach, robots with unmodeled dynamics can successfully operate in unknown environments.

Abstract

Traditional control of robotic systems relies on the availability of an exact model, which assumes complete knowledge of the robot’s parameters and all dynamic effects. However, this idealized scenario rarely holds in practice, as real-world interactions introduce unpredictable environmental influences, friction, and edge effects. This paper presents a novel data-driven approach to modeling and estimating robot dynamics by leveraging data collected during the robot’s movements. The proposed method operates without prior knowledge of the system parameters, thereby addressing the limitations of conventional model-based control strategies in complex and uncertain environments. Our unified data-driven framework integrates classical control theory with modern machine learning techniques, including system identification, physics-informed neural networks (PINNs), and deep learning. We demonstrate its efficacy in the case of a two-link robotic manipulator that achieves superior trajectory tracking and robustness to unmodeled dynamics. The technique is modular and can be extended to manipulators with more joints.

1. Introduction

The control of robotic systems has traditionally relied on accurate and comprehensive mathematical models that describe a robot’s behavior under a wide range of operating conditions. In their seminal work, Slotine and Li [1] laid the foundation for adaptive control, which assumes complete knowledge of system parameters, including mass distribution, frictional forces, actuator dynamics, and other critical characteristics. However, in real-world applications, acquiring such complete and precise models is challenging due to the inherent complexity of robot–environment interactions. Factors such as external disturbances, sensor noise, and unmodeled dynamics (e.g., frictional nonlinearities, structural flexibilities, and edge effects) can significantly degrade the performance of traditional controllers as noted by Siciliano et al. [2].
Computed torque control (CTC), in particular, has emerged as one of the most effective model-based control strategies. Under the assumption of complete and precise modeling, this method demonstrates superior tracking accuracy and disturbance rejection. However, despite their effectiveness under ideal conditions, even minor inaccuracies or unmodeled dynamics can lead to performance degradation in model-based control. This has spurred research into data-driven approaches that aim to overcome these limitations by learning from real-time sensor data. Data-driven methods for CTC have gained traction as powerful alternatives to traditional model-based approaches in complex environments or modeling uncertainties. Unlike classical CTC, which relies on precise knowledge of the dynamic model of a robot (involving inertia, Coriolis, and gravity terms), data-driven techniques leverage machine learning to approximate these dynamics directly from sensor data, allowing robust control even with incomplete or inaccurate models. In particular, Gaussian Process Regression (GPR) [3] and deep neural networks [4] were employed to learn inverse dynamics models that replace or augment analytical formulations in CTC, thus enabling robust control even with incomplete or inaccurate models. Hybrid methods that combine physics-based models with data-driven corrections (e.g., residual learning) have shown improved generalization and safety. Overall, data-driven CTC methods offer increased flexibility, adaptability, and performance in modern robotic systems. Recent work by Kiumarsi et al. [5] and Chen et al. [6] has demonstrated that data-driven control strategies can adapt to changing environments and unmodeled dynamics, offering improved performance when the full model is not available.
Other recent approaches for robot control include deep reinforcement learning-based control strategies [7] and comprehensive surveys of data-driven robotic control methods [8]. Feedforward networks approximate nonlinear mappings from state control to state derivatives, serving as black-box dynamics models for model-based control or planning [9,10]. These approaches require training on a significant amount of data to generalize. Recurrent neural networks (RNN, LSTM, and GRU) capture temporal dependencies and partial observability, useful when dynamics depend on unmeasured states or previous history of control actions [11]. Non-parametric Gaussian processes (GPs) provide efficient probabilistic models that quantify uncertainty, supporting safe exploration and data-efficient learning [12,13]. These studies explore model-based policy search methods that incorporate a probabilistic dynamics model to express uncertainty. However, GP models are computationally expensive and scale poorly with data. Their application in robotics is limited to smooth and non-switching dynamics.
Physics-informed neural networks (PINNs) embed physical laws (expressed by partial differential equations, e.g., Euler–Lagrange equations) into the loss function or the network architecture, intending to improve data efficiency and generalization. PINNs have found significant applications in fluid dynamics, where they enable the accurate simulation of Navier–Stokes equations without requiring traditional mesh-based methods [14]. In biomedical engineering, PINNs assist in estimating parameters in models of blood flow and tissue mechanics, offering non-invasive diagnostic tools [15]. PINNs obviate the need for acquiring extensive experimental data for model training when the governing equations are known [16]. In the field of robotics, PINNs have been used for dynamic model prediction and parameter identification for collaborative robots [17]. In another study, PINN were employed to handle nonconservative effects for dynamic modeling and control of complex robotic systems [18]. By combining PINN with model-based controllers, precise control performance close to theoretical stability bounds was achieved. Recently, PINNs were used to build an efficient surrogate model that, when coupled with a nonlinear model predictive controller, enabled real-time optimization in legged locomotion [19].
Lagrangian and Hamiltonian neural networks enforce energy conservation constraints in physical systems. As a result, the Hamiltonian network trains faster and generalizes better than a regular neural network [11]. At the same time, learning physics models for model-based control requires robust extrapolation from fewer samples. A deep Lagrangian network can learn the equations of motion of a mechanical system efficiently while ensuring physical plausibility, and performs very well in robot tracking control [4]. However, Lagrangian networks only model conservative forces that do not include friction, damping, and contact effects.
This study presents a novel framework for the modeling and control of robotic systems based on data from real-time sensors to account for unmodeled dynamics. We describe how the parameters of the robot manipulator can be estimated online, followed by a CTC controller design based on the constructed model. The proposed approach eschews the need for complete a priori knowledge of system parameters, providing a viable solution for unknown environments where traditional control methods are not adequate.
Although numerous model-based and data-driven approaches have been proposed for robotic control, existing studies still face key limitations. Classical CTC assumes complete or partial knowledge of the robot dynamics, while purely data-driven models often require large offline datasets and lack physical consistency. Hybrid methods combining analytical and learning-based models partially address these issues but remain task-specific or limited in scope. To overcome these challenges, this paper introduces a unified data-driven framework for online estimation and control of robotic manipulators that merges the interpretability of physics-based models with the adaptability of modern learning. Our main contributions are as follows:
  • Online estimation of gravity, Coriolis, frictional, and inertial effects directly from trajectory control data with no prior parameter knowledge.
  • Use of PINNs for model learning to ensure physical consistency and stability.
  • Integration of these estimates into a CTC structure for adaptive and robust tracking.
The rest of the paper is organized as follows. Control methodologies for robot manipulators are discussed in Section 2, followed by online estimation of the robot parameters in Section 3. Section 4 presents the results for the online estimation of the gravity, Coriolis, and inertial matrices, followed by a conclusion in Section 5.

2. Control Methodologies for Robot Manipulators

In this section, we first discuss the dynamic model of the robotic system and describe the CTC design, which will serve as a benchmark for performance. We then discuss how the data-driven control strategy estimates the dynamic parameters to enable real-time control of robotic systems.

2.1. Computed Torque Control (CTC)

CTC is a model-based scheme that leverages an accurate dynamic model of the robot to ensure stability and precision in tracking tasks. Consider the extended robot dynamics model given by
M ( q ) q ¨ + C ( q , q ˙ ) q ˙ + g ( q ) + f ( q , q ˙ ) = τ ,
where:
  • q R n is the vector of joint positions (where n is the number of joints).
  • M ( q ) R n × n is the symmetric positive definite inertia matrix.
  • C ( q , q ˙ ) R n × n represents the Coriolis and centrifugal forces.
  • g ( q ) R n denotes the gravitational forces.
  • f ( q , q ˙ ) R n models frictional forces, which can be expressed as a linear viscous term F v q ˙ (with F v the positive definite viscous friction matrix) or via more complex models.
  • τ R n is the control input.
Feedback linearization uses the exact model to cancel nonlinear terms, transforming the closed-loop into a linear system controlled by proportional-derivative (PD) feedback controller gains. Lyapunov analysis ensures global asymptotic stability when the model is precise [20]. Assuming that M ( q ) , C ( q , q ˙ ) , g ( q ) , and f ( q , q ˙ ) are exactly known, let q d ( t ) be the desired trajectory with derivatives q ˙ d and q ¨ d . Then, the traditional CTC law is defined as
τ = M ( q ) q ¨ d + K d ( q ˙ d q ˙ ) + K p ( q d q ) + C ( q , q ˙ ) q ˙ + g ( q ) + f ( q , q ˙ ) ,
where K p and K d are positive definite gain matrices and, q d , q ˙ d , and  q ¨ d denote the desired joint position, velocity, and acceleration vectors, respectively. Define the tracking errors as
e = q d q and e ˙ = q ˙ d q ˙ .
The Lyapunov method is used to ensure stability. A Lyapunov function candidate is chosen as
V ( e , e ˙ ) = 1 2 e ˙ T M ( q ) e ˙ + 1 2 e T K p e .
Taking the time derivative of V and substituting the closed-loop dynamics from (1) and (2), one can show that
V ˙ = e ˙ T K d e ˙ ,
This guarantees that the tracking error converges to zero globally (or remains bounded under bounded disturbances), ensuring the stability of the closed-loop system.

2.2. Data-Driven Control

In the data-driven approach, the exact dynamics matrices and vectors are replaced by their estimates, which are learned from the sensor data. In particular, the following robot parameters are replaced by their predicted values:
  • M ^ ( q ) : the estimated inertia matrix.
  • C ^ ( q , q ˙ ) : the estimated Coriolis and centrifugal force matrix.
  • g ^ ( q ) : the estimated gravitational forces.
  • f ^ ( q , q ˙ ) : the estimated frictional forces.
Thus, the data-driven computed torque control law is formulated as
τ = M ^ ( q ) q ¨ d + K d ( q ˙ d q ˙ ) + K p ( q d q ) + C ^ ( q , q ˙ ) q ˙ + g ^ ( q ) + f ^ ( q , q ˙ ) ,
where q d , q ˙ d , and  q ¨ d are the desired position, velocity, and acceleration trajectories, respectively, and  K p , K d are positive definite gain matrices. After learning the parameter values during training, these predictions enable the controller to adaptively compensate for the unmodeled dynamics and disturbances present in the real system.

Stability with Estimated Dynamics

In order to determine the stability, we denote the modeling errors by
Δ M = M M ^ , Δ C = C C ^ , Δ g = g g ^ , Δ f = f f ^ ,
and the lumped uncertainty as
d ( q , q ˙ , q ¨ d , e , e ˙ ) Δ M q ¨ d + K d e ˙ + K p e + Δ C q ˙ + Δ g + Δ f .
We enforce the standard structural assumptions and robot properties on the following estimates:
(i)
M ^ ( q ) = M ^ ( q ) 0 (e.g., by symmetrization and eigenvalue flooring);
(ii)
M ^ ˙ ( q ) 2 C ^ ( q , q ˙ ) is skew-symmetric (e.g., C ^ built from Christoffel symbols of M ^ );
(iii)
f ^ ( q , q ˙ ) is passive (e.g., viscous term with F ^ v 0 ).
These constraints can be enforced by adding projection layers or post-processing of the learned maps.
To assess stability, we consider the Lyapunov function
V ( e , e ˙ ) = 1 2 e ˙ M ^ ( q ) e ˙ + 1 2 e K p e .
Using the closed-loop dynamics, standard manipulator identities, and the properties above, one obtains
V ˙ = e ˙ K d e ˙ + e ˙ d ( q , q ˙ , q ¨ d , e , e ˙ ) .
If the lumped uncertainty is bounded as d ( · ) d max on the operating set (which can be estimated from validation errors of M ^ , C ^ , g ^ , f ^ ), then
V ˙ λ min ( K d ) e ˙ 2 + e ˙ d max .
This inequality implies that the tracking error remains uniformly ultimately bounded (UUB) [20]. Increasing the damping gain K d or improving the accuracy of the estimate (reducing the d m a x ) tightens this bound. The robot trajectory remains stable and converges to a small neighborhood around the desired path. When the estimation error tends to zero, the controller recovers asymptotic stability, identical to the ideal computed torque case.

3. Online Estimation of Model Parameters

In this section, we describe how the various parameters in the robot model, that is, the inertial, Coriolis, friction, and gravity parameters, can be estimated by recording robot trajectories in real-time.

3.1. Estimation of Gravity

To estimate the gravitational torques g ( q ) in the robot dynamics, we exploit the fact that when the robot is in a steady state, the measured joint velocity q ˙ and joint acceleration q ¨ are zero. Under these conditions, the dynamic model simplifies considerably. In particular, if the robot is held in a fixed position by a controller, the inertial term M ( q ) q ¨ and the Coriolis/centrifugal term C ( q , q ˙ ) q ˙ vanish, and friction effects are minimal or can be assumed negligible. Thus, in steady state, the applied control torque is primarily used to balance the gravitational torque, i.e.,
τ = g ( q ) .
To generate the required data for the estimation of gravity, we use a simple PD control law. In this setup, the desired velocity and acceleration are set to zero. The PD control law for each joint is given by
τ P D = K p ( q d q ) K d q ˙ ,
where K p and K d are positive definite gain matrices, q d is the desired final position.
During the experiment, the robot is controlled using this PD law. Once it reaches a steady state (that is, when q ˙ 0 and q q d ), the applied torque τ P D compensates primarily for gravity. At this point, the joint positions q and the corresponding control torque τ P D are recorded. Although the final position may not exactly match q d , it still provides an acceptable data point. Repeating this process in various static positions in the workspace yields a set of data points q , τ P D .
The gravity vector g ^ ( q ) is estimated using a Multilayer Perceptron (MLP) Regressor. This model learns the nonlinear mapping from the joint position to the steady-state torque. The MLP Regressor utilizes fully connected layers. To optimize performance and ensure robustness, the model’s architecture and learning parameters were selected via Randomized Search Cross-Validation ( RandomizedSearchCV ) [21]. The search space included varying the number of layers/neurons (e.g., ( 100 , 100 ) , ( 200 , 100 ) ), activation functions (‘relu’, ‘tanh’), L2 regularization ( α ), and initial learning rate. The best model parameters found are summarized below:
  • Model Type: MLP Regressor.
  • Optimization: Adam solver, with a maximum of 5000 iterations.
  • Best Architecture: hidden layer size = (100, 100), with  relu activation.
  • Regularization: α = 0.001
Before training, both the input positions q and the target torques τ P D were standardized using a StandardScaler. This crucial preprocessing step ensures that all features have zero mean and unit variance, accelerating the convergence and improving the numerical stability during gradient descent optimization.

Stability Considerations for Gravity Estimation

For the robot manipulator with PD control with no gravity compensation, the Lyapunov function is typically defined as
V = 1 2 q ˙ M ( q ) q ˙ + 1 2 ( q d q ) K p ( q d q ) .
This Lyapunov function V is always positive (except at equilibrium when it is zero), and its time derivative is given by
V ˙ = q ˙ K d q ˙ q ˙ F v q ˙ 0 ,
which is non-positive, indicating that the total “energy” of the system decreases over time. Hence, the closed-loop system is stable under PD control without gravity compensation. Although the PD controller ensures stability, it exhibits a steady-state offset due to uncompensated gravitational torques. This behavior is consistent with the data generation objective, which focuses on the static equilibrium states of the manipulator.

3.2. Estimation of Combined Coriolis and Friction Effects (C + f)

The combined effects of Coriolis, centrifugal, and friction forces are denoted as
C ( q , q ˙ ) q ˙ + f ( q , q ˙ ) .
To estimate these forces, we take advantage of the data collected during robot motion at a constant speed. Under such conditions, the acceleration is approximately zero ( q ¨ 0 ), so the dynamic model in (1) simplifies to
τ g ( q ) + C ( q , q ˙ ) q ˙ + f ( q , q ˙ ) .
Assuming that external disturbances d ( t ) are negligible or have been filtered out, and using our previously estimated gravity model g ^ ( q ) , we can isolate the combined term by subtracting the estimated gravitational component from the measured torque:
τ g ^ ( q ) C ( q , q ˙ ) q ˙ + f ( q , q ˙ ) .
To generate a constant-speed motion trajectory, we consider implementing the control law given by a PID Position Controller with Estimated Gravity Compensation:
τ = g ^ ( q ) + K d ( q ˙ d q ˙ ) + K p ( q d q ) + K i ( q d q ) d t ,
where K i is a positive definite gain matrix for the integral action. For constant-speed motion, the desired trajectory is defined as q ˙ d = v const , and  q d ( t ) is its integral. This control law ensures that the torque τ compensates for gravity while the integral term generates the necessary steady-state torque to overcome unmodeled Coriolis and friction effects, driving the position and velocity errors to zero. Once the control action is applied at a constant speed, the term τ g ^ ( q ) effectively captures the combined dynamics:
M ( q ) q ¨ + C ( q , q ˙ ) q ˙ + f ( q , q ˙ ) g ˜ ( q ) ,
where g ˜ ( q ) = g ( q ) g ^ ( q ) denotes the residual gravity estimation error. By collecting data during these stable, constant-speed movements, we record the joint positions q, the joint velocities q ˙ , and compute the total residual torque τ g ^ ( q ) , which is dominated by the unmodeled dynamic effects. This yields a dataset { ( q , q ˙ , τ g ^ ( q ) ) } , which is used to train a regression model to predict the combined Coriolis and friction terms based on q and q ˙ .

Stability Considerations for Coriolis and Friction Effects

The controller incorporates the learned gravity term and is expressed as
τ = g ^ ( q ) + K d ( q ˙ d q ˙ ) + K p ( q d q ) + K i ( q d q ) d t .
Defining the position error e = q d q , velocity error e ˙ = q ˙ d q ˙ , and integral error z = e d t , the closed-loop dynamics can be written as
M ( q ) e ¨ + K d e ˙ + K p e + K i z = d ( q , q ˙ , e , e ˙ ) ,
where d ( q , q ˙ , e , e ˙ ) contains all uncompensated terms, including Coriolis, friction, and residual gravity. Consider the Lyapunov function candidate
V ( e , e ˙ , z ) = 1 2 e ˙ M ( q ) e ˙ + 1 2 e K p e + 1 2 z K i z ,
Differentiating V and substituting the closed-loop error dynamics together with the skew-symmetry property M ˙ ( q ) 2 C ( q , q ˙ ) being skew-symmetric (so that e ˙ ( M ˙ 2 C ) e ˙ = 0 ), yields
V ˙ = e ˙ K d e ˙ + e ˙ d ( q , q ˙ , e , e ˙ ) .
If d ( q , q ˙ , e , e ˙ ) D max on the operating set, then This establishes Uniform Ultimate Boundedness [20] of the tracking errors, with the ultimate bound tightened by larger K d or smaller D max . Hence, the closed-loop system remains stable, and the joint velocities converge to q ˙ d , enabling reliable collection of torque data.

3.3. Estimation of the Inertia Matrix

Once the gravitational, Coriolis, and frictional torques have been factored out, the inertial torques can be estimated during the normal operation of the robot, i.e., sensor data obtained during joint acceleration and deceleration.
The training data for the physics-informed neural network (PINN) was generated through a high-fidelity simulation of a two-link robotic manipulator under closed-loop control. This section details the key components of the data generation pipeline.

3.3.1. Closed-Loop Trajectory Control Design

During the inertia estimation phase, the torque applied to the manipulator is generated by the controller, which combines the learned dynamic model with feedback regulation. The control law is expressed as
τ = C ^ ( q , q ˙ ) q ˙ + f ^ ( q , q ˙ ) + g ^ ( q ) + K d ( q ˙ d q ˙ ) + K p ( q d q ) + K i ( q d q ) d t .
Here, the feedforward terms C ^ ( q , q ˙ ) q ˙ , g ^ ( q ) , and  f ^ ( q , q ˙ ) compensate for the Coriolis, gravitational, and frictional effects, while the PID feedback terms ensure a stable and sufficiently excited motion. At each sampling instant, the applied control torque τ and the joint states ( q , q ˙ , q ¨ ) are recorded.
To isolate the inertial component of the dynamics, the predicted gravity, Coriolis, and friction terms are subtracted from the total applied torque, yielding the residual torque
τ res = τ C ^ ( q , q ˙ ) q ˙ g ^ ( q ) f ^ ( q , q ˙ ) .
This residual term corresponds to the torque portion responsible for generating joint acceleration, i.e., the inertial contribution M ( q ) q ¨ , up to modeling and estimation errors. Physically, τ res represents the effective torque that drives acceleration once all other dynamic effects have been compensated by the learned models.
Consequently, each recorded sample ( q , q ˙ , q ¨ , τ res ) captures the instantaneous relationship between joint accelerations and the corresponding inertial torque. The complete dataset is defined as
D = { ( q ( i ) , q ˙ ( i ) , q ¨ ( i ) , τ res ( i ) ) } i = 1 N ,
where N denotes the total number of recorded data samples collected during all simulation runs. This dataset serves as the basis for learning the inertia matrix M ( q ) through the physics-informed neural network. The proposed approach ensures that the collected data directly represent the inertial dynamics of the manipulator, while the feedback controller maintains stability and provides sufficient excitation for accurate parameter identification.

3.3.2. Physics-Informed Inertia Matrix Estimation

The inertia matrix M ( q ) is a fundamental component of robotic dynamics that encodes the mass distribution and coupling effects between joints. Traditional methods of estimating M ( q ) require precise knowledge of the robot’s physical parameters, which are often unavailable in practice. We present a data-driven approach using neural networks to learn the inertia matrix directly from operational data.
This study presents a PINN approach for learning the inertia matrix of a robotic manipulator. The method combines data-driven learning with fundamental physics constraints to ensure physically consistent predictions. By embedding the structure of the Euler–Lagrange equations into the neural network architecture and training process, we achieve accurate parameter estimation while maintaining physical plausibility. We implement a feedforward neural network f θ : R n R n ( n + 1 ) / 2 that maps joint configurations to the unique elements of the symmetric inertia matrix:
f θ ( q ) = [ M ^ 11 , M ^ 12 , , M ^ 1 n , M ^ 22 , , M ^ n n ] .
The inertia matrix is then constructed to ensure physical consistency:
M ( q ) = e M ^ 11 M ^ 12 M ^ 1 n M ^ 12 e M ^ 22 M ^ 2 n M ^ 1 n M ^ 2 n e M ^ n n .
This parameterization guarantees the following:
  • Positive definiteness through exponential terms on the diagonal.
  • Symmetry by construction.
  • Continuous and differentiable dependence on the joint configuration q
The PINN architecture predicts the unique elements of the inertia matrix. The PINN training incorporates two loss terms:
1.
Data fitting loss:
L mse = τ res M ^ ( q ) q ¨ 2
2.
Physics consistency loss:
L phys = q ˙ T d M ^ d t 2 C q ˙ 2
where d M ^ d t is computed via automatic differentiation. The  Jacobian computation is achieved via TensorFlow’s automatic differentiation [22]. The total loss is
L total = L mse + λ phys L phys
where λ phys is the tuning scalar hyperparameter coefficient that balances how much emphasis is placed on the physics-consistency term versus the purely data-fitting term in the total loss.

3.3.3. Stability Considerations for Estimation of Inertial Dynamics

Using the robot dynamics and defining the position error e = q d q , the velocity error e ˙ = q ˙ d q ˙ , and the integral of the position error z = e d t , The closed-loop error dynamics become
M ( q ) e ¨ + C ( q , q ˙ ) e ˙ + K d e ˙ + K p e + K i z = Δ ,
where Δ = ( C C ^ ) q ˙ + ( g g ^ ) + ( f f ^ ) represents the bounded modeling error, with  Δ D max . Using the Lyapunov candidate function
V = 1 2 e ˙ M ( q ) e ˙ + 1 2 e K p e + 1 2 z K i z ,
and the skew-symmetry property M ˙ ( q ) 2 C ( q , q ˙ ) , the time derivative of V satisfies
V ˙ λ min ( K d ) e ˙ 2 + e ˙ D max .
where λ min ( K d ) denotes the smallest eigenvalue of the positive-definite gain matrix K d , representing the minimum damping level in the control system. Hence, the tracking error is UUB [20]. Increasing the damping gain K d or improving the accuracy of the learned models (reducing D max ) tightens this bound. This controller ensures stable tracking performance without requiring knowledge of the inertia matrix, while still benefiting from learned compensation of gravitational, Coriolis, and frictional effects.

4. Results and Discussion

All simulations were conducted using a planar two-link robotic manipulator modeled with standard rigid-body dynamics. The mechanical and inertial parameters of each link are listed in Table 1. These values are consistent with benchmark models widely used in robotic control studies.
The controllers used during data generation are summarized in Table 2. The proportional–derivative (PD) controller was employed for static equilibrium tests to estimate gravitational torques, whereas the velocity–integral controller was used for constant-velocity experiments to isolate Coriolis and frictional effects. The computed-torque controller, incorporating the learned dynamics, was used for trajectory-tracking experiments.
Simulation results for online parameter estimation in the case of a two-link robotic manipulator are presented below, starting with online estimation of gravitational torques, followed by the estimation of Coriolis and inertia matrices.

4.1. Estimation of Gravitational Torques

We conducted 20,000 simulations to construct the dataset { ( q , τ P D ) } . Eighty percent of the dataset was used to train the optimized model, and a dedicated 20% held-out test set was used to assess its generalization capability across the operational space. Figure 1 illustrates the PD control true robot joint torques τ P D = [ True τ 1 , True τ 2 ] versus the predicted joint torques g ^ ( q ) = [ Predicted τ 1 , Predicted τ 2 ] when the manipulator reached various static configurations. The trained multi-layer perceptron (MLP) model predicts the static torques required to hold a two-link robotic arm at desired joint angles with very high accuracy, as evidenced by a mean squared error (MSE) of approximately 0.01048 (Nm)2 and an R 2 value of about 0.9997 on the test set. This near-perfect alignment is also evident in the scatter plots of predicted versus true torque components, where the data points lie almost exactly on the ideal y = x line. The simulations rely on a PD controller to drive the arm to various final positions within [ π / 2 , π / 2 ] for each joint, effectively sampling a wide range of configurations. Because the final torques in this setup largely compensate for gravity (with a small PD offset), the collected dataset captures the essential information for learning the torque–angle relationship.
The sample size of 20,000 simulated configurations was determined based on the model’s complexity and empirical convergence analysis. Following standard neural network heuristics ( N 10 W , where W denotes the number of trainable parameters), the adopted two-hidden-layer MLP with approximately 12,000 parameters would nominally require on the order of 10 5 samples for exhaustive coverage of the configuration space. However, due to the smoothness and low stochasticity of the simulated torque–angle mapping, 20,000 samples were experimentally found to ensure stable generalization with no significant accuracy gain beyond this threshold. Model hyperparameters were tuned using 5-fold cross-validation within the RandomizedSearchCV [21] framework to guarantee robust parameter selection. All simulations were performed in Python 3.10 on Google Colab using a fourth-order Runge–Kutta integrator for trajectory computation.

4.2. Estimation of Coriolis and Friction Effects

A total of 44,548 samples were generated through numerical simulations of a two-link robotic manipulator operating under constant-velocity conditions. Each simulation lasted 10 s with a sampling period of 0.01 s, producing approximately 1000 time steps per run. A total of 3000 simulations were executed in parallel, each with randomly initialized joint angles and velocities, and distinct desired joint velocity vectors q ˙ d drawn uniformly within [ 0.3 , 0.7 ]  rad/s. At each simulation step where the velocity tracking error satisfied q ˙ q ˙ d < 10 3 , a data record was saved. The collected dataset contains six columns representing both the robot’s configuration and control signals:
[ q 1 , q 2 , q ˙ 1 , q ˙ 2 , τ 1 , τ 2 ] .
Here, ( q 1 , q 2 ) are the joint positions, ( q ˙ 1 , q ˙ 2 ) are the corresponding joint velocities, and  τ = [ τ 1 , τ 2 ] denotes the total control torques computed by the velocity-integral controller that includes proportional and integral feedback terms, as well as gravity compensation through the pre-trained model g ^ ( q ) . The resulting dataset, consisting of 44,548 samples and 6 features, provides a rich and diverse collection of robot motion and control data suitable for learning dynamic models such as the Coriolis and friction components. To isolate the Coriolis and friction term, the exact combined term, C exact , was obtained by subtracting the predicted gravitational torque, g ^ ( q ) , from the total measured torque τ as expressed by
C exact = τ g ^ ( q ) .
The optimized Random Forest (RF) Regressor model [23,24], which predicts the combined torque contribution of the Coriolis and friction effects,
C predicted = C ^ ( q , q ˙ ) q ˙ + f ^ ( q , q ˙ ) ,
was trained to approximate C exact using the collected dataset containing configuration and control signals. The model was optimized through RandomizedSearchCV with 5-fold cross-validation and achieved a test mean squared error (MSE) of 6.90 × 10 5 (N·m)2 and an R 2 score of 0.992 . These results demonstrate high accuracy in capturing the nonlinear coupling between joint velocities and torques. The model learns the mapping from ( q 1 , q 2 , q ˙ 1 , q ˙ 2 ) to C exact , effectively modeling the difference between the total measured torque and the predicted gravity torque. Scatter plots in Figure 2 of exact versus predicted values further confirm the strong alignment between the model’s predictions and the ground truth, showing that the learned models for g ^ ( q ) and C ^ ( q , q ˙ ) q ˙ + f ^ ( q , q ˙ ) track the true dynamics closely, even in the presence of small unmodeled effects.
To evaluate robustness, Gaussian noise of varying intensity was added to the input data. As the noise intensity doubled, the estimation error increased significantly: the MSE rose from 6.90 × 10 5 (N·m)2 with no noise ( σ = 0 ) to 8.47 × 10 5 (N·m)2 at σ = 0.01 , 1.21 × 10 4 (N·m)2 at σ = 0.02 , and 2.38 × 10 4 (N·m)2 at σ = 0.04 , corresponding to roughly a 100 % increase in error when the noise intensity was doubled. This behavior highlights a nonlinear correlation between noise level and estimation accuracy. Despite these promising results, the study has several limitations, including a relatively small dataset, a single-joint model that does not capture multi-DOF coupling, and fixed load conditions that overlook the effect of payload variations. Future work should therefore adopt a joint-wise estimation with a global fusion framework to extend scalability to multi-joint systems, integrate data augmentation through simulated trajectories under different load and speed conditions, implement noise-aware training to enhance robustness, and explore hybrid modeling approaches that combine analytical dynamic equations with learned residuals to improve both accuracy and interpretability.

4.3. Estimation of Inertial Dynamics

The parameters used for the simulation and data collection for estimation of inertial dynamics are summarized in Table 3. These settings ensure a realistic operating range for the two-link manipulator and provide a sufficient signal-to-noise ratio for accurate estimation of inertial effects.
To estimate the inertial dynamics, a persistently exciting reference trajectory was generated as
q d , 1 ( t ) = i = 1 5 a i sin ( ω i t ) , q d , 2 ( t ) = i = 1 5 a i cos ( ω i t + 0.2 ) ,
with excitation frequencies ω = [ 0.3 , 0.8 , 1.2 , 1.8 , 2.5 ] rad/s and amplitudes a = [ 1.0 , 0.7 , 0.5 , 0.3 , 0.2 ] . This multi-frequency design ensures excitation of all dynamic modes, while the phase shift between joints prevents correlated motion. Control inputs were saturated at ± 60 N·m to simulate realistic actuator limits.
To mimic sensor noise, Gaussian perturbations were added to all measured signals:
q meas = q + N ( 0 , 0 . 02 2 ) , q ˙ meas = q ˙ + N ( 0 , 0 . 05 2 ) , q ¨ meas = q ¨ + N ( 0 , 0 . 10 2 ) .
Samples were retained only when the joint acceleration satisfied q ¨ 2 > 0.02 rad/s2, as low-acceleration regions contribute little information to inertia estimation. After filtering, approximately N 2000 samples remained, providing a diverse and informative dataset for learning the inertia matrix.
Figure 3 compares the exact and predicted elements of the inertia matrix, while Table 4 summarizes the inertia-matrix prediction performance across three representative robot configurations. The home position corresponds to the nominal posture q = [ 0 , 0 ] , the extended configuration represents the fully stretched pose q = [ π / 2 , 0 ] , and the singularity occurs when the two links are vertically aligned q = [ π , 0 ] . The exponential parameterization guarantees positive definiteness, with the MSE between 0.021 and 0.052 (N·m)2 and a maximum relative error below 8.3 % . These results confirm that the inertia model’s prediction accuracy lies within the standard 10 % tolerance commonly accepted in robot dynamics identification.

4.4. Sensitivity and Robustness Analysis

To assess stability, the proposed PINN was trained under various physical-consistency weights λ phys { 0.1 , 1 , 10 } . As summarized in Table 5, the mean inertia-matrix reconstruction error decreased from 2.82 × 10 1 at λ phys = 0.1 to 1.41 × 10 1 at λ phys = 1 , confirming that moderate physical regularization improves both convergence and generalization. A higher value λ phys = 10 offered no further benefit, indicating an optimal balance around λ phys 1 . Five repeated runs yielded a standard deviation σ < 6 × 10 2 , demonstrating result repeatability. Boundary-condition experiments showed limited degradation: the MSE increased by approximately 23 % under doubled noise intensity, 28 % for higher-frequency trajectories, and less than 10 % for a + 10 % gravity bias. These results confirm the robustness of the proposed PINN estimator to measurement noise, excitation variations, and parametric uncertainty.
Overall, the experiments demonstrate that incorporating a physical-consistency term significantly improves inertia-matrix learning stability and robustness. Moreover, moderate weighting ( λ phys = 1 ) yields the best accuracy while maintaining low sensitivity to measurement noise and modeling uncertainties.

4.5. Manipulator Control with Estimated Dynamics

In this section, we present the outcome of the two-link robot’s movement when controlled using only the data-driven estimates of the inertia matrix M ^ ( q ) , the Coriolis/centrifugal matrix C ^ ( q , q ˙ ) , and the gravity vector g ^ ( q ) .
Figure 4 illustrates the performance of the manipulator in following a desired trajectory. It is observed that despite relying solely on the learned model, the robot’s joints (solid) closely follow the desired paths (dashed) over the entire 10 s maneuver. This confirms that M ^ , C ^ , and g ^ provide a sufficiently accurate estimate of the manipulator dynamics to achieve effective trajectory tracking.

5. Conclusions

Traditional control of robotic systems has often been predicated on the assumption of complete knowledge of system parameters. In reality, unmodeled dynamics, friction, and external disturbances usually degrade performance. This study presented a data-driven framework that learns key components of robot dynamics from operational data. Using real-time sensor information, the proposed method provides an effective alternative to purely model-based control, particularly in scenarios where obtaining an accurate model is impractical or impossible. Future research could focus on extending these techniques to high-dimensional systems, incorporating uncertainty quantification, and exploring advanced machine learning architectures for improved generalization.
Future work will focus on extending the proposed framework toward scalable, uncertainty-aware, and experimentally validated robotic control. For high-dimensional manipulators, we plan to employ a distributed PINN structure in which joint-level estimators are fused through a global coordination network to ensure scalability. To quantify model reliability, techniques such as Bayesian dropout and Gaussian-Process residual modeling will be explored for estimating both epistemic and aleatoric uncertainties, enabling probabilistic confidence bounds on predicted torques. The incorporation of attention-based and transformer-enhanced PINNs is expected to capture long-range coupling and improve generalization to multi-joint systems. Further extensions include transfer learning and domain adaptation to facilitate the reuse of learned models across different robot platforms and environments, thereby reducing retraining costs. The integration of hybrid gray-box modeling, combining analytical rigid-body dynamics with data-driven residual estimators, will improve interpretability and data efficiency. Experimental implementation on a physical manipulator will provide validation under variable payload, friction, and noise conditions, while energy-based and Hamiltonian constraints will enforce physical consistency.
Finally, the deployment of uncertainty-aware computed-torque controllers on embedded or edge hardware will be investigated to achieve real-time operation in industrial settings. Collectively, these developments will advance the proposed framework toward a generalizable, robust, and physically grounded solution for adaptive control of complex robotic systems.

Author Contributions

Conceptualization, H.K.; writing—original draft, H.K.; writing—review and editing, H.K. and K.I. All authors have read and agreed to the published version of the manuscript.

Funding

This publication was partially funded by the UA Little Rock Open Access Article Publishing Support Fund.

Institutional Review Board Statement

Not applicable.

Informed Consent Statement

Not applicable.

Data Availability Statement

The data gathered during this study are available upon request from the first author.

Conflicts of Interest

The authors declare no conflicts of interest.

References

  1. Slotine, J.J.E.; Li, W. Applied Nonlinear Control; Prentice-Hall: Hoboken, NJ, USA, 1991. [Google Scholar]
  2. Siciliano, B.; Sciavicco, L.; Villani, L.; Oriolo, G. Robotics: Modelling, Planning and Control; Springer: Berlin/Heidelberg, Germany, 2010. [Google Scholar]
  3. Nguyen-Tuong, D.; Peters, J. Using model knowledge for learning inverse dynamics. In Proceedings of the IEEE International Conference on Robotics and Automation (ICRA), Anchorage, AK, USA, 3–8 May 2010; pp. 2677–2682. [Google Scholar]
  4. Lutter, M.; Ritter, C.; Peters, J. Deep Lagrangian networks: Using physics as model prior for deep learning. arXiv 2019, arXiv:1907.04490. [Google Scholar]
  5. Benosman, M. Model-based vs data-driven adaptive control: An overview. Int. J. Adapt. Control. Signal Process. 2018, 32, 753–776. [Google Scholar] [CrossRef]
  6. Raouf, I.; Lee, H.; Kim, H.S. Mechanical fault detection based on machine learning for robotic RV reducer using electrical current signature analysis: A data-driven approach. J. Comput. Des. Eng. 2022, 9, 417–433. [Google Scholar] [CrossRef]
  7. Fu, J.; Kumar, A.; Nachum, O.; Tucker, G.; Levine, S. D4RL: Datasets for deep data-driven reinforcement learning. arXiv 2020, arXiv:2004.07219. [Google Scholar]
  8. Chen, Z.; Renda, F.; Le Gall, A.; Mocellin, L.; Bernabei, M.; Dangel, T.; Ciuti, G.; Cianchetti, M.; Stefanini, C. Data-driven methods applied to soft robot modeling and control: A review. IEEE Trans. Autom. Sci. Eng. 2024, 22, 2241–2256. [Google Scholar] [CrossRef]
  9. Narendra, K.S.; Parthasarathy, K. Identification and control of dynamical systems using neural networks. IEEE Trans. Neural Netw. 1990, 1, 4–27. [Google Scholar] [CrossRef] [PubMed]
  10. Hornik, K.; Stinchcombe, M.; White, H. Multilayer feedforward networks are universal approximators. Neural Netw. 1989, 2, 359–366. [Google Scholar] [CrossRef]
  11. Greydanus, S.; Dzamba, M.; Yosinski, J. Hamiltonian neural networks. In Proceedings of the 32nd Conference on Neural Information Processing Systems (NeurIPS 2019), Vancouver, BC, Canada, 9–14 December 2019. [Google Scholar]
  12. Deisenroth, M.P.; Rasmussen, C.E. PILCO: A model-based and data-efficient approach to policy search. In Proceedings of the 28th International Conference on Machine Learning (ICML-11), Bellevue, WA, USA, 28 June–2 July 2011. [Google Scholar]
  13. Seeger, M. Gaussian processes for machine learning. Int. J. Neural Systems. 2004, 14, 69–106. [Google Scholar] [CrossRef] [PubMed]
  14. Raissi, M.; Perdikaris, P.; Karniadakis, G.E. Physics-informed neural networks: A deep learning framework for solving forward and inverse problems involving nonlinear partial differential equations. J. Comput. Phys. 2019, 378, 686–707. [Google Scholar] [CrossRef]
  15. Kissas, G.; Yang, Y.; Hwuang, E.; Witschey, W.R.; Detre, J.A.; Perdikaris, P. Machine learning in cardiovascular flows modeling: Predicting arterial blood pressure from non-invasive 4D flow MRI data using physics-informed neural networks. Comput. Methods Appl. Mech. Eng. 2020, 358, 112623. [Google Scholar] [CrossRef]
  16. Haghighat, E.; Raissi, M.; Moure, A.; Gomez, H.; Juanes, R. A physics-informed deep learning framework for inversion and surrogate modeling in solid mechanics. Comput. Methods Appl. Mech. Eng. 2021, 379, 113741. [Google Scholar] [CrossRef]
  17. Yang, X.; Du, Y.; Li, L.; Zhou, Z.; Zhang, X. Physics-informed Neural Networks for Model Prediction and Dynamics Parameter Identification of Collaborative Robot Joints. IEEE Robot. Autom. Lett. 2023, 8, 8462–8469. [Google Scholar] [CrossRef]
  18. Liu, J.; Borja, P.; Santina, C.D. Physics-informed Neural Networks to Model and Control Robots: A Theoretical and Experimental Investigation. Adv. Intell. Syst. 2024, 6, 2300385. [Google Scholar] [CrossRef]
  19. Li, H.; Chai, Y.; Lv, B.; Ruan, L.; Zhao, H.; Zhao, Y.; Luo, J. Physics-informed Neural Network Predictive Control for Quadruped Locomotion. arXiv 2025, arXiv:2503.06995. [Google Scholar] [CrossRef]
  20. Khalil, H.K.; Grizzle, J.W. Nonlinear Systems, 3rd ed.; Prentice Hall: Upper Saddle River, NJ, USA, 2002. [Google Scholar]
  21. Bergstra, J.; Bengio, Y. Random Search for Hyper-Parameter Optimization. J. Mach. Learn. Res. 2012, 13, 281–305. [Google Scholar]
  22. Abadi, M.; Agarwal, A.; Barham, P.; Brevdo, E.; Chen, Z.; Citro, C.; Corrado, G.S.; Davis, A.; Dean, J.; Devin, M.; et al. TensorFlow: Large-Scale Machine Learning on Heterogeneous Systems. arXiv 2015, arXiv:1603.04467v2. [Google Scholar]
  23. Breiman, L. Random Forests. Mach. Learn. 2001, 45, 5–32. [Google Scholar] [CrossRef]
  24. Segal, M.R. Machine Learning Benchmarks and Random Forest Regression. UCSF: Center for Bioinformatics and Molecular Biostatistics. 2004. Available online: https://escholarship.org/uc/item/35x3v9t4 (accessed on 1 July 2025).
Figure 1. Comparison of true vs. predicted torque components τ 1 and τ 2 all in Nm. Red dashed line is the ideal y = x line.
Figure 1. Comparison of true vs. predicted torque components τ 1 and τ 2 all in Nm. Red dashed line is the ideal y = x line.
Sensors 25 06831 g001
Figure 2. Scatter plots comparing exact vs. predicted Coriolis terms (C1, C2) all in N·m. Red dashed line is the ideal y = x line.
Figure 2. Scatter plots comparing exact vs. predicted Coriolis terms (C1, C2) all in N·m. Red dashed line is the ideal y = x line.
Sensors 25 06831 g002
Figure 3. Plots comparing exact vs. the predicted Inertia terms M11, M12, M22 all in kg·m2.
Figure 3. Plots comparing exact vs. the predicted Inertia terms M11, M12, M22 all in kg·m2.
Sensors 25 06831 g003
Figure 4. Joint angles and velocities under the data-driven computed-torque controller. Dashed lines show the desired trajectories q d ( t ) , while solid lines show the actual joint responses.
Figure 4. Joint angles and velocities under the data-driven computed-torque controller. Dashed lines show the desired trajectories q d ( t ) , while solid lines show the actual joint responses.
Sensors 25 06831 g004
Table 1. Geometric and inertial parameters of the two-link manipulator.
Table 1. Geometric and inertial parameters of the two-link manipulator.
ParameterLink 1Link 2
Mass m i [kg]1.01.0
Length l i [m]1.01.0
Center of mass l c i [m]0.50.5
Moment of inertia I i [kg·m2]0.10.1
Gravity g [m/s2]9.81
Table 2. Control gains for data-generation and validation experiments.
Table 2. Control gains for data-generation and validation experiments.
Controller K p K d K i
PD (gravity estimation)diag(100, 100)diag(20, 20)
Velocity–integral (Coriolis/friction)diag(20, 20)diag(5, 5)
CTC (inertia and tracking)diag(100, 100)diag(20, 20)diag(5, 5)
Table 3. Summary of data generation parameters.
Table 3. Summary of data generation parameters.
ParameterValue
Simulation duration10 s
Sampling timestep ( Δ t ) 0.004 s
Position noise (std. dev.)0.02 rad
Velocity noise (std. dev.)0.05 rad/s
Torque limits ± 60  N·m
Acceleration threshold0.02 rad/s2
Table 4. Inertia matrix prediction performance.
Table 4. Inertia matrix prediction performance.
ConfigurationMSEMax Rel. ErrorPositive Definite
Home position0.0214.2%Yes
Extended config.0.0346.1%Yes
Singularity0.0528.3%Yes
Table 5. Effect of λ phys and boundary conditions on inertia-matrix estimation accuracy.
Table 5. Effect of λ phys and boundary conditions on inertia-matrix estimation accuracy.
ExperimentMean MSEStd MSEComment
λ phys = 0.1 2.82 × 10 1 6.34 × 10 2 Weak physical constraint
λ phys = 1 1.41 × 10 1 4.36 × 10 2 Best trade-off between fit and physics
λ phys = 10 1.37 × 10 1 3.03 × 10 2 Slightly smoother, no major gain
High noise ( σ × 2 ) 1.73 × 10 1 + 23 % degradation vs. nominal
High frequency ( 1.5 × ) 1.8 × 10 1 + 28 % degradation expected
Gravity + 10 % 1.6 × 10 1 Low sensitivity to parameter bias
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

Kallel, H.; Iqbal, K. Online Estimation of Manipulator Dynamics for Computed Torque Control of Robotic Systems. Sensors 2025, 25, 6831. https://doi.org/10.3390/s25226831

AMA Style

Kallel H, Iqbal K. Online Estimation of Manipulator Dynamics for Computed Torque Control of Robotic Systems. Sensors. 2025; 25(22):6831. https://doi.org/10.3390/s25226831

Chicago/Turabian Style

Kallel, Hichem, and Kamran Iqbal. 2025. "Online Estimation of Manipulator Dynamics for Computed Torque Control of Robotic Systems" Sensors 25, no. 22: 6831. https://doi.org/10.3390/s25226831

APA Style

Kallel, H., & Iqbal, K. (2025). Online Estimation of Manipulator Dynamics for Computed Torque Control of Robotic Systems. Sensors, 25(22), 6831. https://doi.org/10.3390/s25226831

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