iSAM2 部分状态更新算法 (I - 原理解读)

Title: iSAM2 部分状态更新算法 (I-原理解读)


文章目录

  • I. 前言
  • II. 部分状态的更新 (Partial State Update)
  • III. 因子图的线性化 (Linearization of Factor Grahps)
    • 1. 简单实例的设定
    • 2. 一个线性化计算
    • 3. 其他线性化计算
    • 4. 状态更新量说明
  • IV. 部分 QR 分解实现变量消元 (Eliminating Variables Using Partial QR)
    • 1. 首变量的消元
    • 2. 中间变量的消元
    • 3. 最末变量的消元
  • V. 状态更新的反向替代 (Back Substitution for State Update)
  • VI. 总结
  • 参考文献


关联博客:

因子图、边缘化与消元算法的抽丝剥茧 —— Notes for “Factor Graphs for Robot Perception”

基于 GTSAM 的因子图简单实例

GTSAM 中的鲁棒噪声模型与 M-估计 (GTSAM Robust Noise Model and M-Estimator)

贝叶斯树定义与构建的寻行数墨 —— Notes for “The Bayes Tree: An Algorithmic Foundation for Probabilistic Robot Mapping”

贝叶斯树增量式更新的细嚼慢咽 —— Notes for “The Bayes Tree: An Algorithmic Foundation for Probabilistic Robot Mapping”

iSAM2 部分状态更新算法 (I-原理解读) ⇐ \quad\Leftarrow\quad 本篇


I. 前言

SLAM 后端优化中基于因子图 (Factor Graph) 的增量式平滑和建图算法 iSAM2[1] 的原理以及 GTSAM 的实现, 内容丰富非常精彩, 尝试理解的过程中会很烧脑.

我们此处只选其中一小部分 “iSAM 中的部分状态更新子算法”, 尝试对其原理和源码分别解读一下.

本篇先讲原理部分, 对应于论文 “iSAM2: Incremental smoothing and mapping using the Bayes tree”[1] 中的 “Algorithm 7 Partial state update: solving the Bayes tree in the nonlinear case returns an update Δ \Delta Δ to the current linearization point Θ \Theta Θ”.


II. 部分状态的更新 (Partial State Update)

部分状态更新算法的伪代码如下[1]:

部分状态更新算法: 解非线性情况下的贝叶斯树, 返回当前线性化点 (状态) Θ \Theta Θ 的更新 Δ \Delta Δ

输入: 贝叶斯树 T \mathcal{T} T

输出: 状态的更新 Δ \Delta Δ

[1]   从根团 C r = F r C_r = F_r Cr=Fr 开始执行:

[2]        对于现在的团 C k = F k : S k C_k=F_k: S_k Ck=Fk:Sk, 从局部条件概率密度 P ( F k ∣ S k ) P(F_k | S_k) P(FkSk) 中计算前端变量 F k F_k Fk 的状态更新 Δ k \Delta_k Δk.

[3]        如果状态更新 Δ k \Delta_k Δk 中的变量 Δ k j \Delta_{k_j} Δkj 大于阈值 α \alpha α, 则对包含该变量的子团递归地执行本算法.

需要说明:

- 部分状态更新的驱动因素源自贝叶斯树的更新, 如整个因子图中加入了新的因子、贝叶斯树需要重线性化等.

- 算法名中所谓的 “部分” 就是仅对部分变量进行更新计算, 只有贝叶斯树的团中包含大于阈值的变量更新时, 更新计算才向子团传播.

- 状态更新和重线性化 (Fluid Relinearization) 是不同的, 状态更新只计算线性化后的状态偏差 Δ \Delta Δ 偏离零点 0 0 0 的程度, 而重线性化是在新的线性化点 Θ [ 0 ] \Theta^{[0]} Θ[0] 上作关于变量 Θ \Theta Θ 的因子图与贝叶斯树的线性化.

状态变量 Θ \Theta Θ 及其偏差 Δ \Delta Δ 之间的相互关系如下:
Θ [ 0 ] ⟼ Θ ∣ ∣ 0 ⟼ Δ = Θ − Θ [ 0 ] \begin{array}{ll} \Theta^{[0]} & \longmapsto & \Theta\\ |&&|\\ 0 &\longmapsto & \Delta = \Theta- \Theta^{[0]} \end{array} Θ[0]0ΘΔ=ΘΘ[0]

消元运算 (Elimination) 是贯穿于整个因子图算法的重要技术, 状态更新也和消元运算紧密相关, 我们还是从消元运算开始.

不同于之前博文 “因子图、边缘化与消元算法的抽丝剥茧 —— Notes for ‘Factor Graphs for Robot Perception’” 侧重于定性分析, 本文重点在于消元的计算过程. 因为要用作变量的数值更新计算, 所以定量计算公式是重点.

实际问题都是非线性问题, 定量计算一般要从线性化着手.


III. 因子图的线性化 (Linearization of Factor Grahps)

1. 简单实例的设定

此处还是借用最简单的 SLAM 例子作说明, 稍有不同的是这次在 SLAM 运行过程中新增加了因子 ϕ 10 \phi_{10} ϕ10, 如 Fig .1. 在本例中具体新增哪个因子或什么样的因子并不重要, 只是新增加因子就会触发 iSAM2 算法更新贝叶斯树以及执行增量式优化, 故也引起了部分状态更新算法的执行.

factor_graph_2_slam_addAfactor
Fig. 1 一个简单的 SLAM 中的因子图例子

该例子中的变量 Θ = [ θ 1 θ 2 θ 3 θ 4 θ 5 ] ≜ [ l 1 l 2 x 1 x 2 x 3 ] \Theta = \begin{bmatrix}\theta_1 \\ \theta_2 \\ \theta_3 \\ \theta_4 \\ \theta_5 \end{bmatrix} \triangleq \begin{bmatrix}l_1 \\ l_2 \\ x_1 \\ x_2 \\ x_3 \end{bmatrix} Θ= θ1θ2θ3θ4θ5 l1l2x1x2x3 .

而其中每个变量又由于应用场景的不同, 又都是不同维度的向量, 如二维应用中 l 1 = [ l 1 , x l 1 , y ] ∈ R 2 l_1= \begin{bmatrix} l_{1, x} \\ l_{1, y}\end{bmatrix}\in \mathbb{R}^2 l1=[l1,xl1,y]R2 x 1 = [ x 1 , x x 1 , y x 1 , r o t ] ∈ S E ( 3 ) x_1 = \begin{bmatrix} x_{1,x}\\ x_{1, y} \\ x_{1, rot}\end{bmatrix}\in \mathbb{SE}(3) x1= x1,xx1,yx1,rot SE(3). 此处我们忽略不同流形的空间结构, 都视作欧式空间.

例子中有因子 ϕ 1 , ⋯   , ϕ 10 \phi_1, \cdots,\phi_{10} ϕ1,,ϕ10, 所谓因子图的线性化就是先对其中的每个因子进行线性化, 组成的整个因子图也就完成了线性化.

下面我们以变量 l 1 l_1 l1 关联的三个因子 { ϕ 3 , ϕ 7 , ϕ 8 } \{\phi_3, \phi_7, \phi_8\} {ϕ3,ϕ7,ϕ8} 为例进行因子的线性化.


2. 一个线性化计算

假设路标 l 1 l_1 l1 的先验因子是高斯概率分布因子
ϕ 4 = N ( l 1 ; z 4 , Σ 4 ) ∝ exp ⁡ ( − 1 2 ∥ l 1 − z 4 ∥ Σ 4 2 ) \begin{aligned} \phi_4 = \mathcal{N}(l_1; z_4, \Sigma_4) \propto \exp(-\frac{1}{2} \left\|l_1 - z_4 \right\|^2_{\Sigma_4}) \end{aligned} ϕ4=N(l1;z4,Σ4)exp(21l1z4Σ42)
变量 θ 1 ≜ l 1 \theta_1 \triangleq l_1 θ1l1, 测量函数 h 4 ( θ 1 ) = θ 1 h_4(\theta_1) = \theta_1 h4(θ1)=θ1. 则在线性化点 θ 1 [ 0 ] \theta_1^{[0]} θ1[0] 处的测量雅可比矩阵 (Measurement Jacobian) 为
H 4 = ∂ h 4 ( θ 1 ) ∂ θ 1 ∣ θ 1 [ 0 ] = 1 H_4 = \left. \frac{\partial h_4(\theta_1)}{\partial \theta_1}\right|_{ \theta_1^{[0]}}= 1 H4=θ1h4(θ1) θ1[0]=1
定义变量相对于线性化点的偏差 Δ 1 ≜ θ 1 − θ 1 [ 0 ] \Delta_1 \triangleq \theta_1 - \theta_1^{[0]} Δ1θ1θ1[0], 则测量函数的一阶泰勒展开为 h 4 ( θ 1 ) ≈ θ 1 [ 0 ] + H 4 ( θ 1 − θ 1 [ 0 ] ) = θ 1 [ 0 ] + H 4 Δ 1 h_4(\theta_1) \approx \theta_1^{[0]} + H_4 (\theta_1 - \theta_1^{[0]}) = \theta_1^{[0]} + H_4 \Delta_1 h4(θ1)θ1[0]+H4(θ1θ1[0])=θ1[0]+H4Δ1.

将一阶近似代入因子
ϕ 4 ( θ 1 ) ∝ exp ⁡ ( − 1 2 ∥ θ 1 [ 0 ] + H 4 Δ 1 − z 4 ∥ Σ 4 2 ) ∝ exp ⁡ ( − 1 2 ∥ Σ 4 − 1 2 H 4 Δ 1 − Σ 4 − 1 2 ( z 4 − θ 1 [ 0 ] ) ∥ 2 ) \begin{aligned} \phi_4(\theta_1) &\propto \exp(-\frac{1}{2} \left\|\theta_1^{[0]} + H_4 \Delta_1 - z_4 \right\|^2_{\Sigma_4})\\ &\propto \exp(-\frac{1}{2} \left\|\Sigma_4^{-\frac{1}{2}} H_4 \Delta_1 - \Sigma_4^{-\frac{1}{2}} \left( z_4 - \theta_1^{[0]}\right) \right\|^2) \end{aligned} ϕ4(θ1)exp(21 θ1[0]+H4Δ1z4 Σ42)exp(21 Σ421H4Δ1Σ421(z4θ1[0]) 2)
再定义 A 41 ≜ Σ 4 − 1 2 H 4 A_{41} \triangleq \Sigma_4^{-\frac{1}{2}} H_4 A41Σ421H4, b 4 ≜ Σ 4 − 1 2 ( z 4 − θ 1 [ 0 ] ) b_4 \triangleq \Sigma_4^{-\frac{1}{2}} \left( z_4 - \theta_1^{[0]}\right) b4Σ421(z4θ1[0]). 得到在线性化点 θ 1 [ 0 ] \theta_1^{[0]} θ1[0] 处的线性化高斯因子
ϕ 4 ( θ 1 ) ∝ exp ⁡ ( − 1 2 ∥ A 41 Δ 1 − b 4 ∥ 2 ) (II-2-1) \phi_4(\theta_1) \propto \exp(-\frac{1}{2} \left\|A_{41} \Delta_1 - b_4 \right\|^2) \tag{II-2-1} ϕ4(θ1)exp(21A41Δ1b42)(II-2-1)


3. 其他线性化计算

同样的方法计算 ϕ 7 \phi_7 ϕ7 的线性化,
ϕ 7 ( θ 1 , θ 3 ) ∝ exp ⁡ ( 1 2 ∥ θ 1 − θ 3 − z 7 ∥ Σ 7 2 ) ∝ exp ⁡ ( − 1 2 ∥ [ A 71 , A 73 ] [ Δ 1 Δ 3 ] − b 7 ∥ 2 ) (II-3-1) \begin{aligned} \phi_7(\theta_1, \theta_3) & \propto \exp(\frac{1}{2} \Vert \theta_1 - \theta_3 - z_7\Vert_{\Sigma_7}^2) \\ & \propto \exp(-\frac{1}{2} \left\Vert \begin{bmatrix}A_{71}, A_{73}\end{bmatrix} \begin{bmatrix}\Delta_1 \\ \Delta_3 \end{bmatrix} - b_7 \right \Vert^2) \end{aligned} \tag{II-3-1} ϕ7(θ1,θ3)exp(21θ1θ3z7Σ72)exp(21 [A71,A73][Δ1Δ3]b7 2)(II-3-1)
其中中间变量有
h 7 ( θ 1 , θ 3 ) = θ 1 − θ 3 H 7 = ∂ h 7 ( θ 1 , θ 3 ) ∂ [ θ 1 , θ 3 ] T ∣ θ 1 [ 0 ] , θ 3 [ 0 ] = [ I , − I ] Δ 3 ≜ θ 3 − θ 3 [ 0 ] h 7 ( θ 1 , θ 3 ) = θ 1 [ 0 ] − θ 3 [ 0 ] + H 7 [ Δ 1 Δ 3 ] [ A 71 , A 73 ] = Σ 7 − 1 2 H 7 b 7 = Σ 7 − 1 2 ( z 7 − θ 1 [ 0 ] + θ 3 [ 0 ] ) \begin{aligned} h_7(\theta_1, \theta_3) & = \theta_1 - \theta_3\\ H_7 &= \left. \frac{\partial h_7(\theta_1, \theta_3)}{\partial \begin{bmatrix}\theta_1, \theta_3\end{bmatrix}^{\rm \small T}}\right|_{\theta_1^{[0]}, \theta_3^{[0]}} = \begin{bmatrix}I, -I\end{bmatrix}\\ \Delta_3 &\triangleq \theta_3 - \theta_3^{[0]} \\ h_7(\theta_1, \theta_3) & = \theta_1^{[0]} - \theta_3^{[0]} + H_7 \begin{bmatrix} \Delta_1 \\ \Delta_3 \end{bmatrix}\\ \begin{bmatrix} A_{71}, A_{73} \end{bmatrix}&=\Sigma_7^{-\frac{1}{2}} H_7\\ b_7 &= \Sigma_7^{-\frac{1}{2}}(z_7 - \theta_1^{[0]}+ \theta_3^{[0]}) \end{aligned} h7(θ1,θ3)H7Δ3h7(θ1,θ3)[A71,A73]b7=θ1θ3=[θ1,θ3]Th7(θ1,θ3) θ1[0],θ3[0]=[I,I]θ3θ3[0]=θ1[0]θ3[0]+H7[Δ1Δ3]=Σ721H7=Σ721(z7θ1[0]+θ3[0])

再用同样的方法计算 ϕ 8 \phi_8 ϕ8 的线性化
ϕ 8 ( θ 1 , θ 4 ) ∝ exp ⁡ ( 1 2 ∥ θ 1 − θ 4 − z 8 ∥ Σ 8 2 ) ∝ exp ⁡ ( − 1 2 ∥ [ A 81 , A 84 ] [ Δ 1 Δ 4 ] − b 8 ∥ 2 ) (II-3-2) \begin{aligned} \phi_8(\theta_1, \theta_4) & \propto \exp(\frac{1}{2} \Vert \theta_1 - \theta_4 - z_8\Vert_{\Sigma_8}^2) \\ & \propto \exp(-\frac{1}{2} \left\Vert \begin{bmatrix}A_{81}, A_{84}\end{bmatrix} \begin{bmatrix}\Delta_1 \\ \Delta_4 \end{bmatrix} - b_8 \right \Vert^2) \end{aligned} \tag{II-3-2} ϕ8(θ1,θ4)exp(21θ1θ4z8Σ82)exp(21 [A81,A84][Δ1Δ4]b8 2)(II-3-2)
其中中间变量有
h 8 ( θ 1 , θ 4 ) = θ 1 − θ 4 H 8 = [ I , − I ] Δ 4 ≜ θ 4 − θ 4 [ 0 ] h 8 ( θ 1 , θ 4 ) = θ 1 [ 0 ] − θ 4 [ 0 ] + H 8 [ Δ 1 Δ 4 ] [ A 81 , A 84 ] = Σ 8 − 1 2 H 8 b 8 = Σ 8 − 1 2 ( z 8 − θ 1 [ 0 ] + θ 4 [ 0 ] ) \begin{aligned} h_8(\theta_1, \theta_4) & = \theta_1 - \theta_4\\ H_8 &= \begin{bmatrix}I, -I\end{bmatrix}\\ \Delta_4 &\triangleq \theta_4 - \theta_4^{[0]} \\ h_8(\theta_1, \theta_4) & = \theta_1^{[0]} - \theta_4^{[0]} + H_8 \begin{bmatrix} \Delta_1 \\ \Delta_4 \end{bmatrix}\\ \begin{bmatrix} A_{81}, A_{84} \end{bmatrix}&=\Sigma_8^{-\frac{1}{2}} H_8\\ b_8 &= \Sigma_8^{-\frac{1}{2}}(z_8 - \theta_1^{[0]}+ \theta_4^{[0]}) \end{aligned} h8(θ1,θ4)H8Δ4h8(θ1,θ4)[A81,A84]b8=θ1θ4=[I,I]θ4θ4[0]=θ1[0]θ4[0]+H8[Δ1Δ4]=Σ821H8=Σ821(z8θ1[0]+θ4[0])


4. 状态更新量说明

在线性化过程中, 定义了变量相对于线性化点的偏差 (状态更新变量更新)
Δ = [ Δ 1 Δ 2 Δ 3 Δ 4 Δ 5 ] ≜ [ l 1 − l 1 [ 0 ] l 2 − l 2 [ 0 ] x 1 − x 1 [ 0 ] x 2 − x 2 [ 0 ] x 3 − x 3 [ 0 ] ] (II-4-1) \Delta = \begin{bmatrix} \Delta_1 \\ \Delta_2 \\ \Delta_3 \\ \Delta_4 \\ \Delta_5 \end{bmatrix} \triangleq \begin{bmatrix} l_1 - l_1^{[0]} \\ l_2 - l_2^{[0]} \\ x_1 - x_1^{[0]} \\ x_2 - x_2^{[0]} \\ x_3 - x_3^{[0]} \end{bmatrix} \tag{II-4-1} Δ= Δ1Δ2Δ3Δ4Δ5 l1l1[0]l2l2[0]x1x1[0]x2x2[0]x3x3[0] (II-4-1)
这是本博文的主角.

线性化点 Θ [ 0 ] = [ l 1 [ 0 ] , l 2 [ 0 ] , x 1 [ 0 ] , x 2 [ 0 ] , x 3 [ 0 ] ] T \Theta^{[0]}=\begin{bmatrix} l_1^{[0]}, l_2^{[0]}, x_1^{[0]}, x_2^{[0]}, x_3^{[0]}\end{bmatrix}^{\small\rm T} Θ[0]=[l1[0],l2[0],x1[0],x2[0],x3[0]]T 是贝叶斯树根据之前信息获得的参数最优估计.

如果没有新的因子进入 (如获得新的测量值), 线性化点就认为是实际变量值 (最优估计). 当获得新的因子后, 需要重新计算系统变量的最优估计.

这个新的潜在的变量最优估计和原来的线性化点 (老的最优估计) 之间的差值 (偏差) 就是 Δ \Delta Δ, 称之为状态更新量.

状态更新量 Δ \Delta Δ 就这样走向了前台, 这里虽然需要消除的变量是 Θ \Theta Θ, 但计算操作都是基于 Δ \Delta Δ.

此时, 变量值 Θ \Theta Θ 已被拆分为线性化点 Θ [ 0 ] \Theta^{[0]} Θ[0] (常量) 和状态更新 Δ \Delta Δ (变量).

作为常量的 Θ [ 0 ] \Theta^{[0]} Θ[0] 隐藏在了公式中的代换变量中 (如各个 b i b_i bi).

随着对各个非线性因子的线性化, 相应地因子图也在 Θ [ 0 ] \Theta^{[0]} Θ[0] 处被线性化了.

线性化后的因子图称为高斯因子图.


IV. 部分 QR 分解实现变量消元 (Eliminating Variables Using Partial QR)

上一节完成了因子图的线性化, 得到了高斯因子图, 这一节就针对高斯因子图作消元. 高斯因子图消元与原始因子图消元在原理上是一样的, 但高斯因子图消元具有的优点是可以方便地利用线性代数知识 (如 QR 分解) 进行计算.

1. 首变量的消元

根据之前博文 “因子图、边缘化与消元算法的抽丝剥茧 —— Notes for ‘Factor Graphs for Robot Perception’” 对因子图变量消元算法原理的描述, 先收集变量 θ 1 \theta_1 θ1 关联的因子的乘积
ψ ( θ 1 , S 1 ) = exp ⁡ ( − 1 2 ∥ A 41 Δ 1 − b 4 ∥ 2 )    ⋅ exp ⁡ ( − 1 2 ∥ [ A 71 , A 73 ] [ Δ 1 Δ 3 ] − b 7 ∥ 2 )    ⋅ exp ⁡ ( − 1 2 ∥ [ A 81 , A 84 ] [ Δ 1 Δ 4 ] − b 8 ∥ 2 ) = e x p ( − 1 2 ∥ A 41 Δ 1 − b 4 ∥ 2        − 1 2 ∥ [ A 71 , A 73 ] [ Δ 1 Δ 3 ] − b 7 ∥ 2        − 1 2 ∥ [ A 81 , A 84 ] [ Δ 1 Δ 4 ] − b 8 ∥ 2 ) = exp ⁡ ( − 1 2 ∥ [ A 41 A 71 A 73 A 81 A 84 ] [ Δ 1 Δ 3 Δ 4 ] − [ b 4 b 7 b 8 ] ∥ 2 ) (III-1-1) \begin{aligned} \psi(\theta_1, S_1) &= \exp(-\frac{1}{2} \left\|A_{41} \Delta_1 - b_4 \right\|^2)\\ &\quad\; \cdot \exp(-\frac{1}{2} \left\Vert \begin{bmatrix}A_{71}, A_{73}\end{bmatrix} \begin{bmatrix}\Delta_1 \\ \Delta_3 \end{bmatrix} - b_7 \right \Vert^2)\\ &\quad\; \cdot \exp(-\frac{1}{2} \left\Vert \begin{bmatrix}A_{81}, A_{84}\end{bmatrix} \begin{bmatrix}\Delta_1 \\ \Delta_4 \end{bmatrix} - b_8 \right \Vert^2)\\ & = {\rm exp}\left(-\frac{1}{2} \left\|A_{41} \Delta_1 - b_4 \right\|^2 \right.\\ & \qquad \quad\;\;\; -\frac{1}{2} \left\Vert \begin{bmatrix}A_{71}, A_{73}\end{bmatrix} \begin{bmatrix}\Delta_1 \\ \Delta_3 \end{bmatrix} - b_7 \right \Vert^2 \\ & \qquad \quad\;\;\; \left. -\frac{1}{2} \left\Vert \begin{bmatrix}A_{81}, A_{84}\end{bmatrix} \begin{bmatrix}\Delta_1 \\ \Delta_4 \end{bmatrix} - b_8 \right \Vert^2 \right)\\ &=\exp(-\frac{1}{2}\left\Vert \left[\begin{array}{l:ll} A_{41} & & \\ A_{71} &A_{73} & \\ A_{81} && A_{84} \end{array}\right] \begin{bmatrix}\Delta_1 \\ \hdashline \Delta_3 \\ \Delta_4 \end{bmatrix} - \begin{bmatrix} b_4\\ b_7\\ b_8\end{bmatrix}\right\Vert^2) \end{aligned} \tag{III-1-1} ψ(θ1,S1)=exp(21A41Δ1b42)exp(21 [A71,A73][Δ1Δ3]b7 2)exp(21 [A81,A84][Δ1Δ4]b8 2)=exp(21A41Δ1b4221 [A71,A73][Δ1Δ3]b7 221 [A81,A84][Δ1Δ4]b8 2)=exp(21 A41A71A81A73A84 Δ1Δ3Δ4 b4b7b8 2)(III-1-1)
这里 θ 1 \theta_1 θ1 是待消元变量, S 1 = { θ 3 , θ 4 } S_1 = \{\theta_3, \theta_4\} S1={θ3,θ4} θ 1 \theta_1 θ1 的分离子集合. 为了消元 θ 1 \theta_1 θ1 和后面将涉及的反向替代计算状态更新 Δ 1 \Delta_1 Δ1, 需要对分块矩阵
A ˉ 1 ≜ [ A 41 A 71 A 73 A 81 A 84 ] \bar A_1 \triangleq \left[\begin{array}{l:ll} A_{41} & & \\ A_{71} &A_{73} & \\ A_{81} && A_{84} \end{array}\right] Aˉ1 A41A71A81A73A84
中的第一列作 QR 分解 (或 Gram-Schmidt 正交化)[1, 2], 连带着 [ b 4 b 7 b 8 ] \begin{bmatrix} b_4\\ b_7\\ b_8\end{bmatrix} b4b7b8 也执行相应的操作. 即
[ A 41 b 4 A 71 A 73 b 7 A 81 A 84 b 8 ] = Q 1 [ R 1 T 1 d 1 A ~ τ 1 b ~ τ 1 ] (III-1-2) \left[\begin{array}{l:ll|l} A_{41} & & & b_4 \\ A_{71} &A_{73} & & b_7 \\ A_{81} && A_{84} &b_8 \end{array}\right] = Q_1 \left[\begin{array}{l:l|l} R_1 & T_1 & d_1 \\ & {\tilde A}_{\tau 1} & {\tilde b}_{\tau 1} \end{array}\right] \tag{III-1-2} A41A71A81A73A84b4b7b8 =Q1[R1T1A~τ1d1b~τ1](III-1-2)
其中 Q 1 Q_1 Q1 是正交矩阵; R 1 R_1 R1 是上三角矩阵, 维度和 Δ 1 \Delta_1 Δ1 兼容. 记分离子偏差为 S ^ 1 ≜ [ Δ 3 Δ 4 ] {\hat S}_1 \triangleq \begin{bmatrix} \Delta_3\\ \Delta_4 \end{bmatrix} S^1[Δ3Δ4].

因为正交矩阵具有保范性, 所以正交阵 Q 1 Q_1 Q1 不会对范数运算产生影响.

这样, 变量 θ 1 \theta_1 θ1 关联的因子的乘积可以改写成
ψ ( θ 1 , S 1 ) = exp ⁡ ( − 1 2 ∥ R 1 Δ 1 + T 1 S ^ 1 − d 1 ∥ 2 ) ‾    exp ⁡ ( − 1 2 ∥ A ~ τ 1 S ^ 1 − b ~ τ 1 ∥ 2 ) ‾ ‾ = p ( Δ 1 ∣ S ^ 1 ) ‾    τ 1 ( S ^ 1 ) ‾ ‾ (III-1-3) \begin{aligned} \psi(\theta_1, S_1) & =\underline{ \exp(-\frac{1}{2}\left\Vert R_1 \Delta_1 + T_1 \hat{S}_1 -d_1 \right\Vert^2)} \;\underline{\underline{\exp(-\frac{1}{2}\left\Vert \tilde{A}_{\tau 1} \hat{S}_1 -\tilde{b}_{\tau 1}\right\Vert^2)}}\\ & = \underline{p(\Delta_1 | \hat{S}_1)}\; \underline{\underline{\tau_1(\hat{S}_1)}} \end{aligned} \tag{III-1-3} ψ(θ1,S1)=exp(21 R1Δ1+T1S^1d1 2)exp(21 A~τ1S^1b~τ1 2)=p(Δ1S^1)τ1(S^1)(III-1-3)
其中 p ( Δ 1 ∣ S ^ 1 ) p(\Delta_1 | \hat{S}_1) p(Δ1S^1) 称为条件概率密度 (Conditional Density), τ 1 ( S ^ 1 ) \tau_1(\hat{S}_1) τ1(S^1) 称为边缘化因子 (Marginal Factor).

因为不是对整个 A ˉ 1 \bar A_1 Aˉ1 矩阵进行 QR 分解, 而只针对变量 Δ 1 \Delta_1 Δ1 相关的第一列 (分块矩阵中的列) 进行, 故称为部分 QR 分解.


2. 中间变量的消元

推广变量 θ 1 \theta_1 θ1 的消元公式到一般变量 ( 1 ≤ i < 5 1 \le i < 5 1i<5, 除了消元顺序上的最后一个变量 θ 5 \theta_5 θ5) 上
ψ ( θ i , S i ) = exp ⁡ ( − 1 2 ∥ R i Δ i + T i S ^ i − d i ∥ 2 ) ‾    exp ⁡ ( − 1 2 ∥ A ~ τ i S ^ i − b ~ τ i ∥ 2 ) ‾ ‾ = p ( Δ i ∣ S ^ i ) ‾    p τ i ( S ^ i ) ‾ ‾ (III-2-1) \begin{aligned} \psi(\theta_i, S_i) & =\underline{ \exp(-\frac{1}{2}\left\Vert R_i \Delta_i + T_i \hat{S}_i -d_i \right\Vert^2)} \;\underline{\underline{\exp(-\frac{1}{2}\left\Vert \tilde{A}_{\tau i} \hat{S}_i -\tilde{b}_{\tau i}\right\Vert^2)}}\\ & = \underline{p(\Delta_i | \hat{S}_i)}\; \underline{\underline{p_{\tau i}(\hat{S}_i)}} \end{aligned} \tag{III-2-1} ψ(θi,Si)=exp(21 RiΔi+TiS^idi 2)exp(21 A~τiS^ib~τi 2)=p(ΔiS^i)pτi(S^i)(III-2-1)
中间变量的消元和第一个变量的消元相比没有特别之处.


3. 最末变量的消元

当消元只剩下最后一个变量 θ 5 \theta_5 θ5 时, 也需要对块矩阵 [ A ~ 25 A ~ 35 A ~ 45 ] \begin{bmatrix} \tilde{A}_{25}\\ \tilde{A}_{35} \\ \tilde{A}_{45} \end{bmatrix} A~25A~35A~45 做 QR 分解, 并连带对 [ b 25 b 35 b 45 ] \begin{bmatrix} b_{25}\\ b_{35} \\ b_{45} \end{bmatrix} b25b35b45 执行相同操作. 即
[ A ~ 25 b 25 A ~ 35 b 35 A ~ 45 b 45 ] = Q 5 [ R 5 d 5 0 b ~ 5 ] (III-2-2) \left[ \begin{array}{c|c} \tilde{A}_{25} & b_{25} \\ \tilde{A}_{35} & b_{35} \\ \tilde{A}_{45} & b_{45} \end{array} \right] = Q_5 \left[ \begin{array}{c|c} R_5 & d_5 \\ 0 & \tilde{b}_5\end{array} \right] \tag{III-2-2} A~25A~35A~45b25b35b45 =Q5[R50d5b~5](III-2-2)
需要说明, 因子数量 (测量数量) 必然大于变量数量, 所以涉及的线性化矩阵 (如 [ A 41 A 71 A 73 A 81 A 84 ] \left[\begin{array}{l:ll} A_{41} & & \\ A_{71} &A_{73} & \\ A_{81} && A_{84} \end{array}\right] A41A71A81A73A84 [ A ~ 25 A ~ 35 A ~ 45 ] \begin{bmatrix} \tilde{A}_{25}\\ \tilde{A}_{35} \\ \tilde{A}_{45} \end{bmatrix} A~25A~35A~45 ) 都是行数大于列数, 且都是列满秩的, 不然系统就没有确切解了.

由式 (III-2-2) 可知最后一变量的消元为
ψ ( θ 5 ) = exp ⁡ ( − 1 2 ∥ R 5 Δ 5 − d 5 ∥ 2 ) exp ⁡ ( − 1 2 ∥ b ~ 5 ∥ 2 ) ⏟ c o n s t ∝ exp ⁡ ( − 1 2 ∥ R 5 Δ 5 − d 5 ∥ 2 ) = p ( Δ 5 ) (III-2-3) \begin{aligned} \psi(\theta_5) &= {\exp(-\frac{1}{2} \Vert R_5 \Delta_5 - d_5 \Vert^2)} {\underbrace{\exp(-\frac{1}{2}\Vert \tilde{b}_5 \Vert^2)}_{\rm const}} \\ &\propto {\exp(-\frac{1}{2} \Vert R_5 \Delta_5 - d_5 \Vert^2)}\\ & = {p(\Delta_5)} \end{aligned}\tag{III-2-3} ψ(θ5)=exp(21R5Δ5d52)const exp(21b~52)exp(21R5Δ5d52)=p(Δ5)(III-2-3)
因为是最后消元的, 此处的分离子集合为空集. 因为整个算法求的是最大后验概率对应的变量值, 常数不会对结果产生影响.

完成消元后, 整个因子图转换为了贝叶斯网络 (Bayes Net).


V. 状态更新的反向替代 (Back Substitution for State Update)

所谓直接反向替代就是利用 QR 分解得到的上三角矩阵 R j R_j Rj 的可逆性, 以逆消元顺序, 先求出最后消元变量的最大后验估计 (MAP), 然后向前推进计算所有变量的优化值. 比如, 先计算最后消元的变量偏差
R 5 Δ 5 − d 5 = 0 ⇒ Δ 5 = R 5 − 1 d 5 R_5 \Delta_5 - d_5 = 0 \quad\Rightarrow \quad \Delta_5 = R_5^{-1}d_5 R5Δ5d5=0Δ5=R51d5
然后, 以最后消元变量偏差 Δ 5 \Delta_5 Δ5 作为前面消元变量偏差 Δ 4 \Delta_4 Δ4 的分离子偏差, 进行计算
R 4 Δ 4 + T 4 S ^ 4 − d 4 = 0 S ^ 4 = Δ 5 } ⇒ Δ 4 = R 4 − 1 ( d 4 − T 4 S ^ 4 ) \left.\begin{array}{r} R_4 \Delta_4 + T_4 \hat{S}_4 -d_4 = 0\\ \hat{S}_4 = \Delta_5 \end{array}\right\} \Rightarrow \Delta_4 = R_4^{-1} (d_4 -T_4 \hat{S}_4) R4Δ4+T4S^4d4=0S^4=Δ5}Δ4=R41(d4T4S^4)
如此以消元逆序从根节点向所有叶节点推进.

高斯分布下的最大后验估计在条件概率密度的均值处取得, 即直接反向替代中每一步都是在计算高斯条件概率均值.

所以有算法如下.

贝叶斯网络中的直接反向替代[2]

function S o l v e ( p ( Δ ) ) Solve(p(\Delta)) Solve(p(Δ))                         ⊳ \rhd 给定贝叶斯网络

        for j = n , … , 1 j=n,\ldots,1 j=n,,1 do                       ⊳ \rhd 消元顺序的逆

               Δ j ← R j − 1 ( d j − T j S ^ j ) \Delta_j \leftarrow R^{-1}_{j} (d_j - T_j \hat{S}_j) ΔjRj1(djTjS^j)                       ⊳ \rhd 给定分离子偏差 S ^ j \hat{S}_j S^j 求变量偏差 Δ j \Delta_j Δj

说明:

- “直接反向替代算法” 逆序遍历整个贝叶斯网络, 更新计算整个贝叶斯树中所有参数偏差.

- 这里所谓的"直接"就是直接解线性方程组, 而不是采用迭代逼近方法获得原非线性系统的解.

- “部分状态更新算法” 伪代码中并没有约束更新计算的方式 (如线性矩阵计算、非线性迭代等). 这是为了算法的一般性描述, 但因为经过了线性化处理, 最终只需直接求解线性方程组即可 (如 GTSAM 源码中).

- “部分状态更新算法” 区别于 “直接反向替代算法” 的是利用阈值来控制反向替代计算的传播. 如果当前节点的变量偏差小于阈值 (即 Δ k < α \Delta_{k} < \alpha Δk<α) 时, 根据线性方程的特点, 可以预测子节点的变量偏差也将比较小 (控制在线型比例范围内). 为了节约计算资源, 不再更新预测为较小变量偏差的节点. 这就实现了贝叶斯树中变量偏差的部分计算更新.

- “部分状态更新算法” 中提到了树团. 该树团只是贝叶斯树中节点的组织形式, 最终计算还是要落在一个个节点变量偏差上的. 也就是说, 贝叶斯树、贝叶斯网络、因子图等不同的描述从不方面刻画同一个 SLAM 优化问题, 虽然有不同的数据结构和洞察力, 但最终都要落在同一计算上.


VI. 总结

这样就大概明白的 iSAM2 算法中部分状态更新的原理.

要了解具体如何控制 “部分” 更新, 还需要在源码中找答案.


参考文献

[1] Kaess M, Johannsson H, Roberts R, Ila V, Leonard JJ, Dellaert F. iSAM2: Incremental smoothing and mapping using the Bayes tree. The International Journal of Robotics Research. 31(2):216-235. 2012

[2] Frank Dellaert, Michael Kaess, Factor Graphs for Robot Perception, Foundations and Trends in Robotics, Vol. 6, No. 1-2 (2017) 1–139

本文来自互联网用户投稿,该文观点仅代表作者本人,不代表本站立场。本站仅提供信息存储空间服务,不拥有所有权,不承担相关法律责任。如若转载,请注明出处:/a/476248.html

如若内容造成侵权/违法违规/事实不符,请联系我们进行投诉反馈qq邮箱809451989@qq.com,一经查实,立即删除!

相关文章

基于傅里叶描述子的手势动作识别,Matlab实现

博主简介&#xff1a; 专注、专一于Matlab图像处理学习、交流&#xff0c;matlab图像代码代做/项目合作可以联系&#xff08;QQ:3249726188&#xff09; 个人主页&#xff1a;Matlab_ImagePro-CSDN博客 原则&#xff1a;代码均由本人编写完成&#xff0c;非中介&#xff0c;提供…

什么是智慧公厕?智慧公厕打造公共厕所信息化应用基座

公共厕所一直以来都是城市管理的一项重要工作&#xff0c;而随着科技的发展&#xff0c;智慧公厕成为了城市管理的新方向。智慧公厕应用基座是利用物联网、互联网、大数据、云计算和自动化控制等技术&#xff0c;将公共厕所进行全方位的信息化、数字化和智慧化升级&#xff0c;…

训练YOLOv9-S

1. YOLOv9-S网络结构 1.1 改前改后的网络结构&#xff08;参数量、计算量&#xff09;对比 修改前调用的yolo.py测试的yolov9.yaml的打印网络情况&#xff0c;包含参数量、计算量 修改后调用的yolo.py测试的yolov9.yaml的打印网络情况&#xff0c;包含参数量、计算量 1.2 …

JAVA入门第一步

学习总结&#xff1a; 打开CMD常见的CMD命令 一、打开CMD CMD的概念 CMD是Windows操作系统中的命令提示符(Command Prompt)程序&#xff0c;它是一种命令行工具&#xff0c;可以让用户通过键入命令来与计算机进行交互。CMD是Windows中一个基本的系统组件&#xff0c;它提供了一…

Python学习:元组

Python 元组概念 Python 中的元组&#xff08;tuple&#xff09;是不可变的有序集合。它是一种数据类型&#xff0c;类似于列表&#xff08;list&#xff09;&#xff0c;但在创建后不能被修改。元组使用圆括号 () 来表示&#xff0c;其中的元素可以是任意类型&#xff0c;并且…

【C++ STL】string类最全解析(什么是string?string类的常用接口有哪些?)

目录 一、前言 二、什么是 string ? &#x1f4a6; string 类的基本概念 &#x1f4a6; string 类与 char * 的区别 &#x1f4a6; string 类的作用 &#x1f4a6; 总结 三、string 的常用接口详解 &#x1f4a6;string 类对象的默认成员函数 ① 构造函数(初始化) ② 赋值…

详解python中函数的参数传递

在这个用例中&#xff0c;我们要讨论的是关于函数的传参问题 我所使用的python版本为3.3.2 对于函数: def fun(arg):print(arg)def main():fun(hello,Hongten)if __name__ __main__:main() 当我们传递一个参数给fun()函数&#xff0c;即可打印出传递的参数值信息。 这里打印…

扫码签到效果如何制作?二维码签到表的制作技巧

一般参加活动或者会议时&#xff0c;都会需要在入口处签到登记之后才可进入&#xff0c;这种方式需要耗费大量的时间&#xff0c;而且带给参与者的体验也不好。面对这个问题&#xff0c;现在会通过签到二维码的方式来解决&#xff0c;只需要扫描二维码就可以在手机上登记信息&a…

c语言--字符转换函数(tolower、toupper.)

目录 一、前言二、使用举例 一、前言 C语⾔提供了2个字符转换函数&#xff1a; int tolower ( int c ); //将参数传进去的⼤写字⺟转⼩写 int toupper ( int c ); //将参数传进去的⼩写字⺟转⼤写二、使用举例 #include <ctype.h> #include<stdio.h> int main(…

go|sync系列:WaitGroup、Once、Cond

文章目录 sync.WaitGroup使用方式底层原理AddDoneWait总结 sync.Once存在的意义使用方式第一个例子&#xff0c;开启十个协程利用once运行同一个函数第二个例子&#xff0c;懒汉单例获取配置文件 底层原理存在的问题改进sync.Once解决问题 sync.Cond使用方式底层原理 参考文章 …

广西开放大学的电大搜题:为学子提供便捷高效的学习辅助

尊敬的读者朋友们&#xff0c;您了解过广西开放大学的电大搜题吗&#xff1f;作为一名现代学者&#xff0c;我有幸为您揭示这个令广大学子受益匪浅的学习利器。电大搜题是广西开放大学为学子们提供的一项便捷高效的学习辅助服务&#xff0c;旨在帮助学子们更好地应对学习难题&a…

一种震荡抑制电路

Hi uu们,好久没讲有意思的电路架构了,主要是做的要是有点价值都去申请专利了,刚好这个电路专利已经公开实质审查了,拉出来和大家分享下这是怎么一个玩法.图1展示了完整的电路图. 图1:积分器电路配合震荡抑制电路 其中框选部分为典型的积分器电路,右边这几个三极管构成了震荡抑…

GESP图形化编程二级认证真题 2024年3月

GESP 图形化二级试卷 &#xff08;满分&#xff1a;100 分 考试时间&#xff1a;120 分钟&#xff09; 一、单选题&#xff08;共 10 题&#xff0c;每题 3 分&#xff0c;共 30 分&#xff09; 1、小杨的父母最近刚刚给他买了一块华为手表&#xff0c;他说手表上跑的是鸿…

有趣的大模型之我见 | Mistral 7B 和 Mixtral 8x7B

开发者告诉我们&#xff0c;有一些因素阻碍了他们更好更广泛地使用基础模型。比如&#xff0c;在可预见的将来&#xff0c;随着技术的新进步&#xff0c;不断有新的模型加入&#xff0c;同时模型的升级和迭代也在不断加速。那么&#xff0c;对于特定的用例&#xff0c;如何选择…

24计算机考研调剂 | (研究所)北京微电子技术研究所

北京微电子技术研究所2024年考研调剂信息 调剂信息 一、招生专业 二、调剂对象 统考科目为思想政治理论、英语&#xff08;一&#xff09;、数学&#xff08;一&#xff09;&#xff1b;本科为电子科学与技术、微电子学、集成电路设计、电子信息工程、通信工程、计算机科学与…

代码随想录算法训练营 DAY 16 | 104.二叉树最大深度 111.二叉树最小深度 222.完全二叉树的节点个数

104.二叉树最大深度 深度和高度 二叉树节点的深度&#xff1a;指从根节点到该节点的最长简单路径边的条数或者节点数&#xff08;取决于深度从0开始还是从1开始&#xff09;二叉树节点的高度&#xff1a;指从该节点到叶子节点的最长简单路径边的条数或者节点数&#xff08;取…

8节点空间壳单元Matlab有限元编程 | 曲壳单元 | 模态分析 | 3D壳单元 | 板壳理论| 【源代码+理论文本】

专栏导读 作者简介&#xff1a;工学博士&#xff0c;高级工程师&#xff0c;专注于工业软件算法研究本文已收录于专栏&#xff1a;《有限元编程从入门到精通》本专栏旨在提供 1.以案例的形式讲解各类有限元问题的程序实现&#xff0c;并提供所有案例完整源码&#xff1b;2.单元…

linux 升级openssl1.1.1w 亲测记录

下载好openssl源码包,解压到指定目录下 tar -xzvf openssl-1.1.1w.tar.gz -C /usr/localcd openssl-1.1.1w/*预编译、编译、安装*/./config --prefix/usr/local/openssl sharedmake && make install备份配置系统中原有的文件、创建软链接、动态库查找路径配置文件 ld.s…

day-25 无重复字符的最长子串

思路&#xff1a;动态规划的思想&#xff0c;遍历字符串&#xff0c;每遇到一个新的字符&#xff0c;将其存入HashMap中&#xff0c;并给其一个唯一值value(value递增)&#xff0c;当前字符若与HashMap中的字符都不一样&#xff0c;则存入HashMap中&#xff0c;若已经存在&…

剑指offer经典题目整理(七)

一、经典dp——最大子数组之和 1.链接 53. 最大子数组和 - 力扣&#xff08;LeetCode&#xff09; 2.描述 给你一个整数数组 nums &#xff0c;请你找出一个具有最大和的连续子数组&#xff08;子数组最少包含一个元素&#xff09;&#xff0c;返回其最大和。 3.思路 这是…