StateOptions.h
Go to the documentation of this file.
1 /*
2  * OpenVINS: An Open Platform for Visual-Inertial Research
3  * Copyright (C) 2018-2023 Patrick Geneva
4  * Copyright (C) 2018-2023 Guoquan Huang
5  * Copyright (C) 2018-2023 OpenVINS Contributors
6  * Copyright (C) 2018-2019 Kevin Eckenhoff
7  *
8  * This program is free software: you can redistribute it and/or modify
9  * it under the terms of the GNU General Public License as published by
10  * the Free Software Foundation, either version 3 of the License, or
11  * (at your option) any later version.
12  *
13  * This program is distributed in the hope that it will be useful,
14  * but WITHOUT ANY WARRANTY; without even the implied warranty of
15  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
16  * GNU General Public License for more details.
17  *
18  * You should have received a copy of the GNU General Public License
19  * along with this program. If not, see <https://www.gnu.org/licenses/>.
20  */
21 
22 #ifndef OV_MSCKF_STATE_OPTIONS_H
23 #define OV_MSCKF_STATE_OPTIONS_H
24 
27 #include "utils/print.h"
28 #include "utils/sensor_data.h"
29 
30 namespace ov_msckf {
31 
35 struct StateOptions {
36 
38  bool do_fej = true;
39 
42 
44  IntegrationMethod integration_method = IntegrationMethod::RK4;
45 
47  bool do_calib_camera_pose = false;
48 
51 
54 
57 
60 
62  enum ImuModel { KALIBR, RPNG };
63 
65  ImuModel imu_model = ImuModel::KALIBR;
66 
68  int max_clone_size = 11;
69 
72 
74  int max_slam_in_update = 1000;
75 
77  int max_msckf_in_update = 1000;
78 
80  int max_aruco_features = 1024;
81 
83  int num_cameras = 1;
84 
86  ov_type::LandmarkRepresentation::Representation feat_rep_msckf = ov_type::LandmarkRepresentation::Representation::GLOBAL_3D;
87 
89  ov_type::LandmarkRepresentation::Representation feat_rep_slam = ov_type::LandmarkRepresentation::Representation::GLOBAL_3D;
90 
92  ov_type::LandmarkRepresentation::Representation feat_rep_aruco = ov_type::LandmarkRepresentation::Representation::GLOBAL_3D;
93 
95  void print(const std::shared_ptr<ov_core::YamlParser> &parser = nullptr) {
96  if (parser != nullptr) {
97  parser->parse_config("use_fej", do_fej);
98 
99  // Integration method
100  std::string integration_str = "rk4";
101  parser->parse_config("integration", integration_str);
102  if (integration_str == "discrete") {
103  integration_method = IntegrationMethod::DISCRETE;
104  } else if (integration_str == "rk4") {
105  integration_method = IntegrationMethod::RK4;
106  } else if (integration_str == "analytical") {
107  integration_method = IntegrationMethod::ANALYTICAL;
108  } else {
109  PRINT_ERROR(RED "invalid imu integration model: %s\n" RESET, integration_str.c_str());
110  PRINT_ERROR(RED "please select a valid model: discrete, rk4, analytical\n" RESET);
111  std::exit(EXIT_FAILURE);
112  }
113 
114  // Calibration booleans
115  parser->parse_config("calib_cam_extrinsics", do_calib_camera_pose);
116  parser->parse_config("calib_cam_intrinsics", do_calib_camera_intrinsics);
117  parser->parse_config("calib_cam_timeoffset", do_calib_camera_timeoffset);
118  parser->parse_config("calib_imu_intrinsics", do_calib_imu_intrinsics);
119  parser->parse_config("calib_imu_g_sensitivity", do_calib_imu_g_sensitivity);
120 
121  // State parameters
122  parser->parse_config("max_clones", max_clone_size);
123  parser->parse_config("max_slam", max_slam_features);
124  parser->parse_config("max_slam_in_update", max_slam_in_update);
125  parser->parse_config("max_msckf_in_update", max_msckf_in_update);
126  parser->parse_config("num_aruco", max_aruco_features);
127  parser->parse_config("max_cameras", num_cameras);
128 
129  // Feature representations
131  parser->parse_config("feat_rep_msckf", rep1);
134  parser->parse_config("feat_rep_slam", rep2);
137  parser->parse_config("feat_rep_aruco", rep3);
139 
140  // IMU model
141  std::string imu_model_str = "kalibr";
142  parser->parse_external("relative_config_imu", "imu0", "model", imu_model_str);
143  if (imu_model_str == "kalibr" || imu_model_str == "calibrated") {
144  imu_model = ImuModel::KALIBR;
145  } else if (imu_model_str == "rpng") {
146  imu_model = ImuModel::RPNG;
147  } else {
148  PRINT_ERROR(RED "invalid imu model: %s\n" RESET, imu_model_str.c_str());
149  PRINT_ERROR(RED "please select a valid model: kalibr, rpng\\n" RESET);
150  std::exit(EXIT_FAILURE);
151  }
152  if (imu_model_str == "calibrated" && (do_calib_imu_intrinsics || do_calib_imu_g_sensitivity)) {
153  PRINT_ERROR(RED "calibrated IMU model selected, but requested calibration!\n" RESET);
154  PRINT_ERROR(RED "please select what model you have: kalibr, rpng\n" RESET);
155  std::exit(EXIT_FAILURE);
156  }
157  }
158  PRINT_DEBUG(" - use_fej: %d\n", do_fej);
159  PRINT_DEBUG(" - integration: %d\n", integration_method);
160  PRINT_DEBUG(" - calib_cam_extrinsics: %d\n", do_calib_camera_pose);
161  PRINT_DEBUG(" - calib_cam_intrinsics: %d\n", do_calib_camera_intrinsics);
162  PRINT_DEBUG(" - calib_cam_timeoffset: %d\n", do_calib_camera_timeoffset);
163  PRINT_DEBUG(" - calib_imu_intrinsics: %d\n", do_calib_imu_intrinsics);
164  PRINT_DEBUG(" - calib_imu_g_sensitivity: %d\n", do_calib_imu_g_sensitivity);
165  PRINT_DEBUG(" - imu_model: %d\n", imu_model);
166  PRINT_DEBUG(" - max_clones: %d\n", max_clone_size);
167  PRINT_DEBUG(" - max_slam: %d\n", max_slam_features);
168  PRINT_DEBUG(" - max_slam_in_update: %d\n", max_slam_in_update);
169  PRINT_DEBUG(" - max_msckf_in_update: %d\n", max_msckf_in_update);
170  PRINT_DEBUG(" - max_aruco: %d\n", max_aruco_features);
171  PRINT_DEBUG(" - max_cameras: %d\n", num_cameras);
172  PRINT_DEBUG(" - feat_rep_msckf: %s\n", ov_type::LandmarkRepresentation::as_string(feat_rep_msckf).c_str());
173  PRINT_DEBUG(" - feat_rep_slam: %s\n", ov_type::LandmarkRepresentation::as_string(feat_rep_slam).c_str());
174  PRINT_DEBUG(" - feat_rep_aruco: %s\n", ov_type::LandmarkRepresentation::as_string(feat_rep_aruco).c_str());
175  }
176 };
177 
178 } // namespace ov_msckf
179 
180 #endif // OV_MSCKF_STATE_OPTIONS_H
ov_msckf::StateOptions::DISCRETE
@ DISCRETE
Definition: StateOptions.h:41
ov_msckf::StateOptions::feat_rep_slam
ov_type::LandmarkRepresentation::Representation feat_rep_slam
What representation our features are in (slam features)
Definition: StateOptions.h:89
ov_msckf::StateOptions::RPNG
@ RPNG
Definition: StateOptions.h:62
ov_type::LandmarkRepresentation::from_string
static Representation from_string(const std::string &feat_representation)
LandmarkRepresentation.h
PRINT_DEBUG
#define PRINT_DEBUG(x...)
ov_msckf::StateOptions::ImuModel
ImuModel
IMU intrinsic models.
Definition: StateOptions.h:62
ov_msckf
Extended Kalman Filter estimator.
Definition: VioManager.h:46
ov_msckf::StateOptions::max_slam_features
int max_slam_features
Max number of estimated SLAM features.
Definition: StateOptions.h:71
sensor_data.h
ov_msckf::StateOptions::max_clone_size
int max_clone_size
Max clone size of sliding window.
Definition: StateOptions.h:68
opencv_yaml_parse.h
ov_msckf::StateOptions::RK4
@ RK4
Definition: StateOptions.h:41
PRINT_ERROR
#define PRINT_ERROR(x...)
ov_msckf::StateOptions::feat_rep_msckf
ov_type::LandmarkRepresentation::Representation feat_rep_msckf
What representation our features are in (msckf features)
Definition: StateOptions.h:86
ov_msckf::StateOptions::do_calib_camera_pose
bool do_calib_camera_pose
Bool to determine whether or not to calibrate imu-to-camera pose.
Definition: StateOptions.h:47
ov_type::LandmarkRepresentation::Representation
Representation
ov_msckf::StateOptions::do_calib_imu_intrinsics
bool do_calib_imu_intrinsics
Bool to determine whether or not to calibrate the IMU intrinsics.
Definition: StateOptions.h:56
ov_msckf::StateOptions::do_calib_camera_timeoffset
bool do_calib_camera_timeoffset
Bool to determine whether or not to calibrate camera to IMU time offset.
Definition: StateOptions.h:53
ov_msckf::StateOptions::max_slam_in_update
int max_slam_in_update
Max number of SLAM features we allow to be included in a single EKF update.
Definition: StateOptions.h:74
ov_msckf::StateOptions::max_aruco_features
int max_aruco_features
Max number of estimated ARUCO features.
Definition: StateOptions.h:80
ov_msckf::StateOptions::print
void print(const std::shared_ptr< ov_core::YamlParser > &parser=nullptr)
Nice print function of what parameters we have loaded.
Definition: StateOptions.h:95
ov_msckf::StateOptions::KALIBR
@ KALIBR
Definition: StateOptions.h:62
print.h
ov_msckf::StateOptions::IntegrationMethod
IntegrationMethod
Numerical integration methods.
Definition: StateOptions.h:41
ov_msckf::StateOptions
Struct which stores all our filter options.
Definition: StateOptions.h:35
ov_msckf::StateOptions::ANALYTICAL
@ ANALYTICAL
Definition: StateOptions.h:41
ov_msckf::StateOptions::imu_model
ImuModel imu_model
What model our IMU intrinsics are.
Definition: StateOptions.h:65
RESET
#define RESET
ov_msckf::StateOptions::feat_rep_aruco
ov_type::LandmarkRepresentation::Representation feat_rep_aruco
What representation our features are in (aruco tag features)
Definition: StateOptions.h:92
ov_msckf::StateOptions::integration_method
IntegrationMethod integration_method
What type of numerical integration is used during propagation.
Definition: StateOptions.h:44
ov_msckf::StateOptions::do_calib_camera_intrinsics
bool do_calib_camera_intrinsics
Bool to determine whether or not to calibrate camera intrinsics.
Definition: StateOptions.h:50
ov_msckf::StateOptions::num_cameras
int num_cameras
Number of distinct cameras that we will observe features in.
Definition: StateOptions.h:83
ov_msckf::StateOptions::do_calib_imu_g_sensitivity
bool do_calib_imu_g_sensitivity
Bool to determine whether or not to calibrate the Gravity sensitivity.
Definition: StateOptions.h:59
ov_msckf::StateOptions::do_fej
bool do_fej
Bool to determine whether or not to do first estimate Jacobians.
Definition: StateOptions.h:38
RED
RED
ov_msckf::StateOptions::max_msckf_in_update
int max_msckf_in_update
Max number of MSCKF features we will use at a given image timestep.
Definition: StateOptions.h:77
ov_type::LandmarkRepresentation::as_string
static std::string as_string(Representation feat_representation)


ov_msckf
Author(s): Patrick Geneva , Kevin Eckenhoff , Guoquan Huang
autogenerated on Mon Dec 16 2024 03:06:54