DVO

 Dense Visual Odometry(DVO)とはミュンヘン工科大学によって提供されている,direct methodに基づいたVisual Odometryのパッケージである.上の動画は本稿の筆者がそれを再現実装し,動作させたものである.
 DVOはSteinbrückerらの手法 [1] とKerlらの手法 [2] から成り立っている.いずれの論文も,2 つの視点で観測されたカメラの輝度情報と深度情報を用いて,視点間の移動を推定する手法について解説している.Steinbrückerらの手法 [1] では,測光誤差を正規分布でモデル化し,最尤推定によってカメラ姿勢の変化を求めている.一方で,Kerlらの手法 [2] では,測光誤差をt分布でモデル化し,MAP 推定によってカメラ姿勢の変化を求めている.ここでは2つの手法それぞれについて解説する.

Steinbrückerらの手法 [1]

問題設定

 Visual Odometry は,カメラから連続的に得られる輝度情報を用いて,カメラの姿勢変化を逐次的に推定する問題である.カメラの姿勢変化を ξR6s.t.[ξ]×se(3) ,時刻 t における画像を ItIt の座標 xi,(i=1,,N) における輝度を It(xi) で表現する.ここで []× は次で定義される演算子である.
[ξ]×=[0ξ6ξ5ξ1ξ60ξ4ξ2ξ5ξ40ξ30000]se(3),ξR6

It0(xi) が各ピクセル xi についてi.i.dだと仮定すると,2視点間の姿勢変化 ξ を画像変化から求める問題は,尤度

L(ξ)=p(It0|ξ)=ip(It0(xi)|ξ)
を最大化する問題とみなすことができる.
 問題をより詳細に記述するため,warping関数を定義する.wξ(x,t) を,ピクセル x を時刻 t0 における画像平面から時刻 t における画像平面に写す関数
wξ(x,t)=π(g(G(t),π1(x)))
とする. G(t)SE(3) は時刻 t におけるカメラ姿勢を表すユークリッド群の元 G(t)=exp((tt0)[ξ]×)G(t0) であり, g(G,p) は3次元点 pR3 の変換 g(G,p)=Rp+t を表す関数である.また, π1(x) は投影モデルの逆写像を表す.
 Steinbrückerらの手法 [1] では p(It0(xi)|ξ)N(It1(wξ(xi,t1)),σ2) でモデル化し,最尤推定によって姿勢変化 ξ を求める.結果として姿勢 ξ をパラメータとした二乗誤差関数が得られる.すなわち,
p(It0(xi)|ξ)=12πσexp([It0(xi)It1(wξ(xi,t1))]2σ2)

とおいて,推定値 ˆξ を求める.

ˆξ=argmaxξlogp(It0|ξ)=argmaxξlogip(It0(xi)|ξ)=argmaxξilogp(It0(xi)|ξ)

確率密度関数を代入すると,

ˆξ=argmaxξilogp(It0(xi)|ξ)=argmaxξilog[12πσexp([It0(xi)It1(wξ(xi,t1))]2σ2)]

定数項を省くと

ˆξ=argminξi[It0(xi)It1(wξ(xi,t1))]2

となり,二乗誤差関数

(27)E(ξ)=i[It1(wξ(xi,t1))It0(xi)]2

が得られる.

解法

 Steinbrückerらの手法 [1] では誤差関数を一次近似し, (27) を最小二乗法に落としこむ.
 まず画像を空間方向に一次近似する.
It1(xi+Δx)It1(xi)+It1(xi)xΔx

xi+Δx=wξ(xi,t1) とおくと次のようになる.

(28)It1(wξ(xi,t1))It1(xi)+It1(xi)x(wξ(xi,t1)xi)

warping関数を近似する.

wξ(xi,t1)wξ(xi,t0)+wξ(xi,t0)t(t1t0)=xi+wξ(xi,t0)t(t1t0)

これを (28) に代入すると

It1(wξ(xi,t1))It1(xi)+It1(xi)xwξ(xi,t0)t(t1t0)

t1t0 はフレームの撮影間隔(フレームレートの逆数)である.今回は t1t0=1 とおく.すなわち,フレームの撮影間隔を1単位時間とみなす.

It1(wξ(xi,t1))It1(xi)+It1(xi)xwξ(xi,t0)t

この結果を用いて誤差関数を書き換えると次のようになる.

(29)E(ξ)=i[It1(wξ(xi,t1))It0(xi)]2i[It1(xi)It0(xi)+It1(xi)xwξ(xi,t0)t]2
 さて, It1(xi)It0(xi) は画像間の差分を意味しており, It1(xi)x は一次の勾配を表しているため,これらは容易に実装することができる.しかし wξ(xi,t0)t はその中身が具体的なかたちで書かれていないため,さらに詳しく表現する必要がある.
 warping関数の微分は,chain ruleより
wξ(xi,t0)t=π(g(G(t0),pi))gg(G(t0),pi)GG(t0)t

である.G(t)t=[ξ]×G(t) (参考: リー代数による回転表現) を用いると,

wξ(xi,t0)ξ=π(g(G(t0),pi))gg(G(t0),pi)G[ξ]×G(t0)

g(G(t0),pi)G は行列 G による微分であり,コードで実装すると3次元配列になってしまう. これを回避するため,以下で定義される stack(G) を導入する.

GSE(3)

G=[r11r12r13t1r21r22r23t2r33r32r33t30001]

と表現したとき

stack(G)=[r11r21r33r12r22r32r13r23r33t1t2t3]

ここで, stack([ξk]×G(t0))=JGξ を満たすような JG が存在する(具体的な導出は後で示す).これを用いると,

wξ(xi,t0)ξ=π(g(G(t0),pi))gg(G(t0),pi)stack(G)JGξ

もとの誤差関数 (29) に代入すると

E(ξ)=i[It1(wξ(xi,t1))It0(xi)]2i[It1(xi)It0(xi)+It1(xi)xπ(g(G(t0),pi))gg(G(t0),pi)stack(G)JGξ]2

となる.

Ci=It1(xi)xπ(g(G(t0,pi)))gg(G(t0,pi))stack(G)JGξyi=[It1(xi)It0(xi)]

とおけば,誤差関数 E(ξ)

E(ξ)i[Ciξyi]2
という最小二乗法の形で記述でき,これを解けば (27) を近似的に最小化する姿勢変化 ξ が得られる.
 以降は Ci の各項の具体的な形を計算していく. It1(xi)x については先述のとおりであるため,それ以外の項を計算する.
G(t)=[r11r12r13t1r21r22r23t2r33r32r33t30001]

と表現すると, JG

JG=[0000r31r21000r310r11000r21r1100000r32r22000r320r12000r22r1200000r33r23000r330r13000r23r1301000t3t2010t30t1001t3t10]
となる. JG は確かに JGξ=stack([ξ]×G) を満たしている.
 g/stack(G) は, G(t) によって変換された点 p=g(G(t),p)G(t) の各成分で微分したものなので,
g(G(t),p)stack(G)=[x00y00z001000x00y00z001000x00y00z001]

である. p=[x,y,z]=g(G(t),p) とおくと

g(G(t),p)stack(G)JG=[1000zy010z0x001yx0]

 以上より Ci が計算できる.

Ci=It1(xi)xπ(pi)pg(G(t1),pi)stack(G)JG=It1(xi)x[fxz0fxxz2fxxyz2fx(1+x2z2)fxyz0fyzfyyz2fy(1+y2z2)fyxyz2fyxz]

Kerlらの手法 [2]

 Kerlらの手法 [2] は,Steinbrückerらの手法 [1] をつぎの点で改良した手法である.

  • 測光誤差をt分布でモデル化し,MAP推定で解いている
  • t分布は裾野が広いため外れ値に対して高いロバスト性を確保できる
  • MAP推定を用いているため,IMUなどカメラ以外から得られた情報を事前分布として使うことができる

MAP推定による記述

 姿勢変化を推定する問題は最尤推定で記述できるが,この論文では最尤推定ではなくMAP推定で記述している.これはMAP推定を用いるとIMUなどのカメラ以外のセンサ情報を事前分布 p(ξ) として設定することができるためである.すなわちベイズの定理から

p(ξ|It1)p(It1|ξ)p(ξ)

として

ξMAP=argmaxξp(ξ|It1)=argmaxξp(It1|ξ)p(ξ)=argmaxξip(It1(xi)|ξ)p(ξ)=argmaxξ[ilogp(It1(xi)|ξ)+logp(ξ)]

を解いている.事前分布 p(ξ) は自由に設定できるため,このうち対数尤度関数 logp(ri|ξ) のみに着目し式を変形していくと

ξMAP=argminξiw(ri)(ri(ξ))2ri=It1(wξ(xi,t1))It1(xi)

という式が得られる.これはピクセルごとの誤差 ri(ξ)w(ri) で重み付けし総和をとったものだと解釈することができる. w(ri) の形は分布の設定方法によって変わってくるが,測光誤差 ri がt分布に従うという仮定のもとでは

w(ri)=ν+1ν+r2iσ2

となる.ここで分散は

σ2=1nir2iν+1ν+r2iσ2

で与えられる. 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.