SaDVIO
|
A SLAM class for non overlapping FoV setups. More...
#include <slamCore.h>
Public Member Functions | |
SLAMNonOverlappingFov () | |
SLAMNonOverlappingFov (std::shared_ptr< SLAMParameters > slam_param) | |
bool | init () override |
Initialization step : create the first 3D landmarks and keyframe(s) More... | |
bool | frontEndStep () override |
Front End: detection, tracking, pose estimation and landmark triangulation. More... | |
bool | backEndStep () override |
brief description Back End: marginalization, local map optimization More... | |
void | outlierRemoval () |
To remove outliers on both cameras. More... | |
void | initLandmarks (std::shared_ptr< Frame > &f) |
To init landmarks on both cameras. More... | |
int | scaleEstimationRANSAC (const Eigen::Affine3d T_cam0_cam1, const Eigen::Affine3d T_cam0_cam0p, typed_vec_match matches_cam1, double &lambda) |
To compute the scale using a single point in a RANSAC fashion. More... | |
bool | isDegenerativeMotion (Eigen::Affine3d T_cam0_cam0p, Eigen::Affine3d T_cam0_cam1, typed_vec_match matches) |
To check if the scale can't be recovered. More... | |
bool | predict (std::shared_ptr< Frame > &f) |
Prediction that takes into account both camera motions. More... | |
![]() | |
SLAMCore () | |
SLAMCore (std::shared_ptr< isae::SLAMParameters > slam_param) | |
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... | |
Additional Inherited Members | |
![]() | |
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 |
![]() | |
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 |
A SLAM class for non overlapping FoV setups.
|
inline |
|
inline |
|
overridevirtual |
brief description Back End: marginalization, local map optimization
Implements isae::SLAMCore.
|
overridevirtual |
Front End: detection, tracking, pose estimation and landmark triangulation.
Implements isae::SLAMCore.
|
overridevirtual |
Initialization step : create the first 3D landmarks and keyframe(s)
Implements isae::SLAMCore.
void isae::SLAMNonOverlappingFov::initLandmarks | ( | std::shared_ptr< Frame > & | f | ) |
To init landmarks on both cameras.
bool isae::SLAMNonOverlappingFov::isDegenerativeMotion | ( | Eigen::Affine3d | T_cam0_cam0p, |
Eigen::Affine3d | T_cam0_cam1, | ||
typed_vec_match | matches | ||
) |
To check if the scale can't be recovered.
void isae::SLAMNonOverlappingFov::outlierRemoval | ( | ) |
To remove outliers on both cameras.
bool isae::SLAMNonOverlappingFov::predict | ( | std::shared_ptr< Frame > & | f | ) |
Prediction that takes into account both camera motions.
int isae::SLAMNonOverlappingFov::scaleEstimationRANSAC | ( | const Eigen::Affine3d | T_cam0_cam1, |
const Eigen::Affine3d | T_cam0_cam0p, | ||
typed_vec_match | matches_cam1, | ||
double & | lambda | ||
) |
To compute the scale using a single point in a RANSAC fashion.
T_cam0_cam1 | Extrinsic between cameras |
T_cam0_cam0p | Up to scale estimation of motion of cam0 |
matches_cam1 | Matches in time of cam1 |
lambda | Scale estimate passed as reference |