Skip to main content

Overview

This guide will help you run your first ORB-SLAM3 example. We’ll use the monocular SLAM example with the TUM RGB-D dataset, which is one of the simplest configurations to get started.
Before proceeding, make sure you have installed ORB-SLAM3 and verified that the compilation was successful.

Quick Start with TUM Dataset

1

Download a Dataset

Download a sample sequence from the TUM RGB-D dataset:
# Create a directory for datasets
mkdir -p ~/Datasets
cd ~/Datasets

# Download a small sequence (freiburg1_xyz, ~154 MB)
wget https://vision.in.tum.de/rgbd/dataset/freiburg1/rgbd_dataset_freiburg1_xyz.tgz

# Extract the dataset
tar -xvzf rgbd_dataset_freiburg1_xyz.tgz
This sequence contains 798 frames of a camera moving in x, y, and z directions.
2

Navigate to ORB-SLAM3 Directory

Make sure you’re in the ORB-SLAM3 root directory:
cd ~/ORB_SLAM3
3

Run Monocular SLAM

Execute the monocular SLAM example:
./Examples/Monocular/mono_tum \
    Vocabulary/ORBvoc.txt \
    Examples/Monocular/TUM1.yaml \
    ~/Datasets/rgbd_dataset_freiburg1_xyz
Command breakdown:
  • Vocabulary/ORBvoc.txt: The ORB vocabulary for place recognition
  • Examples/Monocular/TUM1.yaml: Camera calibration and SLAM parameters
  • ~/Datasets/rgbd_dataset_freiburg1_xyz: Path to the dataset
4

View the Results

You should see two windows:
  1. ORB-SLAM3 Viewer: 3D visualization showing:
    • Green points: Current map points
    • Red boxes: Keyframes
    • Blue line: Current camera pose
    • Camera trajectory in real-time
  2. Frame Viewer: Shows the current frame with:
    • Tracked ORB features
    • Current tracking state
    • Number of tracked features
The system needs a few frames to initialize. Look for the message “System initialized” in the terminal.

Understanding the Output

During execution, ORB-SLAM3 will print status information:
Images in the sequence: 798
-------
Start processing sequence ...

New Map created with 135 points
System initialized

Local Mapping: Active
Loop Closing: Active
After processing completes, you’ll see performance statistics:
-------
median tracking time: 0.0342
mean tracking time: 0.0389
The camera trajectory is automatically saved to KeyFrameTrajectory.txt in TUM format.

Understanding the System API

Here’s how the monocular example initializes and uses ORB-SLAM3 (from Examples/Monocular/mono_tum.cc:50):
// Create SLAM system. It initializes all system threads and gets ready to process frames.
ORB_SLAM3::System SLAM(argv[1], argv[2], ORB_SLAM3::System::MONOCULAR, true);

// Main tracking loop
for(int ni=0; ni<nImages; ni++)
{
    // Read image from file
    cv::Mat im = cv::imread(image_path, cv::IMREAD_UNCHANGED);
    double timestamp = vTimestamps[ni];
    
    // Pass the image to the SLAM system
    SLAM.TrackMonocular(im, timestamp);
}

// Stop all threads
SLAM.Shutdown();

// Save camera trajectory
SLAM.SaveKeyFrameTrajectoryTUM("KeyFrameTrajectory.txt");

System Constructor

The System constructor (from include/System.h:105) takes:
System(const string &strVocFile,           // Path to vocabulary file
       const string &strSettingsFile,      // Path to settings YAML file  
       const eSensor sensor,               // Sensor type
       const bool bUseViewer = true,       // Enable/disable viewer
       const int initFr = 0,               // Initial frame number
       const string &strSequence = std::string())  // Sequence name

Sensor Types

Available sensor types (from include/System.h:87-94):
enum eSensor{
    MONOCULAR=0,
    STEREO=1,
    RGBD=2,
    IMU_MONOCULAR=3,
    IMU_STEREO=4,
    IMU_RGBD=5,
};

Tracking Methods

Depending on your sensor configuration, use the appropriate tracking method:
// Monocular (from include/System.h:121)
Sophus::SE3f TrackMonocular(const cv::Mat &im, 
                             const double &timestamp,
                             const vector<IMU::Point>& vImuMeas = vector<IMU::Point>());

// Stereo (from include/System.h:110)
Sophus::SE3f TrackStereo(const cv::Mat &imLeft, 
                         const cv::Mat &imRight, 
                         const double &timestamp,
                         const vector<IMU::Point>& vImuMeas = vector<IMU::Point>());

// RGB-D (from include/System.h:116)
Sophus::SE3f TrackRGBD(const cv::Mat &im, 
                       const cv::Mat &depthmap, 
                       const double &timestamp,
                       const vector<IMU::Point>& vImuMeas = vector<IMU::Point>());
All tracking methods return the camera pose as a Sophus::SE3f transformation (empty if tracking fails).

Other Examples

Stereo SLAM (EuRoC Dataset)

# Download EuRoC dataset sequence
wget http://robotics.ethz.ch/~asl-datasets/ijrr_euroc_mav_dataset/machine_hall/MH_01_easy/MH_01_easy.zip
unzip MH_01_easy.zip -d ~/Datasets/EuRoC/MH01

# Run stereo SLAM
./Examples/Stereo/stereo_euroc \
    Vocabulary/ORBvoc.txt \
    Examples/Stereo/EuRoC.yaml \
    ~/Datasets/EuRoC/MH01 \
    Examples/Stereo/EuRoC_TimeStamps/MH01.txt

RGB-D SLAM

# Using the same TUM dataset with depth
./Examples/RGB-D/rgbd_tum \
    Vocabulary/ORBvoc.txt \
    Examples/RGB-D/TUM1.yaml \
    ~/Datasets/rgbd_dataset_freiburg1_xyz \
    Examples/RGB-D/associations/fr1_xyz.txt
RGB-D examples require association files that pair RGB images with depth images. These are provided in Examples/RGB-D/associations/.

Using Your Own Camera

To use ORB-SLAM3 with your own camera:
1

Calibrate Your Camera

Follow the instructions in Calibration_Tutorial.pdf to calibrate your camera and create a YAML configuration file.
2

Modify an Example

Copy and modify one of the provided examples (e.g., Examples/Monocular/mono_tum.cc) to read from your camera source instead of files.
3

Build Your Example

Add your example to CMakeLists.txt and rebuild:
./build.sh
For Intel RealSense cameras (T265, D435i), ready-to-use examples are provided in the Examples directory.

Performance Tips

  • Use a powerful computer (Intel i7 or equivalent)
  • Reduce image resolution if needed (configure in YAML file)
  • Disable the viewer for maximum performance: set the 4th parameter to false in the System constructor
  • Compile in Release mode (default in build.sh)
  • Ensure good lighting conditions
  • Avoid rapid camera movements during initialization
  • Include visual texture in the scene (avoid blank walls)
  • For IMU configurations, keep the camera-IMU synchronized
  • Check the Frame Viewer for the number of tracked features (should be > 30)
  • Look for “Tracking Lost” messages in the terminal
  • Verify camera calibration is correct
  • Enable verbose output by setting the verbosity level

Saving and Loading Results

ORB-SLAM3 provides several methods to save trajectory data (from include/System.h:143-168):
// Save in TUM RGB-D format (works for all sensor types)
SLAM.SaveKeyFrameTrajectoryTUM("KeyFrameTrajectory.txt");

// Save in EuRoC format
SLAM.SaveTrajectoryEuRoC("CameraTrajectory.txt");
SLAM.SaveKeyFrameTrajectoryEuRoC("KeyFrameTrajectory.txt");

// Save in KITTI format (stereo and RGB-D only)
SLAM.SaveTrajectoryKITTI("CameraTrajectory.txt");
Always call SLAM.Shutdown() before saving trajectories to ensure all threads have finished processing.

Next Steps

Now that you’ve run your first example, explore more advanced features:

API Reference

Learn about the complete System class API

Configuration

Understand the YAML configuration files

Examples

Explore examples for all sensor configurations

Datasets

Download and use popular SLAM datasets

Build docs developers (and LLMs) love