Previous Article in Journal
Research on Machine Tool Thermal Error Compensation Based on an Optimized LSTM Model
 
 
Font Type:
Arial Georgia Verdana
Font Size:
Aa Aa Aa
Line Spacing:
Column Width:
Background:
Article

Sensorless Payload Estimation of Serial Robots Using an Improved Disturbance Kalman Filter with a Variable-Parameter Noise Model

1
Shanghai Robotics Institute, School of Mechatronic Engineering and Automation, Shanghai University, Shanghai 200444, China
2
Shanghai Key Laboratory of Intelligent Manufacturing and Robotics, School of Mechatronic Engineering and Automation, Shanghai University, Shanghai 200444, China
*
Authors to whom correspondence should be addressed.
Actuators 2025, 14(12), 568; https://doi.org/10.3390/act14120568 (registering DOI)
Submission received: 5 October 2025 / Revised: 13 November 2025 / Accepted: 17 November 2025 / Published: 23 November 2025
(This article belongs to the Section Actuators for Robotics)

Abstract

The accurate estimation of the end-effector load force is essential in dynamic robotic scenarios, especially when the end-effector payload varies, to ensure safe and stable physical interaction among humans, robots, and environments. Currently, most applications still rely on payload calibration schemes, but existing calibration techniques often struggle to balance efficiency and accuracy. Moreover, current-based payload estimation methods, which are a commonly used and low-cost technique, face practical challenges such as non-negligible noise. To handle these issues, we propose a sensorless scheme based on a modified disturbance Kalman filter for accurately estimating the load force exerted on robots. Specifically, we introduce the dynamic model of robots that incorporates the nonlinear friction related to velocity and load. Subsequently, a generalized disturbance observer for the robot dynamics is adopted to avoid the measurement noise of joint acceleration. Considering the influence of friction and velocity on the noise parameters in the Kalman filter, a variable-parameter noise model is established. Finally, experimental results demonstrate that the proposed method achieves better performance in terms of accuracy, response, and overshoot suppression compared to the existing methods.

1. Introduction

With the advancement of robotic technology, interactions among humans, robots, and environments have become increasingly frequent, such as zero-force dragging teachers [1]. In most industrial scenarios, robotic arms typically carry unknown dynamic payloads during dragging operations. These uncertain loads alter the dynamic parameters of the manipulator and degrade the estimation accuracy of end-effector contact forces. Therefore, accurate load force estimation of the robotic end-effector is crucial to achieve safe and stable physical interaction, especially when the robot must quickly grasp and assemble components of varying weights while accurately detecting external contacts with human operators and the environment [2].
To address this, numerous methods have been proposed to mitigate errors caused by varying payloads. Conventional payload compensation typically relies on pre-calibration, where load parameters are updated upon payload replacement. These approaches are broadly categorized into two main types: model-free and model-based.
  • Model-based methods rely on an explicit analytical dynamics model derived from physics principles, where payload parameters are directly incorporated into the model equations.
  • Model-free methods bypass the need for a physics-based model and instead use data-driven techniques (e.g., machine learning) to compensate for payload-induced errors directly from data.
In the former, Shareef et al. [3] gave a detailed comparison among various learning-based techniques. To reduce the time consumption associated with online fine-tuning data collection across the joint space, Shan et al. [4] proposed a learning-based calibration scheme that leverages pre-trained neural network models to learn calibrated dynamic characteristics across a wide joint space in advance. Taie et al. [5] put forward a new online identification method that employs a bagging ensemble machine learning approach to estimate payload inertial parameters. While data-driven methods excel in handling complex dynamics, they often lack interpretability and require substantial computational resources for training and inference.
Conversely, model-based calibration methods are designed to achieve rapid calibration by compensating for variations in the end-effector payload. In [6], it is demonstrated that rapid calibration can be achieved when force/torque measurements are available and the payload geometry is known. Common ways for payload identification can be broadly classified into four categories [7]: (1) Wrench-based estimation using external sensors: this approach employs a wrist-mounted 6D force/torque sensor to measure the interaction wrench between the end-effector and the payload, combined with an inertial measurement unit (IMU) to capture accelerations. As this technique relies solely on external sensing, it imposes no additional requirements on the robot [8,9]. (2) Model-based estimation with joint torque sensing: if joint torque sensors and an accurate dynamic model of the robot are available, the external joint torques can be estimated, and payload forces can thereby be deduced [10]. It is worth noting the advances in sensor technology, including the development of highly sensitive integrated unidirectional pressure sensors [11]. (3) Differential torque measurement: If the system repeatedly executes the same trajectory, the inertial parameters of the payload can be determined by analyzing the difference in joint torque measurements between loaded and unloaded motions. This approach is illustrated in [12,13]. (4) Combined dynamics–payload identification: Given the similarity between payload identification and robot dynamics identification, it is feasible to estimate both simultaneously within a unified formulation, as demonstrated in [14,15]. The least squares fitting methods used in the aforementioned methods assume that all measurement errors originate solely from torque measurements and that the data matrix that includes joint accelerations is error-free. However, the double-time differentiation of position data obtained from encoders to compute joint accelerations results in highly noisy acceleration signals and multiple outliers [5]. Moreover, force/torque-sensor-based methods are costly and susceptible to drift and external influence. To eliminate the need for prior knowledge of the payload and to enable intuitive online payload identification, Kurdas et al. [16] presented a momentum-observer-based online payload identification method utilizing proprioceptive sensors from tactile robots and a novel filter design for kinematic measurements. However, fixed-gain first-order filter architectures often fail to meet the requirements of systems subject to unknown payload variations, and the accuracy of an observer is largely determined by the precision of the dynamic model of robots, particularly the modeling of joint friction.
Motivated by the challenges outlined above, this paper proposes a novel sensorless payload estimation scheme of serial robots using a disturbance Kalman filter with the variable-parameter noise model to enhance the robustness of the algorithm to process noise and model uncertainty. The major contributions can be summarized as follows:
(1) We give an accurate dynamic model with the nonlinear friction related to the velocity load; the dynamic model-based disturbance observer is integrated in an online payload estimation process.
(2) We establish a variable-parameter noise model via considering the influence of friction and velocity on the noise parameters in the Kalman filter, thus modifying the Kalman filter algorithm.
The remainder of this article is structured as follows. Section 2 introduces the modeling of robot dynamics involving velocity- and load-dependent friction and the establishment of a generalized momentum-based dynamic model. Section 3 designs the disturbance Kalman filter with a variable-parameter noise model. Later, the experimental results, analysis, and discussion are provided in Section 4. Finally, Section 5 gives the conclusion and future work of this paper.

2. Generalized Momentum-Based Dynamic Model

The inverse dynamics model of an n-DOFs serial robot, accounting for external torques induced by payload, can be expressed as follows [17]:
τ I = M q q ¨ + C q , q ˙ q ˙ + G q
τ J + τ e x t = τ I + τ f
τ m = H 1 τ J = K m i
τ e x t = J e T q F l o a d
where q , q ˙ , and q ¨ denote the vectors of joint angular position, velocity, and acceleration, respectively; M q , C q , q ˙ , and G q are inertial dynamic parameter matrices that characterize the inertia force/torque, centrifugal and Coriolis force/torque, and the gravity, respectively; τ I denotes the torque matrix related to inertial dynamics; τ f captures the friction torque vector of the joint side; τ e x t is called the external disturbance from external payload applied to the robotic manipulator system; H is a diagonal matrix of the joint reduction ratio; the matrix τ J represents the joint torque; and the motor output torque vector τ m is expressed as a function of the motor current matrix i and torque constant matrix K m ; F e x t is the external force/torque acting on the end-effector of the robot; J e is the Jacobian matrix.
In previous studies, friction has been shown to exhibit nonlinear characteristics that depend on joint velocity and load torque. For the j-th joint, the friction model can be written as follows [18]:
τ f j = f v 1 j q j ˙ + f v 2 j s g n q j ˙ q ˙ j 2 + f s j s g n q ˙ j e q ˙ j / ν j δ + f c j s g n q ˙ j 1 e q ˙ j / ν j δ + f l 1 j τ l j s g n q ˙ j + f l 2 j e f l 3 j τ l j / q ˙ j s g n q ˙ j
where f v 1 j and f v 2 j are the coefficients of the quadratic term for the viscous friction; f s j is the static friction coefficient; f c j is the Coulomb friction coefficient; the parameters ν j denotes the Stribeck velocity characterizing static friction and Coulomb friction; f l 1 j , f l 2 j , and f l 3 j are the load-dependent friction coefficients; and τ l j indicates the load torque. Note that the friction model (2) resists direct linearization due to its inherent nonlinear characteristics. For dynamic parameter identification methods involving velocity- and load-dependent friction, refer to literatures [18,19].
Since joint accelerations are obtained through second-order numerical differentiation of joint positions, which induce significant noise, we formulate the generalized momentum equation to circumvent this issue, the generalized momentum p and its derivative p ˙ are defined as follows [20]:
p = M q q ˙
p ˙ = M ˙ q , q ˙ q ˙ + M q q ¨
Based on the skew-symmetric nature of the matrix M ˙ q , q ˙ 2 C q , q ˙ and the symmetric structure of the inertia matrix M q [21], the following property can be derived:
M ˙ q , q ˙ = C q , q ˙ + C q , q ˙ T
By substituting Equations (1a), (1b) and (4) into Equation (3b), we can obtain the following momentum-based dynamic model:
p ˙ = τ J + τ e x t + C q , q ˙ T q ˙ G q τ f

3. Payload Estimation Using the Disturbance Kalman Filter

3.1. Design of Disturbance Kalman Filter

Employing a linearized system model improves computational efficiency in state observation processes. Combining Equation (1c), the dynamic model (5) can be rewritten as:
p ˙ = τ c o m + J e T q F l o a d + w p
where the term τ c o m = τ J + C q , q ˙ T q ˙ G q τ f serves as the deterministic driving component of the dynamic model; w p represents the dynamic noise, which primarily arises from incomplete compensation of dynamic errors such as friction. The primary source of this uncertainty is the residual error from the friction compensation, given that our friction model (Equation (2)) is an approximation of the complex, nonlinear reality. Assume that it can be followed a normal distribution with independent noise effects across each joint:
w p N μ c , p , Q c , p
where μ c , p denotes the mean vector of the dynamic noise distribution, typically μ c , p = 0 n × 1 , and the subscript c indicates that Q c , p represents the covariance matrix of the dynamic noise distribution of a continuous time system. This joint-wise independence is a standard simplification, justified by the fact that the friction phenomena and thus the compensation errors are predominantly local to each joint. This model effectively captures the most significant unmodeled dynamics while keeping the filter computationally tractable.
Considering the dynamic characteristics of unknown payload at the manipulator’s end-effector, along with existing noise disturbances, the external payload can be modeled as:
F ˙ l o a d = A f F l o a d + w f
where the matrix A f defines the dynamic characteristics attributed to the external wrench. While A f = 0 n × n constitutes the conventional selection in disturbance observer design, employing a negative definite diagonal matrix for A f facilitates the attenuation of constant estimation biases induced by disturbances [22]. w f is the load noise vector, which can be assumed to be normally distributed with mutually independent influences across its dimensions, i.e., w f N μ c , f , Q c , f . The terms μ c , f and Q c , f denote the mean and the covariance matrix of the load noise distribution, respectively.
Combining Equations (6) and (8), and defining the system state vector as x = p T F l o a d T T . The system equation can be expressed in state-space form as:
p ˙ F ˙ l o a d x ˙ = 0 7 × 7 J e T 0 6 × 7 A f A c p F l o a d x + I 7 × 7 0 6 × 7 B c τ c o m u + w p w f w
We can calculate τ c o m when τ J can be obtained by the motor current of joints. The joint positions q and velocities q ˙ are directly accessible through the software interface of the joint, and the measured generalized momentum p can be computed using Equation (3a). Consequently, the output equation of the system is expressed in state-space form with the following measurement equation:
p y = I 7 × 7 0 7 × 6 C c p F l o a d x + v m v
where v m N μ c , m , R c , m represents the measurement noise caused by joint velocity errors due to the high accuracy of the joint position; C c denotes the measurement matrix.
Based on the discretized form of the robotic manipulator’s system Equation (9) and measurement Equation (10), a disturbance Kalman filtering method is derived as [23,24]:
x k + 1 = A k x k + B k u k + w k y k = C k x k + v k
where the relationships between the state transition matrix A k , control input matrix B k , and observation matrix C k are thoroughly derived and analyzed. Notaly, the detailed representation of the matrices describing the discrete-time system can be found in Reference [22]. Given a sampling time of T s , the state matrix A k , the input matrix B k , and the process noise covariance matrix Q k of the discrete-time system dynamics can be described as:
A k B k 0 7 × 13 I 7 × 7 = exp A c B c 0 7 × 13 0 7 × 7 T s
M k 11 M k 12 0 13 × 13 M k 22 = exp A c Q c 0 13 × 13 A c T T s
Q k = M k 12 ( M k 11 ) T
the subscript k on the state-space matrices indicates their values at time k T s . The matrices A k and B k are defined via the matrix exponential [23]:
A k = e A c T s = I 7 × 7 J e T T s 0 6 × 7 I 6 × 6
B k = k T s ( k + 1 ) T s e A c [ ( k + 1 ) T s s ] B c d s = diag T s 1 , , T s n 0 6 × 7
Since the general calculation of the process noise covariance matrix Q k involves the multiplication of Jacobian matrices, its value becomes dependent on the manipulator’s posture. Although this precise computation can enhance filtering accuracy, it demands prohibitive computational resources. Thus, Q k can be expressed as:
Q k = k T s ( k + 1 ) T s e A c [ ( k + 1 ) T s s ] Q c e A c T s d s · ( e A c T s ) T Q c T s = Q c , p T s 0 7 × 6 0 6 × 7 Q c , f T s
In contrast to the system equation, the measurement Equation (10) is not a differential equation. Therefore, its discrete-time measurement matrix C k and measurement noise covariance matrix R k can be readily obtained as:
C k = C c , R k = R c , m T s
By introducing the state vector in the augmented system representation to incorporate external payload dynamics, the payload estimation can be directly derived from the state variables, as follows:
F ^ k = 0 6 × 7 I 6 × 6 x ^ k ,
where external force observation F ^ k essentially corresponds to a component of the state estimate x ^ k after each iteration. Through a finite number of Kalman filter updates, the observer converges to a steady state, yielding the estimated external end-effector load F ^ l o a d . Due to space limitations, implementation details are omitted here; a comprehensive description is provided in [17].

3.2. Establishment of the Variable-Parameter Noise Model

The core objective of the Kalman filter is to produce a state estimate x ^ k that solves the following optimization problem: finding the estimator that minimizes the mean-square estimation error. The solution to this problem relies critically on the accurate specification of the process and measurement noise covariance matrices, Q c and R c . However, in practical robotic systems, the underlying noise statistics are not constant but vary with the system’s operating state (e.g., payload, velocity). A fixed noise model leads to a mismatch between the filter’s internal assumptions and the true, time-varying optimization problem, resulting in degraded performance. Our method, therefore, reformulates the problem as one of adaptive optimization under state-dependent uncertainty. The goal is to dynamically adjust Q c and R c such that the filter’s internal model continuously aligns with the evolving external conditions, thereby consistently pursuing the minimum mean-square error solution across different operational regimes. To facilitate the determination of the noise matrices Q c , p , Q c , f , and R c , m , the system and measurement noises are initially assumed to follow a Gaussian distribution. However, the actual noise may deviate from white Gaussian noise, which can adversely affect the filtering performance. Therefore, we optimize the noise models through a tuning process.

3.2.1. Payload Noise Model

The covariance matrix Q c , f characterizes the uncertainty and disturbance errors between the payload model (8) and the actual end-effector load. Its magnitude quantifies the confidence level of the system in the load model assumption F l o a d = 0 . When no prior knowledge of the payload is available, a fixed noise covariance may hinder accurate load estimation. Under constant load conditions, the system relies strongly on the model, necessitating a small Q c , f . Conversely, during payload changes, the load experiences abrupt variations, resulting in an instantaneous unbounded F l o a d . In such cases, the system exhibits reduced reliance on the payload model, and a larger Q c , f should be used to enhance adaptation to sudden variations.
In theory, real-time monitoring of the external payload allows for the detection of load variations when the change Δ F l o a d exceeds a predefined threshold, triggering the assignment of new parameters to Q c , f . These parameters are subsequently restored once F l o a d stabilizes. However, in practice, identifying an appropriate threshold remains challenging: an excessively large threshold reduces the system’s sensitivity to load changes, while an excessively small one may lead to false alarms or even instability. Moreover, different systems and operating conditions require distinct threshold values. Consequently, a simple switching function proves inadequate for enabling Q c , f to adapt effectively to varying payload conditions. To address this, we introduce a weighted moving average WMA filtering algorithm to optimize the detection of load variations. Let Δ F l o a d at time t be denoted as F t , After determining the window width T, the WMA value of F t at time t can be given by:
F W M A ( t , T ) = 2 i = 0 T 1 ( T i ) F t i T ( T + 1 )
To mitigate the lagging effect induced by linear weight decay, we further implement the hull moving average HMA algorithm, which divides the sampling window into two distinct halves for separate computation within the WMA framework. The HMA value of F t at time t can be expressed as:
F H M A ( t , T ) = F W M A 2 F W M A t , int T 2 F W M A ( t , T ) , int ( T )
where the operator int · denotes the integer function.
Since the payload noise matrix Q c , f exhibits a positive correlation with variations in the payload, we define the optimized load noise model as follows:
Q c , f = L Q F H M A ( t , T )
where the empirical parameter L Q is the base noise of the payload; F H M A ( t , T ) is an adaptive scaling factor for the noise variance at time t.

3.2.2. Dynamic Noise Model

The covariance matrix of the dynamic noise Q c , p primarily characterizes the uncertain disturbance error between the robotic dynamics model (6) and the actual dynamic torques, which arises mainly from incomplete compensation of joint friction such as quasi-static effects. Linderoth et al. [25] proposed that friction noise at different velocities scales by a velocity-dependent coefficient K f = 1 + k q ˙ multiplied by the standard deviation of friction at low speeds. Addressing the nonlinear friction-velocity dependence in low-speed operation, we put forward a new dynamic noise model with the following structure:
K f = 1 + τ f τ l , q ˙ τ f 0 , ε τ f 0 , ε
where τ f 0 , ε represents the mean friction force under no-load conditions at very low velocities, with ε taking values between 0.05 and 0.1 .
Extending to the multi-dimensional space of the robotic manipulator, we define K f as the scaling factor for the noise standard deviation. Thus, the optimized covariance matrix Q c , p can be expressed as:
Q c , p = E w p w p T = R w τ f , θ ˙ = diag K f 2 R w ( 0 , ε )
where E [ · ] denotes the expectation operator; diag { · } represents a diagonal matrix; and R w 0 , ε corresponds to the friction variance of each joint under no-load and ultra-low-speed conditions.

3.2.3. Measurement Noise Model

The measurement noise covariance matrix R c , m primarily characterizes the uncertain disturbance errors during the acquisition of the generalized momentum p . Given p = M q q ˙ and assuming an accurately identified inertial matrix M q in the dynamic model, the measurement noise essentially originates from the sensing of joint position q and velocity q ˙ . In practice, the acquisition precision of position signals is significantly higher than that of velocity signals. Hence, compared to velocity-induced noise, position-dependent noise can be neglected. The uncertainty in momentum measurement is therefore dominated by velocity noise, leading to the following measurement noise model [22]:
R c , m = M q Q q ˙ M T q
where Q q ˙ is a diagonal matrix whose elements correspond to the estimated variances of the velocities in the individual joints.

4. Experimental Results

In this section, we employ a seven-DOF SIASUN collaborative robot (SIASUN Robot & Automation Co., Ltd., Shenyang, China) equipped with a six-axis force/torque sensor Axia 80 (ATI Industrial Automation, USA), as shown in Figure 1, to accomplish the comparative experimental study of unknown constant load estimation for the performance of different payload estimation approaches such as force sensor measurements, direct current estimation, generalized momentum observers, and Kalman-filter-based observers. The hardware of the control system for the robotic arm is a Beckhoff C6320-30 industrial computer (Beckhoff Automation GmbH & Co. KG., Weilburg, Germany) running on the Windows platform. To achieve real-time industrial control, the industrial computer is also equipped with TwinCAT3 automation motion control software based on the TwinCAT NC runtime core, thus transforming the industrial computer into a control system that integrates a logic controller (PLC), motion controller (NC) and I/O. Communication with the Elmo drives of each joint of the robotic arm is achieved through the EtherCAT bus. It should be noted that the inertial parameters (masses, centers of mass, and inertia tensors) for all links of the 7-DOF manipulator were extracted from a high-fidelity computer-aided design (CAD) model of the robot; see Table 1.

4.1. Payload Estimation

To evaluate the performance of the external load observer with the optimized noise model, we designate the Kalman filter (KF)-based observers employing fixed- and variable-parameter noise models as the base Kalman filter BKF observer and optimized Kalman filter OKF observer, respectively. Among the compared methods, the direct current estimation and generalized momentum observer first estimate the external joint torques and then compute the resultant end-effector load. In contrast, the force sensor method, BKF observer, and OKF observer directly measure or estimate the external load. The experimental procedure is structured as follows:
(1) Following a one-hour warm-up period, the manipulator is positioned into the initial configuration depicted in Figure 2a under position control mode, with the payload resting stationary on the table and connected to the end-effector via a cable.
(2) As illustrated in Figure 2b, the end-effector is then commanded to move vertically upward at a velocity of 10 mm/s for 10 seconds until the payload is fully lifted. Force sensor data and observer outputs are recorded throughout the motion. Four payload masses 0.8 kg , 1 kg , 1.2 kg , and 1.5 kg are tested. Although forces and torques in other directions are also influenced by the payload variation, the dominant change manifests primarily in the gravitational direction, and the results are shown in Figure 3. It should be noted that this experiment was designed to compare the performance of different load observers; thus, the analysis focuses exclusively on the response speed and convergence performance during payload lifting. Accordingly, Figure 3 presents only the data segments immediately before and after the payload is lifted.
As shown in Figure 3, aside from the substantial noise in the current-based method that impairs its convergence, the steady-state performance of the three observers is quite similar. Given the presence of certain unmodeled dynamics in the observers, the deviation between their steady-state values and the actual measurements from the force sensor remains within an acceptable range. Therefore, the performance analysis focuses primarily on dynamic characteristics. The unknown constant load can be treated as a step input, and common step response metrics, including rise time, peak time, overshoot, and settling time, are used for evaluation. Additionally, a noticeable reverse peak is observed in the observers at the onset of load variation, likely caused by current noise during contact transition. This contact-induced peak is also considered as a dynamic performance metric. Although the peak emerges from the initial zero baseline, it correlates positively with the overshoot, as seen in Figure 3. We define the contact peak as the percentage ratio of the difference between the peak value and the initial value relative to the steady-state value. The commonly used step response performance metrics are summarized in Table 2, Table 3, Table 4 and Table 5.
A cross-experimental comparison of the dynamic parameters of the four observation methods reveals that, apart from the nearly identical rise times across all methods, the OKF observer consistently achieves the minimum values in all other metrics. Under most operating conditions, the contact peak and overshoot are reduced by at least 20%, while improvements in peak time and settling time remain below 10%. These results demonstrate that the OKF observer exhibits superior dynamic performance compared to alternative methods, characterized by faster response and convergence, reduced overshoot, and diminished contact peaks. This validates the effectiveness and advantages of the OKF-based external load observer. A longitudinal comparison of the dynamic parameters across experimental groups reveals that as the external load mass increases, the observer exhibits faster response speeds but also introduces larger overshoot. Since the observer fundamentally relies on current information, this indicates that the dynamic performance of current-based observation methods is influenced by the load magnitude. Although reducing the observer gain can mitigate overshoot, it concurrently diminishes response speed. Thus, in practical applications, parameter tuning is essential to achieve an optimal balance between response rapidity and overshoot suppression.

4.2. Direct Teaching for Unknown Payload

To bridge the gap between theory and validation and verify the effectiveness of the drag-to-demonstrate strategy based on unknown load compensation at variable speeds 10 mm / s , 25 mm / s , we designed two experimental scenarios: linear drag demonstration and curved drag demonstration, as shown in Figure 4. These were conducted under three experimental conditions: end-effector without load (“no-load condition”), end-effector with load but without load compensation (“load condition”), and end-effector with load and load compensation (“load compensation condition”). During the experiments, the robot arm’s end-effector was dragged to move along the trajectory. A six-axis force sensor was installed at the end-effector, with the drag force primarily manifested as the resultant force in the X and Y directions of the sensor. The force exerted by the load itself on the force sensor was subsequently subtracted from the measurements.
The experimental results of drag forces under various conditions are presented in Table 6. The magnitude of the drag force is characterized by its mean and peak values, while the compliance of the dragging motion is represented by the maximum mean square error. The data in parentheses indicates the percentage difference between the drag force values after load compensation and those before compensation, relative to the difference between the drag forces under loaded and no-load conditions. A negative symbol and a larger absolute value indicate more complete load compensation. It can be observed that for linear drag teaching, the reduction in drag force after load compensation is significant, with the compensated values being very close to those under the no-load condition. For curved-path drag teaching, due to the complexity of the task, the overall compensation effect is slightly inferior to that of linear dragging. Nevertheless, the results still validate the effectiveness of the load compensation strategy during dragging operations.

5. Conclusions

In the paper, we present a novel sensorless disturbance Kalman filter DKF for accurately estimating the different payload exerted on the end-effector of serial robots. The DKF employs a generalized momentum-based dynamic model of robots that incorporates velocity- and load-dependent nonlinear friction, achieving superior performance in external force estimation. A classic Kalman filter framework is adopted to effectively implement the approach. Furthermore, the influence of load, friction, and velocities on noise parameters within the Kalman filtering algorithm is explicitly considered through a variable-parameter modeling of the noise term, thereby enhancing the overall performance and adaptability of the DKF. Comparative experimental results of multiple external load observations for the robotic end-effector demonstrate that the proposed OKF observer achieves significant improvements in dynamic performance, such as response speed and overshoot, over both the BKF observer and other existing methods.
In the design of the external load observer for robotic end-effectors, our study only addresses loads with constant or slowly varying mass, which limits application to highly dynamic scenarios. In practice, loads may change unpredictably in more complex ways. In future work, we will extend this research to more complex and dynamic loading conditions. Moreover, we plan to integrate unidirectional pressure sensors, which could assist in integrating the DKF into a force controller, enabling tasks like collision detection with payloads and assembly.

Author Contributions

Methodology, J.Y., Y.H., S.B. and Z.H.; Data curation, Y.H.; Writing—original draft, R.L.; Writing—review & editing, R.L., J.Y., S.B. and L.D.; Funding acquisition, J.Y. and Z.H. All authors have read and agreed to the published version of the manuscript.

Funding

This research was funded by the National Natural Science Foundation of China under Grant 62403297.

Institutional Review Board Statement

Not applicable.

Informed Consent Statement

Not applicable.

Data Availability Statement

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

Conflicts of Interest

The authors declare no conflicts of interest.

Nomenclature

nNumber of degrees of freedom (DOFs) of the serial robot
qJoint angular position vector
q ˙ Joint angular velocity vector
q ¨ Joint angular acceleration vector
M ( q ) Inertia matrix of the robot
C ( q , q ˙ ) Coriolis and centrifugal matrix
G ( q ) Gravitational torque vector
τ I Torque vector related to inertial dynamics
τ f Joint friction torque vector
τ e x t External disturbance torque vector due to payload
HDiagonal matrix of joint reduction ratios
τ m Motor output torque vector
iMotor current vector
K m Motor torque constant matrix
F l o a d External force/torque vector acting on the end-effector
J e Jacobian matrix of the end-effector
τ f j Friction torque for the j-th joint
f v 1 j , f v 2 j Coefficients of the quadratic term for the viscous friction
f s j Static friction coefficient
f c j Coulomb friction coefficient
v j Stribeck velocity characterizing static friction and Coulomb friction
f l 1 j , f l 2 j , f l 3 j Load-dependent friction coefficients
pGeneralized momentum vector
p ˙ Time derivative of generalized momentum
A f Dynamic characteristic matrix attributed to external wrench
w p Dynamic process noise vector
w f Payload process noise vector
Q c , p Covariance matrix of the dynamic noise distribution of a continuous time system
Q c , f Covariance matrix of the load noise distribution
xAugmented state vector [ p T , F l o a d T ] T
A k , B k , C k Discrete-time state-space matrices
T s Sampling time
Q k , R k Discrete-time process and measurement noise covariance matrices
K f Velocity-dependent friction noise scaling factor
Q c , p Optimized covariance matrix

References

  1. Suomalainen, M.; Karayiannidis, Y.; Kyrki, V. A survey of robot manipulation in contact. Robot. Auton. Syst. 2022, 156, 104224. [Google Scholar] [CrossRef]
  2. Shan, S.; Pham, Q.C. Fine robotic manipulation without force/torque sensor. IEEE Robot. Autom. Lett. 2024, 9, 1206–1213. [Google Scholar] [CrossRef]
  3. Shareef, Z.; Reinhart, F.; Steil, J. Generalizing a learned inverse dynamic model of KUKA LWR IV+ for load variations using regression in the model space. In Proceedings of the 2016 IEEE/RSJ International Conference on Intelligent Robots and Systems (IROS), Daejeon, Republic of Korea, 9–14 October 2016; IEEE: Piscataway, NJ, USA, 2016; pp. 606–611. [Google Scholar]
  4. Shan, S.; Pham, Q.C. Fast Payload Calibration for Sensorless Contact Estimation Using Model Pre-Training. IEEE Robot. Autom. Lett. 2024, 9, 9007–9014. [Google Scholar] [CrossRef]
  5. Taie, W.; ElGeneidy, K.; AL-Yacoub, A.; Ronglei, S. Online Identification of Payload Inertial Parameters Using Ensemble Learning for Collaborative Robots. IEEE Robot. Autom. Lett. 2024, 9, 1350–1356. [Google Scholar] [CrossRef]
  6. Nadeau, P.; Giamou, M.; Kelly, J. Fast Object Inertial Parameter Identification for Collaborative Robots. In Proceedings of the 2022 International Conference on Robotics and Automation (ICRA), Philadelphia, PA, USA, 23–27 May 2022; IEEE: Piscataway, NJ, USA, 2022; pp. 3560–3566. [Google Scholar]
  7. Khalil, W.; Gautier, M.; Lemoine, P. Identification of the payload inertial parameters of industrial manipulators. In Proceedings of the Proceedings 2007 IEEE International Conference on Robotics and Automation, Rome, Italy, 10–14 April 2007; IEEE: Piscataway, NJ, USA, 2007; pp. 4943–4948. [Google Scholar]
  8. Lin, S.T.; Yae, K.H. Identification of Unknown Payload and Environmental Parameters for Robot Compliant Motion. In Proceedings of the 1992 American Control Conference, Chicago, IL, USA, 24–26 June 1992; pp. 2952–2956. [Google Scholar]
  9. Kubus, D.; Kroger, T.; Wahl, F.M. On-line rigid object recognition and pose estimation based on inertial parameters. In Proceedings of the 2007 IEEE/RSJ International Conference on Intelligent Robots and Systems, San Diego, CA, USA, 29 October–2 November 2007; IEEE: Piscataway, NJ, USA, 2007; pp. 1402–1408. [Google Scholar]
  10. Haddadin, S.; De Luca, A.; Albu-Schäffer, A. Robot Collisions: A Survey on Detection, Isolation, and Identification. IEEE Trans. Robot. 2017, 33, 1292–1312. [Google Scholar] [CrossRef]
  11. Merces, L.; de Oliveira, R.F.; Bof Bufon, C.C. Nanoscale Variable-Area Electronic Devices: Contact Mechanics and Hypersensitive Pressure Application. ACS Appl. Mater. Interfaces 2018, 10, 39168–39176. [Google Scholar] [CrossRef] [PubMed]
  12. Dong, Y.; Ren, T.; Chen, K.; Wu, D. An efficient robot payload identification method for industrial application. Ind. Robot. Int. J. Robot. Res. Appl. 2018, 45, 505–515. [Google Scholar] [CrossRef]
  13. Salah, S.; Sandoval, J.; Ghiss, M.; Laribi, M.A.; Zeghloul, S. Online Payload Identification of a Franka Emika Robot for Medical Applications. In Advances in Service and Industrial Robotics; Springer: Cham, Switzerland, 2020; pp. 130–136. [Google Scholar]
  14. Gaz, C.; De Luca, A. Payload estimation based on identified coefficients of robot dynamics — With an application to collision detection. In Proceedings of the 2017 IEEE/RSJ International Conference on Intelligent Robots and Systems (IROS), Vancouver, BC, Canada, 24–28 September 2017; IEEE: Piscataway, NJ, USA, 2017; pp. 3033–3040. [Google Scholar]
  15. Huang, Q.; Zhang, X.; Pan, H.; Cheng, Y.; Lu, K. Offsets and Gravity Parameters Estimation for Noncontact Force Compensation With Wrist-Mounted Force/Torque Sensor. IEEE Sens. J. 2024, 24, 30575–30583. [Google Scholar] [CrossRef]
  16. Kurdas, A.; Hamad, M.; Vorndamme, J.; Mansfeld, N.; Abdolshah, S.; Haddadin, S. Online Payload Identification for Tactile Robots Using the Momentum Observer. In Proceedings of the 2022 International Conference on Robotics and Automation (ICRA), Philadelphia, PA, USA, 23–27 May 2022; IEEE: Piscataway, NJ, USA, 2022; pp. 5953–5959. [Google Scholar]
  17. Wahrburg, A.; Morara, E.; Cesari, G.; Matthias, B.; Ding, H. Cartesian contact force estimation for robotic manipulators using Kalman filters and the generalized momentum. In Proceedings of the 2015 IEEE International Conference on Automation Science and Engineering (CASE), Gothenburg, Sweden, 24–28 August 2015; IEEE: Piscataway, NJ, USA, 2015; pp. 1230–1235. [Google Scholar]
  18. He, Y.; Wang, C.; Bao, S.; Yuan, J.; Du, L.; Ma, S.; Wan, W. A Joint Friction Model of Robotic Manipulator for Low-speed Motion. In Proceedings of the 2021 IEEE International Conference on Robotics and Biomimetics (ROBIO), Sanya, China, 27–31 December 2021; IEEE: Piscataway, NJ, USA, 2021; pp. 545–550. [Google Scholar]
  19. Luo, R.; Yuan, J.; Hu, Z.; Du, L.; Bao, S.; Zhou, M. Lie-theory-based dynamic model identification of serial robots considering nonlinear friction and optimal excitation trajectory. Robotica 2024, 42, 3552–3569. [Google Scholar] [CrossRef]
  20. Hu, J.; Xiong, R. Contact Force Estimation for Robot Manipulator Using Semiparametric Model and Disturbance Kalman Filter. IEEE Trans. Ind. Electron. 2018, 65, 3365–3375. [Google Scholar] [CrossRef]
  21. Spong, M.W.; Hutchinson, S.; Vidyasagar, M. Robot Modeling and Control; John Wiley: Hoboken, NJ, USA, 2020. [Google Scholar]
  22. Wahrburg, A.; Bös, J.; Listmann, K.D.; Dai, F.; Matthias, B.; Ding, H. Motor-Current-Based Estimation of Cartesian Contact Forces and Torques for Robotic Manipulators and Its Application to Force Control. IEEE Trans. Autom. Sci. Eng. 2018, 15, 879–886. [Google Scholar] [CrossRef]
  23. Van Loan, C. Computing integrals involving the matrix exponential. IEEE Trans. Autom. Control 1978, 23, 395–404. [Google Scholar] [CrossRef]
  24. Axelsson, P.; Gustafsson, F. Discrete-Time Solutions to the Continuous-Time Differential Lyapunov Equation with Applications to Kalman Filtering. IEEE Trans. Autom. Control 2015, 60, 632–643. [Google Scholar] [CrossRef]
  25. Linderoth, M.; Stolt, A.; Robertsson, A.; Johansson, R. Robotic force estimation using motor torques and modeling of low velocity friction disturbances. In Proceedings of the 2013 IEEE/RSJ International Conference on Intelligent Robots and Systems, Tokyo, Japan, 3–7 November 2013; IEEE: Piscataway, NJ, USA, 2013; pp. 3550–3556. [Google Scholar]
Figure 1. Experimental Setup: the seven-DOF collaborative robot from SINSUN is equipped with a Beckhoff C6320-30 industrial PC running the Windows platform.
Figure 1. Experimental Setup: the seven-DOF collaborative robot from SINSUN is equipped with a Beckhoff C6320-30 industrial PC running the Windows platform.
Actuators 14 00568 g001
Figure 2. External load observation experiment: (a) initial state; (b) motion state.
Figure 2. External load observation experiment: (a) initial state; (b) motion state.
Actuators 14 00568 g002
Figure 3. External load observation results of different methods: (a) load of 0.8 kg; (b) load of 1 kg; (c) load of 1.2 kg; (d) load of 1.5 kg.
Figure 3. External load observation results of different methods: (a) load of 0.8 kg; (b) load of 1 kg; (c) load of 1.2 kg; (d) load of 1.5 kg.
Actuators 14 00568 g003
Figure 4. Drag-teaching experiments under unknown load conditions: (a) linear drag teaching; (b) curvilinear drag teaching.
Figure 4. Drag-teaching experiments under unknown load conditions: (a) linear drag teaching; (b) curvilinear drag teaching.
Actuators 14 00568 g004
Table 1. Inertial parameters of the robot.
Table 1. Inertial parameters of the robot.
Link i m i P c , i I xx , i I yy , i I zz , i I xy , i I xz , i I yz , i
17.079[0,0.001,−0.022]0.0350.0370.024000.001
24.966[0,−0.176,0.019]0.0460.0180.043000.012
34.001[0,0.005,−0.02]0.0160.0160.01000.001
44.889[0,−0.183,0.02]0.0440.0170.04000.012
51.281[0,0.049,−0.071]0.0080.0130.008000.002
64.178[0,−0.045,0.021]0.0180.0090.015000.004
70.371[0,−0.002,−0.022]000.001000
Note:  m i is the mass of link i (kg); P c , i corresponds to the center of mass position vector (m); I i is the inertia tensor matrix (kg·m2) with respect to the link frame.
Table 2. Primary performance metrics for 0.8 kg external payload observation.
Table 2. Primary performance metrics for 0.8 kg external payload observation.
Observation MethodContact Peak (%)Rise Time(s)Peak Time(s)Overshoot (%)Settling Time(s)
Current-based Estimation18.20.320.7525.7/
Generalized Momentum Observer11.60.310.479.121.55
BKF Observer6.750.320.467.621.54
OKF Observer our method 3.62 ( 46 %)0.32 (0%) 0.43 ( 6 %) 6.12 ( 20 %) 1.38 ( 10 %)
Table 3. Primary performance metrics for 1.0 kg external payload observation.
Table 3. Primary performance metrics for 1.0 kg external payload observation.
Observation MethodContact Peak (%)Rise Time(s)Peak Time(s)Overshoot (%)Settling Time(s)
Current-based Estimation7.250.290.5926.8/
Generalized Momentum Observer10.80.300.7212.12.47
BKF Observer9.720.300.8711.52.39
OKF Observer our method 1.64 ( 83 %) 0.29 ( 3 %) 0.56 ( 36 %) 11.3 ( 2 %) 1.98 ( 17 %)
Table 4. Primary performance metrics for 1.2 kg external payload observation.
Table 4. Primary performance metrics for 1.2 kg external payload observation.
Observation MethodContact Peak (%)Rise Time(s)Peak Time(s)Overshoot (%)Settling Time(s)
Current-based Estimation21.20.230.48149/
Generalized Momentum Observer80.20.230.411331.72
BKF Observer33.90.230.391141.68
OKF Observer our method 7.03 ( 79 %) 0.23 ( 0 %) 0.36 ( 7 %) 94.6 ( 17 %) 1.63 ( 3 %)
Table 5. Primary performance metrics for 1.5 kg external payload observation.
Table 5. Primary performance metrics for 1.5 kg external payload observation.
Observation MethodContact Peak (%)Rise Time(s)Peak Time(s)Overshoot (%)Settling Time(s)
Current-based Estimation1130.210.53273/
Generalized Momentum Observer56.10.200.421811.55
BKF Observer28.60.200.401491.48
OKF Observer our method 11.6 ( 59 %) 0.20 ( 0 %) 0.36 ( 10 %) 104 ( 30 %) 1.39 ( 6 %)
Table 6. Experimental results of drag force in drag-teaching experiments with unknown load.
Table 6. Experimental results of drag force in drag-teaching experiments with unknown load.
Linear Drag TeachingCurvilinear Drag Teaching
No-LoadLoadLoad CompensationNo-LoadLoadLoad Compensation
Mean Value (N)12.419.414.0 (−77.1%)18.526.320.0 (−80.8%)
Peak Value (N)15.931.716.4 (−96.8%)29.443.634.8 (−62.0%)
Max MSE (N)4.2713.63.85 (−104%)12.817.916.2 (−33.3%)
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

Luo, R.; Yuan, J.; He, Y.; Bao, S.; Du, L.; Hu, Z. Sensorless Payload Estimation of Serial Robots Using an Improved Disturbance Kalman Filter with a Variable-Parameter Noise Model. Actuators 2025, 14, 568. https://doi.org/10.3390/act14120568

AMA Style

Luo R, Yuan J, He Y, Bao S, Du L, Hu Z. Sensorless Payload Estimation of Serial Robots Using an Improved Disturbance Kalman Filter with a Variable-Parameter Noise Model. Actuators. 2025; 14(12):568. https://doi.org/10.3390/act14120568

Chicago/Turabian Style

Luo, Ruiqing, Jianjun Yuan, Yimin He, Sheng Bao, Liang Du, and Zhengtao Hu. 2025. "Sensorless Payload Estimation of Serial Robots Using an Improved Disturbance Kalman Filter with a Variable-Parameter Noise Model" Actuators 14, no. 12: 568. https://doi.org/10.3390/act14120568

APA Style

Luo, R., Yuan, J., He, Y., Bao, S., Du, L., & Hu, Z. (2025). Sensorless Payload Estimation of Serial Robots Using an Improved Disturbance Kalman Filter with a Variable-Parameter Noise Model. Actuators, 14(12), 568. https://doi.org/10.3390/act14120568

Note that from the first issue of 2016, this journal uses article numbers instead of page numbers. See further details here.

Article Metrics

Article metric data becomes available approximately 24 hours after publication online.
Back to TopTop