

1. 清华大学 机械工程系, 北京 100084;
2. 清华大学 摩擦学国家重点实验室, 北京 100084;
3. 清华大学 精密超精密制造装备及控制北京市重点实验室, 北京 100084
收稿日期:2022-03-31
基金项目:国家自然科学基金资助项目(51975307)
作者简介:李政清(1999—),男,博士研究生
通讯作者:唐晓强,教授,E-mail: tang-xq@tsinghua.edu.cn
摘要:针对用于物流仓储领域的平面四索并联机器人,提出一种基于视觉定位的自标定方法。通过相机和货架上的AprilTag获取末端动平台的位置,进行模型参数辨识和误差补偿,实现平面四索并联机器人的几何参数快速标定。首先,建立该四索并联机器人的运动学模型;然后,提出基于该机器人构型的运动学参数标定方法及位姿测量方法;最后,通过计算机仿真和实验验证该标定方法的有效性。实验结果表明,该标定方法能够快速实现末端动平台的运动学标定,达到小于1 mm的定位精度,满足仓储堆垛任务的定位误差要求。
关键词:索驱动机器人并联机构仓储物流运动学标定
Vision-based auto-calibration method for planar cable-driven parallel robot for warehouse and logistics tasks
LI Zhengqing1, HOU Senhao1, WEI Jinhao1, TANG Xiaoqiang1,2,3


1. Department of Mechanical Engineering, Tsinghua University, Beijing 100084, China;
2. State Key Laboratory of Tribology, Tsinghua University, Beijing 100084, China;
3. Beijing Key Laboratory of Precision/Ultra-Precision Manufacturing Equipment and Control, Tsinghua University, Beijing 100084, China
Abstract: An auto-calibration method was developed for planar four-cable parallel robots based on visual measurements. The end-effector pose is obtained using a camera fixed on the end-effector that measures the pose of AprilTags on storage racks. Geometric parameter identification and error compensation are then used for rapid calibration of the planar four-cable parallel robot. The system model is based on a kinematics model of the planar four-cable parallel robot for storage and logistics tasks. Then, the kinematics calibration method is used with the pose measuring method to calibrate the robot. The calibration accuracy was verified using both computer simulations and tests. The results show that this rapid calibration method provides positioning accuracy of less than 1 mm, which meets the accuracy requirement for the storage and stacking tasks.
Key words: cable-driven robotparallel mechanismwarehouse and logisticskinematics calibration
索并联机器人是在绳索的驱动下实现空间运动的并联机构,具有工作空间大、负载能力高、结构重量轻、响应速度快等优点。索并联机器人可应用于仓储货物分拣领域[1-2],如图 1所示。根据Ramadan等[3]和Bruckmann等[4]的研究,相比传统的堆垛机,索并联机器人在存取货物工作中能够有效提高效率并降低能耗。为保证存取货物的位置精度,仓库货物分拣通常要求索并联机器人的定位精度不低于2 mm。由于零件加工和装配过程中存在误差,索并联机器人运动学模型中使用的几何参数名义值不同于真实值,会影响末端动平台的定位精度。此外,索并联机器人工作时绳索中持续存在的张紧力会使绳索长度伸长,使运动学模型中的几何参数产生偏差,进而导致存取货物的精度降低[5]。因此,与一般的机器人不同,有必要对用于仓储的索驱动机器人运动学模型几何参数进行经常性的标定。
![]() |
图 1 一种仓储物流中使用的索并联机器人 |
图选项 |
国内外****对并联机器人的标定方法进行了研究,根据测量方法和测量运动学量的不同,运动学参数的标定方法主要分为外标定方法和自标定方法两大类[6]。外标定方法是通过机构外部的高精度测量设备检测末端的位置和姿态信息或关节信息,得到与运动学模型的残差数值,并结合运动学模型进行参数识别的标定方法。自标定方法则是通过机器人被动关节上的传感器或其他方法获取机器人内部的运动学量,并利用运动学模型进行参数识别[7]。外标定方法通常需要使用三坐标测量仪或激光跟踪仪等高精度的测量设备,对设备有着较高的要求,且这些测量设备通常成本高昂。自标定方法仅需要测量机构内部被动关节等处的运动学量来进行标定。
国内外****针对索并联机器人提出了一些外标定方法。郑亚青等[8]参考了Besnard和Khall的方法,采用倾角计,以末端动平台的姿态偏差最小为优化目标,提出了对空间6自由度8索机构进行运动学参数标定的方法,并进行了仿真验证。Vanegas等[9]提出了基于视觉测量的平面四索机器人外标定方法,通过外部相机获取末端动平台的位姿信息并进行标定,能够有效提高末端动平台的运动精度。但由于固定在外部的摄像机观测空间有限,无法对末端动平台在较大的工作空间内进行标定,因此该方法不适用于大型物流仓库环境下对工作空间较大的索并联机器人进行运动学参数标定。
相比外标定方法,自标定方法的测量装置集成在关节或安装在动平台上,通常不依赖于外部安装的测量设备,因而能够适用于空间较大的场合,且可以随时进行标定。对于索并联机器人,其被动关节为静平台上的出索点和动平台上的索结点,通常难以在这些关节上设置传感器进行测量[10],因此一般利用索驱动单元内的电机编码器和力传感器来实现索并联机器人的运动学标定[11-13]。Yuan等[7]基于索并联机器人的冗余驱动关节实现了一种利用电机编码器进行测量的自标定方法。Miermeister等[14]实现了一种通过力传感器测量绳索索力进而利用索并联机器人静力学与运动学耦合的特性标定运动学参数的方法。尽管上述的标定方法通常无需引入其他的传感器或测量元件,但电机编码器和力传感器的测量精度有限,无法实现较高的几何参数标定精度。Jin等[15]利用激光距离传感器实现了一种对空间6自由度八索机构进行运动学参数标定的自标定方法(也称内标定),但该标定方法需要激光照射点落在反射板范围内,因此也难以应用于工作空间较大的仓库场景。
本文以平面四索并联机器人为研究对象,提出一种基于固定在末端动平台上的相机进行测量的视觉自标定方法。相比已有的索并联机器人标定方法,该方法能够适用于仓储搬运等工作空间较大的场合。同时利用成本较低的视觉相机设备实现了不低于2 mm的标定精度,比其他外标定方法具有更好的经济性。最终通过计算机数值仿真和实验验证了该标定方法的精度,满足了仓储搬运场景下末端动平台定位精度要求。
1 模型分析1.1 平面四索并联机器人的运动学建模本文所研究的平面四索并联机器人的构型见图 2,具有沿x和y轴的2个平动自由度和绕z轴方向的1个转动自由度。图中Ai(i=1, 2, 3, 4)表示静平台出索点,其在世界坐标系κ0下的坐标记作向量ai;Bi表示动平台索结点,其在动平台固连坐标系κP下的坐标记作向量bi,li表示由Bi指向Ai的向量,li表示绳索索长,α表示动平台绕z轴的转角;P表示κP的原点,其在κ0下的位置即为末端动平台位置,记作向量p。
![]() |
图 2 平面四索并联机器人构型 |
图选项 |
记描述末端动平台姿态的旋转矩阵为R,则索长表示为
$ l_{i}=\left\|\boldsymbol{l}_{i}\right\|_{2}=\left\|a_{i}-\boldsymbol{p}-\boldsymbol{R} \boldsymbol{b}_{i}\right\|_{2}. $ | (1) |
$l=\varphi^{\mathrm{IK}}(\tilde{\boldsymbol{p}}) .$ | (2) |
$S(\boldsymbol{p})=\left\|\hat{\boldsymbol{l}}-\varphi^{I K}(\tilde{\boldsymbol{p}})\right\|_{2} .$ | (3) |
$\underset{\widetilde{\bf{p}} \in \mathbb{R}^{3}}{\operatorname{argmin}} S(\tilde{\boldsymbol{p}}) .$ | (4) |
1.2 误差来源分析及误差建模索并联机器人的误差主要来自于工作过程中绳索拉力引起的索长变化、系统结构的动态特性和索力变化引起的振动所导致的动态误差,以及制造、装配精度等引起的静态误差。本文中机器人主要用于定位后静止状态下的堆垛操作,因此主要对索并联机器人的静态误差进行分析和讨论。
根据式(2),对末端姿态有影响的几何参数主要包括κ0坐标系下4个出索点的位置坐标和κP坐标系下4个索结点的位置坐标。同时,注意到由电机编码器所得到的理论索长值与实际索长值之间也会存在常值偏差,因此,下面主要讨论以上3组参数对于该索并联机器人定位精度的影响。
记该索并联机器人的正运动学问题为φDK,有
$\delta \tilde{\boldsymbol{p}}=\frac{\partial \varphi^{\mathrm{DK}}(\boldsymbol{q}, \boldsymbol{g})}{\partial(\boldsymbol{q}, \boldsymbol{g})} \delta(\boldsymbol{q}, \boldsymbol{g})=\boldsymbol{J}_{q} \delta \boldsymbol{q}+\boldsymbol{J}_{g} \delta \boldsymbol{g}.$ | (5) |
$\boldsymbol{g}_{20 \times 1}=\left[\begin{array}{llll}g_{1} & g_{2} & \cdots & g_{20}\end{array}\right]^{\mathrm{T}}.$ | (6) |
$\left[\begin{array}{c}\Delta x \\\Delta y \\\Delta \alpha\end{array}\right]=\left[\begin{array}{llll}J_{1, 1} & J_{1, 2} & \cdots & J_{1, 20} \\J_{2, 1} & J_{2, 2} & \cdots & J_{2, 20} \\J_{3, 1} & J_{3, 2} & \cdots & J_{3, 20}\end{array}\right]\left[\begin{array}{c}\Delta g_{1} \\\Delta g_{2} \\\vdots \\\Delta g_{20}\end{array}\right].$ | (7) |
2 视觉标定方法2.1 位姿测量末端动平台的位姿测量可以通过动平台上固连的相机,借助计算机视觉的方法测量世界坐标系下的固定参照物来实现。为降低视觉方法的识别难度,提高视觉相机的辨识速度,实验中所选用的靶标为AprilTag,为一种类似于二维码的平面点阵图形,在各类视觉识别和视觉标定任务中得到了广泛的应用。相比普通的二维码和其他类型的视觉靶标,AprilTag在不同光照条件以及不同位置姿态下具有更高的识别率和更强的鲁棒性,同时拥有更高的视觉定位精度[16-17],能够满足标定过程中视觉位姿测量的要求。
相机测量位姿的原理为求解从世界坐标系到像素坐标系的坐标变换[18],进而求得相机及与其固连的动平台相对于世界坐标系的位置和姿态。该视觉相机的位姿测量原理如图 3所示。对一般情况下,考虑在视觉相机坐标系下测量得到的AprilTag位置为Ct,其姿态为CRt,AprilTag在世界坐标系下的位置为t,记视觉相机相对于动平台的位置和姿态分别为bC和RC,则得到位置和姿态关系如下:
$\boldsymbol{t}=\boldsymbol{p}+\boldsymbol{R}\left(\boldsymbol{b}_{\mathrm{C}}+{^{\mathrm{C}}} \boldsymbol{t}\right).$ | (8) |
![]() |
图 3 双目视觉相机位姿测量原理 |
图选项 |
且有
$\boldsymbol{R}^{\mathrm{C}} \boldsymbol{R}_{\mathrm{t}}=\boldsymbol{I}.$ | (9) |
$\boldsymbol{R}={ }^{\mathrm{C}} \boldsymbol{R}_{\mathrm{t}}^{-1}={ }^{\mathrm{C}} \boldsymbol{R}_{\mathrm{t}}^{\mathrm{T}}, $ | (10) |
$\boldsymbol{p}=\boldsymbol{t}-{ }^{\mathrm{C}} \boldsymbol{R}_{\mathrm{t}}^{\mathrm{T}}\left(\boldsymbol{b}_{\mathrm{C}}+{ }{^{\mathrm{C}}} \boldsymbol{t}\right).$ | (11) |
$\left\|\tilde{\boldsymbol{p}}_{\mathrm{m}}-\varphi^{\mathrm{DK}}\left(\boldsymbol{l}_{\mathrm{m}}, \boldsymbol{g}\right)\right\|_{2}=0.$ | (12) |
$\begin{gathered}\underset{\boldsymbol{g} \in \varOmega}{\operatorname{argmin}} F_{1}=\underset{\boldsymbol{g} \in \varOmega}{\operatorname{argmin}}\left\|\tilde{\boldsymbol{p}}_{\mathrm{m}}-\tilde{\boldsymbol{p}}_{\mathrm{r}}\right\|_{2}= \\\underset{{g} \in \varOmega}{\operatorname{argmin}}\left\|\tilde{\boldsymbol{p}}_{\mathrm{m}}-\varphi^{\mathrm{DK}}\left(\boldsymbol{l}_{\mathrm{m}}, \boldsymbol{g}\right)\right\|_{2}.\end{gathered}$ | (13) |
$\begin{gathered}\underset{\boldsymbol{g} \in \varOmega}{\operatorname{argmin}} F_{2}=\underset{\boldsymbol{g} \in \varOmega}{\operatorname{argmin}}\left\|\boldsymbol{l}_{\mathrm{m}}-\boldsymbol{l}_{\mathrm{r}}\right\|_{2}= \\\underset{\boldsymbol{g} \in \varOmega}{\operatorname{argmin}}\left\|\boldsymbol{l}^{\mathrm{m}}-\varphi^{\mathrm{IK}}\left(\tilde{\boldsymbol{p}}_{\mathrm{m}}, \boldsymbol{g}\right)\right\|_{2} .\end{gathered}$ | (14) |
![]() |
图 4 视觉标定算法流程图 |
图选项 |
2.3 误差补偿由于实际工作环境条件下,索驱动机器人的定位精度还会受到滑轮几何形状、绳索弹性变形、绳索垂度以及其他非几何因素的影响[19-20]。在这些因素的影响下,经过几何参数识别后末端动平台仍会存在较大的残余误差,同时残余误差的分布存在与末端动平台x和y坐标的相关性。因此可以考虑利用关于x和y坐标的二次多项式对残余误差进行补偿。即将残余误差Δx和残余误差Δy分别表示为
$\left\{\begin{array}{l}\Delta x=a_{0}+a_{1} x+a_{2} y+a_{3} x^{2}+a_{4} x y+a_{5} y^{2}, \\\Delta y=b_{0}+b_{1} x+b_{2} y+b_{3} x^{2}+b_{4} x y+b_{5} y^{2}.\end{array}\right.$ | (15) |
3 标定算法验证针对本文所提出的标定方法,利用MATLAB软件对该标定方法中的参数识别算法进行仿真验证。首先,在不存在观测误差的理想情况下,对该算法的正确性进行验证。在该四索并联机器人的平面工作空间内,按照给定的x方向间隔和y方向间隔,将工作空间内的一系列网格点设置为位姿测量点,根据所假定的待标定几何参数的名义值g,通过运动学逆解
进一步,在考虑观测误差的情况下,利用计算机数值仿真的方法对该参数识别算法的精度进行分析。与前述仿真过程类似,采用相同的方式生成一系列给定位姿
表 1 观测误差分布参数
误差项 | 分布期望μ | 分布标准差σm |
相机位置测量/mm | 0 | 2.00 |
相机姿态测量/rad | 0 | 0.011 |
索长测量误差/mm | 0 | 0.10 |
表选项
利用标定算法按照上述方法进行数值仿真,误差结果如图 5所示。各测量点上的平均偏差为0.41 mm,最大偏差为1.45 mm。
![]() |
图 5 标定出索点、索结点和初始索长仿真结果 |
图选项 |
考虑到动平台的尺寸较小,其加工精度较高,且动平台的出索点坐标能够通过外部测量方式精确获取,因此考虑不对动平台出索点坐标进行标定,将待标定的几何参数个数减少为12个。采用与上文相同的方法进行仿真。其各点上的定位误差结果如图 6所示。各测量点上的平均偏差为0.38 mm,最大偏差为1.19 mm。
![]() |
图 6 标定出索点和初始索长仿真结果 |
图选项 |
![]() |
图 7 选取待标定几何参数对标定结果的影响对比 |
图选项 |
综上,经过仿真分析发现,在使用实测的动平台出索点坐标而不对末端动平台的出索点进行参数标识的情况下,标定结果的精度更高,定位误差更小。综上,在实际标定过程中使用末端动平台出索点的测量值,待辨识的几何参数为4个静平台出索点的坐标和初始索长值向量。
4 实验验证4.1 标定实验为验证在工作环境中该基于视觉相机的标定算法的标定精度,在实验室搭建相同结构的索并联机器人进行实验验证。实验中所使用的平面四索并联机器人如图 8所示。该平面索并联机器人的末端动平台通过4组平行索分别与4个索驱动单元连接。使用Beckhoff CX5130控制器实现末端动平台的姿态控制。在末端动平台上固连一台双目视觉相机用于测量末端动平台的位姿。在与世界坐标系固连的货架上贴有AprilTag。双目视觉相机通过检测AprilTag在相机坐标系下的位置和姿态,反算出动平台的位置和姿态,实现动平台位姿的测量。可以通过在不同位置粘贴内容不同的AprilTag来增加双目视觉相机的测量范围,实现大工作空间标定的要求。标定完成后,通过外部的激光跟踪仪测量动平台的实际位置,评估标定后末端的定位误差。
![]() |
图 8 平面四索仓储物流机器人实验平台 |
图选项 |
由于该平面四索并联机器人的应用背景为物流仓库的货物堆垛工作,主要交互对象为具有网格化特点的货架,因此按照网格节点等间距均匀选取测量点是一种简单易行的方式。在平面四索并联机器人的工作空间内,选取合适的测量间距,测量28组位姿数据进行几何参数标定实验。将几何参数的名义值代入控制系统,控制末端动平台粗略运动至测量位置。利用双目视觉相机测量此时末端动平台的位姿,并通过电机编码器换算得到各索的相对索长,根据测量结果进行几何参数辨识。在进行几何参数辨识后,由于末端动平台的定位精度受到滑轮效应,绳索弹性以及其他非几何参数的影响,其仍会存在一定的定位误差。为进一步提高定位精度,采用关于末端动平台x和y坐标的二次多项式对末端动平台的残余误差拟合,并进行误差补偿。
为了验证标定后平面四索并联机器人实际工作时的定位精度,利用激光跟踪仪对标定后末端动平台的定位精度进行测量,并与给定的定位坐标进行比较,计算得到末端动平台的定位误差。
4.2 实验结果利用缩比模型装置进行实验,在指定网格节点上利用视觉相机测量末端动平台的位姿并读取电机编码器对应的索长向量,进行几何参数辨识。实验中几何参数识别结果如表 2所示。使用激光跟踪仪采集测量点的实际位置对参数辨识后的定位误差进行评估,分别计算得到参数辨识后末端动平台的定位误差如图 9和10所示。经过几何参数辨识后,末端动平台的x方向定位的最大正偏差为+1.94 mm,最大负偏差为-4.71 mm,x方向定位精度为6.65 mm;y方向定位的最大正偏差为+11.84 mm,最大负偏差为-1.97 mm,y方向的定位精度为13.81 mm。
表 2 几何参数标定结果
参数 | 参数值/mm | 参数 | 参数值/mm | |
xA1 | 732.742 | xA4 | 3 696.265 | |
yA1 | 484.979 | yA4 | 515.093 | |
xA2 | 75.782 | l0, 1 | 1 142.108 | |
yA2 | 3 021.288 | l0, 2 | 3 031.481 | |
xA3 | 4 484.074 | l0, 3 | 3 438.888 | |
yA3 | 3 016.239 | l0, 4 | 1 642.021 |
表选项
![]() |
图 9 几何参数识别后动平台x方向定位误差 |
图选项 |
![]() |
图 10 几何参数识别后动平台y方向定位误差 |
图选项 |
为进一步减小末端动平台的定位误差,采用关于动平台x和y坐标的二次多项式对几何参数识别后双目视觉相机测量得到的末端动平台的定位残余误差进行拟合,并进行误差补偿,得到补偿后的末端动平台定位误差如图 11和12所示。经几何参数识别和误差补偿后,再次用激光跟踪仪测量末端动平台的定位精度。测量得到末端动平台的x方向定位的最大正偏差为+0.41 mm,最大负偏差为-0.42 mm,x方向定位精度为0.83 mm;y方向定位的最大正偏差为+0.45 mm,最大负偏差为-0.45 mm,y方向的定位精度为0.90 mm。根据标定实验结果,平面四索并联机器人末端动平台的x方向定位误差和y方向定位误差均小于1 mm。按偏差距离
![]() |
图 11 误差补偿后动平台x方向定位误差 |
图选项 |
![]() |
图 12 误差补偿后动平台y方向定位误差 |
图选项 |
![]() |
图 13 误差补偿后末端动平台定位误差 |
图选项 |
5 结论针对物流仓储用索驱动机器人需要多次进行精度标定的特点,本文提出了一种基于双目视觉的平面四索机器人运动学参数自标定方法,通过在货架上粘贴的二维码,并采用安装在动平台上的双目相机进行测量,利用非线性最小二乘算法进行参数识别,并利用关于末端动平台位置坐标的二次多项式进行误差补偿,可以不借助外部昂贵的测量设备,完成机器人的自标定;在实验室搭建的4 m尺度索机器人模型中,本文标定方法的最大定位误差为0.58 mm。
参考文献
[1] | 张飞, 张彬, 周烽, 等. 面向自动仓储的绳索牵引并联机器人构型选择与参数优化[J]. 机械工程学报, 2020, 56(1): 1-8. ZHANG F, ZHANG B, ZHOU F, et al. Configuration selection and parameter optimization of redundantly actuated cable-driven parallel robots[J]. Journal of Mechanical Engineering, 2020, 56(1): 1-8. (in Chinese) |
[2] | TANG X Q. An overview of the development for cable-driven parallel manipulator[J]. Advances in Mechanical Engineering, 2014, 2014: 823028. |
[3] | RAMADAN M, SALAH B, NOCHE B. Innovative estimating travel time model for dual-command cycle time of Stewart-Gough platform in automated storage/retrieval systems[C]//ASME 2012 International Design Engineering Technical Conferences and Computers and Information in Engineering Conference. Chicago, USA: ASME, 2012: 737-743. |
[4] | BRUCKMANN T, STURM C, FEHLBERG L, et al. An energy-efficient wire-based storage and retrieval system[C]//2013 IEEE/ASME International Conference on Advanced Intelligent Mechatronics. Wollongong, Australia: IEEE, 2013: 631-636. |
[5] | LAU D. Initial length and pose calibration for cable-driven parallel robots with relative length feedback[C]//3rd International Conference on Cable-Driven Parallel Robots (CableCon). Cham, Switzerland: Springer, 2018: 140-151. |
[6] | MAJARENA A C, SANTOLARIA J, SAMPER D, et al. An overview of kinematic and calibration models using internal/external sensors or constraints to improve the behavior of spatial parallel mechanisms[J]. Sensors, 2010, 10(11): 10256-10297. DOI:10.3390/s101110256 |
[7] | YUAN H, YOU X H, ZHANG Y Q, et al. A novel calibration algorithm for cable-driven parallel robots with application to rehabilitation[J]. Applied Sciences, 2019, 9(11): 2182. DOI:10.3390/app9112182 |
[8] | 郑亚青. 6自由度绳牵引并联机构的运动学参数标定[J]. 华侨大学学报(自然科学版), 2006, 27(2): 184-188. ZHENG Y Q. Kinematic calibration of 6-DOF wire-driven parallel manipulators[J]. Journal of Huaqiao University (Natural Science), 2006, 27(2): 184-188. (in Chinese) |
[9] | GARCíA-VANEGAS A, LIBERATO-TAFUR B, FORERO M G, et al. Automatic vision based calibration system for planar cable-driven parallel robots[M]//MANUEL G F, BRHAYAN L T, ANDRES G V, et al. Pattern recognition and image analysis. Cham: Springer, 2019: 600-609. |
[10] | 黄田, 汪劲松, CHETWYND D G, 等. 并联构型装备几何参数可辨识性研究[J]. 机械工程学报, 2002, 38(S1): 1-6. HUANG T, WANG J S, CHETWYND D G, et al. Investigation into the identifiability of geometric parameters of pkm systems using a subset of pose error measurements[J]. Chinese Journal of Mechanical Engineering, 2002, 38(S1): 1-6. (in Chinese) |
[11] | VARZIRI M S, NOTASH L. Kinematic calibration of a wire-actuated parallel robot[J]. Mechanism and Machine Theory, 2007, 42(8): 960-976. DOI:10.1016/j.mechmachtheory.2006.07.007 |
[12] | ZHENG T J, WANG Y, YANG G L, et al. Self-calibration method for two DOF cable-driven joint module[C]//Recent Trends in Intelligent Computing, Communication and Devices: Proceedings of ICCD 2018. Guangzhou, China: Springer, 2020: 983-991. |
[13] | LOU Y N, LIN H Y, QUAN P K, et al. Self-calibration for the general cable-driven serial manipulator with multi-segment cables[J]. Electronics, 2021, 10(4): 444. DOI:10.3390/electronics10040444 |
[14] | MIERMEISTER P, POTT A. Auto calibration method for cable-driven parallel robots using force sensors[M]//LENARCIC J, HUSTY M. Latest advances in robot kinematics. Dordrecht: Springer, 2012: 269-276. |
[15] | JIN X J, JUNG J, KO S Y, et al. Geometric parameter calibration for a cable-driven parallel robot based on a single one-dimensional laser distance sensor measurement and experimental modeling[J]. Sensors, 2018, 18(7): 2392. DOI:10.3390/s18072392 |
[16] | OLSON E. AprilTag: A robust and flexible visual fiducial system[C]//2011 IEEE International Conference on Robotics and Automation. Shanghai, China: IEEE, 2011: 3400-3407. |
[17] | XU W F, YAN P H, WANG F X, et al. Vision-based simultaneous measurement of manipulator configuration and target pose for an intelligent cable-driven robot[J]. Mechanical Systems and Signal Processing, 2022, 165: 108347. DOI:10.1016/j.ymssp.2021.108347 |
[18] | 路红亮. 机器视觉中相机标定方法的研究[D]. 沈阳: 沈阳工业大学, 2013. LU H L. Camera calibration method for machine vision[D]. Shenyang: Shenyang University of Technology, 2013. (in Chinese) |
[19] | ZHANG F, SHANG W W, LI G J, et al. Calibration of geometric parameters and error compensation of non-geometric parameters for cable-driven parallel robots[J]. Mechatronics, 2021, 77: 102595. DOI:10.1016/j.mechatronics.2021.102595 |
[20] | ZHANG Z K, XIE G Q, SHAO Z F, et al. Kinematic calibration of cable-driven parallel robots considering the pulley kinematics[J]. Mechanism and Machine Theory, 2022, 169: 104648. DOI:10.1016/j.mechmachtheory.2021.104648 |