SaDVIO
Public Member Functions | Public Attributes | Protected Attributes | List of all members
isae::SLAMCore Class Referenceabstract

The core abstract class of the SLAM system. It handles front-end, back-end and initialization. More...

#include <slamCore.h>

Inheritance diagram for isae::SLAMCore:
Inheritance graph
[legend]

Public Member Functions

 SLAMCore ()
 
 SLAMCore (std::shared_ptr< isae::SLAMParameters > slam_param)
 
virtual bool init ()=0
 Initialization step : create the first 3D landmarks and keyframe(s) More...
 
virtual bool frontEndStep ()=0
 Front End: detection, tracking, pose estimation and landmark triangulation. More...
 
virtual bool backEndStep ()=0
 brief description Back End: marginalization, local map optimization More...
 
void runBackEnd ()
 Thread for the backend. More...
 
void runFrontEnd ()
 Thread for the frontend. More...
 
void runFullOdom ()
 Thread for the backend. More...
 
typed_vec_features detectFeatures (std::shared_ptr< ImageSensor > &sensor)
 Detect all types of features for a given sensor with bucketting. More...
 
void cleanFeatures (std::shared_ptr< Frame > &f)
 Clean all the features that are outliers or are linked to outlier landmark. More...
 
uint matchFeatures (std::shared_ptr< ImageSensor > &sensor0, std::shared_ptr< ImageSensor > &sensor1, typed_vec_match &matches, typed_vec_match &matches_lmk, typed_vec_features features_to_track)
 Predicts the position of the features and matches all the features between sensors. More...
 
uint trackFeatures (std::shared_ptr< ImageSensor > &sensor0, std::shared_ptr< ImageSensor > &sensor1, typed_vec_match &matches, typed_vec_match &matches_lmk, typed_vec_features features_to_track)
 Predicts the position of the features and tracks all the features. More...
 
void predictFeature (std::vector< std::shared_ptr< AFeature >> features, std::shared_ptr< ImageSensor > sensor, std::vector< std::shared_ptr< AFeature >> &features_init, vec_match previous_matches)
 Predicts the position of a set of features on a given sensor. More...
 
typed_vec_match epipolarFiltering (std::shared_ptr< ImageSensor > &cam0, std::shared_ptr< ImageSensor > &cam1, typed_vec_match matches)
 Filters the matches between two sensors (with consistent pose estimates) using epipolar plane check. More...
 
void outlierRemoval ()
 Remove all the outlier features of _frame. More...
 
bool predict (std::shared_ptr< Frame > &f)
 Estimates the pose of a given frame. More...
 
void initLandmarks (std::shared_ptr< Frame > &f)
 Initialize all the landmarks of the current frame using _matches_in_time and _matches_in_frame. More...
 
void updateLandmarks (typed_vec_match matches_lmk)
 
uint recoverFeatureFromMapLandmarks (std::shared_ptr< isae::AMap > localmap, std::shared_ptr< Frame > &f)
 Performs landmark resurection. More...
 
bool shouldInsertKeyframe (std::shared_ptr< Frame > &f)
 Determines if the frame in argument is a KF. More...
 
std::shared_ptr< FramegetLastKF ()
 
void profiling ()
 A function to monitor the SLAM behaviour. More...
 

Public Attributes

bool _is_init = false
 Flag for initialization. More...
 
int _successive_fails = 0
 Number of successive failure to trigger reinitialization. More...
 
std::shared_ptr< isae::SLAMParameters_slam_param
 
std::shared_ptr< Frame_frame_to_display
 
std::shared_ptr< isae::LocalMap_local_map_to_display
 
std::shared_ptr< isae::GlobalMap_global_map_to_display
 
std::shared_ptr< Mesh3D_mesh_to_display
 

Protected Attributes

std::shared_ptr< Frame_frame
 Current frame. More...
 
typed_vec_match _matches_in_time
 Typed vector of the matches between the last KF and _frame. More...
 
typed_vec_match _matches_in_time_lmk
 Typed vector of the matches with landmarks between the last KF and _frame. More...
 
typed_vec_match _matches_in_frame
 Typed vector of the matches between the sensors of _frame. More...
 
typed_vec_match _matches_in_frame_lmk
 Typed vector of the matches with landmarks between the sensors of _frame. More...
 
std::shared_ptr< isae::LocalMap_local_map
 Current local map. More...
 
std::shared_ptr< isae::GlobalMap_global_map
 Current global map. More...
 
std::shared_ptr< Mesher_mesher
 Mesher of the SLAM. More...
 
double _max_movement_parallax
 Max parallax until a KF is voted. More...
 
double _min_movement_parallax
 Under this parallax, no motion is considered. More...
 
double _min_lmk_number
 Under this number of landmark in _frame a KF is voted. More...
 
double _parallax
 Parallax between the last KF and _frame. More...
 
Vector6d _6d_velocity
 Current Velocity as a Twist vector. More...
 
std::mutex _map_mutex
 
std::shared_ptr< Frame_frame_to_optim
 For communication between front-end and back-end. More...
 
uint _nframes
 
uint _nkeyframes
 
float _avg_detect_t
 
float _avg_processing_t
 
float _avg_match_frame_t
 
float _avg_match_time_t
 
float _avg_filter_t
 
float _avg_lmk_init_t
 
float _avg_lmk_resur_t
 
float _avg_predict_t
 
float _avg_frame_opt_t
 
float _avg_clean_t
 
float _avg_marg_t
 
float _avg_wdw_opt_t
 
float _removed_lmk
 
float _removed_feat
 
float _lmk_inmap
 
float _avg_matches_time
 
float _avg_matches_frame
 
float _avg_resur_lmk
 
std::vector< std::vector< float > > _timings_frate
 
std::vector< std::vector< float > > _timings_kfrate_fe
 
std::vector< std::vector< float > > _timings_kfrate_be
 

Detailed Description

The core abstract class of the SLAM system. It handles front-end, back-end and initialization.

This is the skeleton of the SLAM system that will call all the subsystems (sensor processing, optimizer, map processing...) It loads all the parameters of the SLAM and implements frontEnd and backEnds that must be called in a separated thread. A few important methods relative to feature processing and pose estimation are implemented as well to make the frontEndStep() and backEndStep() methods readable. Also, a few profiling variables and methods are implemented to monitor the performances.

Constructor & Destructor Documentation

◆ SLAMCore() [1/2]

isae::SLAMCore::SLAMCore ( )
inline

◆ SLAMCore() [2/2]

isae::SLAMCore::SLAMCore ( std::shared_ptr< isae::SLAMParameters slam_param)

Member Function Documentation

◆ backEndStep()

virtual bool isae::SLAMCore::backEndStep ( )
pure virtual

brief description Back End: marginalization, local map optimization

Implemented in isae::SLAMNonOverlappingFov, isae::SLAMMono, isae::SLAMMonoVIO, isae::SLAMBiMonoVIO, and isae::SLAMBiMono.

◆ cleanFeatures()

void isae::SLAMCore::cleanFeatures ( std::shared_ptr< Frame > &  f)

Clean all the features that are outliers or are linked to outlier landmark.

◆ detectFeatures()

typed_vec_features isae::SLAMCore::detectFeatures ( std::shared_ptr< ImageSensor > &  sensor)

Detect all types of features for a given sensor with bucketting.

◆ epipolarFiltering()

typed_vec_match isae::SLAMCore::epipolarFiltering ( std::shared_ptr< ImageSensor > &  cam0,
std::shared_ptr< ImageSensor > &  cam1,
typed_vec_match  matches 
)

Filters the matches between two sensors (with consistent pose estimates) using epipolar plane check.

Parameters
cam0First sensor
cam1Second sensor
matchesTyped vector of matches to be filtered
Returns
A Typed vector of the valid matches

◆ frontEndStep()

virtual bool isae::SLAMCore::frontEndStep ( )
pure virtual

Front End: detection, tracking, pose estimation and landmark triangulation.

Implemented in isae::SLAMNonOverlappingFov, isae::SLAMMono, isae::SLAMMonoVIO, isae::SLAMBiMonoVIO, and isae::SLAMBiMono.

◆ getLastKF()

std::shared_ptr<Frame> isae::SLAMCore::getLastKF ( )
inline

◆ init()

virtual bool isae::SLAMCore::init ( )
pure virtual

Initialization step : create the first 3D landmarks and keyframe(s)

Implemented in isae::SLAMNonOverlappingFov, isae::SLAMMono, isae::SLAMMonoVIO, isae::SLAMBiMonoVIO, and isae::SLAMBiMono.

◆ initLandmarks()

void isae::SLAMCore::initLandmarks ( std::shared_ptr< Frame > &  f)

Initialize all the landmarks of the current frame using _matches_in_time and _matches_in_frame.

◆ matchFeatures()

uint isae::SLAMCore::matchFeatures ( std::shared_ptr< ImageSensor > &  sensor0,
std::shared_ptr< ImageSensor > &  sensor1,
typed_vec_match matches,
typed_vec_match matches_lmk,
typed_vec_features  features_to_track 
)

Predicts the position of the features and matches all the features between sensors.

Parameters
sensor0First sensor
sensor1Second sensor
matchesTyped vector of matches without landmarks passed as reference
matches_lmkTyped vector of matches with landmarks passed as reference
features_to_trackTyped vector of the features on sensor0 that will be matched for prediction
Returns
The number of tracks

◆ outlierRemoval()

void isae::SLAMCore::outlierRemoval ( )

Remove all the outlier features of _frame.

◆ predict()

bool isae::SLAMCore::predict ( std::shared_ptr< Frame > &  f)

Estimates the pose of a given frame.

Parameters
fThe frame whose pose is estimated passed as a reference
Returns
True if the prediction is a success, False otherwise

◆ predictFeature()

void isae::SLAMCore::predictFeature ( std::vector< std::shared_ptr< AFeature >>  features,
std::shared_ptr< ImageSensor sensor,
std::vector< std::shared_ptr< AFeature >> &  features_init,
vec_match  previous_matches = {} 
)

Predicts the position of a set of features on a given sensor.

Parameters
featuresSet of features to be predicted
sensorSensor on which the features has to be predicted
features_initThe set of features predicted passed as a reference
previous_matchesA prior on features_init that can eventually be used default is an empty set

◆ profiling()

void isae::SLAMCore::profiling ( )

A function to monitor the SLAM behaviour.

◆ recoverFeatureFromMapLandmarks()

uint isae::SLAMCore::recoverFeatureFromMapLandmarks ( std::shared_ptr< isae::AMap localmap,
std::shared_ptr< Frame > &  f 
)

Performs landmark resurection.

Parameters
localmapLocal maps that contains the landmark to project
fFrame on which the landmarks are resurected
Returns
The number of resurected landmarks

◆ runBackEnd()

void isae::SLAMCore::runBackEnd ( )

Thread for the backend.

◆ runFrontEnd()

void isae::SLAMCore::runFrontEnd ( )

Thread for the frontend.

◆ runFullOdom()

void isae::SLAMCore::runFullOdom ( )

Thread for the backend.

◆ shouldInsertKeyframe()

bool isae::SLAMCore::shouldInsertKeyframe ( std::shared_ptr< Frame > &  f)

Determines if the frame in argument is a KF.

◆ trackFeatures()

uint isae::SLAMCore::trackFeatures ( std::shared_ptr< ImageSensor > &  sensor0,
std::shared_ptr< ImageSensor > &  sensor1,
typed_vec_match matches,
typed_vec_match matches_lmk,
typed_vec_features  features_to_track 
)

Predicts the position of the features and tracks all the features.

Parameters
sensor0First sensor
sensor1Second sensor
matchesTyped vector of matches without landmarks passed as reference
matches_lmkTyped vector of matches with landmarks passed as reference
features_to_trackTyped vector of the features on sensor0 that will be tracked for prediction
Returns
The number of tracks

◆ updateLandmarks()

void isae::SLAMCore::updateLandmarks ( typed_vec_match  matches_lmk)

Member Data Documentation

◆ _6d_velocity

Vector6d isae::SLAMCore::_6d_velocity
protected

Current Velocity as a Twist vector.

◆ _avg_clean_t

float isae::SLAMCore::_avg_clean_t
protected

◆ _avg_detect_t

float isae::SLAMCore::_avg_detect_t
protected

◆ _avg_filter_t

float isae::SLAMCore::_avg_filter_t
protected

◆ _avg_frame_opt_t

float isae::SLAMCore::_avg_frame_opt_t
protected

◆ _avg_lmk_init_t

float isae::SLAMCore::_avg_lmk_init_t
protected

◆ _avg_lmk_resur_t

float isae::SLAMCore::_avg_lmk_resur_t
protected

◆ _avg_marg_t

float isae::SLAMCore::_avg_marg_t
protected

◆ _avg_match_frame_t

float isae::SLAMCore::_avg_match_frame_t
protected

◆ _avg_match_time_t

float isae::SLAMCore::_avg_match_time_t
protected

◆ _avg_matches_frame

float isae::SLAMCore::_avg_matches_frame
protected

◆ _avg_matches_time

float isae::SLAMCore::_avg_matches_time
protected

◆ _avg_predict_t

float isae::SLAMCore::_avg_predict_t
protected

◆ _avg_processing_t

float isae::SLAMCore::_avg_processing_t
protected

◆ _avg_resur_lmk

float isae::SLAMCore::_avg_resur_lmk
protected

◆ _avg_wdw_opt_t

float isae::SLAMCore::_avg_wdw_opt_t
protected

◆ _frame

std::shared_ptr<Frame> isae::SLAMCore::_frame
protected

Current frame.

◆ _frame_to_display

std::shared_ptr<Frame> isae::SLAMCore::_frame_to_display

◆ _frame_to_optim

std::shared_ptr<Frame> isae::SLAMCore::_frame_to_optim
protected

For communication between front-end and back-end.

◆ _global_map

std::shared_ptr<isae::GlobalMap> isae::SLAMCore::_global_map
protected

Current global map.

◆ _global_map_to_display

std::shared_ptr<isae::GlobalMap> isae::SLAMCore::_global_map_to_display

◆ _is_init

bool isae::SLAMCore::_is_init = false

Flag for initialization.

◆ _lmk_inmap

float isae::SLAMCore::_lmk_inmap
protected

◆ _local_map

std::shared_ptr<isae::LocalMap> isae::SLAMCore::_local_map
protected

Current local map.

◆ _local_map_to_display

std::shared_ptr<isae::LocalMap> isae::SLAMCore::_local_map_to_display

◆ _map_mutex

std::mutex isae::SLAMCore::_map_mutex
protected

◆ _matches_in_frame

typed_vec_match isae::SLAMCore::_matches_in_frame
protected

Typed vector of the matches between the sensors of _frame.

◆ _matches_in_frame_lmk

typed_vec_match isae::SLAMCore::_matches_in_frame_lmk
protected

Typed vector of the matches with landmarks between the sensors of _frame.

◆ _matches_in_time

typed_vec_match isae::SLAMCore::_matches_in_time
protected

Typed vector of the matches between the last KF and _frame.

◆ _matches_in_time_lmk

typed_vec_match isae::SLAMCore::_matches_in_time_lmk
protected

Typed vector of the matches with landmarks between the last KF and _frame.

◆ _max_movement_parallax

double isae::SLAMCore::_max_movement_parallax
protected

Max parallax until a KF is voted.

◆ _mesh_to_display

std::shared_ptr<Mesh3D> isae::SLAMCore::_mesh_to_display

◆ _mesher

std::shared_ptr<Mesher> isae::SLAMCore::_mesher
protected

Mesher of the SLAM.

◆ _min_lmk_number

double isae::SLAMCore::_min_lmk_number
protected

Under this number of landmark in _frame a KF is voted.

◆ _min_movement_parallax

double isae::SLAMCore::_min_movement_parallax
protected

Under this parallax, no motion is considered.

◆ _nframes

uint isae::SLAMCore::_nframes
protected

◆ _nkeyframes

uint isae::SLAMCore::_nkeyframes
protected

◆ _parallax

double isae::SLAMCore::_parallax
protected

Parallax between the last KF and _frame.

◆ _removed_feat

float isae::SLAMCore::_removed_feat
protected

◆ _removed_lmk

float isae::SLAMCore::_removed_lmk
protected

◆ _slam_param

std::shared_ptr<isae::SLAMParameters> isae::SLAMCore::_slam_param

◆ _successive_fails

int isae::SLAMCore::_successive_fails = 0

Number of successive failure to trigger reinitialization.

◆ _timings_frate

std::vector<std::vector<float> > isae::SLAMCore::_timings_frate
protected

◆ _timings_kfrate_be

std::vector<std::vector<float> > isae::SLAMCore::_timings_kfrate_be
protected

◆ _timings_kfrate_fe

std::vector<std::vector<float> > isae::SLAMCore::_timings_kfrate_fe
protected

The documentation for this class was generated from the following files: