API Reference

This module provides Python bindings for the cuVSLAM library.

Data Structures

class cuvslam.Pose

Bases: object

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

Bases: object

Camera distortion model with parameters.

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

property model

Distortion model type

property parameters

Array of distortion parameters depending on model

class cuvslam.Camera

Bases: object

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

Bases: object

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

Bases: object

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

Bases: object

Rig pose estimate from the tracker.

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 is_valid

True if the pose estimate is valid

property pose

Transformation from the rig coordinate frame to the world coordinate frame

property timestamp_ns

Pose timestamp matching image timestamp (in nanoseconds)

class cuvslam.ImuMeasurement

Bases: object

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

Bases: object

3D landmark point

property coords

3D coordinates of the landmark

property id

Unique ID of the landmark

class cuvslam.Observation

Bases: object

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.TrackerConfig

Bases: object

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 TrackerMulticameraMode

property odometry_mode

See TrackerOdometryMode

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

Core Classes

class cuvslam.Tracker

Bases: object

Visual Inertial Odometry (VIO) Tracker

track(self, timestamp: int, images: collections.abc.Sequence[ndarray[writable=False]], masks: collections.abc.Sequence[ndarray[writable=False]] | None = None) cuvslam.pycuvslam.PoseEstimate

Track a rig pose using current image frame.

Synchronously tracks current image frame and returns a PoseEstimate.

By default, this function uses visual odometry to compute a pose. In Inertial mode, if visual odometry tracker fails to compute a pose, the function returns the position calculated from a user-provided IMU data. If after several calls of track() visual odometry is not able to recover, then invalid pose will be returned. The track will output poses in the same coordinate system until a loss of tracking.

Parameters:
  • timestamp – Image timestamp in nanoseconds

  • images – List of numpy arrays containing the camera images

  • masks – Optional list of numpy arrays containing masks for the images

Returns:

PoseEstimate object with the computed pose. If tracking fails, is_valid will be False.

register_imu_measurement(self, sensor_index: int, imu_measurement: cuvslam.pycuvslam.ImuMeasurement) None

Register an IMU measurement.

Requires Inertial mode. If visual odometry loses camera position, it briefly continues execution using user-provided IMU measurements while trying to recover the position. Timestamps of IMU measurements and frame images must be synchronized, track() and register_imu_measurement() must be called in strict ascending order of timestamps.

get_last_gravity(self) object

Get gravity vector in the last VO frame.

Returns None if gravity is not yet available. Requires Inertial mode (odometry_mode=TrackerOdometryMode.Inertial in TrackerConfig)

get_last_observations(self, camera_index: int) list[cuvslam.pycuvslam.Observation]

Get an array of observations from the last VO frame.

Requires enable_observations_export=True in TrackerConfig.

get_last_landmarks(self) list[cuvslam.pycuvslam.Landmark]

Get an array of landmarks from the last VO frame.

Landmarks are 3D points in the last camera frame. Requires enable_landmarks_export=True in TrackerConfig.

get_final_landmarks(self) dict[int, list[float]]

Get all final landmarks from all frames.

Landmarks are 3D points in the odometry start frame. Requires enable_final_landmarks_export=True in TrackerConfig.

Enums

class cuvslam.DistortionModel(value)

Bases: Enum

Distortion model types for camera calibration

Pinhole = 0
Brown = 2
Fisheye = 1
Polynomial = 3
class cuvslam.TrackerMulticameraMode(value)

Bases: Enum

Performance = 0
Precision = 1
Moderate = 2
class cuvslam.TrackerOdometryMode(value)

Bases: Enum

Multicamera = 0
Inertial = 1
Mono = 3

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.