ORB-SLAM3
Source: https://github.com/UZ-SLAMLab/ORB_SLAM3
V1.0, December
**Authors:** Carlos Campos, Richard Elvira, Juan J. Gómez Rodríguez, José MM Montiel, Juan D. Tardos.
The changelog describes the features of each version.
ORB-SLAM3 is the first real-time SLAM library capable of performing visual, visual-inertial, and multi-map SLAM using monocular, stereo, and RGB-D cameras, supporting both pinhole and fisheye lens models. Across all sensor configurations, ORB-SLAM3 achieves robustness comparable to the best systems in the literature while significantly improving accuracy.
We provide examples of running ORB-SLAM3 using stereo or monocular (including IMU and monocular) on the EuRoC dataset, and using fisheye stereo or monocular (including IMU and monocular) on the TUM-VI dataset. Videos of some of these examples can be found on the ORB-SLAM3 channel.
This software is based on ORB-SLAM2 developed by Raul Mur-Artal, Juan D. Tardos, JMM Montiel, and Dorian Galvez-Lopez ( DBoW2 ).
Related publications
[ORB-SLAM3] Carlos Campos, Richard Elvira, Juan J. Gómez Rodríguez, Jos é MM Montiel, and Juan D. Tardós. ORB-SLAM3: An accurate open-source library for visual, visual-inertial, and multi-map SLAM. IEEE Transactions on Robotics 37(6):1874–1890, December 2021. PDF.**
[IMU Initialization] Carlos Campos, JMM Montiel, and Juan D. Tardós, Pure Inertial Optimization for Visual-Inertial Initialization, ICRA 2020. PDF
[ORBSLAM-Atlas] Richard Elvira, J.M.M. Montiel, and Juan D. Tardós, ORBSLAM- Atlas ****: A Robust and Accurate Multi-Map System, IROS 2019. PDF.
[ORBSLAM-VI] Raúl Mur-Artal and Juan D. Tardós. Visual-Inertial Monocular SLAM with Reusable Maps. IEEE Robotics and Automation Letters, vol. 2, no. 2, pp. 796–803, 2017. PDF .
[Stereo and RGB-D] Raúl Mur-Artal and Juan D. Tardós. ORB -SLAM2: An open-source SLAM system for monocular, stereo, and RGB-D cameras. IEEE Transactions on Robotics, Vol. 33, No. 5, pp. 1255–1262, 2017. PDF .
[Monocular] Raúl Mur-Artal, José M. M. Montiel, and Juan D. Tardós. ORB -SLAM: A Versatile and Accurate Monocular SLAM System. IEEE Transactions on Robotics, Vol. 31, No. 5, pp. 1147–1163, 2015. ( 2015 IEEE Transactions on Robotics Best Paper Award ) . PDF.
[DBoW2 Place Recognition] Dorian Gálvez-López and Juan D. Tardós. Fast Place Recognition in Image Sequences Based on Binary Bag of Words. IEEE Transactions on Robotics, Vol. 28, No. 5, pp. 1188–1197, 2012. PDF
1. License
ORB-SLAM3 is released under the GPLv3 license. For a list of all code/library dependencies (and their associated licenses), see Dependencies.md.
To obtain a closed-source version of ORB-SLAM3 for commercial use, please contact the orbslam (at) unizar (dot) es.
If you use ORB-SLAM3 in your academic work, please cite:
@article{ORBSLAM3_TRO,
title={{ORB-SLAM3}: An Accurate Open-Source Library for Visual, Visual-Inertial
and Multi-Map {SLAM}},
author={Campos, Carlos AND Elvira, Richard AND G\´omez, Juan J. AND Montiel,
Jos\'e M. M. AND Tard\'os, Juan D.},
journal={IEEE Transactions on Robotics},
volume={37},
number={6},
pages={1874-1890},
year={2021}
}
2. Prerequisites
We have tested the library in Ubuntu 16.04 and 18.04, but it should be easy to compile on other platforms as well. A powerful computer (e.g. an i7) will ensure real-time performance and provide more stable and accurate results.
C++11 or C++0x
We use the new threading and timing features of C++11.
Pangolin
We use Pangolin for visualization and user interface. Download and installation instructions can be found at: https://github.com/stevenlovegrove/Pangolin.
OpenCV
We use OpenCV to process images and features. Download and installation instructions can be found at http://opencv.org. At least version 3.0 is required. We have tested it with OpenCV 3.2.0 and 4.4.0.
Feature
Required for g2o (see below). Download and installation instructions are available at: http://eigen.tuxfamily.org. At least version 3.1.0 is required.
DBoW2 and g2o (included in the third-party folder
We use a modified version of the DBoW2 library for position recognition and the g2o library for nonlinear optimization. Both modified versions (BSD versions) are included in the _Thirdparty_ folder.
Python
Used to compute alignment of trajectories with ground truth. Requires Numpy module.
- (win) http://www.python.org/downloads/windows
- (say)
sudo apt install libpython2.7-dev - (Mac) Pre-installed OSX
ROS (optional
We provide some examples for processing monocular, monocular-inertial, stereo, stereo-inertial, or RGB-D camera input using ROS. Building these examples is optional. These examples have been tested using ROS Melodic on an Ubuntu 18.04 system.
3. Build ORB-SLAM3 library and examples
Clone the repository:
git clone https://github.com/UZ-SLAMLab/ORB_SLAM3.git ORB_SLAM3
We provide a script build.sh to build the third-party libraries and ORB-SLAM3. Please make sure you have installed all required dependencies (see Section 2). Execute the following command:
cd ORB_SLAM3
chmod +x build.sh
./build.sh
This will create libORB_SLAM3.so in the _lib folder and the executable in the _Examples_ folder.
4. Run ORB-SLAM3 with a camera
The directory Examples contains several demo programs and calibration files for running ORB-SLAM3 in all sensor configurations with Intel Realsense cameras T265 and D435i. The steps required to use your own camera are as follows:
- Calibrate camera tracking
Calibration_Tutorial.pdfand write calibration filesyour_camera.yaml - Modify one of the provided demos to suit your specific camera model, then build it
- Connect the camera to the computer using USB3 or an appropriate interface
- Run ORB-SLAM3. For example, for our D435i camera, we would execute:
./Examples/Stereo-Inertial/stereo_inertial_realsense_D435i Vocabulary/ORBvoc.txt ./Examples/Stereo-Inertial/RealSense_D435i.yaml
5. EuRoC Example
The EuRoC dataset was recorded with two pinhole cameras and one inertial sensor. We provide a sample script to start a EuRoC sequence in all sensor configurations.
- Download the sequences (ASL format) from http://projects.asl.ethz.ch/datasets/doku.php?id=kmavvisualinertialdatasets
- Open the script "euroc_examples.sh" in the project root directory. Change the pathDatasetEuroc variable to point to the directory where the dataset is unpacked.
- Execute the following script to process all sequences for all sensor configurations:
./euroc_examples
Evaluation
EuRoC provides ground truth for each sequence in the IMU body reference. Since the trajectories reported by the vision-only implementation are centered on the left camera, we provide the ground truth to left-camera reference transformation in the "evaluation" folder. The visual-inertial trajectories use the ground truth from the dataset.
Execute the following script to process the sequence and calculate the RMS ATE:
./euroc_eval_examples
6. TUM-VI Example
The TUM-VI dataset is recorded by two fisheye cameras and one inertial sensor.
- Download a sequence from https://vision.in.tum.de/data/datasets/visual-inertial-dataset and unzip it.
- Open the script "tum_vi_examples.sh" in the project root directory and change the pathDatasetTUM_VI variable to point to the directory where the dataset is unzipped.
- Execute the following script to process all sequences for all sensor configurations:
./tum_vi_examples
Evaluation
In TUM-VI, ground truth is only available in the rooms where all sequences start and end. Therefore, the error measures the drift at the end of the sequence.
Execute the following script to process the sequence and calculate the RMS ATE:
./tum_vi_eval_examples
7. ROS Examples
Build Mono, Mono Inertial, Stereo, Stereo Inertial, and RGB-D
Tested using ROS Melodic and Ubuntu 18.04.
- _Add the path containing Examples/ROS/ORB_SLAM3_ to the ROS_PACKAGE_PATH environment variable. Open the.bashrc file:
gedit ~/.bashrc
and add the following line at the end. Replace PATH with the folder where you cloned ORB_SLAM3:
export ROS_PACKAGE_PATH=${ROS_PACKAGE_PATH}:PATH/ORB_SLAM3/Examples/ROS
- Execute
build_ros.shthe script:
chmod +x build_ros.sh
./build_ros.sh
Running a Monocular
For monocular input from a subject, /camera/image_raw run the node ORB_SLAM3/Mono. You will need to provide a vocabulary file and a settings file. See the monocular example above.
rosrun ORB_SLAM3 Mono PATH_TO_VOCABULARY PATH_TO_SETTINGS_FILE
Running the Monocular Inertial
For the monocular input from the subject /camera/image_raw and the inertial input from the subject /imu, run the node ORB_SLAM3/Mono_Inertial. Setting the optional third parameter to true will apply CLAHE equalization to the image (primarily for the TUM-VI dataset).
rosrun ORB_SLAM3 Mono PATH_TO_VOCABULARY PATH_TO_SETTINGS_FILE [EQUALIZATION]
Running the Stereo
For stereo input from a subject /camera/left/image_raw, /camera/right/image_raw run the node ORB_SLAM3/Stereo. You will need to provide a vocabulary file and a settings file. For pinhole camera models, the node will rectify the image online if you provide a rectification matrix (see Examples/Stereo/EuRoC.yaml for an example); otherwise, the image must be pre-rectified. For fisheye camera models, no rectification is required because the system uses the raw image directly:
rosrun ORB_SLAM3 Stereo PATH_TO_VOCABULARY PATH_TO_SETTINGS_FILE ONLINE_RECTIFICATION
Run the Stereo Inertial
/camera/left/image_raw For stereo input from the subject /camera/right/image_raw and inertial input from the subject /imu, run the node ORB_SLAM3/Stereo_Inertial. You need to provide a vocabulary file and a settings file, and if needed, a correction matrix, in a similar way to the stereo case:
rosrun ORB_SLAM3 Stereo_Inertial PATH_TO_VOCABULARY PATH_TO_SETTINGS_FILE ONLINE_RECTIFICATION [EQUALIZATION]
Run the RGB_D
/camera/rgb/image_raw For RGB-D input from the subject and the RGB-D image /camera/depth_registered/image_raw, run the node ORB_SLAM3/RGBD. You will need to provide a vocabulary file and a settings file. See the RGB-D example above.
rosrun ORB_SLAM3 RGBD PATH_TO_VOCABULARY PATH_TO_SETTINGS_FILE
**Running ROS examples:** Download a rosbag (e.g. V1_02_medium.bag) from the EuRoC dataset ( http://projects.asl.ethz.ch/datasets/doku.php?id=kmavvisualinertialdatasets ). Open three terminal tabs and run the following command in each tab to configure stereo inertial:
roscore
rosrun ORB_SLAM3 Stereo_Inertial Vocabulary/ORBvoc.txt Examples/Stereo-Inertial/EuRoC.yaml true
rosbag play --pause V1_02_medium.bag /cam0/image_raw:=/camera/left/image_raw /cam1/image_raw:=/camera/right/image_raw /imu0:=/imu
Once ORB-SLAM3 has loaded the vocabulary, press the spacebar in the rosbag tab.
**Note:** For rosbags from the TUM-VI dataset, some playback issues may occur due to block size issues. A possible solution is to repack them using the default block size, for example:
rosrun rosbag fastrebag.py dataset-room1_512_16.bag dataset-room1_512_16_small_chunks.bag
8. Runtime Analysis
The flag in include\Config.h activates time measurement. This line needs to be uncommented #define REGISTER_TIMES to get time statistics for one execution, which are displayed on the terminal and stored in a text file ( ExecTimeMean.txt).
9. Calibration
You can find a tutorial for visual-inertial calibration and a detailed description of the contents of valid configuration files at Calibration_Tutorial.pdf