3.2. Crosstalk Calibration
The reason for setting
to zero when designing the crosstalk matrix
is that torque is minimally affected by crosstalk.
Figure 5 shows the results when the wrist angle of the end-effector is rotated 360 degrees, starting from a posture with the highest torque, as in the calibration data collection postures. In this case, the CoM is estimated without inclination, and no crosstalk calibration was performed. As a result, the
exhibited significant errors due to the influence of crosstalk. In contrast, the
showed a maximum error of 0.1 Nm, indicating that the influence of crosstalk on torque is minimal. As shown in
Table 4, the mean and variance of the external torque are very small. Therefore, our approach to modeling the crosstalk matrix is reasonable.
To evaluate whether the crosstalk calibration can compensate for the effects of the end tool’s own weight, we conducted an experiment using the Robotiq 3F gripper, trying a pick-and-place scenario on a non-inclined base. The path of the scenario is described in
Figure 6. The robot moves to predefined joint positions using its internal controller, which is based on H-infinity control [
19]. When the CoM is not estimated, the data from the gripper’s datasheet are used directly. During the experiment, the gripper does not grasp any object, and no external forces are applied. Ideally, the external wrench
should be zero, where
.
The first experiment is conducted on a non-inclined surface to investigate the impact of crosstalk.
Figure 7a shows the external force and torque graphs during the pick-and-place operation in the
No Calibration case, while
Figure 7b shows the same data for
LSM Calibration. As you can see in
Figure 7, in postures where torque is generated due to the influence of the end tool, significant force errors are observed due to crosstalk. The analysis of the external force and torque data along each axis, as shown in
Figure 7a, is summarized in
Table 5.
When crosstalk calibration was applied, the MSE reduced 55.8%, 56.2%, and 14.5% with respect to No Calibration for external force. In contrast, the external torque showed almost identical results. This is because the estimated CoM closely matches the CoM specified in the datasheet, and no crosstalk compensation was applied for torque. Therefore, crosstalk compensation effectively reduces errors due to force.
3.3. Inclination Calibration
To investigate the impact of the inclined base, we conduct the second experiment with three calibration steps: No Calibration, LSM Calibration, and Full Calibration. The parameters and initial values for non-linear optimization are set as follows: the learning rate for CoM is , the learning rate for alpha and beta is , and the learning rate for crosstalk is . For the ground inclination, since it is measured in radians and the base inclination is generally small, it is advantageous to optimize with a small learning rate. Similarly, for CoM, as its value is in meters and relatively small, a small learning rate is also appropriate. For initial values, the CoM can converge easily by directly using the values provided in the datasheet, as they are close to the optimal point. For ground inclination, even if the inclination is unknown, setting it to 0 allows convergence due to the small learning rate. For crosstalk, it is recommended to set the initial value to 0, as sensor manufacturers usually perform internal calibration. As will be shown in the experimental results discussed later, the inclination significantly impacts accurate force–torque decoupling. Therefore, setting the tolerance to to ensure sufficient convergence is advantageous for obtaining precise results.
The results of the experiment are shown in
Figure 8. The base is inclined by approximately 5 degrees as we set up in
Figure 4. Comparing
Figure 8a,b, one can see that while the external force error in
Figure 8b has decreased due to crosstalk compensation, the torque error remains due to the base’s incline, indicating that the estimated CoM and crosstalk are insufficient to reduce the torque error. In fact, the torque error is the same as in
Figure 8a, where
No Calibration is applied. Comparing
Figure 8b,c, one can observe that both force and torque have converged close to zero in
Figure 8c. This result demonstrates effective compensation for the errors in force and torque caused by the inclined base, and compared to
Figure 8a, where
No Calibration is applied, it shows that the influence of the end tool has been effectively compensated for. Additionally, as mentioned in the CoM results, our calibration method compensates using the data provided by the sensor, enabling effective calibration from the sensor’s perspective even if there are discrepancies with the datasheet.
The analyzed experimental data are presented in the table.
Figure 8a,b show a trend similar to that in
Figure 7. Although crosstalk compensation reduced the force error, the presence of the base incline prevented convergence close to zero. Comparing the data in
Figure 8b,c, one can see that estimating the incline angle allowed the error to converge close to zero. The
Full Calibration reduced MSE with respect to
No Calibration by 85.8%, 5.4%, and 56.8% for external force and 27.3% and 65.3% for external torque as you can see in
Table 6. Additionally, the final results in
Table 5, obtained from experiments on a non-inclined base, are nearly identical to the results obtained on an inclined base. Therefore, our calibration method achieves the same external force estimation accuracy on an inclined base as on an even floor.
From Equations (
3) and (
4), it can be observed that the predicted force and torque are dependent on the ground inclination and the CoM. In the case of the crosstalk matrix used in Equation (
8) with LSM or in Equation (
9) in the non-linear form, it can be interpreted as a constant value multiplied by the error of the predicted force and torque. Therefore, in the absence of inclination, multiplying the torque by the crosstalk matrix can reduce the error. However, when inclination is present, the inclination and CoM are coupled, making it impossible to reduce the error using only the crosstalk matrix. Furthermore, as seen in Equation (
3), when there is no inclination, the sine term becomes 0, eliminating many terms. However, when inclination is present, a sine value appears, increasing the non-linearity. Hence, the influence of inclination can be considered the most significant factor. This is notable in the experimental results shown in
Figure 8, where the error remains large until the inclination is compensated for.
We conduct the same pick-and-place motion with the gripper holding an object with 2 kg of mass. Since the gripper is grasping the object, the FT sensor measures the wrench resulting from both the gripper’s weight and the object’s weight. Given that the calibration was performed using the previously described method to compensate for the gripper’s weight, the external wrench should reflect only the effect of the object’s weight. The results of estimating the object’s mass under three conditions are shown in
Figure 9. To estimate the mass of an object grasped by the gripper, we calculated the l2-norm of external force. However, the actual wrench applied is not ideally separated into force and torque components. In the
No Calibration results, during the period between 2 and 8 s, where both force and torque are applied together, there is a significant fluctuation in the magnitude of the external force. This is due to the lack of ideal separation between force and torque, which requires the crosstalk calibration we propose. With
LSM Calibration, force and torque separation is achieved, resulting in a more stable external force magnitude over the same period. However, due to the inclined base, there remains an offset from the true mass of 2 kg. Finally, in the
Full Calibration results, where the base incline is accounted for, the estimated mass converges closer to the actual 2 kg.
The analysis of mass estimation data from the three calibration stages in the pick-and-place scenario is shown in
Table 7. In the
No Calibration results, the error is due to crosstalk from external torque, while in the
LSM Calibration results, it is due to an offset from the inclined base. This is evident from the MSE result, which decreased 40% with respect to
No Calibration. However, the remaining error reflects the failure to accurately separate force and torque due to the inclined base. With
Full Calibration, compensating for the gravity axis error brought the estimated mass closer to 2 kg, and alignment of the gravity axis further reduced the MSE by an additional 91.7%.
The above results were obtained from dynamic data collected during the pick-and-place scenario. To ensure an accurate comparison, we also performed mass estimation under static conditions across various postures with different orientations, as shown in
Table 8. The overall trends are consistent with the previous experiment: crosstalk compensation enabled force and torque separation, while incline compensation allowed for more accurate estimations.
Additionally, we evaluate whether the external force converges to 0 when no object is grasped and to 2 kg when a 2 kg object is grasped by repeatedly performing the same pick-and-place scenario under various base inclination angles, as shown in
Table 9. The base inclinations are set to roll angles of
and
and pitch angles of
and
. The grippers used are the Robotiq 3f and Barrett hand. Similar to previous experimental results, the
No Calibration scenario exhibits significant errors. While the
LSM Calibration reduces errors to some extent, substantial errors still remain. With
Full Calibration, the errors are significantly reduced compared to both
No Calibration and
LSM Calibration, achieving a maximum reduction of 98.7%. Consistent with our experimental analysis, these results indicate that compensating for inclination plays the most significant role in accurately estimating a consistent mass.