作者简介: 刘佳君(1987—), 男(汉), 辽宁, 博士研究生。
为了解决水轮机叶片坑内修焊空间加工作业需求,研制了适用于复杂曲面的两端吸附式爬壁机器人,该机器人由永磁间隙吸附式移动平台、多自由度机械臂(包括3个主动关节和3个被动关节)和永磁间隙吸附式末端作业单元组成。针对给定末端路径,这种结构的机器人需基于局部平面假设来完成主动关节的轨迹生成。但经仿真分析,在1.5 m半径外球面上的简化造成的误差达到5 mm以上,不满足修焊工艺要求精度。为此,提出在机械臂加工运动过程中,通过Jacobi矩阵将末端作业单元在Descartes坐标系下的误差转换为关节角修正量以完成动态修正的算法。仿真实验表明,该算法可有效降低运动路径误差至1 mm以下。
A wall climbing robot with both ends using magnetic adsorption is developed for on-site hydraulic turbine blade repairs. The magnetic mobile platform has a multiple degrees of freedom (DOF) manipulator and an end operating unit. The manipulator has 3 active and 3 passive joints, so the trajectory planning method for a given working path assumes a local curve where the end effector of the manipulator works on a plane. However, simulations for a sphere with a 1.5 m curvature show that the path error due to this assumption is larger than 5 mm. A correction algorithm to reduce the error transforms the error from Cartesian space to the joint space through a Jacobian matrix. Simulations show that the error can be reduced to less than 1 mm by this algorithm.
针对三峡等大型电站水轮叶片坑内修复机器人技术及装备在国内外尚属空白的现状,本文作者所在课题组多年来从机器人机械结构设计[1]、自主定位[2,3]、主从分布式控制[4]等方面,开展了具有中国自主知识产权的面向复杂曲面大型结构件的机器人修焊作业单元关键技术研究,取得了一系列创新性成果,开发了如图1所示的具有自主知识产权、适用于三峡等大型水电站的两端吸附式爬壁机器人样机用于叶片修复。该机器与目前国际上最先进的SCOMPI系列轨道式水轮机专用修复机器人[5,6]相比,不仅可以摆脱在修复过程中装拆轨道的束缚,而且通过移动平台和末端作业单元的两端永磁间隙吸附的独特设计有效地克服了串联式关节型机械臂结构存在的刚度差、加工效率不高、难以承受较大的切削力的不足,大大提高了其曲面自适应能力、整体刚性、作业范围和修复生产率。
如图1所示,机器人移动平台和末端作业单元采用永磁间隙吸附方式吸附于叶片表面,多自由度机械臂的被动关节根据待作业曲面的形貌变化进行随形运动,与主动关节共同决定末端作业单元运动路径。考虑到末端作业单元完成一次作业的运动范围相对有限,本文假设该局部作业曲面近似为平面(以下称为“局部平面假设”)。在此基础上,近似估计目标路径及被动关节运动,生成主动关节运动轨迹。但实际的混流式水轮叶片表面是曲率半径不断变化的呈“X”型扭曲状的复杂空间曲面,机器人移动平台和末端作业单元可能处于不同的空间曲面上。当机械臂位于曲率半径较小的区域时,仍然采用平面来近似被作业曲面进行主动关节的轨迹生成,将使得末端作业单元的实际运动路径与目标作业路径间存在较大误差。
本文建立了修复机械臂的运动学模型,提出了相应的机械臂轨迹生成方法; 然后根据水轮机叶片表面形貌情况[7,8]选择曲率半径为1.5 m的外球面进行了针对“局部平面假设”的运动路径误差分析,提出了根据运动过程中测算的机械臂末端作业单元在Descartes空间的位置误差,通过Jacobi矩阵推算需要在关节空间施加的修正量进行误差修正的算法,并对该算法进行了仿真计算。
采用D-H方法建立机器人正运动学模型[9]。各关节D-H坐标系及D-H参数如图2、表1所示。
θi为关节变量,以坐标轴 Zi-1为轴,正方向为逆时针。{6}坐标系与末端作业单元固联, Y6轴负方向在修复作业过程中保持与作业运动方向重合。
由D-H参数,相邻坐标系之间的坐标转换矩阵为
进一步的机器人末端作业单元上固联的{6}坐标系相对于基坐标系{0}的位姿变换矩阵为
6自由度机械臂逆运动学问题仅在其具有3个相邻且相交于一点(或互相平行)的关节轴的情况下才具有封闭解(Pieper准则[10])。本研究涉及的机械臂不满足此要求,一般情况下不存在逆运动学解析解。但若作业过程中,移动平台与末端作业单元始终位于同一平面,则存在解析解,此时 θ1 =0, θ4 =-π /2, θ5 =π /2。代入式(2)有
其中: Si表示sin θi, Sij表示sin( θi+θj); Ci表示cos θi, Cij表示cos( θi+θj)。
设已知条件为末端作业单元在基坐标系{0}系中的 X分量
θ3的符号可由当前对应关节绝对编码器的角度根据“关节运动量最小”的原则确定。
根据表1中对关节变量的限制, θ2有定解。根据 Y6轴与作业运动方向的关系可得
综上,对于移动平台与末端作业单元位于同一平面的特殊情况,该机械臂逆运动学问题存在解析解,且根据一定的限制条件,解析解具有唯一性。而针对不满足Pieper准则的一般情况,一些学者为了得到全部逆运动学解(对于给定位姿, 6自由度机械臂至多可能存在16组解), 通过机械臂的逆运动学等式经过复杂的推导得到一元24次或16次方程,进而求取完备的逆运动学解[11]。但在实际生成中,不需要针对给定位姿求取完备的逆运动学解,因此本文采用非线性最优化的方式进行逆运动学求解。
令 Oi=[ r1 i r2 i r3 i]T; P=[ tx ty tz]T, 则
局部平面假设下,一次作业过程中表示末端作业单元姿态的3个向量 O10、 O20、 O30保持不变,表示末端作业单元位置的向量 P0可通过目标路径求出。定义误差函数 E为
于是,机械臂的逆运动学问题转化为针对误差函数 E的非线性最优化问题。
此种方法虽然能够较快地求取单一的逆运动学结果,但是求解结果受到初值的影响较大,多自由度机械臂逆运动学问题具有多解性,初值选取不当会收敛至不同解[12]。本文根据机械臂的实际作业情况,提出一种“两步法”逆运动学求解方法: 1) 令被动关节角 θ1 =0; θ4 =-π /2; θ5 =π /2, 通过式(4)—(6)求出各主动关节角; 2) 以上一步求取的解析解为初值,通过最优化方法将式(8)的误差函数最小化,从而求取各主、被动关节关节角。由于机械臂实际作业过程中,被动关节运动幅度较小,故此方法第一步中的假设合理。
数字控制器实现轨迹生成的过程中,连续的目标路径需要首先根据一定规则(本文采用等时间间隔规则)被离散化为 n个路径点。首先,由连续路径生成离散路径点在基坐标系{0}中的坐标序列 Pi( xi, yi, zi), 以及表示各个路径点处路径方向的单位向量序列{ ri}, 其中 i=1,2,3,…, n。进而,通过机器人逆运动学求解,求取各关节角度序列{ θkPi}。其中: k=1,2,3,…,6; i=1,2,3,…, n。
但实际轨迹生成中,已知条件为各个路径点在{0}坐标系 XZ平面内的投影坐标 PiXZ( xi,0, zi)及其运动方向向量在{0}系 XZ平面内的投影与 X0轴的夹角 θM(以下简称为“投影方向角”)。曲面形貌未知导致的位姿信息不完备使得无法直接完成各关节轨迹生成。下面介绍本文提出的轨迹生成方法。
首先,末端作业单元位于起始路径点 P0( x0, y0, z0)时,通过机械臂各关节安装的绝对编码器可以测量得出各主动、被动关节变量
其中: A=r13, B=r23, C=r33, D=x0 r13 +y0 r23 +z0 r33。
由此,其余路径点的完整坐标及方向向量均可通过该平面解析式及已知条件 PiXZ和 θM进行估计,从而进一步通过机器人逆运动学完成轨迹生成。
在第2节中,虽然通过对未知曲面的“局部平面假设”完成了关节轨迹生成,但是假设与实际曲面有偏差,该偏差会造成实际运动过程中末端作业单元的运行路径与目标路径间的误差。本文选取各方向曲率半径均最小、非理想状况最为严重的曲率半径1 .5 m的外球面作为作业面,对该误差进行分析。不失一般性,球面与机械臂的相对位置选择为: 球面与移动平台所在平面相切,切点在基座标系{0}的 XZ平面内投影与{0}系原点重合。由于修复作业中的典型路径为直线,典型修焊焊缝的宽度为10 mm、 长度100 mm, 故选择曲面上投影在基坐标系{0}的 XZ平面上为直线的一组路径为目标路径。结合机械臂的工作空间,选取投影在{0}系 XZ平面内坐标为(400 mm,0)的点为目标路径起点,路径长度为200 mm, 路径方向由投影方向角 θM确定。
本文定义在局部平面假设下生成的关节轨迹序列为{ θkPi}, 对应的末端作业单元位置序列为{ PPi}; 实际运动时的关节轨迹序列为{ θkRi}, 对应位置序列为{ PRi}; 目标路径对应的真实轨迹序列为{ θkAi}, 对应位置序列为{ PAi} ={ Pi}。其中: k=1,2,3,…,6; i=1,2,3,…, n。根据轨迹生成的过程, { PPi}与{ PAi}在{0}坐标系 XZ平面上的投影重合,但它们分别位于假设的平面和实际的曲面上。而实际运动时,控制器仅能保证主动关节按照生成的轨迹序列运动,即仅对 k=2,3,6, θkRi=θkPi成立,而被动关节序列则与实际曲面形状相关。故此时{ PRi}与{ PAi}存在偏差,定义路径误差为
其中, ‖ *‖F为Frobenius范数。
实际运动的位置序列{ PRi}的求取过程基于已知曲面对机械臂的几何限制条件。已知条件为各路径点对应的主动关节变量 θkRi( k=2,3,6)、 曲面形状及相对位置(此时为球面球心在{0}坐标系中的坐标 Ps( xs, ys, zs)及球面半径 Rs)。需要据此对被动关节变量进行求解,进而求取实际运动的位置序列。当机械臂末端作业单元稳定吸附于曲面上时,末端作业单元底部的3个万向滚珠(如图1)均与曲面相切。设万向滚珠球心与{6}系原点的高度差为 hb, 滚珠分布圆半径为 rb, 滚珠半径为 Rb, 那么3个万向滚珠在{6}坐标系中的坐标为
其中: φi=(2 i-1)π /3, i=1,2,3。
通过位姿变换矩阵式(1)可以求出3个万向滚珠在基坐标系{0}系中的坐标。而根据它们与曲面的相切关系可以分别列出3个非线性方程。当作业曲面为外球面时,相切关系可用球心距等于半径之和的形式表达,
由于主动关节变量和其他D-H参数均为已知,因此该3元非线性方程组仅有3个被动关节变量为未知量,可通过数值方法求解。
图3为误差分析结果,横坐标为与起点的距离,纵坐标为式(10)定义的路径误差。该分析选取了5组投影方向角不同的目标路径。由误差分析结果发现,在小曲率半径(1 .5 m)作业面上,局部平面假设在距离初始点较近的范围内产生的误差较小,但随着路径长度增加,最大误差达5 mm,仍然不能很好地满足工艺要求,有必要进一步对误差进行修正。
局部平面假设的数学本质是根据起始点 P0( x0, y0, z0)处的信息对未知曲面 y=f( x, z)进行Taylor展开,从而获取近似平面,
其中:
当机械臂各关节运行至第 i个轨迹点{ θkRi}时,末端作业单元实际位置{ PRi}与作为目标的真实位置{ PAi}存在偏差。令
此时,通过机械臂各关节绝对编码器返回的各关节变量,结合机械臂正运动学可以求得每个 PRi的全部3个分量( xRi, yRi, zRi)。但是,由于运动过程中曲面未知,对于 PAi仅 X分量 xAi与 Z分量 zAi已知。通过式(14)可计算出Δ xi与Δ zi。于是,机械臂正运动学公式为:
其中: Si表示sin θi, Sij表示sin( θi+θj); Ci表示cos θi, Cij表示cos( θi+θj)。
由式(15)、 (16)及Taylor公式可得
其中: 关节角误差Δ θki=θkAi-θkRi( k=1,2,3,4), J2 ×4为2 ×4的Jacobi矩阵。
整理式(17)得
通过误差分析相关计算可知,整个运动过程中被动关节角误差比主动关节角误差小至少一个数量级。那么,直接令Δ θ1 i=Δ θ4 i=0, 式(18)化为
其中,
矩阵 J2 ×2的行列式为
根据表1中各关节变量的限制范围,仅 θ3 =0时 J2 ×2行列式为0, 此时机械臂处于奇异位置,而这个位置在路径规划时会避开,因此在机械臂运动的全过程中, J2 ×2可逆,且
根据式(19), 可以通过当前末端作业单元 Descartes 空间内的误差量Δ xi与Δ zi计算关节空间内主动关节2、 3在第 i个路径点处应修正的角度Δ θ2 i, Δ θ3 i。
以下求解主动关节6在第 i个路径点处应进行的修正。由于 Y6轴在作业过程中始终与路径方向保持反向,那么根据式(2)以及已知的投影方向角 θM可得
其中, ΘAi=[ θ1 Ai, θ2 Ai, θ3 Ai, θ4 Ai, θ5 Ai, θ6 Ai]T。令 F( Θ) =r12( Θ)cos θM -r32( Θ)sin θM, 则根据Taylor公式及式(22)可得
式(23)中,仍然认为对于被动关节变量, Δ θki=0。除Δ θ6 i为未知外,其余均为已知。综上,当机械臂运行至第 i个路径点时,第 i组主动关节轨迹的修正量均可以求解。但此时应当修正的是 i+1组以后的主动关节轨迹,因此需要根据第 i个路径点Descartes空间下的误差估计其后续路径点主动关节轨迹的修正量。由于水轮机叶片为连续光滑曲面,因此对于任意正数 ε, 存在正数 n与 k, 使划分路径点数为 n时,
实际作业过程中,临近路径点的Jacobi矩阵的偏导数元素相差不大,故可以直接采用第 i个路径点的修正值对其后临近的路径点对应的主动关节角进行修正; 而待修正路径点距离修正值计算点 i较远时,将导致Taylor公式近似误差增大,此时应重新根据位置误差在当前点进行修正值的计算。
仿真实验在局部平面假设下误差最大的曲率半径1 .5 m外球面、 θM =0的条件下进行。修正进行的条件是: 当max (Δ xi,Δ zi) >0 .4 mm时进行修正。仿真结果表明: 即使在局部平面假设产生的误差最大的状况下,修正算法仍然成功地将误差进一步的限制在1 mm之内,修正效果良好(见图4)。
1) 针对项目组研制的适用于复杂曲面的两端永磁间隙吸附式水轮机叶片坑内修焊机器人,通过假设末端作业单元位于局部作业曲面上,提出并实现了一种由3个主动关节和3个被动关节组成的多自由度机械臂的作业运动轨迹生成方法。
2) 模拟仿真结果表明,在1.5 m曲率半径外球面的最强非理想条件下,按局部曲面作为平面的假设所生成的关节轨迹运动将使末端作业单元的实际运动路径相对目标路径产生约5 mm的路径误差。
3) 分析了产生误差的原因,提出一种基于 Jacobi 矩阵及Taylor公式的修正算法,将可以直接测算的Descartes空间内的误差转换至关节空间,以解析解形式估计出主动关节的修正量。仿真实验表明: 该算法可将路径误差由5 mm减小至 1 mm 以下,能够更好地满足作业工艺的要求。
[1] |
|
[2] |
|
[3] |
|
[4] |
|
[5] |
|
[6] |
|
[7] |
|
[8] |
|
[9] |
|
[10] |
|
[11] |
|
[12] |
|