1. 程式人生 > 實用技巧 >A Micro Lie Theory 論文理解

A Micro Lie Theory 論文理解

找到一篇 2018 年的論文 [1],是 Quaternion kinematics for the error-state Kalman filter [2] 的作者 Joan Solà 寫的。

論文的名字是 A micro Lie theory for state estimation in robotics。這篇論文介紹 Lie Theory,先中規中矩地介紹了 Lie Group, Tangent space, Lie Algebra。後面詳細介紹了與 Lie Algebra 有關的導數計算。導數計算是我關注的重點。

以下正文中的公式引用使用兩種形式:本文的公式,如(1);原文 [1] 的公式,如(1*)。

本文有可能概念不清,僅作為我對這些概念的自我理解。

1. 概念介紹

進行簡單的概念介紹。配合 [3] III.48 Lie Theory 理解這部分內容更好。

Group 是 set 與 operation 的組合,operation 作用於 set,並且滿足 4 條性質,見公式 (1-4*)。

Lie Group 是 Group,並且是連續的。對於”連續“的理解可以參考 [3] Page 230。

The group SO(2) is not just a continuous group, but also a Lie group. Roughly speaking, this means that it is a group in which one can meaningfully define the concept of a smooth curve (that is, a curve that is not just continuous but differentiable as well). Given any two elements \(R_{\theta}\)

and \(R_{\varphi}\) of SO(2), one can easily define a smooth path from \(R_{\theta}\) to \(R_{\varphi}\) by smoothly modifying \(\theta\) until it becomes \(\varphi\). (The most obvious such path would be given in parametric form by \(R_{(1-t)\theta + t\varphi}\), as t goes from 0 to 1.)

注意:

  1. Group 的本質是集合,並且在這個集合上定義了一種運算,並且要求這個集合與運算一起滿足一些條件。Group 並不是 Matrix,只是在大多數應用中,使用 Matrix 表達 Group,方便運算。
  2. Group 可以是不連續,如在 SO(2) 中選擇有限的 element,組成 Subgroup。subgroup 對應的集合是 {旋轉 0,旋轉 \(\pi/2\),旋轉 \(\pi\),旋轉 \(3\pi/2\)},集合上的操作就是 rotation composition。(Subgroup 一定包含原 Group 中的 identity element。)

”連續“的概念中出現了”smooth curve“,為了應對這個概念,引出了 Smooth Manifold 的概念。[1] 中對 Smooth Manifold 的說明如下。也可以參考 [1] Figure 2。

On one hand, a differentiable or smooth manifold is a topological space that locally resembles linear space.

topological space 的定義見 [4] Page 20。簡單說就是一個 set 與一個 collection。collection 是這個 set 的 subsets 組成的 set。並且要求這個 collection 滿足3 個條件:空集與原 set 是這個 collection 的元素;collection 中任意有限個元素的交集在 collection 中;collection 中任意個元素的並集在 collection 中。

Smooth Manifold 在任意一點處可以建立一個小的 vector space,Smooth Manifold 任意一點對 curve 引數方程的引數 t 求導的結果在這點的 vector space 上。這個 vector space 被稱作這一點處的 Tangent Space。

Lie Algebra 是 Lie Group 的 Smooth Manifold 在 Lie Group 的 Identity element 處的 tangent space,是一個 matrix space。如 SO(3) 對 t 的導數是一個 skew-symmetric matrix,這個 skew-symmetric matrix 就是 lie algebra。而角速度 \(\omega \in \mathbb{R}^3\) 並不是 lie algebra,skew-symmetric matrix 與 \(\mathbb{R}^3\) 同構(Homomorphism)。

即 Smooth Manifold 存在兩個 space:一個 space 是 Lie Group 中元素組成的 space 稱作 Manifold;一個 space 是 Tangent Space,是 vector space(對 scalar product 與 plus 閉合),用於在區域性近似 Manifold

2. 導數

在本科的高等數學微積分中學到的導數定義如下。

\[\begin{align} f^{\prime}(x) = \lim_{\Delta x \to 0} {f(x + \Delta x) - f(x) \over \Delta x} \label{eq:R_derivative} \end{align}\]

\(f: \mathbb{R} \to \mathbb{R}\),是一個定義域與值域都是 \(\mathbb{R}\) 的函式。\(\Delta x\) 的取值空間也是 \(\mathbb{R}\)

但是如果 \(f\) 的定義域是 Lie Group,即 \(x\) 應當寫作 \(\mathcal{X}\)\(\mathcal{X}\) 是 Manifold 中的元素,對應的 \(\Delta x\) 寫作 \(\bm{\tau}\) 是 Tangent Space 中的元素。也不能用 \(\mathbb{R}\) 中的 + 號,需要重新定義。Manifold 中的元素有 Group 定義中的操作 \(\circ\) 可以替換 + 號。但是,現在是 Manifold 與 Tangent Space 中元素的加號需要定義。

2.1. \(\oplus, \ominus\) 的定義

[1] 的 II. E (25-28*) 定義了在 Manifold 上的加法與減法,因為 Group 的定義中沒有保證 Commutative Law(交換律)。所以加法與減法的定義分為左右兩種(在 Group 定義的基礎上滿足交換律的 Group 叫做 Abelian Group)。

定義中的基本思想是使用 exponential map 將 tangent space 中的元素轉換為 lie group 中的元素,即將 tangent space 中的元素(delta)轉換為 Manifold 中的元素。使用 Group 定義中的 operation 將 delta apply 到 Manifold 的元素中去。

需要注意的是 \(\ominus\) 的定義,這個定義的核心是保證 tangent space 的 exponential map 在最左側或者最右側,不與 manifold 元素糅合在一起(這一點在 VIO 的 orientation 定義中非常重要)。

注意,在 (25-28) 的定義中只有 \(T_{\epsilon}\mathcal{M}\) 是 lie algebra,見 lie algebra 的定義 (8)。lie algebra 是特殊的 tangent space。

返回去看 \((\ref{eq:R_derivative})\) 的定義,可以將 \((\mathbb{R}, +)\) 看做是一個 group,這個 group 的 identity element 是 0,元素的逆就是其相反數,加法是有結合律的。\(\Delta x\) 是在 tangent space 上的元素,tangent space 與 manifold 都是 \(\mathbb{R}\),所以可以用 Group 中的 operation + 法將 tangent space 中的元素 apply 到 manifold 中的元素。

之後的文章預設使用右 \(\oplus, \ominus\)

2.2. Adjoint 定義

Adjiont 的定義是為了方便,方便將 manifold 中的元素 apply 到 tangent space 中的元素,將這個過程用 adjoint 表示。

區分好 adjoint 與 adjoint matrix。

在我之前的部落格中,我說了 SO(3) 的 adjoint matrix 是它自身。即參考 [5] 的公式 (10)。

\[\begin{align} \mathbf{R}\bm{\phi}^{\wedge}\mathbf{R}^T = (\mathbf{R}\bm{\phi})^{\wedge} \end{align}\]

上式中等號右側的 \(\mathbf{R}\) 應當寫作 \(\mathbf{Ad}_\mathbf{R}\)。即 \(\mathbf{Ad}_\mathbf{R} = \mathbf{R}\)

2.3. 導數定義

[1] II. G. 2) 與 3) 的公式 (41)(44) 定義了兩個 Jacobian,分別是使用左右 \(\oplus, \ominus\) 定義的。這種 Jacobian 的使用方式見 (43) 與 (45)。

緊接著作者在 [1] II. G. 4) 提到了在某些應用中存在將 \(\oplus, \ominus\) 混用的情況。如,使用左 \(\oplus\) 與右 \(\ominus\)

公式 (47) 與 (48) 第一次出現了分數線下的 \(D\) 左上角標。這個需要搞清楚,之後的公式 (59), (60) 也涉及到分數線下的 \(D\) 左上角標。

可以從 (49) (50) 推測分數線上下的左上角標的含義,但是這只是從導數的應用上推測。並沒有對這個導數的含義又說明。分數線上的 \(D\) 左上角標表示使用的 \(\ominus\) 方式的左右方向,\(\epsilon\) 表示 left minus,\(\mathcal{X}, \mathcal{Y}\) 表示 right minus(\(\mathcal{X}, \mathcal{Y}\) 應當理解成 \(f(\mathcal{X})\))。分數線下的 \(D\) 左上角標表示使用的 \(\oplus\) 的左右方向,\(\epsilon\) 表示 left plus,\(\mathcal{X}\) 表示 right plus(此處只有 \(\mathcal{X}\) 是變數)。所以可以知道公式 (41*) 的 \({{}^\mathcal{X} D f(\mathcal{X})\over D \mathcal{X}}\)\({{}^\mathcal{X} D f(\mathcal{X})\over {}^\mathcal{X} D \mathcal{X}}\) 的簡寫,同理公式 (44)。

舉個例子,\({{}^{\epsilon}D\mathcal{Y} \over {}^\mathcal{X}D\mathcal{X}}\) 的定義。

\[\begin{align} {{}^{\epsilon}D\mathcal{Y} \over {}^\mathcal{X}D\mathcal{X}} &= \lim_{{}^\mathcal{X}\bm{\tau} \to \bm{0}} {f(\mathcal{X} \oplus {}^\mathcal{X}\bm{\tau}) \ominus f(\mathcal{X})\over {}^\mathcal{X}\bm{\tau}} \\ &= \lim_{{}^\mathcal{X}\bm{\tau} \to \bm{0}} {\text{Log}[f(\mathcal{X}\circ\text{Exp}({}^\mathcal{X}\bm{\tau}))\circ f(\mathcal{X})^{-1}] \over {}^\mathcal{X}\bm{\tau}} \end{align}\]

證明 (47) (48)。按照 (49) (50) 寫出公式中出現的 6 個 Jacobians 的”含義“,再使用 \(f(\mathcal{X} \oplus {}^\mathcal{X}\bm{\tau}) = f({}^\epsilon\bm{\tau} \oplus\mathcal{X})\) 的方式去證明。令 \(\mathcal{Y} = f(\mathcal{X})\)

\[\begin{align} f(\mathcal{X} \oplus {}^\mathcal{X}\bm{\tau}) &\longrightarrow_{{}^\mathcal{X}\bm{\tau}\to\bm{0}} {{}^{\epsilon}D\mathcal{Y} \over {}^\mathcal{X}D\mathcal{X}} {}^\mathcal{X}\bm{\tau} \oplus f(\mathcal{X}) \\ f({}^\epsilon\bm{\tau} \oplus\mathcal{X}) &\longrightarrow_{{}^\epsilon\bm{\tau}\to\bm{0}} {{}^{\epsilon}D\mathcal{Y} \over {}^\epsilon D\mathcal{X}} {}^\epsilon\bm{\tau} \oplus f(\mathcal{X}) \\ f(\mathcal{X} \oplus {}^\mathcal{X}\bm{\tau}) &\longrightarrow_{{}^\mathcal{X}\bm{\tau}\to\bm{0}} f(\mathcal{X}) \oplus {{}^{\mathcal{Y}}D\mathcal{Y} \over {}^\mathcal{X}D\mathcal{X}} {}^\mathcal{X}\bm{\tau} \\ f({}^\epsilon\bm{\tau} \oplus\mathcal{X}) &\longrightarrow_{{}^\mathcal{X}\bm{\tau}\to\bm{0}} f(\mathcal{X}) \oplus {{}^{\mathcal{Y}}D\mathcal{Y} \over {}^\epsilon D\mathcal{X}} {}^\epsilon\bm{\tau} \\ f(\mathcal{X} \oplus {}^\mathcal{X}\bm{\tau}) &\longrightarrow_{{}^\mathcal{X}\bm{\tau}\to\bm{0}} f(\mathcal{X}) \oplus {{}^{\mathcal{Y}}D\mathcal{Y} \over {}^\mathcal{X} D\mathcal{X}} {}^\mathcal{X}\bm{\tau} \end{align}\]

(47*) 第 1 個等號。

\[\begin{align} {{}^{\epsilon}D\mathcal{Y} \over {}^\mathcal{X}D\mathcal{X}} {}^\mathcal{X}\bm{\tau} \oplus f(\mathcal{X}) &= {{}^{\epsilon}D\mathcal{Y} \over {}^\epsilon D\mathcal{X}} {}^\epsilon\bm{\tau} \oplus f(\mathcal{X}) \\ {{}^{\epsilon}D\mathcal{Y} \over {}^\mathcal{X}D\mathcal{X}} {}^\mathcal{X}\bm{\tau} &= {{}^{\epsilon}D\mathcal{Y} \over {}^\epsilon D\mathcal{X}} {}^\epsilon\bm{\tau} \\ {{}^{\epsilon}D\mathcal{Y} \over {}^\mathcal{X}D\mathcal{X}} {}^\mathcal{X}\bm{\tau} &=^{(30^*)} {{}^{\epsilon}D\mathcal{Y} \over {}^\epsilon D\mathcal{X}} \mathbf{Ad}_{\mathcal{X}} {}^\mathcal{X}\bm{\tau} \\ {{}^{\epsilon}D\mathcal{Y} \over {}^\mathcal{X}D\mathcal{X}} &= {{}^{\epsilon}D\mathcal{Y} \over {}^\epsilon D\mathcal{X}} \mathbf{Ad}_{\mathcal{X}} \\ \end{align}\]

(47*) 第 2 個等號。

\[\begin{align} {{}^{\epsilon}D\mathcal{Y} \over {}^\mathcal{X}D\mathcal{X}} {}^\mathcal{X}\bm{\tau} \oplus f(\mathcal{X}) &= f(\mathcal{X}) \oplus {{}^{\mathcal{Y}}D\mathcal{Y} \over {}^\mathcal{X}D\mathcal{X}} {}^\mathcal{X}\bm{\tau} \\ f(\mathcal{X}) \oplus {{}^{\mathcal{Y}}D\mathcal{Y} \over {}^\mathcal{X}D\mathcal{X}} {}^\mathcal{X}\bm{\tau} &= {{}^{\epsilon}D\mathcal{Y} \over {}^\mathcal{X}D\mathcal{X}} {}^\mathcal{X}\bm{\tau} \oplus f(\mathcal{X}) \\ {{}^{\epsilon}D\mathcal{Y} \over {}^\mathcal{X}D\mathcal{X}} {}^\mathcal{X}\bm{\tau} &=^{(32^*)} \mathbf{Ad}_{f(\mathcal{X})} {{}^{\mathcal{Y}}D\mathcal{Y} \over {}^\mathcal{X}D\mathcal{X}} {}^\mathcal{X}\bm{\tau} \\ {{}^{\epsilon}D\mathcal{Y} \over {}^\mathcal{X}D\mathcal{X}} &= \mathbf{Ad}_{f(\mathcal{X})} {{}^{\mathcal{Y}}D\mathcal{Y} \over {}^\mathcal{X}D\mathcal{X}} \\ &= \mathbf{Ad}_{\mathcal{Y}} {{}^{\mathcal{Y}}D\mathcal{Y} \over {}^\mathcal{X}D\mathcal{X}} \end{align}\]

(48*) 第 1 個等號。

\[\begin{align} f(\mathcal{X}) \oplus {{}^{\mathcal{Y}}D\mathcal{Y} \over {}^\epsilon D\mathcal{X}} {}^\epsilon\bm{\tau} &= f(\mathcal{X}) \oplus {{}^{\mathcal{Y}}D\mathcal{Y} \over {}^\mathcal{X} D\mathcal{X}} {}^\mathcal{X}\bm{\tau} \\ {{}^{\mathcal{Y}}D\mathcal{Y} \over {}^\epsilon D\mathcal{X}} {}^\epsilon\bm{\tau} &= {{}^{\mathcal{Y}}D\mathcal{Y} \over {}^\mathcal{X} D\mathcal{X}} {}^\mathcal{X}\bm{\tau} \\ {{}^{\mathcal{Y}}D\mathcal{Y} \over {}^\epsilon D\mathcal{X}} \mathbf{Ad}_{\mathcal{X}} {}^\mathcal{X}\bm{\tau} &=^{(30^*)} {{}^{\mathcal{Y}}D\mathcal{Y} \over {}^\mathcal{X} D\mathcal{X}} {}^\mathcal{X}\bm{\tau} \\ {{}^{\mathcal{Y}}D\mathcal{Y} \over {}^\epsilon D\mathcal{X}} \mathbf{Ad}_{\mathcal{X}} &= {{}^{\mathcal{Y}}D\mathcal{Y} \over {}^\mathcal{X} D\mathcal{X}} \\ {{}^{\mathcal{Y}}D\mathcal{Y} \over {}^\epsilon D\mathcal{X}} &= {{}^{\mathcal{Y}}D\mathcal{Y} \over {}^\mathcal{X} D\mathcal{X}} \mathbf{Ad}_{\mathcal{X}}^{-1} \end{align}\]

(48*) 第 2 個等號。

\[\begin{align} f(\mathcal{X}) \oplus {{}^{\mathcal{Y}}D\mathcal{Y} \over {}^\epsilon D\mathcal{X}} {}^\epsilon\bm{\tau} &= {{}^{\epsilon}D\mathcal{Y} \over {}^\epsilon D\mathcal{X}} {}^\epsilon\bm{\tau} \oplus f(\mathcal{X}) \\ {{}^{\epsilon}D\mathcal{Y} \over {}^\epsilon D\mathcal{X}} {}^\epsilon\bm{\tau} &=^{(32^*)} \mathbf{Ad}_{f(\mathcal{X})} {{}^{\mathcal{Y}}D\mathcal{Y} \over {}^\epsilon D\mathcal{X}} {}^\epsilon\bm{\tau} \\ {{}^{\epsilon}D\mathcal{Y} \over {}^\epsilon D\mathcal{X}} &= \mathbf{Ad}_{f(\mathcal{X})} {{}^{\mathcal{Y}}D\mathcal{Y} \over {}^\epsilon D\mathcal{X}} \\ {{}^{\epsilon}D\mathcal{Y} \over {}^\epsilon D\mathcal{X}} &= \mathbf{Ad}_{\mathcal{Y}} {{}^{\mathcal{Y}}D\mathcal{Y} \over {}^\epsilon D\mathcal{X}} \\ {{}^{\mathcal{Y}}D\mathcal{Y} \over {}^\epsilon D\mathcal{X}} &= \mathbf{Ad}_{\mathcal{Y}}^{-1} {{}^{\epsilon}D\mathcal{Y} \over {}^\epsilon D\mathcal{X}} \end{align}\]

2.4. 鏈式法則

在對 Lie Theory 沒有清晰瞭解之前,我嘗試使用自己所認為的 naive 鏈式法則計算一些導數,發現結果與直接使用左右擾動計算出來的導數不一致。

[1] III. A 的 (59) (60) 給出了鏈式法則,公式下面有證明 (59) 的第 1 個等號。作為練習,我證明 (59) 的第 2 個等號與 (60*)。

(59*) 第 1 個等號。

\[\begin{align} g(f({}^\epsilon\bm{\tau} \oplus \mathcal{X})) &\longrightarrow_{{}^\epsilon\bm{\tau}\to\bm{0}} g({{}^\epsilon D \mathcal{Y} \over {}^\epsilon D \mathcal{X}} {}^\epsilon\bm{\tau} \oplus f(\mathcal{X})) \\ &\longrightarrow_{{}^\epsilon\bm{\tau}\to\bm{0}} g(f(\mathcal{X})) \oplus {{}^\mathcal{Z} D \mathcal{Z}\over {}^\epsilon D \mathcal{Y}} ({{}^\epsilon D \mathcal{Y} \over {}^\epsilon D \mathcal{X}} {}^\epsilon\bm{\tau}) \end{align}\]

[1] 的原文在 (59*) 上說了一句 we need to chain also the reference frames。從上面這個公式看,第二行擴展出來的 \({{}^\mathcal{Z} D \mathcal{Z}\over {}^\epsilon D \mathcal{Y}}\) 的分數線下 \(D\) 左上角標 \(\epsilon\) 是固定,不能是 \(\mathcal{Y}\),因為第一行右側出現的 \(\oplus\) 是一個左 \(\oplus\)。而第一行右側的左 \(\oplus\) 是由第一行左側的左 \(\oplus\) 決定的,反應到 Jacobian 符號上就是 chain rule。這就是這一句話的含義。

(60*) 證明。

\[\begin{align} g(f(\mathcal{X} \oplus {}^\mathcal{X}\bm{\tau})) &\longrightarrow_{{}^\mathcal{X}\bm{\tau}\to\bm{0}} {{{}^\epsilon D \mathcal{Z}\over {}^\mathcal{X} D \mathcal{X}}} {}^\mathcal{X}\bm{\tau} \oplus g(f(\mathcal{X})) \\ g(f(\mathcal{X} \oplus {}^\mathcal{X}\bm{\tau})) &\longrightarrow_{{}^\mathcal{X}\bm{\tau}\to\bm{0}} g(f(\mathcal{X}) \oplus {{}^\mathcal{Y} D \mathcal{Y} \over {}^\mathcal{X} D \mathcal{X}} {}^\mathcal{X}\bm{\tau}) \\ &\longrightarrow_{{}^\mathcal{X}\bm{\tau}\to\bm{0}} {{}^\epsilon D \mathcal{Z} \over {}^\mathcal{Y} D \mathcal{Y}} ({{}^\mathcal{Y} D \mathcal{Y} \over {}^\mathcal{X} D \mathcal{X}} {}^\mathcal{X}\bm{\tau}) \oplus g(f(\mathcal{X}) \\ g(f(\mathcal{X} \oplus {}^\mathcal{X}\bm{\tau})) &\longrightarrow_{{}^\mathcal{X}\bm{\tau}\to\bm{0}} g({{}^\epsilon D \mathcal{Y} \over {}^\mathcal{X} D \mathcal{X}} {}^\mathcal{X}\bm{\tau} \oplus f(\mathcal{X})) \\ &\longrightarrow_{{}^\mathcal{X}\bm{\tau}\to\bm{0}} {{}^\epsilon D \mathcal{Z} \over {}^\epsilon D \mathcal{Y}}({{}^\epsilon D \mathcal{Y} \over {}^\mathcal{X} D \mathcal{X}} {}^\mathcal{X}\bm{\tau}) \oplus g(f(\mathcal{X})) \end{align}\]

2.5. 一些常見的雅克比

[1] III. B 作者開始介紹一些常見的雅克比結論。其中的 3) 介紹了左右雅克比,喜聞樂見。這是 State Estimation for Robotics 直接給出結論的東西,見 [6] 公式 (7.75)。

這一部分非常有意思。所以給出所有公式的證明。

2.5.1. Inverse

\[\begin{align} \mathbf{J}^{\mathcal{X}^{-1}}_{\mathcal{X}} &= {{}^{\mathcal{X}} D \mathcal{X}^{-1} \over D \mathcal{X}} = {{}^{\mathcal{X}} D \mathcal{X}^{-1} \over {}^{\mathcal{X}} D \mathcal{X}} \\ &=^{(41b^*)} \lim_{\bm{\tau}\to\bm{0}} {\text{Log}[f(\mathcal{X})^{-1} \circ f(\mathcal{X} \circ \text{Exp}(\tau))] \over \bm{\tau}} \\ &= \lim_{\bm{\tau}\to\bm{0}} {\text{Log}[(\mathcal{X}^{-1})^{-1} \circ (\mathcal{X} \circ \text{Exp}(\tau))^{-1}] \over \bm{\tau}} \\ &= \lim_{\bm{\tau}\to\bm{0}} {\text{Log}[\mathcal{X} \text{Exp}(-\tau) \mathcal{X}^{-1}] \over \bm{\tau}} \\ &= \lim_{\bm{\tau}\to\bm{0}} {\text{Log}[\mathcal{X} \text{exp}((-\tau)^{\wedge}) \mathcal{X}^{-1}] \over \bm{\tau}} \\ &= \lim_{\bm{\tau}\to\bm{0}} {\text{log}[ \text{exp}(\mathcal{X}(-\tau)^{\wedge}\mathcal{X}^{-1})]^{\vee} \over \bm{\tau}} \\ &= \lim_{\bm{\tau}\to\bm{0}} {-[(\mathcal{X}\tau^{\wedge}\mathcal{X}^{-1})]^{\vee} \over \bm{\tau}} \\ &=^{(31^*)} \lim_{\bm{\tau}\to\bm{0}} {-\mathbf{Ad}_{\mathcal{X}} \bm{\tau} \over \bm{\tau}} \\ &= -\mathbf{Ad}_{\mathcal{X}} \end{align}\]

2.5.2. Composition

公式 (65) (66) 的 SO(3) 情況作者在 [2] 中有推導過,見 [2] 的 4.3.5 Jacobians of rotation composition,在 [2] 中使用偏導 \(\partial\) 的形式寫是不合適是與 [1] 相違背的(見 (41c*)),SO(3) 是不能求對 SO(3) 的導數的,只能求 so(3) 對應的 \(\mathbb{R}^3\) 對 so(3) 對應的 \(\mathbb{R}^3\) 的導數。

\[\begin{align} \mathbf{J}^{\mathcal{X}\circ\mathcal{Y}}_{\mathcal{X}} &= {{}^{\mathcal{X}} D \mathcal{X} \circ \mathcal{Y} \over D \mathcal{X}} \\ &= \lim_{\bm{\tau}\to\bm{0}} {\text{Log}[(\mathcal{X}\mathcal{Y})^{-1}(\mathcal{X}\text{Exp}(\bm{\tau})\mathcal{Y})] \over \bm{\tau}} \\ &= \lim_{\bm{\tau}\to\bm{0}} {\text{Log}[\mathcal{Y}^{-1}\mathcal{X}^{-1}\mathcal{X}\text{Exp}(\bm{\tau})\mathcal{Y}] \over \bm{\tau}} \\ &= \lim_{\bm{\tau}\to\bm{0}} {\text{Log}[\mathcal{Y}^{-1}\text{Exp}(\bm{\tau})\mathcal{Y}] \over \bm{\tau}} \\ &= \lim_{\bm{\tau}\to\bm{0}} {\text{Log}[\text{Exp}(\mathbf{Ad}_{\mathcal{Y}^{-1}}\bm{\tau})] \over \bm{\tau}} \\ &= \mathbf{Ad}_{\mathcal{Y}^{-1}} = \mathbf{Ad}_{\mathcal{Y}}^{-1} \end{align}\]

\[\begin{align} \mathbf{J}^{\mathcal{X}\circ\mathcal{Y}}_{\mathcal{Y}} &= {{}^{\mathcal{X}} D \mathcal{X} \circ \mathcal{Y} \over D \mathcal{Y}} \\ &= \lim_{\bm{\tau}\to\bm{0}} {\text{Log}[(\mathcal{X}\mathcal{Y})^{-1}(\mathcal{X}\mathcal{Y}\text{Exp}(\bm{\tau}))] \over \bm{\tau}} \\ &= \lim_{\bm{\tau}\to\bm{0}} {\text{Log}[\text{Exp}(\bm{\tau})] \over \bm{\tau}} \\ &= \mathbf{I} \end{align}\]

2.5.3. Jacobians of \(\mathcal{M}\)

定義左右雅克比,(67) (71)。

證明 (68*)。

\[\begin{align} \mathbf{J}_r(\bm{\tau}) &= {{}^{\bm{\tau}} D \text{Exp}(\bm{\tau}) \over D \bm{\tau}} \\ \text{Exp}(\bm{\tau} + \delta \bm{\tau})&=^{(43^*)} \text{Exp}(\bm{\tau}) \oplus {{}^{\bm{\tau}} D \text{Exp}(\bm{\tau}) \over D \bm{\tau}} \delta\bm{\tau} \\ &= \text{Exp}(\bm{\tau}) \text{Exp}({{}^{\bm{\tau}} D \text{Exp}(\bm{\tau}) \over D \bm{\tau}} \delta\bm{\tau}) \\ &= \text{Exp}(\bm{\tau}) \text{Exp}(\mathbf{J}_r(\bm{\tau}) \delta\bm{\tau}) \end{align}\]

同理可證 (72*)。

證明(75),(68) (72*) 的左側相等,分別取右側,令它們相等。

\[\begin{align} \text{Exp}(\bm{\tau}) \text{Exp}(\mathbf{J}_r(\bm{\tau}) \delta\bm{\tau}) &= \text{Exp}(\mathbf{J}_l(\bm{\tau}) \delta\bm{\tau}) \text{Exp}(\bm{\tau}) \\ \text{Exp}(\bm{\tau}) \oplus (\mathbf{J}_r(\bm{\tau}) \delta\bm{\tau}) &= (\mathbf{J}_l(\bm{\tau}) \delta\bm{\tau}) \oplus \text{Exp}(\bm{\tau}) \\ \mathbf{J}_l(\bm{\tau}) \delta\bm{\tau} &=^{(32^*)} \mathbf{Ad}_{\text{Exp}(\bm{\tau})} \mathbf{J}_r(\bm{\tau}) \delta\bm{\tau} \\ \mathbf{J}_l(\bm{\tau}) &= \mathbf{Ad}_{\text{Exp}(\bm{\tau})} \mathbf{J}_r(\bm{\tau}) \\ \mathbf{Ad}_{\text{Exp}(\bm{\tau})} &= \mathbf{J}_l(\bm{\tau}) \mathbf{J}_r^{-1}(\bm{\tau}) \end{align}\]

(76) 的過程,(76) 的第 2 行第 2 個等號是比較難的。

\[\begin{align} \mathbf{J}_r(-\bm{\tau}) &= \mathbf{J}_{-\bm{\tau}}^{\text{Exp}(-\bm{\tau})} \\ &= \mathbf{J}_{\bm{\tau}}^{\text{Exp}(-\bm{\tau})} \mathbf{J}_{-\bm{\tau}}^{\bm{\tau}} \\ &= \mathbf{J}_{\bm{\tau}}^{\text{Exp}(-\bm{\tau})} (-\mathbf{I}) \\ &= -\mathbf{J}_{\text{Exp}(\bm{\tau})}^{\text{Exp}(\bm{\tau})^{-1}} \mathbf{J}_{\bm{\tau}}^{\text{Exp}(\bm{\tau})} \\ &=^{(62^*)} -(-\mathbf{Ad}_{\text{Exp}(\bm{\tau})}) \mathbf{J}_{\bm{\tau}}^{\text{Exp}(\bm{\tau})} \\ &= \mathbf{Ad}_{\text{Exp}(\bm{\tau})} \mathbf{J}_{\bm{\tau}}^{\text{Exp}(\bm{\tau})} \\ &=^{(67^*)} \mathbf{Ad}_{\text{Exp}(\bm{\tau})} \mathbf{J}_r(\bm{\tau}) \\ &=^{(75^*)} \mathbf{J}_l(\bm{\tau}) \end{align}\]

2.5.4. Group action

這就是最常見的 \(\mathbf{R}\mathbf{p}\)\(\mathbf{R}\) 的 Tangent Space 對應的 \(\mathbf{\phi} \in \mathbb{R}^3\) 的導數。

2.6. 使用 chain rule

[1] III. C 部分。

公式 (79*) 的證明,注意 \(\text{Log}(\mathcal{X})\in\mathbb{R}^m\),所以 \(\ominus\) 不能使用 manifold 上的定義。

\[\begin{align} \mathbf{J}^{\text{Log}(\mathcal{X})}_\mathcal{X} &= {{}^{\mathcal{X}} D \text{Log}(\mathcal{X}) \over D \mathcal{X}} \\ &=^{(41a^*)} \lim_{\delta\bm{\tau}\to\bm{0}} {\text{Log}(\mathcal{X}\oplus\delta\bm{\tau}) \ominus \text{Log}(\mathcal{X}) \over\delta \bm{\tau}} \\ &= \lim_{\delta\bm{\tau}\to\bm{0}} {\text{Log}(\mathcal{X}\text{Exp}(\delta\bm{\tau})) - \text{Log}(\mathcal{X}) \over \delta\bm{\tau}} \\ &= \lim_{\delta\bm{\tau}\to\bm{0}} {\text{Log}(\text{Exp}(\bm{\tau})\text{Exp}(\delta\bm{\tau})) - \text{Log}(\text{Exp}(\bm{\tau})) \over \delta\bm{\tau}} \\ &=^{(70^*)} \lim_{\delta\bm{\tau}\to\bm{0}} {\bm{\tau} + \mathbf{J}_r^{-1}(\bm{\tau})\delta\bm{\tau} - \bm{\tau} \over \delta\bm{\tau}} \\ &= \mathbf{J}_r^{-1}(\bm{\tau}) \end{align}\]

證明公式 (80*)。

\[\begin{align} \mathbf{J}_\mathcal{X}^{\mathcal{X}\oplus\bm{\tau}} &= \mathbf{J}_\mathcal{X}^{\mathcal{X}\circ\text{Exp}(\bm{\tau})} \\ &=^{(65^*)} \mathbf{Ad}_{\text{Exp}(\bm{\tau})}^{-1} \\ \mathbf{J}_\mathcal{X}^{\mathcal{X}\oplus\bm{\tau}} &= {{}^{\mathcal{X}}D \mathcal{X}\oplus\bm{\tau} \over {}^{\mathcal{X}}D\mathcal{X}} \\ &=^{(41a^*)} \lim_{\delta\bm{\tau}\to\bm{0}}{(\mathcal{X}\oplus\delta\bm{\tau}\oplus\bm{\tau}) \ominus (\mathcal{X}\oplus\bm{\tau}) \over \delta \bm{\tau}} \\ &= \lim_{\delta\bm{\tau}\to\bm{0}}{\text{Log}[(\mathcal{X}\oplus\bm{\tau})^{-1}\circ(\mathcal{X}\oplus\delta\bm{\tau}\oplus\bm{\tau})] \over \delta \bm{\tau}} \\ &= \lim_{\delta\bm{\tau}\to\bm{0}}{\text{Log}[(\mathcal{X}\text{Exp}(\bm{\tau}))^{-1}(\mathcal{X}\text{Exp}(\delta\bm{\tau})\text{Exp}(\bm{\tau}))] \over \delta \bm{\tau}} \\ &= \lim_{\delta\bm{\tau}\to\bm{0}}{\text{Log}[\text{Exp}(\bm{\tau})^{-1}\mathcal{X}^{-1}\mathcal{X}\text{Exp}(\delta\bm{\tau})\text{Exp}(\bm{\tau})] \over \delta \bm{\tau}} \\ &= \lim_{\delta\bm{\tau}\to\bm{0}}{\text{Log}[\text{Exp}(\bm{\tau})^{-1}\text{Exp}(\delta\bm{\tau})\text{Exp}(\bm{\tau})] \over \delta \bm{\tau}} \\ &= \lim_{\delta\bm{\tau}\to\bm{0}}{\text{Log}[\text{Exp}(\mathbf{Ad}_{\text{Exp}(\bm{\tau})^{-1}}\delta\bm{\tau})] \over \delta \bm{\tau}} \\ &= \mathbf{Ad}_{\text{Exp}(\bm{\tau})^{-1}} = \mathbf{Ad}_{\text{Exp}(\bm{\tau})}^{-1} \end{align}\]

證明公式 (81*)。

\[\begin{align} \mathbf{J}_\bm{\tau}^{\mathcal{X}\oplus\bm{\tau}} &= \mathbf{J}_\bm{\tau}^{\mathcal{X}\circ\text{Exp}(\bm{\tau})} \\ &= \mathbf{J}_{\text{Exp}(\bm{\tau})}^{\mathcal{X}\circ\text{Exp}(\bm{\tau})} \mathbf{J}_\bm{\tau}^{\text{Exp}(\bm{\tau})} \\ &=^{(66^*)} \mathbf{I} \mathbf{J}_\bm{\tau}^{\text{Exp}(\bm{\tau})} \\ &=^{(67^*)} \mathbf{J}_r(\bm{\tau}) \\ \mathbf{J}_\bm{\tau}^{\mathcal{X}\oplus\bm{\tau}} &= {{}^{\bm{\tau}}D \mathcal{X}\oplus\bm{\tau} \over {}^{\bm{\tau}}D\bm{\tau}} \\ &=^{(41a^*)} \lim_{\delta\bm{\tau}\to\bm{0}}{(\mathcal{X}\oplus(\bm{\tau} + \delta\bm{\tau})) \ominus (\mathcal{X}\oplus\bm{\tau}) \over \delta \bm{\tau}} \\ &= \lim_{\delta\bm{\tau}\to\bm{0}}{\text{Log}[(\mathcal{X}\oplus\bm{\tau})^{-1}\circ(\mathcal{X}\oplus(\bm{\tau} + \delta\bm{\tau}))] \over \delta \bm{\tau}} \\ &= \lim_{\delta\bm{\tau}\to\bm{0}}{\text{Log}[(\mathcal{X}\text{Exp}(\bm{\tau}))^{-1}(\mathcal{X}\text{Exp}(\bm{\tau} + \delta\bm{\tau}))] \over \delta \bm{\tau}} \\ &= \lim_{\delta\bm{\tau}\to\bm{0}}{\text{Log}[\text{Exp}(\bm{\tau})^{-1}\text{Exp}(\bm{\tau} + \delta\bm{\tau})] \over \delta \bm{\tau}} \\ &=^{(68^*)} \lim_{\delta\bm{\tau}\to\bm{0}}{\text{Log}[\text{Exp}(\mathbf{J}_r(\bm{\tau})\delta\bm{\tau})] \over \delta \bm{\tau}} \\ &= \mathbf{J}_r(\bm{\tau}) \end{align}\]

Reference

[1] Sola, Joan, Jeremie Deray, and Dinesh Atchuthan. "A micro Lie theory for state estimation in robotics." arXiv preprint arXiv:1812.01537 (2018).

[2] Sola, Joan. "Quaternion kinematics for the error-state Kalman filter." arXiv preprint arXiv:1711.02508 (2017).

[3] Gowers, Timothy, June Barrow-Green, and Imre Leader, eds. The Princeton companion to mathematics. Princeton University Press, 2008.

[4] Lee, John. Introduction to topological manifolds. Vol. 202. Springer Science & Business Media, 2010.

[5] Forster, Christian, et al. "IMU preintegration on manifold for efficient visual-inertial maximum-a-posteriori estimation." Georgia Institute of Technology, 2015.

[6] Barfoot, Timothy D. State estimation for robotics. Cambridge University Press, 2017.