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

Classes

struct  Config
 SLAM configuration parameters. More...
 
struct  Landmark
 Landmark with additional information. More...
 
struct  Landmarks
 
struct  LocalizationSettings
 Localization settings for use in LocalizeInMap. More...
 
struct  LocalizerProbe
 Localizer probe. More...
 
struct  LocalizerProbes
 Localizer probes array. More...
 
struct  Metrics
 Metrics. More...
 
struct  PoseGraph
 Pose graph. More...
 
struct  PoseGraphEdge
 Pose graph edge. More...
 
struct  PoseGraphNode
 Pose graph node. More...
 

Public Types

enum class  DataLayer : uint8_t {
  Landmarks ,
  Map ,
  LoopClosure ,
  PoseGraph ,
  LocalizerProbes ,
  LocalizerMap ,
  LocalizerLandmarks ,
  LocalizerLoopClosure ,
  Max
}
 Data layer for SLAM. More...
 
using ImageSet = std::vector< Image >
 Image set.
 
using LocalizationCallback = std::function< void(const Result< Pose > &result)>
 Localization callback, may be called in a separate thread.
 

Public Member Functions

 Slam (const Rig &rig, const std::vector< uint8_t > &primary_cameras, const Config &config=GetDefaultConfig())
 
 Slam (Slam &&other) noexcept
 
 ~Slam ()
 Destructor.
 
Pose Track (const Odometry::State &state, const Pose *gt_pose=nullptr)
 
void SetSlamPose (const Pose &pose)
 
void GetAllSlamPoses (std::vector< PoseStamped > &poses, uint32_t max_poses_count=0) const
 
void SaveMap (const std::string_view &folder_name, std::function< void(bool success)> callback) const
 
void LocalizeInMap (const std::string_view &folder_name, const Pose &guess_pose, const ImageSet &images, LocalizationSettings settings, LocalizationCallback callback)
 
void GetSlamMetrics (Metrics &metrics) const
 
void GetLoopClosurePoses (std::vector< PoseStamped > &poses) const
 
void EnableReadingData (DataLayer layer, uint32_t max_items_count)
 
void DisableReadingData (DataLayer layer)
 
std::shared_ptr< const LandmarksReadLandmarks (DataLayer layer)
 
std::shared_ptr< const PoseGraphReadPoseGraph ()
 
std::shared_ptr< const LocalizerProbesReadLocalizerProbes ()
 

Static Public Member Functions

static Config GetDefaultConfig ()
 
static void MergeMaps (const Rig &rig, const std::vector< std::string_view > &databases, const std::string_view &output_folder)
 

Detailed Description

Simultaneous Localization and Mapping (SLAM)


Class Documentation

◆ cuvslam::Slam::Config

struct cuvslam::Slam::Config

SLAM configuration parameters.

Class Members
string_view map_cache_path

If empty, map is kept in memory only. Else, map is synced to disk (LMDB) at this path, allowing large-scale maps; if the path already exists it will be overwritten. To load an existing map, use LocalizeInMap(). To save map, use SaveMap().

bool use_gpu Enable GPU use for SLAM.
bool sync_mode Synchronous mode (does not run a separate work thread if true)
bool enable_reading_internals

Enable reading internal data from SLAM (Pose Graph, Loop Closures, Landmarks, etc.). Additionally separate data layers are enabled by EnableReadingData.

bool planar_constraints Planar constraints. SLAM poses will be modified so that the camera moves on a horizontal plane.
bool gt_align_mode

Special SLAM mode for visual map building in case ground truth is present. Not realtime, no loop closure, no map global optimization, SBA must be in main thread.

float map_cell_size Size of map cell. Default is 0 (the size will be calculated from the camera baseline).
float max_landmarks_distance Maximum distance from camera to landmark for inclusion in map. Default is 100 meters.
uint32_t max_map_size

Maximum number of poses in SLAM pose graph. 300 is suitable for real-time mapping. The special value 0 means unlimited pose-graph.

uint32_t throttling_time_ms

Minimum time interval between loop closure events in milliseconds. 1000 is suitable for real-time mapping.

◆ cuvslam::Slam::Landmark

struct cuvslam::Slam::Landmark

Landmark with additional information.

Class Members
uint64_t id identifier
float weight weight (ignored now)
Vector3f coords x, y, z in meters in world frame

◆ cuvslam::Slam::Landmarks

struct cuvslam::Slam::Landmarks

Landmarks array

Class Members
int64_t timestamp_ns

timestamp of landmarks in nanoseconds; corresponds to the timestamp of the frame where the landmarks were observed

vector< Landmark > landmarks landmarks list

◆ cuvslam::Slam::LocalizationSettings

struct cuvslam::Slam::LocalizationSettings

Localization settings for use in LocalizeInMap.

Class Members
float horizontal_search_radius horizontal search radius in meters
float vertical_search_radius vertical search radius in meters
float horizontal_step horizontal step in meters
float vertical_step vertical step in meters
float angular_step_rads angular step around vertical axis in radians
bool enable_reading_internals enable reading internal data from SLAM

◆ cuvslam::Slam::LocalizerProbe

struct cuvslam::Slam::LocalizerProbe

Localizer probe.

Debug data from localizer for internal use.

Class Members
uint64_t id probe identifier
Pose guess_pose input hint
Pose exact_result_pose exact pose if localizer success
float weight input weight
float exact_result_weight result weight
bool solved true for solved, false for unsolved

◆ cuvslam::Slam::LocalizerProbes

struct cuvslam::Slam::LocalizerProbes

Localizer probes array.

Debug data from localizer for internal use.

Class Members
int64_t timestamp_ns timestamp of localizer try in nanoseconds
float size size of search area in meters
vector< LocalizerProbe > probes list of probes

◆ cuvslam::Slam::Metrics

struct cuvslam::Slam::Metrics
Class Members
int64_t timestamp_ns timestamp of these measurements (in nanoseconds)
bool lc_status loop closure status
bool pgo_status pose graph optimization status
uint32_t lc_selected_landmarks_count Count of Landmarks Selected.
uint32_t lc_tracked_landmarks_count Count of Landmarks Tracked.
uint32_t lc_pnp_landmarks_count Count of Landmarks in PNP.
uint32_t lc_good_landmarks_count Count of Landmarks in LC.

◆ cuvslam::Slam::PoseGraph

struct cuvslam::Slam::PoseGraph

Pose graph.

Class Members
int64_t timestamp_ns timestamp of the pose graph in nanoseconds
vector< PoseGraphNode > nodes nodes list
vector< PoseGraphEdge > edges edges list

◆ cuvslam::Slam::PoseGraphEdge

struct cuvslam::Slam::PoseGraphEdge

Pose graph edge.

Class Members
uint64_t node_from node id
uint64_t node_to node id
Pose transform transform
PoseCovariance covariance covariance

◆ cuvslam::Slam::PoseGraphNode

struct cuvslam::Slam::PoseGraphNode

Pose graph node.

Class Members
uint64_t id node identifier
Pose node_pose node pose

Member Enumeration Documentation

◆ DataLayer

enum cuvslam::Slam::DataLayer : uint8_t
strong

Data layer for SLAM.

Enumerator
Landmarks 

Landmarks that are visible in the current frame.

Map 

Landmarks of the map.

LoopClosure 

Map's landmarks that are visible in the last loop closure event.

PoseGraph 

Pose Graph.

LocalizerProbes 

Localizer probes.

LocalizerMap 

Landmarks of the Localizer map (opened database)

LocalizerLandmarks 

Landmarks that are visible in the localization.

LocalizerLoopClosure 

Landmarks that are visible in the final loop closure of the localization.

Constructor & Destructor Documentation

◆ Slam() [1/2]

cuvslam::Slam::Slam ( const Rig rig,
const std::vector< uint8_t > &  primary_cameras,
const Config config = GetDefaultConfig() 
)

Construct a SLAM instance with rig and primary cameras

Parameters
[in]rigCamera rig configuration
[in]primary_camerasVector of primary camera indices
[in]configSLAM configuration
Exceptions
std::runtime_errorif SLAM initialization fails

◆ Slam() [2/2]

cuvslam::Slam::Slam ( Slam &&  other)
noexcept

Move constructor

Parameters
[in]otherother SLAM instance

Member Function Documentation

◆ GetDefaultConfig()

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

Get default configuration

Returns
default configuration

◆ Track()

Pose cuvslam::Slam::Track ( const Odometry::State state,
const Pose gt_pose = nullptr 
)

Process tracking results from Odometry::Track. This should be called after each successful tracking.

Parameters
[in]stateOdometry state containing all tracking data
[in]gt_poseOptional ground truth pose. Should be provided if gt_align_mode is enabled, otherwise should be nullptr.
See also
Odometry::Track
Exceptions
std::invalid_argumentif gt_pose is passed incorrectly
Returns
On success Pose contains rig pose estimated by SLAM

◆ SetSlamPose()

void cuvslam::Slam::SetSlamPose ( const Pose pose)

Set rig pose estimated by a user.

Parameters
[in]poserig pose estimated by a user

◆ GetAllSlamPoses()

void cuvslam::Slam::GetAllSlamPoses ( std::vector< PoseStamped > &  poses,
uint32_t  max_poses_count = 0 
) const

Get all SLAM poses for each frame.

Parameters
[in]max_poses_countmaximum number of poses to return
[out]posesVector of poses with timestamps This call could be blocked by slam thread.

◆ SaveMap()

void cuvslam::Slam::SaveMap ( const std::string_view &  folder_name,
std::function< void(bool success)>  callback 
) const

Save SLAM database (map) to folder asynchronously. This folder will be created, if it does not exist. Contents of the folder will be overwritten.

Parameters
[in]folder_nameFolder name, where SLAM database (map) will be saved
[in]callbackCallback function to be called when save is complete, may be called in a separate thread

◆ LocalizeInMap()

void cuvslam::Slam::LocalizeInMap ( const std::string_view &  folder_name,
const Pose guess_pose,
const ImageSet images,
LocalizationSettings  settings,
LocalizationCallback  callback 
)

Localize in the existing database (map) asynchronously. Finds the position of the camera in existing SLAM database (map). If successful, moves the SLAM pose to the found position.

Parameters
[in]folder_nameFolder name, which stores saved SLAM database (map)
[in]guess_posePointer to the proposed pose, where the robot might be
[in]imagesObserved images. Will be used if Config::slam_sync_mode = true
[in]settingsLocalization settings
[in]callbackCallback function to be called when localization is complete, may be called in a separate thread.
Note
Errors will be reported in the callback.

◆ GetSlamMetrics()

void cuvslam::Slam::GetSlamMetrics ( Metrics metrics) const

Get SLAM metrics.

Parameters
[out]metricsSLAM metrics

◆ GetLoopClosurePoses()

void cuvslam::Slam::GetLoopClosurePoses ( std::vector< PoseStamped > &  poses) const

Get list of last 10 loop closure poses with timestamps.

Parameters
[out]posesVector of poses with timestamps

◆ EnableReadingData()

void cuvslam::Slam::EnableReadingData ( DataLayer  layer,
uint32_t  max_items_count 
)

Enable reading data layer.

Parameters
[in]layerData layer to enable/disable
[in]max_items_countMaximum number of items to allocate in the layer

◆ DisableReadingData()

void cuvslam::Slam::DisableReadingData ( DataLayer  layer)

Disable reading data layer.

Parameters
[in]layerData layer to disable

◆ ReadLandmarks()

std::shared_ptr<const Landmarks> cuvslam::Slam::ReadLandmarks ( DataLayer  layer)

Read landmarks from a given data layer. Enabled by EnableReadingData.

Parameters
[in]layerData layer to read
Returns
Landmarks

◆ ReadPoseGraph()

std::shared_ptr<const PoseGraph> cuvslam::Slam::ReadPoseGraph ( )

Read pose graph. Enabled by EnableReadingData(DataLayer::PoseGraph).

Returns
Pose graph

◆ ReadLocalizerProbes()

std::shared_ptr<const LocalizerProbes> cuvslam::Slam::ReadLocalizerProbes ( )

Read localizer probes. Enabled by EnableReadingData(DataLayer::LocalizerProbes).

Debug data from localizer for internal use.

Returns
Localizer probes

◆ MergeMaps()

static void cuvslam::Slam::MergeMaps ( const Rig rig,
const std::vector< std::string_view > &  databases,
const std::string_view &  output_folder 
)
static

Merge existing maps into one map.

Parameters
[in]rigCamera rig configuration
[in]databasesInput array of directories with existing databases
[in]output_folderDirectory to save output database
Exceptions
std::runtime_errorif merge fails
See also
Rig