diff --git a/doc/Calibration.md b/doc/Calibration.md index 617e153..e409f4a 100644 --- a/doc/Calibration.md +++ b/doc/Calibration.md @@ -26,7 +26,7 @@ The command line options have the following meaning: After that, you should see the calibration GUI: ![tumvi_cam_calib](doc/img/tumvi_cam_calib.png) -The buttons in the GUI are located in the order which you should follow to calibrate the camera: +The buttons in the GUI are located in the order which you should follow to calibrate the camera. After pressing a button the system will print the output to the command line: * `load_dataset` loads the dataset. * `detect_corners` starts corner detection in the backround thread. Since it is the most time consuming part of the calibration process, the detected corners are cached and loaded if you run the executable again pointing to the same result folder path. * `init_cam_intr` computes an initial guess for camera intrinsics. diff --git a/doc/VioMapping.md b/doc/VioMapping.md index 3e0c958..ee8becb 100644 --- a/doc/VioMapping.md +++ b/doc/VioMapping.md @@ -83,4 +83,31 @@ basalt_opt_flow --dataset-path MH_05_difficult/ --cam-calib /usr/etc/basalt/euro ``` This will run the GUI and print an average track length after the dataset is processed. -![MH_05_OPT_FLOW](doc/img/MH_05_OPT_FLOW.png) \ No newline at end of file +![MH_05_OPT_FLOW](doc/img/MH_05_OPT_FLOW.png) + + +## TUM-VI dataset + +We demonstrate the usage of the system with the `magistrale1` sequence of the [TUM-VI dataset](https://vision.in.tum.de/data/datasets/visual-inertial-dataset) as an example. + +Download the sequence from the dataset and extract it. +``` +mkdir tumvi_data +cd tumvi_data +wget http://vision.in.tum.de/tumvi/exported/euroc/512_16/dataset-magistrale1_512_16.tar +tar -xvf dataset-magistrale1_512_16.tar +``` + +### Visual-inertial odometry +To run the visual-inertial odometry execute the following command in `tumvi_data` folder where you downloaded the dataset. +``` +basalt_vio --dataset-path dataset-magistrale1_512_16/ --cam-calib /usr/etc/basalt/tumvi_512_ds_calib.json --dataset-type euroc --config-path /usr/etc/basalt/tumvi_512_config.json --marg-data tumvi_marg_data --show-gui 1 +``` +![magistrale1_vio](doc/img/magistrale1_vio.png) + +### Visual-inertial mapping +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) \ No newline at end of file diff --git a/doc/img/magistrale1_mapping.png b/doc/img/magistrale1_mapping.png new file mode 100644 index 0000000..8bc6918 Binary files /dev/null and b/doc/img/magistrale1_mapping.png differ diff --git a/doc/img/magistrale1_vio.png b/doc/img/magistrale1_vio.png new file mode 100644 index 0000000..5ec266f Binary files /dev/null and b/doc/img/magistrale1_vio.png differ diff --git a/include/basalt/io/dataset_io_euroc.h b/include/basalt/io/dataset_io_euroc.h index 5ca5a8c..d699aaf 100644 --- a/include/basalt/io/dataset_io_euroc.h +++ b/include/basalt/io/dataset_io_euroc.h @@ -37,6 +37,9 @@ OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. #include +#include +namespace fs = std::experimental::filesystem; + namespace basalt { class EurocVioDataset : public VioDataset { @@ -124,6 +127,9 @@ class EurocIO : public DatasetIoInterface { EurocIO() {} void read(const std::string &path) { + if (!fs::exists(path)) + std::cerr << "No dataset found in " << path << std::endl; + data.reset(new EurocVioDataset); data->num_cams = 2; diff --git a/include/basalt/io/dataset_io_rosbag.h b/include/basalt/io/dataset_io_rosbag.h index 01f6919..76b58a2 100644 --- a/include/basalt/io/dataset_io_rosbag.h +++ b/include/basalt/io/dataset_io_rosbag.h @@ -51,6 +51,9 @@ OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. #include #include +#include +namespace fs = std::experimental::filesystem; + namespace basalt { class RosbagVioDataset : public VioDataset { @@ -154,6 +157,9 @@ class RosbagIO : public DatasetIoInterface { RosbagIO(bool with_images) : with_images(with_images) {} void read(const std::string &path) { + if (!fs::exists(path)) + std::cerr << "No dataset found in " << path << std::endl; + data.reset(new RosbagVioDataset); data->bag.reset(new rosbag::Bag);