問題設定
Visual Odometry は,カメラから連続的に得られる輝度情報を用いて,カメラの姿勢変化を逐次的に推定する問題である.カメラの姿勢変化を \(\mathbf{\xi} \in \mathbb{R}^{6} \; \textrm{s.t.} \;\skew{\mathbf{\xi}} \in \se(3)\) ,時刻 \(t\) における画像を \(I_{t}\) , \(I_{t}\) の座標 \(\mathbf{x}_{i},(i=1,\dots,N)\) における輝度を \(I_{t}(\mathbf{x}_{i})\) で表現する.ここで \(\skew{\cdot}\) は次で定義される演算子である.
\[\begin{split}\skew{\mathbf{\xi}} &= \begin{bmatrix}
0 & -\xi_{6} & \xi_{5} & \xi_{1} \\
\xi_{6} & 0 & -\xi_{4} & \xi_{2} \\
-\xi_{5} & \xi_{4} & 0 & \xi_{3} \\
0 & 0 & 0 & 0 \\
\end{bmatrix} \in \se(3),\;\mathbf{\xi} \in \mathbb{R}^{6}\end{split}\]
\(I_{t_{0}}(\mathbf{x}_{i})\) が各ピクセル \(\mathbf{x}_{i}\) についてi.i.dだと仮定すると,2視点間の姿勢変化 \(\pose\) を画像変化から求める問題は,尤度
\[L(\xi) = p(I_{t_{0}}|\pose) = \prod_{i} p(I_{t_{0}}(\mathbf{x}_{i})|\pose)\]
を最大化する問題とみなすことができる.
問題をより詳細に記述するため,warping関数を定義する.\(\mathbf{w}_{\pose}(\mathbf{x}, t)\) を,ピクセル \(\mathbf{x}\) を時刻 \(t_{0}\) における画像平面から時刻 \(t\) における画像平面に写す関数
\[\begin{split}\mathbf{w}_{\pose}(\mathbf{x}, t)
= \mathbf{\pi}(g(G(t), \mathbf{\pi}^{-1}(\mathbf{x}))) \\\end{split}\]
とする. \(G(t)\in \SE(3)\) は時刻 \(t\) におけるカメラ姿勢を表すユークリッド群の元 \(G(t) = \exp((t-t_{0})\skew{\pose})G(t_{0})\) であり, \(g(G, \mathbf{p})\) は3次元点 \(\mathbf{p} \in \mathbb{R}^{3}\) の変換 \(g(G, \mathbf{p}) = R\mathbf{p} + \mathbf{t}\) を表す関数である.また, \(\mathbf{\pi}^{-1}(\mathbf{x})\) は投影モデルの逆写像を表す.
Steinbrückerらの手法 では \(p(I_{t_{0}}(\mathbf{x}_{i})|\pose)\) を \(N(I_{t_{1}}(\mathbf{w}_{\pose}(\mathbf{x}_{i}, t_{1})), \sigma^{2})\) でモデル化し,最尤推定によって姿勢変化 \(\pose\) を求める.結果として姿勢 \(\pose\) をパラメータとした二乗誤差関数が得られる.すなわち,
\[p(I_{t_{0}}(\mathbf{x}_i)|\pose)
= \frac{1}{\sqrt{2\pi}\sigma}\exp(
-\frac{
[I_{t_{0}}(\mathbf{x}_{i})-I_{t_{1}}(\mathbf{w}_{\pose}(\mathbf{x}_{i}, t_{1}))]^2
}{\sigma^2}
)\]
とおいて,推定値 \(\hat{\pose}\) を求める.
\[\begin{split}\begin{align}
\hat{\pose}
&= \underset{\pose}{\arg \max} \log p(I_{t_{0}}|\pose) \\
&= \underset{\pose}{\arg \max} \log \prod_{i} p(I_{t_{0}}(\mathbf{x}_i)|\pose) \\
&= \underset{\pose}{\arg \max} \sum_{i} \log p(I_{t_{0}}(\mathbf{x}_i)|\pose)
\end{align}\end{split}\]
確率密度関数を代入すると,
\[\begin{split}\begin{align}
\hat{\pose}
&= \underset{\pose}{\arg \max} \sum_{i} \log p(I_{t_{0}}(\mathbf{x}_i)|\pose) \\
&= \underset{\pose}{\arg \max} \sum_{i} \log [\frac{1}{\sqrt{2\pi}\sigma}
\exp(-\frac{[I_{t_{0}}(\mathbf{x}_{i})-I_{t_{1}}(\mathbf{w}_{\pose}(\mathbf{x}_{i}, t_{1}))]^2}{\sigma^2})
]
\end{align}\end{split}\]
定数項を省くと
\[\hat{\pose} = \underset{\pose}{\arg \min}\; \sum_{i}[I_{t_{0}}(\mathbf{x}_{i})-I_{t_{1}}(\mathbf{w}_{\pose}(\mathbf{x}_{i}, t_{1}))]^2\]
となり,二乗誤差関数
(1)\[E(\pose)
= \sum_{i}[I_{t_{1}}(\mathbf{w}_{\pose}(\mathbf{x}_{i}, t_{1})) - I_{t_{0}}(\mathbf{x}_{i})]^2\]
が得られる.
解法
Steinbrückerらの手法 では誤差関数を一次近似し,
(1) を最小二乗法に落としこむ.
まず画像を空間方向に一次近似する.
\[I_{t_{1}}(\mathbf{x}_{i} + \Delta\mathbf{x})
\approx I_{t_{1}}(\mathbf{x}_{i}) +
\frac{\partial I_{t_{1}}(\mathbf{x}_{i})}{\partial \mathbf{x}}
\Delta \mathbf{x}\]
\(\mathbf{x}_{i} + \Delta\mathbf{x} = \mathbf{w}_{\pose}(\mathbf{x}_{i}, t_{1})\) とおくと次のようになる.
(2)\[I_{t_{1}}(\mathbf{w}_{\pose}(\mathbf{x}_{i}, t_{1}))
\approx I_{t_{1}}(\mathbf{x}_{i}) +
\frac{\partial I_{t_{1}}(\mathbf{x}_{i})}{\partial \mathbf{x}}
(\mathbf{w}_{\pose}(\mathbf{x}_{i}, t_{1})-\mathbf{x}_{i})\]
warping関数を近似する.
\[\begin{split}\begin{align}
\mathbf{w}_{\pose}(\mathbf{x}_{i}, t_{1})
&\approx \mathbf{w}_{\pose}(\mathbf{x}_{i}, t_{0}) +
\frac{\partial \mathbf{w}_{\pose}(\mathbf{x}_{i}, t_{0})}{\partial t}(t_{1} - t_{0}) \\
&= \mathbf{x}_{i} +
\frac{\partial \mathbf{w}_{\pose}(\mathbf{x}_{i}, t_{0})}{\partial t} (t_{1} - t_{0})
\end{align}\end{split}\]
これを (2) に代入すると
\[I_{t_{1}}(\mathbf{w}_{\pose}(\mathbf{x}_{i}, t_{1}))
\approx I_{t_{1}}(\mathbf{x}_{i}) +
\frac{\partial I_{t_{1}}(\mathbf{x}_{i})}{\partial \mathbf{x}}
\frac{\partial \mathbf{w}_{\pose}(\mathbf{x}_{i}, t_{0})}{\partial t} (t_{1} - t_{0})\]
\(t_{1} - t_{0}\) はフレームの撮影間隔(フレームレートの逆数)である.今回は \(t_{1} - t_{0} = 1\) とおく.すなわち,フレームの撮影間隔を1単位時間とみなす.
\[I_{t_{1}}(\mathbf{w}_{\pose}(\mathbf{x}_{i}, t_{1}))
\approx I_{t_{1}}(\mathbf{x}_{i}) +
\frac{\partial I_{t_{1}}(\mathbf{x}_{i})}{\partial \mathbf{x}}
\frac{\partial \mathbf{w}_{\pose}(\mathbf{x}_{i}, t_{0})}{\partial t}\]
この結果を用いて誤差関数を書き換えると次のようになる.
(3)\[\begin{split}\begin{align}
E(\pose)
&= \sum_{i}[I_{t_{1}}(\mathbf{w}_{\pose}(\mathbf{x}_{i}, t_{1})) - I_{t_{0}}(\mathbf{x}_{i})]^2 \\
&\approx \sum_{i}[
I_{t_{1}}(\mathbf{x}_{i})-I_{t_{0}}(\mathbf{x}_{i}) +
\frac{\partial I_{t_{1}}(\mathbf{x}_{i})}{\partial \mathbf{x}}
\frac{\partial \mathbf{w}_{\pose}(\mathbf{x}_{i}, t_{0})}{\partial t}
]^2
\end{align}\end{split}\]
さて, \(I_{t_{1}}(\mathbf{x}_{i})-I_{t_{0}}(\mathbf{x}_{i})\) は画像間の差分を意味しており, \(\frac{\partial I_{t_{1}}(\mathbf{x}_{i})}{\partial \mathbf{x}}\) は一次の勾配を表しているため,これらは容易に実装することができる.しかし \(\frac{\partial \mathbf{w}_{\pose}(\mathbf{x}_{i}, t_{0})}{\partial t}\) はその中身が具体的なかたちで書かれていないため,さらに詳しく表現する必要がある.
warping関数の微分は,chain ruleより
\[\begin{align}
\frac{
\partial \mathbf{w}_{\pose}(\mathbf{x}_{i}, t_{0})
}{\partial t}
&= \frac{\partial \mathbf{\pi}(g(G(t_{0}), \mathbf{p}_{i}))}{\partial g}
\cdot \frac{\partial g(G(t_{0}), \mathbf{p}_{i})}{\partial G}
\cdot \frac{\partial G(t_{0})}{\partial t}
\end{align}\]
である.\(\frac{\partial G(t)}{\partial t} = \skew{\mathbf{\xi}}G(t)\) (参考: リー代数による回転表現) を用いると,
\[\begin{align}
\frac{
\partial \mathbf{w}_{\pose}(\mathbf{x}_{i}, t_{0})
}{\partial \pose}
&= \frac{\partial \mathbf{\pi}(g(G(t_{0}), \mathbf{p}_{i}))}{\partial g}
\cdot \frac{\partial g(G(t_{0}), \mathbf{p}_{i})}{\partial G}
\cdot \skew{\pose} \cdot G(t_{0})
\end{align}\]
\(\frac{\partial g(G(t_{0}), \mathbf{p}_{i})}{\partial G}\) は行列 \(G\) による微分であり,コードで実装すると3次元配列になってしまう.
これを回避するため,以下で定義される \(\mathrm{stack}(G)\) を導入する.
\(G \in \SE(3)\) を
\[\begin{split}G = \begin{bmatrix}
r_{11} & r_{12} & r_{13} & t_{1} \\
r_{21} & r_{22} & r_{23} & t_{2} \\
r_{33} & r_{32} & r_{33} & t_{3} \\
0 & 0 & 0 & 1 \\
\end{bmatrix}\end{split}\]
と表現したとき
\(\mathrm{stack}(G) = \begin{bmatrix} r_{11} & r_{21} & r_{33} & r_{12} & r_{22} & r_{32} & r_{13} & r_{23} & r_{33} & t_{1} & t_{2} & t_{3} \end{bmatrix}^{\top}\)
ここで, \(\mathrm{stack}(\skew{\pose_{k}} \cdot G(t_{0})) = J_{G} \cdot \pose\) を満たすような \(J_{G}\) が存在する(具体的な導出は後で示す).これを用いると,
\[\begin{align}
\frac{\partial \mathbf{w}_{\pose}(\mathbf{x}_{i}, t_{0})}{\partial \pose}
&= \frac{\partial \mathbf{\pi}(g(G(t_{0}), \mathbf{p}_{i}))}{\partial g}
\cdot \frac{\partial g(G(t_{0}), \mathbf{p}_{i})}{\partial \mathrm{stack}(G)}
\cdot J_{G} \cdot \pose
\end{align}\]
もとの誤差関数 (3) に代入すると
\[\begin{split}\begin{align}
E(\pose)
&= \sum_{i}\left[
I_{t_{1}}(\mathbf{w}_{\pose}(\mathbf{x}_{i}, t_{1}))-I_{t_{0}}(\mathbf{x}_{i})
\right]^2 \\
&\approx \sum_{i}\left[
I_{t_{1}}(\mathbf{x}_{i}) -
I_{t_{0}}(\mathbf{x}_{i}) +
\frac{\partial I_{t_{1}}(\mathbf{x}_{i})}{\partial \mathbf{x}}
\frac{\partial \mathbf{\pi}(g(G(t_{0}), \mathbf{p}_{i}))}{\partial g}
\cdot \frac{\partial g(G(t_{0}), \mathbf{p}_{i})}{\partial \mathrm{stack}(G)}
\cdot J_{G} \cdot \pose
\right]^2
\end{align}\end{split}\]
となる.
\[\begin{split}\begin{align}
C_{i}
&= \frac{\partial I_{t_{1}}(\mathbf{x}_{i})}{\partial \mathbf{x}}
\cdot \frac{\partial \mathbf{\pi}(g(G(t_{0}, \mathbf{p}_{i})))}{\partial g}
\cdot \frac{\partial g(G(t_{0}, \mathbf{p}_{i}))}{\partial \mathrm{stack}(G)}
\cdot J_{G} \\
y_{i}
&= -\left[ I_{t_{1}}(\mathbf{x}_{i}) - I_{t_{0}}(\mathbf{x}_{i}) \right]
\end{align}\end{split}\]
とおけば,誤差関数 \(E(\pose)\) は
\[E(\pose) \approx \sum_{i} \left[ C_{i} \pose - y_{i} \right]^2\]
という最小二乗法の形で記述でき,これを解けば
(1) を近似的に最小化する姿勢変化
\(\pose\) が得られる.
以降は \(C_{i}\) の各項の具体的な形を計算していく. \(\frac{\partial I_{t_{1}}(\mathbf{x}_{i})}{\partial \mathbf{x}}\) については先述のとおりであるため,それ以外の項を計算する.
\[\begin{split}G(t) = \begin{bmatrix}
r_{11} & r_{12} & r_{13} & t_{1} \\
r_{21} & r_{22} & r_{23} & t_{2} \\
r_{33} & r_{32} & r_{33} & t_{3} \\
0 & 0 & 0 & 1 \\
\end{bmatrix}\end{split}\]
と表現すると, \(J_{G}\) は
\[\begin{split}J_{G} = \begin{bmatrix}
0 & 0 & 0 & 0 & r_{31} & -r_{21}\\
0 & 0 & 0 & -r_{31} & 0 & r_{11} \\
0 & 0 & 0 & r_{21} & -r_{11} & 0 \\
0 & 0 & 0 & 0 & r_{32} & -r_{22}\\
0 & 0 & 0 & -r_{32} & 0 & r_{12} \\
0 & 0 & 0 & r_{22} & -r_{12} & 0 \\
0 & 0 & 0 & 0 & r_{33} & -r_{23}\\
0 & 0 & 0 & -r_{33} & 0 & r_{13} \\
0 & 0 & 0 & r_{23} & -r_{13} & 0 \\
1 & 0 & 0 & 0 & t_{3} & -t_{2} \\
0 & 1 & 0 & -t_{3} & 0 & t_{1} \\
0 & 0 & 1 & t_{2} & -t_{1} & 0 \\
\end{bmatrix}\end{split}\]
となる. \(J_{G}\) は確かに \(J_{G} \cdot \pose = \mathrm{stack}(\skew{\pose} \cdot G)\) を満たしている.
\(\partial g / \partial \mathrm{stack}(G)\) は, \(G(t)\) によって変換された点 \(\mathbf{p}' = g(G(t), \mathbf{p})\) を \(G(t)\) の各成分で微分したものなので,
\[\begin{split}\frac{\partial g(G(t), \mathbf{p})}{\partial \mathrm{stack}(G)}
= \begin{bmatrix}
x & 0 & 0 & y & 0 & 0 & z & 0 & 0 & 1 & 0 & 0 \\
0 & x & 0 & 0 & y & 0 & 0 & z & 0 & 0 & 1 & 0 \\
0 & 0 & x & 0 & 0 & y & 0 & 0 & z & 0 & 0 & 1 \\
\end{bmatrix}\end{split}\]
である. \(\mathbf{p}' = \left[x', y', z'\right] = g(G(t), \mathbf{p})\) とおくと
\[\begin{split}\frac{\partial g(G(t), \mathbf{p})}{\partial \mathrm{stack}(G)}
\cdot J_{G}
= \begin{bmatrix}
1 & 0 & 0 & 0 & z' & -y' \\
0 & 1 & 0 & -z' & 0 & x' \\
0 & 0 & 1 & y' & -x' & 0 \\
\end{bmatrix}\end{split}\]
以上より \(C_{i}\) が計算できる.
\[\begin{split}\begin{align}
C_{i}
&= \frac{\partial I_{t_{1}}(\mathbf{x}_{i})}{\partial \mathbf{x}} \cdot
\frac{\partial \mathbf{\pi}(\mathbf{p}'_{i})}{\partial \mathbf{p}'} \cdot
\frac{\partial g(G(t_{1}), \mathbf{p}_{i})}{\partial \mathrm{stack}(G)} \cdot
J_{G} \\
&= \frac{\partial I_{t_{1}}(\mathbf{x}_{i})}{\partial \mathbf{x}}
\begin{bmatrix}
\frac{f_{x}}{z'} & 0 & -\frac{f_{x}x'}{z'^2} &
-\frac{f_{x}x'y'}{z'^2} & f_{x}(1+\frac{x'^2}{z'^2}) & -\frac{f_{x}y'}{z'} \\
0 & \frac{f_{y}}{z'} & -\frac{f_{y}y'}{z'^2} &
-f_{y}(1+\frac{y'^2}{z'^2}) & \frac{f_{y}x'y'}{z'^2} & \frac{f_{y}x'}{z'} \\
\end{bmatrix}
\end{align}\end{split}\]