Struct which stores all options needed for state estimation. More...
#include <InertialInitializerOptions.h>
Public Member Functions | |
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. More... | |
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 that everything was loaded properly from ROS/CMD parsers. More... | |
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 everything was loaded properly from ROS/CMD parsers. More... | |
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 everything was loaded properly from ROS/CMD parsers. More... | |
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 visual checking that everything was loaded properly from ROS/CMD parsers. More... | |
Public Attributes | |
double | calib_camimu_dt = 0.0 |
Time offset between camera and IMU (t_imu = t_cam + t_off) More... | |
std::map< size_t, Eigen::VectorXd > | camera_extrinsics |
Map between camid and camera extrinsics (q_ItoC, p_IinC). More... | |
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) More... | |
bool | downsample_cameras = false |
Will half the resolution all tracking image (aruco will be 1/4 instead of halved if dowsize_aruoc also enabled) More... | |
double | gravity_mag = 9.81 |
Gravity magnitude in the global frame (i.e. should be 9.81 typically) More... | |
Eigen::Vector3d | init_dyn_bias_a = Eigen::Vector3d::Zero() |
Initial IMU accelerometer bias values for dynamic initialization (will be optimized) More... | |
Eigen::Vector3d | init_dyn_bias_g = Eigen::Vector3d::Zero() |
Initial IMU gyroscope bias values for dynamic initialization (will be optimized) More... | |
double | init_dyn_inflation_bias_accel = 100.0 |
Magnitude we will inflate initial covariance of accelerometer bias. More... | |
double | init_dyn_inflation_bias_gyro = 100.0 |
Magnitude we will inflate initial covariance of gyroscope bias. More... | |
double | init_dyn_inflation_orientation = 10.0 |
Magnitude we will inflate initial covariance of orientation. More... | |
double | init_dyn_inflation_velocity = 10.0 |
Magnitude we will inflate initial covariance of velocity. More... | |
double | init_dyn_min_deg = 45.0 |
Minimum degrees we need to rotate before we try to init (sum of norm) More... | |
double | init_dyn_min_rec_cond = 1e-15 |
int | init_dyn_mle_max_iter = 20 |
Max number of MLE iterations for dynamic initialization. More... | |
int | init_dyn_mle_max_threads = 20 |
Max number of MLE threads for dynamic initialization. More... | |
double | init_dyn_mle_max_time = 5.0 |
Max time for MLE optimization (seconds) More... | |
bool | init_dyn_mle_opt_calib = false |
If we should optimize and recover the calibration in our MLE. More... | |
int | init_dyn_num_pose = 5 |
Number of poses to use during initialization (max should be cam freq * window) More... | |
bool | init_dyn_use = false |
If we should perform dynamic initialization. More... | |
double | init_imu_thresh = 1.0 |
Variance threshold on our acceleration to be classified as moving. More... | |
double | init_max_disparity = 1.0 |
Max disparity we will consider the unit to be stationary. More... | |
int | init_max_features = 50 |
Number of features we should try to track. More... | |
double | init_window_time = 1.0 |
Amount of time we will initialize over (seconds) More... | |
int | num_cameras = 1 |
Number of distinct cameras that we will observe features in. More... | |
double | sigma_a = 2.0000e-3 |
Accelerometer white noise (m/s^2/sqrt(hz)) More... | |
double | sigma_ab = 3.0000e-03 |
Accelerometer random walk (m/s^3/sqrt(hz)) More... | |
double | sigma_pix = 1 |
Noise sigma for our raw pixel measurements. More... | |
double | sigma_w = 1.6968e-04 |
Gyroscope white noise (rad/s/sqrt(hz)) More... | |
double | sigma_wb = 1.9393e-05 |
Gyroscope random walk (rad/s^2/sqrt(hz)) More... | |
double | sim_distance_threshold = 1.2 |
bool | sim_do_perturbation = false |
If we should perturb the calibration that the estimator starts with. More... | |
double | sim_freq_cam = 10.0 |
Frequency (Hz) that we will simulate our cameras. More... | |
double | sim_freq_imu = 400.0 |
Frequency (Hz) that we will simulate our inertial measurement unit. More... | |
double | sim_max_feature_gen_distance = 10 |
Feature distance we generate features from (maximum) More... | |
double | sim_min_feature_gen_distance = 5 |
Feature distance we generate features from (minimum) More... | |
int | sim_seed_measurements = 0 |
int | sim_seed_preturb = 0 |
Seed for calibration perturbations. Change this to perturb by different random values if perturbations are enabled. More... | |
int | sim_seed_state_init = 0 |
Seed for initial states (i.e. random feature 3d positions in the generated map) More... | |
std::string | sim_traj_path = "../ov_data/sim/udel_gore.txt" |
Path to the trajectory we will b-spline and simulate on. Should be time(s),pos(xyz),ori(xyzw) format. More... | |
bool | use_stereo = true |
If we should process two cameras are being stereo or binocular. If binocular, we do monocular feature tracking on each image. More... | |
Struct which stores all options needed for state estimation.
This is broken into a few different parts: estimator, trackers, and simulation. If you are going to add a parameter here you will need to add it to the parsers. You will also need to add it to the print statement at the bottom of each.
Definition at line 49 of file InertialInitializerOptions.h.
|
inline |
This function will load the non-simulation parameters of the system and print.
parser | If not null, this parser will be used to load our parameters |
Definition at line 55 of file InertialInitializerOptions.h.
|
inline |
This function will load print out all initializer settings loaded. This allows for visual checking that everything was loaded properly from ROS/CMD parsers.
parser | If not null, this parser will be used to load our parameters |
Definition at line 124 of file InertialInitializerOptions.h.
|
inline |
This function will load print out all noise parameters loaded. This allows for visual checking that everything was loaded properly from ROS/CMD parsers.
parser | If not null, this parser will be used to load our parameters |
Definition at line 215 of file InertialInitializerOptions.h.
|
inline |
This function will load print out all simulated parameters. This allows for visual checking that everything was loaded properly from ROS/CMD parsers.
parser | If not null, this parser will be used to load our parameters |
Definition at line 388 of file InertialInitializerOptions.h.
|
inline |
This function will load and print all state parameters (e.g. sensor extrinsics) This allows for visual checking that everything was loaded properly from ROS/CMD parsers.
parser | If not null, this parser will be used to load our parameters |
Definition at line 260 of file InertialInitializerOptions.h.
double ov_init::InertialInitializerOptions::calib_camimu_dt = 0.0 |
Time offset between camera and IMU (t_imu = t_cam + t_off)
Definition at line 246 of file InertialInitializerOptions.h.
std::map<size_t, Eigen::VectorXd> ov_init::InertialInitializerOptions::camera_extrinsics |
Map between camid and camera extrinsics (q_ItoC, p_IinC).
Definition at line 252 of file InertialInitializerOptions.h.
std::unordered_map<size_t, std::shared_ptr<ov_core::CamBase> > ov_init::InertialInitializerOptions::camera_intrinsics |
Map between camid and camera intrinsics (fx, fy, cx, cy, d1...d4, cam_w, cam_h)
Definition at line 249 of file InertialInitializerOptions.h.
bool ov_init::InertialInitializerOptions::downsample_cameras = false |
Will half the resolution all tracking image (aruco will be 1/4 instead of halved if dowsize_aruoc also enabled)
Definition at line 243 of file InertialInitializerOptions.h.
double ov_init::InertialInitializerOptions::gravity_mag = 9.81 |
Gravity magnitude in the global frame (i.e. should be 9.81 typically)
Definition at line 234 of file InertialInitializerOptions.h.
Eigen::Vector3d ov_init::InertialInitializerOptions::init_dyn_bias_a = Eigen::Vector3d::Zero() |
Initial IMU accelerometer bias values for dynamic initialization (will be optimized)
Definition at line 116 of file InertialInitializerOptions.h.
Eigen::Vector3d ov_init::InertialInitializerOptions::init_dyn_bias_g = Eigen::Vector3d::Zero() |
Initial IMU gyroscope bias values for dynamic initialization (will be optimized)
Definition at line 113 of file InertialInitializerOptions.h.
double ov_init::InertialInitializerOptions::init_dyn_inflation_bias_accel = 100.0 |
Magnitude we will inflate initial covariance of accelerometer bias.
Definition at line 106 of file InertialInitializerOptions.h.
double ov_init::InertialInitializerOptions::init_dyn_inflation_bias_gyro = 100.0 |
Magnitude we will inflate initial covariance of gyroscope bias.
Definition at line 103 of file InertialInitializerOptions.h.
double ov_init::InertialInitializerOptions::init_dyn_inflation_orientation = 10.0 |
Magnitude we will inflate initial covariance of orientation.
Definition at line 97 of file InertialInitializerOptions.h.
double ov_init::InertialInitializerOptions::init_dyn_inflation_velocity = 10.0 |
Magnitude we will inflate initial covariance of velocity.
Definition at line 100 of file InertialInitializerOptions.h.
double ov_init::InertialInitializerOptions::init_dyn_min_deg = 45.0 |
Minimum degrees we need to rotate before we try to init (sum of norm)
Definition at line 94 of file InertialInitializerOptions.h.
double ov_init::InertialInitializerOptions::init_dyn_min_rec_cond = 1e-15 |
Minimum reciprocal condition number acceptable for our covariance recovery (min_sigma / max_sigma < sqrt(min_reciprocal_condition_number))
Definition at line 110 of file InertialInitializerOptions.h.
int ov_init::InertialInitializerOptions::init_dyn_mle_max_iter = 20 |
Max number of MLE iterations for dynamic initialization.
Definition at line 82 of file InertialInitializerOptions.h.
int ov_init::InertialInitializerOptions::init_dyn_mle_max_threads = 20 |
Max number of MLE threads for dynamic initialization.
Definition at line 85 of file InertialInitializerOptions.h.
double ov_init::InertialInitializerOptions::init_dyn_mle_max_time = 5.0 |
Max time for MLE optimization (seconds)
Definition at line 88 of file InertialInitializerOptions.h.
bool ov_init::InertialInitializerOptions::init_dyn_mle_opt_calib = false |
If we should optimize and recover the calibration in our MLE.
Definition at line 79 of file InertialInitializerOptions.h.
int ov_init::InertialInitializerOptions::init_dyn_num_pose = 5 |
Number of poses to use during initialization (max should be cam freq * window)
Definition at line 91 of file InertialInitializerOptions.h.
bool ov_init::InertialInitializerOptions::init_dyn_use = false |
If we should perform dynamic initialization.
Definition at line 76 of file InertialInitializerOptions.h.
double ov_init::InertialInitializerOptions::init_imu_thresh = 1.0 |
Variance threshold on our acceleration to be classified as moving.
Definition at line 67 of file InertialInitializerOptions.h.
double ov_init::InertialInitializerOptions::init_max_disparity = 1.0 |
Max disparity we will consider the unit to be stationary.
Definition at line 70 of file InertialInitializerOptions.h.
int ov_init::InertialInitializerOptions::init_max_features = 50 |
Number of features we should try to track.
Definition at line 73 of file InertialInitializerOptions.h.
double ov_init::InertialInitializerOptions::init_window_time = 1.0 |
Amount of time we will initialize over (seconds)
Definition at line 64 of file InertialInitializerOptions.h.
int ov_init::InertialInitializerOptions::num_cameras = 1 |
Number of distinct cameras that we will observe features in.
Definition at line 237 of file InertialInitializerOptions.h.
double ov_init::InertialInitializerOptions::sigma_a = 2.0000e-3 |
Accelerometer white noise (m/s^2/sqrt(hz))
Definition at line 201 of file InertialInitializerOptions.h.
double ov_init::InertialInitializerOptions::sigma_ab = 3.0000e-03 |
Accelerometer random walk (m/s^3/sqrt(hz))
Definition at line 204 of file InertialInitializerOptions.h.
double ov_init::InertialInitializerOptions::sigma_pix = 1 |
Noise sigma for our raw pixel measurements.
Definition at line 207 of file InertialInitializerOptions.h.
double ov_init::InertialInitializerOptions::sigma_w = 1.6968e-04 |
Gyroscope white noise (rad/s/sqrt(hz))
Definition at line 195 of file InertialInitializerOptions.h.
double ov_init::InertialInitializerOptions::sigma_wb = 1.9393e-05 |
Gyroscope random walk (rad/s^2/sqrt(hz))
Definition at line 198 of file InertialInitializerOptions.h.
double ov_init::InertialInitializerOptions::sim_distance_threshold = 1.2 |
We will start simulating after we have moved this much along the b-spline. This prevents static starts as we init from groundtruth in simulation.
Definition at line 368 of file InertialInitializerOptions.h.
bool ov_init::InertialInitializerOptions::sim_do_perturbation = false |
If we should perturb the calibration that the estimator starts with.
Definition at line 361 of file InertialInitializerOptions.h.
double ov_init::InertialInitializerOptions::sim_freq_cam = 10.0 |
Frequency (Hz) that we will simulate our cameras.
Definition at line 371 of file InertialInitializerOptions.h.
double ov_init::InertialInitializerOptions::sim_freq_imu = 400.0 |
Frequency (Hz) that we will simulate our inertial measurement unit.
Definition at line 374 of file InertialInitializerOptions.h.
double ov_init::InertialInitializerOptions::sim_max_feature_gen_distance = 10 |
Feature distance we generate features from (maximum)
Definition at line 380 of file InertialInitializerOptions.h.
double ov_init::InertialInitializerOptions::sim_min_feature_gen_distance = 5 |
Feature distance we generate features from (minimum)
Definition at line 377 of file InertialInitializerOptions.h.
int ov_init::InertialInitializerOptions::sim_seed_measurements = 0 |
Measurement noise seed. This should be incremented for each run in the Monte-Carlo simulation to generate the same true measurements, but diffferent noise values.
Definition at line 358 of file InertialInitializerOptions.h.
int ov_init::InertialInitializerOptions::sim_seed_preturb = 0 |
Seed for calibration perturbations. Change this to perturb by different random values if perturbations are enabled.
Definition at line 354 of file InertialInitializerOptions.h.
int ov_init::InertialInitializerOptions::sim_seed_state_init = 0 |
Seed for initial states (i.e. random feature 3d positions in the generated map)
Definition at line 351 of file InertialInitializerOptions.h.
std::string ov_init::InertialInitializerOptions::sim_traj_path = "../ov_data/sim/udel_gore.txt" |
Path to the trajectory we will b-spline and simulate on. Should be time(s),pos(xyz),ori(xyzw) format.
Definition at line 364 of file InertialInitializerOptions.h.
bool ov_init::InertialInitializerOptions::use_stereo = true |
If we should process two cameras are being stereo or binocular. If binocular, we do monocular feature tracking on each image.
Definition at line 240 of file InertialInitializerOptions.h.