DVO¶
Steinbrückerらの手法 [1]¶
問題設定¶
It0(xi) が各ピクセル xi についてi.i.dだと仮定すると,2視点間の姿勢変化 ξ を画像変化から求める問題は,尤度
とおいて,推定値 ˆξ を求める.
確率密度関数を代入すると,
定数項を省くと
となり,二乗誤差関数
が得られる.
解法¶
xi+Δx=wξ(xi,t1) とおくと次のようになる.
warping関数を近似する.
これを (28) に代入すると
t1−t0 はフレームの撮影間隔(フレームレートの逆数)である.今回は t1−t0=1 とおく.すなわち,フレームの撮影間隔を1単位時間とみなす.
この結果を用いて誤差関数を書き換えると次のようになる.
である.∂G(t)∂t=[ξ]×G(t) (参考: リー代数による回転表現) を用いると,
∂g(G(t0),pi)∂G は行列 G による微分であり,コードで実装すると3次元配列になってしまう. これを回避するため,以下で定義される stack(G) を導入する.
G∈SE(3) を
G=[r11r12r13t1r21r22r23t2r33r32r33t30001]と表現したとき
stack(G)=[r11r21r33r12r22r32r13r23r33t1t2t3]⊤
ここで, stack([ξk]×⋅G(t0))=JG⋅ξ を満たすような JG が存在する(具体的な導出は後で示す).これを用いると,
もとの誤差関数 (29) に代入すると
となる.
とおけば,誤差関数 E(ξ) は
と表現すると, JG は
である. p′=[x′,y′,z′]=g(G(t),p) とおくと
以上より Ci が計算できる.
Kerlらの手法 [2]¶
Kerlらの手法 [2] は,Steinbrückerらの手法 [1] をつぎの点で改良した手法である.
- 測光誤差をt分布でモデル化し,MAP推定で解いている
- t分布は裾野が広いため外れ値に対して高いロバスト性を確保できる
- MAP推定を用いているため,IMUなどカメラ以外から得られた情報を事前分布として使うことができる
MAP推定による記述¶
姿勢変化を推定する問題は最尤推定で記述できるが,この論文では最尤推定ではなくMAP推定で記述している.これはMAP推定を用いるとIMUなどのカメラ以外のセンサ情報を事前分布 p(ξ) として設定することができるためである.すなわちベイズの定理から
として
を解いている.事前分布 p(ξ) は自由に設定できるため,このうち対数尤度関数 logp(ri|ξ) のみに着目し式を変形していくと
という式が得られる.これはピクセルごとの誤差 ri(ξ) を w(ri) で重み付けし総和をとったものだと解釈することができる. w(ri) の形は分布の設定方法によって変わってくるが,測光誤差 ri がt分布に従うという仮定のもとでは
となる.ここで分散は
で与えられる. n は画像のピクセル数である.分散の式は再帰的に記述されているが, σ2 の値は数回の反復で収束する.
[1] | (1, 2, 3, 4, 5, 6) Steinbrücker Frank, Jürgen Sturm, and Daniel Cremers. “Real-time visual odometry from dense RGB-D images.” Computer Vision Workshops (ICCV Workshops), 2011 IEEE International Conference on. IEEE, 2011. |
[2] | (1, 2, 3, 4) Kerl, Christian, Jürgen Sturm, and Daniel Cremers. “Robust odometry estimation for RGB-D cameras.” Robotics and Automation (ICRA), 2013 IEEE International Conference on. IEEE, 2013. |