Merge branch 'david_devel' into 'master'

Small fixes in documentation

See merge request VladyslavUsenko/basalt!3
This commit is contained in:
Vladyslav Usenko 2019-04-16 11:50:42 +00:00
commit d583c03111
4 changed files with 23 additions and 19 deletions

View File

@ -73,7 +73,7 @@ The buttons in the GUI are located in the order which you need to follow to cali
You can also control the visualization using the following buttons:
* `show_frame` - `show_ids` the same as above.
* `show_spline` toggles the visibility of enabled measurements (accel, gyro, position, velocity) generated from the spline that we optimize.
* `show_data` toggles the visibility of raw data containted in the dataset.
* `show_data` toggles the visibility of raw data contained in the dataset.
* `show_accel` shows accelerometer data.
* `show_gyro` shows gyroscope data.
* `show_pos` shows spline position for `show_spline` and positions generated from camera pose initialization transformed into IMU coordinate frame for `show_data`.
@ -87,12 +87,12 @@ The following options control the optimization process:
* `opt_poses` enables optimization based camera pose initialization. Sometimes helps to better initialize the spline before running optimization with `opt_corners`.
* `opt_corners` enables optimization based on reprojection corner positions **(should be used by default)**.
* `opt_cam_time_offset` computes the time offset between camera and the IMU. This option should be used only for refinement when the optimization already converged.
* `opt_imu_scale` enables IMU axis scaling, rotation and mislignment calibration. This option should be used only for refinement when the optimization already converged.
* `opt_imu_scale` enables IMU axis scaling, rotation and misalignment calibration. This option should be used only for refinement when the optimization already converged.
* `opt_mocap` enables Mocap optimization. You should run it only after pressing `init_mocap`.
* `huber_thresh` controls the threshold for the huber norm in pixels for the optimization.
**NOTE:** In this case the we use pre-calibrated sequence, so most of refinements or Mocap to IMU calibration will not have any visible effect. If you want to test this functionality use the "raw" sequences, for example `http://vision.in.tum.de/tumvi/raw/dataset-calib-cam3.bag` and `http://vision.in.tum.de/tumvi/raw/dataset-calib-imu1.bag`.
**NOTE:** In this case we use a pre-calibrated sequence, so most of refinements or Mocap to IMU calibration will not have any visible effect. If you want to test this functionality use the "raw" sequences, for example `http://vision.in.tum.de/tumvi/raw/dataset-calib-cam3.bag` and `http://vision.in.tum.de/tumvi/raw/dataset-calib-imu1.bag`.
## EuRoC dataset
Download the datasets for camera and camera-IMU calibration:

View File

@ -19,16 +19,16 @@ This opens the GUI and runs the sequence.
![SIM_VIO](doc/img/SIM_VIO.png)
The buttons in the GUI have the following meaning:
* `show_obs` toggles the visibility the ground-truth landmarks in the image view.
* `show_noisy` toggles the visibility the noisy landmarks in the image view.
* `show_vio` toggles the visibility the landmarks estimated by VIO in the image view.
* `show_obs` toggles the visibility of the ground-truth landmarks in the image view.
* `show_obs_noisy` toggles the visibility of the noisy landmarks in the image view.
* `show_obs_vio` toggles the visibility of the landmarks estimated by VIO in the image view.
* `show_ids` toggles the IDs of the landmarks.
* `show_accel` shows noisy accelerometer measurements generated from ground truth spline.
* `show_gyro` shows noisy gyroscope measurements generated from ground truth spline.
* `show_accel` shows noisy accelerometer measurements generated from the ground-truth spline.
* `show_gyro` shows noisy gyroscope measurements generated from the ground-truth spline.
* `show_gt_...` shows ground truth position, velocity and biases.
* `show_est_...` shows VIO estimates of the position, velocity and biases.
* `next_step` proceeds to next frame.
* `continue` plays the sequence.
* `continue_btn` plays the sequence.
* `align_button` performs SE(3) alignment with ground-truth trajectory and prints the RMS ATE to the console.

View File

@ -24,24 +24,25 @@ The command line options have the following meaning:
* `--dataset-path` path to the dataset.
* `--dataset-type` type of the datset. Currently only `bag` and `euroc` formats of the datasets are supported.
* `--cam-calib` path to camera calibration file. Check [calibration instructions](doc/Calibration.md) to see how the calibration was generated.
* `--config-path` path to the configuration file.
* `--marg-data` folder where the data from keyframe marginalization will be stored. This data can be later used for visual-inertial mapping.
* `--show-gui` enables or disables GUI.
This opens the GUI and runs the sequence. The processing happens in the background as fast as possible, and the visualization results are saved in GUI and can be analysed offline.
This opens the GUI and runs the sequence. The processing happens in the background as fast as possible, and the visualization results are saved in the GUI and can be analysed offline.
![MH_05_VIO](doc/img/MH_05_VIO.png)
The buttons in the GUI have the following meaning:
* `show_obs` toggles the visibility the tracked landmarks in the image view.
* `show_obs` toggles the visibility of the tracked landmarks in the image view.
* `show_ids` toggles the IDs of the points.
* `show_est_pos` shows the plot of the estimated position.
* `show_est_vel` shows the plot of the estimated velocity.
* `show_est_bg` shows the plot of the estimated gyro bias.
* `show_est_ba` shows the plot of the estimated accel bias.
* `show_ge` shows ground-truth trajectory in the 3D view.
* `show_gt` shows ground-truth trajectory in the 3D view.
By default the system starts with `continue_fast` enabled. This option visualizes the latest processed frame until the end of the sequence. Alternatively, the `continue_btn` visualizes every frame without skipping. If both options are disabled the system shows the frame that is selected with `show_frame` slider and user can move forward and backward with `next_step` and `prev_step` buttons. The `follow` button changes between the static camera and the camera attached to the current frame.
By default the system starts with `continue_fast` enabled. This option visualizes the latest processed frame until the end of the sequence. Alternatively, the `continue_btn` visualizes every frame without skipping. If both options are disabled the system shows the frame that is selected with the `show_frame` slider and the user can move forward and backward with `next_step` and `prev_step` buttons. The `follow` button changes between the static camera and the camera attached to the current frame.
For evaluation the button `align_svd` is used. It aligns the GT trajectory with the current estimate with SE(3) transformation and prints the transformation and the root-mean-squared absolute trajectory error (RMS ATE).
For evaluation the button `align_svd` is used. It aligns the GT trajectory with the current estimate using an SE(3) transformation and prints the transformation and the root-mean-squared absolute trajectory error (RMS ATE).
### Visual-inertial mapping
To run the mapping tool execute the following command:
@ -67,12 +68,15 @@ The workflow for the mapping is the following:
* `detect` detect the keypoints in the keyframe images.
* `match` run the geometric 2D to 2D matching between image frames.
* `tracks` build tracks from 2D matches and triangulate the points.
* `optimize` run the optimization
* `optimize` run the optimization.
* `align_svd` align ground-truth trajectory in SE(3) and print the transformation and the error.
For more systematic evaulation see the evaluation scripts in `scripts/eval_full` folder.
The `num_opt_iter` slider controls the maximum number of iterations executed when pressing `optimize`.
**NOTE: It appears that only the datasets in ASL Dataset Format (`euroc` dataset type in our notation) contain ground truth that is time-aligned to the IMU and camera images. It is located in `state_groundtruth_estimate0` folder. Bag files have raw Mocap measurements that are not time aligned and should not be used for evaluations.**
For more systematic evaluation see the evaluation scripts in the `scripts/eval_full` folder.
**NOTE: It appears that only the datasets in ASL Dataset Format (`euroc` dataset type in our notation) contain ground truth that is time-aligned to the IMU and camera images. It is located in the `state_groundtruth_estimate0` folder. Bag files have raw Mocap measurements that are not time aligned and should not be used for evaluations.**
@ -110,4 +114,4 @@ To run the mapping tool execute the following command:
```
basalt_mapper --cam-calib /usr/etc/basalt/tumvi_512_ds_calib.json --marg-data tumvi_marg_data --vocabulary /usr/etc/basalt/orbvoc.dbow3
```
![magistrale1_mapping](doc/img/magistrale1_mapping.png)
![magistrale1_mapping](doc/img/magistrale1_mapping.png)

View File

@ -700,7 +700,7 @@ void CamImuCalib::saveMocapCalib() {
vio_dataset->get_mocap_to_imu_offset_ns());
std::cout << "Saved Mocap calibration in " << cache_path
<< "/mocap_calibration.json" << std::endl;
<< "mocap_calibration.json" << std::endl;
}
}