The raw address: https://github.com/UZ-SLAMLab/ORB_SLAM3
Copy: git config --global core.protectNTFS false && git clone https://github.com/shanpenghui/ORB_SLAM3_Fixed
Reference article 参考文章:
EVO Evaluation of SLAM 4 --- ORB-SLAM3 编译和利用数据集运行 https://blog.csdn.net/shanpenghui/article/details/109354918
EVO Evaluation of SLAM 5 --- ORB-SLAM3 精度和性能效果评估 https://blog.csdn.net/shanpenghui/article/details/109361766
Examples Monocular/Monocular-Inertial is available
Authors: Carlos Campos, Richard Elvira, Juan J. Gómez Rodríguez, José M. M. Montiel, Juan D. Tardos.
The Changelog describes the features of each version.
ORB-SLAM3 is the first real-time SLAM library able to perform Visual, Visual-Inertial and Multi-Map SLAM with monocular, stereo and RGB-D cameras, using pin-hole and fisheye lens models. In all sensor configurations, ORB-SLAM3 is as robust as the best systems available in the literature, and significantly more accurate.
We provide examples to run ORB-SLAM3 in the EuRoC dataset using stereo or monocular, with or without IMU, and in the TUM-VI dataset using fisheye stereo or monocular, with or without IMU. Videos of some example executions can be found at ORB-SLAM3 channel.
This software is based on ORB-SLAM2 developed by Raul Mur-Artal, Juan D. Tardos, J. M. M. Montiel and Dorian Galvez-Lopez (DBoW2).
Pangolin:
git clone https://github.com/stevenlovegrove/Pangolin.git
sudo apt install libglew-dev
cd Pangolin && mkdir build && cd build
cmake ..
make -j 32
sudo make install
Googlelog:
git clone https://github.com/google/glog
cd glog
cmake -H. -Bbuild -G "Unix Makefiles"
cmake --build build
cmake --build build --target test
cd build
sudo make install
OpenCV: https://docs.opencv.org/master/d0/d3d/tutorial_general_install.html
git clone https://github.com/opencv/opencv
git -C opencv checkout 4.5.1
git clone https://github.com/opencv/opencv_contrib
git -C opencv_contrib checkout 4.5.1
git clone https://github.com/opencv/opencv_extra
git -C opencv_extra checkout 4.5.1
cmake ..
make -j4
sudo make install
OpenCV:
git clone https://github.com/opencv/opencv
cd opencv
mkdir build
cd build
cmake ..
make -j 32
sudo make install
ippicv_2020_lnx_intel64_20191018_general.tgz 下载地址: 链接: https://pan.baidu.com/s/1XwhaDnTaCxAIpmZCRijYvg 提取码: rq4r
Work in shells path, continue the operation upon:
cd shells
./build.sh
Before running, you should change the path in tum_vi.sh where you save the dataset, such as:
pathDatasetTUM_VI='/home/sph/Downloads' #Example, it is necesary to change it by the dataset path
Remember to unzip the ORBvoc.txt.tar.gz into Vocabulary folder!!!
Work in shells path
cd shells
./tum_vi.sh
or
./euroc.sh
Build ros version
cd shells
./build_ros.sh
Set ROS_PACKAGE_PATH:
export ROS_PACKAGE_PATH=${ROS_PACKAGE_PATH}:/home/sph/Documents/ORB_SLAM3_Fixed/Examples/ROS
Run ros-version ORB-SLAM3 in root path:
cd ORB_SLAM3_Fixed
rosrun ORB_SLAM3 Mono Vocabulary/ORBvoc.txt Examples/Monocular-Inertial/TUM_512.yaml
目前只有单目带IMU的被激活,里面的配置需要对应自己的电脑更新
原版出现的错误(因为本工程是在ORB3刚开放的时候就建立了,所以有些问题应该被作者修复了,如果有遗漏或冗余请读者自行忽略)
原版ros的编译会出现ORBSLAM2的错误
error: ‘ORB_SLAM2’ has not been declared
ImageGrabber(ORB_SLAM2::System* pSLAM):mpSLAM(pSLAM){}
需要用指令修复:
sed -i "s/ORB_SLAM2/ORB_SLAM3/g" `grep -rl "ORB_SLAM2"`
原版ros的编译也有可能出现找不到文件的错误:
fatal error: GeometricCamera.h: No such file or directory #include "GeometricCamera.h"
需要在CMakeList添加文件路径:
${PROJECT_SOURCE_DIR}/../../../include/CameraModels
But!!!! You can`t run ORB-SLAM3 without run the camera_node!!!! So, if you want to test ros-version, just use your computer camera(wish you have)
git clone https://github.com/bosch-ros-pkg/usb_cam.git
Build and launch it, so you can see the /usb_cam/image_raw in rostopic. But, that is not enough!!!!! You should change the rostopic name in ORB-SLAM3, which is in Line 62, ros_mono.cc
ros::Subscriber sub = nodeHandler.subscribe("/usb_cam/image_raw", 1, &ImageGrabber::GrabImage,&igb);
After the steps up, it work finally!
When I first run it, error come out:
Failed to load module "canberra-gtk-module"
To solve this problem, install the module:
sudo apt-get install libcanberra-gtk-module
Make sure docker is installed please !!!
docker pull registry.cn-hangzhou.aliyuncs.com/slam_docker/slam_docker:gpu
cd ORB_SLAM3_Fixed/shells
sudo ./run_docker_gpu.sh <path_of_realsense_ros> <path_of_orbslam3_fixed> host
The project realsense-ros link is https://github.com/IntelRealSense/realsense-ros
If you can not launch roscore, you can solve by add hostname which is needed by roscore into the file /etc/hosts.
If want to debug remote by clion, try in docker after run with run_docker_gpu.sh shells:
service ssh restart
service rsync restart
And then use sftp name/password :
user/crc
Or
remoter_user/crc
If cannot create a directory, delete the cmake-build-debug-remote-host folder and reload cmake project.
If you want to add dataset, just add the text:
--volume="/home/<your_user_name>:/home/<your_user_name>" \
into ORB_SLAM3_Fixed/shells/run_docker_gpu.sh file.
Run the command below:
rs-enumerate-devices -c
Modify the file ORB-SLAM3-Fixed/Examples/Monocular-Inertial/TUM_512.yaml.
The relation of .yaml file and realsense-sdk info is :
Intrinsic/Extrinsic from "Gyro" To "Fisheye 1" (realsense-sdk info) = Rotation matrix of Tbc #Transformation from body-frame (imu) to camera (ORB-SLAM3-Fixed/Examples/Monocular-Inertial/TUM_512.yaml)
Intrinsic Params:
PPX --> Camera.cx
PPY --> Camera.cy
Fx --> Camera.fx
Fy --> Camera.fy
Coeffs[0] --> Camera.k1
Coeffs[1] --> Camera.k2
Coeffs[2] --> Camera.k3
Coeffs[3] --> Camera.k4
Extrinsic Params:
Rotation_Matrix (Extrinsic from "Gyro" To "Fisheye 1") --> Tbc.data.R
Rotation_Matrix[0][0] --> Tbc.data[0][0]
Rotation_Matrix[0][1] --> Tbc.data[0][1]
Rotation_Matrix[0][2] --> Tbc.data[0][2]
Rotation_Matrix[1][0] --> Tbc.data[1][0]
Rotation_Matrix[1][1] --> Tbc.data[1][1]
Rotation_Matrix[1][2] --> Tbc.data[1][2]
Rotation_Matrix[2][0] --> Tbc.data[2][0]
Rotation_Matrix[2][1] --> Tbc.data[2][1]
Rotation_Matrix[2][2] --> Tbc.data[2][2]
Translation Vector (Extrinsic from "Gyro" To "Fisheye 1") --> Tbc.data.t
Translation_Vector[0] --> Tbc.data[0][3]
Translation_Vector[1] --> Tbc.data[1][3]
Translation_Vector[2] --> Tbc.data[2][3]
- terminal one
mkdir -p imu_utils_ws/src && cd imu_utils_ws/src && git clone https://github.com/IntelRealSense/realsense-ros.git
cd .. && source /opt/ros/noetic/setup.bash && catkin_make && source devel/setup.bash
roslaunch realsense2_camera rs_t265.launch fisheye_width:=848 fisheye_height:=800 enable_fisheye1:=true enable_fisheye2:=true unite_imu_method:=copy
- terminal two
rosbag record -O imu_calibration /camera/imu
- terminal one
mkdir -p imu_utils_ws/src && cd imu_utils_ws/src && git clone https://github.com/shanpenghui/imu_utils.git
cd .. && source /opt/ros/noetic/setup.bash && catkin_make && source devel/setup.bash
roslaunch imu_utils realsense.launch
- terminal two
rosbag play -r 200 imu_calibration.bag
The result is in imu_utils/imu_utils/data/t265_imu_calibration_imu_param.yaml, map to ORB-SLAM3-Fixed/Examples/Monocular-Inertial/TUM_512.yaml
Gyr.avg-axis.gyr_n --> IMU.NoiseGyro
Gyr.avg-axis.gyr_w --> IMU.GyroWalk
Acc.avg-axis.acc_n --> IMU.NoiseAcc
Acc.avg-axis.acc_w --> IMU.AccWalk
So git checkout tag , then build and run (don't forget changing the unite_imu_method param in rs_t265.launch) :
git clone https://github.com/IntelRealSense/realsense-ros
cd realsense-ros
git checkout development
git pull
Run rs_t265.launch with params :
roslaunch realsense2_camera rs_t265.launch fisheye_width:=848 fisheye_height:=800 enable_fisheye1:=true enable_fisheye2:=true unite_imu_method:=copy
To make this code suitable for dataset, so the topic change is not commited in code.
Before use own camera, you should change imu topic name from /imu to :
(in Line 98 of ORB_SLAM3_Fixed/Examples/ROS/ORB_SLAM3/src/ros_mono_inertial.cc)
/camera/imu
Before do this step, change the file_path in mono_inertial.launch file to your own env.
This example is :
args="/home/user/Downloads/ORB_SLAM3_Fixed/Vocabulary/ORBvoc.txt /home/user/Downloads/ORB_SLAM3_Fixed/Examples/Monocular-Inertial/TUM_512.yaml"
The format is :
args="<your_path>/ORB_SLAM3_Fixed/Vocabulary/ORBvoc.txt <your_path>/ORB_SLAM3_Fixed/Examples/Monocular-Inertial/TUM_512.yaml"
Then run :
source /opt/ros/noetic/setup.bash
export ROS_PACKAGE_PATH=${ROS_PACKAGE_PATH}:<your_path>/ORB_SLAM3_Fixed/Examples/ROS
roslaunch ORB_SLAM3 mono_inertial.launch
Authors: Carlos Campos, Richard Elvira, Juan J. Gómez Rodríguez, José M. M. Montiel, Juan D. Tardos.
The Changelog describes the features of each version.
ORB-SLAM3 is the first real-time SLAM library able to perform Visual, Visual-Inertial and Multi-Map SLAM with monocular, stereo and RGB-D cameras, using pin-hole and fisheye lens models. In all sensor configurations, ORB-SLAM3 is as robust as the best systems available in the literature, and significantly more accurate.
We provide examples to run ORB-SLAM3 in the EuRoC dataset using stereo or monocular, with or without IMU, and in the TUM-VI dataset using fisheye stereo or monocular, with or without IMU. Videos of some example executions can be found at ORB-SLAM3 channel.
This software is based on ORB-SLAM2 developed by Raul Mur-Artal, Juan D. Tardos, J. M. M. Montiel and Dorian Galvez-Lopez (DBoW2).
[ORB-SLAM3] Carlos Campos, Richard Elvira, Juan J. Gómez Rodríguez, José M. M. 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, Dec. 2021. PDF.
[IMU-Initialization] Carlos Campos, J. M. M. Montiel and Juan D. Tardós, Inertial-Only 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 map reuse, 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. Bags of Binary Words for Fast Place Recognition in Image Sequences. IEEE Transactions on Robotics, vol. 28, no. 5, pp. 1188-1197, 2012. PDF
ORB-SLAM3 is released under GPLv3 license. For a list of all code/library dependencies (and associated licenses), please see Dependencies.md.
For a closed-source version of ORB-SLAM3 for commercial purposes, please contact the authors: orbslam (at) unizar (dot) es.
If you use ORB-SLAM3 in an 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}
}
We have tested the library in Ubuntu 16.04 and 18.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.
We use the new thread and chrono functionalities of C++11.
We use Pangolin for visualization and user interface. Dowload and install instructions can be found at: https://github.com/stevenlovegrove/Pangolin.
We use OpenCV to manipulate images and features. Dowload and install instructions can be found at: http://opencv.org. Required at leat 3.0. Tested with OpenCV 3.2.0 and 4.4.0.
Required by g2o (see below). Download and install instructions can be found at: http://eigen.tuxfamily.org. Required at least 3.1.0.
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.
Required to calculate the alignment of the trajectory with the ground truth. Required Numpy module.
- (win) http://www.python.org/downloads/windows
- (deb)
sudo apt install libpython2.7-dev
- (mac) preinstalled with osx
We provide some examples to process input of a monocular, monocular-inertial, stereo, stereo-inertial or RGB-D camera using ROS. Building these examples is optional. These have been tested with ROS Melodic under Ubuntu 18.04.
Clone the repository:
git clone https://github.com/UZ-SLAMLab/ORB_SLAM3.git ORB_SLAM3
We provide a script build.sh
to build the Thirdparty libraries and ORB-SLAM3. Please make sure you have installed all required dependencies (see section 2). Execute:
cd ORB_SLAM3
chmod +x build.sh
./build.sh
This will create libORB_SLAM3.so at lib folder and the executables in Examples folder.
Directory Examples
contains several demo programs and calibration files to run ORB-SLAM3 in all sensor configurations with Intel Realsense cameras T265 and D435i. The steps needed to use your own camera are:
-
Calibrate your camera following
Calibration_Tutorial.pdf
and write your calibration fileyour_camera.yaml
-
Modify one of the provided demos to suit your specific camera model, and build it
-
Connect the camera to your computer using USB3 or the 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
EuRoC dataset was recorded with two pinhole cameras and an inertial sensor. We provide an example script to launch EuRoC sequences in all the sensor configurations.
-
Download a sequence (ASL format) from http://projects.asl.ethz.ch/datasets/doku.php?id=kmavvisualinertialdatasets
-
Open the script "euroc_examples.sh" in the root of the project. Change pathDatasetEuroc variable to point to the directory where the dataset has been uncompressed.
-
Execute the following script to process all the sequences with all sensor configurations:
./euroc_examples
EuRoC provides ground truth for each sequence in the IMU body reference. As pure visual executions report trajectories centered in the left camera, we provide in the "evaluation" folder the transformation of the ground truth to the left camera reference. Visual-inertial trajectories use the ground truth from the dataset.
Execute the following script to process sequences and compute the RMS ATE:
./euroc_eval_examples
TUM-VI dataset was recorded with two fisheye cameras and an inertial sensor.
-
Download a sequence from https://vision.in.tum.de/data/datasets/visual-inertial-dataset and uncompress it.
-
Open the script "tum_vi_examples.sh" in the root of the project. Change pathDatasetTUM_VI variable to point to the directory where the dataset has been uncompressed.
-
Execute the following script to process all the sequences with all sensor configurations:
./tum_vi_examples
In TUM-VI ground truth is only available in the room where all sequences start and end. As a result the error measures the drift at the end of the sequence.
Execute the following script to process sequences and compute the RMS ATE:
./tum_vi_eval_examples
Tested with ROS Melodic and ubuntu 18.04.
- Add the path including Examples/ROS/ORB_SLAM3 to the ROS_PACKAGE_PATH environment variable. Open .bashrc file:
gedit ~/.bashrc
and add at the end the following line. Replace PATH by the folder where you cloned ORB_SLAM3:
export ROS_PACKAGE_PATH=${ROS_PACKAGE_PATH}:PATH/ORB_SLAM3/Examples/ROS
- Execute
build_ros.sh
script:
chmod +x build_ros.sh
./build_ros.sh
For a monocular input from topic /camera/image_raw
run node ORB_SLAM3/Mono. You will need to provide the vocabulary file and a settings file. See the monocular examples above.
rosrun ORB_SLAM3 Mono PATH_TO_VOCABULARY PATH_TO_SETTINGS_FILE
For a monocular input from topic /camera/image_raw
and an inertial input from topic /imu
, run node ORB_SLAM3/Mono_Inertial. Setting the optional third argument to true will apply CLAHE equalization to images (Mainly for TUM-VI dataset).
rosrun ORB_SLAM3 Mono PATH_TO_VOCABULARY PATH_TO_SETTINGS_FILE [EQUALIZATION]
For a stereo input from topic /camera/left/image_raw
and /camera/right/image_raw
run node ORB_SLAM3/Stereo. You will need to provide the vocabulary file and a settings file. For Pinhole camera model, if you provide rectification matrices (see Examples/Stereo/EuRoC.yaml example), the node will recitify the images online, otherwise images must be pre-rectified. For FishEye camera model, rectification is not required since system works with original images:
rosrun ORB_SLAM3 Stereo PATH_TO_VOCABULARY PATH_TO_SETTINGS_FILE ONLINE_RECTIFICATION
For a stereo input from topics /camera/left/image_raw
and /camera/right/image_raw
, and an inertial input from topic /imu
, run node ORB_SLAM3/Stereo_Inertial. You will need to provide the vocabulary file and a settings file, including rectification matrices if required in a similar way to Stereo case:
rosrun ORB_SLAM3 Stereo_Inertial PATH_TO_VOCABULARY PATH_TO_SETTINGS_FILE ONLINE_RECTIFICATION [EQUALIZATION]
For an RGB-D input from topics /camera/rgb/image_raw
and /camera/depth_registered/image_raw
, run node ORB_SLAM3/RGBD. You will need to provide the 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 example: Download a rosbag (e.g. V1_02_medium.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 for a Stereo-Inertial configuration:
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 space in the rosbag tab.
Remark: For rosbags from TUM-VI dataset, some play issue may appear due to chunk size. One possible solution is to rebag them with the default chunk size, for example:
rosrun rosbag fastrebag.py dataset-room1_512_16.bag dataset-room1_512_16_small_chunks.bag
A flag in include\Config.h
activates time measurements. It is necessary to uncomment the line #define REGISTER_TIMES
to obtain the time stats of one execution which is shown at the terminal and stored in a text file(ExecTimeMean.txt
).
You can find a tutorial for visual-inertial calibration and a detailed description of the contents of valid configuration files at Calibration_Tutorial.pdf