视觉SLAM中的数学基础 第四篇 李群与李代数(2)

前言

  理解李群与李代数,是理解许多SLAM中关键问题的基础。本讲我们继续介绍李群李代数的相关知识,重点放在李群李代数的微积分上,这对解决姿态估计问题具有重要意义。


 回顾

  为了描述三维空间里的运动,我们使用3×3的旋转矩阵R来描述一个刚体的旋转,并且,用4×4的变换矩阵来描述六自由度的旋转+平移。这两种矩阵在传统的欧氏空间R3×3R4×4中,不存在加法运算,只有乘法运算,故无法构成线性空间,只能构成群。也就是我们说的李群SO(3)SE(3)

(1)SO(3)={RR3×3|RRT=I,det(R)=1}

(2)SE(3)={T=[Rt0T1]R4×4|RSO(3),tR3}

   在李群中,我们使用矩阵来表达一个旋转和平移,这存在冗余的自由度。三维空间的旋转只有三自由度,旋转+平移有六自由度。因此,我们希望寻找一个没有冗余自由度(但是相应的存在奇异性)的表示,也就是李代数so(3)se(3)

(3)so(3)={ϕR3}

(4)se(3)={ξR6}

  怎么将李代数和李群元素对应起来呢?我们说,从李代数到李群,通过指数映射;反之,从李群到李代数,则通过对数映射

  so(3)的一个元素ϕ=aθ的指数映射为:

(5)exp(ϕ)=cosθI+(1cosθ)aaT+sinθa

  其中算符把一个三维向量变换为它对应的反对称矩阵(3×3)。

  该式和Rodrigues(罗德里格斯)公式是一致的。说明李代数so(3)里的向量,其方向指向旋转轴,而模长表示转过的角度。因此,平时用的rpy欧拉角,实际上是李代数之一。另一点需要说明的是,指数映射是一个满射而非单射。由于旋转具有周期性,多转360度和不转,表示的是同一个旋转。如果我们把旋转限制在正负180度内,那么李群到李代数就是一一对应的。

  反之,对数映射ln(R)将一个旋转矩阵转换为一个李代数。但由于对数的泰勒展开不是很优雅,通常直接按照下式计算李代数向量的大小和方向:

(6)θ=cos1tr(R)12+2kπRa=a

  根据该结果得到的ϕ=θa就是对应的李代数了。到这为止的内容都在上一讲中介绍过,本讲我们就接着往下说。


 SE(3)中的指数映射和对数映射

  se(3)里的向量经常写成ξ。它是一个六维向量,通常前三维为平移,后三维为旋转(也就是so(3)里的元素)。请注意,有些地方的定义是倒过来的,即前三维为旋转,后三维为平移,在使用的时候一定要小心!例如g2o的李代数和Sohpus的李代数定义就不一样。

   记ξ=[ρ,ϕ]T,它们各为三维向量,一共组成了六维,构成一个李代数。我们的记法里ρ为平移,ϕ为旋转,与SO(3)中一致。

  与SO(3)类似,se(3)SE(3)的指数映射为:

(7)exp(ξ)=n=01n!(ξ)n=[exp(ϕ)Jρ0T1]

   请注意该式左上即 SO(3) 的指数映射,右上较特殊一些,是平移量 ρ 的线性表示。其系数J3×3的计算方式如下:

J=n=01(n+1)!(ϕ)n=sinθθI+(1sinθθ)aaT+1cosθθa

   它与Rodrigues相似但有差别,实际上是对ϕ求了一次导数,所以这个阵也就记成了J,意为一个雅可比阵。它在后续许多地方会用到,所以现在单独提一下它。

  这个矩阵是可逆的,它的逆形式如下:

(8)J1=θ2cotθ2I+(1θ2cotθ2)aaTθ2a

  嗯,现在我们说清了SE(3)上的指数映射。那么它的对数映射怎么计算呢?也就是一个SE(3)中的矩阵怎么找到对应的向量呢?我们并不需要实际地计算一个矩阵对数,而只需要计算: 

  对于

T=[Rt0T1]

  它对应的李代数 ξ=[ρ,ϕ]T 为:

  (9)ϕ=ln(R),ρ=J1t

   因为已经有了SO(3)上的计算方式,这里的式子就变得十分简单了。


 Baker-Campbell-Hausdorff公式

  小萝卜:师兄我还有个问题啊。

  师兄:嗯你说。

  小萝卜:李群和李代数的对应关系倒是不难啦。但实际用的时候,我经常在李群上做两个矩阵的乘法。例如,做R1R2时,它们对应的李代数发生了什么呢?是不是直接加起来啊

  对,这就是我们要讨论的问题,即:

  (10)exp(ϕ1)exp(ϕ2)=exp((ϕ1+ϕ2))

  成立吗?

  如果该式成立的话,李群和李代数的结构就很方便了。因为我们可以直接把李群的乘法变成李代数的加法,而不需要改变任何东西。直观上,两个指数函数相乘,也确实等于把幂加起来,再取指数。唯一不同的是,这里我们不是对一个数求指数,而是求一个反对称矩阵的指数

  但是成不成立呢?

  很遗憾,虽然我们非常希望该式成立,但是实质上它是不满足的。Baker-Campbell-Hausdorff公式(https://en.wikipedia.org/wiki/Baker%E2%80%93Campbell%E2%80%93Hausdorff_formula)给出了这个运算的答案:

ln(exp(A)exp(B))=n=1(1)n1nri+si>0,i[1,n](i=1n(ri+si))1i=1nri!si![Ar1Bs1Ar2Bs2ArnBsn]

  那么这式子在说什么鬼呢?

  为了避免过于冗长的解释,我们就直接看它的近似式好了:

  ln(exp(A)exp(B))=A+B+12[A,B]+112[A,[A,B]]112[B,[A,B]]+

  这里的方括号指的是李括号,也就是:

[A,B]=ABBA

  特别地,在SO(3)上,我们可以求它关于某一个变量的一阶近似:

(11)ln(R1R2){Jl(ϕ2)1ϕ1+ϕ2Jr(ϕ1)1ϕ2+ϕ1

  对我们用处最大的就是这个近似式。在 ϕ1 较小时,使用第一个式;在在 ϕ2 较小时,使用第二个式。这里的 JlJr 也称为左/右雅可比——从而李代数就分成了左右两种模型(因此,李代数程序库会声明它使用的是左乘模型还是右乘模型)。

  那么这俩雅可比是啥类?

  事实上,前面已经提到过它了:

(12)Jl=J=n=01(n+1)!(ϕ)n,Jr=J(ϕ)

  在这个近似下,我们只保留了和小量相关的一阶信息,而舍弃了它的高阶项。因此,可以把这个过程类比于保留泰勒展开的一阶项而舍弃高阶项的过程,其中泰勒展开类比于BCH公式。


 BCH近似的直观意义

   以左乘形式(ϕ1较小)为例。我们给一个旋转矩阵 R 左乘一个微小扰动 ΔR=exp(Δϕ),得到了ΔRR。那么,对应到李代数上的变化量为:

  (13)ln(ΔRR)=ϕ+Jl1(ϕ)Δϕ

  反过来说,如果对某个固定的李代数ϕ增加一个小量δϕ,对应到李代数上,为:

  (14)exp(ϕ+δϕ)=exp(Jlδϕ)exp(ϕ)

  相当于左乘一个 Jlϕ 对应的旋转阵。类似地,由于左右对称,有:

  (15)exp(ϕ+δϕ)=exp(Jlδϕ)exp(ϕ)=exp(ϕ)exp(Jrδϕ)

  从这两个式子可以清楚地看到,BCH近似为我们指明了,李群与李代数微小量之间的关系——即,在BCH线性近似的意义下,它们只差一个雅可比矩阵。当区别左右乘时,这两个雅可比自变量差一个符号。


 应用:微分模型和扰动模型

  实际中,我们经常考虑这样一个问题(我们先讨论SO(3)上,再讨论SE(3)上):

  设一个空间点P=[x,y,z],它经过一次旋转,变成RP。问RP随着R是如何变化的?

  由于SO(3)上面没有加法,我们无法使用传统导数的定义(因为 R+ΔR 不再是旋转矩阵):

  d(RP)dR=limΔR0(R+ΔR)PRPΔR

  为了解决这个问题,有两种方式:一是把增量定义在李代数上,对应于微分模型;二是把增量直接乘在R,对应于扰动模型。如果读者熟悉了前面的公式,那这件事情是很轻松的。

  1. 定义在李代数上的增量

  在这个意义下,导数的含义为(最后一步跳过了若干过程,实际需要分开对各分量计算导数):

d(RP)dϕ=limδϕ0exp(ϕ+δϕ)Pexp(ϕ)Pδϕ=limΔϕ0(exp(Jlδϕ)1)exp(ϕ)Pδϕ=(RP)Jl

  2. 定义在李群上的乘增量

   另一种方式是将小量乘在李群上,而非加在李代数上。这种方式定义的模型称为扰动模型。由于左右的差异,需要区别这个增量是左乘在旋转阵,还是右乘在旋转阵上的。如果使用左乘,那么导数的含义为:

(16)d(RP)dR=limδϕ0exp(δϕ)RPRPδϕ=limΔϕ0(exp(δϕ)1)RPδϕ=(RP)

  可见,由于我们把小量乘在李群上(而非加在李代数上),结果中的导数将少一个雅可比矩阵。因此,扰动模型计算更为简洁,在实际上更加常用。


 SE(3)上扰动模型

  SE(3)上扰动模型为:考虑一个空间点P(必须为齐次坐标,否则维数不对)受到刚体变换 T ,得到 TP 。求 TP 是如何随 T 变化的。

  类似于SO(3),我们给T左乘一个小量ΔT=exp(δξ),得到:

(17)d(TP)dT=limδξ0exp(δξ)TPTPδξ=(TP)

  其中算符把一个4×4的矩阵变换成一个4×6的矩阵,计算方式如下:

(18)p=[x3×1w1×1],p=[wI3×3x3×30T3×10T3×1]

  至此,我们明确了一个被变换之后的点,是如何随变换矩阵而变化的。注意,我们省略了SE(3)上BCH近似雅可比的推导(比较复杂且扰动模型里没有该雅可比),如果读者感兴趣可参考[1]。

  小萝卜:师兄,知识我倒是知道了,您能讲讲怎么念吗?

  师兄:诶?……你看它像一个石子掉进井里,就念"dong"吧。

  小萝卜:所以SE(3)对李代数的扰动的导数就是那个点自己的“dong”喽?

  师兄:你愿意怎么记就怎么记吧……我不管了。


 小结

  本节介绍了以下几个关于李群代数的知识:

  1.  SE(3)的结构,指数映射和对数映射;

  2.  BCH公式与近似公式;

  3.  李代数上的微分运算。

  其中,介绍微分是介绍李代数的主要目的所在。知道了如何对位姿求导,我们才能深入地讨论姿态估计,直接法VO等话题。下一讲我们将介绍direct VO和semi-direct VO的方法

 [1]. Barfoot, State Estimation for Robotics: A Matrix-Lie-Group Approach, 2016

posted @   半闲居士  阅读(30502)  评论(11编辑  收藏  举报
编辑推荐:
· 从 HTTP 原因短语缺失研究 HTTP/2 和 HTTP/3 的设计差异
· AI与.NET技术实操系列:向量存储与相似性搜索在 .NET 中的实现
· 基于Microsoft.Extensions.AI核心库实现RAG应用
· Linux系列:如何用heaptrack跟踪.NET程序的非托管内存泄露
· 开发者必知的日志记录最佳实践
阅读排行:
· TypeScript + Deepseek 打造卜卦网站:技术与玄学的结合
· Manus的开源复刻OpenManus初探
· AI 智能体引爆开源社区「GitHub 热点速览」
· 三行代码完成国际化适配,妙~啊~
· .NET Core 中如何实现缓存的预热?
点击右上角即可分享
微信分享提示