Skip to content
Ze edited this page Jul 17, 2023 · 24 revisions

Welcome to the LF-VIO wiki! Our wiki is constantly updated......

Camera Model:

For large FoV cameras, there are already many models. The MEI camera model and the Scaramuzza camera model are currently supported in our program.

Scaramuzza camera model calibration tool: OCamCalib

MEI camera model calibration tool:Omnidirectional Calibration Toolbox

...

Dataset:

Indoors datasets are open sourced as follows:

ID01, ID06, ID10: Google Drive

ID01~ID10: Baidu Yun, Code: d7wq

IDL01~IDL02: Baidu Yun, Code: khw2

Initialization for Large FoV camera

* Epipolar geometry problem

Essential matrix E Acquisition

Ev3

Problem formulation:

$\mathbf{x}_2^T\left( \left[\mathbf{t}^{O_2}_{O_1}\right]^\wedge \mathbf{R}^{O_2}_{O_1} \right)\mathbf{x}_1=0$

$\mathbf{x}_1=\begin{bmatrix} \alpha_1 \\\beta_1 \\\gamma_1\end{bmatrix},\mathbf{x}_2=\begin{bmatrix} \alpha_2 \\\beta_2 \\\gamma_2\end{bmatrix}$

$ \mathbf{E}^{O_2}_{O_1}=\left[\mathbf{t}^{O_2}_{O_1}\right]^\wedge \mathbf{R}^{O_2}_{O_1}$

Code:

Eigen::Matrix3d InitialEXRotation::compute_E_21(vector<Eigen::Vector3d> &bearings_1, vector<Eigen::Vector3d> &bearings_2)

Input: bearings_1 and bearings_2

Output: best_E

Essential matrix E decomposition

Code:

int MotionEstimator::recoverPose(Eigen::Matrix3d E, vector<Eigen::Vector3d> _points1, vector<Eigen::Vector3d> _points2,
 Matrix3d _R, Vector3d _t, vector<uchar> _mask)

Input: E, _points1, _points2

Output: _R, _t, mask(1:inlier 0:outlier)

* Triangulation problem

epipolarv2

$\lambda\begin{bmatrix} \alpha \\ \beta \\ \gamma\ \end{bmatrix}=\left[ R|t \right]\begin{bmatrix} x\\y\\z\\1 \end{bmatrix}$

let $\textbf{u}=\begin{bmatrix} \alpha \\ \beta \\ \gamma\ \end{bmatrix}$,$\textbf{X}=\begin{bmatrix} x\\y\\z\\1 \end{bmatrix}$

$\lambda \textbf{u}=\textbf{P}\textbf{X}$ ,the left and right sides of the formula are cross-multiplied by $\textbf{u}$

$\left[ \textbf{u} \right]_\times\textbf{P}\textbf{X}=0 \Rightarrow \begin{bmatrix} 0&amp;-\gamma &amp;\beta\\ \gamma&amp;0&amp;-\alpha\\-\beta&amp;\alpha&amp;0 \end{bmatrix}\begin{bmatrix}\textbf{P}_1\\\textbf{P}_2\\\textbf{P}_3\end{bmatrix}\textbf{X}=0 $

$\left\{\begin{matrix}\left(\beta\textbf{P}_3-\gamma\textbf{P}_2 \right)\textbf{X}=0\\ \left(\gamma\textbf{P}_1-\alpha\textbf{P}_3 \right)\textbf{X}=0\\ \left(\alpha\textbf{P}_2-\gamma\textbf{P}_1 \right)\textbf{X}=0 \end{matrix}\right.$ Since the first two formulas can lead to the third formula, a point has two equations.

Code:

void MotionEstimator::triangulatePoint(Eigen::Matrix<double, 3, 4> &Pose0, Eigen::Matrix<double, 3, 4> &Pose1,
                                       const Vector3d &point0, const Vector3d &point1, Vector3d &point_3d)

Input: Pose0, Pose1, point0, point1

Output: point_3d

* Perspective-n-Point(PnP) problem

......

Optimization after initialization for Large FoV camera

  • Visual measurement residual
  • Inertial Measurement Unit(IMU) residual
  • Marginalized residual
Clone this wiki locally