7. IMU measurement error
In order to obtain the IMU measurement error, you must first know about the IMU preintegration technique and error-state modeling. The following figure expresses the overall IMU measurement error-based optimization process.

The overall IMU measurement error-based optimization process, with detailed explanations and color highlighting added for better understanding, is as follows.

TBA...
8. Other jacobians
8.1. Jacobian of unit quaternion
NOMENCLATURE of jacobian of unit quaternion
- A quaternion expressed in hamilton notation. For more information on this, please refer to this post.
The Jacobians described earlier in the reprojection error section are:
Among them,
Given a point
Unpacking and expanding it, we get:
You can use this to find the Jacobian
At this time,
In addition, the quaternion
Finally, the Jacobian
8.1.1. Code Implementations
- ProSLAM code: trajectory_analyzer.cpp#L253
- refered to jinyongjeong blog post
8.2. Jacobian of camera intrinsics
NOMENCLATURE of jacobian of camera intrinsics
: Back-projection function that back-projects a point on an image onto a 3D space : Projection function that projects a point in 3D space onto an image plane. : Camera intrinsic matrix : I omitted the last line of internal parameters to project to
When camera calibration is performed to perform SLAM, the intrinsic matrix
For example, let's say we want to find
At this time, the first
The relationship between the points
Since back projection
Next, we need to calculate the elements of the above equation.
To find this, first find
The above expression is rearranged as follows.
Based on this, (
Finally, (
8.2.1. Code Implementations
- DSO code: Residuals.cpp#L123
- For a detailed description of the code, refer to [SLAM] Direct Sparse Odometry (DSO) 논문 및 코드 리뷰 (2).
8.3. Jacobian of inverse depth
NOMENCLATURE of jacobian of inverse depth
8.3.1. Inverse depth parameterization
In SLAM, inverse depth parameterization refers to a method of expressing a 3D point
8.3.2. Jacobian of inverse depth
Let's assume that
At this time, the first
First of all, expressing
Next, we need to find
Referring to the above expression,
The second line in the above equation can be obtained by transforming (
-
-
8.3.3. Code Implementations
- DSO code: CoarseInitializer.cpp#L424
- For a detailed description of the code, refer to [SLAM] Direct Sparse Odometry (DSO) 논문 및 코드 리뷰 (2).
References
[1] [Blog] [SLAM] Bundle Adjustment 개념 리뷰: Reprojection error
[2] [Blog] [SLAM] Optical Flow와 Direct Method 개념 및 코드 리뷰: Photometric error
[3] [Blog] [SLAM] Pose Graph Optimization 개념 설명 및 예제 코드 분석: Relative pose error
[4] [Blog] Plücker Coordinate 개념 정리: Line projection error
'English' 카테고리의 다른 글
[En] Notes on Lie Theory (SO(3), SE(3)) (0) | 2023.01.17 |
---|---|
[En] Notes on Plücker Coordinate (0) | 2023.01.17 |
[SLAM][En] Errors and Jacobian Derivations for SLAM Part 1 (0) | 2023.01.17 |
[En] Vim - Useful plugins and C++/Python development environment (1) | 2023.01.16 |
[SLAM][En] Notes on Formula Derivation and Analysis of the VINS-mono (0) | 2023.01.16 |