API Reference

This module provides Python bindings for the cuVSLAM library.

Data Structures

class cuvslam.Pose

Transformation from one frame to another.

Consists of rotation (quaternion in x, y, z, w order) and translation (3-vector).

property rotation

Rotation (quaternion in x, y, z, w order)

property translation

Translation (3-vector)

class cuvslam.Distortion

Camera distortion model with parameters.

Supports Pinhole (no distortion), Brown (radial and tangential),Fisheye (equidistant), and Polynomial distortion models.

Brown = 2
Fisheye = 1
class Model(value)

Distortion model types for camera calibration

Pinhole = 0
Brown = 2
Fisheye = 1
Polynomial = 3
Pinhole = 0
Polynomial = 3
property model

Distortion model type, see Distortion.Model

property parameters

Array of distortion parameters depending on model

class cuvslam.Camera

Camera calibration parameters.

Describes intrinsic and extrinsic parameters of a camera and per-camera settings. For camera coordinate system, top left pixel has (0, 0) coordinate (y is down, x is right).

property border_bottom

Bottom border to ignore in pixels (0 to use full frame)

property border_left

Left border to ignore in pixels (0 to use full frame)

property border_right

Right border to ignore in pixels (0 to use full frame)

property border_top

Top border to ignore in pixels (0 to use full frame)

property distortion

Distortion parameters, see Distortion

property focal

Focal length (fx, fy)

property principal

Principal point (cx, cy)

property rig_from_camera

Transformation from the camera coordinate frame to the rig coordinate frame

property size

Size of the camera (width, height)

class cuvslam.ImuCalibration

IMU Calibration parameters

property accelerometer_noise_density

Accelerometer noise density in m/(s2sqrt(hz))

property accelerometer_random_walk

Accelerometer random walk in m/(s3sqrt(hz))

property frequency

IMU frequency in hz

property gyroscope_noise_density

Gyroscope noise density in rad/(ssqrt(hz))

property gyroscope_random_walk

Gyroscope random walk in rad/(s2sqrt(hz))

property rig_from_imu

Transformation from IMU coordinate frame to the rig coordinate frame

class cuvslam.Rig

Rig consisting of cameras and 0 or 1 IMU sensors

property cameras

List of cameras in the rig, see Camera

property imus

List of IMU sensors in the rig (0 or 1 only), see ImuCalibration

class cuvslam.PoseEstimate

Rig pose estimate from the tracker. The pose is world_from_rig where:

The rig coordinate frame is user-defined and depends on the extrinsic parameters of the cameras. The world coordinate frame is an arbitrary 3D coordinate frame, corresponding to the rig frame at the start of tracking.

property timestamp_ns

Timestamp of the pose estimate in nanoseconds

property world_from_rig

Rig pose in the world coordinate frame

class cuvslam.ImuMeasurement
property angular_velocities

Angular velocities in rad/s

property linear_accelerations

Linear accelerations in m/s2

property timestamp_ns

Timestamp of the IMU measurement in nanoseconds

class cuvslam.Landmark

3D landmark point

property coords

3D coordinates of the landmark

property id

Unique ID of the landmark

class cuvslam.Observation

2D observation of a landmark in an image

property camera_index

Index of the camera that made this observation

property id

Unique ID of the observed landmark

property u

Horizontal pixel coordinate of the observation

property v

Vertical pixel coordinate of the observation

class cuvslam.core.Odometry.MulticameraMode(value)
Performance = 0
Precision = 1
Moderate = 2
class cuvslam.core.Odometry.OdometryMode(value)
Multicamera = 0
Inertial = 1
RGBD = 2
Mono = 3
class cuvslam.core.Odometry.Config
property async_sba

Whether to run bundle adjustment asynchronously

property debug_dump_directory

Directory for debug data dumps. If empty, no debug data will be dumped

property debug_imu_mode

Whether to enable IMU debug mode

property enable_final_landmarks_export

Whether to export final landmarks

property enable_landmarks_export

Whether to export landmarks during tracking

property enable_observations_export

Whether to export landmark observations in images during tracking

property horizontal_stereo_camera

Whether stereo cameras are rectified and horizontally aligned

property max_frame_delta_s

Maximum time difference between frames in seconds

property multicam_mode

See Odometry.MulticameraMode

property odometry_mode

See Odometry.OdometryMode

property rgbd_settings

Settings for RGB-D odometry mode. See Odometry.RGBDSettings

property use_denoising

Whether to apply denoising to input images

property use_gpu

Whether to use GPU acceleration

property use_motion_model

Whether to use motion model for prediction

class cuvslam.core.Odometry.RGBDSettings

Settings for RGB-D odometry mode

property depth_camera_id

ID of the camera that the depth image is aligned with

property depth_scale_factor

Scale factor for depth measurements

property enable_depth_stereo_tracking

Whether to enable stereo tracking between depth-aligned camera and other cameras

class cuvslam.core.Slam.Config

SLAM configuration parameters

property enable_reading_internals

Enable reading internal data from SLAM

property gt_align_mode

Special mode for visual map building with ground truth

property map_cell_size

Size of map cell (0 for auto-calculate from camera baseline)

property max_map_size

Maximum number of poses in SLAM pose graph (0 for unlimited)

property planar_constraints

Modify poses so camera moves on a horizontal plane

property sync_mode

If true, localization and mapping run in the same thread as visual odometry

property throttling_time_ms

Minimum time between loop closure events in milliseconds

property use_gpu

Whether to use GPU acceleration

class cuvslam.core.Slam.Metrics

SLAM metrics

property lc_good_landmarks_count

Count of landmarks in loop closure

property lc_pnp_landmarks_count

Count of landmarks in PnP for loop closure

property lc_selected_landmarks_count

Count of landmarks selected for loop closure

property lc_status

Loop closure status

property lc_tracked_landmarks_count

Count of landmarks tracked in loop closure

property pgo_status

Pose graph optimization status

property timestamp_ns

Timestamp of measurements in nanoseconds

class cuvslam.core.Slam.LocalizationSettings

Localization settings

property angular_step_rads

Angular step around vertical axis in radians

property horizontal_search_radius

Horizontal search radius in meters

property horizontal_step

Horizontal step in meters

property vertical_search_radius

Vertical search radius in meters

property vertical_step

Vertical step in meters

Tracker class

class cuvslam.Tracker(rig: ~cuvslam.pycuvslam.Rig, odom_config: ~cuvslam.pycuvslam.Odometry.Config | None = <cuvslam.pycuvslam.Odometry.Config object>, slam_config: ~cuvslam.pycuvslam.Slam.Config | None = None)[source]

A wrapper that combines cuVSLAM Odometry and SLAM functionality.

This class automatically manages both the Odometry and SLAM instances, providing a simplified interface for common use cases.

Parameters:
OdometryConfig

alias of Config

OdometryRGBDSettings

alias of RGBDSettings

SlamConfig

alias of Config

SlamMetrics

alias of Metrics

SlamLocalizationSettings

alias of LocalizationSettings

track(timestamp: int, images: List[Any], masks: List[Any] | None = None, depths: List[Any] | None = None) Tuple[PoseEstimate, Pose | None][source]

Track a rig pose using current image frame.

This method combines tracking and SLAM processing in a single call.

Parameters:
  • timestamp (int) – Images timestamp in nanoseconds

  • images (List[Any]) – List of numpy arrays containing the camera images

  • masks (List[Any] | None) – Optional list of numpy arrays containing masks for the images

  • depths (List[Any] | None) – Optional list of numpy arrays containing depth images

Returns:

The computed pose estimate from Odometry Pose: The computed pose estimate from SLAM

Return type:

PoseEstimate

register_imu_measurement(sensor_index: int, imu_measurement: ImuMeasurement) None[source]

Register an IMU measurement with the tracker.

Parameters:
Return type:

None

get_last_observations(camera_index: int) List[Any][source]

Get observations from the last frame.

Parameters:

camera_index (int)

Return type:

List[Any]

get_last_landmarks() List[Any][source]

Get landmarks from the last frame.

Return type:

List[Any]

get_last_gravity() Any | None[source]

Get gravity vector from the last frame.

Return type:

Any | None

get_final_landmarks() dict[int, Any][source]

Get all final landmarks from all frames.

Return type:

dict[int, Any]

get_all_slam_poses(max_poses_count: int = 0) List[Any] | None[source]

Get all SLAM poses for each frame.

Parameters:

max_poses_count (int)

Return type:

List[Any] | None

get_pose_graph() Any | None[source]

Get pose graph.

Return type:

Any | None

get_slam_metrics() Any | None[source]

Get SLAM metrics.

Return type:

Any | None

get_loop_closure_poses() List[Any] | None[source]

Get list of last 10 loop closure poses with timestamps.

Return type:

List[Any] | None

Functions

cuvslam.get_version() tuple[str, int, int]

Get the version of cuVSLAM library you are using.

Returns a tuple with the detailed version and major and minor versions.

cuvslam.set_verbosity(arg: int, /) None

Set the verbosity level of the library.

Available values: 0 (default) for no output, 1 for error messages, 2 for warnings, 3 for info messages.

cuvslam.warm_up_gpu() None

Warm up the GPU (CUDA runtime).

It is not necessary to call it before the first call to cuvslam, but it can help to reduce the first call latency.