All Projects → YoujieXia → Vi_orb_slam2

YoujieXia / Vi_orb_slam2

Licence: other
Monocular/Stereo Visual-Inertial ORB-SLAM based on ORB-SLAM2

Labels

Projects that are alternatives of or similar to Vi orb slam2

Cerebro
Intelligent place recognition module for vins-fusion
Stars: ✭ 94 (-31.39%)
Mutual labels:  slam
Turtlebot3 simulations
Simulations for TurtleBot3
Stars: ✭ 104 (-24.09%)
Mutual labels:  slam
Se2clam
SE(2)-Constrained Localization and Mapping by Fusing Odometry and Vision (IEEE Transactions on Cybernetics 2019)
Stars: ✭ 116 (-15.33%)
Mutual labels:  slam
Awesome Visual Slam
📚 The list of vision-based SLAM / Visual Odometry open source, blogs, and papers
Stars: ✭ 1,336 (+875.18%)
Mutual labels:  slam
Evo
Python package for the evaluation of odometry and SLAM
Stars: ✭ 1,373 (+902.19%)
Mutual labels:  slam
Orb Slam2 Based Ar On Android
This is a Android Augmented Reality APP based on ORB-SLAM2 and OpenGL,which can work well on both outdoor and indoor environments
Stars: ✭ 107 (-21.9%)
Mutual labels:  slam
Eval Vislam
Toolkit for VI-SLAM evaluation.
Stars: ✭ 89 (-35.04%)
Mutual labels:  slam
Cleanit
Open-source Autonomy Software in Rust-lang with gRPC for the Roomba series robot vacuum cleaners. Under development.
Stars: ✭ 125 (-8.76%)
Mutual labels:  slam
Rtabmap
RTAB-Map library and standalone application
Stars: ✭ 1,376 (+904.38%)
Mutual labels:  slam
M Loam
Robust Odometry and Mapping for Multi-LiDAR Systems with Online Extrinsic Calibration
Stars: ✭ 114 (-16.79%)
Mutual labels:  slam
Ssl slam2
SSL_SLAM2: Lightweight 3-D Localization and Mapping for Solid-State LiDAR (mapping and localization separated) ICRA 2021
Stars: ✭ 96 (-29.93%)
Mutual labels:  slam
Eao Slam
[IROS 2020] EAO-SLAM: Monocular Semi-Dense Object SLAM Based on Ensemble Data Association
Stars: ✭ 95 (-30.66%)
Mutual labels:  slam
Dre slam
RGB-D Encoder SLAM for a Differential-Drive Robot in Dynamic Environments
Stars: ✭ 110 (-19.71%)
Mutual labels:  slam
Slambook
Learn 视觉slam十四讲
Stars: ✭ 95 (-30.66%)
Mutual labels:  slam
Ov2slam
OV²SLAM is a Fully Online and Versatile Visual SLAM for Real-Time Applications
Stars: ✭ 119 (-13.14%)
Mutual labels:  slam
Elasticfusion
Real-time dense visual SLAM system
Stars: ✭ 1,298 (+847.45%)
Mutual labels:  slam
Door Slam
Distributed, Online, and Outlier Resilient SLAM for Robotic Teams
Stars: ✭ 107 (-21.9%)
Mutual labels:  slam
Maplab
An open visual-inertial mapping framework.
Stars: ✭ 1,722 (+1156.93%)
Mutual labels:  slam
Dl Vision Papers
深度学习和三维视觉相关的论文
Stars: ✭ 123 (-10.22%)
Mutual labels:  slam
Awesome Robotic Tooling
Tooling for professional robotic development in C++ and Python with a touch of ROS, autonomous driving and aerospace.
Stars: ✭ 1,876 (+1269.34%)
Mutual labels:  slam

VI_ORB_SLAM2: Monocular/Stereo Visual-Inertial ORB-SLAM based on ORB-SLAM2

The repository includes the Monocular version and the Stereo version of Visual-Inertial ORB-SLAM. These two are the no ros version of jingpang's LearnVIORB and ZuoJiaxing's LearnVIORBnorosgai2. For details, you may refer to Examples/Monocular/mono_euroc_VI.cc and Examples/Stereo/stereo_euroc_VI.cc.

I have fix some bugs to make it more stable to pass through more datasets and modify the code to make it compatible with ORB-SLAM2.

Not bug-free. Not real-time.

If you think this repo is useful, please watch, star or fork it!

TO DO List

  • [ ] Real-time
  • [ ] Support the Localization mode for stereo VI ORB-SLAM
  • [ ] Relative Pose Error Analysis, like orientation and translation error

Building VI-ORB-SLAM2 library and examples

Clone the repository:

git clone https://github.com/YoujieXia/VI_ORB_SLAM2.git VI_ORB_SLAM2

We provide a script build.sh to build the Thirdparty libraries and VI_ORB-SLAM2. Please make sure you have installed all required dependencies (see section 2 of ORB-SLAM2 README). Execute:

cd VI_ORB_SLAM2
chmod +x build.sh
./build.sh

This will create libORB_SLAM2.so at lib folder and the executables mono_tum, mono_kitti, rgbd_tum, stereo_kitti, mono_euroc, stereo_euroc, mono_euroc_VI and stereo_euroc_VI in Examples folder.

Example commands for running on the EuRoC Dataset.

  1. Download a sequence (ASL format) from http://projects.asl.ethz.ch/datasets/doku.php?id=kmavvisualinertialdatasets

  2. For Mono VI ORB-SLAM:

MH_01_easy

./Examples/Monocular/mono_euroc_VI Vocabulary/ORBvoc.bin Examples/Monocular/EuRoC_VI.yaml PATH_TO_EuRoC/MH_01_easy/mav0/imu0/data.csv PATH_TO_EuRoC/MH_01_easy/mav0/cam0/data.csv PATH_TO_EuRoC/MH_01_easy/mav0/cam0/data MH_01_easy
  1. For Stereo VI ORB-SLAM:

MH_01_easy

./Examples/Stereo/stereo_euroc_VI Vocabulary/ORBvoc.bin Examples/Stereo/EuRoC_VI.yaml PATH_TO_EuRoC/MH_01_easy/mav0/imu0/data.csv PATH_TO_EuRoC/MH_01_easy/mav0/cam0/data.csv PATH_TO_EuRoC/MH_01_easy/mav0/cam0/data PATH_TO_EuRoC/MH_01_easy/mav0/cam1/data MH_01_easy

Note that we use the ORBvoc.bin instead of ORBvoc.txt to speed up processing. The ORBvoc.bin could be generated by the executable bin_vocabulary at Vocabulary folder. You may still refer to the end of CMakeLists.txt to see how it works.

Results

The temp results are stored at tmp_result/mono_VI/ and tmp_result/stereo_VI/ for Monocular and Stereo VI ORB-SLAM respectively. In each folder, files about camera poses, IMU biases, scale are saved.

Quantitative Evaluation

Here we use the translation RMSE (m) of the keyframe trajectory as the metric. The results are shown below.

Mono ORB-SLAM** Mono VI ORB-SLAM** Stereo VI ORB-SLAM Stereo ORB-SLAM
MH_01_easy 0.070 0.068 0.044528 0.038111
MH_02_easy 0.066 0.072 0.050601 0.047465
MH_03_medium 0.071 0.071 0.050824 0.040883
MH_04_difficult 0.081 0.066 0.708554 0.146833
MH_05_difficult 0.060 0.060 0.097576 0.04993
V1_01_easy 0.015 0.016 0.089984 0.088299
V1_02_medium 0.020 0.019 0.066742 0.065743
V1_03_difficult X* X 0.104091 0.065842
V2_01_easy 0.015 0.017 0.089429 0.062083
V2_02_medium 0.017 0.017 0.059391 0.079471
V2_03_difficult X 0.045 X 0.468666
  • 'X' indicates the failure in this sequence.

** The left two columns are referring to Visual-Inertial Monocular SLAM with Map Reuse.

*** The right two columns are results of this repository obtained on laptop.

Visualization

The example visualizations on the dataset MH_04_difficult are at visualizations folder.

Trajectories in MH_04_difficult

Error projected on trajectory in MH_04_difficult

Accelerator biases


NOTE on Monocular VI ORB-SLAM from pangjing:

An implementation of Visual Inertial ORBSLAM based on ORB-SLAM2

Not bug-free. Not real-time. Just try the basic ideas of Visual Inertial SLAM in above paper. Welcome to improve it together!

Build with build.sh. Modify the path in config/euroc.yaml.

Tested on EuRoc ROS bag data with ROS launch file Examples/ROS/ORB_VIO/launch/testeuroc.launch. Files in pyplotscripts can be used to visualize some results.

Tested on sensors: UI-1221-LE and 3DM-GX3-25, see video on Youtube (real-time) or YouKu.

Please contact jp08-at-foxmail-dot-com for more details.

Below is the primary README of ORBSLAM2.


ORB-SLAM2

Authors: Raul Mur-Artal, Juan D. Tardos, J. M. M. Montiel and Dorian Galvez-Lopez (DBoW2)

Current version: 1.0.0

ORB-SLAM2 is a real-time SLAM library for Monocular, Stereo and RGB-D cameras that computes the camera trajectory and a sparse 3D reconstruction (in the stereo and RGB-D case with true scale). It is able to detect loops and relocalize the camera in real time. We provide examples to run the SLAM system in the KITTI dataset as stereo or monocular, in the TUM dataset as RGB-D or monocular, and in the EuRoC dataset as stereo or monocular. We also provide a ROS node to process live monocular, stereo or RGB-D streams. The library can be compiled without ROS. ORB-SLAM2 provides a GUI to change between a SLAM Mode and Localization Mode, see section 9 of this document.

ORB-SLAM2 ORB-SLAM2 ORB-SLAM2

Related Publications:

[Monocular] Raúl Mur-Artal, J. 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.

[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.

[DBoW2 Place Recognizer] Dorian Gálvez-López and Juan D. Tardós. Bags of Binary Words for Fast Place Recognition in Image Sequences. IEEE Transactions on Robotics, vol. 28, no. 5, pp. 1188-1197, 2012. PDF

1. License

ORB-SLAM2 is released under a GPLv3 license. For a list of all code/library dependencies (and associated licenses), please see Dependencies.md.

For a closed-source version of ORB-SLAM2 for commercial purposes, please contact the authors: orbslam (at) unizar (dot) es.

If you use ORB-SLAM2 (Monocular) in an academic work, please cite:

@article{murTRO2015,
  title={{ORB-SLAM}: a Versatile and Accurate Monocular {SLAM} System},
  author={Mur-Artal, Ra\'ul, Montiel, J. M. M. and Tard\'os, Juan D.},
  journal={IEEE Transactions on Robotics},
  volume={31},
  number={5},
  pages={1147--1163},
  doi = {10.1109/TRO.2015.2463671},
  year={2015}
 }

if you use ORB-SLAM2 (Stereo or RGB-D) in an academic work, please cite:

@article{murORB2,
  title={{ORB-SLAM2}: an Open-Source {SLAM} System for Monocular, Stereo and {RGB-D} Cameras},
  author={Mur-Artal, Ra\'ul and Tard\'os, Juan D.},
  journal={IEEE Transactions on Robotics},
  volume={33},
  number={5},
  pages={1255--1262},
  doi = {10.1109/TRO.2017.2705103},
  year={2017}
 }

2. Prerequisites

We have tested the library in Ubuntu 12.04, 14.04 and 16.04, but it should be easy to compile in other platforms. A powerful computer (e.g. i7) will ensure real-time performance and provide more stable and accurate results.

C++11 or C++0x Compiler

We use the new thread and chrono functionalities of C++11.

Pangolin

We use Pangolin for visualization and user interface. Dowload and install instructions can be found at: https://github.com/stevenlovegrove/Pangolin.

OpenCV

We use OpenCV to manipulate images and features. Dowload and install instructions can be found at: http://opencv.org. Required at leat 2.4.3. Tested with OpenCV 2.4.11 and OpenCV 3.2.

Eigen3

Required by g2o (see below). Download and install instructions can be found at: http://eigen.tuxfamily.org. Required at least 3.1.0.

BLAS and LAPACK

BLAS and LAPACK libraries are requiered by g2o (see below). On ubuntu:

sudo apt-get install libblas-dev
sudo apt-get install liblapack-dev

DBoW2 and g2o (Included in Thirdparty folder)

We use modified versions of the DBoW2 library to perform place recognition and g2o library to perform non-linear optimizations. Both modified libraries (which are BSD) are included in the Thirdparty folder.

ROS (optional)

We provide some examples to process the live input of a monocular, stereo or RGB-D camera using ROS. Building these examples is optional. In case you want to use ROS, a version Hydro or newer is needed.

3. Building ORB-SLAM2 library and examples

Clone the repository:

git clone https://github.com/raulmur/ORB_SLAM2.git ORB_SLAM2

We provide a script build.sh to build the Thirdparty libraries and ORB-SLAM2. Please make sure you have installed all required dependencies (see section 2). Execute:

cd ORB_SLAM2
chmod +x build.sh
./build.sh

This will create libORB_SLAM2.so at lib folder and the executables mono_tum, mono_kitti, rgbd_tum, stereo_kitti, mono_euroc and stereo_euroc in Examples folder.

4. Monocular Examples

TUM Dataset

  1. Download a sequence from http://vision.in.tum.de/data/datasets/rgbd-dataset/download and uncompress it.

  2. Execute the following command. Change TUMX.yaml to TUM1.yaml,TUM2.yaml or TUM3.yaml for freiburg1, freiburg2 and freiburg3 sequences respectively. Change PATH_TO_SEQUENCE_FOLDERto the uncompressed sequence folder.

./Examples/Monocular/mono_tum Vocabulary/ORBvoc.txt Examples/Monocular/TUMX.yaml PATH_TO_SEQUENCE_FOLDER

KITTI Dataset

  1. Download the dataset (grayscale images) from http://www.cvlibs.net/datasets/kitti/eval_odometry.php

  2. Execute the following command. Change KITTIX.yamlby KITTI00-02.yaml, KITTI03.yaml or KITTI04-12.yaml for sequence 0 to 2, 3, and 4 to 12 respectively. Change PATH_TO_DATASET_FOLDER to the uncompressed dataset folder. Change SEQUENCE_NUMBER to 00, 01, 02,.., 11.

./Examples/Monocular/mono_kitti Vocabulary/ORBvoc.txt Examples/Monocular/KITTIX.yaml PATH_TO_DATASET_FOLDER/dataset/sequences/SEQUENCE_NUMBER

EuRoC Dataset

  1. Download a sequence (ASL format) from http://projects.asl.ethz.ch/datasets/doku.php?id=kmavvisualinertialdatasets

  2. Execute the following first command for V1 and V2 sequences, or the second command for MH sequences. Change PATH_TO_SEQUENCE_FOLDER and SEQUENCE according to the sequence you want to run.

./Examples/Monocular/mono_euroc Vocabulary/ORBvoc.txt Examples/Monocular/EuRoC.yaml PATH_TO_SEQUENCE_FOLDER/mav0/cam0/data Examples/Monocular/EuRoC_TimeStamps/SEQUENCE.txt 
./Examples/Monocular/mono_euroc Vocabulary/ORBvoc.txt Examples/Monocular/EuRoC.yaml PATH_TO_SEQUENCE/cam0/data Examples/Monocular/EuRoC_TimeStamps/SEQUENCE.txt 

5. Stereo Examples

KITTI Dataset

  1. Download the dataset (grayscale images) from http://www.cvlibs.net/datasets/kitti/eval_odometry.php

  2. Execute the following command. Change KITTIX.yamlto KITTI00-02.yaml, KITTI03.yaml or KITTI04-12.yaml for sequence 0 to 2, 3, and 4 to 12 respectively. Change PATH_TO_DATASET_FOLDER to the uncompressed dataset folder. Change SEQUENCE_NUMBER to 00, 01, 02,.., 11.

./Examples/Stereo/stereo_kitti Vocabulary/ORBvoc.txt Examples/Stereo/KITTIX.yaml PATH_TO_DATASET_FOLDER/dataset/sequences/SEQUENCE_NUMBER

EuRoC Dataset

  1. Download a sequence (ASL format) from http://projects.asl.ethz.ch/datasets/doku.php?id=kmavvisualinertialdatasets

  2. Execute the following first command for V1 and V2 sequences, or the second command for MH sequences. Change PATH_TO_SEQUENCE_FOLDER and SEQUENCE according to the sequence you want to run.

./Examples/Stereo/stereo_euroc Vocabulary/ORBvoc.txt Examples/Stereo/EuRoC.yaml PATH_TO_SEQUENCE/mav0/cam0/data PATH_TO_SEQUENCE/mav0/cam1/data Examples/Stereo/EuRoC_TimeStamps/SEQUENCE.txt
./Examples/Stereo/stereo_euroc Vocabulary/ORBvoc.txt Examples/Stereo/EuRoC.yaml PATH_TO_SEQUENCE/cam0/data PATH_TO_SEQUENCE/cam1/data Examples/Stereo/EuRoC_TimeStamps/SEQUENCE.txt

6. RGB-D Example

TUM Dataset

  1. Download a sequence from http://vision.in.tum.de/data/datasets/rgbd-dataset/download and uncompress it.

  2. Associate RGB images and depth images using the python script associate.py. We already provide associations for some of the sequences in Examples/RGB-D/associations/. You can generate your own associations file executing:

python associate.py PATH_TO_SEQUENCE/rgb.txt PATH_TO_SEQUENCE/depth.txt > associations.txt
  1. Execute the following command. Change TUMX.yaml to TUM1.yaml,TUM2.yaml or TUM3.yaml for freiburg1, freiburg2 and freiburg3 sequences respectively. Change PATH_TO_SEQUENCE_FOLDERto the uncompressed sequence folder. Change ASSOCIATIONS_FILE to the path to the corresponding associations file.
./Examples/RGB-D/rgbd_tum Vocabulary/ORBvoc.txt Examples/RGB-D/TUMX.yaml PATH_TO_SEQUENCE_FOLDER ASSOCIATIONS_FILE

7. ROS Examples

Building the nodes for mono, monoAR, stereo and RGB-D

  1. Add the path including Examples/ROS/ORB_SLAM2 to the ROS_PACKAGE_PATH environment variable. Open .bashrc file and add at the end the following line. Replace PATH by the folder where you cloned ORB_SLAM2:
export ROS_PACKAGE_PATH=${ROS_PACKAGE_PATH}:PATH/ORB_SLAM2/Examples/ROS
  1. Execute build_ros.sh script:
chmod +x build_ros.sh
./build_ros.sh

Running Monocular Node

For a monocular input from topic /camera/image_raw run node ORB_SLAM2/Mono. You will need to provide the vocabulary file and a settings file. See the monocular examples above.

rosrun ORB_SLAM2 Mono PATH_TO_VOCABULARY PATH_TO_SETTINGS_FILE

Running Monocular Augmented Reality Demo

This is a demo of augmented reality where you can use an interface to insert virtual cubes in planar regions of the scene. The node reads images from topic /camera/image_raw.

rosrun ORB_SLAM2 MonoAR PATH_TO_VOCABULARY PATH_TO_SETTINGS_FILE

Running Stereo Node

For a stereo input from topic /camera/left/image_raw and /camera/right/image_raw run node ORB_SLAM2/Stereo. You will need to provide the vocabulary file and a settings file. If you provide rectification matrices (see Examples/Stereo/EuRoC.yaml example), the node will recitify the images online, otherwise images must be pre-rectified.

rosrun ORB_SLAM2 Stereo PATH_TO_VOCABULARY PATH_TO_SETTINGS_FILE ONLINE_RECTIFICATION

Example: Download a rosbag (e.g. V1_01_easy.bag) from the EuRoC dataset (http://projects.asl.ethz.ch/datasets/doku.php?id=kmavvisualinertialdatasets). Open 3 tabs on the terminal and run the following command at each tab:

roscore
rosrun ORB_SLAM2 Stereo Vocabulary/ORBvoc.txt Examples/Stereo/EuRoC.yaml true
rosbag play --pause V1_01_easy.bag /cam0/image_raw:=/camera/left/image_raw /cam1/image_raw:=/camera/right/image_raw

Once ORB-SLAM2 has loaded the vocabulary, press space in the rosbag tab. Enjoy!. Note: a powerful computer is required to run the most exigent sequences of this dataset.

Running RGB_D Node

For an RGB-D input from topics /camera/rgb/image_raw and /camera/depth_registered/image_raw, run node ORB_SLAM2/RGBD. You will need to provide the vocabulary file and a settings file. See the RGB-D example above.

rosrun ORB_SLAM2 RGBD PATH_TO_VOCABULARY PATH_TO_SETTINGS_FILE

8. Processing your own sequences

You will need to create a settings file with the calibration of your camera. See the settings file provided for the TUM and KITTI datasets for monocular, stereo and RGB-D cameras. We use the calibration model of OpenCV. See the examples to learn how to create a program that makes use of the ORB-SLAM2 library and how to pass images to the SLAM system. Stereo input must be synchronized and rectified. RGB-D input must be synchronized and depth registered.

9. SLAM and Localization Modes

You can change between the SLAM and Localization mode using the GUI of the map viewer.

SLAM Mode

This is the default mode. The system runs in parallal three threads: Tracking, Local Mapping and Loop Closing. The system localizes the camera, builds new map and tries to close loops.

Localization Mode

This mode can be used when you have a good map of your working area. In this mode the Local Mapping and Loop Closing are deactivated. The system localizes the camera in the map (which is no longer updated), using relocalization if needed.

Note that the project description data, including the texts, logos, images, and/or trademarks, for each open source project belongs to its rightful owner. If you wish to add or remove any projects, please contact us at [email protected].