[KnowledgeBase] LPSLAM Configuration File

This page documents and describes all the available parameters to configure LPSLAM.

manager section

The manager acts as the primary interface between the user and the Visual-SLAM backend. It allows users to set, enable, and disable general functionalities of LPSLAM.

Argument

Type

Description

Argument

Type

Description

create_occupancy

bool

Activate/deactivate filling the occupancy grid.

drop_frames

bool

Allow to drop frames if the processing time is too slow.

occupancy_file

string

File to save the generated occupancy map.

record

bool

Enable/disable recording data.

record_raw

bool

If "record": true, record raw data.

replay_chunks

int

Number of items in the processing batch when replaying data.

show_live

bool

Activate/deactivate a live view of the camera input.

thread_num

int

Number of threads to use for processing.

 

cameras section

Here, one sets the crucial calibration parameters for the utilized camera. These parameters define the relationship between 3D points in the world and their corresponding image projections. Accurate calibration ensures the camera model accurately reflects the real world, allowing for precise reconstruction of the environment in Visual-SLAM.

Argument

Type

Description

Argument

Type

Description

number

int

The number assigned to the desired camera device starts from 0. When there is only one camera connected to the system 0 is the default.

model

string

Specifies the camera’s mathematical model.

Available options:

  • fisheye

  • omni

  • perspective

  • no_distortion

fx

double

Focal length of the camera in the X-direction, in pixels.

fy

double

Focal length of the camera in the Y-direction, in pixels.

cx

double

The principal point (optical center) of the camera in the X-direction, in pixels. It represents the intersection of the optical axis with the image plane.

cy

double

The principal point (optical center) of the camera in the Y-direction, in pixels.

f_correction

double

If model: omni : Factor to correct the focal length in the calibration matrix. In general, a smaller focal length leads to a smaller field of view and vice versa.

c_correction

double

If model: omni : Factor to correct the camera’s origin in the calibration matrix.

resolution_x

double

The horizontal resolution of the camera image sensor, in pixels.

resolution_y

double

The vertical resolution of the camera image sensor, in pixels.

scaling_factor

double

Factor to scale down the image.

Use values between [0, 1].

fps

int

Represents the camera’s frame rate or the number of images it captures per second.

distortion

vector<double>

Deviation of the camera lens from a perfect pinhole model. In other words, the geometric distortion introduced by the lens. It is represented as a vector of distortion coefficients:

  • [k1, k2, p1, p2, k3] for equirectangular and perspective distortion models.

  • [k1, k2, k3, k4] for fisheye distortion model.

  • [xi, k1, k2, p1, p2] for omni distortion model.

focal_x_baseline

double

Specific to stereo cameras, it represents the distance between the optical centers of the left and right cameras.

translation

vector<double>

The 3D translation vector of the camera relative to a reference frame. A vector that specifies the camera position along the X, Y, and Z axes.

rotation

vector<double>

Describes the camera’s orientation relative to a reference frame. Represented as a rotation matrix SO(3).

rotation_vec

vector<double>

This is interchangeable with the rotation parameter when the orientation of the camera is represented by a vector of Euler angles as [roll, pitch, yaw] instead of the rotation matrix.

mask

string

The mask type used during calibration. It can be used to exclude certain regions of the image from the calibration process.

Available options:

  • image

  • none

  • radial

When using a stereo camera, each camera requires its own configuration within the same file. They are differentiated by numerical identifiers, with the left camera typically assigned 0 and the right camera assigned to 1. Notably, the parameters focal_x_baseline, translation, and rotation (or rotation_vec) are only specified for the first camera.

 

datasources section

This section configures the image data source to use and defines its general settings.

File Source

This data source is utilized when it is desired to utilize LPSLAM with a pre-recorded dataset file (.pb) in replay mode.

Argument

Type

Description

Argument

Type

Description

type

string

FileSource

configuration

list

 

 

camera_position

vector<double>

Camera’s relative position.

camera_orientation

vector<double>

Camera’s relative quaternion orientation.

file_names

string

File path.

LeapMotion and Rigel

Argument

Type

Description

Argument

Type

Description

type

string

  • LeapMotion

  • Rigel

configuration

list

 

 

camera_position

vector<double>

Camera’s relative position.

camera_orientation

vector<double>

Camera’s relative quaternion orientation.

OpenCV

Generally, this data source type can be used for any camera that the system detects and can be accessed via OpenCV (e.g. StereoLabs ZED2)

Argument

Type

Description

Argument

Type

Description

type

string

OpenCV

configuration

list

 

 

camera_position

vector<double>

Camera’s relative position.

camera_orienation

vector<double>

Camera’s relative quaternion orientation.

camera_number

int

ID of the input camera in the system.

grayscale

bool

Enable/disable grayscale as the color order.

width

int

The horizontal resolution of the camera image sensor, in pixels.

height

int

The vertical resolution of the camera image sensor, in pixels.

stereo_mode

string

The orientation of the stereo camera.

Available options:

  • horizontal

  • vertical

fps

float

Framerate of input images.

exposure

float

Exposure value for the camera.

gain

float

Gain value for the camera.

opencv_logging_verbose

bool

Activate/deactivate OpenCV’s verbosity.

target_fps

int

The desired fps if these were not set at the camera driver level.

Varjo

This type is for using Varjo XR-3 HMD cameras as data source.

Requires LPSLAM_BUILD_VARJO

Argument

Type

Description

Argument

Type

Description

type

string

Varjo

configuration

list

 

 

camera_position

vector<double>

Camera’s relative position.

camera_orientation

vector<double>

Camera’s relative quaternion orientation.

prescale

int

 

Others

Argument

Type

Description

Argument

Type

Description

type

string

Available options:

  • RaspiCam

  • OpenVR

  • LeapSDK

  • OpenZen

  • Webots

  • Zed

  • ZedSdk

configuration

list

{}

 

 

 

 

 

trackers section

The mechanism or object responsible for the tracking functionality is referred to as a tracker. Here, one sets the specific configuration for it.

VSLAM

Argument

Type

Description

Argument

Type

Description

type

string

  • VSLAMMono

  • VSLAMStereo

configuration

list

 

 

 

 

 

 

 

 

General

camera_setup

string

Available options:

  • monocular

  • stereo

  • RGBD

config_from_file

string

Path of a direct configuration YAML file for the Visual-SLAM backend.

live_view

bool

Activate/deactivate the viewer.

only_orientation

bool

Activate/deactivate sending poses with only orientation information.

proxy_port

int

Port number to which the poses will be sent.

tracking_id

int

An ID for the tracker.

viewer_FPS

int

Images per second to show in the viewer.

use_CUDA

bool

Enable/disable using CUDA.

use_OpenCL

bool

Enable/disable using OpenCL.

undistort_image

bool

Enable/disable undistorting the images for better feature estimation and tracking.

vocab_file

string

Path of the file containing the Bag of Words database to assign identifiers to the visual features.

 

 

 

 

Mapping

emit_map

bool

Enable/disable publishing the generated map in real-time.

enable_mapping

bool

Enable/disable creating a map and only perform localization.

loop_closure

bool

Enable/disable looking for loop closure poses to add to the pose graph.

map_file_name

string

If "use_map_database": true, the path of the .db file containing the map database.

use_map_database

bool

Enable/disable using a map database.

 

 

 

 

 

 

 

Visual

Features

depth_threshold

float

Depth threshold used to compute ORB keypoints.

min_triangulated_points

int

Minimum number of triangulated points required for a successful pose update in the Visual-SLAM backend.

max_keypoints

int

Maximum number of keypoints to estimate.

ini_keypoints_threshold

int

Initial threshold for intensity difference when examining pixels around the potential corner detected by FAST. ORB starts with comparing intensities around the corner based on this parameter.

min_keypoints_threshold

int

Minimum acceptable intensity difference for a pixel to be considered part of the corner feature. It acts as a filter. Only corners where a certain number of pixels (defined by ORB) exhibit an intensity difference greater than this parameter are retained as features.

num_levels

int

Total number of levels in the image pyramid created by ORB.

scale_factor

float

Multiplicative factor by which the image is progressively scaled down to create a pyramid of images. Each level in the pyramid represents a different scale of the original image.

 

 

 

 

 

Others

forward_high_res_nav

bool

Activate/deactivate forwarding data with a higher rate than the image fps for smoother visualization.

forward_IMU

bool

Enable/disable processing and forwarding IMU data to the Visual-SLAM backend.

forward_nav_state

bool

Enable/disable processing and forwarding navigation odometry data to the Visual-SLAM backend.

max_laser_age

float

The maximum age of laser data before it’s considered outdated when using a laser scanner and a camera in the system.

reloc_with_navigation

bool

Enable/disable relocalize with navigation odometry data.

wait_for_navigation

bool

Enable/disable waiting for navigation odometry data to be processed.

Marker

Argument

Type

Description

Argument

Type

Description

type

string

Marker

configuration

list

 

 

marker_size

float

The size of the marker, in meters.

process_noise

float

Scaling factor for the Process Noise Covariance Q of Chilitags' Kalman Filter.

observation_noise

float

Scaling factor for the Observation Noise Covariance R of Chilitags' Kalman Filter.

proxy_port

int

Port number to which the poses will be sent.

show_tags

bool

Enable/disable showing a window with the tracked tag.

detect_only

int

If its desired to detect only one marker, the number ID of the desired marker.

 

processors section

This section allows to apply some pre-defined image processing methods to the incoming images.

Camera Calibration

To be deprecated.

Argument

Type

Description

Argument

Type

Description

type

string

CameraCalibration

configuration

list

{}

Coordinates Alignment

To be deprecated.

Argument

Type

Description

Argument

Type

Description

type

string

CoordAlign

configuration

list

{}

Image Blackout

To be deprecated.

Argument

Type

Description

Argument

Type

Description

type

string

BlackoutImage

Blacks out the image frames between 150 and 190.

configuration

list

{}

Image Thresholding

This image processor thresholds the images using truncate fixed-level thresholding.

Argument

Type

Description

Argument

Type

Description

type

string

ThresholdImage

configuration

list

 

 

auto_threshold

bool

Whether automatically determine the threshold via Otsu’s algorithm.

threshold

int

Threshold value [0, 255] to use if auto_threshold is false.

Intensity Adjustment

This image processor adjusts the contrast of the images by mapping the input intensity range to a specified output range.

Argument

Type

Description

Argument

Type

Description

type

string

AdjustIntensity

configuration

list

 

 

lower_bound

double

Lower bound of the output intensity range.

upper_bound

double

Upper bound of the output intensity range.

Online Photometric Calibration

This performs Online Photometric Calibration with the upcoming images to generate the camera’s inverse response function. For further details about it refer to: Online Photometric Calibration of Auto Exposure Video for Realtime Visual Odometry and SLAM (P. Bergmann, R. Wang, D. Cremers), In IEEE Robotics and Automation Letters (RA-L), volume 3, 2018 (pdf).

Argument

Type

Description

Argument

Type

Description

type

string

PhotoCalib

configuration

list

 

 

patch_size

int

Image patch size used in the frontend tracker.

pyramid_levels

int

Number of image pyramid levels used in the frontend tracker.

num_active_features

int

Number of features kept for each frame.

num_rapid_exposure_images

int

Number of images used for rapid exposure time estimation.

num_active_frames

int

Number of frames kept in the database.

keyframes_spacing

int

Spacing for sampling keyframes in the backend optimization.

min_valid_keyframes

int

Minimum number of keyframes a feature should appear.

Undistortion

This image processor undistorts the images based on the camera parameters and lens model.

Argument

Type

Description

Argument

Type

Description

type

string

Undistort

configuration

list

{}

markers section

Argument

Type

Description

Argument

Type

Description

type

string

Available options:

  • Aruco

configuration

list

 

 

id

int

ID of the Chilitags marker.

 

position

vector<double>

Relative position of the marker to the camera.

 

orientation

vector<double>

Relative orientation of the marker to the camera.

 

Â