空间代数
空间代数是一种在刚体动力学中常用的数学符号体系,用于表示和处理诸如速度、加速度和力等物理量。Pinocchio库就是基于这种数学符号体系构建的。它提供了专门的类来表示三维欧几里得空间中的坐标变换(命名为SE3)、空间运动向量(Motion)、空间力向量(Force)以及空间惯性(Inertia)。结合可用的方法,这使得Pinocchio成为一个高效的空间代数计算软件库。
模型与数据
Pinocchio的一个基本范式是严格区分 “模型” 和 “数据”。这里的 “模型” 指的是机器人的物理描述,包括定义其结构的运动学参数,可能还包括惯性参数。这些信息由一个专门的类来保存,一旦创建,Pinocchio的算法不会对其进行修改。而 “数据” 指的是所有计算结果的值。“数据” 会根据系统的关节配置、速度等因素而变化,例如,它包含每个连杆的速度和加速度。它还存储算法的中间计算结果和最终结果,以避免内存分配。通过这种划分,Pinocchio中的所有算法都遵循以下签名:
algorithm(model, data, arg1, arg2, ...)
其中arg1, arg2, ...
是函数的参数(例如配置或速度)。在对同一机器人执行多个不同任务时,尤其是涉及并行计算时,保持模型和数据的分离可以减少内存占用。每个进程可以使用自己的数据对象,同时共享相同的模型对象。在Pinocchio的算法中,模型对象始终保持不变,这增强了代码的可预测性。
可以使用C++ API创建模型,也可以从外部文件加载模型,这些文件可以是URDF、Lua(遵循RBDL标准)或Python格式。
关节
在一个模型中,机器人被表示为一个运动学树,它包含所有关节的集合、关节连接信息,以及可选的与每个连杆相关的惯性量。在Pinocchio中,一个关节可以有一个或多个自由度,并且它属于以下类别之一:
- 旋转关节:围绕固定轴旋转,该轴可以是(X)、(Y)、(Z)轴之一,也可以是自定义轴;
- 棱柱关节:沿固定轴平移,与旋转关节类似;
- 球形关节:在三维空间中自由旋转;
- 平移关节:在三维空间中自由平移;
- 平面关节:在二维空间中自由运动;
- 自由浮动关节:在三维空间中自由运动。平面关节和自由浮动关节通常用作移动机器人(如人形机器人、自动驾驶汽车或操作规划中的物体)运动学树的基础。
- 通过 “复合” 关节的概念,可以将多个普通关节组合成更复杂的关节。
注:在URDF格式中,可以定义 “固定” 类型的关节。然而,“固定” 关节实际上并不是真正的关节,因为它不能移动。出于效率考虑,它被视为模型的操作框架。
从关节到李群几何
每种类型的关节都有其特定的配置空间和切空间。例如,旋转关节的配置空间和切空间都是实数轴(R\mathbb{R}R),而球形关节的配置空间对应于三维旋转矩阵的集合,其切空间是三维实向量空间(R3\mathbb{R}^{3}R3)。有些配置空间可能不具备向量空间的性质,但必须赋予相应的积分(指数映射exp)和微分(对数映射log)算子。Pinocchio实现了所有这些特定的积分和微分算子。
有关此主题的更多内容,请参见 “处理李群几何”。
几何和碰撞模型
除了运动学模型,Pinocchio还定义了几何模型,即附着在运动学树上的体积。这个模型可用于显示机器人以及计算与碰撞相关的量。与运动学模型类似,固定的量(体积的位置和形状)存储在 “GeometricModel” 对象中,而相关算法使用的缓冲区和量则在另一个对象中定义。体积使用FCL库进行表示。机器人的各个部分附着在每个关节上,而环境中的障碍物则在世界坐标系中定义。基于FCL方法,实现了运动学树的碰撞和距离算法。
处理李群几何
Pinocchio在很大程度上依赖李群和李代数来处理运动,尤其是旋转。因此,它支持以下特殊群(SO(2)SO(2)SO(2))、(SO(3)SO(3)SO(3))、(SE(2)SE(2)SE(2))、(SE(3)SE(3)SE(3)),并实现了它们相关的代数(se(2)\mathfrak{se}(2)se(2))、(se(3)\mathfrak{se}(3)se(3))。
它有多种应用,例如表示机器人自由飞行关节(通常是移动机器人的底座)的运动,或者机器人连杆的运动。后者在碰撞检测中特别有用。
定义李代数的一般向量空间也很有意义。
在C++中使用(SE(2))与Pinocchio
作为一个示例,考虑一个在平面((R2×S1)(\mathbb{R}^2 \times \mathbb{S}^1)(R2×S1))中运动的移动机器人。
机器人从位置(poses=(xs,ys,θs)pose_s = (x_s,y_s,\theta_s)poses=(xs,ys,θs))出发,经过刚性运动(δu=(δx,δy,δθ)\delta_u=(\delta x,\delta y,\delta \theta)δu=(δx,δy,δθ))后,到达位置(poseg=(xg,yg,θg)pose_g = (x_{g},y_{g},\theta_{g})poseg=(xg,yg,θg))。
可以使用以下代码实例化相应的(SE(2)SE(2)SE(2))对象:
typedef double Scalar;
enum {
Options = 0};
SpecialEuclideanOperationTpl<2,Scalar,Options> aSE2;
SpecialEuclideanOperationTpl<2,Scalar,Options>::ConfigVector_t pose_s,pose_g;
SpecialEuclideanOperationTpl<2,Scalar,Options>::TangentVector_t delta_u;
可以将Scalar
替换为其他类型,如float
。
在这个例子中,(poses=(1,1,π/4)pose_s=(1,1,\pi/4)poses=(1,1,π/4)),(poseg=(3,1,−π/2)pose_g=(3,1,-\pi/2)poseg=(3,1,−π/2)),我们想要计算(δu\delta_uδu):
pose_s(0) = 1.0; pose_s(1) = 1.0;
pose_s(2) = cos(M_PI/4.0); pose_s(3) = sin(M_PI/4.0);
pose_g(0) = 3.0; pose_g(1)