6083 words
30 minutes
机器人学基础 第一章 刚体运动
首次发布: 2025-03-28
... 次访问

机械臂是由一个个的刚体连接而成。为了分析机器人的运动,首先需要一个刚体的运动学模型。通过将一个参考框架固连在刚体上,就可以用描述这个框架位姿的 4×44 \times 4 矩阵来描述刚体的运动。

1.1 位姿#

1.1.1 刚体固连框架#

在质点运动学中,为了描述质点的运动需要定义一个参考的固定坐标系。同样地,在刚体运动学中也需要定义一个固定的空间参考框架(框架的含义其实就是坐标系)。定义这个框架为 {S}\{S\}, 作为空间中的参考坐标系。

定义与刚体固连的框架{B}\{B\}, 作为刚体位姿描述的参考框架。根据几何学中的框架变换公式,刚体固连框架 {B}\{B\} 相对于空间参考框架 {S}\{S\} 的位姿可以用一个 4×44 \times 4 矩阵来描述

 BST=[ BSR SpBorg01]\ ^{S}_{B}T = \begin{bmatrix} \ ^{S}_{B} R & \ ^{S} p_{Borg} \\ 0 & 1 \end{bmatrix}

其中  BSR\ ^{S}_{B} R3×33 \times 3 的旋转矩阵,描述了刚体固连框架 {B}\{B\} 相对于空间参考框架 {S}\{S\} 的朝向旋转关系。 SpBorg\ ^{S} p_{Borg}3×13 \times 1 的列向量,描述了刚体固连框架 {B}\{B\} 相对于空间参考框架 {S}\{S\} 的平移关系。

这里的具体的变换关系是,假设有一个与空间参考框架 {S}\{S\} 重合的框架,此框架先通过一个旋转矩阵  BSR\ ^{S}_{B} R 旋转到一个特定的朝向,然后此框架的原点再根据向量  SpBorg\ ^{S} p_{Borg} 平移到一个位置,通过上述两次变换得到的这个新框架就是刚体固连框架 {B}\{B\}

frame

需要注意的是,这里框架的旋转与普通质点的旋转不同。形象化的表述可以是框架的三个坐标轴同时绕一个过空间参考框架 {S}\{S\} 的旋转轴做相同角度大小的旋转,从而得到新的三个坐标轴。

1.1.2 齐次坐标变换#

上文说到,刚体的绝对位姿可以用框架之间的旋转加平移得到,这个旋转加平移的数学描述采用了 4×44 \times 4 的形式(其实刚体的位姿采用旋转矩阵  BSR\ ^{S}_{B}R 和 平移向量  SpBorg\ ^{S}p_{Borg} 描述也是可以的,采用 4×44 \times 4 矩阵是因为有更好的运算性质)。在其他学科如计算机视觉中,这类 4×44 \times 4 矩阵有一个特殊的名称,叫齐次变换矩阵,“齐次”的含义源于对坐标的变换是齐次形式的。

设空间中有两个参考坐标系 {A}\{A\}{B}\{B\},两个参考坐标系之间的相对位置关系为 BAR\ ^{A}_{B} R ApBorg\ ^{A}p_{Borg}。假设空间中还有第三个点 qq,它在 {A}\{A\} 系下的坐标描述为  Aq\ ^{A}_{}q,在 {B}\{B\} 系中的坐标描述为  Bq\ ^{B}_{}q,则有变换关系为

 Aq= BAR Bq+ ApBorg\ ^{A}_{}q = \ ^{A}_{B} R \ ^{B}_{}q + \ ^{A}_{}p_{Borg}

这个公式就是在不同参考坐标系下坐标的变换公式。注意不同的参考坐标系的坐标轴单位矢量是不同的,因此这个公式是包含了线性变换的,而不是单纯的物理相对位矢变换。纯粹的物理相对位矢变换是纯矢量的计算,不涉及向量坐标分解的运算,其公式为

 Aq= ApBorg+ Bq\ ^{A}_{}\vec{q} = \ ^{A}_{}\overrightarrow{p_{Borg}} + \ ^{B}_{}\vec{q}

对坐标变换公式进行改写,使用点 qq 的齐次坐标 qˉ=[q1]\bar{q} = \begin{bmatrix}q \\ 1\end{bmatrix},并且令  BAT=[ BAR ApBorg01]\ ^{A}_{B}T = \begin{bmatrix}\ ^{A}_{B} R & \ ^{A}_{}p_{Borg}\\ 0 & 1 \end{bmatrix},则有

 Aqˉ= BAT Bqˉ\ ^{A}_{}\bar{q} = \ ^{A}_{B}T \ ^{B}_{}\bar{q}

这个矩阵的形式与描述刚体位姿的 4×44 \times 4 矩阵形式一致。

1.1.3 坐标系切换#

点的坐标切换#

根据上面的推导,不难发现描述刚体位姿的 4×44 \times 4 矩阵其实是一个齐次变换矩阵,更确切地说,是描述从空间坐标系 {S}\{S\} 下描述的坐标到 刚体坐标系 {B}\{B\} 下坐标描述的变换,即对于空间中的点 qq,它在空间坐标系 {S}\{S\} 和 刚体坐标系 {B}\{B\} 下的坐标之间的关系为

 Sqˉ= BST Bqˉ\ ^{S}_{}\bar{q} = \ ^{S}_{B}T \ ^{B}_{}\bar{q}

这个公式具有重要价值。试想假设我需要规划机械臂上的某一个点的运动,那就在机械臂上装一个摄像头或者传感器,可以得到在机械臂的某个连杆的坐标系下的这个点的坐标。但是很显然规划在空间绝对坐标系中进行会更加方便,因此,通过刚体位姿的描述矩阵可以将这个点的坐标变换到空间坐标系中,用于算法的规划。

刚体位姿切换#

刚体的位姿不同于点的坐标,空间中点有 3 个自由度,而刚体有 6 个自由度,刚体比点多出的那三个自由度正是刚体具有方向性,旋转带来的 3 个自由度。如前文所述,描述刚体的位姿用的也是 4×44 \times 4 矩阵  BST\ ^{S}_{B}T,那么是否存在类似于点的坐标切换的齐次变换公式呢?

答案是肯定的。首先,利用性质

 BSR=[ Sx^B Sy^B Sz^B]\ ^{S}_{B} R = \begin{bmatrix} \ ^{S}_{}\mathbf{\hat{x}}_B & \ ^{S}_{}\mathbf{\hat{y}}_B & \ ^{S}_{}\mathbf{\hat{z}}_B \end{bmatrix}

其中,  Sx^B, Sy^B, Sz^B\ ^{S}_{}\mathbf{\hat{x}}_B, \ ^{S}_{}\mathbf{\hat{y}}_B, \ ^{S}_{}\mathbf{\hat{z}}_B 分别是沿刚体固连框架 {B}\{B\} 坐标轴的三个单位向量(注意是三个自由单位向量,内积为1,因此在变换中不用考虑平移变换)在空间绝对框架 {S}\{S\} 中的表示。因此,对刚体的位姿在不同框架下的描述变换可以用对这三个点的坐标的变换来实现。

假设空间中有另外一个绝对参考框架 {S}\{S'\},有绝对参考框架之间的变换关系

 SST=[ SSR SpSorg01]\ ^{S}_{S'}T = \begin{bmatrix} \ ^{S}_{S'} R &\ ^{S}_{}p_{S'org} \\ 0 & 1\end{bmatrix}

那么有,

[ Sx^B Sy^B Sz^B]= SSR[ Sx^B Sy^B Sz^B]\begin{bmatrix} \ ^{S}_{}\mathbf{\hat{x}}_B & \ ^{S}_{}\mathbf{\hat{y}}_B & \ ^{S}_{}\mathbf{\hat{z}}_B \end{bmatrix} = \ ^{S}_{S'} R \begin{bmatrix} \ ^{S'}_{}\mathbf{\hat{x}}_B & \ ^{S'}_{}\mathbf{\hat{y}}_B & \ ^{S'}_{}\mathbf{\hat{z}}_B \end{bmatrix}

 BSR= SSR BSR\ ^{S}_{B} R = \ ^{S}_{S'}R \ ^{S'}_{B}R

现在再考虑刚体固连框架 {B}\{B\} 的坐标原点的变换情况,有

 SpBorg= SSR SpBorg+ SpSorg\ ^{S}_{}p_{Borg} = \ ^{S}_{S'}R \ ^{S'}_{} p_{Borg} + \ ^{S}_{}p_{S'org}

综合以上式子,可以得到

[ BSR SpBorg01]=[ SSR SpSorg01][ BSR SpBorg01]\begin{aligned} \begin{bmatrix} \ ^{S}_{B} R &\ ^{S}_{}p_{Borg} \\ 0 & 1\end{bmatrix} = \begin{bmatrix} \ ^{S}_{S'} R &\ ^{S}_{}p_{S'org} \\ 0 & 1\end{bmatrix}\begin{bmatrix} \ ^{S'}_{B} R &\ ^{S'}_{}p_{Borg} \\ 0 & 1\end{bmatrix} \end{aligned}

 BST= SST BST\ ^{S}_{B} T = \ ^{S}_{S'} T \ ^{S'}_{B}T

这个式子和点的坐标齐次变换相似,是在不同框架下刚体位姿的变换。

1.2 速度#

得到了刚体的位姿描述和变换公式后,接下的问题就是研究速度的表达和变换公式了。

1.2.1 刚体速度的表示#

物理学中,速度定义为位矢对是时间的一阶导数。在坐标系的描述下,质点的速度可以分解为沿坐标轴的三个速度分量。对于刚体而言,刚体的位姿是用 4×44 \times 4 矩阵描述的,其中旋转矩阵  BSR\ ^{S}_{B} R 和平移分量(也就是框架的原点坐标) SpBorg\ ^{S}_{} p_{Borg} 可能是关于时间的变量,具有导数。

需要注意的是,旋转矩阵  BSR\ ^{S}_{B}R 并不简单的属于 R3×3\mathbb{R}^{3\times 3} 矩阵集合,更准确的描述是旋转矩阵属于特殊正交群 SO(3)SO(3),对旋转矩阵的加法不具有封闭性,因此对导数运算也不具有封闭性(因为导数涉及到减法操作)。不过旋转矩阵依然是可以对时间求导的,为了更好的描述导数,定义与导数相关的切空间为李代数 so(3)so(3),这是一个由反对称矩阵 A=AA^\top = -A 所构成的集合。

1.2.2 旋转矩阵对时间的导数#

利用  BSR BSR=1\ ^{S}_{B}R \ ^{S}_{B}R^\top = 1, 对时间求导,有

 BSR˙ BSR+ BSR BSR˙=0\ ^{S}_{B}\dot{R}\ ^{S}_{B}R^\top + \ ^{S}_{B}R \ ^{S}_{B}\dot{R}^\top = 0

整理得,

 BSR˙ BSR=( BSR˙ BSR)\ ^{S}_{B}\dot{R} \ ^{S}_{B}R^\top = - (\ ^{S}_{B}\dot{R} \ ^{S}_{B}R^\top )^\top

定义

[ SΩB]= BSR˙ BSR[\ ^{S}_{}\Omega_B] = \ ^{S}_{B}\dot{R} \ ^{S}_{B}R^\top

 BSR˙=[ SΩB] BSR\ ^{S}_{B}\dot{R} = [\ ^{S}_{}\Omega_B]\ ^{S}_{B}R

现在,通过导数的原始定义来推导出 [ SΩB][\ ^{S}_{}\Omega_B] 的物理含义。

 BSR˙=limΔt0R(t+Δt)R(t)Δt=limΔt0Rω^(Δθ(t)) R(t)R(t)Δt=limΔt0Rω^(Δθ(t))IΔtR(t)=(limΔt01Δt[0ω^zΔθω^yΔθω^zΔθ0ω^xΔθω^yΔθω^xΔθ0])R(t)=[0ω^zθ˙ω^yθ˙ω^zθ˙0ω^xθ˙ω^yθ˙ω^xθ˙0]R(t)=[ω^θ˙]R(t)\begin{aligned} \ ^{S}_{B}\dot{R} &= \lim_{\Delta t\rightarrow 0} \frac{R(t + \Delta t) - R(t)}{\Delta t} = \lim_{\Delta t \rightarrow 0}\frac{R_{\hat{\omega}}(\Delta \theta(t))\ R(t) - R(t)}{\Delta t}\\ &= \lim_{\Delta t \rightarrow 0}\frac{R_{\hat{\omega}}(\Delta\theta(t)) - I}{\Delta t}R(t) \\ &= \left(\lim_{\Delta t \rightarrow 0}\frac{1}{\Delta t}\begin{bmatrix} 0 & -\hat\omega_z\Delta\theta & \hat\omega_y\Delta\theta \\ \hat\omega_z\Delta\theta & 0 & -\hat\omega_x\Delta\theta \\ -\hat\omega_y\Delta\theta & \hat\omega_x\Delta\theta & 0 \end{bmatrix}\right)R(t)\\ &= \begin{bmatrix} 0 & -\hat\omega_z\dot{\theta} & \hat\omega_y\dot{\theta} \\ \hat\omega_z\dot{\theta} & 0 & -\hat\omega_x\dot{\theta} \\ -\hat\omega_y\dot{\theta} & \hat\omega_x\dot{\theta} & 0 \end{bmatrix}R(t)\\ &= [\hat\omega\dot{\theta}]R(t) \end{aligned}

注意这个推到中运用到了如下性质

  • 乘积公式 R(t+Δt)=Rω^(Δθ)R(t)R(t + \Delta t) = R_{\hat\omega}(\Delta \theta) R(t),其中 ω^\hat\omega 是旋转轴方向的单位向量,Δθ\Delta\theta 是旋转角度。
  • Rodrigues 公式 Rω^(Δθ)=I+sin(Δθ)[ω^]+(1cos(Δθ))[ω^]2R_{\hat\omega}(\Delta \theta) = I + \sin(\Delta\theta)[\hat\omega] + (1 - \cos(\Delta\theta))[\hat\omega]^2,其中 [ω^][\hat\omega]ω^\hat\omega 的反对称矩阵形式。可以得到
Rω^(Δθ)=[1ω^zΔθω^yΔθω^zΔθ1ω^xΔθω^yΔθω^xΔθ1]R_{\hat\omega}(\Delta \theta) = \begin{bmatrix} 1 & -\hat\omega_z\Delta\theta & \hat\omega_y\Delta\theta \\ \hat\omega_z\Delta\theta & 1 & -\hat\omega_x\Delta\theta \\ -\hat\omega_y\Delta\theta & \hat\omega_x\Delta\theta & 1 \end{bmatrix}

利用上述的公式,可以得到

 BSR=[ω^Bθ˙] BSR=[ SΩB] BSR\ ^{S}_{B} R = [\hat\omega_B \dot{\theta}] \ ^{S}_{B} R = [\ ^{S}_{}\Omega_B]\ ^{S}_{B}R

从而,得到 [ SΩB]=[ω^Bθ˙][\ ^{S}_{}\Omega_B] = [\hat\omega_B \dot\theta],即

 SΩB=ω^Bθ˙\ ^{S}_{} \Omega_B = \hat\omega_B \dot{\theta}

物理含义是  SΩB\ ^{S}_{}\Omega_B 就是在绝对参考框架下刚体的角速度(角速度方向和角速度大小)。由此我们求得了旋转矩阵对时间的导数,即

 BSR˙=[ SΩB] BSR=[ω^Bθ˙] BSR\ ^{S}_{B}\dot{R} = [\ ^{S}_{}\Omega_B]\ ^{S}_{B}R = [\hat\omega_B \dot{\theta}] \ ^{S}_{B}R

1.2.3 旋转矩阵的指数公式#

对上式变形,得到

ddt BSR=[ω^Bθ˙] BSR=[ω^B] BSR dθdt\frac{d}{dt}\ ^{S}_{B}R = [\hat{\omega}_B \dot{\theta}] \ ^{S}_{B}R = [\hat{\omega}_B] \ ^{S}_{B}R \ \frac{d\theta}{dt} \\

于是

ddθ BSR(θ)=[ω^B] BSR\frac{d}{d\theta}\ ^{S}_{B}R(\theta) = [\hat{\omega}_B] \ ^{S}_{B}R

这是指数微分方程的形式,当 [ω^B][\hat\omega_B]θ\theta 是常数时,求解可得

 BSR(θ)=e[ω^B]θ\ ^{S}_{B} R(\theta) = e^{[\hat{\omega}_B]\theta}

这便是旋转矩阵的指数公式。

1.2.4 平移向量对时间的导数#

平移向量  SpBorg\ ^{S} p_{Borg} 对时间的导数可看作刚体固连框架 {B}\{B\} 的原点坐标的速度向量

 SVBorg=ddt SpBorg=[x˙Borgy˙Borgz˙Borg]\ ^{S} V_{Borg} = \frac{d}{dt} \ ^{S}_{} p_{Borg} = \begin{bmatrix} \dot{x}_{Borg} \\\dot{y}_{Borg} \\\dot{z}_{Borg} \end{bmatrix}

这里介绍以下速度相关的符号表示

  •  AVq\ ^{A}_{} V_{q}:点 qq 相对于框架 {A}\{A\} 的速度(相对于框架 {A}\{A\} 求导),且用框架 {A}\{A\} 表达向量(理解为向量 AVq^{A}_{}\vec{V}_q[x^Ay^Az^A] AVq= AVqxx^A+ AVqyy^A+ AVqzz^A\begin{bmatrix} \mathbf{\hat{x}}_A & \mathbf{\hat{y}}_A &\mathbf{\hat{z}}_A\end{bmatrix} \ ^{A}V_q = \ ^{A}V_{qx}\mathbf{\hat{x}}_A + \ ^{A}V_{qy}\mathbf{\hat{y}}_A + \ ^{A}V_{qz}\mathbf{\hat{z}}_A 表示)

  •  B(AVq)\ ^{B}(^{A}_{} V_{q}) B(AVq)= ABR AVq\ ^{B}(^{A}_{} V_{q}) = \ ^{B}_{A}R \ ^{A}_{} V_{q},即点 qq 相对于框架 {A}\{A\} 的速度(相对于框架 {A}\{A\} 求导),但用框架 {B}\{B\} 表达向量(理解为向量 AVq^{A}_{}\vec{V}_q[x^By^Bz^B] B(AVq)= B(AVq)xx^A+ B(AVq)yy^A+ B(AVq)zz^A\begin{bmatrix} \mathbf{\hat{x}}_B & \mathbf{\hat{y}}_B &\mathbf{\hat{z}}_B\end{bmatrix} \ ^{B}(^{A}V_q) = \ ^{B}(^{A}V_q)_x\mathbf{\hat{x}}_A + \ ^{B}(^{A}V_q)_y\mathbf{\hat{y}}_A + \ ^{B}(^{A}V_q)_z\mathbf{\hat{z}}_A 表示)

  • vqv_qvq= SVqv_q = \ ^{S} V_{q},即点 qq 相对于绝对参考坐标系 {S}\{S\} 且在 {S}\{S\} 中的速度表达

  • Avq^{A}v_qAvq= A( SVq)^{A}v_q =\ ^{A}(\ ^{S} V_{q}),即点 qq 相对于绝对参考坐标系 {S}\{S\} 但在 {A}\{A\} 中的速度表达

类似地,角速度也有相关的符号规范

  •  AΩq\ ^{A}_{} \Omega_{q}:点 qq 相对于框架 {A}\{A\} 的角速度(相对于框架 {A}\{A\} 求导),且用框架 {A}\{A\} 表达向量(理解为向量 AΩq^{A}_{}\vec{\Omega}_q[x^Ay^Az^A] AΩq= AΩqxx^A+ AΩqyy^A+ AΩqzz^A\begin{bmatrix} \mathbf{\hat{x}}_A & \mathbf{\hat{y}}_A &\mathbf{\hat{z}}_A\end{bmatrix} \ ^{A}\Omega_q = \ ^{A}\Omega_{qx}\mathbf{\hat{x}}_A + \ ^{A}\Omega_{qy}\mathbf{\hat{y}}_A + \ ^{A}\Omega_{qz}\mathbf{\hat{z}}_A 表示)

  •  B(AΩq)\ ^{B}(^{A}_{} \Omega_{q}) B(AΩq)= ABR AΩq\ ^{B}(^{A}_{} \Omega_{q}) = \ ^{B}_{A}R \ ^{A}_{} \Omega_{q},即点 qq 相对于框架 {A}\{A\} 的角速度(相对于框架 {A}\{A\} 求导),但用框架 {B}\{B\} 表达向量(理解为向量 AΩq^{A}_{}\vec{\Omega}_q[x^By^Bz^B] B(AΩq)= B(AΩq)xx^A+ B(AΩq)yy^A+ B(AΩq)zz^A\begin{bmatrix} \mathbf{\hat{x}}_B & \mathbf{\hat{y}}_B &\mathbf{\hat{z}}_B\end{bmatrix} \ ^{B}(^{A}\Omega_q) = \ ^{B}(^{A}\Omega_q)_x\mathbf{\hat{x}}_A + \ ^{B}(^{A}\Omega_q)_y\mathbf{\hat{y}}_A + \ ^{B}(^{A}\Omega_q)_z\mathbf{\hat{z}}_A 表示)

  • ωq\omega_qωq= SΩq\omega_q = \ ^{S} \Omega_{q},即点 qq 相对于绝对参考坐标系 {S}\{S\} 且在 {S}\{S\} 中的角速度表达

  • Aωq^{A}\omega_qAωq= A( SΩq)^{A}\omega_q =\ ^{A}(\ ^{S} \Omega_{q}),即点 qq 相对于绝对参考坐标系 {S}\{S\} 但在 {A}\{A\} 中的角速度表达

1.2.5 运动旋量#

为了统一旋转矩阵和平移向量的导数,考虑直接对 4×44 \times 4 齐次矩阵求导。

 BST˙(t)=[ BSR˙(t) Sp˙Borg(t)00]\ ^{S}_{B}\dot{T}(t) = \begin{bmatrix} \ ^{S}_{B} \dot{R}(t) & \ ^{S}_{}\dot{p}_{Borg}(t) \\ 0 & 0\end{bmatrix}

左乘齐次矩阵的逆

 BST1 BST˙=[ BSR BSR SpBorg01][ BSR˙ Sp˙Borg00]=[ BSR BSR˙ BSR Sp˙Borg00]=[[ SBR SΩB] SBR SVBorg00]=[[ BΩB]  BVBorg00]se(3)\begin{aligned} \ ^{S}_{B}T^{-1} \ ^{S}_{B}\dot{T} &= \begin{bmatrix} \ ^{S}_{B} R^\top & -\ ^{S}_{B} R^\top \ ^{S}_{}p_{Borg} \\ 0 & 1\end{bmatrix} \begin{bmatrix} \ ^{S}_{B} \dot{R} & \ ^{S}_{}\dot{p}_{Borg} \\ 0 & 0\end{bmatrix} \\ &= \begin{bmatrix} \ ^{S}_{B} R^\top \ ^{S}_{B} \dot{R} & \ ^{S}_{B}R^\top \ ^{S}\dot{p}_{Borg} \\ 0 & 0\end{bmatrix}\\ &= \begin{bmatrix} [\ ^{B}_{S}R\ ^{S}_{}\Omega_B] & \ ^{B}_{S}R \ ^{S}V_{Borg} \\ 0 & 0\end{bmatrix}\\ &= \begin{bmatrix} [\ ^{B} \Omega_B] & \ \ ^{B}V_{Borg} \\ 0 & 0\end{bmatrix} \in se(3)\\ \end{aligned}

右乘齐次矩阵的逆

 BST˙ BST1=[ BSR˙ Sp˙Borg00][ BSR BSR SpBorg01]=[ BSR˙ BSR Sp˙Borg BSR˙ BSR SpBorg00]=[[ SΩ˙B] SVBorg[SΩB] SpBorg00]se(3)\begin{aligned} \ ^{S}_{B}\dot{T} \ ^{S}_{B}T^{-1} &= \begin{bmatrix} \ ^{S}_{B} \dot{R} & \ ^{S}_{}\dot{p}_{Borg} \\ 0 & 0\end{bmatrix} \begin{bmatrix} \ ^{S}_{B} R^\top & -\ ^{S}_{B} R^\top \ ^{S}_{}p_{Borg} \\ 0 & 1\end{bmatrix}\\ &= \begin{bmatrix} \ ^{S}_{B} \dot{R} \ ^{S}_{B} R^\top & \ ^{S} \dot{p}_{Borg} - \ ^{S}_{B} \dot{R} \ ^{S}_{B} R^\top \ ^{S}_{}p_{Borg} \\ 0 & 0\end{bmatrix}\\ &= \begin{bmatrix} [\ ^{S} \dot{\Omega}_B] & \ ^{S} V_{Borg} - [^{S}\Omega_B] \ ^{S}_{}p_{Borg} \\ 0 & 0\end{bmatrix} \in se(3) \end{aligned}

定义

[BξB]=[[ BΩB] BVBorg00]= BST1 BST˙se(3)[^{B}\xi_B] = \begin{bmatrix} [\ ^{B} \Omega_B] & \ ^{B}V_{Borg} \\ 0 & 0\end{bmatrix} = \ ^{S}_{B}T^{-1} \ ^{S}_{B}\dot{T} \in se(3)

[SξB]=[[ SΩ˙B] SVBorg[SΩB] SpBorg00]= BST˙ BST1se(3)[^{S}\xi_B] = \begin{bmatrix} [\ ^{S} \dot{\Omega}_B] & \ ^{S} V_{Borg} - [^{S}\Omega_B] \ ^{S}_{}p_{Borg} \\ 0 & 0\end{bmatrix} = \ ^{S}_{B}\dot{T} \ ^{S}_{B}T^{-1} \in se(3)

对应有

 BξB=[ BVBorg BΩB]R6 SξB=[ SVBorg[ SΩB] SpBorg SΩB]R6\begin{aligned} \ ^{B}_{}\xi_B &= \begin{bmatrix} \ ^{B}V_{Borg} \\ \ ^{B}_{}\Omega_B \end{bmatrix} \in \mathbb{R}^6\\ \ ^{S}_{}\xi_B &= \begin{bmatrix} \ ^{S}V_{Borg} - [\ ^{S}_{}\Omega_B] \ ^{S}_{}p_{Borg} \\ \ ^{S}_{}\Omega_B \end{bmatrix} \in \mathbb{R}^6 \end{aligned}

称这两个向量为运动旋量。具体地,称  BξB\ ^{B}_{}\xi_B刚体运动旋量,称  SξB\ ^{S}_{}\xi_B空间运动旋量

一般地,如果一个 66 维列向量 ξ\xi 的前三维分量是线速度,后三维分量是角速度,则这个向量对应于一个刚体的运动旋量。

螺旋轴——单位旋量

类似旋转角速度 Ω=ω^θ˙\Omega = \hat\omega \dot\theta 有旋转轴的单位向量 ω^\hat\omega,运动旋量也可以有单位向量的表示,我们称这个单位向量为螺旋轴,形式为

S=[vω]R6S = \begin{bmatrix} v \\ \omega\end{bmatrix} \in \mathbb{R}^6

其中,SS 分为两种情况(只有两种)

  • 1. S=[v^0]S = \begin{bmatrix} \hat v \\ 0\end{bmatrix},即 v^=1\Vert \hat v \Vert = 1ω=0\omega = 0,此时的螺旋运动是不旋转只平移的形式。

  • 2. S=[vω^]S = \begin{bmatrix} v \\ \hat\omega\end{bmatrix},即 ω^=1\Vert \hat\omega \Vert = 1,此时的螺旋运动是绕着螺旋轴螺旋前进的形式。

当给定螺旋速度 θ˙\dot\theta 和 螺旋轴 ω^\hat\omega 后,可以得到运动旋量表示为

ξ=Sθ˙={[v^0]θ˙,此时θ˙表征线速度大小[vω^]θ˙此时θ˙表征角速度大小\xi = S\dot\theta = \begin{cases} \begin{bmatrix} \hat v \\ 0\end{bmatrix} \dot\theta, &\quad \text{此时}\dot\theta\text{表征线速度大小} \\\\ \begin{bmatrix} v \\ \hat\omega\end{bmatrix} \dot\theta &\quad\text{此时}\dot\theta\text{表征角速度大小} \end{cases}

之所以划分为两种情况而不直接统一为 S=ξξS = \frac{\xi}{\Vert\xi\Vert} 的形式,是因为这种归一化的形式并不具有物理意义,线速度和角速度的量纲不同,不能直接归一化。于是根据角速度是否为 0 对螺旋轴进行划分。通用的螺旋运动形式是第 2 种情况,边界情况是第 1 种。

screw

1.2.6 点的速度变换#

旋转矩阵和平移向量形式#

设有任意的框架 {A}\{A\}{B}\{B\},对

Aq= BAR Bq+ ApBorg^{A} q = \ ^{A}_{B}R \ ^{B} q + \ ^{A}_{}p_{Borg}

求导,得到

AVq= BAR BVq+[AΩB] BAR Bq+ AVBorg^{A} V_q = \ ^{A}_{B}R \ ^{B}V_q + [^{A}\Omega_B] \ ^{A}_{B}R \ ^{B} q +\ ^{A}V_{Borg}

这就是点 qq 在框架 {A}\{A\} 下的速度表达式。

旋量形式#

设刚体上有一个固定qq,根据变换关系

 Sqˉ(t)= BST(t) Bqˉ(t)\ ^{S} \bar{q}(t) = \ ^{S}_{B}T(t) \ ^{B} \bar{q}(t)

 SVˉq= BST˙ BST1 Sqˉ=[SξB] Sqˉ\begin{aligned} \ ^{S}\bar{V}_q = \ ^{S}_{B} \dot{T} \ ^{S}_{B}T^{-1} \ ^{S}\bar{q} = [^{S} \xi_B] \ ^{S} \bar{q} \end{aligned}

即可以用刚体的空间运动旋量与空间坐标系下的点 qq 的坐标表示点 qq 在空间坐标系下的速度。本质上,继续推导,可以得到

 SVq=[SΩB] Sq[SΩB] SpBorg+ SVBorg= SΩB×( Sq SpBorg)+ SVBorg\ ^{S}V_q = [^{S}\Omega_B] \ ^{S}q - [^{S}\Omega_B] \ ^{S}_{}p_{Borg} + \ ^{S}V_{Borg} = \ ^{S}\Omega_B \times (\ ^{S}q - \ ^{S}_{}p_{Borg}) + \ ^{S}V_{Borg}

符合物理中的运动学公式。

同理,可以得到刚体上固定qq 在刚体固连框架下的速度为

 B(SVˉq)= BST1 SVˉq= BST1 BST˙ Bqˉ=[BξB] Bqˉ\ ^{B}(^{S}\bar{V}_q) = \ ^{S}_{B}T^{-1}\ ^{S}\bar{V}_q = \ ^{S}_{B}T^{-1}\ ^{S}_{B} \dot{T} \ ^{B}\bar{q} = [^{B}\xi_B] \ ^{B}\bar{q}

即可以用刚体的空间运动旋量与刚体固连框架下的点 qq 的坐标求解点 qq 在刚体固连框架下的绝对速度。

观察公式 SSξ\xi 的表达式,可以发现齐次坐标和三维坐标的相似性。将运动旋量与齐次坐标进行叉乘运算,可以得到点的速度,仿佛质点在随刚体旋转。也因此,叉乘坐标的向量被称作运动旋量

1.2.7 伴随矩阵——刚体速度变换#

定义齐次变换矩阵 T=[Rp01]T = \begin{bmatrix} R & p \\ 0 & 1\end{bmatrix} 的伴随矩阵为

AdT=[R [p]R0R]\text{Ad}_{T} = \begin{bmatrix} R & \ [p] R \\ 0 & R\end{bmatrix}

伴随矩阵的作用是对旋量做变换,设有运动旋量 ξ=[vω]\xi = \begin{bmatrix} v \\ \omega\end{bmatrix},则有

[AdTξ]=T[ξ]T1=def[ξ]se(3)[\text{Ad}_T \xi] = T [\xi] T^{-1} \stackrel{\text{def}}{=} [\xi'] \in se(3)

其中

ξ=AdTξ\xi' = \text{Ad}_T \xi

下面将说明上面公式的细节部分。

AdTξ=[R [p]R0R][vω]=[Rv+[p]RωRω]=[vω]R6[AdTξ]=[[ω]v00]=[[Rω]Rv+[p]Rω00]se(3)T[ξ]T1=[Rp01][[ω]v00][RRp01]=[R[ω]RR[ω]Rp+Rv00]=[[Rω]Rv+[p]Rω00]se(3)\begin{aligned} \text{Ad}_T \xi &= \begin{bmatrix} R & \ [p] R \\ 0 & R\end{bmatrix} \begin{bmatrix} v \\ \omega\end{bmatrix} = \begin{bmatrix} Rv + [p]R\omega \\ R\omega\end{bmatrix} = \begin{bmatrix} v' \\ \omega'\end{bmatrix} \in \mathbb{R}^6 \\ [\text{Ad}_T \xi] &= \begin{bmatrix} [\omega'] & v' \\ 0 & 0\end{bmatrix} = \begin{bmatrix} [R\omega] & R v + [p]R\omega \\ 0 & 0\end{bmatrix} \in se(3)\\ T[\xi]T^{-1} &= \begin{bmatrix} R & p \\ 0 & 1\end{bmatrix} \begin{bmatrix} [\omega] & v \\ 0 & 0\end{bmatrix} \begin{bmatrix} R^\top & -R^\top p \\ 0 & 1\end{bmatrix}\\ &= \begin{bmatrix} R[\omega]R^\top & -R[\omega]R^\top p + Rv \\ 0 & 0\end{bmatrix} = \begin{bmatrix} [R\omega] & Rv + [p]R\omega \\ 0 & 0\end{bmatrix} \in se(3) \end{aligned}

其中用到了以下性质

  • R[ω]R=[Rω]R[\omega]R^\top = [R\omega],即对反对称矩阵的正交特征变换
  • 反对称矩阵的加法性质 [ω1]+[ω2]=[ω1+ω2][\omega_1] + [\omega_2] = [\omega_1 + \omega_2],即对反对称矩阵的加法具有封闭性
  • 反对称矩阵与叉乘的联系 [ω]v=ω×v[\omega]v = \omega \times v
  • 反对称矩阵对数乘封闭性 k[ω]=[kω]k[\omega] = [k\omega],这里用到的是 [Rωp]=[Rωp]-[R\omega p] = [-R\omega p]
  • 叉乘的反交换性 [a]b=[b]a[a]b = -[b]a,这里用到的是 [p]Rω=[Rω]p[p]R\omega = -[R\omega]p

于是证明出了 [AdTξ]=T[ξ]T1[\text{Ad}_T \xi] = T[\xi]T^{-1},即伴随矩阵的作用是对运动旋量做变换。

在不同框架下的描述

设从框架 {A}\{A\} 到 框架 {B}\{B\} 的变换矩阵为  BAT=[ BAR ApBorg01]\ ^{A}_{B}T = \begin{bmatrix} \ ^{A}_{B}R & \ ^{A}_{}p_{Borg} \\ 0 & 1\end{bmatrix},在框架 {B}\{B\} 下某个旋量 ξ\xi 的向量表示为 Bξ^{B}\xi,那么它在框架 {A}\{A\} 下的向量表示为

 Aξ=AdBAT Bξ\ ^{A}\xi = \text{Ad}_{^{A}_{B}T} \ ^{B}\xi

由于螺旋轴的本质是归一化后的运动旋量,因此也可以用上述公式变换

AS^=AdBAT BS^^{A}\hat{S} = \text{Ad}_{^{A}_{B}T} \ ^{B}\hat{S}

重要变换性质

在刚体固连框架 {B}\{B\} 中描述的刚体相对于绝对框架 {S}\{S\} 的运动旋量(即刚体运动旋量)BξB^{B}\xi_B 与在绝对框架 {S}\{S\} 中描述的刚体相对于绝对框架 {S}\{S\} 的运动旋量(即空间运动旋量)SξB^{S}\xi_B 之间的关系为

 SξB=AdBST BξB\ ^{S}\xi_B = \text{Ad}_{^{S}_{B}T} \ ^{B}\xi_B

其中,AdBST=[ BSR [ BSpBorg] BSR0 BSR]\text{Ad}_{^{S}_{B}T} = \begin{bmatrix} \ ^{S}_{B}R & \ [\ ^{S}_{B}p_{Borg}] \ ^{S}_{B}R \\ 0 & \ ^{S}_{B}R\end{bmatrix} 是伴随矩阵。这个公式可以由下式得到

[SξB]= BST˙ BST1= BST BST1 BST˙ BST1= BST [BξB] BST1=[AdBST BξB][^{S}\xi_B] = \ ^{S}_{B}\dot{T}\ ^{S}_{B}T^{-1} = \ ^{S}_{B}T\ ^{S}_{B}T^{-1} \ ^{S}_{B}\dot{T}\ ^{S}_{B}T^{-1} = \ ^{S}_{B}T\ [^{B}\xi_B]\ ^{S}_{B}T^{-1} = [\text{Ad}_{^{S}_{B}T} \ ^{B}\xi_B]

伴随矩阵的性质

  • 伴随矩阵的逆
AdT1=[RR[p]0R]=AdT1\text{Ad}_T^{-1} = \begin{bmatrix} R^\top & -R^\top [p] \\ 0 & R^\top\end{bmatrix} = \text{Ad}_{T^{-1}}
  • 结合律,利用结合律可以推导出伴随矩阵的逆性质
AdT1AdT2=AdT1T2\text{Ad}_{T_1} \text{Ad}_{T_2} = \text{Ad}_{T_1 T_2}

1.3 加速度#

加速度的符号表示与速度的标准相同,A(BV˙)^{A}(^{B} \dot V) 等含义在此不予赘述。

1.3.1 线加速度#

设有框架 {A}\{A\} 和框架 {B}\{B\} 和 点 qq,对速度变换公式求导,有

AV˙q=([AΩ˙B] BAR Bq+[AΩB][AΩB] BAR Bq+[AΩB] BAR BVq)+([AΩB] BAR BVq+ BAR BV˙q)+ AV˙Borg= AV˙Borg+ BAR BV˙q+2[AΩB] BAR BVqCoriolis+[AΩ˙B] BAR BqEuler+[AΩB][AΩB] BAR BqCentrifugal\begin{aligned} ^{A} \dot V_q &= \left([^{A}\dot\Omega_B]\ ^{A}_{B}R \ ^{B}q + [^{A}\Omega_B][^{A}\Omega_B]\ ^{A}_{B}R \ ^{B}q + [^{A}\Omega_B] \ ^{A}_{B}R \ ^{B}V_q\right) + \left([^{A}\Omega_B] \ ^{A}_{B}R \ ^{B}V_q + \ ^{A}_{B}R\ ^{B}\dot V_q\right) + \ ^{A}\dot V_{Borg}\\ &= \ ^{A}\dot V_{Borg} + \ ^{A}_{B}R \ ^{B}\dot V_q + \underbrace{2[^{A}\Omega_B] \ ^{A}_{B}R \ ^{B}V_q}_{Coriolis} + \underbrace{[^{A}\dot\Omega_B] \ ^{A}_{B}R \ ^{B}q}_{Euler} + \underbrace{[^{A}\Omega_B][^{A}\Omega_B]\ ^{A}_{B}R \ ^{B}q}_{Centrifugal} \end{aligned}

1.3.2 角加速度#

对于角加速度,利用

SΩB= SΩA+ ASR AΩB^{S}\Omega_B = \ ^{S}\Omega_A + \ ^{S}_{A}R\ ^{A}\Omega_B

对时间求导,得到

SΩ˙B= SΩ˙A+[SΩA] ASR AΩB+ ASR AΩ˙B\begin{aligned} ^{S}\dot\Omega_B &= \ ^{S}\dot\Omega_A + [^{S}\Omega_A]\ ^{S}_{A}R\ ^{A}\Omega_B + \ ^{S}_{A}R\ ^{A}\dot\Omega_B \end{aligned}

1.4 力#

ff 和力矩 nn 可以结合在一起统一表达为一个六维的广义力 F=[ff]\mathcal{F} = \begin{bmatrix} f \\ f\end{bmatrix},其中 f,nR3f, n \in \mathbb{R}^3。我们称这个广义力叫力旋量 (Wrench)

力旋量也有在不同框架下的切换公式,假设同一个力旋量在框架 {A}\{A\} 中表示为 AF^{A}\mathcal{F},在框架 {B}\{B\} 中表示为 BF^{B}\mathcal{F},则有

BF=AdBAT AF^{B}\mathcal{F} = \text{Ad}_{^{A}_{B}T}^\top \ ^{A}\mathcal{F}

这个公式可以从做功的角度推导出,在不同框架下的力旋量表达虽然不同,但是其做功应是相同的,即

BF Bξ=AF Aξ Aξ=AdBAT Bξ\begin{aligned} ^{B}\mathcal{F}^\top \ ^{B}\xi &= ^{A}\mathcal{F}^\top \ ^{A}\xi \\ \ ^{A}\xi &= \text{Ad}_{^{A}_{B}T} \ ^{B}\xi \end{aligned}

从而推导出上式。

1.5 质量与惯量#

1.5.1 经典的标量描述方法#

刚体,不同于质点,通常在空间中会占据一定的空间,因此不能只以一个点的位矢完全概括它的位置。假设刚体的密度分布为 ρ\rho, p\vec{p} 为空间中点的位矢,则可以通过积分的方式得到刚体的质量,并求出相应的质心位置

m=ρdVpc=1mpρdV\begin{aligned} m &= \int \rho \mathrm{d}V \\ \vec{p}_c &= \frac{1}{m}\int \vec{p}\rho \mathrm{d}V \end{aligned}

质点的动力学模型仅仅通过质量即可完整描述(牛顿第二定律),但是刚体不行,因为刚体还需要考虑自身转动,因此刚体还有一个用于描述转动动力学模型的参量叫转动惯量

J=r2ρdVJ = \int r^2\rho\mathrm{d}V

其中 rr 是位于 p\vec{p} 处的质点到旋转轴的距离。

有了质量 mm 和转动惯量 JJ 之后,就可以相应地对刚体做动力学分析了。通常的分析方程有牛顿第二定律、欧拉动力学方程和动能定理等

{mpc¨=fextJω˙+ω×(Jω)=τextK=12mp˙cp˙c+12Jωω\begin{cases} &m\ddot{\vec{p_c}} = \sum \vec{f}_{\text{ext}} \\ &J\dot{\vec{\omega}} + \vec{\omega} \times (J\vec{\omega}) = \sum \vec{\tau}_{\text{ext}} \\ &\mathcal{K} = \frac{1}{2}m\dot{\vec{p}}_c\cdot \dot{\vec{p}}_c + \frac{1}{2}J\vec{\omega}\cdot \vec{\omega} \end{cases}

其中 fext\sum \vec{f}_{\mathrm{ext}} 为外力合力,τext\sum \vec{\tau}_{\mathrm{ext}} 为关于质心的外力矩合力。

注意这里所使用的质量和转动惯量均是标量的形式。

1.5.2 张量形式的描述方法#

在三维空间中,标量形式的转动惯量只能描述绕一个特定轴的旋转,而无法全面反映刚体在不同方向上的转动特性。因此引入了惯性张量这个二阶张量以方便问题的分析。

定义相对于框架 {A}\{A\} 的惯性张量为

AI=[Ap][Ap]dm^{A}I = \int [^{A}p]^\top[^{A}p]\mathrm{d}m

注意这里的位矢 Ap^{A}p 是相对于绝对框架的位置坐标,在刚体运动的过程中往往是随时间变化的,也就是说,惯性张量对时间的导数通常不为0。只有当参考框架取为质心框架 {c}\{c\} 时,惯性参量才是不随时间变化的。

1.5.3 惯性张量在不同参考框架下的切换#

设惯性张量 II 在框架 {A}\{A\} 中的表达为 AI^{A}I,在框架 {B}\{B\} 中的表达为 BI^{B}I,则根据角动量的框架切换公式和角速度的切换公式

AL= AI AωBL= BI BωAL= BAR BLAω= BAR Bω\begin{aligned} ^{A}L &= \ ^{A}I \ ^{A}\omega\\ ^{B}L &= \ ^{B}I \ ^{B}\omega\\ ^{A}L &= \ ^{A}_{B}R \ ^{B}L \\ ^{A}\omega &= \ ^{A}_{B}R \ ^{B}\omega \\ \end{aligned}

 AI Aω= BAR BI Bω= BAR BI ABR Aω\begin{aligned} \ ^{A}I \ ^{A}\omega = \ ^{A}_{B}R\ ^{B}I \ ^{B}\omega = \ ^{A}_{B}R\ ^{B}I \ ^{B}_{A}R\ ^{A}\omega \end{aligned}

于是

 AI= BAR BI BAR\ ^{A}I = \ ^{A}_{B}R\ ^{B}I \ ^{A}_{B}R^\top

1.6 能量与角动量#

1.6.1 动能#

在框架 {A}\{A\} 中,定义刚体 BB 绕任意轴做纯转动的动能为

AKR=12 Av Av dm^{A}\mathcal{K}_R = \frac{1}{2} \int\ ^{A}v^\top\ ^{A} v\ \mathrm{d}m

其中速度向量 Av= AVdm^{A}v = \ ^{A}V_{\mathrm{d}m} 表示在框架 {A}\{A\} 下质元 dm\mathrm{d}m 的三维速度向量。展开动能,有

AKR=12 Av Av dm=12(Aω× Ap)(Aω× Ap)dm=12 Aω[Ap][Ap] Aω dm=12 Aω AI Aω\begin{aligned} ^{A}\mathcal{K}_R &= \frac{1}{2} \int\ ^{A} v^\top\ ^{A} v\ \mathrm{d}m\\ &= \frac{1}{2} \int(^{A}\omega \times \ ^{A}p)^\top(^{A}\omega \times\ ^{A} p) \mathrm{d}m\\ &= \frac{1}{2} \int\ ^{A}\omega^\top[^{A}p]^\top [^{A}p]\ ^{A} \omega\ \mathrm{d}m\\ &= \frac{1}{2}\ ^{A} \omega^\top\ ^{A}I\ ^{A} \omega \end{aligned}

于是得到转动动能表示为

AKR=12 Aω AI Aω^{A}\mathcal{K}_R = \frac{1}{2}\ ^{A} \omega^\top\ ^{A}I\ ^{A} \omega

其中,Aω= AΩB^{A}\omega = \ ^{A}\Omega_B 是刚体 BB 的转动角速度。

结合刚体平动动能,可以得到刚体运动的全部动能为

AK=12m Ap˙c Ap˙c+12 Aω AI Aω^{A}\mathcal{K} = \frac{1}{2}m\ ^{A}\dot{p}_c^\top\ ^{A}\dot{p}_c + \frac{1}{2}\ ^{A} \omega^\top\ ^{A}I\ ^{A} \omega

1.6.2 角动量#

同样地,角动量也有惯性张量的表达形式。根据定义,在框架 {A}\{A\} 中,刚体 BB 的角动量表达为

Ah= Ap× Av dm^{A}h = \int\ ^{A}p \times \ ^{A}v\ \mathrm{d}m

展开有

Ah= Ap× Av dm= Ap×(Aω× Ap) dm= Ap×(Ap× Aω) dm=[Ap][Ap] Aω dm=[Ap][Ap] dm Aω= AI Aω\begin{aligned} ^{A}h &= \int\ ^{A}p \times \ ^{A}v\ \mathrm{d}m \\ &= \int \ ^{A}p \times (^{A}\omega \times \ ^{A}p)\ \mathrm{d}m \\ &= -\int \ ^{A}p \times (^{A}p \times\ ^{A}\omega)\ \mathrm{d}m \\ &= -\int [^{A}p][^{A}p]\ ^{A}\omega \ \mathrm{d}m\\ &= \int [^{A}p]^\top[^{A}p]\ \mathrm{d}m \ ^{A}\omega \\ &= \ ^{A}I \ ^{A}\omega \end{aligned}

这里用到了反对称矩阵的性质 [Ap]=[Ap][^{A}p]^\top = -[^{A}p];其中 Aω^{A}\omega 是刚体的转动角速度。

惯性主轴

需要注意的事情是,从上面公式可以看出,角动量 Ah^{A}h 的方向并不一定和角速度 Aω^{A}\omega 的方向相同,只有当满足下面方程时,二者的方向才相同

AI Aω=k Aω^{A}I \ ^{A}\omega = k \ ^{A}\omega

我们称满足这个特征向量关系的轴线为惯性主轴。

欧拉方程

刚体所受合力矩是其角动量的变化率

Aτ=d ALdt=ddt(AI Aω)=ddt( cAR cI  cAR Aω)= cAR˙ cI cAR Aω+ cAR cI cAR˙ Aω+ cAR cI cAR Aω˙=[Aω] cAR cI cAR Aω+ cAR cI cAR[Aω] Aω+ cAR cI cAR Aω˙= Aω× AI Aω+ AI Aω˙\begin{aligned} ^{A} \tau &= \frac{\mathrm{d}\ ^{A}L}{\mathrm{d} t} = \frac{\mathrm{d}}{\mathrm{d} t}(^{A}I\ ^{A}\omega) = \frac{\mathrm{d}}{\mathrm{d} t}(\ ^{A}_{c}R\ ^{c}I\ \ ^{A}_{c}R^\top \ ^{A}\omega) \\ &= \ ^{A}_{c}\dot R \ ^{c}I \ ^{A}_{c}R^\top\ ^{A}\omega + \ ^{A}_{c} R \ ^{c}I \ ^{A}_{c}\dot R^\top\ ^{A}\omega + \ ^{A}_{c}R \ ^{c}I \ ^{A}_{c}R^\top\ ^{A}\dot \omega \\ &= [^{A}\omega]\ ^{A}_{c}R \ ^{c}I \ ^{A}_{c}R^\top\ ^{A}\omega + \ ^{A}_{c}R \ ^{c}I \ ^{A}_{c}R^\top[^{A}\omega]^\top\ ^{A}\omega + \ ^{A}_{c}R \ ^{c}I \ ^{A}_{c}R^\top\ ^{A}\dot \omega \\ &= \ ^{A}\omega \times\ ^{A}I \ ^{A}\omega + \ ^{A}I \ ^{A}\dot\omega \end{aligned}

这里的推导利用到了质心框架下的惯性张量不随时间变化的性质。于是欧拉方程为

Aτ= Aω× AI Aω+ AI Aω˙^{A}\tau = \ ^{A}\omega \times\ ^{A}I \ ^{A}\omega + \ ^{A}I \ ^{A}\dot\omega

其中 {A}\{A\} 为任意框架。

机器人学基础 第一章 刚体运动
https://adalovelemon.github.io/blog/en/posts/content/coursenotes/robotics/chapter-1/
Author
Ada Lovelemon
Published at
2025-03-28

Comments Section