Documentation Index
Fetch the complete documentation index at: https://mintlify.com/UZ-SLAMLab/ORB_SLAM3/llms.txt
Use this file to discover all available pages before exploring further.
Overview
Settings is the configuration management class that loads and provides access to all system parameters from YAML configuration files. It handles camera calibration, ORB feature settings, IMU parameters, viewer options, and sensor-specific configurations.
Header: Settings.h
Namespace: ORB_SLAM3
Constructor
Settings(const std::string &configFile, const int &sensor)
Load settings from YAML configuration file.
Parameters:
configFile - Path to YAML configuration file
sensor - Sensor type (MONOCULAR, STEREO, RGBD, IMU_MONOCULAR, IMU_STEREO, IMU_RGBD)
Note: Default constructor is deleted; must construct with config file.
Camera Type Enum
enum CameraType {
PinHole = 0,
Rectified = 1,
KannalaBrandt = 2
}
Defines supported camera model types.
Camera Settings
Camera Type and Models
Get the camera type.
GeometricCamera* camera1()
Get the primary camera model (or left camera in stereo).
GeometricCamera* camera2()
Get the secondary camera model (right camera in stereo).
Returns: Pointer to Pinhole or KannalaBrandt8 camera.
Distortion Coefficients
cv::Mat camera1DistortionCoef()
cv::Mat camera2DistortionCoef()
Get distortion coefficients for pinhole cameras (radial-tangential model).
Returns: OpenCV matrix of distortion coefficients.
Image Processing Flags
Check if images need undistortion.
Check if images need resizing.
Check if stereo images need rectification.
Image Properties
Get target image size after preprocessing.
Get camera frame rate (frames per second).
Check if images are RGB (true) or BGR (false).
Stereo Settings
Get transform from left to right camera.
Get baseline × focal length product (used for depth computation).
Get stereo baseline in meters.
Depth Threshold
Get depth threshold for far/close point classification.
Returns: Threshold in meters (typically 40 × baseline).
Rectification Maps
cv::Mat M1l()
cv::Mat M2l()
cv::Mat M1r()
cv::Mat M2r()
Get rectification maps for left (l) and right (r) cameras.
Returns: OpenCV remap matrices (M1 = x map, M2 = y map).
IMU Settings
Relevant for IMU-enabled modes (IMU_MONOCULAR, IMU_STEREO, IMU_RGBD).
Noise Parameters
Get gyroscope noise density (rad/s/√Hz).
Get accelerometer noise density (m/s²/√Hz).
Random Walk
Get gyroscope random walk (rad/s²/√Hz).
Get accelerometer random walk (m/s³/√Hz).
IMU Properties
Get IMU sampling frequency (Hz).
Get transform from IMU body frame to camera frame.
Tracking Behavior
Check if keyframes should be inserted when tracking is lost.
RGBD Settings
Get depth scaling factor (converts depth image values to meters).
Example: If depth is in mm, factor = 1000.0 or 5000.0.
ORB Feature Settings
Feature Parameters
Get number of ORB features to extract per frame.
Default: Typically 1000-2000.
Get pyramid scale factor between levels.
Default: Typically 1.2.
Get number of pyramid levels.
Default: Typically 8.
FAST Thresholds
Get initial FAST threshold.
Get minimum FAST threshold (fallback if too few features detected).
Viewer Settings
Display Scales
Keyframe visualization size.
float keyFrameLineWidth()
Keyframe edge line width.
Covisibility graph line width.
Map point visualization size.
Camera frustum size.
Camera frustum line width.
Viewpoint
float viewPointX()
float viewPointY()
float viewPointZ()
float viewPointF()
Get initial viewpoint position (X, Y, Z) and focal length (F) for the 3D viewer.
Image Viewer
Get image viewer display scale factor.
Map Save/Load
std::string atlasLoadFile()
Get path to load existing map atlas.
std::string atlasSaveFile()
Get path to save map atlas.
Other Parameters
Get threshold for far points (used in certain tracking scenarios).
Stream Output
friend std::ostream& operator<<(std::ostream &output, const Settings &s)
Output all settings to stream for debugging.
Usage:
Settings settings("config.yaml", System::STEREO);
std::cout << settings << std::endl;
Usage Example
#include "Settings.h"
#include "System.h"
// Load settings
Settings settings("config.yaml", ORB_SLAM3::System::IMU_STEREO);
// Camera parameters
GeometricCamera* cam1 = settings.camera1();
GeometricCamera* cam2 = settings.camera2();
float baseline = settings.b();
// IMU parameters
if (settings.sensor_ >= System::IMU_MONOCULAR) {
float gyro_noise = settings.noiseGyro();
float acc_noise = settings.noiseAcc();
Sophus::SE3f Tbc = settings.Tbc();
}
// ORB parameters
int num_features = settings.nFeatures();
float scale_factor = settings.scaleFactor();
int num_levels = settings.nLevels();
// Print all settings
std::cout << settings;
YAML Configuration Structure
The Settings class reads from YAML files with the following sections:
Camera Section
Camera.type: "PinHole" or "KannalaBrandt"
Camera1.fx: 458.654
Camera1.fy: 457.296
Camera1.cx: 367.215
Camera1.cy: 248.375
# Pinhole distortion (optional)
Camera1.k1: -0.28340811
Camera1.k2: 0.07395907
# Fisheye distortion (KB8)
Camera1.k3: 0.0
Camera1.k4: 0.0
Stereo Section
Stereo.ThDepth: 40.0
Stereo.b: 0.0573
# Stereo rectification
LEFT.D: [distortion coefficients]
LEFT.K: [3x3 intrinsic matrix]
IMU Section
IMU.NoiseGyro: 0.01
IMU.NoiseAcc: 0.1
IMU.GyroWalk: 0.0001
IMU.AccWalk: 0.001
IMU.Frequency: 200
# IMU-Camera extrinsics (4x4 matrix)
Tbc: !!opencv-matrix
rows: 4
cols: 4
data: [... 16 values ...]
ORB Section
ORBextractor.nFeatures: 1000
ORBextractor.scaleFactor: 1.2
ORBextractor.nLevels: 8
ORBextractor.iniThFAST: 20
ORBextractor.minThFAST: 7
Viewer Section
Viewer.KeyFrameSize: 0.05
Viewer.KeyFrameLineWidth: 1.0
Viewer.GraphLineWidth: 0.9
Viewer.PointSize: 2.0
Viewer.CameraSize: 0.08
Viewer.CameraLineWidth: 3.0
Viewer.ViewpointX: 0.0
Viewer.ViewpointY: -0.7
Viewer.ViewpointZ: -1.8
Viewer.ViewpointF: 500.0
Implementation Details
The Settings class:
- Uses OpenCV’s FileStorage to parse YAML
- Validates required parameters (exits if missing)
- Supports optional parameters with defaults
- Precomputes rectification maps for stereo
- Creates appropriate camera model objects (Pinhole or KannalaBrandt8)
Thread Safety
Settings objects are typically read-only after construction and can be safely shared across threads.
See Also
- System - Main SLAM system using Settings
- GeometricCamera - Camera model interface
- IMU Types - IMU structures and calibration
- Example configuration files in
Examples/ directories