1. Introduction to ROVIO
ROVIO는 RObust Visual Inertial Odometry의 약자로 ETHZ의 ASL 연구실의 Bloesch et al.이 제안한 VIO 알고리즘이다. IROS 학회에 2015년에 처음 발표되었으며 이후 IJRR에 2017년 자세한 설명을 포함한 저널이 게재되었다. ROVIO는 MSCKF와 더불어 대표적인 필터링 기반 Tightly-coupled VIO이다. MSCKF와 가장 큰 차이점은 밝기 오차(photometric error)를 IEKF의 Update 과정에 사용한다는 점이다. 이를 통해 실시간 성능의 가벼우면서도 모션블러 및 텍스쳐가 적은 환경에 강인한 알고리즘을 제안하였다.
1.1. Loosely-coupled VIO vs Tightly-coupled VIO

Loosely-coupled VIO는 카메라와 IMU의 센서 데이터에서 각각 pose를 추출한 후 이를 퓨전하는 방법을 말한다. Pose를 추출한 후 퓨전하기 때문에 비교적 알고리즘 구성이 단순하지만 정확도가 낮다는 단점이 있다.

이와 달리, tightly-coupled VIO는 카메라와 IMU의 센서 데이터를 모은 후 한 번에 pose를 추출하는 방법을 말한다. Tightly-coupled VIO는 pose를 구하는 구체적인 방법에 따라 필터링 방법과 최적화 방법으로 패러다임이 나뉜다. Loosely-coupled VIO에 비해 정확도가 높지만 연산량이 많다는 단점이 있다.
1.2. Filtering-based vs Optimization-based
필터링 기반(Filtering-based) 방법은 EKF를 사용하여 IMU와 카메라를 퓨전하는 방법을 말한다. 일반적으로 IMU는 prediction 스텝에 사용되고 카메라는 update 스텝에 사용된다. 대표적인 논문으로는 MSCKF(07'), ROVIO(15'), S-MSCKF(18') 등이 있으며 이 중 MSCKF는 Google Tango(16') 프로젝트에 사용되어 실제 기기에 사용되었다. 필터링 기반 방법은 최적화 기반 방법 대비 연산량이 비교적 작다는 장점이 있어 소형 임베디드 기기에 활용하기 적합하다. 하지만 incremental하게 상태를 추정하기 때문에 상대적으로 최적화 기반 방법 대비 정확도가 낮은 편이다.
최적화 기반(Optimization-based) 방법은 비선형 최적화 방법을 사용하여 IMU와 카메라를 퓨전하는 방법을 말한다. 2010년대초 IMU preintegration 기법이 개발되면서 본격적으로 최적화 기반의 VIO들이 많이 개발되었다. 대표적인 알고리즘으로는 OKVIS(15'), VINS-mono(17'), VI-DSO(18'), ORB-SLAM3(20') 등이 있다. 최적화 방법은 필터링 방식에 비해 정확도가 높은 편이지만 연산량이 상대적으로 많다는 단점이 존재한다.
1.3. Representation of 3D rotations
ROVIO에서는 물체의 회전을 표현하기 위해 SO(3)군을 사용한다. 이 때, 유의할 점은 SO(3)군이 회전 행렬이나 쿼터니언을 특정하는 것이 아닌 순수하게 두 좌표계 사이의 회전을 표현하는 집합(또는 군)을 사용한다는 것이다. 이러한 순수 회전을 의미하는 SO(3)군은 Quaternion kinematics for the error-state Kalman filter 내용 정리 포스팅의 2.2 섹션에서 자세히 설명하고 있다. 또는 저자의 다른 논문인 [5]를 참조하면 된다. 회전 행렬로 표현된 SO(3)군에 대한 설명은 리군 이론(Lie Theory) 개념 정리 포스팅의 SO(3) 섹션을 참조하면 된다.
따라서 논문에서는
임의의 벡터
- 위 식은 복잡해보이지만
1.4. Representation of 3D unit vectors
ROVIO에서는 단위 크기를 가진 bearing vector
-
-
-
여기서 주의할 점은 [2]의 3.3 섹션을 설명할 때는

위 식에서 편미분되는 부분은

즉, 실제 편미분 되는 식은

1.5. Robocentric representation

ROVIO의 저자는 fully robocentric 표현법을 사용하여 시스템의 상태를 표현한 것이 논문의 핵심 contribution이라고 하였다. Robocentric 표현법이란 IMU의 위치, 속도, 특징점의 좌표를 월드 좌표계
World-centric
IMU 측정값이 들어오면 이를 통해 위치의 증분량을 계산한 후 월드 좌표계로 변환하는 연산
Robocentric
IMU 측정값이 들어오면
특징점에 대한 bearing vector
1.6. Bearing vector and inverse depth

ROVIO에서는 3차원 공간 상의 점
-
역깊이
임의의 3차원 공간 상의 점
이미지 좌표계
2. Multilevel patches and photometric error

ROVIO는 피라미드 이미지에서 패치를 추출하여 동일한 패치 크기(6x6 또는 8x8)에서도 다양한 영역의 정보를 포함할 수 있도록 하였다. 이미지 패치를 사용하여 순차적인 이미지 사이의 밝기 오차(photometric error)를 innovation term으로 설정하였다.
2.1. Photometric error

l 번째 피라미드 이미지에서 패치의 j번째 점에 대한 밝기 오차
-
-
-
-
위 그림에서 왼쪽 이미지는 t-1 시간의 이미지이고 오른쪽 이미지는 t 시간의 이미지라고 하자. t-1 이미지에서 특징점

-
-
2.2. QR decomposition of matrix
자코비안 행렬

QR 분해는 임의의 행렬을 직교(orthogonal) 행렬
따라서 위와 같이 블록 행렬 곱에 의해
이후 양 변에
ROVIO에서는 위 식을 IEKF Update 스텝의 innovation term으로 사용한다.
-
-
Innovation term의 자코비안 행렬
3. Iterated EKF
Kalman Filter
Kalman filter(KF)는 선형 동적 시스템에 대한 상태

Extended Kalman Filter
만약 상태변수

Iterated Extended Kalman Filter
Iterated EKF(IEKF)는 EKF의 선형화 오차 단점을 극복하기 위해 update 스텝에서 상태 변수

3.1. IEKF formulation
비선형 항을 포함한 상태변수
-
-
-
3.2. Prediction step
ROVIO는 IMU 입력이 들어오면 prediction 스텝을 진행한다. 일반적으로 IMU는 고속(~1000hz)로 들어오기 때문에 실시간 성능을 유지하기 위해 일정 시간동안 IMU 값들을 저장한 다음 한 번에 병합(merge)하여 처리하는 방식을 기본값으로 사용한다.
이전 k-1 스텝에서 posterior 평균과 공분산
이 때, 자코비안
3.2.1. State propagation

ROVIO에서 IEKF의 상태 변수
-
-
-
-
-
-
-
-
-
-
IEKF prediction 스텝의 모션 모델
-
-
-
-
IMU에서 측정되는 가속도
따라서 실제 가속도와 각속도는 다음과 같이 구할 수 있다.
State equation in discrete time
지금까지 유도한 식을 컴퓨터로 구현하기 위해서는 연속 시간(continuous time)을 이산 시간(discrete time)으로 변환하여 차분 방정식으로 표현해야 한다. 미분 방정식에 대한 수치 해법은 euler, midpoint, RK4 등 여러 방법이 있으나 ROVIO에서는 euler 방법을 통해 이산화하였다.
-
-
위 식은 ROVIO 코드 중 IMUPrediction::evalPrediction() 메소드에 구현되어 있다. 최종적으로 위 식을 통해 이전 k-1 스텝의 posterior 평균
Jacobian
자코비안 행렬
각각의 행열마다 의미하는 상태는 다음과 같다. 이외에

위 식은 ROVIO 코드 중 IMUPrediction::jacPreviousStateI() 메소드에 구현되어 있다.
3.3. Update step
ROVIO는 카메라에서 이미지 입력이 들어올 때마다 update 스텝을 수행한다. Prediction 스텝에 의해 propagation된 상태 변수
-
-
EKF는 위 식을 최소화하는
-
-
-
위 식을 미분하여 0으로 설정 후 전개하면 다음과 같은 식을 얻을 수 있다.
색상을 추가하여 시각적으로 잘 보이도록 표현하면 아래와 같다.

위 식을 변화량
4. Landmark management
IEKF 프레임워크는 앞서 말한 것처럼 특징점(=landmark)의 개수에 따라 연산량이 기하급수적으로 증가하기 때문에 실시간 성능을 확보하기 위해서는 특징점의 개수를 잘 관리해야 한다.
4.1. Detection and scoring
이미지 패치를 위한 특징점은 다음과 같은 과정에 의해 탐지된다.
- 새로운 이미지 패치를 위한 특징점을 추출할 때는 잘 알려진 FAST Detector를 사용한다
- 현재 트래킹하고 있는 특징점과 가까운 점들은 제거한다
- 식 (
)에서 는 hessian 행렬 를 의미한다. 에 대한 eigenvalue를 구해보면 가 나오는데 이 값들의 크기에 따라 이미지 패치가 평면인지, 엣지인지, 코너인지 판단할 수 있다.
- 식 (
- Shi-Tomasi Score를 사용하여 해당 점이 평면인지, 엣지인지, 코너인지를 스코어링한다.
- 이 때, 모든 피라미드 이미지에 대해 모두 점수를 계산한다.

3. 과정에서 스코어를
4.2. Tracking and pruning
특징점은 탐지하는 과정 뿐만 아니라 탐지된 이후에도 지속적으로 트래킹할 것인지 여부를 결정한다.

-
트래킹하고 있는 특징점의 공분산이 큰 경우 (e.g., 방금 탐지된 특징점), 한 패치 내에서 여러 점들을 동시에 트래킹한다. 공분산 ellipse 내에 있는 여러 점들을 동시에 IEKF Update 과정을 통해 반복적으로 업데이트한다
-
여러 점들 중 절반 이상 Innovation Term 값이 변하지 않는다면 해당 특징점을 제거한다
- 추가로 Heuristic Quality Score를 계산하여 점수가 Threshold보다 작으면 해당 특징점을 제거한다. Threshold 또한 전체 특징점 개수를 고려하여 Adaptive하게 변형한다.
- 1) Global Quality: 처음 탐지된 순간부터 얼마나 자주 트래킹 되는가
- 2) Local Quality: FOV 시야 안에 들어왔을 때 얼마나 자주 트래킹되는가
- 3) Local Visibility: FOV 시야 안에 얼마나 자주 보이는가
- 1) Global Quality: 처음 탐지된 순간부터 얼마나 자주 트래킹 되는가

5. Overall flowchart
필자가 생각하는 ROVIO의 알고리즘 흐름도는 다음과 같다.

6. Derivation of state propagations
본 섹션에서는 (
6.1. Derivation of
(
-
-
ROVIO에서는 회전에 대한 표현을 SO(3)군

다음으로 속도

6.2. Derivation of

먼저
-
-
-
위 식은 그림에서 보는것과 같이 3차원 공간 상에 고정된 특징점(또는 랜드마크)가 주어졌을 때 이를 관성 좌표계
좌측 항은 고정된 특징점이므로
-
-
-
-
각각의 수식은 다음과 같이 유도할 수 있다.

지금까지 유도한 수식을 모두 통합하여 (
위 식의 양 변의 왼쪽에
자세한 유도 과정의 그림을 아래 첨부하였다.


6.3. Derivation of discrete
본 섹션에서는 (

7. Code review
ROVIO 코드의 클래스 간 상관 관계는 다음과 같이 구성되어 있다.

8. References
[3] ROVIO analysis document by Steven Cui
[4] A Quick Guide for the Iterated Extended Kalman Filter on Manifolds by Jianzhu Huai, Xiang Gao
[5] A Primer on the Differential Calculus of 3D Orientations, M. Bloesch et al., 2016, arXiv
'Engineering' 카테고리의 다른 글
[SLAM] FAST-LIO2 논문 리뷰 (+ IKF, ikd-tree) (39) | 2024.04.17 |
---|---|
[SLAM] VINS-mono 논문 리뷰 (+ IMU preintegration) (23) | 2022.10.15 |
[MVG] Stereo Camera Calibration 예제코드 및 설명 (C++) (3) | 2022.07.14 |
[MVG] Scene Plane-based Homography 예제코드 및 설명 (C++) (0) | 2022.07.07 |
[MVG] Vanishing Point-based Metric Rectification 예제코드 및 설명 (C++) (0) | 2022.07.03 |