cuVSLAM API Reference
Classes | Public Types | Public Member Functions | Static Public Member Functions | List of all members
cuvslam::Odometry Class Reference

Visual Inertial Odometry (VIO) Tracker. More...

Classes

struct  Config
 Configuration parameters of the VIO tracker. More...
 
struct  RGBDSettings
 RGBD odometry settings. More...
 
struct  State
 State of the odometry tracker. More...
 

Public Types

enum class  MulticameraMode : uint8_t {
  Performance ,
  Precision ,
  Moderate
}
 Multicamera mode. More...
 
enum class  OdometryMode : uint8_t {
  Multicamera ,
  Inertial ,
  RGBD ,
  Mono
}
 Odometry mode. More...
 
using ImageSet = std::vector< Image >
 Image set.
 
using Gravity = Vector3f
 Gravity vector.
 

Public Member Functions

 Odometry (const Rig &rig, const Config &cfg=GetDefaultConfig())
 Construct a tracker. More...
 
 Odometry (Odometry &&other) noexcept
 Move constructor. More...
 
 ~Odometry ()
 Destructor.
 
PoseEstimate Track (const ImageSet &images, const ImageSet &masks={}, const ImageSet &depths={})
 Track a rig pose using current frame. More...
 
void RegisterImuMeasurement (uint32_t sensor_index, const ImuMeasurement &imu)
 Register IMU measurement. More...
 
std::vector< ObservationGetLastObservations (uint32_t camera_index) const
 Get Last Observations. More...
 
std::vector< LandmarkGetLastLandmarks () const
 Get Last Landmarks. More...
 
std::optional< GravityGetLastGravity () const
 Get Last Gravity. More...
 
void GetState (Odometry::State &state) const
 Get tracker state. More...
 
std::unordered_map< uint64_t, Vector3f > GetFinalLandmarks () const
 Get all final landmarks from all frames. More...
 
const std::vector< uint8_t > & GetPrimaryCameras () const
 Get primary camera indices used for tracking. More...
 

Static Public Member Functions

static Config GetDefaultConfig ()
 Get default configuration. More...
 

Detailed Description

Visual Inertial Odometry (VIO) Tracker.


Class Documentation

◆ cuvslam::Odometry::Config

struct cuvslam::Odometry::Config

Configuration parameters of the VIO tracker.

Class Members
MulticameraMode multicam_mode Multicamera mode. Default: MulticameraMode::Precision.
OdometryMode odometry_mode Odometry mode. Default: OdometryMode::Multicamera.
bool use_gpu Enable tracking using GPU. Default: true.
bool async_sba Enable SBA asynchronous mode. Default: true.
bool use_motion_model Enable internal pose prediction mechanism. Default: true.

If frame rate is high enough it improves tracking performance and stability. As a general rule it is better to use a pose prediction mechanism tailored to a specific application. If you have an IMU, consider using it to provide pose predictions to cuVSLAM.

bool use_denoising

Enable image denoising. Disable if the input images have already passed through a denoising filter. Default: false

bool rectified_stereo_camera

Enable fast and robust tracking between rectified cameras with principal points on the horizontal line. Default: false

bool enable_observations_export

Enable GetLastObservations(). Warning: export flags slow down execution and result in additional memory usage. Default: false

bool enable_landmarks_export

Enable GetLastLandmarks(). Warning: export flags slow down execution and result in additional memory usage. Default: false

bool enable_final_landmarks_export

Enable GetFinalLandmarks(). Warning: export flags slow down execution and result in additional memory usage. This flag also sets enable_landmarks_export and enable_observations_export. Default: false

float max_frame_delta_s

Maximum frame delta in seconds. Odometry will warn if time delta between frames is higher than the threshold. Default: 1.f

string_view debug_dump_directory Directory where input data will be dumped in edex format.
bool debug_imu_mode Enable IMU debug mode. Default: false.
RGBDSettings rgbd_settings RGBD odometry settings.

◆ cuvslam::Odometry::RGBDSettings

struct cuvslam::Odometry::RGBDSettings

RGBD odometry settings.

Class Members
float depth_scale_factor Scale of provided depth measurements. Default: 1.f.

The scale factor is the denominator used to convert raw depth values from the input depth image to actual distance measurements in meters. For example, in TUM RGB-D a factor of 5000 is used for 16-bit PNG images, meaning each pixel value should be divided by 5000 to get the depth in meters, while a factor of 1 is used for 32-bit float images, where the depth values are already in meters.

int32_t depth_camera_id Depth camera id.

Depth image is supposed to be pixel-to-pixel aligned with some RGB camera image. This field specifies camera id, that depth is aligned with. Default: -1

bool enable_depth_stereo_tracking Allows stereo 2D tracking between depth-aligned camera and any other camera. Default: false.

◆ cuvslam::Odometry::State

struct cuvslam::Odometry::State

State of the odometry tracker.

Only available if data export is enabled in Config.

Class Members
typedef unordered_map< uint8_t, shared_ptr< Context > > ContextMap
Class Members
uint64_t frame_id Internal frame id.
int64_t timestamp_ns Timestamp in nanoseconds.
Pose delta Pose change since last keyframe.
bool keyframe Is this frame a keyframe?
bool warming_up Is the tracker in warming up phase?
optional< Gravity > gravity Optional gravity information. Only available in OdometryMode::Inertial mode.
vector< Observation > observations Observations for this frame.
vector< Landmark > landmarks Landmarks for this frame.
ContextMap context Opaque context information for this frame (used internally by Slam)

Member Enumeration Documentation

◆ MulticameraMode

enum cuvslam::Odometry::MulticameraMode : uint8_t
strong

Multicamera mode.

Multicamera mode defines which cameras will be used for mono SOF (primary cameras)

Enumerator
Performance 

primary cameras auto selection, each secondary camera must be connected to only one primary camera

Precision 

all cameras are primary cameras

Moderate 

primary cameras auto selection, secondary cameras may be connected to more than one primary camera

◆ OdometryMode

enum cuvslam::Odometry::OdometryMode : uint8_t
strong

Odometry mode.

Odometry mode defines what data is expected and how it will be used by odometry tracker

Enumerator
Multicamera 

Uses multiple synchronized stereo cameras, all cameras need to have frustum overlap with at least one another camera.

Inertial 

Uses stereo camera and IMU measurements. A single stereo-camera with a single IMU sensor is supported.

RGBD 

Uses RGB-D camera for tracking. A single RGB-D camera is supported. RGB & Depth images must be aligned.

Mono 

Uses a single camera, tracking is accurate up to scale.

Constructor & Destructor Documentation

◆ Odometry() [1/2]

cuvslam::Odometry::Odometry ( const Rig rig,
const Config cfg = GetDefaultConfig() 
)

Construct a tracker.

Parameters
[in]rigrig setup
[in]cfgtracker configuration
Exceptions
std::runtime_errorif tracker fails to initialize
std::invalid_argumentif rig or config is invalid

◆ Odometry() [2/2]

cuvslam::Odometry::Odometry ( Odometry &&  other)
noexcept

Move constructor.

Parameters
[in]otherother tracker

Member Function Documentation

◆ GetDefaultConfig()

static Config cuvslam::Odometry::GetDefaultConfig ( )
inlinestatic

Get default configuration.

See also
Config for default values.
Returns
default configuration

◆ Track()

PoseEstimate cuvslam::Odometry::Track ( const ImageSet images,
const ImageSet masks = {},
const ImageSet depths = {} 
)

Track a rig pose using current frame.

Track current frame synchronously: the function blocks until the tracker has computed a pose. By default, this function uses visual odometry to compute a pose. If visual odometry tracker fails to compute a pose, in inertial mode 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.

Image timestamps have to match. cuVSLAM will use timestamp from the camera 0 image. If a camera rig provides "almost synchronized" frames, the timestamps should be within 1 millisecond. The number of images for tracker should not exceed rig->num_cameras.

Parameters
[in]imagesan array of synchronized images no more than rig->num_cameras. Must use ImageData::DataType::UINT8. Partial ImageSet is supported, for example due to frame drops. Corresponding cameras are identified by Image::camera_index.
[in]masks(Optional) an array of corresponding masks no more than rig->num_cameras. Must use ImageData::DataType::UINT8. Partial ImageSet is supported, for example if mask is calculated on for some cameras. Corresponding cameras are identified by Image::camera_index.
[in]depths(Optional) an array of corresponding depth images. One depth image is now supported. Must use ImageData::Encoding::MONO and ImageData::DataType::UINT16 or ImageData::DataType::FLOAT32.
Returns
On success PoseEstimate contains estimated rig pose, on failure PoseEstimate::world_from_rig will be nullopt.
Exceptions
std::invalid_argumentif image parameters are invalid
std::runtime_errorin case of unexpected errors

◆ RegisterImuMeasurement()

void cuvslam::Odometry::RegisterImuMeasurement ( uint32_t  sensor_index,
const ImuMeasurement imu 
)

Register IMU measurement.

If visual odometry loses camera position, it briefly continues execution using user-provided IMU measurements while trying to recover the position. You should call these functions in the order of ascending timestamps however many IMU measurements you have between image acquisitions:

  • tracker.Track
  • tracker.RegisterImuMeasurement
  • ...
  • tracker.RegisterImuMeasurement
  • tracker.Track

IMU measurement and frame image both have timestamps, so it is important to call these functions in strict ascending order of timestamps. RegisterImuMeasurement is thread-safe so it's allowed to call RegisterImuMeasurement and Track in parallel.

Parameters
[in]sensor_indexSensor index; must be 0, as only one sensor is supported now
[in]imuIMU measurements
Exceptions
std::invalid_argumentif IMU fusion is disabled or if called out of the order of timestamps
See also
Track

◆ GetLastObservations()

std::vector<Observation> cuvslam::Odometry::GetLastObservations ( uint32_t  camera_index) const

Get Last Observations.

Get an array of observations from the last VO frame for a specific camera

Parameters
[in]camera_indexIndex of the camera to get observations for
Returns
Array of observations
Exceptions
std::invalid_argumentif stats export is disabled
See also
Observation

◆ GetLastLandmarks()

std::vector<Landmark> cuvslam::Odometry::GetLastLandmarks ( ) const

Get Last Landmarks.

Get an array of landmarks from the last VO frame; Landmarks are 3D points in the last camera frame.

Returns
Array of landmarks
Exceptions
std::invalid_argumentif stats export is disabled
See also
Landmark

◆ GetLastGravity()

std::optional<Gravity> cuvslam::Odometry::GetLastGravity ( ) const

Get Last Gravity.

Get gravity vector in the last VO frame

Returns
Optional gravity vector. Empty if gravity is not yet available.
Exceptions
std::invalid_argumentif IMU fusion is disabled
See also
Gravity

◆ GetState()

void cuvslam::Odometry::GetState ( Odometry::State state) const

Get tracker state.

Only available if data export is enabled in Config.

Parameters
[out]stateOdometry state to be filled
Exceptions
std::invalid_argumentif stats export is disabled
See also
State

◆ GetFinalLandmarks()

std::unordered_map<uint64_t, Vector3f> cuvslam::Odometry::GetFinalLandmarks ( ) const

Get all final landmarks from all frames.

Landmarks are 3D points in the odometry start frame.

Returns
std::unordered_map<uint64_t, Vector3f>
Exceptions
std::invalid_argumentif stats export is disabled
See also
Landmark

◆ GetPrimaryCameras()

const std::vector<uint8_t>& cuvslam::Odometry::GetPrimaryCameras ( ) const

Get primary camera indices used for tracking.

Returns
Vector of primary camera indices