Skip to content


本文的代码实现使用了pinocchio库

原理讲解

逆运动学这里主要方法总结为:Pseudo inversing a Jacobian iteratively until convergence

对于Jacobian以及其在李代数流形下的求导,可以参考这个链接

Jacobian of the task(关节角度到姿态误差)

(PS:速度Jacobian是力Jacobian的转置) 设当前机械臂位姿为q,这里我们可以设位姿误差写为e(q).在逆运动学中,我们需要的就是位姿误差收敛到0。所以 Jacobian of the task 就是 Jacobian of the e(q).

为了让误差收敛,我们希望误差满足如下方程:

e˙(q)=αe(q), (α>0)

这里e˙(q)可以理解成期望的执行器的位姿速度

这里的J(q)eq的Jacobian

Jerr(q):=eq(q)

由于我们希望e˙(q)=αe(q)成立,又因为

e˙(q)=ddte(q)=eq(q)ddtq=Jerr(q)q˙

PS: 全微分公式为de=eqdq+etdt

因为,e为位姿误差,不显含t所以et=0

姿态误差的定义(SE(3)中的度量)

此处,我们定义,基坐标系为frame 0,机器人执行器坐标系为frame b,目标坐标系为frame t

在特殊欧几里德群中,执行器和目标姿态相对于frame 0的姿态差分别为T0bSE(3)T0tSE(3)

需要指出的是,要定义误差,就要定义度量(metrics),这里我们首先需要进行对数映射

SE(3)R4×4se(3)R6

为了方便书写,我们记log6代表了如上式从SE(3)se(3)的映射

然后再对se(3)六维向量求范数,从而得到度量。需要指出的是,SE(3)上并没有公认的权威度量定义

具体而言,本文中我们定义姿态误差如下

e(q):=T0tT0b=log6(Tb0T0t)=log6(Tbt)

可以看出,以上e(q)的定义本质上也是从关节流形空间到李代数空间的一个映射。

Frame Jacobian(从关节角度到执行器姿态)

bJ0b(q)=T0bq(q)=limτ0T0b(qτ)T0b(q)τ=log6(Tb0(q)(T0b(q)expc(τ)))τ|τ=0

上式中expc是从切空间位移映射到关节空间位移,即

τ=vδtcC

这里具体细节推导请参考A micro Lie theory for state estimation in robotics这篇文章。

在实际的pinocchio使用中,指数映射运算其实就对应了pinocchio.integrate,具体来说

python
tau = velocity * dt
q * exp(tau) := pinocchio.integrate(model, q, tau)

PS:(:= 符号代表“定义为”)

Pose task Jacobian (从关节角度到误差,并写成与关节角度以及姿态相关的形式)

由于我们最终要求“误差Jacobian的表达式”,并且希望误差Jacobian中的内容都写成和关节角相关的形式。

这一小节的目的就是结合上面两小节,分别从“误差和执行器姿态关系”以及“执行器姿态到关节角度关系”两个方面,将上面两小节推导结果进行整合,从而得到最终的“由关节角度表示的任务Jacobian”

由于有

e(q)=log6(Tbt)

又因为

Jerr(q):=eq(q)

故得到

J(q):=eq(q)=log6(Tbt)q=log6(Tb0T0t)q=log6(Tb0T0t)Tb0Tb0T0bT0bq

我们假定T0t是恒定的,所以可以忽略掉T0tTb0的导数。通过一些推导J(q)可以写成如下形式。关于log6(AB)A形式的具体的推导还是看这篇文章,此处略去一些细节

Jerr(q)=log6(Tb0T0t)Tb0Tb0T0bT0bq=Jlog6(Ttb)bJ0b(q)

上式中,我们Jlog6的定义如下

Jlog6(T)=log6(T)T

至此,我们可以去处理一些J(q)非奇异情况的问题了。

Effect of the log-derivative

Log-derivative with a single non-singular task

首先引入两个公式,具体证明参考官方Jlog6()文档

Jlog6(T1)1log6T=log6(T)Jlog6(T1)=Jlog6(T)

可以使用如下程序验证

python
import pinocchio as pin
import numpy as np
T = pin.SE3.Random()
print(pin.log6(T))
print(pin.Motion(np.linalg.inv(pin.Jlog6(T.inverse()))@pin.log6(T)))

需要注意的是,在实际使用中,我们通常不写成

python
np.linalg.inv(A) @ b

为了避免求逆,最好还是写成

python
np.linalg.solve(A, b)

IK最终结论(单点目标)

因为

Jerr(q):=eq(q)Jerr(q)dqdt=dedt

又因为,我们希望de/dt=αe(q), (α>0),可令α=1,故有

Jerr(q)v=e(q)Jlog6(Ttb)bJ0b(q)v=e(q)bJ0b(q)v=Jlog6(Ttb)1e(q)

由于

e(q)=log6(Tbt)=log6(Ttb)

故可得:

bJ0b(q)v=Jlog6(Ttb)1log6(Ttb)

又因为

Jlog6(T1)1log6T=log6(T)

最终得到

v=bJ0b(q)1Jlog6(Ttb)1log6(Ttb)=bJ0b(q)1Jlog6(Ttb1)1log6(Ttb)=bJ0b(q)1log6(Ttb)=bJ0b(q)1e(q)=bJ0b(q)1e˙(q)

其实根据bJ0b(q)作为Frame Jacobian的定义也知道bJ0b(q)v=e˙(q)

优化视角看IK问题

无damping,λ=0

以优化的视角来看,上述的无约束情况的IK问题,可以写成如下的二次规划问题,(这里用到了导数为0的性质) 此处之所以要把求逆变成优化问题,其实是为了方便计算机求解

v=argminv12vTPv+QTvPv=Q

上述IK求解过程中,若这里λ=0.在这种情况下,我们可以直接令其中PQ写成如下形式

Jl:=Jlog6(Ttb)Jb:=bJ0b(q)P=JbTJlTWJlJb+λI=(WJlJb)TJlJb+λIQ=JbTJlTWe(q)=(WJlJb)Te(q)

此前直接推导所得的IK结果就可以改写成

v=Jb1e(q)

需要指出的是,在实际的求解过程中,不应该采用直接求逆,而应该i选择伪逆。

接下来解释论证本小节的优化问题和原IK问题的等价性

由于我们的优化问题等价于如下问题

Pv=Q=(WJlJb)Te(q)

在上式等号两边均左乘(WJlJb)T,可以得到

JlJbv=e(q)

又因为,

e(q):=log6(Ttb)Jl:=Jlog6(Ttb)Jl1e(q)=Jlog6(Ttb)1e(q)=Jlog6(Ttb1)1e(q)=Jlog6(Ttb1)1log6(Ttb)=log6(Ttb)=e(q)Jle(q)=e(q)

故,可得

v=Jb1e(q)

显然,和此前的公式一致。

存在damping,λ0

当存在damping时,我们再通过在Pv=(WJlJb)Te(q)等号两边均左乘(WJlJb)T,可以得到

v=[Jb+λJl1W1JlTJbT]1e(q)(JbTJlTWJlJb+λI)v=JbTJlTWJle(q)

不妨令W=I, 又因为Jle(q)=e(q),又因为JlJb=Jerror,可得

(JerrTJerr+λI)v=JerrTe(q)

程序里可以写为:

python
T_bt = robot.data.oMi[idx].actInv(T_t)
J_b = pin.computeJointJacobian(robot.model, robot.data, q, idx)
J_l = -pin.Jlog6(T_bt.inverse())

# 接下来会这里会利用J_error v^{*} = -e(q)来求v^{*}
J_error = J_l.dot(J_b)
e_q = pin.log(T_bt).vector

v_star = np.linalg.solve(J_error.T.dot(J_error) + damp * np.eye(6), -J_error.T.dot(e_q))
q = pin.integrate(robot.model, q, v_star*dt)