Abstract In industrial robotics, precise force sensing is critical for robotic polishing of complex parts. This paper presents a gravity compensation method for six-dimensional force sensors at the end of an industrial robot. The approach combines least squares method and particle swarm optimization (PSO) to eliminate the influence of end-load gravity, sensor zero drift, and tool installation angles. Experimental results show that after static compensation, the force error remains within ±1N and the torque error within ±0.05N·m. For dynamic compensation with varying tool angles, the force error stabilizes within ±1N, verifying the method’s effectiveness in enhancing external contact force perception for industrial robots.

Keywords: industrial robot; gravity compensation; six-dimensional force sensor; particle swarm optimization; Euler angle
1. Introduction
Industrial robots have gained widespread application in grinding and polishing complex parts due to their flexibility and precision . However, accurate measurement of external contact forces is challenged by end-load gravity, sensor zero drift, and tool installation variations. Traditional methods often neglect sensor mounting angles or require complex equipment, limiting their robustness .
Existing studies, such as Li et al. (2021), used genetic algorithms to optimize gravity compensation but required special tool postures . Zhang et al. (2021) employed least squares for parameter estimation but faced complexity in implementation . Duan et al. (2022) introduced acceleration sensors, but this approach is limited to specialized hardware . None of these methods fully address the impact of tool installation angles on compensation accuracy.
This paper proposes a novel gravity compensation method for industrial robots. By integrating least squares for parameter estimation and PSO for sensor angle optimization, the method dynamically compensates for gravity effects under varying tool postures. The key innovations include:
- Simultaneous calibration of sensor zero points, load gravity, and centroid position using multi-posture data.
- PSO-based optimization of sensor mounting angles to reduce installation errors.
- Real-time compensation for tool installation angles to enhance force sensing accuracy in complex polishing tasks.
2. Mathematical Model for Gravity Compensation
2.1 Force and Torque Relationships in Six-Dimensional Sensors
The six-dimensional force sensor measures three orthogonal forces and torques. In static or low-speed conditions, the sensor data can be decomposed into load gravity, zero drift, and actual polishing forces . Let \([F_x, F_y, F_z]\) and \([M_x, M_y, M_z]\) denote the measured forces and torques, with zero drift values \([F_{x0}, F_{y0}, F_{z0}]\) and \([M_{x0}, M_{y0}, M_{z0}]\). The load gravity G and its centroid coordinates \((x, y, z)\) in the sensor coordinate system satisfy:
\(\begin{cases} G_x = F_x – F_{x0} \\ G_y = F_y – F_{y0} \\ G_z = F_z – F_{z0} \end{cases} \quad \text{(1)}\)
\(\begin{cases} M_{gx} = M_x – M_{x0} = G_z \cdot y – G_y \cdot z \\ M_{gy} = M_y – M_{y0} = G_x \cdot z – G_z \cdot x \\ M_{gz} = M_z – M_{z0} = G_y \cdot x – G_x \cdot y \end{cases} \quad \text{(2)}\)
Combining (1) and (2), the torque equations can be rewritten as:
\(\begin{bmatrix} M_x \\ M_y \\ M_z \end{bmatrix} = \begin{bmatrix} 0 & F_z & -F_y & 1 & 0 & 0 \\ -F_z & 0 & F_x & 0 & 1 & 0 \\ F_y & -F_x & 0 & 0 & 0 & 1 \end{bmatrix} \begin{bmatrix} x \\ y \\ z \\ k_1 \\ k_2 \\ k_3 \end{bmatrix} \quad \text{(3)}\)
where \(k_1 = M_{x0} + F_{y0}z – F_{z0}y\), \(k_2 = M_{y0} + F_{z0}x – F_{x0}z\), \(k_3 = M_{z0} + F_{x0}y – F_{y0}x\).
Using the least squares method, the parameters \(p = [x, y, z, k_1, k_2, k_3]^T\) are estimated as:
\(p = (F^T F)^{-1} F^T m \quad \text{(4)}\)
where m is the vector of measured torques, and F is the coefficient matrix from equation (3) .
2.2 Robot Coordinate System Transformations
The robot’s coordinate systems include the base frame \(O_0\), sensor frame \(O_1\), and tool frame \(O_2\). The sensor frame is derived from the base frame via Euler angles \((\alpha, \beta, \gamma)\) (Z-Y-Z convention). The rotation matrix from \(O_1\) to \(O_0\) is:
\(^0_1 R = \text{Rot}(z, \alpha) \cdot \text{Rot}(y, \beta) \cdot \text{Rot}(z, \gamma) \quad \text{(5)}\)
where:
\(\text{Rot}(z, \theta) = \begin{bmatrix} \cos\theta & -\sin\theta & 0 \\ \sin\theta & \cos\theta & 0 \\ 0 & 0 & 1 \end{bmatrix}, \quad \text{Rot}(y, \theta) = \begin{bmatrix} \cos\theta & 0 & \sin\theta \\ 0 & 1 & 0 \\ -\sin\theta & 0 & \cos\theta \end{bmatrix}\)
Gravity in the base frame is \(g_0 = [0, 0, -G]^T\). Transforming to the sensor frame:
\(g_1 = {}^0_1 R^T g_0 \quad \text{(6)}\)
The force components in the sensor frame are:
\(\begin{bmatrix} F_x \\ F_y \\ F_z \end{bmatrix} = {}^0_1 R \begin{bmatrix} 0 \\ 0 \\ -G \end{bmatrix} + \begin{bmatrix} F_{x0} \\ F_{y0} \\ F_{z0} \end{bmatrix} \quad \text{(7)}\)
For N robot postures, equation (7) forms a system solvable by least squares to obtain G, \(F_{x0}\), \(F_{y0}\), and \(F_{z0}\) .
2.3 Sensor Mounting Angle Optimization via Particle Swarm Optimization (PSO)
Due to mechanical errors, the sensor frame may have mounting angles relative to the robot flange. Assuming rotations around the Z and Y axes (angles \(\alpha\) and \(\beta\)), the transformation matrix is:
\(T = \begin{bmatrix} \cos\alpha\cos\beta & -\sin\alpha & \cos\alpha\sin\beta \\ \sin\alpha\cos\beta & \cos\alpha & \sin\alpha\sin\beta \\ -\sin\beta & 0 & \cos\beta \end{bmatrix} \quad \text{(8)}\)
The objective is to minimize the sum of squared errors (SSE) between measured and compensated forces:
\(\gamma(\alpha, \beta) = \sum_{i=1}^N \left( (F_{xi} – F_{x0} – g_{2xi})^2 + (F_{yi} – F_{y0} – g_{2yi})^2 + (F_{zi} – F_{z0} – g_{2zi})^2 \right) \quad \text{(9)}\)
where \(g_{2x}, g_{2y}, g_{2z}\) are gravity components in the sensor frame after alignment. PSO iteratively updates particle velocities and positions to find the optimal \((\alpha, \beta)\) that minimizes \(\gamma\) .
The PSO update equations are:\(v_i^{t+1} = \omega v_i^t + c_1 r_1 (pbest_i^t – x_i^t) + c_2 r_2 (gbest^t – x_i^t) \quad \text{(10)}\)\(x_i^{t+1} = x_i^t + v_i^{t+1} \quad \text{(11)}\) where \(\omega\) is the inertia weight, \(c_1, c_2\) are learning factors, and \(r_1, r_2\) are random numbers in [0,1].
2.4 Tool Installation Angle Compensation
For different tool postures defined by Euler angles \((A, B, C)\), the tool-to-base rotation matrix is:
\(^0_2 R = \text{Rot}(z, A) \cdot \text{Rot}(y, B) \cdot \text{Rot}(z, C) \quad \text{(12)}\)
The gravity components in the sensor frame, accounting for tool angles, are:
\(\begin{bmatrix} g_{3x} \\ g_{3y} \\ g_{3z} \end{bmatrix} = T^T \cdot {}^0_2 R \cdot \begin{bmatrix} g_x \\ g_y \\ g_z \end{bmatrix} \quad \text{(13)}\)
This allows real-time compensation for varying tool orientations during polishing .
3. Experimental Validation
3.1 Experimental Setup
The experiment uses a Kawasaki RS020N industrial robot and an ATI Delta SI-660-60 six-dimensional force sensor. The robot executes six different postures (Table 1), with 1000 data points collected per posture to compute average forces and torques .
Table 1. Robot Postures and Euler Angles
Posture | \(\alpha\) (°) | \(\beta\) (°) | \(\gamma\) (°) |
---|---|---|---|
1 | -179.960 | 85.362 | -35.598 |
2 | -91.398 | 179.184 | 88.600 |
3 | -0.620 | 89.839 | 179.810 |
4 | -115.523 | 0.477 | -64.472 |
5 | 89.998 | 90.936 | 89.793 |
6 | -154.608 | 144.128 | -165.311 |
3.2 Static Compensation Results
Using least squares, the estimated parameters are:
- Load gravity \(G = 76.8773 \, \text{N}\)
- Centroid coordinates \((x, y, z) = (-0.00006 \, \text{m}, 0.0054 \, \text{m}, 0.0601 \, \text{m})\)
- Sensor zero drift: \(F_{x0} = 2.3583 \, \text{N}\), \(F_{y0} = -4.9745 \, \text{N}\), \(F_{z0} = 4.0776 \, \text{N}\) (Table 2) .
Table 2. Sensor Zero Drift Values
Parameter | Value (N or N·m) |
---|---|
\(F_{x0}\) | 2.3583 |
\(F_{y0}\) | -4.9745 |
\(F_{z0}\) | 4.0776 |
\(M_{x0}\) | -0.4786 |
\(M_{y0}\) | -0.9727 |
\(M_{z0}\) | 0.2399 |
After static compensation, the force error is within ±2.5N. With PSO-optimized sensor angles (\(\alpha = 1.53^\circ\), \(\beta = -1.7^\circ\)), the error reduces to ±1N, and torque error to ±0.05N·m (Table 3) .
Table 3. Static Compensation Errors
Posture | \(\Delta F_x\) (N) | \(\Delta F_y\) (N) | \(\Delta F_z\) (N) | \(\Delta M_x\) (N·m) | \(\Delta M_y\) (N·m) | \(\Delta M_z\) (N·m) |
---|---|---|---|---|---|---|
1 | -1.3295 | 1.7227 | 1.0260 | -0.1930 | -0.0899 | -0.0128 |
2 | -0.8782 | -0.3877 | 0.1587 | 0.0189 | -0.2128 | 0.0193 |
3 | 0.0453 | -1.8373 | -1.4797 | 0.0825 | 0.0040 | 0.0193 |
4 | 1.2243 | 1.5125 | -0.2882 | -0.2012 | 0.1859 | -0.0116 |
5 | 1.5924 | 1.0561 | -2.1535 | -0.0719 | 0.2470 | -0.0219 |
6 | -1.1230 | -2.4299 | 0.8946 | 0.1416 | -0.0777 | 0.0104 |
3.3 Dynamic Compensation with Tool Angles
Six tool postures (Table 4) are tested to evaluate dynamic compensation. The results show that ignoring tool angles leads to large errors, while the proposed method maintains force errors within ±1N for all postures .
Table 4. Tool Installation Angles
Posture | A (°) | B (°) | C (°) |
---|---|---|---|
1 | 25 | 45 | 105 |
2 | 30 | 30 | 30 |
3 | 45 | 45 | 45 |
4 | 60 | 45 | 150 |
5 | 75 | 35 | 180 |
6 | 60 | 90 | 135 |
3.4 External Force Sensing Experiment
To validate contact force perception, six different loads (Table 5) are attached to the robot end-effector. The measured forces and estimated loads show errors within ±1N, confirming the method’s accuracy .
Table 5. External Loads and Sensing Errors
Load Type | Actual Gravity (N) | Measured Gravity (N) | Error (N) |
---|---|---|---|
Flat Panel | 5.380 | 5.955 | +0.575 |
Circular Tube | 7.540 | 7.656 | +0.116 |
Elliptical Tube | 1.913 | 1.713 | -0.200 |
Large Blade | 19.322 | 19.139 | -0.183 |
Small Blade | 8.455 | 8.268 | -0.187 |
Copper Rod | 13.366 | 13.978 | +0.612 |
4. Error Analysis
4.1 Sensor Noise Impact
The sensor’s random noise, characterized by 极差 (range) and 标准差 (standard deviation), affects force measurements more significantly than torques (Table 6). For example, \(F_z\) has a range of 0.0776N, contributing to force error variability .
Table 6. Sensor Data Noise Statistics
Parameter | Range (D) | Standard Deviation (σ) |
---|---|---|
\(F_x\) | 0.029691 | 0.009231 |
\(F_y\) | 0.006209 | 0.001715 |
\(F_z\) | 0.077644 | 0.023167 |
\(M_x\) | 0.000484 | 0.000159 |
\(M_y\) | 0.000244 | 0.000050 |
\(M_z\) | 0.004163 | 0.001370 |
4.2 Euler Angle Errors
Euler angles \(\beta\) and \(\gamma\) introduce non-linear errors in force compensation. Experimental results show that errors first decrease then increase with angle deviations, with minimal errors at \(\beta = 1.1^\circ\) and \(\gamma = 0.9^\circ\) .
5. Conclusion
This paper presents an effective gravity compensation method for industrial robots in complex part polishing. By integrating least squares for parameter estimation and PSO for sensor angle optimization, the method achieves high precision in both static and dynamic conditions. Key findings include:
- Static compensation reduces force errors to ±1N and torque errors to ±0.05N·m.
- Dynamic compensation with tool angle consideration maintains force errors within ±1N, outperforming traditional methods.
- Sensor noise and Euler angle errors are identified as primary error sources, with mitigation strategies proposed.
The method’s advantages include reduced dependency on specialized equipment, improved robustness to tool posture changes, and enhanced force sensing accuracy, making it suitable for industrial applications requiring precise contact force control in robotic polishing.