Go to the documentation of this file.
22 #ifndef OV_INIT_INERTIALINITIALIZEROPTIONS_H
23 #define OV_INIT_INERTIALINITIALIZEROPTIONS_H
25 #include <Eigen/Eigen>
55 void print_and_load(
const std::shared_ptr<ov_core::YamlParser> &parser =
nullptr) {
126 if (parser !=
nullptr) {
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);
157 std::exit(EXIT_FAILURE);
163 std::exit(EXIT_FAILURE);
169 std::exit(EXIT_FAILURE);
186 std::exit(EXIT_FAILURE);
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);
261 if (parser !=
nullptr) {
264 parser->parse_config(
"use_stereo",
use_stereo);
271 parser->parse_external(
"relative_config_imucam",
"cam" + std::to_string(i),
"timeshift_cam_imu",
calib_camimu_dt,
false);
275 std::string dist_model =
"radtan";
276 parser->parse_external(
"relative_config_imucam",
"cam" + std::to_string(i),
"distortion_model", dist_model);
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);
292 std::vector<int> matrix_wh = {1, 1};
293 parser->parse_external(
"relative_config_imucam",
"cam" + std::to_string(i),
"resolution", matrix_wh);
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);
302 Eigen::Matrix<double, 7, 1> cam_eigen;
304 cam_eigen.block(4, 0, 3, 1) = -T_CtoI.block(0, 0, 3, 3).transpose() * T_CtoI.block(0, 3, 3, 1);
307 if (dist_model ==
"equidistant") {
308 camera_intrinsics.insert({i, std::make_shared<ov_core::CamEqui>(matrix_wh.at(0), matrix_wh.at(1))});
311 camera_intrinsics.insert({i, std::make_shared<ov_core::CamRadtan>(matrix_wh.at(0), matrix_wh.at(1))});
327 std::exit(EXIT_FAILURE);
331 std::stringstream ss;
332 ss <<
"cam_" << n <<
"_fisheye:" << (std::dynamic_pointer_cast<ov_core::CamEqui>(
camera_intrinsics.at(n)) !=
nullptr) << 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();
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;
389 if (parser !=
nullptr) {
417 #endif // OV_INIT_INERTIALINITIALIZEROPTIONS_H
double sim_max_feature_gen_distance
Feature distance we generate features from (maximum)
int sim_seed_measurements
double init_dyn_inflation_velocity
Magnitude we will inflate initial covariance of velocity.
double sim_freq_imu
Frequency (Hz) that we will simulate our inertial measurement unit.
int init_dyn_mle_max_threads
Max number of MLE threads for dynamic initialization.
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)
double sigma_pix
Noise sigma for our raw pixel measurements.
Struct which stores all options needed for state estimation.
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...
std::map< size_t, Eigen::VectorXd > camera_extrinsics
Map between camid and camera extrinsics (q_ItoC, p_IinC).
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...
Eigen::Vector3d init_dyn_bias_a
Initial IMU accelerometer bias values for dynamic initialization (will be optimized)
#define PRINT_DEBUG(x...)
double init_dyn_min_deg
Minimum degrees we need to rotate before we try to init (sum of norm)
int num_cameras
Number of distinct cameras that we will observe features in.
double sigma_w
Gyroscope white noise (rad/s/sqrt(hz))
int init_max_features
Number of features we should try to track.
double gravity_mag
Gravity magnitude in the global frame (i.e. should be 9.81 typically)
int init_dyn_mle_max_iter
Max number of MLE iterations for dynamic initialization.
double sim_distance_threshold
#define PRINT_ERROR(x...)
double sigma_ab
Accelerometer random walk (m/s^3/sqrt(hz))
double init_window_time
Amount of time we will initialize over (seconds)
double init_dyn_mle_max_time
Max time for MLE optimization (seconds)
bool init_dyn_use
If we should perform dynamic initialization.
double sim_freq_cam
Frequency (Hz) that we will simulate our cameras.
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.
double calib_camimu_dt
Time offset between camera and IMU (t_imu = t_cam + t_off)
bool init_dyn_mle_opt_calib
If we should optimize and recover the calibration in our MLE.
State initialization code.
double init_dyn_inflation_orientation
Magnitude we will inflate initial covariance of orientation.
Eigen::Matrix< double, 4, 1 > rot_2_quat(const Eigen::Matrix< double, 3, 3 > &rot)
Eigen::Matrix< double, 3, 3 > quat_2_Rot(const Eigen::Matrix< double, 4, 1 > &q)
double init_dyn_inflation_bias_accel
Magnitude we will inflate initial covariance of accelerometer bias.
bool use_stereo
If we should process two cameras are being stereo or binocular. If binocular, we do monocular feature...
double init_imu_thresh
Variance threshold on our acceleration to be classified as moving.
bool downsample_cameras
Will half the resolution all tracking image (aruco will be 1/4 instead of halved if dowsize_aruoc als...
double init_max_disparity
Max disparity we will consider the unit to be stationary.
bool sim_do_perturbation
If we should perturb the calibration that the estimator starts with.
std::string sim_traj_path
Path to the trajectory we will b-spline and simulate on. Should be time(s),pos(xyz),...
int sim_seed_preturb
Seed for calibration perturbations. Change this to perturb by different random values if perturbation...
double init_dyn_inflation_bias_gyro
Magnitude we will inflate initial covariance of gyroscope bias.
double sigma_a
Accelerometer white noise (m/s^2/sqrt(hz))
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...
Eigen::Vector3d init_dyn_bias_g
Initial IMU gyroscope bias values for dynamic initialization (will be optimized)
double init_dyn_min_rec_cond
double sim_min_feature_gen_distance
Feature distance we generate features from (minimum)
double sigma_wb
Gyroscope random walk (rad/s^2/sqrt(hz))
#define PRINT_WARNING(x...)
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...
int sim_seed_state_init
Seed for initial states (i.e. random feature 3d positions in the generated map)
int init_dyn_num_pose
Number of poses to use during initialization (max should be cam freq * window)
ov_init
Author(s): Patrick Geneva
, Kevin Eckenhoff , Guoquan Huang
autogenerated on Mon Dec 16 2024 03:06:51