Sensor Calibration ================== To assist in explaining the calibration process presented in this section, the hardware measurements and schematic of the coordinate system transformations are provided below. .. image:: /images/side_ann.svg :width: 50% .. image:: /images/tf.svg :width: 49% Calibration datasets ---------------------------- The following datasets provide the raw data used to compute the extrinsic and intrinsic parameters for the Bell 412 seqences. .. list-table:: :widths: 30 70 :header-rows: 1 * - Dataset Type - Download Link * - **Down-facing Camera** (Intrinsics) - `Google Drive Folder `_ * - **Front-facing Camera** (Intrinsics) - `Google Drive Folder `_ * - **IMU + Down-facing Camera** (Extrinsics) - `Download File `_ * - **IMU + Front-facing Camera** (Extrinsics) - `Download File `_ * - **LiDAR + Down-facing Camera** (Extrinsics) - `Google Drive Folder `_ * - **LiDAR + Front-facing Camera** (Extrinsics) - `Google Drive Folder `_ .. note:: Calibration data for DJI M600 sequences are not available. Methodology & Tools ------------------- * **LiDAR + Camera:** These datasets include time-synchronized ``.pcd`` point clouds and ``.jpg`` images. * **IMU + Camera:** Calibration was performed using `Kalibr `_ with `Aprilgrid 6x6 0.8x0.8m (A0 page) `_. The Aprilgrid parameters are listed `here `_. * **Camera Intrinsics:** The checkerboard used was a 70mm square-size checkerboard of 8x11. However, the input target size for the `VINS-Fusion Camera Calibration Tool `_ was 6x8. Camera Intrinsic Calibration ---------------------------- The intrinsic parameters of the cameras, such as the camera model, camera matrix [K], and distortion parameters, were obtained using the camera calibration tool that is included in the VINS-Fusion package. The values obtained are presented below. .. :math:`\begin{aligned} .. & K = \begin{bmatrix} .. a_{11} & a_{12} & a_{13} \\ .. a_{21} & a_{22} & a_{23} \\ .. a_{31} & a_{32} & a_{33} .. \end{bmatrix} \\ .. &\text{This is some text below the matrix.} .. \end{aligned}` For Bell412 Datasets: .. literalinclude:: /images/cam_intrinsic_bell412.yaml :language: yaml For DJI M600 Datasets: .. literalinclude:: /images/cam_intrinsic_m600.yaml :language: yaml IMU Intrinsic Calibration ------------------------- The IMU parameters for both Bell412 and DJI M600 datasets are given below. .. literalinclude:: /images/imu_prams.yaml :language: yaml Camera-IMU Extrinsic Calibration -------------------------------- The camera-IMU transformation was found using Kalibr package. For Bell412 Datasets: The down camera :math:`T_{BCd}` and front camera :math:`T_{BCf}` .. literalinclude:: /images/T_BC_bell412.yaml :language: yaml For DJI M600 Datasets: The down camera :math:`T_{BCd}` and front camera :math:`T_{BCf}` .. literalinclude:: /images/T_BC_m600.yaml :language: yaml Camera-LiDAR Extrinsic Calibration ---------------------------------- Down camera to LiDAR transfromation :math:`[T_{CLd}]` was found using Matlab LiDAR calibrator toolbox and fine-tuned using manual realignment. For Bell412 datasets: .. literalinclude:: /images/T_CL_bell412.yaml :language: yaml For DJI M600 datasets: .. literalinclude:: /images/T_CL_m600.yaml :language: yaml IMU-GNSS Extrinsic Calibration ------------------------------ IMU to GNSS transformation :math:`[T_{BG}]` for both Bell412 and DJI M600 datasets are given here. .. literalinclude:: /images/T_BG.yaml :language: yaml