点到面(Point-to-Plane)ICP 点云配准中,信息矩阵(Information Matrix) 是稀疏非线性优化中的重要组成部分,常用于:
- SLAM 后端中误差建模;
- 估计配准参数的可靠性;
- 构建优化问题的 Hessian 近似;
- 作为联合优化中各残差项的权重;
下面将从点到面 ICP 的基本残差定义出发,完整推导信息矩阵 的数学公式和含义,并说明其几何意义与代码实现方式。
一、预备知识
1. 点到面残差定义
对于源点 p _ s \mathbf{p}\_s p_s 和目标点 p _ t \mathbf{p}\_t p_t 及其单位法向量 n _ t \mathbf{n}\_t n_t,点到面的残差定义为:
r = n t ⊤ ( R p s + t − p t ) r = \mathbf{n}_t^\top \left( R \mathbf{p}_s + \mathbf{t} - \mathbf{p}_t \right) r=nt⊤(Rps+t−pt)
其中:
- R ∈ S O ( 3 ) R \in SO(3) R∈SO(3) 为旋转矩阵
- t ∈ R 3 \mathbf{t} \in \mathbb{R}^3 t∈R3 为平移向量
设最终优化变量为 T = [ R ∣ t ] ∈ S E ( 3 ) T = [R|\mathbf{t}] \in SE(3) T=[R∣t]∈SE(3)。
2. 最小化目标函数
我们希望通过非线性最小二乘最小化以下代价函数:
E ( T ) = ∑ i = 1 N [ r i ( T ) ] 2 E(T) = \sum_{i=1}^N \left[ r_i(T) \right]^2 E(T)=i=1∑N[ri(T)]2
目标是对变换 T T T 进行迭代优化。
二、雅可比与高斯牛顿方法回顾
1. 李代数扰动建模
设当前估计位姿为 T = [ R ∣ t ] T = [R | \mathbf{t}] T=[R∣t],我们在 S E ( 3 ) SE(3) SE(3) 上做一次微小扰动 δ ξ ∈ R 6 \delta \boldsymbol{\xi} \in \mathbb{R}^6 δξ∈R6,其左乘作用为:
T ′ = exp ( δ ξ ∧ ) T T' = \exp(\delta \boldsymbol{\xi}^\wedge) T T′=exp(δξ∧)T
其中:
δ ξ = [ δ ϕ δ t ] ∈ R 6 , δ ϕ ∈ R 3 是旋转扰动 \delta \boldsymbol{\xi} = \begin{bmatrix} \delta \boldsymbol{\phi} \\ \delta \mathbf{t} \end{bmatrix} \in \mathbb{R}^6,\quad \delta \boldsymbol{\phi} \in \mathbb{R}^3 \text{ 是旋转扰动} δξ=[δϕδt]∈R6,δϕ∈R3 是旋转扰动
2. 一阶近似残差函数
令残差 r ( ξ ) r(\boldsymbol{\xi}) r(ξ) 关于 δ ξ \delta \boldsymbol{\xi} δξ 在当前估计处做泰勒展开:
r ( δ ξ ) ≈ r ( 0 ) + J ⋅ δ ξ r(\delta \boldsymbol{\xi}) \approx r(0) + \mathbf{J} \cdot \delta \boldsymbol{\xi} r(δξ)≈r(0)+J⋅δξ
其中 J = ∂ r ∂ ξ ∈ R 1 × 6 \mathbf{J} = \frac{\partial r}{\partial \boldsymbol{\xi}} \in \mathbb{R}^{1 \times 6} J=∂ξ∂r∈R1×6 是残差关于位姿扰动的 雅可比矩阵。
三、点到面残差的雅可比推导
考虑源点 p _ s \mathbf{p}\_s p_s 变换后的位置为:
p s ′ = R p s + t \mathbf{p}'_s = R \mathbf{p}_s + \mathbf{t} ps′=Rps+t
目标为最小化:
r = n t ⊤ ( p s ′ − p t ) r = \mathbf{n}_t^\top (\mathbf{p}'_s - \mathbf{p}_t) r=nt⊤(ps′−pt)
对李代数扰动 δ ξ \delta \boldsymbol{\xi} δξ 展开后:
p s ′ ( δ ξ ) ≈ ( I + [ δ ϕ ] × ) R p s + t + δ t \mathbf{p}'_s(\delta \boldsymbol{\xi}) \approx (I + [\delta \boldsymbol{\phi}]_\times) R \mathbf{p}_s + \mathbf{t} + \delta \mathbf{t} ps′(δξ)≈(I+[δϕ]×)Rps+t+δt
r ≈ n t ⊤ ( ( I + [ δ ϕ ] × ) R p s + t + δ t − p t ) r \approx \mathbf{n}_t^\top \left( (I + [\delta \boldsymbol{\phi}]_\times) R \mathbf{p}_s + \mathbf{t} + \delta \mathbf{t} - \mathbf{p}_t \right) r≈nt⊤((I+[δϕ]×)Rps+t+δt−pt)
忽略高阶项,取导:
∂ r ∂ δ ϕ = n t ⊤ [ R p s ] × = − n t ⊤ [ R p s ] × \frac{\partial r}{\partial \delta \boldsymbol{\phi}} = \mathbf{n}_t^\top [R \mathbf{p}_s]_\times = -\mathbf{n}_t^\top [R \mathbf{p}_s]_\times ∂δϕ∂r=nt⊤[Rps]×=−nt⊤[Rps]×
∂ r ∂ δ t = n t ⊤ \frac{\partial r}{\partial \delta \mathbf{t}} = \mathbf{n}_t^\top ∂δt∂r=nt⊤
因此残差对 S E ( 3 ) SE(3) SE(3) 的雅可比为:
J i = [ n t ⊤ [ R p s ] × n t ⊤ ] ∈ R 1 × 6 \mathbf{J}_i = \begin{bmatrix} \mathbf{n}_t^\top [R \mathbf{p}_s]_\times & \mathbf{n}_t^\top \end{bmatrix} \in \mathbb{R}^{1 \times 6} Ji=[nt⊤[Rps]×nt⊤]∈R1×6
设 q _ s = R p _ s \mathbf{q}\_s = R \mathbf{p}\_s q_s=Rp_s 是当前配准下的源点,则可记为:
J i = [ n t ⊤ ⋅ [ 0 − z y z 0 − x − y x 0 ] n t ⊤ ] \mathbf{J}_i = \begin{bmatrix} \mathbf{n}_t^\top \cdot \begin{bmatrix} 0 & -z & y \\ z & 0 & -x \\ -y & x & 0 \end{bmatrix} & \mathbf{n}_t^\top \end{bmatrix} Ji= nt⊤⋅ 0z−y−z0xy−x0 nt⊤
四、信息矩阵推导
1. 定义
高斯牛顿算法中,我们需要构建 Hessian 近似矩阵(即信息矩阵):
H = ∑ i = 1 N J i ⊤ J i ∈ R 6 × 6 \mathbf{H} = \sum_{i=1}^N \mathbf{J}_i^\top \mathbf{J}_i \in \mathbb{R}^{6 \times 6} H=i=1∑NJi⊤Ji∈R6×6
这是每个点对的残差雅可比外积之和,用于构建线性系统:
H δ ξ = − ∑ i J i ⊤ r i \mathbf{H} \delta \boldsymbol{\xi} = - \sum_i \mathbf{J}_i^\top r_i Hδξ=−i∑Ji⊤ri
信息矩阵 H \mathbf{H} H 本质上是最小二乘优化中的 正定近似 Hessian,反映了配准结果在各个自由度方向上的 刚性程度。
2. 信息矩阵构造公式
设每个点对的 Jacobian 为 J _ i ∈ R 1 × 6 J\_i \in \mathbb{R}^{1 \times 6} J_i∈R1×6,则:
H = ∑ i = 1 N J i ⊤ J i \mathbf{H} = \sum_{i=1}^N J_i^\top J_i H=i=1∑NJi⊤Ji
每一项贡献为:
J i ⊤ J i = [ 6x1 ] ⋅ [ 1x6 ] 6x6 对称矩阵 J_i^\top J_i = \begin{bmatrix} \text{6x1} \end{bmatrix} \cdot \begin{bmatrix} \text{1x6} \end{bmatrix} \text{6x6 对称矩阵} Ji⊤Ji=[6x1]⋅[1x6]6x6 对称矩阵
五、计算流程小结
给定:
- 源点云 p _ s i {\mathbf{p}\_s^i} p_si
- 目标点云 p _ t i {\mathbf{p}\_t^i} p_ti
- 目标法向量 n _ t i {\mathbf{n}\_t^i} n_ti(单位向量)
- 当前估计位姿 T = ( R , t ) T = (R, \mathbf{t}) T=(R,t)
计算流程:
-
对每个点对 i i i:
- 变换源点: q _ s i = R p _ s i \mathbf{q}\_s^i = R \mathbf{p}\_s^i q_si=Rp_si
- 计算残差: r _ i = n _ t i ⊤ ( q _ s i + t − p _ t i ) r\_i = \mathbf{n}\_t^{i\top} (\mathbf{q}\_s^i + \mathbf{t} - \mathbf{p}\_t^i) r_i=n_ti⊤(q_si+t−p_ti)
- 构造雅可比 J _ i ∈ R 1 × 6 \mathbf{J}\_i \in \mathbb{R}^{1 \times 6} J_i∈R1×6
-
信息矩阵累加:
H = ∑ i J i ⊤ J i \mathbf{H} = \sum_i \mathbf{J}_i^\top \mathbf{J}_i H=i∑Ji⊤Ji
六、C++代码实现计算信息矩阵H
Eigen::Matrix<double, 6, 6> H = Eigen::Matrix<double, 6, 6>::Zero();
for (int i = 0; i < N; ++i) {
Eigen::Vector3d ps = source_points[i];
Eigen::Vector3d pt = target_points[i];
Eigen::Vector3d nt = target_normals[i];
Eigen::Vector3d qs = R * ps;
Eigen::Vector3d diff = qs + t - pt;
double r = nt.dot(diff);
Eigen::Matrix<double, 1, 6> J;
J.block<1,3>(0,0) = (qs.cross(nt)).transpose(); // rotation part
J.block<1,3>(0,3) = nt.transpose(); // translation part
H += J.transpose() * J;
}
七、几何意义
信息矩阵 H \mathbf{H} H 的本质:
- 是关于配准误差的二阶导数近似;
- 反映当前配准结果的局部几何稳定性;
- 条件数大 ⇒ 某方向上约束弱(例如纯平面场景,Z轴不稳定);
- 可用于评估某一帧的贡献程度(比如 SLAM 中是否关键帧);
八 、雅可比矩阵详细推导与展开
雅可比 J i J_i Ji的形式如下:
J i = [ n t ⊤ [ R p s ] × n t ⊤ ] ∈ R 1 × 6 \mathbf{J}_i = \begin{bmatrix} \mathbf{n}_t^\top [R \mathbf{p}_s]_\times & \mathbf{n}_t^\top \end{bmatrix} \in \mathbb{R}^{1 \times 6} Ji=[nt⊤[Rps]×nt⊤]∈R1×6
记号说明:
- p _ s ∈ R 3 \mathbf{p}\_s \in \mathbb{R}^3 p_s∈R3:源点
- p _ t ∈ R 3 \mathbf{p}\_t \in \mathbb{R}^3 p_t∈R3:目标点
- n _ t ∈ R 3 \mathbf{n}\_t \in \mathbb{R}^3 n_t∈R3:目标点的单位法向量
- R ∈ S O ( 3 ) R \in SO(3) R∈SO(3):当前位姿估计中的旋转矩阵
- [ ⋅ ] _ × [ \cdot ]\_\times [⋅]_×:反对称矩阵,定义如下
[ v ] × = [ 0 − v z v y v z 0 − v x − v y v x 0 ] [\mathbf{v}]_\times = \begin{bmatrix} 0 & -v_z & v_y \\ v_z & 0 & -v_x \\ -v_y & v_x & 0 \end{bmatrix} [v]×= 0vz−vy−vz0vxvy−vx0
8.1、向量表示展开
设:
q s = R p s = [ x y z ] , n t = [ n x n y n z ] \mathbf{q}_s = R \mathbf{p}_s = \begin{bmatrix} x \\ y \\ z \end{bmatrix},\quad \mathbf{n}_t = \begin{bmatrix} n_x \\ n_y \\ n_z \end{bmatrix} qs=Rps= xyz ,nt= nxnynz
则:
[ q s ] × = [ 0 − z y z 0 − x − y x 0 ] [\mathbf{q}_s]_\times = \begin{bmatrix} 0 & -z & y \\ z & 0 & -x \\ -y & x & 0 \end{bmatrix} [qs]×= 0z−y−z0xy−x0
然后:
n t ⊤ [ q s ] × [ n x n y n z ] [ 0 − z y z 0 − x − y x 0 ] = [ n y z − n z y , n z x − n x z , n x y − n y x ] \mathbf{n}_t^\top [\mathbf{q}_s]_\times \begin{bmatrix} n_x & n_y & n_z \end{bmatrix} \begin{bmatrix} 0 & -z & y \\ z & 0 & -x \\ -y & x & 0 \end{bmatrix} = \begin{bmatrix} n_y z - n_z y,\, n_z x - n_x z,\, n_x y - n_y x \end{bmatrix} nt⊤[qs]×[nxnynz] 0z−y−z0xy−x0 =[nyz−nzy,nzx−nxz,nxy−nyx]
即旋转部分雅可比为:
∂ r ∂ ϕ = n t ⊤ [ R p s ] × ∈ R 1 × 3 \frac{\partial r}{\partial \boldsymbol{\phi}} = \mathbf{n}_t^\top [R \mathbf{p}_s]_\times \in \mathbb{R}^{1 \times 3} ∂ϕ∂r=nt⊤[Rps]×∈R1×3
平移部分是直接的:
∂ r ∂ t = n t ⊤ ∈ R 1 × 3 \frac{\partial r}{\partial \mathbf{t}} = \mathbf{n}_t^\top \in \mathbb{R}^{1 \times 3} ∂t∂r=nt⊤∈R1×3
所以整个雅可比展开为:
J i = [ n y z − n z y n z x − n x z n x y − n y x n x n y n z ] \mathbf{J}_i = \begin{bmatrix} n_y z - n_z y & n_z x - n_x z & n_x y - n_y x & n_x & n_y & n_z \end{bmatrix} Ji=[nyz−nzynzx−nxznxy−nyxnxnynz]
8.2、几何解释:为什么是叉乘?
考虑 S E ( 3 ) SE(3) SE(3) 李代数扰动中,旋转引起的误差是:
δ p = [ δ ϕ ] × R p s = − ( R p s ) × δ ϕ \delta \mathbf{p} = [\delta \boldsymbol{\phi}]_\times R \mathbf{p}_s = - (R \mathbf{p}_s) \times \delta \boldsymbol{\phi} δp=[δϕ]×Rps=−(Rps)×δϕ
因此:
∂ r ∂ δ ϕ = ∂ ∂ δ ϕ ( n t ⊤ ( − R p s × δ ϕ ) ) = − n t ⊤ [ R p s ] × \frac{\partial r}{\partial \delta \boldsymbol{\phi}} = \frac{\partial}{\partial \delta \boldsymbol{\phi}} \left( \mathbf{n}_t^\top ( - R \mathbf{p}_s \times \delta \boldsymbol{\phi}) \right) = -\mathbf{n}_t^\top [R \mathbf{p}_s]_\times ∂δϕ∂r=∂δϕ∂(nt⊤(−Rps×δϕ))=−nt⊤[Rps]×
所以这表示:当绕旋转轴扰动时,点 R p _ s R \mathbf{p}\_s Rp_s 产生一个垂直于旋转轴的位移方向,该方向对法向量投影就是误差变化率。
8.3、信息矩阵中各项的含义
当构建信息矩阵:
H = ∑ i J i ⊤ J i ∈ R 6 × 6 \mathbf{H} = \sum_i \mathbf{J}_i^\top \mathbf{J}_i \in \mathbb{R}^{6 \times 6} H=i∑Ji⊤Ji∈R6×6
它的结构如下:
块名 | 尺寸 | 含义 |
---|---|---|
H _ rot-rot \mathbf{H}\_{\text{rot-rot}} H_rot-rot | 3 × 3 3\times3 3×3 | 来自旋转扰动部分的影响 |
H _ rot-trans \mathbf{H}\_{\text{rot-trans}} H_rot-trans | 3 × 3 3\times3 3×3 | 旋转-平移耦合项 |
H _ trans-trans \mathbf{H}\_{\text{trans-trans}} H_trans-trans | 3 × 3 3\times3 3×3 | 平移扰动对误差的影响 |
每一项由雅可比矩阵的乘积贡献:
J i ⊤ J i = [ J rot ⊤ J rot J rot ⊤ J trans J trans ⊤ J rot J trans ⊤ J trans ] \mathbf{J}_i^\top \mathbf{J}_i = \begin{bmatrix} \mathbf{J}_{\text{rot}}^\top \mathbf{J}_{\text{rot}} & \mathbf{J}_{\text{rot}}^\top \mathbf{J}_{\text{trans}} \\ \mathbf{J}_{\text{trans}}^\top \mathbf{J}_{\text{rot}} & \mathbf{J}_{\text{trans}}^\top \mathbf{J}_{\text{trans}} \end{bmatrix} Ji⊤Ji=[Jrot⊤JrotJtrans⊤JrotJrot⊤JtransJtrans⊤Jtrans]
其中:
J rot = − n t ⊤ [ R p s ] × ∈ R 1 × 3 \mathbf{J}_{\text{rot}} = -\mathbf{n}_t^\top [\mathbf{R} \mathbf{p}_s]_\times\in \mathbb{R}^{1 \times 3} Jrot=−nt⊤[Rps]×∈R1×3
J _ trans = n _ t ⊤ \mathbf{J}\_{\text{trans}} = \mathbf{n}\_t^\top J_trans=n_t⊤
8.4、典型应用场景
- 在 SLAM 后端中,用 H \mathbf{H} H 的对角元素判断某帧或某约束的信息量;
- 在多帧优化中,使用 H \mathbf{H} H 构造误差项协方差近似 C ≈ H − 1 C \approx H^{-1} C≈H−1;
- 对于退化检测,查看 H \mathbf{H} H 的特征值分布是否存在很小的方向(如 Z 向不确定);