In modern industrial automation, the demand for high-precision tasks such as drilling, assembly, polishing, and drag teaching necessitates real-time monitoring of the interaction forces between robot end-effectors and the environment. The integration of a six-axis force sensor at the robot wrist enables the detection of three-dimensional forces and moments, providing critical feedback for adaptive control and motion correction. However, accurate force measurement is challenged by factors like gravitational effects of the end-effector, sensor zero-point drift, and installation misalignments. Traditional static calibration methods, while precise under specific conditions, fail to account for zero-drift phenomena that occur due to power cycles, environmental changes, or sensor reassembly. This paper proposes an online calibration approach for six-axis force sensors in industrial robots, focusing on real-time compensation of gravitational forces and zero-point variations. By leveraging kinematic parameters and time-series control, our method ensures robust force detection under dynamic operating conditions.
The six-axis force sensor measures orthogonal forces and moments in space, represented as $[F_x, F_y, F_z, M_x, M_y, M_z]^T$. The sensor output comprises three components: the sensor’s zero-point error $[F_{0x}, F_{0y}, F_{0z}, M_{0x}, M_{0y}, M_{0z}]^T$, which drifts over time; the gravitational force of the end-effector $[F_{Gx}, F_{Gy}, F_{Gz}, M_{Gx}, M_{Gy}, M_{Gz}]^T$, which varies with pose; and the external force $[F_{ex}, F_{ey}, F_{ez}, M_{ex}, M_{ey}, M_{ez}]^T$. The relationship is expressed as:
$$
\begin{aligned}
F_x &= F_{0x} + F_{Gx} + F_{ex} \\
F_y &= F_{0y} + F_{Gy} + F_{ey} \\
F_z &= F_{0z} + F_{Gz} + F_{ez} \\
M_x &= M_{0x} + M_{Gx} + M_{ex} \\
M_y &= M_{0y} + M_{Gy} + M_{ey} \\
M_z &= M_{0z} + M_{Gz} + M_{ez}
\end{aligned}
$$
To address this, we establish coordinate systems for the robot base, end-effector, and sensor. The world coordinate system $G$ is defined with $Z_0$ vertically upward, while the base coordinate system $B$ is derived by rotating $G$ by angles $U$ and $V$ around $Y_0$ and $X_0$, respectively. The transformation matrix is:
$$
^B_GR =
\begin{bmatrix}
1 & 0 & 0 \\
0 & \cos U & -\sin U \\
0 & \sin U & \cos U
\end{bmatrix}
\cdot
\begin{bmatrix}
\cos V & 0 & \sin V \\
0 & 1 & 0 \\
-\sin V & 0 & \cos V
\end{bmatrix}
$$
The end-effector coordinate system $T$ relative to $B$ is obtained through forward kinematics, and the sensor coordinate system $S$ relative to $T$ is fixed based on mounting configuration. The composite rotation matrix from $S$ to $G$ is:
$$
^G_SR = ^G_BR \cdot ^B_TR \cdot ^T_SR
$$
The gravitational force $G$ in world coordinates is $[0, 0, -G]^T$, with zero moment $[0, 0, 0]^T$. Using Cartesian transformation, the force and moment in sensor coordinates are:
$$
\begin{bmatrix}
^SF_S \\
^SM_S
\end{bmatrix}
=
\begin{bmatrix}
^S_GR & 0 \\
^SP_G \times ^S_GR & ^S_GR
\end{bmatrix}
\cdot
\begin{bmatrix}
^GF_G \\
^GM_G
\end{bmatrix}
$$
where $^SP_G \times$ is the skew-symmetric matrix of the center of gravity coordinates $[p_x, p_y, p_z]^T$ in $S$:
$$
^SP_G \times =
\begin{bmatrix}
0 & -p_z & p_y \\
p_z & 0 & -p_x \\
-p_y & p_x & 0
\end{bmatrix}
$$
Simplifying, the moment equation becomes:
$$
^SM_S = ^SP_G \times ^SF_G
$$
which expands to:
$$
\begin{aligned}
M_{Gx} &= G_x \cdot p_y – G_y \cdot p_z \\
M_{Gy} &= G_x \cdot p_z – G_z \cdot p_x \\
M_{Gz} &= G_y \cdot p_x – G_x \cdot p_y
\end{aligned}
$$
Combining with sensor data, we derive a linear system for parameter identification:
$$
\begin{bmatrix}
M_x \\
M_y \\
M_z
\end{bmatrix}
=
\begin{bmatrix}
1 & 0 & 0 & 0 & F_z & -F_y \\
0 & 1 & 0 & -F_z & 0 & F_x \\
0 & 0 & 1 & F_y & -F_x & 0
\end{bmatrix}
\cdot
\begin{bmatrix}
k_1 \\
k_2 \\
k_3 \\
p_x \\
p_y \\
p_z
\end{bmatrix}
$$
where $k_1$, $k_2$, $k_3$ are constants incorporating zero-point moments. Using least squares with $N \geq 3$ pose samples, we solve for $P$:
$$
P = (F(N)^T F(N))^{-1} F(N)^T M_S(N)
$$
Similarly, for force components:
$$
\begin{bmatrix}
F_x \\
F_y \\
F_z
\end{bmatrix}
= [^T_SR^T \cdot ^B_TR^T \quad I] \cdot
\begin{bmatrix}
k_4 \\
k_5 \\
k_6 \\
F_{0x} \\
F_{0y} \\
F_{0z}
\end{bmatrix}
$$
where $k_4 = G \cos U \sin V$, $k_5 = -G \sin U$, $k_6 = -G \cos U \cos V$. Least squares estimation yields:
$$
Q = (R(N)^T R(N))^{-1} R(N)^T F_S(N)
$$
From $k_4$, $k_5$, $k_6$, we compute the gravitational force $G$ and installation angles $U$, $V$:
$$
G = \sqrt{k_4^2 + k_5^2 + k_6^2}
$$
$$
U = \arcsin\left(-\frac{k_5}{G}\right), \quad V = \arctan\left(-\frac{k_4}{k_6}\right)
$$
Once $G$, $p_x$, $p_y$, $p_z$, $U$, and $V$ are identified, online compensation is performed using time-series control. The process divides into zero-point calibration ($0$ to $T_1$) and gravity compensation ($T_1$ to $T_2$). At time $t$ in $0$–$T_1$, the sensor output is:
$$
\begin{bmatrix}
F(t) \\
M(t)
\end{bmatrix}
=
\begin{bmatrix}
^SF_G(t) \\
^SM_G(t)
\end{bmatrix}
+
\begin{bmatrix}
F_0(t) \\
M_0(t)
\end{bmatrix}
$$
where $[^SF_G(t), ^SM_G(t)]^T$ is computed from real-time kinematics. The zero-point $[F_0, M_0]^T$ is assumed constant post-calibration. For $k$ in $T_1$–$T_2$, the compensated external force is:
$$
\begin{bmatrix}
F_e(k) \\
M_e(k)
\end{bmatrix}
=
\begin{bmatrix}
F(k) \\
M(k)
\end{bmatrix}
–
\begin{bmatrix}
^SF_G(k) \\
^SM_G(k)
\end{bmatrix}
–
\begin{bmatrix}
F_0 \\
M_0
\end{bmatrix}
$$
This ensures accurate detection of external forces despite zero-drift.

Experimental validation used a six-axis force sensor with ranges of 500 N for forces and 12 N·m for moments, connected to an embedded industrial computer via EtherCAT. The robot’s D-H parameters are listed in Table 1. The online method was tested under multiple power cycles to evaluate zero-drift compensation. Static calibration results showed significant zero-point variations, with $F_{0x}$ drifting up to 1 N, as summarized in Table 2. In contrast, the online approach eliminated these errors by continuously updating compensation parameters.
| Joint | $\theta_i$ | $d_i$ (m) | $a_i$ (m) | $\alpha_i$ |
|---|---|---|---|---|
| 1 | $\theta_1$ | 0.320 | 0.0499 | $-\pi/2$ |
| 2 | $\theta_2$ | 0 | 0.270 | 0 |
| 3 | $\theta_3$ | 0 | 0.0704 | $-\pi/2$ |
| 4 | $\theta_4$ | 0.2991 | 0 | $\pi/2$ |
| 5 | $\theta_5$ | 0 | 0 | $-\pi/2$ |
| 6 | $\theta_6$ | 0.0785 | 0 | 0 |
Using 17 end-effector poses, we identified $U = 0.105^\circ$, $V = 0.125^\circ$, $G = 4.3053$ N, and $[p_x, p_y, p_z]^T = [0.0037, -0.0001, -0.0753]^T$ m. During dynamic pose changes, the sensor output and compensation values were symmetric around the time axis, with errors near zero, confirming effective online compensation. Further tests involved polishing tasks with constant (27.8 N) and variable ($27.8 + 5\sin t$ N) forces. The six-axis force sensor tracked these forces accurately, with minimal deviation after transient phases, demonstrating the method’s practicality for industrial applications.
| Parameter | $F_{0x}$ | $F_{0y}$ | $F_{0z}$ | $M_{0x}$ | $M_{0y}$ | $M_{0z}$ |
|---|---|---|---|---|---|---|
| Range $\epsilon$ | 1.98 | 1.05 | 0.86 | 0.01 | 0.01 | 0.01 |
| Mean $a$ | 4.498 | -2.706 | 38.13 | -0.246 | -0.183 | 0.098 |
| Std Dev $\sigma$ | 0.462 | 0.264 | 0.153 | 0.005 | 0.005 | 0.005 |
In conclusion, the online calibration method for six-axis force sensors effectively compensates for gravitational effects and zero-point drift in industrial robots. By integrating real-time kinematics and time-series control, it outperforms static approaches in dynamic environments. Experiments validate its robustness for force detection in tasks like polishing, ensuring high precision in robotic automation. Future work will extend this to high-speed operations and multi-sensor fusion.
