基本概念
- PoE(Product of Exponential)指数积公式。
- PoE和DH的作用都是一样的。
- 实际使用过程中,绝大多数在售的机器人还都是使用DH模型进行建模的,所以为了验证正确性,在选取螺旋轴的时候最好还是和DH模型方向对正。
- PoE模型的优势:更好的应用于并联机器人结构、不需要对中间关节进行建模,虽然描述量有4n(DH)变为了6n。
- 为了规范在使用PoE进行正运动学建模的时候一定要指明是相对于基座标系{s}还是末端坐标系{b}
- 螺旋轴上选择一点可以是任意的。
这里以UR5为例子,其中{b}{s}和旋转轴方向和UR5的厂家DH模型对齐,所以其正确性可以和真实机器人对照。
正运动学
UR5的PoE模型如下图所示。
但是图中并没有和真实的DH参数对齐,因此不方便验证其正确性。
所以参考->UR机械臂正逆运动学求解这篇博文的真实DH模型进行重新建模。
建模后:
验证结果,这里只展示任意一组关节角,对照DH建模和PoE建模的结果。
可以看出结果对应误差为10e-9,因此PoE建模正确。
源码
%% PoE-基座标系建模
% 参数
mm=pow(10,-3);
d4=109.15*mm;
d6=82.3*mm;
a2=425*mm;
a3=392.25*mm;
d1=89.459*mm;
d5=94.65*mm;
%M
R=[1 0 0;0 0 -1;0 1 0];
P=[-a2-a3;-d4-d6;d1-d5];
M=[R P;0 0 0 1];
%旋转轴
w6=[0;-1;0];
v6=-cross(w6,P);
S6=[w6;v6];
w5=[0;0;-1];
v5=-cross(w5,[-a2-a3;-d4;d1]);
S5=[w5;v5];
w4=[0;-1;0];
v4=-cross(w4,[-a2-a3;0;d1]);
S4=[w4;v4];
w3=[0;-1;0];
v3=-cross(w3,[-a2;0;d1]);
S3=[w3;v3];
w2=[0;-1;0];
v2=-cross(w2,[0;0;d1]);
S2=[w2;v2];
w1=[0;0;1];
v1=-cross(w1,[0;0;0]);
S1=[w1;v1];
theta=randpi(6);
disp(theta.')
PoE_model_FK=FKinSpace(M,[S1 S2 S3 S4 S5 S6],theta)
%% robotic toolbox
mdl_ur5;
DH_model_FK=ur5.fkine(theta)
%% compare
[error,~,~]=PosRotError(PoE_model_FK,mdlFK2Trans(DH_model_FK));
norm(error)
一阶运动学
需要注意的是,PoE建模所定义的雅可比矩阵和DH建模所定义的雅可比矩阵是不同的。具体表在PoE建模的Js的第i列Jsi只是描述第i各关节相对于固定坐标系的旋量。
如果要和DH建模的UR5进比较验证其正确性则需要经过一些转化,这里直接给出结果。
可以看出结果是对应的,因此建模正确。
源码后续更新。