This repo contains ROVTIO, an algorithm for odometry estimation using both a visual camera, an infrared camera and an IMU. To extend visual inertial odometry to dark environments one can instead of a standard visual camera use a thermal camera. However, thermal cameras struggle in thermal flat environments, i.e. environments where everything have the same temperature and the emissivity is similar. To get the best of both modalities ROVTIO use both a thermal camera and a visual camera. Due to the differences between the modalities does it not rely on stereo correspondences and it can both initialize and track if only one of the camera streams is available.
This work is based on ROVIO, which it inheriths some properties from. Same as ROVIO, ROVTIO is a direct, robocentric filter-based method. The filter ROVTIO use is the same iterated extended kalman filter that ROVIO use. These traits also allow ROVTIO to initialize the map at a high uncertainty and let it converge during operation, removing the need for an explicit initialization procedure.
ROVTIO was developed as a part of the work for the authors master thesis. The master thesis contains analysis of the benefit of using both thermal and visual compared to using only one of them.
The data used for analysis in the master thesis is provided here. It is collected by Mihir Kulkarni at Autonomous Robots lab the University of Nevada.
ROVTIO requires no additional dependencies from the ones ROVIO requires. See the ROVIO install directions below.
Note that it is recomended to install kindr
using catkin.
- Install the dependencies for ROVIO
- Configure the rovtio.info file and the .launch file. Examples are in
cfg/rovtio
.
This is using the catkin tools
to build the ros package. You can also build it with catkin_make
.
- Download the desired dataset from here.
- Unzip the zipfile.
- Build ROVTIO
catkin build rovtio --cmake-args -DCMAKE_BUILD_TYPE=Release -DMAKE_SCENE=OFF -DROVIO_NCAM=2 -DROVIO_NMAXFEATURE=25
- Run ROVTIO
roslaunch rovtio rovtio.launch
- Play the bags. Enter the dataset folder and
rosbag play *.bag
- Optional: Open
rviz
and monitor/rovtio/odometry
. You can compare it to the near ground truth result from LOAM at the topic/aft_mapped_to_init_CORRECTED
.
ROVTIO can use several cameras out of the box, but needs to be configured accordingly. They can be either thermal or visual cameras, but the related parameters in the .info
file should be chosen accordingly.
- Edit the launch file: You need to add a
camera_topicX
where the each camera needs to be designated an idX
which is numbers starting at 0 and increasing by 1. If the timing offset between the camera and the IMU is known, you can specify it with thecamX_offset
whereX
is the camera ID. - Edit the .info file: There is several parameters which needs to be specified per camera. This is because you typically want different parameters for thermal cameras and visual cameras. Look in the example file and duplicate all the parameters that ends with a number(eg.
minSTScoreForModalitySelectionX
) and change the numberX
To the camera ID. - Rebuild with the new number of cameras in the
-DROVIO_NCAM
build option.
The camera streams does not have to be synchronized and ROVTIO will align the m if they arrive out of order.
This repo inherits the license from ROVIO. For details see LICENSE
.
This repository contains the ROVIO (Robust Visual Inertial Odometry) framework. The code is open-source (BSD License). Please remember that it is strongly coupled to on-going research and thus some parts are not fully mature yet. Furthermore, the code will also be subject to changes in the future which could include greater re-factoring of some parts.
Video: https://youtu.be/ZMAISVy-6ao
Papers:
- http://dx.doi.org/10.3929/ethz-a-010566547 (IROS 2015)
- http://dx.doi.org/10.1177/0278364917728574 (IJRR 2017)
Please also have a look at the wiki: https://github.com/ethz-asl/rovio/wiki
Dependencies:
- ros
- kindr (https://github.com/ethz-asl/kindr)
- lightweight_filtering (as submodule, use "git submodule update --init --recursive")
#!command
catkin build rovio --cmake-args -DCMAKE_BUILD_TYPE=Release
Additional dependencies: opengl, glut, glew (sudo apt-get install freeglut3-dev, sudo apt-get install libglew-dev)
#!command
catkin build rovio --cmake-args -DCMAKE_BUILD_TYPE=Release -DMAKE_SCENE=ON
The rovio_node.launch file loads parameters such that ROVIO runs properly on the Euroc datasets. The datasets are available under: http://projects.asl.ethz.ch/datasets/doku.php?id=kmavvisualinertialdatasets
- Camera matrix and distortion parameters should be provided by a yaml file or loaded through rosparam
- The cfg/rovio.info provides most parameters for rovio. The camera extrinsics qCM (quaternion from IMU to camera frame, Hamilton-convention) and MrMC (Translation between IMU and Camera expressed in the IMU frame) should also be set there. They are being estimated during runtime so only a rough guess should be sufficient.
- Especially for application with little motion fixing the IMU-camera extrinsics can be beneficial. This can be done by setting the parameter doVECalibration to false. Please be carefull that the overall robustness and accuracy can be very sensitive to bad extrinsic calibrations.