Appearance
注
本文的代码实现使用了pinocchio库
原理讲解
逆运动学这里主要方法总结为:Pseudo inversing a Jacobian iteratively until convergence
对于Jacobian以及其在李代数流形下的求导,可以参考这个链接
Jacobian of the task(关节角度到姿态误差)
(PS:速度Jacobian是力Jacobian的转置) 设当前机械臂位姿为
为了让误差收敛,我们希望误差满足如下方程:
这里
这里的
由于我们希望
PS: 全微分公式为
因为,
姿态误差的定义(SE(3)中的度量)
此处,我们定义,基坐标系为
在特殊欧几里德群中,执行器和目标姿态相对于
需要指出的是,要定义误差,就要定义度量(metrics),这里我们首先需要进行对数映射
为了方便书写,我们记
然后再对
具体而言,本文中我们定义姿态误差如下
可以看出,以上
Frame Jacobian(从关节角度到执行器姿态)
上式中
这里具体细节推导请参考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”
由于有
又因为
故得到
我们假定
上式中,我们
至此,我们可以去处理一些
Effect of the log-derivative
Log-derivative with a single non-singular task
首先引入两个公式,具体证明参考官方Jlog6()文档
可以使用如下程序验证
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最终结论(单点目标)
因为
又因为,我们希望
由于
故可得:
又因为
最终得到
其实根据
优化视角看IK问题
无damping,
以优化的视角来看,上述的无约束情况的IK问题,可以写成如下的二次规划问题,(这里用到了导数为0的性质) 此处之所以要把求逆变成优化问题,其实是为了方便计算机求解
上述IK求解过程中,若这里
此前直接推导所得的IK结果就可以改写成
需要指出的是,在实际的求解过程中,不应该采用直接求逆,而应该i选择伪逆。
接下来解释论证本小节的优化问题和原IK问题的等价性
由于我们的优化问题等价于如下问题
在上式等号两边均左乘
又因为,
故,可得
显然,和此前的公式一致。
存在damping,
当存在damping时,我们再通过在
不妨令
程序里可以写为:
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)