SLAM Engineer

๐ŸŒˆ From-scratched Pose-graph SLAM Tutorial: 1ํŽธ


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.
      • ์ด ๋…ผ๋ฌธ์„ ์ธ์šฉํ•œ ๋…ผ๋ฌธ๋“ค ์ค‘ ์ธ์šฉ์ˆ˜๊ฐ€ ๋งŽ์€ ๊ฒƒ์„ ๋ณด๋Š” ๊ฒƒ ๋˜ํ•œ ๋„์›€์ด ๋˜๊ฒ ๋‹ค.
  • ์™œ ํ•„์š”ํ•œ๊ฐ€?
    • ๋Œ€๋ถ€๋ถ„์˜ 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) ๊ฐ’์„ ๊ตฌํ•ด์„œ, ๋กœ๋ด‡์˜ ์ž์„ธ๋Š” ์ด๊ฒƒ์ด์•ผ! ๋ผ๊ณ  ๋งํ•ด์•ผ ํ• ํ…๋ฐ,
        • ๊ทธ ๊ฒฐ๊ณผ๋Š” ํŒŒ๋ž‘์ƒ‰ ์ถ•์ด๋‹ค.
        • ์ผ๋‹จ ์‚ฌ๋žŒ์ด ์‹œ๊ฐ์ ์œผ๋กœ ๋ณด์•˜์„ ๋•Œ ๋ง์ด ๋งž๋Š” ๊ฒƒ ๊ฐ™์•„๋ณด์ธ๋‹ค. ํŒŒ๋ž‘์ด ์„ธ ์ถ• ๋ชจ๋‘์—์„œ, ๋‹ค๋ฅธ ์…‹ ๋“ค์˜ ์ค‘๊ฐ„ ์ฆˆ์Œ์— ์œ„์น˜ํ•˜๋Š” ๊ฒƒ์„ ์ž˜ ๋ณผ ์ˆ˜ ์žˆ๋‹ค.
      • ์–ด๋–ป๊ฒŒ ๊ตฌํ˜„ํ–ˆ๋Š”์ง€ ์ด์ œ ์ฐจ์ฐจ ์„ค๋ช…์„ ํ•ด๋ณด์ž.
    On-manifold Gauss-Newton Result

๋ฐฐ๊ฒฝ์ง€์‹ 1

  • ์ผ๋‹จ iterative optimization ์˜ ๊ธฐ๊ณ„์ ์ธ ๊ณผ์ •์€ ์•„๋ž˜์™€ ๊ฐ™๋‹ค (์ด๊ฑธ ๋‚˜๋Š” ๊ฐœ์ธ์ ์œผ๋กœ โ€˜๊ธฐ๊ณ„์ ์ธ ๊ณผ์ •โ€™ ์ด๋ผ๋˜๊ฐ€, โ€˜์‚ฐ์ˆ˜โ€™ ๋ผ๋˜๊ฐ€, โ€˜๊ณ„์‚ฐ๊ธฐโ€™๋ผ๊ณ  ๋ถ€๋ฅธ๋‹ค. ์ฆ‰, ์–ด๋ ต์ง€ ์•Š๋‹ค๋Š” ๋ง์ด๋‹ค).
    GN Manifold Diagram
  • ์—ฌ๊ธฐ์„œ $\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์ด๊ธฐ ๋•Œ๋ฌธ์ด๋‹ค.
    • ์›๋ž˜์˜ 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 ์˜ ์™ผ์ชฝ๊ณฑ์ด ๋˜๋Š”์ง€ ๊นŒ์ง€ ์—ฌ๊ธฐ์„œ ์„ค๋ช…ํ•˜์ง€๋Š” ์•Š๋Š”๋‹ค..
  • ์•ž์„œ ์šฐ๋ฆฌ์˜ 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 ์„ ํ•ด์ค€๋‹ค ๋ผ๊ณ  ์ดํ•ดํ•˜๋ฉด ๋œ๋‹ค.
  • $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}$ ๋ผ๊ณ  ์ ์œผ๋ฉด ์ข€ ๋” ์ง์ด ๋งž๋Š” ๋“ฏํ•œ ๋Š๋‚Œ์ด๋‹ค (์ฝ”๋“œ ๋ ˆ๋ฒจ์—์„œ ๋” ์ข‹์€ ๊ฐ€๋…์„ฑ ๋ณด์œ  ๊ฐ€๋Šฅ).

๊ตฌํ˜„

  • ์ง€๊ธˆ๊นŒ์ง€ 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 ์ธ ๊ฒฝ์šฐ๋กœ ํ™•๋Œ€ํ•ด๋ณด์ž.