Abstract
Industrial robots have become more and more important in the advanced manufacturing industry. There is still a degradation problem in the accuracy performance of industrial robots after being calibrated. To maintain the accuracy performance of robots timely, a continuous kinematic calibration method is proposed. Firstly, the Modified DH (MDH) model and kinematic error model of the industrial robot have been established. Secondly, four groups of poses are measured to demonstrate the degradation of the robot’s accuracy performance. Thirdly, the continuous kinematic calibration method for accuracy maintenance based on the recursive least squares (RLS) algorithm is introduced. Finally, several experiments were conducted to verify the efficiency of the continuous calibration method based on the RLS algorithm. The RLS algorithm can achieve better efficiency and stability than the Levenberg–Marquardt (LM) algorithm. When 15 updated poses are used for parameter identification, the continuous calibration method based on the RLS algorithm can improve accuracy by 84.31%. Besides, the proposed continuous calibration method based on the RLS algorithm not only can save calculation time by 69.52% but also can reduce measurement time by 70%.
Similar content being viewed by others
Introduction
The industrial robot becomes increasingly important in modern industry1,2,3,4,5. The demand for high precision in advanced manufacturing is a major challenge for industrial robots. The manufacturing quality and producing production efficiency have been limited by the errors of the industrial robots6,7. Currently, the main approach to accuracy enhancement is robot calibration technology. Robot calibration is usually performed after the equipment is manufactured or during the periodic accuracy maintenance on the production line. It can be divided into body calibration and tool centre point (TCP) calibration8,9,10. The accuracy performance of the robot decays with the usage time7. However, the TCP calibration cannot be implemented when robot errors occur.
Several studies show that the kinematic parameter calibration can greatly enhance the position accuracy of industrial robots11,12,13. The first stage in the robot kinematic calibration is to model the kinematic error. The most classic model is the Denavit-Hartenberg (DH) model14. According to the different measured data and methods, the error models can be divided into three categories: the distance error model15, the position error model16, and the pose error model17. The second stage is to obtain the position error by a measuring device. The common measuring device includes the laser tracker18, the coordinate measuring arm19, the stereo visual system20, the ball bar21, and the Position Sensitive Detector (PSD) device22. A laser tracker, the coordinate measuring arm, and a stereo visual system are applied in the open-loop calibration method. Ball bars and PSD devices are used in the closed-loop calibration method.
The third stage is parameter identification based on the established kinematic error model and the measured error. The optimization algorithms include the Levenberg–Marquardt (LM) algorithm, the Kalman Filter algorithm, and the intelligent algorithms. Le P. et al.23 added the joint deflection model into the kinematic model. A neural network based on the Teaching–Learning-Based Optimization (TLBO) algorithm is employed to decrease the position error of the HH-800 robot from 4.03 mm to 0.41 mm. Cao H. et al.24 utilized the Extended Kalman Filter (EKF) to identify the geometric parameter errors. Chen X. et al.25 proposed an improved Beetle Swarm Optimization (BSO) algorithm. The position error of the KUKA KR500L340-2 robot is decreased from 2.95 mm to 0.20 mm. These optimization algorithms can precisely identify the kinematic parameters to improve the position accuracy. However, many algorithmic parameters need to be tuned. The Least Squares (LS) algorithm et al. have fewer algorithmic parameters. And they are easy to achieve in engineering application. Because of this, LS algorithm has been widely used in parameter identification. LS algorithm is used to find the optimal matching function for the data by minimizing the sum of squares of the errors. Fan M. et al.26 preliminarily identified the parameters error base on the LM algorithm. Then the Beetle Antennae Search (BAS) algorithm is applied for precise identification. The robot position accuracy is enhanced from 0.73 mm to 0.14 mm. Liu J. et al.27 proposed a Logistic‑Tent chaotic mapping Levenberg–Marquardt (LTLM) algorithm. The robot position accuracy has been improved effectively. Luo G. et al.28 combined the LM algorithm and the Differential Evolution (DE) algorithm to enhance the position accuracy of the FANUC M710ic/50 robot from 0.99 mm to 0.26 mm. The above calibration methods are performed after manufacturing and after accuracy degradation. These calibration methods do not allow for continuous parameter updating to keep the robot’s accuracy at a high level.
Online robot calibration enables immediate calibration of robot errors. However, it seriously affects the real-time performance of industrial robot movement. The accuracy of the robot decays more slowly. If the system is capable of obtaining the robot pose error through online measurement with a low sampling rate, the kinematic parameters can be updated with the newly measured pose error. The industrial robot can achieve better accuracy maintenance.
Therefore, a continuous kinematic calibration method for the accuracy maintenance of industrial robots based on the Recursive Least Square (RLS) algorithm is proposed. With fewer pose errors measured, the RLS algorithm is applied to identify the kinematic parameters. The proposed method can improve the calibration efficiency and ensure the robot’s accuracy. Section “The kinematic model of industrial robot”presents the kinematic model of the industrial robot to be calibrated. The framework of the proposed continuous kinematic calibration method is illustrated in Sect. “Continuous kinematic calibration method”As described in Sect. “Experimental Results” several experiments have been conducted to evaluate the performance of the proposed method. The last section describes the conclusions and future work.
The kinematic model of industrial robot
As shown in Fig. 1(a), the industrial robot Staubli TX60 to be calibrated is a manipulator with six revolute joints. Its arm span is 670 mm. The repeated positioning accuracy is ± 0.02 mm, and the rated load is 3.0 kg. Figure 1 (b) shows the definition of joint coordinate frames. Figure 1(c) shows the actual structure of the Staubli TX60 robot.
The industrial robot Staubli TX60 to be calibrated. (a) Rotating joints (b) Coordinate frames (c) Actual structure.
Forward kinematic model
Compared with the traditional DH model, the Modified DH (MDH) model introduce an external joint offset angle β to describe the adjacent parallel joints. In DH model, a small error causing the adjacent parallel joints to be non-parallel can lead to a huge mutation in the link offset d. As shown in Fig. 2, d is substituted with β to avoid the singularity problem caused by the adjacent parallel joint errors29. In this article, only the second and third joints of the Staubli TX60 robot are the adjacent parallel joints. Therefore, the homogeneous transformation matrix between the 2nd joint and the 3rd joint is given by (1).
where θi, ai, αi, and βi are the joint angle, the link length, the link torsion angle, and the joint offset angle of the i-th joint. i = 2. The c and s are the abbreviation of cos and sin functions respectively.
The transformation relationship between adjacent parallel joints in MDH model.
Besides, the homogeneous transformation matrix between other non-parallel joints is described as follow:
where di is the link offset of the i-th joint, i = 1,3,4,5,6.
To sum up, the pose of the 6 DOF industrial robot can be obtained as follow:
where n donates the kinematic parameters are nominal values.
The nominal MDH parameters of the industrial robot Staubli TX60 are listed as Table 1. The nominal joint offset angle β2 is 0.
Kinematic error model
As machining and assembly can lead to structural errors, the pose error of the calibrated robot is defined as the difference ΔT between the actual pose Tr and the nominal pose Tn.
where Δn, Δo, and Δa are the column vector of the attitude error matrix ΔR. Δp is the position error vector. Tr is the actual arrival pose. Tn is calculated based on the forward kinematic model with the nominal kinematic parameters.
Taking partial differentiation of Tn with each kinematic parameter, the kinematic error model is obtained as follow. And the higher-order terms should be ignored.
where \({\varvec{H}}_{p}\) is the position Jacobian matrix, \({\varvec{H}}_{n} \user2{,H}_{o} \user2{,H}_{a}\) are the attitude Jacobian matrixes, the kinematic parameter error to be identified is \(\Delta {\varvec{\eta}} = \left[ {\begin{array}{*{20}c} {...} & {\begin{array}{*{20}c} {\Delta {\varvec{\theta}}_{i} } & {\Delta {\varvec{d}}_{i} } & {\Delta {\varvec{a}}_{i} } & {\Delta {\varvec{\alpha}}_{i} } & {\Delta {\varvec{\beta}}_{i} } \\ \end{array} } & {...} \\ \end{array} } \right]\). The Jacobian matrixes are shown in Eq. (6).
The Eq. (5) is rewritten into matrix form.
where the pose error vector is described as \(\Delta {\varvec{E}} = \left[ {\begin{array}{*{20}c} {\Delta {{\varvec{P}}}^T } & {\Delta {{\varvec{n}}}^T } & {\Delta {{\varvec{o}}}^T } & {\Delta {{\varvec{a}}}^T } \\ \end{array} } \right]\), and the Jacobian matrix of is \({\varvec{H}} = \left[ {\begin{array}{*{20}c} {{\varvec{H}}_{P}^{T} } & {{\varvec{H}}_{n}^{T} } & {{\varvec{H}}_{o}^{T} } & {{\varvec{H}}_{a}^{T} } \\ \end{array} } \right]^{T}\) based on the pose error model of the MDH model.
Continuous kinematic calibration method
As shown in Fig. 3, the robot performance test and error calibration system are established. The system contains the laser tracker Leica AT960 and the industrial robot Staubli TX60. The T-mac is a 6D pose measuring device for laser tracker. It is fixed on the robot flange through an adapter plate. The mass of the T-mac is 1.5 kg. The position accuracy of Leica AT960 is ± 15um + 6um/m. The attitude accuracy is 0.01º. The measurement software applied is Spatial Analysis. The transformation relation between the T-mac frame and the flange frame, and transformation relation between the measurement frame and the base frame should be obtained. The base frame is set as the reference coordinate frame.
The performance measurement and error calibration system established in this paper.
Accuracy degradation of industrial robot
As stated in30, the accuracy performance changes as body temperature and ambient temperature change. According to the ISO 9283 standard31, the industrial robot should be warmed before the robot performance test and calibration. During the working duration, the accuracy performance of the industrial robots degrades. An experiment was conducted to analyse the accuracy of the robot’s performance at different working durations. In the measured experiments, four groups of poses are measured. The first group was measured after the robot had been warmed. Each group contains 100 different poses in the workspace of the calibrated robot. The measured time interval is set at 2 h. During the running time interval, all joints of the industrial robot execute motion. The position accuracy of the industrial robot is shown in the Fig. 4. The average error of the robot increases with working duration increasing.
The accuracy degradation of the Staubli TX60 robot.
Continuous kinematic calibration method
The general robot calibration employs cyclic operations to accomplish robot accuracy maintenance. As shown in Fig. 5, the general robot calibration method affects the manufacturing efficiency of the production line during the calibration process. To avoid this, a novel continuous kinematic calibration method is proposed in this paper. The kinematic calibration can be conducted continuously to ensure the accurate performance of the industrial robot. The proposed continuous kinematic calibration method can recursively identify the kinematic parameters based on the updated measured poses. To achieve this, the RLS algorithm is applied to identify the kinematic parameter errors. The updated poses can be measured through the optical 3D measuring equipment et al.
The differences between the periodic calibration and the proposed continuous kinematic calibration.
Figure 6 shows the process of continuous kinematic calibration in this paper. Before introducing the RLS algorithm, it is essential to explain the fundamentals of the least squares method first. There is a sample { a01, a02,…, a0n, b0} contains the response value b0 and independent variable a0j (j = 1,2,…,n). In the robot calibration, b0 is defined as measured pose error. The a0j is defined as the joint angle. The n is defined as the joint number.
The process of the continuous kinematic calibration.
The measured system continuously acquires the new sample data {ai1, ai2,…, ain, bi}. The kinematic parameters x is applied to fit the actual mapping between the Jacobian matrix Ai = {f(aij)}(i = 1,2,…,m. m is the total sample number) and b = { bi }. The LS algorithm can be simplified as solving the Eq. (8).
The analytical solution can be achieved as Eq. (9).
During the robot calibration process, m poses should be measured. However, it takes significant calculations to solve \(\left( {A^{{\text{T}}} A} \right)^{ - 1}\) with m poses. To avoid calculating \(\left( {A^{{\text{T}}} A} \right)^{ - 1}\) repetitively, the formula of LS algorithm can be written as follow:
where A0 = {f(a0j)}.
When a new sample data is acquired, the Eq. (10) is rewritten as Eq. (11).
where A1 = {f(a1j)}.
For eliminating re-calculation of A0 and b0, equation above can be written as Eq. (12).
where \(G_{0} = A_{0}^{{\text{T}}} A_{0}\), \(G_{1} = G_{0} + A_{1}^{{\text{T}}} A_{1}\),\(x_{0} = G_{0}^{ - 1} A_{0}^{{\text{T}}} b_{0}\).
Based on Eq. (12), the iterative formula of the RLS algorithm is given as Eq. (13).
where \(G_{k + 1} = \left[ {\begin{array}{*{20}c} {A_{k} } \\ {A_{k + 1} } \\ \end{array} } \right]^{{\text{T}}} \left[ {\begin{array}{*{20}c} {A_{k} } \\ {A_{k + 1} } \\ \end{array} } \right] = G_{k} + A_{k + 1}^{{\text{T}}} A_{k + 1}\) .
Based on the Sherman-Morrison formula32, the Eq. (13) can be rewritten as (14). Equation (14) is the core iterative formula of the RLS algorithm.
where \(P_{k + 1} = P_{k} - \frac{{P_{k} a_{k + 1} a_{k + 1}^{{\text{T}}} P_{k} }}{{I + a_{k + 1}^{{\text{T}}} P_{k} a_{k + 1} }}\),\(P_{0} = (A_{0}^{{\text{T}}} A_{0} )^{ - 1}\).
Therefore, kinematic parameter identification can be conducted continually with updating newly measured pose error. In this paper, Eq. (7) is solved by applying the RLS algorithm. This means Eq. (8) in solving the actual parameter identification problem is present as Eq. (15).
where the A in the RLS algorithm represents H, x represents ∆η, and b represents ∆E.
Experimental results
As mentioned above, each group contains 100 measured poses. Fifty poses of each group are set as the identification group, while the remaining 50 poses are set as the verification group. In this section, the accuracy improvement performance and maintenance of the continuous calibration method based on the RLS algorithm have been analysed and compared.
Accuracy improvement based on the RLS algorithm
As shown in Table 1, 24 kinematic parameters in the MDH model that need to be identified. Therefore, the least pose number used in RLS algorithm is 4. A varied number of poses applied in the recursive identification step has a great impact on the effectiveness of the RLS algorithm. In order to figure this out, several experiments were conducted. The pose number is set as 4, 5, 10, 15, 20, 25 and 50 in the RLS algorithm for parameter identification. The comparison results are shown in Fig. 7 and Table 2.
The identification results with the varied pose number in the RLS algorithm. (a) Identification dataset. (b) Verification dataset.
As shown in Fig. 7, the RLS algorithm obtains great performance in improving accuracy in the identification group. However, the position error of the verification groups reaches a steady state when the pose number is larger than 15. As shown in Table 2, the average position accuracy of the robot is enhanced by 91.56% and 87.30% in both the identification group and the verification group, respectively, when fifteen poses are used in the RLS algorithm. Therefore, the appropriate pose number is set as 15, which can maintain a balance between identification accuracy and measurement efficiency.
Accuracy maintenance comparison experiments
Table 3 designs the effectiveness validation experiments for the RLS. The flowchart of the experiments is shown in Fig. 8. The four pose groups shown in Fig. 4 are used in the experiments.
The comparison experiments for robot calibration.
The results of the periodic calibration method
To verify the advantages of the RLS algorithm, the LM algorithm is used for comparison. The kinematic parameters are identified in the four pose groups. The latter parameter identification is based on the kinematic parameters obtained in the previous parameter identification. In the periodic calibration method, fifty poses in each group are all applied to identify the kinematic parameters. The results of kinematic parameter identification based on the RLS and LM algorithms are shown in Fig. 9 and Fig. 10. The average position error of the robot based on the nominal MDH model keeps increasing in both the identification and the verification groups. The position error before each periodic identification is calculated based on the kinematic parameters identified by the previous period. The position error after each periodic identification is calculated based on the kinematic parameters identified by the current period.
The results of periodic calibration method with parameter identification based on RLS algorithm. (a) The results of identification group (b) The results of verification group.
The results of periodic calibration method with parameter identification based on LM algorithm. (a) The results of identification group (b) The results of verification group.
As shown in Fig. 9, the RLS algorithm can maintain the position accuracy of the robot in both the identification and verification groups effectively. The average position error of the robot is reduced from 0.654504 mm to 0.054704 mm in the identification group. And the average position error of the robot is decreased from 0.690698 mm to 0.094008 mm in the verification group. The accuracy performance is enhanced by 91.64% and 86.39% respectively. Moreover, the accuracy performance of the RLS algorithm after each periodic identification is smoother and steadier. As shown in Fig. 10, the LM algorithm can also maintain the position accuracy of the robot in both the identification and verification group. The average position error of the robot is reduced from 0.654504 mm to 0.165852 mm in the identification group. And the average position error of the robot is decreased from 0.690698 mm to 0.226489 mm in the verification group. The accuracy performance is enhanced by 74.66% and 67.21% respectively. However, the position error of the calibrated robot based on the LM algorithm is more than twice as much as the RLS algorithm. To sum up, the accuracy maintenance performance and stability of the RLS algorithm are better than that of the LM algorithm.
The results of the continuous calibration method
As shown in Table 3, the proposed continuous calibration method has been evaluated in this section. When the pose number for the continuous calibration decreases, the accuracy maintenance performance of the RLS and LM algorithms are compared. As discussed in Section "Accuracy improvement based on the RLS algorithm", the appropriate pose number for the RLS algorithm is set as 15. Therefore, the two algorithms are compared with 15 and 20 updated poses. The experimental results with 15 updated poses are illustrated in Fig. 11 and Fig. 12. As shown in Fig. 11, the average position error of the robot with the RLS algorithm is reduced from 0.571258 mm to 0.031632 mm in the identification group, and the average position error of the robot is also decreased from 0.690698 mm to 0.108393 mm in the verification group. The accuracy performance is enhanced by 94.46% and 84.31% respectively. As shown in Fig. 12, the average position error of the robot with the LM algorithm is reduced from 0.743079 mm to 0.145949 mm in the identification group, and the average position error of the robot is decreased from 0.690698 mm to 0.264862 mm in the verification group. The position accuracy performance is enhanced by 80.36% and 61.65% respectively. It is easy to figure out that the average position error of the RLS algorithm after each continuous identification is much smoother and steadier than that of the LM algorithm.
The results of continuous calibration method by using RLS algorithm with 15 updated poses. (a) The results of identification group (b) The result of verification group.
The results of continuous calibration method by using LM algorithm with 15 updated poses. (a) The results of identification group (b) The result of verification group.
The experimental results with 20 updated poses are illustrated in Fig. 13 and Fig. 14. As shown in Fig. 13, when the RLS algorithm is applied, the average position error of the robot is reduced from 0.658827 mm to 0.036790 mm in the identification group, and it is also reduced from 0.690698 mm to 0.091686 mm in the verification group. The accuracy performance is enhanced by 94.42% and 86.73% respectively. As shown in Fig. 14, the average position error of the robot with the LM algorithm is reduced from 0.703732 mm to 0.129492 mm in the identification group, and the average position error of the robot is reduced from 0.690698 mm to 0.280163 mm in the verification group. The accuracy performance is enhanced by 81.60% and 59.44% respectively. It can be seen that the RLS algorithm achieves higher efficiency and stability than the LM algorithm. The experimental results are summarized in Table 4.
The results of continuous calibration method by using RLS algorithm with 20 updated poses. (a) The results of identification group (b) The results of verification group.
The result of continuous calibration method by using LM algorithm with 20 updated poses. (a) The results of identification group (b) The result of verification group.
Furthermore, the calculation time of the RLS algorithm decreased from 212.86 s in 50 updated poses to 64.88 s with 15 updated poses. The continuous calibration method based on the RLS algorithm cannot only save calculation time by 69.52% but also reduce measurement time by 70%. The proposed continuous calibration method for industrial robots can ensure accuracy performance.
Conclusion
To solve the accuracy degradation problem of the industrial robot, a novel continuous calibration method is proposed in this paper. Firstly, the kinematic error model based on the MDH model is established. Secondly, four pose groups are measured by the Leica AT960 laser tracker with fixed work intervals. It can be seen that the accuracy performance of the industrial robot decays. Thirdly, a continuous kinematic calibration method for accuracy maintenance of industrial robots based on RLS algorithm is proposed. Several experiments have been done to verify the advantages of the proposed method. When the RLS algorithm is applied in parameter identification stage, the position error of robot reaches steady state when the pose number is more than 15. The RLS algorithm achieves better efficiency and stability than the LM algorithm. Based on the periodic identification for four times, the accuracy performance of the industrial robot is enhanced by 86.39% based on the RLS algorithm. When 15 or 20 updated poses are used for parameter identification, the continuous calibration method based on the RLS algorithm can improve accuracy by 84.31% and 86.73% respectively. In addition, the continuous calibration method based on the RLS algorithm not only can save calculation time by 69.52% but also can reduce measurement time by 70%. To sum up, the proposed continuous calibration method achieves great performance.
Future work will focus on the online stereo-vision-based pose measurement system. It can better complement the method proposed in this paper. The calibration system can be promoted in engineering applications.
Data availability
All data generated or analysed during this study are included in this published article.
References
Li, R. et al. Real-time trajectory position error compensation technology of industrial robot. Measurement 208, 112418 (2023).
Peta, K., Wlodarczyk, J. & Maniak, M. Analysis of trajectory and motion parameters of an industrial robot cooperating with a numerically controlled machine tools. J. Manuf. Proc. 101, 1332–1342 (2023).
Asif, S. & Webb, P. Managing delays for realtime error correction and compensation of an industrial robot in an open network. Machines. 11(9), 863 (2023).
Arents, J. & Greitans, M. Smart industrial robot control trends, challenges and opportunities within manufacturing. Appl. Sci. 12(2), 937 (2022).
Jiang, G. et al. High-precision robotic kinematic parameter identification and positioning error compensation method for industrial robot. Meas. Sci. Technol. 35, 055016 (2024).
Liu, J. et al. A logistic-tent chaotic mapping Levenberg Marquardt algorithm for improving positioning accuracy of grinding robot. Sci. Rep. 14(1), 9649 (2024).
Qiao, G. & Weiss, B. Industrial robot accuracy degradation monitoring and quick health assessment. J. Manuf. Sci. Eng. 141(7), 071006 (2019).
Yang, Z. et al. Efficient TCP calibration method for vision guided robots based on inherent constraints of target object. IEEE Access. 9, 8902–8911 (2021).
Lin, C. et al. Automatic calibration of tool center point for six degree of freedom robot. Actuators. 12, 107 (2023).
Li, Y. et al. Error similarity analysis and error compensation of industrial robots with uncertainties of TCP calibration. Appl. Sci. 13, 2722 (2023).
Gao, G. et al. Modeling and parameter identification of a 3D measurement system based on redundant laser range sensors for industrial robots. Sensors. 23, 1913 (2023).
Li, Z., Li, S. & Luo, X. An overview of calibration technology of industrial robots. IEEE/CAA J. Autom. Sinica. 8, 23–36 (2021).
Sun, T. et al. Kinematic calibration of serial and parallel robots based on finite and instantaneous screw theory. IEEE Trans. Rob. 36, 816–834 (2020).
Xu, T. et al. Robot dynamic calibration on current level: modeling, identification and applications. Nonlinear Dyn. 109, 2595–2613 (2022).
Wang, Z. et al. A distance error based industrial robot kinematic calibration method. Industrial Robot: An Int. J. 41, 439–446 (2014).
Chen, T. et al. Research of calibration method for industrial robot based on error model of position. Appl. Sci. 11, 1287 (2021).
Xiang, T. et al. Kinematics Parameter Calibration of Serial Industrial Robots Based on Partial Pose Measurement. Mathematics 11(23), 4802 (2023).
Zhang, J., Lou, Z. & Fan, K. Accuracy improvement of a 3D passive laser tracker for the calibration of industrial robots. Robot. Computer-Integrated Manuf. 8, 102487 (2023).
Yang, H. et al. Structural design and performance analysis of a self-driven articulated arm coordinate measuring machine. Meas. Sci. Technol. 33, 035005 (2021).
Abdelaal, M. et al. Uncalibrated stereo vision with deep learning for 6-DOF pose estimation for a robot arm system. Robot. Autonom. Syst. 145, 103847 (2021).
Kuric, I. et al. Industrial robot positioning performance measured on inclined and parallel planes by double ballbar. Appl. Sci. 11, 1777 (2021).
Meng, X. et al. Six-Degree-of-Freedom Posture Measurement Technologies Using Position Sensitive Detectors (PSDs): State of the Art. Micromachines. 13, 1903 (2022).
Le, P. & Kang, H. Robot manipulator calibration using a model based identification technique and a neural network with the teaching learning-based optimization. IEEE Access. 8, 105447–105454 (2020).
Cao, H. et al. A robot calibration method using a neural network based on a butterfly and flower pollination algorithm. IEEE Trans. Ind. Electron. 69, 3865–3875 (2021).
Chen, X. & Zhan, Q. The kinematic calibration of an industrial robot with an improved beetle swarm optimization algorithm. IEEE Robot. Autom. Letters. 7, 4694–4701 (2022).
Fan, M. et al. A novel calibration method for kinematic parameter errors of industrial robot based on Levenberg–Marquard and Beetle Antennae Search algorithm. Meas. Sci. Technol. 34, 105024 (2023).
Liu, J. et al. A logistic-tent chaotic mapping Levenberg Marquardt algorithm for improving positioning accuracy of grinding robot. Sci. Rep. 14, 9649 (2024).
Luo, G. et al. A novel kinematic parameters calibration method for industrial robot based on Levenberg-Marquardt and Differential Evolution hybrid algorithm. Robotics Computer-Integrated Manuf. 71, 102165 (2021).
Mao, C. et al. Separable nonlinear least squares algorithm for robust kinematic calibration of serial robots. J. Int. Robotic Syst. 101, 1–12 (2021).
Yin, S. et al. Real-time thermal error compensation method for robotic visual inspection system. Int. J. Adv. Manuf. Technol.. 75, 933–946 (2014).
GenevaManipulating Industrial Robots Performance Criteria and Test Methods (Switzerland: IOP Published) (1998).
Nadezda, S. An interior point method and Sherman-Morrison formula for solving large scale convex quadratic problems with diagonal Hessians. ANZIAM J. 56, E1–E21 (2014).
Acknowledgements
The research reported in this paper was carried out at the School of Automation, Nanjing Institute of Technology, Nanjing, China and the School of instrument and technology, Southeast University, Nanjing, China. This work was supported in part by the Natural Science Foundation of China under Grant 51905258, the Postgraduate Research & Practice Innovation Program of Jiangsu Province (SJCX23_1164), and the Open Foundation Project of Advanced Industrial Technology Research Institute of Nanjing Institute of Technology under Grant XJY202116.
Funding
National Natural Science Foundation of China, 51905258, Open Foundation Project of Advanced Industrial Technology Research Institute of Nanjing Institute of Technology, XJY202116, Postgraduate Research Practice Innovation Program of Jiangsu Province, SJCX23_1164.
Author information
Authors and Affiliations
Contributions
G.Q. and Y.Z. conceived the experiments; X.J., M.Z. and C.G conducted the experiments; G.Q. and X.J. analysed the results; G.Q. and X.J. wrote the main manuscript text. All authors reviewed the manuscript.
Corresponding author
Ethics declarations
Competing interests
The authors declare no competing interests.
Additional information
Publisher’s note
Springer Nature remains neutral with regard to jurisdictional claims in published maps and institutional affiliations.
Rights and permissions
Open Access This article is licensed under a Creative Commons Attribution-NonCommercial-NoDerivatives 4.0 International License, which permits any non-commercial use, sharing, distribution and reproduction in any medium or format, as long as you give appropriate credit to the original author(s) and the source, provide a link to the Creative Commons licence, and indicate if you modified the licensed material. You do not have permission under this licence to share adapted material derived from this article or parts of it. The images or other third party material in this article are included in the article’s Creative Commons licence, unless indicated otherwise in a credit line to the material. If material is not included in the article’s Creative Commons licence and your intended use is not permitted by statutory regulation or exceeds the permitted use, you will need to obtain permission directly from the copyright holder. To view a copy of this licence, visit http://creativecommons.org/licenses/by-nc-nd/4.0/.
About this article
Cite this article
Qiao, G., Jiang, X., Zhang, M. et al. A continuous kinematic calibration method for accuracy maintenance of industrial robot based on recursive least squares algorithm. Sci Rep 15, 11397 (2025). https://doi.org/10.1038/s41598-025-95523-8
Received:
Accepted:
Published:
Version of record:
DOI: https://doi.org/10.1038/s41598-025-95523-8
















