SaDVIO
slamParameters.h
Go to the documentation of this file.
1 #ifndef SLAMPARAMETERS_H
2 #define SLAMPARAMETERS_H
3 
5 #include <iostream>
6 #include <string>
7 #include <unordered_map>
8 #include <yaml-cpp/yaml.h>
9 
10 namespace isae {
11 
12 class AFeatureDetector;
13 class AFeatureMatcher;
14 class AFeatureTracker;
15 class ADataProvider;
16 class APoseEstimator;
17 class ALandmarkInitializer;
18 class BundleAdjustmentCERES;
19 class LocalMap;
20 
27  std::shared_ptr<AFeatureMatcher> feature_matcher;
28 };
29 
38  std::shared_ptr<AFeatureTracker> feature_tracker;
39 };
40 
44 struct FeatureStruct {
45  std::string label_feature;
46  std::string detector_label;
49  std::string tracker_label;
53  double tracker_max_err;
54  std::string matcher_label;
58  std::string
60 };
61 
65 struct Config {
66  std::string dataset_path;
67  std::string dataset_id;
68  std::string slam_mode;
70  bool enable_visu;
71  std::string optimizer;
73  float clahe_clip;
74  float downsampling;
77  std::string pose_estimator;
78  std::string tracker;
85  bool mesh3D;
86  double ZNCC_tsh;
87  double max_length_tsh;
88 
89  std::vector<FeatureStruct> features_handled;
90 };
91 
99  public:
100  SLAMParameters(const std::string config_file);
101 
102  std::shared_ptr<ADataProvider> getDataProvider() { return _data_provider; }
103  std::unordered_map<std::string, std::shared_ptr<AFeatureDetector>> getFeatureDetectors() { return _detector_map; }
104  std::unordered_map<std::string, FeatureTrackerStruct> getFeatureTrackers() { return _tracker_map; }
105  std::unordered_map<std::string, FeatureMatcherStruct> getFeatureMatchers() { return _matcher_map; }
106  std::unordered_map<std::string, std::shared_ptr<ALandmarkInitializer>> getLandmarksInitializer() {
107  return _lmk_init_map;
108  };
109 
110  std::shared_ptr<APoseEstimator> getPoseEstimator() { return _pose_estimator; }
111  std::shared_ptr<AOptimizer> getOptimizerFront() { return _optimizer_frontend; }
112  std::shared_ptr<AOptimizer> getOptimizerBack() { return _optimizer_backend; }
113  void readConfigFile(const std::string &path_config_folder);
115 
116  private:
117  std::shared_ptr<ADataProvider> _data_provider;
118  std::unordered_map<std::string, std::shared_ptr<AFeatureDetector>> _detector_map;
119  std::unordered_map<std::string, FeatureTrackerStruct> _tracker_map;
120  std::unordered_map<std::string, FeatureMatcherStruct> _matcher_map;
121  std::unordered_map<std::string, std::shared_ptr<ALandmarkInitializer>> _lmk_init_map;
122 
123  std::shared_ptr<APoseEstimator> _pose_estimator;
124  std::shared_ptr<AOptimizer> _optimizer_frontend, _optimizer_backend;
125  std::shared_ptr<LocalMap> _local_map;
126 
127  void createProvider();
128  void createDetectors();
129  void createTrackers();
130  void createMatchers();
131  void createPoseEstimator();
132  void createLandmarkInitializers();
133  void createOptimizer();
134 };
135 
136 } // namespace isae
137 
138 #endif
isae::FeatureStruct::tracker_width
int tracker_width
searchAreaWidth of tracker
Definition: slamParameters.h:51
isae::FeatureTrackerStruct::feature_tracker
std::shared_ptr< AFeatureTracker > feature_tracker
Definition: slamParameters.h:38
isae::SLAMParameters::getOptimizerBack
std::shared_ptr< AOptimizer > getOptimizerBack()
Definition: slamParameters.h:112
isae::FeatureMatcherStruct
A struct that contains a feature matcher and its parameters.
Definition: slamParameters.h:24
isae::Config::fixed_frame_number
int fixed_frame_number
Number of fixed frame for gauge fixing.
Definition: slamParameters.h:81
isae::Config::features_handled
std::vector< FeatureStruct > features_handled
types of features the slam will work on separated with commas (,)
Definition: slamParameters.h:89
isae::FeatureStruct::max_matching_dist
double max_matching_dist
distance for matching
Definition: slamParameters.h:55
isae::SLAMParameters
A class that gathers most of the algorithmic blocks of the SLAM system that can be setup in the confi...
Definition: slamParameters.h:98
isae::SLAMParameters::getFeatureDetectors
std::unordered_map< std::string, std::shared_ptr< AFeatureDetector > > getFeatureDetectors()
Definition: slamParameters.h:103
isae::Config
This structure contains the configuration parameters located in the config file.
Definition: slamParameters.h:65
isae::FeatureStruct::matcher_height
int matcher_height
searchAreaHeight of tracker
Definition: slamParameters.h:56
isae::Config::min_movement_parallax
float min_movement_parallax
Below this parallax, no motion is considered.
Definition: slamParameters.h:83
AOptimizer.h
isae::FeatureMatcherStruct::feature_matcher
std::shared_ptr< AFeatureMatcher > feature_matcher
Definition: slamParameters.h:27
isae::Config::min_lmk_number
float min_lmk_number
Below this number of landmark, a KF is voted.
Definition: slamParameters.h:82
isae::SLAMParameters::getFeatureTrackers
std::unordered_map< std::string, FeatureTrackerStruct > getFeatureTrackers()
Definition: slamParameters.h:104
isae::Config::slam_mode
std::string slam_mode
SLAM mode (mono, bimono, monovio...)
Definition: slamParameters.h:68
isae::Config::max_movement_parallax
float max_movement_parallax
Over this parallax, a KF is voted.
Definition: slamParameters.h:84
isae::Config::clahe_clip
float clahe_clip
Clip of CLAHE (useful only if it is chosen for contrast enhancement)
Definition: slamParameters.h:73
isae::SLAMParameters::getOptimizerFront
std::shared_ptr< AOptimizer > getOptimizerFront()
Definition: slamParameters.h:111
isae::Config::marginalization
int marginalization
0 no marginalization, 1 marginalization
Definition: slamParameters.h:75
isae::FeatureTrackerStruct::tracker_nlvls_pyramids
int tracker_nlvls_pyramids
Definition: slamParameters.h:36
isae::FeatureStruct::detector_label
std::string detector_label
label of the feature detector
Definition: slamParameters.h:46
isae::SLAMParameters::readConfigFile
void readConfigFile(const std::string &path_config_folder)
Definition: slamParameters.cpp:48
isae::Config::pose_estimator
std::string pose_estimator
Type of pose estimator.
Definition: slamParameters.h:77
isae::Config::tracker
std::string tracker
Type of tracking (matcher or klt)
Definition: slamParameters.h:78
isae::FeatureStruct::tracker_nlvls_pyramids
int tracker_nlvls_pyramids
nlevels of pyramids for klt tracking
Definition: slamParameters.h:52
isae::FeatureStruct::matcher_width
int matcher_width
searchAreaWidth of tracker
Definition: slamParameters.h:57
isae::SLAMParameters::getPoseEstimator
std::shared_ptr< APoseEstimator > getPoseEstimator()
Definition: slamParameters.h:110
isae::FeatureStruct::tracker_height
int tracker_height
searchAreaHeight of tracker
Definition: slamParameters.h:50
isae::FeatureStruct::n_features_per_cell
int n_features_per_cell
number of features per cell for bucketting
Definition: slamParameters.h:48
isae::FeatureStruct
A struct that gathers all the parameters for a feature.
Definition: slamParameters.h:44
isae::FeatureMatcherStruct::matcher_width
int matcher_width
Definition: slamParameters.h:25
isae::Config::ZNCC_tsh
double ZNCC_tsh
Threshold on ZNCC for triangle filtering.
Definition: slamParameters.h:86
isae::FeatureTrackerStruct::tracker_max_err
double tracker_max_err
Definition: slamParameters.h:37
isae::Config::max_kf_number
int max_kf_number
Size maximum of the sliding windown.
Definition: slamParameters.h:80
isae::FeatureMatcherStruct::matcher_height
int matcher_height
Definition: slamParameters.h:26
isae
Definition: AFeature2D.h:8
isae::FeatureTrackerStruct::tracker_height
int tracker_height
Definition: slamParameters.h:35
isae::SLAMParameters::getLandmarksInitializer
std::unordered_map< std::string, std::shared_ptr< ALandmarkInitializer > > getLandmarksInitializer()
Definition: slamParameters.h:106
isae::Config::dataset_path
std::string dataset_path
Path to the dataset.
Definition: slamParameters.h:66
isae::FeatureStruct::lmk_triangulator
std::string lmk_triangulator
landmarkTriangulation class we will use to triangulate landmark of label_feature type
Definition: slamParameters.h:59
isae::Config::dataset_id
std::string dataset_id
Id of the dataset.
Definition: slamParameters.h:67
isae::FeatureStruct::tracker_label
std::string tracker_label
class name of the tracker we will use in our SLAM
Definition: slamParameters.h:49
isae::Config::downsampling
float downsampling
Float to reduce the size of the image (0,5 = half the size of the img)
Definition: slamParameters.h:74
isae::Config::optimizer
std::string optimizer
Optimizer type (ReprojectionError, AngularError...)
Definition: slamParameters.h:71
isae::FeatureStruct::tracker_max_err
double tracker_max_err
error threshold for klt tracking
Definition: slamParameters.h:53
isae::FeatureTrackerStruct
A struct that contains a feature tracker and its parameters.
Definition: slamParameters.h:33
isae::FeatureStruct::matcher_label
std::string matcher_label
class name of the matcher we will use in our SLAM
Definition: slamParameters.h:54
isae::Config::max_length_tsh
double max_length_tsh
Threshold on maximum length for triangle filtering.
Definition: slamParameters.h:87
isae::SLAMParameters::_config
Config _config
Definition: slamParameters.h:114
isae::Config::min_kf_number
int min_kf_number
Minimum KF for optimization.
Definition: slamParameters.h:79
isae::Config::enable_visu
bool enable_visu
Allow visualization.
Definition: slamParameters.h:70
isae::FeatureStruct::number_detected_features
int number_detected_features
number of features to be detected by the detector
Definition: slamParameters.h:47
isae::Config::sparsification
bool sparsification
0 no sparsification, 1 sparsification
Definition: slamParameters.h:76
isae::Config::mesh3D
bool mesh3D
0 no 3D mesh, 1 3D mesh
Definition: slamParameters.h:85
isae::FeatureTrackerStruct::tracker_width
int tracker_width
Definition: slamParameters.h:34
isae::Config::contrast_enhancer
int contrast_enhancer
integer to choose the contrast enhancement algorithm
Definition: slamParameters.h:72
isae::Config::multithreading
bool multithreading
Allow to run front-end and back-end on different threads (unstable...)
Definition: slamParameters.h:69
isae::SLAMParameters::getDataProvider
std::shared_ptr< ADataProvider > getDataProvider()
Definition: slamParameters.h:102
isae::FeatureStruct::label_feature
std::string label_feature
Label of the feature.
Definition: slamParameters.h:45
isae::SLAMParameters::SLAMParameters
SLAMParameters(const std::string config_file)
Definition: slamParameters.cpp:35
isae::SLAMParameters::getFeatureMatchers
std::unordered_map< std::string, FeatureMatcherStruct > getFeatureMatchers()
Definition: slamParameters.h:105