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.
cfg/rovtio
.This is using the catkin tools
to build the ros package. You can also build it with catkin_make
.
catkin build rovtio --cmake-args -DCMAKE_BUILD_TYPE=Release -DMAKE_SCENE=OFF -DROVIO_NCAM=2 -DROVIO_NMAXFEATURE=25
roslaunch rovtio rovtio.launch
rosbag play *.bag
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.
camera_topicX
where the each camera needs to be designated an id X
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 the camX_offset
where X
is the camera ID.minSTScoreForModalitySelectionX
) and change the number X
To the camera ID.-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:
Please also have a look at the wiki: https://github.com/ethz-asl/rovio/wiki
Dependencies:
#!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