Go to the documentation of this file.
22 #ifndef OV_MSCKF_VIOMANAGEROPTIONS_H
23 #define OV_MSCKF_VIOMANAGEROPTIONS_H
25 #include <Eigen/Eigen>
62 void print_and_load(
const std::shared_ptr<ov_core::YamlParser> &parser =
nullptr) {
113 if (parser !=
nullptr) {
115 parser->parse_config(
"try_zupt",
try_zupt);
158 if (parser !=
nullptr) {
159 parser->parse_external(
"relative_config_imu",
"imu0",
"gyroscope_noise_density",
imu_noises.
sigma_w);
160 parser->parse_external(
"relative_config_imu",
"imu0",
"gyroscope_random_walk",
imu_noises.
sigma_wb);
161 parser->parse_external(
"relative_config_imu",
"imu0",
"accelerometer_noise_density",
imu_noises.
sigma_a);
162 parser->parse_external(
"relative_config_imu",
"imu0",
"accelerometer_random_walk",
imu_noises.
sigma_ab);
165 if (parser !=
nullptr) {
229 if (parser !=
nullptr) {
236 parser->parse_external(
"relative_config_imucam",
"cam" + std::to_string(i),
"timeshift_cam_imu",
calib_camimu_dt,
false);
240 std::string dist_model =
"radtan";
241 parser->parse_external(
"relative_config_imucam",
"cam" + std::to_string(i),
"distortion_model", dist_model);
244 std::vector<double> cam_calib1 = {1, 1, 0, 0};
245 std::vector<double> cam_calib2 = {0, 0, 0, 0};
246 parser->parse_external(
"relative_config_imucam",
"cam" + std::to_string(i),
"intrinsics", cam_calib1);
247 parser->parse_external(
"relative_config_imucam",
"cam" + std::to_string(i),
"distortion_coeffs", cam_calib2);
248 Eigen::VectorXd cam_calib = Eigen::VectorXd::Zero(8);
249 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),
250 cam_calib2.at(2), cam_calib2.at(3);
257 std::vector<int> matrix_wh = {1, 1};
258 parser->parse_external(
"relative_config_imucam",
"cam" + std::to_string(i),
"resolution", matrix_wh);
263 Eigen::Matrix4d T_CtoI = Eigen::Matrix4d::Identity();
264 parser->parse_external(
"relative_config_imucam",
"cam" + std::to_string(i),
"T_imu_cam", T_CtoI);
267 Eigen::Matrix<double, 7, 1> cam_eigen;
269 cam_eigen.block(4, 0, 3, 1) = -T_CtoI.block(0, 0, 3, 3).transpose() * T_CtoI.block(0, 3, 3, 1);
272 if (dist_model ==
"equidistant") {
273 camera_intrinsics.insert({i, std::make_shared<ov_core::CamEqui>(matrix_wh.at(0), matrix_wh.at(1))});
276 camera_intrinsics.insert({i, std::make_shared<ov_core::CamRadtan>(matrix_wh.at(0), matrix_wh.at(1))});
281 parser->parse_config(
"use_mask",
use_mask);
284 std::string mask_path;
285 std::string mask_node =
"mask" + std::to_string(i);
286 parser->parse_config(mask_node, mask_path);
287 std::string total_mask_path = parser->get_config_folder() + mask_path;
288 if (!boost::filesystem::exists(total_mask_path)) {
291 std::exit(EXIT_FAILURE);
293 cv::Mat mask = cv::imread(total_mask_path, cv::IMREAD_GRAYSCALE);
294 masks.insert({i, mask});
300 std::exit(EXIT_FAILURE);
306 Eigen::Matrix3d Tw = Eigen::Matrix3d::Identity();
307 parser->parse_external(
"relative_config_imu",
"imu0",
"Tw", Tw);
308 Eigen::Matrix3d Ta = Eigen::Matrix3d::Identity();
309 parser->parse_external(
"relative_config_imu",
"imu0",
"Ta", Ta);
310 Eigen::Matrix3d R_IMUtoACC = Eigen::Matrix3d::Identity();
311 parser->parse_external(
"relative_config_imu",
"imu0",
"R_IMUtoACC", R_IMUtoACC);
312 Eigen::Matrix3d R_IMUtoGYRO = Eigen::Matrix3d::Identity();
313 parser->parse_external(
"relative_config_imu",
"imu0",
"R_IMUtoGYRO", R_IMUtoGYRO);
314 Eigen::Matrix3d Tg = Eigen::Matrix3d::Zero();
315 parser->parse_external(
"relative_config_imu",
"imu0",
"Tg", Tg);
319 Eigen::Matrix3d Dw = Tw.colPivHouseholderQr().solve(Eigen::Matrix3d::Identity());
320 Eigen::Matrix3d Da = Ta.colPivHouseholderQr().solve(Eigen::Matrix3d::Identity());
321 Eigen::Matrix3d R_ACCtoIMU = R_IMUtoACC.transpose();
322 Eigen::Matrix3d R_GYROtoIMU = R_IMUtoGYRO.transpose();
323 if (std::isnan(Tw.norm()) || std::isnan(Dw.norm())) {
324 std::stringstream ss;
325 ss <<
"gyroscope has bad intrinsic values!" << std::endl;
326 ss <<
"Tw - " << std::endl << Tw << std::endl << std::endl;
327 ss <<
"Dw - " << std::endl << Dw << std::endl << std::endl;
329 std::exit(EXIT_FAILURE);
331 if (std::isnan(Ta.norm()) || std::isnan(Da.norm())) {
332 std::stringstream ss;
333 ss <<
"accelerometer has bad intrinsic values!" << std::endl;
334 ss <<
"Ta - " << std::endl << Ta << std::endl << std::endl;
335 ss <<
"Da - " << std::endl << Da << std::endl << std::endl;
337 std::exit(EXIT_FAILURE);
343 vec_dw << Dw.block<3, 1>(0, 0), Dw.block<2, 1>(1, 1), Dw(2, 2);
344 vec_da << Da.block<3, 1>(0, 0), Da.block<2, 1>(1, 1), Da(2, 2);
346 vec_dw << Dw(0, 0), Dw.block<2, 1>(0, 1), Dw.block<3, 1>(0, 2);
347 vec_da << Da(0, 0), Da.block<2, 1>(0, 1), Da.block<3, 1>(0, 2);
349 vec_tg << Tg.block<3, 1>(0, 0), Tg.block<3, 1>(0, 1), Tg.block<3, 1>(0, 2);
363 std::exit(EXIT_FAILURE);
368 std::stringstream ss;
369 ss <<
"cam_" << n <<
"_fisheye:" << (std::dynamic_pointer_cast<ov_core::CamEqui>(
camera_intrinsics.at(n)) !=
nullptr) << std::endl;
371 ss <<
"cam_" << n <<
"_intrinsic(0:3):" << std::endl
372 <<
camera_intrinsics.at(n)->get_value().block(0, 0, 4, 1).transpose() << std::endl;
373 ss <<
"cam_" << n <<
"_intrinsic(4:7):" << std::endl
374 <<
camera_intrinsics.at(n)->get_value().block(4, 0, 4, 1).transpose() << std::endl;
375 ss <<
"cam_" << n <<
"_extrinsic(0:3):" << std::endl <<
camera_extrinsics.at(n).block(0, 0, 4, 1).transpose() << std::endl;
376 ss <<
"cam_" << n <<
"_extrinsic(4:6):" << std::endl <<
camera_extrinsics.at(n).block(4, 0, 3, 1).transpose() << std::endl;
377 Eigen::Matrix4d T_CtoI = Eigen::Matrix4d::Identity();
379 T_CtoI.block(0, 3, 3, 1) = -T_CtoI.block(0, 0, 3, 3) *
camera_extrinsics.at(n).block(4, 0, 3, 1);
380 ss <<
"T_C" << n <<
"toI:" << std::endl << T_CtoI << std::endl << std::endl;
384 std::stringstream ss;
385 ss <<
"imu model:" << ((
state_options.
imu_model == StateOptions::ImuModel::KALIBR) ?
"kalibr" :
"rpng") << std::endl;
386 ss <<
"Dw (columnwise):" <<
vec_dw.transpose() << std::endl;
387 ss <<
"Da (columnwise):" <<
vec_da.transpose() << std::endl;
388 ss <<
"Tg (columnwise):" <<
vec_tg.transpose() << std::endl;
389 ss <<
"q_GYROtoI: " <<
q_GYROtoIMU.transpose() << std::endl;
390 ss <<
"q_ACCtoI: " <<
q_ACCtoIMU.transpose() << std::endl;
454 if (parser !=
nullptr) {
455 parser->parse_config(
"use_stereo",
use_stereo);
456 parser->parse_config(
"use_klt",
use_klt);
457 parser->parse_config(
"use_aruco",
use_aruco);
463 parser->parse_config(
"num_pts",
num_pts);
465 parser->parse_config(
"grid_x",
grid_x);
466 parser->parse_config(
"grid_y",
grid_y);
468 std::string histogram_method_str =
"HISTOGRAM";
469 parser->parse_config(
"histogram_method", histogram_method_str);
470 if (histogram_method_str ==
"NONE") {
472 }
else if (histogram_method_str ==
"HISTOGRAM") {
474 }
else if (histogram_method_str ==
"CLAHE") {
477 printf(
RED "VioManager(): invalid feature histogram specified:\n" RESET);
479 printf(
RED "\t- HISTOGRAM\n" RESET);
481 std::exit(EXIT_FAILURE);
483 parser->parse_config(
"knn_ratio",
knn_ratio);
546 if (parser !=
nullptr) {
574 #endif // OV_MSCKF_VIOMANAGEROPTIONS_H
std::map< size_t, Eigen::VectorXd > camera_extrinsics
Map between camid and camera extrinsics (q_ItoC, p_IinC).
int min_px_dist
Will check after doing KLT track and remove any features closer than this.
UpdaterOptions msckf_options
Update options for MSCKF features (pixel noise and chi2 multiplier)
double sim_freq_cam
Frequency (Hz) that we will simulate our cameras.
double zupt_max_velocity
Max velocity we will consider to try to do a zupt (i.e. if above this, don't do zupt)
double sigma_a
Accelerometer white noise (m/s^2/sqrt(hz))
bool use_stereo
If we should process two cameras are being stereo or binocular. If binocular, we do monocular feature...
std::string sim_traj_path
Path to the trajectory we will b-spline and simulate on. Should be time(s),pos(xyz),...
Struct which stores general updater options.
double dt_slam_delay
Delay, in seconds, that we should wait from init before we start estimating SLAM features.
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_wb
Gyroscope random walk (rad/s^2/sqrt(hz))
#define PRINT_DEBUG(x...)
ov_core::TrackBase::HistogramMethod histogram_method
What type of pre-processing histogram method should be applied to images.
void print_and_load_trackers(const std::shared_ptr< ov_core::YamlParser > &parser=nullptr)
This function will load print out all parameters related to visual tracking This allows for visual ch...
Extended Kalman Filter estimator.
double zupt_max_disparity
Max disparity we will consider to try to do a zupt (i.e. if above this, don't do zupt)
Eigen::Matrix< double, 6, 1 > vec_dw
Gyroscope IMU intrinsics (scale imperfection and axis misalignment, column-wise, inverse)
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 sigma_ab
Accelerometer random walk (m/s^3/sqrt(hz))
bool downsample_cameras
Will half the resolution all tracking image (aruco will be 1/4 instead of halved if dowsize_aruoc als...
int fast_threshold
Fast extraction threshold.
bool sim_do_perturbation
If we should perturb the calibration that the estimator starts with.
void print()
Nice print function of what parameters we have loaded.
#define PRINT_ERROR(x...)
bool use_multi_threading_pubs
If our ROS image publisher should be async (if sim this should be no!)
bool record_timing_information
If we should record the timing performance to file.
void print()
Nice print function of what parameters we have loaded.
double sim_max_feature_gen_distance
Feature distance we generate features from (maximum)
bool use_mask
If we should try to load a mask and use it to reject invalid features.
std::map< size_t, cv::Mat > masks
Mask images for each camera.
int grid_x
Number of grids we should split column-wise to do feature extraction in.
UpdaterOptions slam_options
Update options for SLAM features (pixel noise and chi2 multiplier)
int sim_seed_preturb
Seed for calibration perturbations. Change this to perturb by different random values if perturbation...
int sim_seed_state_init
Seed for initial states (i.e. random feature 3d positions in the generated map)
double sigma_w
Gyroscope white noise (rad/s/sqrt(hz))
bool try_zupt
If we should try to use zero velocity update.
double sim_min_feature_gen_distance
Feature distance we generate features from (minimum)
bool zupt_only_at_beginning
If we should only use the zupt at the very beginning static initialization phase.
void print_and_load(const std::shared_ptr< ov_core::YamlParser > &parser=nullptr)
int grid_y
Number of grids we should split row-wise to do feature extraction in.
double zupt_noise_multiplier
Multiplier of our zupt measurement IMU noise matrix (default should be 1.0)
void print(const std::shared_ptr< ov_core::YamlParser > &parser=nullptr)
Nice print function of what parameters we have loaded.
UpdaterOptions aruco_options
Update options for ARUCO features (pixel noise and chi2 multiplier)
ov_core::FeatureInitializerOptions featinit_options
Parameters used by our feature initialize / triangulator.
bool use_aruco
If should extract aruco tags and estimate them.
bool downsize_aruco
Will half the resolution of the aruco tag image (will be faster)
double calib_camimu_dt
Time offset between camera and IMU.
ov_init::InertialInitializerOptions init_options
Our state initialization options (e.g. window size, num features, if we should get the calibration)
bool use_klt
If we should use KLT tracking, or descriptor matcher.
double sim_distance_threshold
Eigen::Matrix< double, 4, 1 > rot_2_quat(const Eigen::Matrix< double, 3, 3 > &rot)
double gravity_mag
Gravity magnitude in the global frame (i.e. should be 9.81 typically)
Eigen::Matrix< double, 3, 3 > quat_2_Rot(const Eigen::Matrix< double, 4, 1 > &q)
int num_opencv_threads
Threads our front-end should try to use (opencv uses this also)
bool use_multi_threading_subs
If our ROS subscriber callbacks should be async (if sim and serial then this should be no!...
NoiseManager imu_noises
Continuous-time IMU noise (gyroscope and accelerometer)
Eigen::Matrix< double, 4, 1 > q_ACCtoIMU
Rotation from gyroscope frame to the "IMU" accelerometer frame.
int sim_seed_measurements
Struct which stores all our filter options.
Eigen::Matrix< double, 9, 1 > vec_tg
Gyroscope gravity sensitivity (scale imperfection and axis misalignment, column-wise)
ImuModel imu_model
What model our IMU intrinsics are.
Eigen::Matrix< double, 4, 1 > q_GYROtoIMU
Rotation from accelerometer to the "IMU" gyroscope frame frame.
int num_pts
The number of points we should extract and track in each image frame. This highly effects the computa...
void print_and_load_estimator(const std::shared_ptr< ov_core::YamlParser > &parser=nullptr)
This function will load print out all estimator settings loaded. This allows for visual checking that...
StateOptions state_options
Core state options (e.g. number of cameras, use fej, stereo, what calibration to enable etc)
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...
Struct which stores all options needed for state estimation.
double sigma_pix
Noise sigma for our raw pixel measurements.
int num_cameras
Number of distinct cameras that we will observe features in.
double track_frequency
Frequency we want to track images at (higher freq ones will be dropped)
UpdaterOptions zupt_options
Update options for zero velocity (chi2 multiplier)
Eigen::Matrix< double, 6, 1 > vec_da
Accelerometer IMU intrinsics (scale imperfection and axis misalignment, column-wise,...
double knn_ratio
KNN ration between top two descriptor matcher which is required to be a good match.
double sigma_pix_sq
Covariance for our raw pixel measurements.
void print(const std::shared_ptr< ov_core::YamlParser > &parser=nullptr)
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...
Struct of our imu noise parameters.
std::string record_timing_filepath
The path to the file we will record the timing information into.
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...
double sim_freq_imu
Frequency (Hz) that we will simulate our inertial measurement unit.
#define PRINT_WARNING(x...)
double chi2_multipler
What chi-squared multipler we should apply.
ov_msckf
Author(s): Patrick Geneva
, Kevin Eckenhoff , Guoquan Huang
autogenerated on Mon Dec 16 2024 03:06:54