InertialInitializerOptions.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_INIT_INERTIALINITIALIZEROPTIONS_H
23 #define OV_INIT_INERTIALINITIALIZEROPTIONS_H
24 
25 #include <Eigen/Eigen>
26 #include <iostream>
27 #include <sstream>
28 #include <string>
29 #include <vector>
30 
31 #include "cam/CamEqui.h"
32 #include "cam/CamRadtan.h"
34 #include "track/TrackBase.h"
35 #include "utils/colors.h"
37 #include "utils/print.h"
38 #include "utils/quat_ops.h"
39 
40 namespace ov_init {
41 
50 
55  void print_and_load(const std::shared_ptr<ov_core::YamlParser> &parser = nullptr) {
57  print_and_load_noise(parser);
58  print_and_load_state(parser);
59  }
60 
61  // INITIALIZATION ============================
62 
64  double init_window_time = 1.0;
65 
67  double init_imu_thresh = 1.0;
68 
70  double init_max_disparity = 1.0;
71 
74 
76  bool init_dyn_use = false;
77 
79  bool init_dyn_mle_opt_calib = false;
80 
83 
86 
88  double init_dyn_mle_max_time = 5.0;
89 
92 
94  double init_dyn_min_deg = 45.0;
95 
98 
101 
104 
107 
110  double init_dyn_min_rec_cond = 1e-15;
111 
113  Eigen::Vector3d init_dyn_bias_g = Eigen::Vector3d::Zero();
114 
116  Eigen::Vector3d init_dyn_bias_a = Eigen::Vector3d::Zero();
117 
124  void print_and_load_initializer(const std::shared_ptr<ov_core::YamlParser> &parser = nullptr) {
125  PRINT_DEBUG("INITIALIZATION SETTINGS:\n");
126  if (parser != nullptr) {
127  parser->parse_config("init_window_time", init_window_time);
128  parser->parse_config("init_imu_thresh", init_imu_thresh);
129  parser->parse_config("init_max_disparity", init_max_disparity);
130  parser->parse_config("init_max_features", init_max_features);
131  parser->parse_config("init_dyn_use", init_dyn_use);
132  parser->parse_config("init_dyn_mle_opt_calib", init_dyn_mle_opt_calib);
133  parser->parse_config("init_dyn_mle_max_iter", init_dyn_mle_max_iter);
134  parser->parse_config("init_dyn_mle_max_threads", init_dyn_mle_max_threads);
135  parser->parse_config("init_dyn_mle_max_time", init_dyn_mle_max_time);
136  parser->parse_config("init_dyn_num_pose", init_dyn_num_pose);
137  parser->parse_config("init_dyn_min_deg", init_dyn_min_deg);
138  parser->parse_config("init_dyn_inflation_ori", init_dyn_inflation_orientation);
139  parser->parse_config("init_dyn_inflation_vel", init_dyn_inflation_velocity);
140  parser->parse_config("init_dyn_inflation_bg", init_dyn_inflation_bias_gyro);
141  parser->parse_config("init_dyn_inflation_ba", init_dyn_inflation_bias_accel);
142  parser->parse_config("init_dyn_min_rec_cond", init_dyn_min_rec_cond);
143  std::vector<double> bias_g = {0, 0, 0};
144  std::vector<double> bias_a = {0, 0, 0};
145  parser->parse_config("init_dyn_bias_g", bias_g);
146  parser->parse_config("init_dyn_bias_a", bias_a);
147  init_dyn_bias_g << bias_g.at(0), bias_g.at(1), bias_g.at(2);
148  init_dyn_bias_a << bias_a.at(0), bias_a.at(1), bias_a.at(2);
149  }
150  PRINT_DEBUG(" - init_window_time: %.2f\n", init_window_time);
151  PRINT_DEBUG(" - init_imu_thresh: %.2f\n", init_imu_thresh);
152  PRINT_DEBUG(" - init_max_disparity: %.2f\n", init_max_disparity);
153  PRINT_DEBUG(" - init_max_features: %.2f\n", init_max_features);
154  if (init_max_features < 15) {
155  PRINT_ERROR(RED "number of requested feature tracks to init not enough!!\n" RESET);
156  PRINT_ERROR(RED " init_max_features = %d\n" RESET, init_max_features);
157  std::exit(EXIT_FAILURE);
158  }
159  if (init_imu_thresh <= 0.0 && !init_dyn_use) {
160  PRINT_ERROR(RED "need to have an IMU threshold for static initialization!\n" RESET);
161  PRINT_ERROR(RED " init_imu_thresh = %.3f\n" RESET, init_imu_thresh);
162  PRINT_ERROR(RED " init_dyn_use = %d\n" RESET, init_dyn_use);
163  std::exit(EXIT_FAILURE);
164  }
165  if (init_max_disparity <= 0.0 && !init_dyn_use) {
166  PRINT_ERROR(RED "need to have an DISPARITY threshold for static initialization!\n" RESET);
167  PRINT_ERROR(RED " init_max_disparity = %.3f\n" RESET, init_max_disparity);
168  PRINT_ERROR(RED " init_dyn_use = %d\n" RESET, init_dyn_use);
169  std::exit(EXIT_FAILURE);
170  }
171  PRINT_DEBUG(" - init_dyn_use: %d\n", init_dyn_use);
172  PRINT_DEBUG(" - init_dyn_mle_opt_calib: %d\n", init_dyn_mle_opt_calib);
173  PRINT_DEBUG(" - init_dyn_mle_max_iter: %d\n", init_dyn_mle_max_iter);
174  PRINT_DEBUG(" - init_dyn_mle_max_threads: %d\n", init_dyn_mle_max_threads);
175  PRINT_DEBUG(" - init_dyn_mle_max_time: %.2f\n", init_dyn_mle_max_time);
176  PRINT_DEBUG(" - init_dyn_num_pose: %d\n", init_dyn_num_pose);
177  PRINT_DEBUG(" - init_dyn_min_deg: %.2f\n", init_dyn_min_deg);
178  PRINT_DEBUG(" - init_dyn_inflation_ori: %.2e\n", init_dyn_inflation_orientation);
179  PRINT_DEBUG(" - init_dyn_inflation_vel: %.2e\n", init_dyn_inflation_velocity);
180  PRINT_DEBUG(" - init_dyn_inflation_bg: %.2e\n", init_dyn_inflation_bias_gyro);
181  PRINT_DEBUG(" - init_dyn_inflation_ba: %.2e\n", init_dyn_inflation_bias_accel);
182  PRINT_DEBUG(" - init_dyn_min_rec_cond: %.2e\n", init_dyn_min_rec_cond);
183  if (init_dyn_num_pose < 4) {
184  PRINT_ERROR(RED "number of requested frames to init not enough!!\n" RESET);
185  PRINT_ERROR(RED " init_dyn_num_pose = %d (4 min)\n" RESET, init_dyn_num_pose);
186  std::exit(EXIT_FAILURE);
187  }
188  PRINT_DEBUG(" - init_dyn_bias_g: %.2f, %.2f, %.2f\n", init_dyn_bias_g(0), init_dyn_bias_g(1), init_dyn_bias_g(2));
189  PRINT_DEBUG(" - init_dyn_bias_a: %.2f, %.2f, %.2f\n", init_dyn_bias_a(0), init_dyn_bias_a(1), init_dyn_bias_a(2));
190  }
191 
192  // NOISE / CHI2 ============================
193 
195  double sigma_w = 1.6968e-04;
196 
198  double sigma_wb = 1.9393e-05;
199 
201  double sigma_a = 2.0000e-3;
202 
204  double sigma_ab = 3.0000e-03;
205 
207  double sigma_pix = 1;
208 
215  void print_and_load_noise(const std::shared_ptr<ov_core::YamlParser> &parser = nullptr) {
216  PRINT_DEBUG("NOISE PARAMETERS:\n");
217  if (parser != nullptr) {
218  parser->parse_external("relative_config_imu", "imu0", "gyroscope_noise_density", sigma_w);
219  parser->parse_external("relative_config_imu", "imu0", "gyroscope_random_walk", sigma_wb);
220  parser->parse_external("relative_config_imu", "imu0", "accelerometer_noise_density", sigma_a);
221  parser->parse_external("relative_config_imu", "imu0", "accelerometer_random_walk", sigma_ab);
222  parser->parse_config("up_slam_sigma_px", sigma_pix);
223  }
224  PRINT_DEBUG(" - gyroscope_noise_density: %.6f\n", sigma_w);
225  PRINT_DEBUG(" - accelerometer_noise_density: %.5f\n", sigma_a);
226  PRINT_DEBUG(" - gyroscope_random_walk: %.7f\n", sigma_wb);
227  PRINT_DEBUG(" - accelerometer_random_walk: %.6f\n", sigma_ab);
228  PRINT_DEBUG(" - sigma_pix: %.2f\n", sigma_pix);
229  }
230 
231  // STATE DEFAULTS ==========================
232 
234  double gravity_mag = 9.81;
235 
237  int num_cameras = 1;
238 
240  bool use_stereo = true;
241 
243  bool downsample_cameras = false;
244 
246  double calib_camimu_dt = 0.0;
247 
249  std::unordered_map<size_t, std::shared_ptr<ov_core::CamBase>> camera_intrinsics;
250 
252  std::map<size_t, Eigen::VectorXd> camera_extrinsics;
253 
260  void print_and_load_state(const std::shared_ptr<ov_core::YamlParser> &parser = nullptr) {
261  if (parser != nullptr) {
262  parser->parse_config("gravity_mag", gravity_mag);
263  parser->parse_config("max_cameras", num_cameras); // might be redundant
264  parser->parse_config("use_stereo", use_stereo);
265  parser->parse_config("downsample_cameras", downsample_cameras);
266  for (int i = 0; i < num_cameras; i++) {
267 
268  // Time offset (use the first one)
269  // TODO: support multiple time offsets between cameras
270  if (i == 0) {
271  parser->parse_external("relative_config_imucam", "cam" + std::to_string(i), "timeshift_cam_imu", calib_camimu_dt, false);
272  }
273 
274  // Distortion model
275  std::string dist_model = "radtan";
276  parser->parse_external("relative_config_imucam", "cam" + std::to_string(i), "distortion_model", dist_model);
277 
278  // Distortion parameters
279  std::vector<double> cam_calib1 = {1, 1, 0, 0};
280  std::vector<double> cam_calib2 = {0, 0, 0, 0};
281  parser->parse_external("relative_config_imucam", "cam" + std::to_string(i), "intrinsics", cam_calib1);
282  parser->parse_external("relative_config_imucam", "cam" + std::to_string(i), "distortion_coeffs", cam_calib2);
283  Eigen::VectorXd cam_calib = Eigen::VectorXd::Zero(8);
284  cam_calib << cam_calib1.at(0), cam_calib1.at(1), cam_calib1.at(2), cam_calib1.at(3), cam_calib2.at(0), cam_calib2.at(1),
285  cam_calib2.at(2), cam_calib2.at(3);
286  cam_calib(0) /= (downsample_cameras) ? 2.0 : 1.0;
287  cam_calib(1) /= (downsample_cameras) ? 2.0 : 1.0;
288  cam_calib(2) /= (downsample_cameras) ? 2.0 : 1.0;
289  cam_calib(3) /= (downsample_cameras) ? 2.0 : 1.0;
290 
291  // FOV / resolution
292  std::vector<int> matrix_wh = {1, 1};
293  parser->parse_external("relative_config_imucam", "cam" + std::to_string(i), "resolution", matrix_wh);
294  matrix_wh.at(0) /= (downsample_cameras) ? 2.0 : 1.0;
295  matrix_wh.at(1) /= (downsample_cameras) ? 2.0 : 1.0;
296 
297  // Extrinsics
298  Eigen::Matrix4d T_CtoI = Eigen::Matrix4d::Identity();
299  parser->parse_external("relative_config_imucam", "cam" + std::to_string(i), "T_imu_cam", T_CtoI);
300 
301  // Load these into our state
302  Eigen::Matrix<double, 7, 1> cam_eigen;
303  cam_eigen.block(0, 0, 4, 1) = ov_core::rot_2_quat(T_CtoI.block(0, 0, 3, 3).transpose());
304  cam_eigen.block(4, 0, 3, 1) = -T_CtoI.block(0, 0, 3, 3).transpose() * T_CtoI.block(0, 3, 3, 1);
305 
306  // Create intrinsics model
307  if (dist_model == "equidistant") {
308  camera_intrinsics.insert({i, std::make_shared<ov_core::CamEqui>(matrix_wh.at(0), matrix_wh.at(1))});
309  camera_intrinsics.at(i)->set_value(cam_calib);
310  } else {
311  camera_intrinsics.insert({i, std::make_shared<ov_core::CamRadtan>(matrix_wh.at(0), matrix_wh.at(1))});
312  camera_intrinsics.at(i)->set_value(cam_calib);
313  }
314  camera_extrinsics.insert({i, cam_eigen});
315  }
316  }
317  PRINT_DEBUG("STATE PARAMETERS:\n");
318  PRINT_DEBUG(" - gravity_mag: %.4f\n", gravity_mag);
319  PRINT_DEBUG(" - gravity: %.3f, %.3f, %.3f\n", 0.0, 0.0, gravity_mag);
320  PRINT_DEBUG(" - num_cameras: %d\n", num_cameras);
321  PRINT_DEBUG(" - use_stereo: %d\n", use_stereo);
322  PRINT_DEBUG(" - downsize cameras: %d\n", downsample_cameras);
323  if (num_cameras != (int)camera_intrinsics.size() || num_cameras != (int)camera_extrinsics.size()) {
324  PRINT_ERROR(RED "[SIM]: camera calib size does not match max cameras...\n" RESET);
325  PRINT_ERROR(RED "[SIM]: got %d but expected %d max cameras (camera_intrinsics)\n" RESET, (int)camera_intrinsics.size(), num_cameras);
326  PRINT_ERROR(RED "[SIM]: got %d but expected %d max cameras (camera_extrinsics)\n" RESET, (int)camera_extrinsics.size(), num_cameras);
327  std::exit(EXIT_FAILURE);
328  }
329  PRINT_DEBUG(" - calib_camimu_dt: %.4f\n", calib_camimu_dt);
330  for (int n = 0; n < num_cameras; n++) {
331  std::stringstream ss;
332  ss << "cam_" << n << "_fisheye:" << (std::dynamic_pointer_cast<ov_core::CamEqui>(camera_intrinsics.at(n)) != nullptr) << std::endl;
333  ss << "cam_" << n << "_wh:" << std::endl << camera_intrinsics.at(n)->w() << " x " << camera_intrinsics.at(n)->h() << std::endl;
334  ss << "cam_" << n << "_intrinsic(0:3):" << std::endl
335  << camera_intrinsics.at(n)->get_value().block(0, 0, 4, 1).transpose() << std::endl;
336  ss << "cam_" << n << "_intrinsic(4:7):" << std::endl
337  << camera_intrinsics.at(n)->get_value().block(4, 0, 4, 1).transpose() << std::endl;
338  ss << "cam_" << n << "_extrinsic(0:3):" << std::endl << camera_extrinsics.at(n).block(0, 0, 4, 1).transpose() << std::endl;
339  ss << "cam_" << n << "_extrinsic(4:6):" << std::endl << camera_extrinsics.at(n).block(4, 0, 3, 1).transpose() << std::endl;
340  Eigen::Matrix4d T_CtoI = Eigen::Matrix4d::Identity();
341  T_CtoI.block(0, 0, 3, 3) = ov_core::quat_2_Rot(camera_extrinsics.at(n).block(0, 0, 4, 1)).transpose();
342  T_CtoI.block(0, 3, 3, 1) = -T_CtoI.block(0, 0, 3, 3) * camera_extrinsics.at(n).block(4, 0, 3, 1);
343  ss << "T_C" << n << "toI:" << std::endl << T_CtoI << std::endl << std::endl;
344  PRINT_DEBUG(ss.str().c_str());
345  }
346  }
347 
348  // SIMULATOR ===============================
349 
352 
355 
359 
361  bool sim_do_perturbation = false;
362 
364  std::string sim_traj_path = "../ov_data/sim/udel_gore.txt";
365 
369 
371  double sim_freq_cam = 10.0;
372 
374  double sim_freq_imu = 400.0;
375 
378 
381 
388  void print_and_load_simulation(const std::shared_ptr<ov_core::YamlParser> &parser = nullptr) {
389  if (parser != nullptr) {
390  parser->parse_config("sim_seed_state_init", sim_seed_state_init);
391  parser->parse_config("sim_seed_preturb", sim_seed_preturb);
392  parser->parse_config("sim_seed_measurements", sim_seed_measurements);
393  parser->parse_config("sim_do_perturbation", sim_do_perturbation);
394  parser->parse_config("sim_traj_path", sim_traj_path);
395  parser->parse_config("sim_distance_threshold", sim_distance_threshold);
396  parser->parse_config("sim_freq_cam", sim_freq_cam);
397  parser->parse_config("sim_freq_imu", sim_freq_imu);
398  parser->parse_config("sim_min_feature_gen_dist", sim_min_feature_gen_distance);
399  parser->parse_config("sim_max_feature_gen_dist", sim_max_feature_gen_distance);
400  }
401  PRINT_DEBUG("SIMULATION PARAMETERS:\n");
402  PRINT_WARNING(BOLDRED " - state init seed: %d \n" RESET, sim_seed_state_init);
403  PRINT_WARNING(BOLDRED " - perturb seed: %d \n" RESET, sim_seed_preturb);
404  PRINT_WARNING(BOLDRED " - measurement seed: %d \n" RESET, sim_seed_measurements);
405  PRINT_WARNING(BOLDRED " - do perturb?: %d\n" RESET, sim_do_perturbation);
406  PRINT_DEBUG(" - traj path: %s\n", sim_traj_path.c_str());
407  PRINT_DEBUG(" - dist thresh: %.2f\n", sim_distance_threshold);
408  PRINT_DEBUG(" - cam feq: %.2f\n", sim_freq_cam);
409  PRINT_DEBUG(" - imu feq: %.2f\n", sim_freq_imu);
410  PRINT_DEBUG(" - min feat dist: %.2f\n", sim_min_feature_gen_distance);
411  PRINT_DEBUG(" - max feat dist: %.2f\n", sim_max_feature_gen_distance);
412  }
413 };
414 
415 } // namespace ov_init
416 
417 #endif // OV_INIT_INERTIALINITIALIZEROPTIONS_H
ov_init::InertialInitializerOptions::sim_max_feature_gen_distance
double sim_max_feature_gen_distance
Feature distance we generate features from (maximum)
Definition: InertialInitializerOptions.h:380
ov_init::InertialInitializerOptions::sim_seed_measurements
int sim_seed_measurements
Definition: InertialInitializerOptions.h:358
ov_init::InertialInitializerOptions::init_dyn_inflation_velocity
double init_dyn_inflation_velocity
Magnitude we will inflate initial covariance of velocity.
Definition: InertialInitializerOptions.h:100
ov_init::InertialInitializerOptions::sim_freq_imu
double sim_freq_imu
Frequency (Hz) that we will simulate our inertial measurement unit.
Definition: InertialInitializerOptions.h:374
ov_init::InertialInitializerOptions::init_dyn_mle_max_threads
int init_dyn_mle_max_threads
Max number of MLE threads for dynamic initialization.
Definition: InertialInitializerOptions.h:85
ov_init::InertialInitializerOptions::camera_intrinsics
std::unordered_map< size_t, std::shared_ptr< ov_core::CamBase > > camera_intrinsics
Map between camid and camera intrinsics (fx, fy, cx, cy, d1...d4, cam_w, cam_h)
Definition: InertialInitializerOptions.h:249
quat_ops.h
ov_init::InertialInitializerOptions::sigma_pix
double sigma_pix
Noise sigma for our raw pixel measurements.
Definition: InertialInitializerOptions.h:207
ov_init::InertialInitializerOptions
Struct which stores all options needed for state estimation.
Definition: InertialInitializerOptions.h:49
ov_init::InertialInitializerOptions::print_and_load_initializer
void print_and_load_initializer(const std::shared_ptr< ov_core::YamlParser > &parser=nullptr)
This function will load print out all initializer settings loaded. This allows for visual checking th...
Definition: InertialInitializerOptions.h:124
ov_init::InertialInitializerOptions::camera_extrinsics
std::map< size_t, Eigen::VectorXd > camera_extrinsics
Map between camid and camera extrinsics (q_ItoC, p_IinC).
Definition: InertialInitializerOptions.h:252
ov_init::InertialInitializerOptions::print_and_load_simulation
void print_and_load_simulation(const std::shared_ptr< ov_core::YamlParser > &parser=nullptr)
This function will load print out all simulated parameters. This allows for visual checking that ever...
Definition: InertialInitializerOptions.h:388
FeatureInitializerOptions.h
ov_init::InertialInitializerOptions::init_dyn_bias_a
Eigen::Vector3d init_dyn_bias_a
Initial IMU accelerometer bias values for dynamic initialization (will be optimized)
Definition: InertialInitializerOptions.h:116
PRINT_DEBUG
#define PRINT_DEBUG(x...)
ov_init::InertialInitializerOptions::init_dyn_min_deg
double init_dyn_min_deg
Minimum degrees we need to rotate before we try to init (sum of norm)
Definition: InertialInitializerOptions.h:94
ov_init::InertialInitializerOptions::num_cameras
int num_cameras
Number of distinct cameras that we will observe features in.
Definition: InertialInitializerOptions.h:237
ov_init::InertialInitializerOptions::sigma_w
double sigma_w
Gyroscope white noise (rad/s/sqrt(hz))
Definition: InertialInitializerOptions.h:195
ov_init::InertialInitializerOptions::init_max_features
int init_max_features
Number of features we should try to track.
Definition: InertialInitializerOptions.h:73
opencv_yaml_parse.h
ov_init::InertialInitializerOptions::gravity_mag
double gravity_mag
Gravity magnitude in the global frame (i.e. should be 9.81 typically)
Definition: InertialInitializerOptions.h:234
ov_init::InertialInitializerOptions::init_dyn_mle_max_iter
int init_dyn_mle_max_iter
Max number of MLE iterations for dynamic initialization.
Definition: InertialInitializerOptions.h:82
ov_init::InertialInitializerOptions::sim_distance_threshold
double sim_distance_threshold
Definition: InertialInitializerOptions.h:368
PRINT_ERROR
#define PRINT_ERROR(x...)
ov_init::InertialInitializerOptions::sigma_ab
double sigma_ab
Accelerometer random walk (m/s^3/sqrt(hz))
Definition: InertialInitializerOptions.h:204
ov_init::InertialInitializerOptions::init_window_time
double init_window_time
Amount of time we will initialize over (seconds)
Definition: InertialInitializerOptions.h:64
ov_init::InertialInitializerOptions::init_dyn_mle_max_time
double init_dyn_mle_max_time
Max time for MLE optimization (seconds)
Definition: InertialInitializerOptions.h:88
ov_init::InertialInitializerOptions::init_dyn_use
bool init_dyn_use
If we should perform dynamic initialization.
Definition: InertialInitializerOptions.h:76
ov_init::InertialInitializerOptions::sim_freq_cam
double sim_freq_cam
Frequency (Hz) that we will simulate our cameras.
Definition: InertialInitializerOptions.h:371
ov_init::InertialInitializerOptions::print_and_load
void print_and_load(const std::shared_ptr< ov_core::YamlParser > &parser=nullptr)
This function will load the non-simulation parameters of the system and print.
Definition: InertialInitializerOptions.h:55
ov_init::InertialInitializerOptions::calib_camimu_dt
double calib_camimu_dt
Time offset between camera and IMU (t_imu = t_cam + t_off)
Definition: InertialInitializerOptions.h:246
CamRadtan.h
ov_init::InertialInitializerOptions::init_dyn_mle_opt_calib
bool init_dyn_mle_opt_calib
If we should optimize and recover the calibration in our MLE.
Definition: InertialInitializerOptions.h:79
ov_init
State initialization code.
Definition: Factor_GenericPrior.h:27
ov_init::InertialInitializerOptions::init_dyn_inflation_orientation
double init_dyn_inflation_orientation
Magnitude we will inflate initial covariance of orientation.
Definition: InertialInitializerOptions.h:97
ov_core::rot_2_quat
Eigen::Matrix< double, 4, 1 > rot_2_quat(const Eigen::Matrix< double, 3, 3 > &rot)
ov_core::quat_2_Rot
Eigen::Matrix< double, 3, 3 > quat_2_Rot(const Eigen::Matrix< double, 4, 1 > &q)
ov_init::InertialInitializerOptions::init_dyn_inflation_bias_accel
double init_dyn_inflation_bias_accel
Magnitude we will inflate initial covariance of accelerometer bias.
Definition: InertialInitializerOptions.h:106
ov_init::InertialInitializerOptions::use_stereo
bool use_stereo
If we should process two cameras are being stereo or binocular. If binocular, we do monocular feature...
Definition: InertialInitializerOptions.h:240
ov_init::InertialInitializerOptions::init_imu_thresh
double init_imu_thresh
Variance threshold on our acceleration to be classified as moving.
Definition: InertialInitializerOptions.h:67
CamEqui.h
print.h
ov_init::InertialInitializerOptions::downsample_cameras
bool downsample_cameras
Will half the resolution all tracking image (aruco will be 1/4 instead of halved if dowsize_aruoc als...
Definition: InertialInitializerOptions.h:243
ov_init::InertialInitializerOptions::init_max_disparity
double init_max_disparity
Max disparity we will consider the unit to be stationary.
Definition: InertialInitializerOptions.h:70
ov_init::InertialInitializerOptions::sim_do_perturbation
bool sim_do_perturbation
If we should perturb the calibration that the estimator starts with.
Definition: InertialInitializerOptions.h:361
BOLDRED
#define BOLDRED
colors.h
ov_init::InertialInitializerOptions::sim_traj_path
std::string sim_traj_path
Path to the trajectory we will b-spline and simulate on. Should be time(s),pos(xyz),...
Definition: InertialInitializerOptions.h:364
ov_init::InertialInitializerOptions::sim_seed_preturb
int sim_seed_preturb
Seed for calibration perturbations. Change this to perturb by different random values if perturbation...
Definition: InertialInitializerOptions.h:354
RESET
#define RESET
TrackBase.h
ov_init::InertialInitializerOptions::init_dyn_inflation_bias_gyro
double init_dyn_inflation_bias_gyro
Magnitude we will inflate initial covariance of gyroscope bias.
Definition: InertialInitializerOptions.h:103
ov_init::InertialInitializerOptions::sigma_a
double sigma_a
Accelerometer white noise (m/s^2/sqrt(hz))
Definition: InertialInitializerOptions.h:201
ov_init::InertialInitializerOptions::print_and_load_state
void print_and_load_state(const std::shared_ptr< ov_core::YamlParser > &parser=nullptr)
This function will load and print all state parameters (e.g. sensor extrinsics) This allows for visua...
Definition: InertialInitializerOptions.h:260
ov_init::InertialInitializerOptions::init_dyn_bias_g
Eigen::Vector3d init_dyn_bias_g
Initial IMU gyroscope bias values for dynamic initialization (will be optimized)
Definition: InertialInitializerOptions.h:113
ov_init::InertialInitializerOptions::init_dyn_min_rec_cond
double init_dyn_min_rec_cond
Definition: InertialInitializerOptions.h:110
ov_init::InertialInitializerOptions::sim_min_feature_gen_distance
double sim_min_feature_gen_distance
Feature distance we generate features from (minimum)
Definition: InertialInitializerOptions.h:377
RED
RED
ov_init::InertialInitializerOptions::sigma_wb
double sigma_wb
Gyroscope random walk (rad/s^2/sqrt(hz))
Definition: InertialInitializerOptions.h:198
PRINT_WARNING
#define PRINT_WARNING(x...)
ov_init::InertialInitializerOptions::print_and_load_noise
void print_and_load_noise(const std::shared_ptr< ov_core::YamlParser > &parser=nullptr)
This function will load print out all noise parameters loaded. This allows for visual checking that e...
Definition: InertialInitializerOptions.h:215
ov_init::InertialInitializerOptions::sim_seed_state_init
int sim_seed_state_init
Seed for initial states (i.e. random feature 3d positions in the generated map)
Definition: InertialInitializerOptions.h:351
ov_init::InertialInitializerOptions::init_dyn_num_pose
int init_dyn_num_pose
Number of poses to use during initialization (max should be cam freq * window)
Definition: InertialInitializerOptions.h:91


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