Single Rotation Averaging ์ ๊ตฌํํด๋ณด์
- ์ด๋ ต์ง ์์์
- $\text{SO(3)}$ ์ $\mathfrak{so(3)}$ ๋ฏธ๋ถ ๊ณ ์๋๋ ๋ฒ
๊ฐ์
- Rotation averaging ์ SfM (Structure-from-motion), SLAM ๋ฑ์์ ์์ฃผ ๋ฑ์ฅํ๋ task ์ด๋ค.
- ps. rotation averaging ์ด ๋ฌด์์ธ์ง์ ๋ํด์๋ ๋ค์ ๋
ผ๋ฌธ์ ์ฐธ๊ณ .
- Rotation Averaging by Richard Hartley, et al.
- ์ด ๋ ผ๋ฌธ์ ์ธ์ฉํ ๋ ผ๋ฌธ๋ค ์ค ์ธ์ฉ์๊ฐ ๋ง์ ๊ฒ์ ๋ณด๋ ๊ฒ ๋ํ ๋์์ด ๋๊ฒ ๋ค.
- ps. rotation averaging ์ด ๋ฌด์์ธ์ง์ ๋ํด์๋ ๋ค์ ๋
ผ๋ฌธ์ ์ฐธ๊ณ .
- ์ ํ์ํ๊ฐ?
- ๋๋ถ๋ถ์ geometric computer vision ๋ฌธ์ ์์, residual ์ ์ต์ํ ํ ๋,
- ํ์ฌ solution์ผ๋ก๋ถํฐ delta ๋งํผ ์กฐ๊ธ์ฉ ์ด๋ํด๋๊ฐ๋ฉด์ ์ต์ข solution ์ผ๋ก ์๋ ดํด๋๊ฐ๋๋ฐ (i.e., Gauss-Newton),
- ์ด ์์ ์ vector space ์์๋ง ๊ฐ๋ฅํ๋ฏ๋ก,
- nonlinear ํ term ๋ค์ ๊ตญ์์ ์ผ๋ก linearization ํด์ฃผ์ด์ผ ํ๋๋ฐ,
- ์ด ์ด์ผ๊ธฐ์ ๋ํ ๋ ์์ธํ ์ค๋ช ์ ์์ ํฌ์คํธ ๋ฅผ ์ฐธ๊ณ .
- ์ด ๋, ์ง์ solution ์ด ์ ์ข๋ค๋ฉด (== global solution ์ผ๋ก๋ถํฐ ๋ฉ๋ค๋ฉด)
- ํด๊ฐ ์๋ ดํ๊ธฐ ์ด๋ ต๋ค.
- ์ด๊ฒ์ด SfM or SLAM ์์ ๋์ฑ ๋ฌธ์ ๊ฐ ๋๋ ๊ฑด,
- N ๊ฐ์ ๋ ธ๋ (์์ญ๊ฐ์ผ์๋, ์์ฒ ์๋ง ๊ฐ ์ผ์๋) ์ pose ๋ฅผ ๋ชจ๋ joint ํ๊ฒ ์ต์ ํ ํ๋ ๋ฌธ์ ๋ฅผ ํธ๋ ๊ฒ์ด SfM or SLAM ์ธ๋ฐ
- rotation ์ด nonlinear ํ ์์์ด๊ณ ,
- Gauss-newton ๊ณผ์ ์์, rotation ๋ถ๋ถ์ current solution ์ด ์์ข๋ค๋ฉด ์ด๋ pose ์ค rotation ์ด ์๋๋ผ position ๋ถ๋ถ์๋ ์ ์ํฅ์ ๋ผ์น ์ ์๊ธฐ ๋๋ฌธ์ด๋ค (๊ทธ๋ฆฌ๊ณ ๋ง์ฐฌ๊ฐ์ง๋ก ๊ทธ๋ฌํ ํ ๋ ธ๋์ ์๋ฌ๊ฐ ๋ค๋ฅธ ๋ ธ๋๋ค์๋ ์ ์ํฅ์ ๋ผ์น ์๋ ์๊ฒ ๋ค).
- ๊ทธ๋์, ํนํ nonlinear ํ term์ธ rotation ๋ถ๋ถ์ global solution์ ์ ๋ง๊ฒ ์ด๊ธฐ๊ฐ์ ์ ์ค์ ํด๋ ์ ์๋ค๋ฉด, translation loss ๋ฑ์ ๋ํ ์ฝ๊ฒ ํ๋ฆด ์ ์์ ๊ฒ์ด๋ค.
- ์๋ฅผ ๋ค์ด์, ํ๋์ ๋ ธ๋ (pose) ์ rotation (attitude) ์ ๋ํ measurement ๊ฐ k ๊ฐ ์์ ๋, ์ด๊ฒ์ ์๋ง๊ฐ ๋ ธ๋์ joint optimization ์ ํ ๋ ๋ชจ๋ constraint ๋ก ๋ฃ์ด์ฃผ๋ ๊ฒ์ด ์๋๋ผ, k ๊ฐ์ measurement ๋ค์ ์ ๋ถ์ํด์ ์ ๋ขฐํ ๋งํ ํ๋์ ๊ฐ๋ง์ ๋์ถํ ๋ค์, ๊ทธ๊ฒ๋ง์ ์ ์ฒด ์ต์ ํ ๋ฌธ์ ์ constraint ๋ก ์ถ๊ฐํด์ค ์ ์๊ฒ ๋ค.
- ์ฆ, single rotation averaging ์ด๋ผ๋ task๋,
- ํ๋์ ๋ ธ๋ (pose) ์ rotation (attitude) ์ ๋ํ measurement ๊ฐ k ๊ฐ ์์ ๋,
- ์ด ์ธก์ ์น๋ค์ ๋ชจ๋ ์ ๋นํ ๋ง์กฑํ๋๋ก ๊ณ ๋ คํ์ ๋,
- ๊ทธ ๋ ธ๋์ rotation (attitude or orientation ๋ฑ์ผ๋ก๋ ๋ถ๋ฆผ) ์ ๊ทธ๋์ ์ต์ข ์ ์ผ๋ก ๋ฌด์์ธ๊ฐ, ์ ๋ํ ๋๋ต์ ํ๋ ๋ฌธ์ ์ด๋ค.
- rotation (i.e., SO(3)) ์ vector space ์ ์ด๊ณ ์์ง ์๊ธฐ ๋๋ฌธ์, ๋จ์ํ xyz ๋ค์ k ๋ก ๋๋๋, ์ฆ, $ \textbf{sum}(\textbf{R}_1, \textbf{R}_2, \textbf{R}_3) / 3$ ๊ณผ ๊ฐ์ด ๋์ด๋ธํ๊ฒ ๊ณ์ฐํ ์๋ ์๋ค.
- ๋ฌผ๋ก sum ์ด๋ผ๋ ํจ์์ / ๋ผ๋ ๋๋์ ์ ์ด๋ป๊ฒ ์ ์ํ ๊ฑฐ๋์ ๋ฌ๋ฆฐ๊ฒ์ด๊ธด ํ์ง๋งโฆ ์ฌ๊ธฐ์์ ์ด์ผ๊ธฐํ๋ ค๊ณ ํ๋ ๊ฒ์ ์ ๋ฐ deterministic ํ ๊ณ์ฐ์ ํ ๋ฐฉ์ ํ๋ ค๋ ๊ฒ์ด ์๋๋ผ, ๋์ ์ iteratively ์กฐ์ ํด๋๊ฐ๋ ๊ณผ์ ์ ์ด๋ป๊ฒ ์ํํ ์ ์๋๋? ํ๋ ์ ์ด๋ค. ์ฆ, ์ ํ๊ท ์กฐ์ฐจ๋ iterative ํ๊ฒ ์ป์ด์ ธ์ผ ํ๋ค๋ ๊ฒ์ด๋ค. ์ด๋ ๋ค์ ๋งํ์ง๋ง rotation ์ด ์ด๊ณ ์๋ ๊ณต๊ฐ์ nonlinear ํ๊ณ ๊ตญ์์ ์ผ๋ก (== iterative optimization ์ด ์ํ๋๋ tangent space) ๋ง vector space ์ด๊ธฐ ๋๋ฌธ์ ์ ๋ฐ ์ผ๋ฐ ์ฐ์ฐ์ ์ํํ ์ ์๊ธฐ ๋๋ฌธ์ด๋ค.
- ์ ๋ ผ๋ฌธ Rotation Averaging by Richard Hartley, et al. ์์๋ rotation definition์ ๋จผ์ ํ๊ณ , ์ ์ฉํ ์ฑ์ง๋ค์ ๋ํด ์ด์ผ๊ธฐ ํ ๋ค, ์ฌ๋ฌ distance ์ ๋ํด์๋ ๋ ผ์ํ๊ณ , ๋ฉ์ธ์์๋ 1. single rotation averaging ๊ณผ 2. multiple rotation averaging ์ ๋ํด ์ด์ผ๊ธฐํ๋ค.
- ๊ทธ ์ค, ์ด ํฌ์คํธ์์๋ 1. single rotation averaging ์ ๋ํด์๋ง ์์๋ณผ ๊ฒ์ด๋ค.
- rotation ์ ์ ์๋ ๊ธฐ๋ณธ์ ์ธ ์ฑ์ง์ ๋ํด์๋ ๋ ์๊ฐ ์๊ณ ์๋ค๊ณ ๊ฐ์ ํ๋ค.
- ๊ทธ๋์ ๋ 2. multiple rotation averaging ๋ rotation only pose-graph optimization ์ด๋ผ๊ณ ๋ ๋ถ๋ฆฐ๋ค.
- ๊ทธ๋ฆฌ๊ณ ์ ๋ ผ๋ฌธ์ ๋ณด๋ฉด rotation ์ด ์ด๊ณ ์๋ ๊ณต๊ฐ์์ distance ๋ฅผ ์ ์ํ๋ ๋ฐฉ์์ด ์ฌ๋ฌ ๊ฐ๊ฐ ์์์ ์ ์ ์๋๋ฐ, ๋ณธ ํฌ์คํธ์์๋ ๊ฐ์ฅ ๊ธฐ๋ณธ์ ์ด๊ณ ์ ์์ ์ธ tangent space ์์์ L2 loss ๋ก ์ ์ํ ๊ฒ์ด๋ค. ๊ทธ๋ฆฌ๊ณ ๊ทธ ์ฐจ์ด๋ฅผ iteratively ์ค์ฌ๋๊ฐ๋ฉด, ์๋ rotation ๊ณต๊ฐ (we call it manifold, SO(3)) ์์๋ ์ต์ ํ๊ฐ ๋์ด์๋์ง ๋ณด์ผ ๊ฒ์ด๋ค.
ํฐ์
- ์ด ํฌ์คํธ์์๋, single rotation averaging ์ from scratch ๋ก ๊ตฌํํด๋ณด๊ณ ์ค์ตํด๋ณด์.
- ํฐ์
- ๊ฒฐ๊ณผ๋ถํฐ ๋จผ์ ๋ณด์ด์๋ฉด ์๋ ๊ทธ๋ฆผ๊ณผ ๊ฐ๋ค.
- ์ค๋ช
- ๋นจ๊ฐ, ์ฒญ๋ก, ๋
ธ๋ axes ๋ค์, ์ด๋ค ๋ก๋ด์ ์ด๋ค ์์ ์์์ ๋ํ ์์ธ (rotation, attitude, orientation ๋ฑ์ผ๋ก ๋ถ๋ฆผ) ์์ธก ๊ฐ์ ์๋ฏธํ๋ค.
- ์๋ฅผ ๋ค์ด์ ๋์ผํ ์ผ์๋ก ์ธ ๋ฒ ์ธก์ ํ๋๋ฐ, ํ์ค์ธ๊ณ์ ์ผ์๋ noisy ํ๊ณ ๋ถ์์ ํ๋ฏ๋ก ์กฐ๊ธ์ฉ ์ ๋ ๊ฒ ๋ค๋ฅธ ๊ฒฐ๊ณผ๊ฐ ๋์ฌ ์ ์๊ฒ ๋ค.
- ๊ทธ๋ฌ๋ฉด ์ ์ ์ ๋ณด๋ฅผ ๋ชจ๋ ๋ง์กฑํ๋ (== ๊ฐ๋ ์ ์ผ๋ก ํ๊ท , ์ค์ ๊ณ์ฐ์ iterative optimization) ๊ฐ์ ๊ตฌํด์, ๋ก๋ด์ ์์ธ๋ ์ด๊ฒ์ด์ผ! ๋ผ๊ณ ๋งํด์ผ ํ ํ ๋ฐ,
- ๊ทธ ๊ฒฐ๊ณผ๋ ํ๋์ ์ถ์ด๋ค.
- ์ผ๋จ ์ฌ๋์ด ์๊ฐ์ ์ผ๋ก ๋ณด์์ ๋ ๋ง์ด ๋ง๋ ๊ฒ ๊ฐ์๋ณด์ธ๋ค. ํ๋์ด ์ธ ์ถ ๋ชจ๋์์, ๋ค๋ฅธ ์ ๋ค์ ์ค๊ฐ ์ฆ์์ ์์นํ๋ ๊ฒ์ ์ ๋ณผ ์ ์๋ค.
- ๋นจ๊ฐ, ์ฒญ๋ก, ๋
ธ๋ axes ๋ค์, ์ด๋ค ๋ก๋ด์ ์ด๋ค ์์ ์์์ ๋ํ ์์ธ (rotation, attitude, orientation ๋ฑ์ผ๋ก ๋ถ๋ฆผ) ์์ธก ๊ฐ์ ์๋ฏธํ๋ค.
- ์ด๋ป๊ฒ ๊ตฌํํ๋์ง ์ด์ ์ฐจ์ฐจ ์ค๋ช ์ ํด๋ณด์.
- ์ค๋ช
- ๊ฒฐ๊ณผ๋ถํฐ ๋จผ์ ๋ณด์ด์๋ฉด ์๋ ๊ทธ๋ฆผ๊ณผ ๊ฐ๋ค.
๋ฐฐ๊ฒฝ์ง์ 1
- ์ผ๋จ iterative optimization ์ ๊ธฐ๊ณ์ ์ธ ๊ณผ์ ์ ์๋์ ๊ฐ๋ค (์ด๊ฑธ ๋๋ ๊ฐ์ธ์ ์ผ๋ก โ๊ธฐ๊ณ์ ์ธ ๊ณผ์ โ ์ด๋ผ๋๊ฐ, โ์ฐ์โ ๋ผ๋๊ฐ, โ๊ณ์ฐ๊ธฐโ๋ผ๊ณ ๋ถ๋ฅธ๋ค. ์ฆ, ์ด๋ ต์ง ์๋ค๋ ๋ง์ด๋ค).
- ์ด ๊ทธ๋ฆผ์ ๋งค๋ฒ ์ถ์ฒํ๋ ์๋ฃ์ธ, ICRA 2016 SLAM tutorial ์ค, Giorgio Grisetti ๊ต์๋ ์ฌ๋ผ์ด๋ ์์ ๊ฐ์ ธ์จ ๊ฒ์ด๋ค.
- ์ฌ๊ธฐ์ $\textbf{J}$ ๋ง ๊ตฌํ๋ฉด ๋๋ค.
- ps. ๋ด๊ฐ ๋ค๋ฃจ๋ 1. ์ผ์ ํน์ฑ (์: ์นด๋ฉ๋ผ๋ pixel ๋ก ๊ตฌ์ฑ๋์ด์๊ณ ์ธ์์ ์ ๋ณด๊ฐ projective ํ๊ฒ ์์ฑ๋๋ค) ๊ณผ, 2. ๊ทธ ์ผ์ ํน์ฑ์ ๊ณ ๋ คํ observation model (residual model) (์: ๊ทธ๋ฌ๋ฏ๋ก pose ๊ฐ true์๋ค๋ฉด projection ํ์ ๋์ reprojection error ๊ฐ ์์ ๊ฒ์ด๋ค. ๊ทธ๊ฒ์ (u, v) ๊ณต๊ฐ์์์ ๊ทธ์ ๋ ์ฐจ์ ๋ฒกํฐ์ ๋บ์ ์ผ๋ก ์ ์๋๋ค), ์ด ๋ ๊ฐ์ง๋ฅผ ์ด๋ป๊ฒ ์ ์๊ณ ์ ๋ค๋ฃจ๊ณ ์ ๊ตฌํํ ์ ์๋๋๊ฐ ๋จ์ํ geometric vision ์ ๊ณต์๋ฅผ ๋์ด์์ SLAM engineer์ ๋๋ฉ์ธ ๋๋ฆฌ์ง๋ผ๊ณ ํ ์ ์๊ฒ ๋ค.
- J๊ฐ ์ด๋ป๊ฒ ๊ตฌํด์ง๋๋๋ง ๋ค๋ฅด์ง, ๊ทธ ์ดํ๊ณผ์ ์ ๋ชจ๋ ๋ ผ๋ฌธ๋ค์ด ๋์ผํ๋ค.
๋ฐฐ๊ฒฝ์ง์ 2
- $\textbf{J}$ โฆ
- ์์ฝ๋น์, ์ผ์ฝ๋น์, โฆ ๋ค์ํ๊ฒ ๋ถ๋ฆฌ๋ ์ด ๋
์
- ๊ทธ๋ฅ multi-dimensional ๊ธฐ์ธ๊ธฐ๋ผ๊ณ ์๊ฐํ๋ฉด ๋๋ค.
- Gauss-Newton optimization ์ ํ๊ธฐ ์ํด์๋ ๊ธฐ์ธ๊ธฐ ๊ฐ์ ์์์ผ ํ๊ธฐ ๋๋ฌธ.
- ์์ ํฌ์คํธ ์์๋ ์ด ์๊ธฐ๋ ์ด๋ฏธ ํ์๋ค (์ฌ์ค ๊ฒฐ๊ตญ ๋งจ๋ ์ด ์๊ธฐ๋ฅผ ํ๊ฒ ๋๋ ๊ฒ์ด๋ค โฆ).
- ์ฌ๊ธฐ์๋ ๋ค์ ๋งํ์๋ฉด, ์์ฝ๋น์์ ์ด๋ ๊ฒ ๊ธฐ์ตํ๋ฉด ๋๋ค. matrix ๋ค๋ชจ์ ์ธ๋ก(์ฆ, row ๋ค) ๋ cost, ๊ฐ๋ก(์ฆ, column๋ค)๋ state.
- ์๋ฌดํผ ๋ณธ ํฌ์คํธ์์๋ ๊ฒฐ๊ตญ, ์ด๋ค residual function์ ๋ํ, ์ต์ rotation ์ ๋ฏธ์๋ณํ๋, ์ ๋ฏธ๋ถ matrix (== ์์ฝ๋น์) ๋ฅผ ๊ณ์ฐํ๋ ๊ฒ์ด ๊ด๊ฑด์ด ๋๋ค.
- rotation ์ ๋ํด ํด๋ณด์.
์ ๋ ๊ณผ์ (Derivation)
- iterative ํ๊ฒ an averaged rotation ๊ฐ์ ์์ธกํ ๊ฒ์ด๋ฏ๋ก,
- ํ์ฌ ($t$ ๋ฒ์งธ step) ๊น์ง ์์ธก๋ ๊ฐ์ $\textbf{R}^{(t)}$ ์ด๋ผ๊ณ ํด๋ณด์.
- == ์์ ํฐ์ ๊ทธ๋ฆผ์์ ํ๋ ํ์ดํ (ํน์ ์ด๊ฒ์ ๋๋ฌํ๊ธฐ ์ ์ ์คํ )
- ๊ทธ๋ฆฌ๊ณ ์ด๋ค measurement $\textbf{R}_1$, $\textbf{R}_2$, $\textbf{R}_3$ ์ด๋ ๊ฒ 3๊ฐ๊ฐ ์์๋ค๊ณ ํ์.
- == ์์ ํฐ์ ๊ทธ๋ฆผ์์ ํ๋์ ์ ์ธํ ๋๋จธ์ง ํ์ดํ๋ค
- ๊ทธ๋ฌ๋ฉด, ์ด ์ธ ๊ฐ์ measurement ๋ก๋ถํฐ ๊ฐ๊ฐ $\textbf{H}_i$ ์ $\textbf{e}_i$ ๊ฐ ์์ฑ๋๊ณ ,
- ์ ์ฒด $\textbf{H}$ ์ $\textbf{b}$ ๋ ์์ ์๊ฐํ tutorial slide ์์ ์ค๋ช
ํ๋๋ก (๋จ์ํ ๋ง์
์ผ๋ก!) ์ป์ด์ง๊ฒ ๋๋ค.
- ์ฝ๋๋ก๋ ๋น์ฐํ ๋๋ฌด ๊ฐ๋จํ๋ค.
H += J_i.T @ J_i b += J_i.T @ e_i
- ์ฝ๋๋ก๋ ๋น์ฐํ ๋๋ฌด ๊ฐ๋จํ๋ค.
- ๊ทธ๋ผ ์ฐ๋ฆฌ๊ฐ ์ง๊ธ ์ ๋ํ๋ ค๋ ๊ฒ์ ๊ฒฐ๊ตญ ์
J_i
์e_i
๊ฐ ๋ฌด์์ธ๊ฐ ํ๋ ๊ฒ์ด๋ค. J_i
๋e_i
๋ฅผ ๋ฏธ๋ถํจ์ผ๋ก์จ ์ป์ด์ง๋ ๊ฒ์ด๋ฏ๋ก, ๋จผ์ e_i
๋ฅผ ์ ์ํด์ผ ํ๋ค.e_i
๋ ๋ค์๊ณผ ๊ฐ๋ค.- ์ฐ๋ฆฌ๋ iteratively gauss newton optimization ์ ์ํํ ๊ฒ์ด๋ฏ๋ก
- ๊ทธ ์ต์ ์กฐ๊ธ์์ง์ ํด๋ rotation ์ tangent space ์์๋ง ์ ์๊ฐ ๊ฐ๋ฅํ๋ค. ๊ฑฐ๊ธฐ๋ง์ด vector space์ด๊ธฐ ๋๋ฌธ์ด๋ค.
- ์ด ๋ง์ด ์ดํด๊ฐ ๊ฐ์ง ์๋๋ค๋ฉด ์์ ํฌ์คํธ๋ฅผ ์ฝ๊ณ ์ค๊ธฐ๋ฅผ ์ถ์ฒํ๋ค. ์์ ํฌ์คํธ1 ์ ์์ ํฌ์คํธ2.
- ์๋์ rotation ๊ณต๊ฐ์ธ $\mathrm{SO(3)}$ ์์์ residual (์ 3 by 3 matrix ์ด๋ค) ์ $\textbf{Log}(\cdot)$ ์ฐ์ฐ์ ์ทจํด์ฃผ๋ฉด 3-dim vector๊ฐ ์์ฑ๋๋ค.
- ๊ทธ๊ฒ์ด ์ฐ๋ฆฌ์
e_i
๊ฐ ๋๋ค. - ์ ๊ทธ๋ ๊ฒ ํ๋๊ณ ๋ฌป๋๋ค๋ฉด, ๋ค์ ์์ฝํ์๋ฉด, Gauss-Newton opt ๋ vector space ์์๋ง ์ํํ ์ ์๋๋ฐ, ๊ทธ๊ฒ์ $\mathrm{SO(3)}$ ์ tangent space์ธ $\mathfrak{so(3)}$ ์์ ์ ์๋๋ค๊ณ ํ ์ ์๋ค. ๊ทธ๋์ ์ฐ๋ฆฌ๋ $\mathrm{SO(3)}$ ์์ distance ๋ฅผ ๊ตฌํ๊ณ , ๊ฑฐ๊ธฐ์ $\textbf{Log}(\cdot)$ ์ฐ์ฐ์ ์ทจํด์, $\mathfrak{so(3)}$ ์์์์ distance ๋ฅผ ์ ์ํ๋ค๊ณ ํ ์ ์๋ค.
- ps. ์ $\textbf{Log}(\cdot)$ ์ฐ์ฐ์ ์ทจํด์ผ, $\mathfrak{so(3)}$ ์์์์ distance ๊ฐ ๋๋์ง์ ๋ํด์๋ ์ฌ๊ธฐ์์ ๋ ์ค๋ช ํ์ง๋ ์๋๋ค. ๊ทธ๊ฒ์ ์ฝ๊ฐ ๊ธฐ๋ณธ์ด๊ธฐ ๋๋ฌธโฆ ์ฌ๊ธฐ์๋ถํฐ๋ Quaternion kinematics for the error-state Kalman filter ์ด๋, ์๋๋ฉด ๋ค๋ฅธ ๋ ผ๋ฌธ๋ค์ ์ฐธ๊ณ ๋ฐ๋.
- ๊ทธ๋ฆฌ๊ณ $\textbf{Log}(\cdot)$ ๋ ์ฌ์ค $\textbf{log}(\cdot)$ ๋ผ๋ ์ฐ์ฐ์ unskew ๋ฅผ ํด์ฃผ๋ ๊ณผ์ ์ ๋ํ ๊ฒ์, ๊ฐ๋จํ๊ฒ ๋ฌธ์๋ก ํํํ๋ ค๊ณ l์ L๋ก๋ง ๋ฐ๊ฟ์ด๊ฒ์ด๋ค.
- ๊ทธ๋ผ ์ด์ ๊น์ง tangent space ์์์์ error function (our observation model) ์ ์ ์ํ์ผ๋, ์ด๊ฒ์ Jacobian์ ๊ตฌํด๋ณด์.
- ๋จผ์ ,
e_i
์ ์์์ ์ฝ๋๊ฐ ์๋๋ผ latex์ผ๋ก ๋ค์ ์ ์ด๋ณด์.- $e_i = \textbf{Log}(error(\mathbf{R}))$ ์ด๊ณ , ์ฌ๊ธฐ์ $error(\mathbf{R})$๋ ๋ค์๊ณผ ๊ฐ์ด ์ ์๋๋ค. $error(\mathbf{R}) = \mathbf{R}_{\text{measurement}} \ominus \mathbf{R}_{\text{estimated}} = \mathbf{R}_{\text{estimated}}^\top \cdot \mathbf{R}_{\text{measurement}}$
- ์ transpose ์ ์ผ์ชฝ๊ณฑ์ด ๋๋์ง ๊น์ง ์ฌ๊ธฐ์ ์ค๋ช ํ์ง๋ ์๋๋ค..
- $e_i = \textbf{Log}(error(\mathbf{R}))$ ์ด๊ณ , ์ฌ๊ธฐ์ $error(\mathbf{R})$๋ ๋ค์๊ณผ ๊ฐ์ด ์ ์๋๋ค. $error(\mathbf{R}) = \mathbf{R}_{\text{measurement}} \ominus \mathbf{R}_{\text{estimated}} = \mathbf{R}_{\text{estimated}}^\top \cdot \mathbf{R}_{\text{measurement}}$
- ์์ ์ฐ๋ฆฌ์ measurement ๋ฅผ ๊ฐ๋จํ $\mathbf{R}_{i}$ ๋ผ ๋ถ๋ ๊ณ (์: $\mathbf{R}_{1}$, $\mathbf{R}_{2}$, $\mathbf{R}_{3}$), ์ฐ๋ฆฌ์ (step $t$์์์) ์์ธก๊ฐ์ $\mathbf{R}^{(t)}$๋ผ๊ณ ๋ถ๋ ์ผ๋, ๋ค์ ์์ ์จ๋ณด๋ฉด
- $e_i = \textbf{Log}({\mathbf{R}^{(t)}}^\top \cdot \mathbf{R}_{i})$ ๋ผ๊ณ ํ ์ ์๋ค.
- ์ด์ $\mathbf{J}_i$๋ฅผ ๋ ผํ ์ ์๋ค.
- $\mathbf{J}_i$๋, ์ฐ๋ฆฌ์ ๊ด์ฌ์ฌ(์ต์ ์กฐ๊ธ์์ง์๊ฐ์ด ์ผ๋ง์ธ์ง)์ธ tangent space ์์์ value (rotation vector ๋ผ๊ณ ํ์) ์ธ, ์ด 3-dim vector์ธ ์ด ๊ฐ์ด ์กฐ๊ธ ์์ง์ผ ๋, ์์ $e_i$๊ฐ ์ผ๋ง๋ ๋ณํ๋์ง? ๋ก ์ ์๋๋ค.
- ๊ทธ ์ต์ ์ผ๋ก ์กฐ๊ธ ์์ง์ธ rotation vector ๋ฅผ $\delta \boldsymbol{\theta}$๋ผ๊ณ ํ๋ฉด, (ps. ์กฐ๊ธ์ด๋ผ๋ ์๋ฏธ์์ $\delta$ ๋ฅผ ๋ถ์)
- ์ด ๋ (== step $t$์์ ์กฐ๊ธ๋ง ์ต์ ์ผ๋ก ๋ ์์ง์ฌ ๋ณธ)์, ์์ธก ๊ฐ์ ${(\mathbf{R}^{(t)} \oplus \delta\boldsymbol{\theta})}$ ๊ฐ ๋๊ณ ,
- $e_i$๋ ๋ฐ๋ผ์ $\textbf{Log}({(\mathbf{R}^{(t)} \oplus \delta\boldsymbol{\theta})}^\top \cdot \mathbf{R}_{i})$ ๊ฐ ๋๋ฉฐ,
- ps. ์ด ๋ $\oplus$๋ matmul ์ ์๋ฏธํ๋ค. ํ์ง๋ง ์ ๊ทธ๋ ๊ฒ ์ฐ๋๋ฉด, $\delta\boldsymbol{\theta}$ ๋ vector ์ด๊ณ , rotation matrix ๊ฐ ์ด๊ณ ์๋ SO(3) ์ ์ด๊ณ ์์ง ์๊ธฐ ๋๋ฌธ์, ์ผ๋ฐ์ ์ธ ๋ํ๊ธฐ๋ ๊ณฑํ๊ธฐ (i.e., $\cdot$) ๊ธฐํธ๋ฅผ ์ฐ๋ฉด ๋
ผ๋ฆฌ๊ฐ ๋ง์ง์๊ฒ ๋์ด ํธ์์ $\oplus$ ๋ $\boxplus$์ ๊ฐ์ ๊ธฐํธ๋ก ํ๊ธฐํ๋ ํ์ต์ด ์๋ค. ์ค์ ๋ก๋ oplus ๊ฐ ์ ํ์๋ค๋ฉด, rotation vector ์ Exp๋ฅผ ์ทจํ ๋ค matmul ์ ํด์ค๋ค ๋ผ๊ณ ์ดํดํ๋ฉด ๋๋ค.
- ์ด๋ฏธ ์กด์ฌํ๋ ๋ค์ํ ๊ณต๋ถ์๋ฃ๋ค๋ก ๊ทธ ์ค๋ช ์ ๋์ ํ๋ค.
- ps. ์ด ๋ $\oplus$๋ matmul ์ ์๋ฏธํ๋ค. ํ์ง๋ง ์ ๊ทธ๋ ๊ฒ ์ฐ๋๋ฉด, $\delta\boldsymbol{\theta}$ ๋ vector ์ด๊ณ , rotation matrix ๊ฐ ์ด๊ณ ์๋ SO(3) ์ ์ด๊ณ ์์ง ์๊ธฐ ๋๋ฌธ์, ์ผ๋ฐ์ ์ธ ๋ํ๊ธฐ๋ ๊ณฑํ๊ธฐ (i.e., $\cdot$) ๊ธฐํธ๋ฅผ ์ฐ๋ฉด ๋
ผ๋ฆฌ๊ฐ ๋ง์ง์๊ฒ ๋์ด ํธ์์ $\oplus$ ๋ $\boxplus$์ ๊ฐ์ ๊ธฐํธ๋ก ํ๊ธฐํ๋ ํ์ต์ด ์๋ค. ์ค์ ๋ก๋ oplus ๊ฐ ์ ํ์๋ค๋ฉด, rotation vector ์ Exp๋ฅผ ์ทจํ ๋ค matmul ์ ํด์ค๋ค ๋ผ๊ณ ์ดํดํ๋ฉด ๋๋ค.
- $J_i = \frac{\partial e_{i}(\delta \boldsymbol{\theta})}{\partial \delta\boldsymbol{\theta}} = \frac{\partial \textbf{Log}({(\mathbf{R}^{(t)} \oplus \delta\boldsymbol{\theta})}^\top \cdot \mathbf{R}_{i})}{\partial \delta\boldsymbol{\theta}}$ ๊ฐ ๋๋ค.
- ์ด๊ฒ์ด ์ค์ ๋ก ์ฝ๋์์ผ๋ก ์ด๋ป๊ฒ ๊ตฌํ์ด ๋๋์ง, symforce ๋ฑ์ ๋งก๊ฒจ๋ ๋๊ฒ ์ง๋งโฆ
- ์ฐ๋ฆฌ๊ฐ ์๊ณ ์๋ rotation ์ ์ ์ฉํ ์์๋ค์ ์ ์กฐํฉํด์, ์ ํ์ด์ deterministic ํ๊ฒ ์จ๋ด๋ฉด (== ์ฝ๋๋ก ์ฎ๊ธฐ๊ธฐ ์ฌ์ด ํํ) ์ฐ๋ฆฌ์ ๋ชฉํ ๋ฌ์ฑ์ด๋ค.
- ํธ๋ฆญ 1
- ${\mathbf{R}^{(t)} \oplus \delta\boldsymbol{\theta}}$ ์
- $\mathbf{R}^{(t)} \cdot \textbf{Exp}(\delta\boldsymbol{\theta})$ ์ธ๋ฐ,
- ์ฌ๊ธฐ์, $\delta\boldsymbol{\theta}$ ๊ฐ ์์ ๊ฐ์ผ ๋๋ (์ต์ โ์กฐ๊ธโ์์ง์ ๊ฐ์ด๋ฏ๋ก ์ด๋ ๊ฒ ๊ฐ์ ํ ์ ์์)
- $\textbf{Exp}(\delta\boldsymbol{\theta}) \sim \textbf{I} + [\delta\boldsymbol{\theta}]_{\times}$ ๋ก ๊ทผ์ฌํ ์ ์๋ค.
- note: $[ โฆ ]_{\times}$ ๋ input์ด 3-dim vector์ด๊ณ , output์ด skew symmetric matrix ์ธ ํจ์๋ฅผ ์๋ฏธํ๋ค.
- ๊ทธ๋ฌ๋ฉด ๋ค์, $\mathbf{R}^{(t)} \cdot \textbf{Exp}(\delta\boldsymbol{\theta}) = \mathbf{R}^{(t)} \cdot (\textbf{I} + [\delta\boldsymbol{\theta}]_{\times})$ ๊ฐ ๋๋ค.
- ๊ทธ๋ฌ๋ฉด $J_i = \frac{\partial \textbf{Log}({(\mathbf{R}^{(t)} \oplus \delta\boldsymbol{\theta})}^\top \cdot \mathbf{R}_{i})}{\partial \delta\boldsymbol{\theta}}$ ๋
- $J_i = \frac{\partial \textbf{Log}({ (\mathbf{R}^{(t)} \cdot (\textbf{I} + [\delta\boldsymbol{\theta}]_{\times})) }^\top \cdot \mathbf{R}_{i})}{\partial \delta\boldsymbol{\theta}}$ ์ ๊ฐ์ด ๋ค์ ์ธ ์ ์๋ค.
- ํธ๋ฆญ 2
- $\textbf{Log}(\cdot)$ ์ฐ์ฐ์๋ฅผ $\text{unskew}(\textbf{log}(\cdot))$ ์ด๋ ๊ฒ ๋๋ ์ ์ธ ์ ์๋ค. ์ฌ๊ธฐ์ unskew ๋ผ๋ ๋ง์ ๊ทธ๋ฅ ํธ์์ ๋ด๊ฐ ๋ถ์ธ ๋ง์ด๋ฉฐ (์ข ๋ ์ฝ๋ ์นํ์ ์ผ๋ก ์ค๋ช ํ๊ธฐ ์ํด์), ์ค์ ๋ก๋ ์คํ์๋ฉํธ๋ฆญ ํ๋ ฌ์ ๋ฒกํฐ๋ก ๋ค์ ๋ณํํ๋ ์ฐ์ฐ์ โveeโ ์ฐ์ฐ์ด๋ผ๊ณ ํํ ๋ถ๋ฅธ๋ค. $\vee$ ๊ธฐํธ๋ก ์ด๋ค.
- ๊ทธ๋ฌ๋ฉด $J_i = \frac{\partial \texttt{vee}(\textbf{log}({ (\mathbf{R}^{(t)} \cdot (\textbf{I} + [\delta\boldsymbol{\theta}]_{\times})) }^\top \cdot \mathbf{R}_{i}))}{\partial \delta\boldsymbol{\theta}}$ ์ ๊ฐ์ด ๋ค์ ์ธ ์ ์๋ค.
- ํธ๋ฆญ 3
- $(AB)^\top = B^\top \cdot A^\top$ ์ ์ด์ฉํด์, $\textbf{log}(\cdot)$ ์์ ์์ ์ ๋ฆฌํ๋ฉด
- $\left( \mathbf{R}^{(t)} \cdot (\mathbf{I} + [\delta\boldsymbol{\theta}]_\times) \right)^\top = (\mathbf{I} + [\delta\boldsymbol{\theta}]_\times)^\top \cdot (\mathbf{R}^{(t)})^\top$ ๊ฐ ๋๋ค.
- ํธ๋ฆญ 4
- skew-symmetric matrix์ ์ ์๋ฅผ ์ฌ์ฉํ๋ฉด, $([\delta\boldsymbol{\theta}]_\times)^\top = -[\delta\boldsymbol{\theta}]_\times$ ์ด๋ค.
- ๊ทธ๋ฆฌ๊ณ $(A + B)^\top = A^\top + B^\top$ ์ด๋ฏ๋ก
- ์์ ํ $\left( \mathbf{R}^{(t)} \cdot (\mathbf{I} + [\delta\boldsymbol{\theta}]_\times) \right)^\top = (\mathbf{I} + [\delta\boldsymbol{\theta}]_\times)^\top \cdot (\mathbf{R}^{(t)})^\top$ ์ $ = (\mathbf{I} - [\delta\boldsymbol{\theta}]_\times) \cdot (\mathbf{R}^{(t)})^\top$ ๊ฐ ๋๋ค.
- ์ด์ ๊ทธ๋ฌ๋ฉด residual ์์ $e_i(\delta\boldsymbol{\theta}) = \textbf{Log}\left( (\mathbf{I} - [\delta\boldsymbol{\theta}]_\times) \cdot (\mathbf{R}^{(t)})^\top \cdot \mathbf{R}_i \right)$ ๊ฐ ๋๋ค.
- ํธ๋ฆญ 5
- ์ฌ๊ธฐ์ $\mathbf{E} = (\mathbf{R}^{(t)})^\top \cdot \mathbf{R}_i$ ๋ผ๊ณ ํ ๋,
- ์ต์ ํ ๊ณผ์ ์์ ํ์ฌ ์ถ์ ์น $\mathbf{R}^{(t)}$๋ ์ธก์ ์น $\mathbf{R}_i$์ ๊ทผ์ ํ๋ฏ๋ก $\mathbf{E}$๋ ๋จ์ ํ๋ ฌ์ ๊ทผ์ ํ๋ค.
- ์ฆ, $\mathbf{E} \sim \mathbf{I}$ ๋ผ๊ณ ํ ์ ์๋ค.
- ๋ฐ๋ผ์:
- $e_i(\delta\boldsymbol{\theta}) = \textbf{Log}\left( (\mathbf{I} - [\delta\boldsymbol{\theta}]_\times) \cdot \mathbf{E} \right) = \texttt{vee}(\textbf{log}\left( (\mathbf{I} - [\delta\boldsymbol{\theta}]_\times) \cdot \mathbf{E} \right)) = \texttt{vee}(\textbf{log}\left( (\mathbf{I} - [\delta\boldsymbol{\theta}]_\times) \right))$ ๋ก ๊ทผ์ฌํ ์ ์๋ค.
- ํธ๋ฆญ 5
- ํ ์ผ๋ฌ ์ ๊ฐ๋ฅผ ์ด์ฉํ์
- $\textbf{log}(\mathbf{I} + \mathbf{A}) = \mathbf{A} - \frac{1}{2}\mathbf{A}^2 + \frac{1}{3}\mathbf{A}^3 - \cdots$ ์ด๋ค.
- 2์ฐจ ํญ ์ด์์ ์์ผ๋ฏ๋ก ๋ฌด์ํ๋ฉด,
- $\textbf{log}\left( (\mathbf{I} - [\delta\boldsymbol{\theta}]_\times) \right) \sim - [\delta\boldsymbol{\theta}]_\times$ ์ด๋ค.
- ๊ฒฐ๋ก
- ๋ฐ๋ผ์ $J_i = \frac{\partial e_{i}(\delta \boldsymbol{\theta})}{\partial \delta\boldsymbol{\theta}} = \frac{\partial \textbf{Log}({(\mathbf{R}^{(t)} \oplus \delta\boldsymbol{\theta})}^\top \cdot \mathbf{R}_{i})}{\partial \delta\boldsymbol{\theta}} = \frac{\partial \texttt{vee}(\textbf{log}\left( (\mathbf{I} - [\delta\boldsymbol{\theta}]_\times) \right))}{\partial \delta\boldsymbol{\theta}} = \frac{\partial \texttt{vee}(- [\delta\boldsymbol{\theta}]_\times)}{\partial \delta\boldsymbol{\theta}} = \frac{\partial \texttt{unskew}(- \texttt{skew}(\delta\boldsymbol{\theta}))}{\partial \delta\boldsymbol{\theta}} = \frac{\partial (- \delta\boldsymbol{\theta})}{\partial \delta\boldsymbol{\theta}} = -\mathbf{I} $ ๊ฐ ๋๋ค.
- ps. $\texttt{vee}$ ์ $\texttt{unskew}$ ๋ ๊ฐ์ ํํ์ด๋ค. skew ์์ ์ ์ญ์ผ๋ก ํด์ค๋ค๋ ์๋ฏธ์์ ์ฝ๋์์๋ unskew ๋ผ๊ณ ์ ๋๊ฒ ์ข ๋ ์ดํด๊ฐ ์ฌ์์ ๊ทธ๋ ๊ฒ ํํํด๋ณด์๋ค. ๋ง์ฐฌ๊ฐ์ง๋ก $[\cdot ]_\times$ ๋ผ๋ ํํ๋ณด๋ค๋ $\texttt{skew}$ ๋ผ๊ณ ์ ์ผ๋ฉด ์ข ๋ ์ง์ด ๋ง๋ ๋ฏํ ๋๋์ด๋ค (์ฝ๋ ๋ ๋ฒจ์์ ๋ ์ข์ ๊ฐ๋ ์ฑ ๋ณด์ ๊ฐ๋ฅ).
- ๋ฐ๋ผ์ $J_i = \frac{\partial e_{i}(\delta \boldsymbol{\theta})}{\partial \delta\boldsymbol{\theta}} = \frac{\partial \textbf{Log}({(\mathbf{R}^{(t)} \oplus \delta\boldsymbol{\theta})}^\top \cdot \mathbf{R}_{i})}{\partial \delta\boldsymbol{\theta}} = \frac{\partial \texttt{vee}(\textbf{log}\left( (\mathbf{I} - [\delta\boldsymbol{\theta}]_\times) \right))}{\partial \delta\boldsymbol{\theta}} = \frac{\partial \texttt{vee}(- [\delta\boldsymbol{\theta}]_\times)}{\partial \delta\boldsymbol{\theta}} = \frac{\partial \texttt{unskew}(- \texttt{skew}(\delta\boldsymbol{\theta}))}{\partial \delta\boldsymbol{\theta}} = \frac{\partial (- \delta\boldsymbol{\theta})}{\partial \delta\boldsymbol{\theta}} = -\mathbf{I} $ ๊ฐ ๋๋ค.
๊ตฌํ
- ์ง๊ธ๊น์ง e ์ J๋ฅผ ๊ตฌํ๋ค.
- ๋ฐ๋ผ์ ์ฝ๋๋ ๋ฒจ์์๋ ๋ค์๊ณผ ๊ฐ๋ค. ๋งค์ฐ ๊ฐ๋จํ๋ค.
# Initialized at the first step's solution R_optimal = ... # e.g., = R1 # Gauss-newton update for i in range(max_iters): H = np.zeros((3, 3)) b = np.zeros(3) # gather measurements for R_i in [R1, R2, R3]: e_i = unskew(log(np.dot(R_optimal.T, R_i))) J_i = -1 * np.eye(3) H += J_i.T @ J_i b += J_i.T @ e_i # solve the normal equation H * dtheta = -b dtheta_optimal = np.linalg.solve(H, -b) # check termination condition (convergenceness) print(f"iter {i}: dtheta: {dtheta}") if np.linalg.norm(dtheta) < tolerance: print(f"The solution converged. terminate the GN opt at iteration {i}\n") break # update the solution R_optimal = R_optimal @ Exp(dtheta_optimal) # (optional) ์ ๋ฐ์ดํธ ํ SO(3) ๊ฐ ์ ์๋ฅผ ๋ง์กฑํ๋๋ก ๊ฐ์ (make det = 1) U, _, Vt = np.linalg.svd(R0) R0 = np.dot(U, Vt) if np.linalg.det(R0) < 0: U[:, -1] *= -1 R0 = np.dot(U, Vt)
๊ฒฐ๋ก
- ์ฝ๋์์ ๋ง์ง๋ง์
# update the solution
๋ถ๋ถ์์, tangent space์์ ์ป์ ์ต์ ์กฐ๊ธ์์ง์ ๊ฐ์ ์๋ rotation์ ์ฒจ๊ฐํด์ฃผ๋ ๊ฒ์ โretractโ operation ์ด๋ผ๊ณ ๋ถ๋ฅธ๋ค. ์ ์ฒด ๊ณผ์ ์ lift-solve-retract pipeline ์ด๋ผ๊ณ ๋ถ๋ฆฌ๊ธฐ๋ ํ๋ค. ์์ ํฌ์คํธ ์์ ์ธ๊ธํด๋์์. - 2016 T-RO Paper ์ธ On-Manifold Preintegration for Real-Time Visual-Inertial Odometry ์ ๋ณธ์ง๋ ์ฌ์ค ์ด๊ฒ์ด ์ ๋ถ์ด๋ฉฐโฆ ์ซ ํ์๊ฐ ์๊ฒ ๋ค.
- ๊ฒฐ๋ก ์ ์ผ๋ก ๊ฐ๋จํ measurement 3๊ฐ ์ง๋ฆฌ rotation averaging ์ด๋ผ๋ task๋ฅผ ์ง์ from-scratch ๋ถํฐ ๊ตฌํํด๋ด์ผ๋ก์จ, ๊ฒฐ๋ก ์ ์ผ๋ก๋ ์ต์ visual inertial odometry ๋ฐฉ๋ฒ๋ ์ด๋ก ์ ์ผ๋ก๋ ๊ฐ๋ค๋ ์ด์ผ๊ธฐ๋ฅผ ํ๊ณ ์ถ์๋ค.
์ค์ต
- ์ค์ต ์ฝ๋๋ ์ฌ๊ธฐ (main_onmanifold_ganussnewton.py) ์ ์๋ค. (๋ํ๋์๋ ์ ๋ช ํ numpy ์ matplotlib ์ด๋ฏ๋ก ๋ณ๋ ๋์ปคํ๊ฒฝ ์ค์ ์ ์๋ตํ๊ณ ์ค์ตํด๋ณด์.)
- GN ์ต์ ํ ๊ณผ์ ์์ weight ๋ฅผ ๊ณ ๋ คํ update ์์๋ฅผ ๊ตฌํํด๋ณด์. ์๋ฅผ ๋ค์ด์ 3๊ฐ์ measurement ์ค ํ๋๋ฅผ ํนํ ๋ ์ ๋ขฐํ๊ณ ์ถ๋ค๋ฉด?
- ์ด๋ฅผ ๋ ํ์ฅํ๋ฉด outlier robust rotation averaging ๊น์ง ์ค์ตํด๋ณผ ์ ์๊ฒ ๋ค. ์ฌํ outlier ๋ฅผ ํฌํจํ, 100๊ฐ์ measurement ์ธ ๊ฒฝ์ฐ๋ก ํ๋ํด๋ณด์.