Gravity Compensation for Six-Axis Force Sensor at Robot Base

In robotics, the six-axis force sensor is a critical component for measuring forces and moments in three-dimensional space, enabling precise control in applications such as human-robot interaction and assembly tasks. When installed at the robot base, the six-axis force sensor is subjected to errors induced by the robot’s own weight and installation inaccuracies, necessitating robust compensation methods. This paper addresses these challenges by developing a static gravity compensation algorithm based on the Denavit-Hartenberg (D-H) method and least squares optimization. We introduce an orthogonal experimental design to efficiently sample robot postures, reducing the data collection burden while maintaining accuracy. Through a case study on a six-degree-of-freedom (DOF) collaborative robot, we demonstrate the algorithm’s effectiveness in deriving a compensation matrix that minimizes measurement errors. The integration of mathematical modeling, experimental design, and validation highlights the practicality of our approach for real-world implementations.

The six-axis force sensor measures three force components (Fx, Fy, Fz) and three moment components (Mx, My, Mz), but its readings can be distorted by the gravitational forces of the robot’s links and the sensor’s alignment relative to the base coordinate system. Traditional calibration methods often focus on end-effector-mounted sensors, leaving a gap for base-mounted configurations. Our work fills this gap by deriving a universal compensation algorithm that accounts for static gravitational effects across various robot postures. We leverage the D-H parameterization to model robot kinematics, establish gravity equations, and apply least squares to solve for the compensation matrix. The orthogonal experiment method ensures that a minimal set of representative postures is used, optimizing the calibration process. This comprehensive approach not only enhances measurement accuracy but also supports advanced robotic applications like force-controlled manipulation and safety monitoring.

To model the robot’s posture, we employ the D-H parameter method, which defines the relationship between consecutive links using four parameters: joint angle θ, link offset d, link twist α, and link length a. For a robot with n links, the homogeneous transformation matrix from frame i-1 to frame i is given by:

$$^{i-1}_i T = \begin{bmatrix}
\cos\theta_i & -\sin\theta_i \cos\alpha_i & \sin\theta_i \sin\alpha_i & a_i \cos\theta_i \\
\sin\theta_i & \cos\theta_i \cos\alpha_i & -\cos\theta_i \sin\alpha_i & a_i \sin\theta_i \\
0 & \sin\alpha_i & \cos\alpha_i & d_i \\
0 & 0 & 0 & 1
\end{bmatrix}$$

The transformation from the base frame {0} to any link frame {i} is computed as the product of consecutive matrices:

$$^0_i T = ^0_1 T \cdot ^1_2 T \cdot ^2_3 T \cdots ^{i-1}_i T$$

This allows us to determine the position and orientation of each link relative to the base, which is essential for calculating gravitational effects. The six-axis force sensor, mounted at the base, must compensate for the weight of all links, and the D-H model provides the foundational kinematics for this purpose.

Next, we establish the gravity equations for the robot. The center of mass for each link i is defined relative to its local frame as a vector b_i = [b_ix, b_iy, b_iz]^T. The orientation of frame {i} relative to the base frame {0} is given by the rotation matrix ^0_i R. Assuming the center of mass frame {B_i} aligns with {i}, the gravitational force vector in the base frame is ^0 G_i = ^0_i R G_i, where G_i is the gravity vector in the local frame. The total force vector in the base frame due to gravity is:

$$^0 f = \left[ 0, 0, \sum_{i=0}^n ^0 G_i \right]^T$$

To compute the moment, we define the homogeneous transformation from frame {i} to the center of mass frame {B_i} as:

$$^i_{B_i} T = \begin{bmatrix}
1 & 0 & 0 & b_{ix} \\
0 & 1 & 0 & b_{iy} \\
0 & 0 & 1 & b_{iz} \\
0 & 0 & 0 & 1
\end{bmatrix}$$

The transformation from the base frame to {B_i} is then:

$$^0_{B_i} T = ^0_i T \cdot ^i_{B_i} T = \begin{bmatrix}
^0_{B_i} R & ^0_{B_i} p \\
0 & 1
\end{bmatrix}$$

where ^0_{B_i} p = [p_{Bx}, p_{By}, p_{Bz}]^T is the position vector. The total moment vector in the base frame is:

$$^0 m = \left[ \sum_{i=0}^n (^0 G_i \times p_{By}), -\sum_{i=0}^n (^0 G_i \times p_{Bx}), 0 \right]^T$$

These equations capture the gravitational forces and moments that the six-axis force sensor must compensate for.

The relationship between the base frame and the six-axis force sensor frame is crucial for accurate compensation. As shown in the figure, the sensor frame {S} has its Z-axis aligned with the base frame {0}, and the X_S axis is rotated by an angle α around Z_S to align with X_0. The relative displacement in the Z-direction is h. The rotation matrix from the base frame to the sensor frame is:

$$^S_0 R = \begin{bmatrix}
\cos\alpha & -\sin\alpha & 0 \\
\sin\alpha & \cos\alpha & 0 \\
0 & 0 & 1
\end{bmatrix}$$

The position vector cross-product matrix is:

$$^S P_{0ORG} \times = \begin{bmatrix}
0 & -p_z & p_y \\
p_z & 0 & -p_x \\
-p_y & p_x & 0
\end{bmatrix} = \begin{bmatrix}
0 & -h & 0 \\
h & 0 & 0 \\
0 & 0 & 0
\end{bmatrix}$$

The force-moment transformation matrix from the base frame to the sensor frame is:

$$^S_0 T_f = \begin{bmatrix}
^S_0 R & 0 \\
^S P_{0ORG} \times ^S_0 R & ^S_0 R
\end{bmatrix}$$

The ideal force and moment vectors in the sensor frame, denoted as ^S f and ^S m, are computed as:

$$\begin{bmatrix} ^S f \\ ^S m \end{bmatrix} = ^S_0 T_f \begin{bmatrix} ^0 f \\ ^0 m \end{bmatrix}$$

However, due to installation errors and sensor zero-point offsets, the actual measurements from the six-axis force sensor, denoted as ^C f and ^C m, deviate from the ideal values. We define a 6×6 compensation matrix A to relate the actual and ideal measurements:

$$\begin{bmatrix} ^C f \\ ^C m \end{bmatrix} = A \begin{bmatrix} ^S f \\ ^S m \end{bmatrix}$$

Expanding this, for each component, such as the force in the X-direction F_CX, we have:

$$F_{CX} = \begin{bmatrix} F_{SX} & F_{SY} & F_{SZ} & M_{SX} & M_{SY} & M_{SZ} \end{bmatrix} A_1^T$$

where A_1 is the first row of the compensation matrix A. For N postures, this forms an overdetermined system:

$$\begin{bmatrix} F_{CX1} \\ F_{CX2} \\ \vdots \\ F_{CXn} \end{bmatrix} = \begin{bmatrix} F_{SX1} & F_{SY1} & F_{SZ1} & M_{SX1} & M_{SY1} & M_{SZ1} \\ F_{SX2} & F_{SY2} & F_{SZ2} & M_{SX2} & M_{SY2} & M_{SZ2} \\ \vdots & \vdots & \vdots & \vdots & \vdots & \vdots \\ F_{SXn} & F_{SYn} & F_{SZn} & M_{SXn} & M_{SYn} & M_{SZn} \end{bmatrix} \begin{bmatrix} a_{11} \\ a_{12} \\ a_{13} \\ a_{14} \\ a_{15} \\ a_{16} \end{bmatrix}$$

Using least squares, we solve for A_1^T as:

$$A_1^T = (G^T G)^{-1} G^T F_1$$

where G is the matrix of ideal measurements and F_1 is the vector of actual F_CX values. This process is repeated for all six rows of A to obtain the full compensation matrix. This algorithm provides a universal method for static gravity compensation of the six-axis force sensor at the robot base.

To reduce the number of required postures for data collection, we employ the orthogonal experiment method. This approach selects a representative subset of postures that uniformly cover the robot’s workspace, minimizing experiments while maintaining accuracy. For a robot with k factors (joints) and m levels (joint angles), the orthogonal table L_n(m^k) specifies n experiments, where n = k(m-1) + 1. For example, a 4-DOF robot with 3 levels per joint requires only 9 experiments, as shown in the table below:

Experiment Joint 1 (°) Joint 2 (°) Joint 3 (°) Joint 4 (°)
1 -175 -30 -120 -115
2 -87.5 -15 -55 -57.5
3 0 0 10 0
4 87.5 15 75 57.5
5 175 30 140 115
6 -175 0 75 -57.5
7 -87.5 30 -120 0
8 0 -15 -55 115
9 87.5 0 10 -115

This method ensures that the sampled postures are evenly distributed, capturing the variability in gravitational effects without exhaustive testing.

We apply our compensation algorithm to the AUBO i5 collaborative robot, a 6-DOF system. The D-H parameters for this robot are listed in the table below, where θ_i is the joint variable and offset accounts for initial rotations.

Link i a_i (mm) α_i (°) d_i (mm) θ_i (°) Offset (°)
1 0 -90 121.5 q1 0
2 -408 -180 140.5 q2 90
3 -376 180 121.5 q3 0
4 0 90 102.5 q4 -90
5 0 -90 102.5 q5 0
6 0 0 94 q6 0

The masses of the links are as follows:

Link Mass (kg)
0 6.06
1 5.31
2 6.21
3 2.81
4 1.75
5 1.75
6 0.10

For the orthogonal experiment, we consider 6 factors (joints) and 5 levels, resulting in 25 experiments. The joint angle ranges are: Joint 1: -175° to 175°, Joint 2: -30° to 30°, Joint 3: -120° to 140°, Joint 4: -115° to 115°, Joint 5 and 6: -175° to 175°. The levels are defined in the table:

Level Joint 1 (°) Joint 2 (°) Joint 3 (°) Joint 4 (°) Joint 5 (°) Joint 6 (°)
1 -175 -30 -120 -115 -175 -175
2 -87.5 -15 -55 -57.5 -87.5 -87.5
3 0 0 10 0 0 0
4 87.5 15 75 57.5 87.5 87.5
5 175 30 140 115 175 175

Using these postures, we compute the ideal force and moment values in the sensor frame. For instance, the ideal values for three postures are:

Posture F_SX (N) F_SY (N) F_SZ (N) M_SX (N·m) M_SY (N·m) M_SZ (N·m)
1 0 0 -236.200 -9.155 -17.009 0
2 0 0 -236.200 3.417 -27.645 0
3 0 0 -236.200 -2.667 -22.924 0

Actual measurements from the six-axis force sensor for these postures are:

Posture F_CX (N) F_CY (N) F_CZ (N) M_CX (N·m) M_CY (N·m) M_CZ (N·m)
1 -6.854 -10.063 -233.359 -9.236 -17.183 -0.627
2 -5.262 -8.036 -235.177 2.164 -28.013 -1.300
3 -5.837 -8.485 -234.002 -3.468 -22.933 -0.947

Applying the least squares algorithm to all 25 postures, we derive the compensation matrix A:

$$A = \begin{bmatrix}
0 & 0 & 0.0695 & -0.2408 & -0.3916 & 0 \\
0 & 0 & 0.0148 & -0.3250 & 0.2059 & 0 \\
0 & 0 & 1.0108 & -0.4426 & -0.0943 & 0 \\
0 & 0 & 0.0002 & 0.9735 & 0.0398 & 0 \\
0 & 0 & 0.0020 & -0.0414 & 0.9869 & 0 \\
0 & 0 & 0.0013 & -0.0225 & 0.0325 & 0
\end{bmatrix}$$

To validate the compensation matrix, we test three arbitrary postures. The ideal values are:

Posture F_SX (N) F_SY (N) F_SZ (N) M_SX (N·m) M_SY (N·m) M_SZ (N·m)
A 0 0 -236.200 10.877 0 0
B 0 0 -236.200 -34.314 -6.514 0
C 0 0 -236.200 -3.909 -31.768 0

After applying the compensation matrix, the corrected values are:

Posture F_CX (N) F_CY (N) F_CZ (N) M_CX (N·m) M_CY (N·m) M_CZ (N·m)
A -25.051 5.683 -249.225 21.165 9.388 -0.434
B -6.915 -15.948 -222.968 -33.703 -5.285 0.260
C -3.175 -11.307 -234.025 -5.117 -31.662 -1.252

Comparing these with the actual sensor measurements:

Posture F_CX (N) F_CY (N) F_CZ (N) M_CX (N·m) M_CY (N·m) M_CZ (N·m)
A -24.216 9.326 -252.049 21.173 9.356 -0.432
B -8.333 -14.164 -228.262 -33.859 -5.550 0.328
C -4.380 -9.310 -234.825 -5.247 -31.595 -1.213

The compensated values closely match the actual measurements, demonstrating the effectiveness of the algorithm. The six-axis force sensor, after compensation, provides accurate readings that account for gravitational effects and installation errors.

In conclusion, we have developed a comprehensive method for static gravity compensation of a six-axis force sensor mounted at the robot base. By integrating D-H kinematics, least squares optimization, and orthogonal experimental design, we efficiently derive a compensation matrix that minimizes measurement errors. The case study on the AUBO i5 robot validates our approach, showing significant improvement in accuracy. This work underscores the importance of precise calibration for six-axis force sensors in advanced robotics, enabling reliable force control and interaction. Future research could extend this method to dynamic compensation, further enhancing the versatility of six-axis force sensors in robotic systems.

Scroll to Top