4. Keyframes
4.1. Inverse Depth Update
To be added
4.2. Immature Point Activation
To be added
4.3. Sliding Window Optimization
4.3.1. Error Function Formulation

특정 프레임이 키프레임으로 결정되면 sliding window 내부의 키프레임들과 새로운 키프레임 사이에 에러함수를 업데이트해야 한다. 이 때, 키프레임 뿐만 아니라 이와 연결되어 있는 맵 상의 포인트들까지 같이 최적화하는 Local Bundle Adjustment (LBA)를 수행한다.

주목할 점은 하나의 맵포인트가 두 개의 키프레임(host, target)과 연결되어 최적화된다는 점이다. 여기서 host 키프레임은 해당 맵포인트를 가장 먼저 발견한 키프레임이고 target 키프레임은 이후에 발견한 키프레임을 의미한다.

또한 최적화 과정에서 연산량을 줄이기 위해 Jacobian을 계산할 때 카메라의 월드좌표계를 기준으로 계산한 Jacobian
sliding window optimization을 수행하기 위해 우선 에러함수를 설정해야 한다. 이 때, 에러함수의 파라미터는 pose(6) + photometric(2) + camera intrinsic(4) + idepth(N)로써 총 12+N개의 파라미터가 최적화에 사용된다. 참고로 Initialization 과정에서는 camera intrinsic(4)를 제외한 8+N개의 파라미터가 최적화되었다. 즉, camera intrinsic (

에러(residual)은 다음과 같이 설정할 수 있다.
-

이 때, residual은 한 점이 아닌 8-point patch 점들의 에러 합을 의미한다. 최종적으로 huber norm까지 적용된 에러함수는 다음과 같다.
해당 에러함수가 최소가 되는 파라미터를 찾기 위해
에러함수
-
-
-
-
Initialization 과정과 달리 에러함수
idepth(N)
pose(6)
photometric(2)
하지만 sliding window optimization 과정에서는 추가적으로 Jacobian of Camera Intrinsic
4.3.2. Derivate Jacobian of Camera Intrinsics

이 때,
그리고
다음 순서로
따라서
위 식을 사용하여
최종적으로
Camera Intrinsic(4)
4.3.3. First Estimate Jacobian (FEJ)
sliding window optimization을 수행하면 매 iteration 마다 state variable
-

-
-
-
-
DSO에서는 LBA를 수행할 때마다 6번의 최적화를 수행하는데 만약 매 iteration마다 Jacobian을 새로 계산하면 다음과 같은 단점이 존재한다. (자세한 내용은 https://blog.csdn.net/heyijia0327/article/details/53707261 참조)
1. 연산량이 매우 증가하므로 실시간 성능을 보장할 수 없다.
2. 서로 다른 state의 Jacobian을 한 시스템에서 같이 사용하는 경우 성능의 저하를 일으킬 가능성이 존재한다.
따라서 LBA를 수행할 때 매 iteration마다(marginalization 포함) 업데이트로 인해 state variable
1. LBA를 시작하기 전에 현재
2. LBA를 수행하면서 매 iteration마다 업데이트 값을 누적시킨다.
3. 매 iteration동안 Jacobian은
4. LBA iteration이 끝난 경우 현재 상태에서 누적된 증분량을 업데이트한다.
4.3.4. Adjoint Transformation

앞서 설명한 것과 같이 DSO에서는 하나의 맵포인트에 2개의 키프레임(host, target)이 연결되어 있다. 이에 따라 최적화 수행 시 연산량을 줄이기 위해 target, host 키프레임 사이의 상대 포즈를 기반으로 계산한 Jacobian
https://www.cnblogs.com/JingeTU/p/8306727.html 참조)
(+23.11.6 SLAMUS님의 수식 오류 지적으로 내용을 수정하였습니다.
-
-
-
-
host
target
이 때, twist의 변화량은 다음과 같이 계산할 수 있다.
여기서
구체적으로
다음으로
derivative of host
derivative of target
4.3.5. Marginalization
To be added
4.3.6. Solving the Incremental Equation
DSO에서는 sliding window 내부에 항상 8개의 키프레임을 유지하면서 12+N개의 파라미터를 최적화한다. (Pose(6) + Photometric(2) + Camera Intrinsics(4) + Idepth(N)). 이렇게 특정 윈도우 내의 키프레임 포즈와 맵포인트를 동시에 최적화하는 방법을 Local Bundle Adjustment (LBA)라고 한다. 이전 섹션에서 유도한 LBA의 에러함수는 다음과 같고 이 때, state variable
-
-
-
-
-
해당 에러함수를 이용해 least squares optimization 형태로 나타내면 최종적으로 다음과 같은 형태의 식이 유도된다. 해당 식의 유도는 Initialization 챕터에서 다뤘기 때문에 생략한다.
-
이 때, Hessian Matrix

Schur Complement 섹션에서 설명한 것처럼
Details of H and b matrix
H_yy
-
H_rho_rho, H_rho_y, H_y_rho
이 된다. 이를 자세하게 전개하면 다음과 같다.
4.4. Null Space Effect Elimination
4.4.1. Ambiguity Problems

DSO는 단안카메라를 활용한 Visual Odometry이므로 맵포인트의 깊이를 정확하게 알 수 없는 scale ambiguity 문제를 가진다. 예를 들면, 내가 현재 실제 도시의 이미지를 보고 있는 것인지 도시의 미니어쳐 이미지를 보고 있는 것인지를 단안카메라만 사용하서는 정확하게 알 수 없다는 의미이다. 즉, 카메라의 trajectory와 모든 맵포인트들을 일괄적으로 키우거나 줄여도 최적화 단계에서 아무런 영향을 미치지 않는다.

또한 모든 카메라 포즈들과 맵포인트에 동일한 SE(3) 변환을 적용하면 이 또한 최적화 단계에서 아무런 영향을 미치지 않는다. 이를 coordinate system ambiguity 문제라고 한다. (자세한 정보는 https://blog.csdn.net/wubaobao1993/article/details/105106301 참조)
4.4.2. Null Space
null space란 정방행렬
일반적으로 Gauss-Newton (GN) 방법을 사용할 때 다음과 같은 공식을 풀어야 하는 상황이 발생한다.
-
-
-
만약
우선 비동차방정식(non-homogeneous equation)에서 특수해
다음으로 동차방정식(homogeneous equation)에서 일반해
따라서
여기서 null space는
null space는 전체 방정식의 값에 영향을 미치지 않으므로 null space의 선형결합인
4.4.3. Null Space in DSO

null space는 시스템(=에러함수)

예를 들어 위 그림과 같이 LBA를 통해 업데이트 값
프로젝션 행렬
결론적으로 다음과 같이 최적의 업데이트 값
4.4.4. Detailed Derivation of Null Space in DSO
프로젝션 행렬을 사용하지 않고 다른 방법으로 유도하면 다음과 같다. 우선 최적의 업데이트 값
null space가 에러함수의 값에 영향을 미치지 않는다는 점을 사용하면 다음 공식이 성립한다.
위 공식의 두 에러함수를 1차 테일러 전개하여 정리하면 다음과 같이 나타낼 수 있다.
따라서 공통부분을 소거한 후 다시 정리하면 다음과 같은 공식이 성립하고
여기서 null space의 선형결합에 해당하는
따라서 남은 식들을 정리하면 다음 공식이 성립한다.
하지만 위 공식은 실제로 서로 일치하지 않으므로 이를
결론적으로 다음과 같이 최적의 업데이트 값
null space 영향이 제거된
따라서 최종적으로 다음의 연산을 통해 null space의 영향을 제거할 수 있다.
5. Pixel Selection
5.1. Make Histogram

ORB-SLAM2와 같은 feature-based VO의 경우 이미지 내에서 특정 포인트를 추출할 때 feature extraction 알고리즘을 사용하여 키포인트를 추출한다. 그 다음 해당 키포인트를 3차원 점으로 Unprojection

하지만 direct method를 사용하는 DSO는 키포인트를 추출하는 과정없이 특정 픽셀의 밝기 오차를 계산하기 때문에 특정 포인트를 추출하는 방법 또한 feature-based와 달라지게 된다. DSO에서는 이미지에서 특정 포인트를 추출하기 위해 gradient histogram과 dynamic grid 방법을 사용했다. 해당 방법은 DSO 논문에서도 자세한 설명이 부족하고 참고 논문이 없으며 구글링해도 나오는 정보가 거의 없으므로 해당 섹션에서 다루는 내용이 100% 정확하다고 볼 수 없다. 해당 내용은 논문을 볼 때 참고용으로 보면 좋을 것 같다.

1. 우선 새로운 이미지가 들어오면 gradient histogram을 생성하기 위해 이미지를 32x32 영역으로 나눈다. (grayscale)
2. 하나의 영역을 확대해서 보면 아래 그림과 깉이 여러 픽셀들로 구성되어 있고 각 픽셀마다 고유의 밝기 값을 가지고 있다. 이를 이용해 image gradient (dx,dy)를 구할 수 있고 해당 영역에 대한 히스토그램을 만들 수 있다.

3. 이 때, gradient
bin은 위와 같은 범위를 가지지만 이를 1~50 범위로 제한하여 50이 넘는 경우 최대값을 50으로 설정하여 히스토그램의 범위를 단순화했다.

4. 이러한 히스토그램을 32x32 모든 영역에 대해 계산한다.


5. 히스토그램에서 total count의 50%가 되는 bin 값을 1-50 순서대로 찾는다. 예를 들어, 히스토그램의 모든 bin에서 총 1000개가 카운트되었다면 1번 bin부터 순서대로 카운트 값을 빼주면서 해당 값이 500보다 작아지는 bin을 threshold로 설정한다. 또한, 주변 3x3 영역의 threshold 평균을 사용한 smoothed threshold 값 또한 설정한다.
5.2. Dynamic Grid

한 이미지에 대한 32x32 히스토그램을 생성하고 threshold 값을 설정하였으면 다음으로 dynamic grid 방법을 통해 이미지 내에서 픽셀을 선택한다. 이를 통해 high gradient 영역에 대부분의 포인트가 추출되는 것을 방지하고 한 이미지 내에서 추출할 수 있는 총 포인트의 개수(N=2000)을 관리할 수 있다.
1. 하나의 grid 영역의 크기를 설정한다. DSO는 초기값으로 12x12 [pixel]을 사용했다. 640x480 이미지 기준으로 봤을 때 일반적으로 32x32 histogram 영역보다 작은 크기를 사용한다. grid 크기를 설정하였으면 이미지 전체를 grid로 나눈다.
2. 한 grid 영역을 확대해보면 아래와 같다. 이 때, 한 영역에서 총 3개의 피라미드 이미지의 gradient를 사용한다. Alalagong님의 자료를 참조하여 피라미드 별로 파란색(lv2), 초록색(lv1), 빨간색(lv0, 원본)으로 표시하면 아래 그림과 같고 순서대로 해당 영역의 픽셀을 탐색한다.

3. 피라미드 레벨이 낮은 곳(lv0, 원본)부터 한 픽셀 씩 루프를 돌면서 해당 영역 히스토그램의 smoothed threshold 값과 픽셀의 squared gradient
이 때, 특정 픽셀 값이 smoothed treshold보다 크면 다음 단계로써 해당 픽셀의
4. 최종적으로 norm까지 특정 값보다 크다면 해당 픽셀을 grid를 대표하는 픽셀로 선정하고 루프를 탈출한다.
ex) 만약 115 픽셀의
5. 만약 픽셀이 smoothed threshold보다 작은 경우 lv0 -> lv1 -> lv2 순서로 값을 비교한다. 이 때, 레벨이 높을수록 threshold에 0.75를 곱한 후 픽셀의 밝기 값과 비교하여 높은 피라미드 레벨의 픽셀일수록 추출될 확률을 높였다.
6. 모든 픽셀을 전부 검사했음에도 추출한 포인트의 총합이 원하는 총량(기본 N=2000)보다 적을 경우 (

7. 한 이미지 내에서 모든 grid에 대해 루프를 돌면서 smoothed threshold를 통과한 픽셀들만 pixel map에 저장한다. pixel map에는 lv0에서 추출된 포인트의 경우 '1', lv1에서 추출된 포인트는 '2', lv3에서 추출된 포인트는 '4'의 값을 갖는다. 포인트가 추출되지 않는 영역의 값은 '0'을 갖는다.

6. Code Review
References
5. [CH] DSO tracking and optimization
8. [CH] DSO photometric calibration
9. [CH] DSO code with comments
11. [CH] DSO (5) Calculation and Derivation of Null Space
'Engineering' 카테고리의 다른 글
[SLAM] g2o example 코드 리뷰 (0) | 2022.06.09 |
---|---|
[SLAM] Visual LiDAR Odometry and Mapping (V-LOAM) 논문 리뷰 (0) | 2022.06.08 |
[SLAM] Depth Enhanced Monocular Odometry (DEMO) 논문 리뷰 (0) | 2022.06.08 |
[SLAM] Direct Sparse Odometry (DSO) 논문 및 코드 리뷰 (1) (5) | 2022.06.03 |
[SLAM] Lidar Odometry And Mapping (LOAM) 논문 리뷰 (29) | 2022.06.02 |