SaDVIO
|
The core abstract class of the SLAM system. It handles front-end, back-end and initialization. More...
#include <slamCore.h>
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< Frame > | getLastKF () |
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 |
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.
|
inline |
isae::SLAMCore::SLAMCore | ( | std::shared_ptr< isae::SLAMParameters > | slam_param | ) |
|
pure virtual |
brief description Back End: marginalization, local map optimization
Implemented in isae::SLAMNonOverlappingFov, isae::SLAMMono, isae::SLAMMonoVIO, isae::SLAMBiMonoVIO, and isae::SLAMBiMono.
void isae::SLAMCore::cleanFeatures | ( | std::shared_ptr< Frame > & | f | ) |
Clean all the features that are outliers or are linked to outlier landmark.
typed_vec_features isae::SLAMCore::detectFeatures | ( | std::shared_ptr< ImageSensor > & | sensor | ) |
Detect all types of features for a given sensor with bucketting.
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.
cam0 | First sensor |
cam1 | Second sensor |
matches | Typed vector of matches to be filtered |
|
pure virtual |
Front End: detection, tracking, pose estimation and landmark triangulation.
Implemented in isae::SLAMNonOverlappingFov, isae::SLAMMono, isae::SLAMMonoVIO, isae::SLAMBiMonoVIO, and isae::SLAMBiMono.
|
inline |
|
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.
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.
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.
sensor0 | First sensor |
sensor1 | Second sensor |
matches | Typed vector of matches without landmarks passed as reference |
matches_lmk | Typed vector of matches with landmarks passed as reference |
features_to_track | Typed vector of the features on sensor0 that will be matched for prediction |
void isae::SLAMCore::outlierRemoval | ( | ) |
Remove all the outlier features of _frame.
bool isae::SLAMCore::predict | ( | std::shared_ptr< Frame > & | f | ) |
Estimates the pose of a given frame.
f | The frame whose pose is estimated passed as a reference |
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.
features | Set of features to be predicted |
sensor | Sensor on which the features has to be predicted |
features_init | The set of features predicted passed as a reference |
previous_matches | A prior on features_init that can eventually be used default is an empty set |
void isae::SLAMCore::profiling | ( | ) |
A function to monitor the SLAM behaviour.
uint isae::SLAMCore::recoverFeatureFromMapLandmarks | ( | std::shared_ptr< isae::AMap > | localmap, |
std::shared_ptr< Frame > & | f | ||
) |
Performs landmark resurection.
localmap | Local maps that contains the landmark to project |
f | Frame on which the landmarks are resurected |
void isae::SLAMCore::runBackEnd | ( | ) |
Thread for the backend.
void isae::SLAMCore::runFrontEnd | ( | ) |
Thread for the frontend.
void isae::SLAMCore::runFullOdom | ( | ) |
Thread for the backend.
bool isae::SLAMCore::shouldInsertKeyframe | ( | std::shared_ptr< Frame > & | f | ) |
Determines if the frame in argument is a KF.
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.
sensor0 | First sensor |
sensor1 | Second sensor |
matches | Typed vector of matches without landmarks passed as reference |
matches_lmk | Typed vector of matches with landmarks passed as reference |
features_to_track | Typed vector of the features on sensor0 that will be tracked for prediction |
void isae::SLAMCore::updateLandmarks | ( | typed_vec_match | matches_lmk | ) |
|
protected |
Current Velocity as a Twist vector.
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
Current frame.
std::shared_ptr<Frame> isae::SLAMCore::_frame_to_display |
|
protected |
For communication between front-end and back-end.
|
protected |
Current global map.
std::shared_ptr<isae::GlobalMap> isae::SLAMCore::_global_map_to_display |
bool isae::SLAMCore::_is_init = false |
Flag for initialization.
|
protected |
|
protected |
Current local map.
std::shared_ptr<isae::LocalMap> isae::SLAMCore::_local_map_to_display |
|
protected |
|
protected |
Typed vector of the matches between the sensors of _frame.
|
protected |
Typed vector of the matches with landmarks between the sensors of _frame.
|
protected |
Typed vector of the matches between the last KF and _frame.
|
protected |
Typed vector of the matches with landmarks between the last KF and _frame.
|
protected |
Max parallax until a KF is voted.
std::shared_ptr<Mesh3D> isae::SLAMCore::_mesh_to_display |
|
protected |
Under this number of landmark in _frame a KF is voted.
|
protected |
Under this parallax, no motion is considered.
|
protected |
|
protected |
|
protected |
Parallax between the last KF and _frame.
|
protected |
|
protected |
std::shared_ptr<isae::SLAMParameters> isae::SLAMCore::_slam_param |
int isae::SLAMCore::_successive_fails = 0 |
Number of successive failure to trigger reinitialization.
|
protected |
|
protected |
|
protected |