Public Member Functions | Public Attributes | List of all members
ov_msckf::VioManagerOptions Struct Reference

Struct which stores all options needed for state estimation. More...

#include <VioManagerOptions.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_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 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...
 
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 checking that everything was loaded properly from ROS/CMD parsers. More...
 

Public Attributes

UpdaterOptions aruco_options
 Update options for ARUCO features (pixel noise and chi2 multiplier) More...
 
double calib_camimu_dt = 0.0
 Time offset between camera and IMU. 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...
 
bool downsize_aruco = true
 Will half the resolution of the aruco tag image (will be faster) More...
 
double dt_slam_delay = 2.0
 Delay, in seconds, that we should wait from init before we start estimating SLAM features. More...
 
int fast_threshold = 20
 Fast extraction threshold. More...
 
ov_core::FeatureInitializerOptions featinit_options
 Parameters used by our feature initialize / triangulator. More...
 
double gravity_mag = 9.81
 Gravity magnitude in the global frame (i.e. should be 9.81 typically) More...
 
int grid_x = 5
 Number of grids we should split column-wise to do feature extraction in. More...
 
int grid_y = 5
 Number of grids we should split row-wise to do feature extraction in. More...
 
ov_core::TrackBase::HistogramMethod histogram_method = ov_core::TrackBase::HistogramMethod::HISTOGRAM
 What type of pre-processing histogram method should be applied to images. More...
 
NoiseManager imu_noises
 Continuous-time IMU noise (gyroscope and accelerometer) More...
 
ov_init::InertialInitializerOptions init_options
 Our state initialization options (e.g. window size, num features, if we should get the calibration) More...
 
double knn_ratio = 0.85
 KNN ration between top two descriptor matcher which is required to be a good match. More...
 
std::map< size_t, cv::Mat > masks
 Mask images for each camera. More...
 
int min_px_dist = 10
 Will check after doing KLT track and remove any features closer than this. More...
 
UpdaterOptions msckf_options
 Update options for MSCKF features (pixel noise and chi2 multiplier) More...
 
int num_opencv_threads = 4
 Threads our front-end should try to use (opencv uses this also) More...
 
int num_pts = 150
 The number of points we should extract and track in each image frame. This highly effects the computation required for tracking. More...
 
Eigen::Matrix< double, 4, 1 > q_ACCtoIMU
 Rotation from gyroscope frame to the "IMU" accelerometer frame. More...
 
Eigen::Matrix< double, 4, 1 > q_GYROtoIMU
 Rotation from accelerometer to the "IMU" gyroscope frame frame. More...
 
std::string record_timing_filepath = "ov_msckf_timing.txt"
 The path to the file we will record the timing information into. More...
 
bool record_timing_information = false
 If we should record the timing performance to file. 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 = "src/open_vins/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...
 
UpdaterOptions slam_options
 Update options for SLAM features (pixel noise and chi2 multiplier) More...
 
StateOptions state_options
 Core state options (e.g. number of cameras, use fej, stereo, what calibration to enable etc) More...
 
double track_frequency = 20.0
 Frequency we want to track images at (higher freq ones will be dropped) More...
 
bool try_zupt = false
 If we should try to use zero velocity update. More...
 
bool use_aruco = true
 If should extract aruco tags and estimate them. More...
 
bool use_klt = true
 If we should use KLT tracking, or descriptor matcher. More...
 
bool use_mask = false
 If we should try to load a mask and use it to reject invalid features. More...
 
bool use_multi_threading_pubs = true
 If our ROS image publisher should be async (if sim this should be no!) More...
 
bool use_multi_threading_subs = false
 If our ROS subscriber callbacks should be async (if sim and serial then this should be no!) 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...
 
Eigen::Matrix< double, 6, 1 > vec_da
 Accelerometer IMU intrinsics (scale imperfection and axis misalignment, column-wise, inverse) More...
 
Eigen::Matrix< double, 6, 1 > vec_dw
 Gyroscope IMU intrinsics (scale imperfection and axis misalignment, column-wise, inverse) More...
 
Eigen::Matrix< double, 9, 1 > vec_tg
 Gyroscope gravity sensitivity (scale imperfection and axis misalignment, column-wise) More...
 
double zupt_max_disparity = 1.0
 Max disparity we will consider to try to do a zupt (i.e. if above this, don't do zupt) More...
 
double zupt_max_velocity = 1.0
 Max velocity we will consider to try to do a zupt (i.e. if above this, don't do zupt) More...
 
double zupt_noise_multiplier = 1.0
 Multiplier of our zupt measurement IMU noise matrix (default should be 1.0) More...
 
bool zupt_only_at_beginning = false
 If we should only use the zupt at the very beginning static initialization phase. More...
 
UpdaterOptions zupt_options
 Update options for zero velocity (chi2 multiplier) More...
 

Detailed Description

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 56 of file VioManagerOptions.h.

Member Function Documentation

◆ print_and_load()

void ov_msckf::VioManagerOptions::print_and_load ( const std::shared_ptr< ov_core::YamlParser > &  parser = nullptr)
inline

This function will load the non-simulation parameters of the system and print.

Parameters
parserIf not null, this parser will be used to load our parameters

Definition at line 62 of file VioManagerOptions.h.

◆ print_and_load_estimator()

void ov_msckf::VioManagerOptions::print_and_load_estimator ( const std::shared_ptr< ov_core::YamlParser > &  parser = nullptr)
inline

This function will load print out all estimator settings loaded. This allows for visual checking that everything was loaded properly from ROS/CMD parsers.

Parameters
parserIf not null, this parser will be used to load our parameters

Definition at line 109 of file VioManagerOptions.h.

◆ print_and_load_noise()

void ov_msckf::VioManagerOptions::print_and_load_noise ( const std::shared_ptr< ov_core::YamlParser > &  parser = nullptr)
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.

Parameters
parserIf not null, this parser will be used to load our parameters

Definition at line 156 of file VioManagerOptions.h.

◆ print_and_load_simulation()

void ov_msckf::VioManagerOptions::print_and_load_simulation ( const std::shared_ptr< ov_core::YamlParser > &  parser = nullptr)
inline

This function will load print out all simulated parameters. This allows for visual checking that everything was loaded properly from ROS/CMD parsers.

Parameters
parserIf not null, this parser will be used to load our parameters

Definition at line 545 of file VioManagerOptions.h.

◆ print_and_load_state()

void ov_msckf::VioManagerOptions::print_and_load_state ( const std::shared_ptr< ov_core::YamlParser > &  parser = nullptr)
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.

Parameters
parserIf not null, this parser will be used to load our parameters

Definition at line 228 of file VioManagerOptions.h.

◆ print_and_load_trackers()

void ov_msckf::VioManagerOptions::print_and_load_trackers ( const std::shared_ptr< ov_core::YamlParser > &  parser = nullptr)
inline

This function will load print out all parameters related to visual tracking This allows for visual checking that everything was loaded properly from ROS/CMD parsers.

Parameters
parserIf not null, this parser will be used to load our parameters

Definition at line 453 of file VioManagerOptions.h.

Member Data Documentation

◆ aruco_options

UpdaterOptions ov_msckf::VioManagerOptions::aruco_options

Update options for ARUCO features (pixel noise and chi2 multiplier)

Definition at line 145 of file VioManagerOptions.h.

◆ calib_camimu_dt

double ov_msckf::VioManagerOptions::calib_camimu_dt = 0.0

Time offset between camera and IMU.

Definition at line 208 of file VioManagerOptions.h.

◆ camera_extrinsics

std::map<size_t, Eigen::VectorXd> ov_msckf::VioManagerOptions::camera_extrinsics

Map between camid and camera extrinsics (q_ItoC, p_IinC).

Definition at line 214 of file VioManagerOptions.h.

◆ camera_intrinsics

std::unordered_map<size_t, std::shared_ptr<ov_core::CamBase> > ov_msckf::VioManagerOptions::camera_intrinsics

Map between camid and camera intrinsics (fx, fy, cx, cy, d1...d4, cam_w, cam_h)

Definition at line 211 of file VioManagerOptions.h.

◆ downsample_cameras

bool ov_msckf::VioManagerOptions::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 409 of file VioManagerOptions.h.

◆ downsize_aruco

bool ov_msckf::VioManagerOptions::downsize_aruco = true

Will half the resolution of the aruco tag image (will be faster)

Definition at line 406 of file VioManagerOptions.h.

◆ dt_slam_delay

double ov_msckf::VioManagerOptions::dt_slam_delay = 2.0

Delay, in seconds, that we should wait from init before we start estimating SLAM features.

Definition at line 80 of file VioManagerOptions.h.

◆ fast_threshold

int ov_msckf::VioManagerOptions::fast_threshold = 20

Fast extraction threshold.

Definition at line 424 of file VioManagerOptions.h.

◆ featinit_options

ov_core::FeatureInitializerOptions ov_msckf::VioManagerOptions::featinit_options

Parameters used by our feature initialize / triangulator.

Definition at line 445 of file VioManagerOptions.h.

◆ gravity_mag

double ov_msckf::VioManagerOptions::gravity_mag = 9.81

Gravity magnitude in the global frame (i.e. should be 9.81 typically)

Definition at line 190 of file VioManagerOptions.h.

◆ grid_x

int ov_msckf::VioManagerOptions::grid_x = 5

Number of grids we should split column-wise to do feature extraction in.

Definition at line 427 of file VioManagerOptions.h.

◆ grid_y

int ov_msckf::VioManagerOptions::grid_y = 5

Number of grids we should split row-wise to do feature extraction in.

Definition at line 430 of file VioManagerOptions.h.

◆ histogram_method

ov_core::TrackBase::HistogramMethod ov_msckf::VioManagerOptions::histogram_method = ov_core::TrackBase::HistogramMethod::HISTOGRAM

What type of pre-processing histogram method should be applied to images.

Definition at line 436 of file VioManagerOptions.h.

◆ imu_noises

NoiseManager ov_msckf::VioManagerOptions::imu_noises

Continuous-time IMU noise (gyroscope and accelerometer)

Definition at line 136 of file VioManagerOptions.h.

◆ init_options

ov_init::InertialInitializerOptions ov_msckf::VioManagerOptions::init_options

Our state initialization options (e.g. window size, num features, if we should get the calibration)

Definition at line 77 of file VioManagerOptions.h.

◆ knn_ratio

double ov_msckf::VioManagerOptions::knn_ratio = 0.85

KNN ration between top two descriptor matcher which is required to be a good match.

Definition at line 439 of file VioManagerOptions.h.

◆ masks

std::map<size_t, cv::Mat> ov_msckf::VioManagerOptions::masks

Mask images for each camera.

Definition at line 220 of file VioManagerOptions.h.

◆ min_px_dist

int ov_msckf::VioManagerOptions::min_px_dist = 10

Will check after doing KLT track and remove any features closer than this.

Definition at line 433 of file VioManagerOptions.h.

◆ msckf_options

UpdaterOptions ov_msckf::VioManagerOptions::msckf_options

Update options for MSCKF features (pixel noise and chi2 multiplier)

Definition at line 139 of file VioManagerOptions.h.

◆ num_opencv_threads

int ov_msckf::VioManagerOptions::num_opencv_threads = 4

Threads our front-end should try to use (opencv uses this also)

Definition at line 412 of file VioManagerOptions.h.

◆ num_pts

int ov_msckf::VioManagerOptions::num_pts = 150

The number of points we should extract and track in each image frame. This highly effects the computation required for tracking.

Definition at line 421 of file VioManagerOptions.h.

◆ q_ACCtoIMU

Eigen::Matrix<double, 4, 1> ov_msckf::VioManagerOptions::q_ACCtoIMU

Rotation from gyroscope frame to the "IMU" accelerometer frame.

Definition at line 202 of file VioManagerOptions.h.

◆ q_GYROtoIMU

Eigen::Matrix<double, 4, 1> ov_msckf::VioManagerOptions::q_GYROtoIMU

Rotation from accelerometer to the "IMU" gyroscope frame frame.

Definition at line 205 of file VioManagerOptions.h.

◆ record_timing_filepath

std::string ov_msckf::VioManagerOptions::record_timing_filepath = "ov_msckf_timing.txt"

The path to the file we will record the timing information into.

Definition at line 101 of file VioManagerOptions.h.

◆ record_timing_information

bool ov_msckf::VioManagerOptions::record_timing_information = false

If we should record the timing performance to file.

Definition at line 98 of file VioManagerOptions.h.

◆ sim_distance_threshold

double ov_msckf::VioManagerOptions::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 525 of file VioManagerOptions.h.

◆ sim_do_perturbation

bool ov_msckf::VioManagerOptions::sim_do_perturbation = false

If we should perturb the calibration that the estimator starts with.

Definition at line 518 of file VioManagerOptions.h.

◆ sim_freq_cam

double ov_msckf::VioManagerOptions::sim_freq_cam = 10.0

Frequency (Hz) that we will simulate our cameras.

Definition at line 528 of file VioManagerOptions.h.

◆ sim_freq_imu

double ov_msckf::VioManagerOptions::sim_freq_imu = 400.0

Frequency (Hz) that we will simulate our inertial measurement unit.

Definition at line 531 of file VioManagerOptions.h.

◆ sim_max_feature_gen_distance

double ov_msckf::VioManagerOptions::sim_max_feature_gen_distance = 10

Feature distance we generate features from (maximum)

Definition at line 537 of file VioManagerOptions.h.

◆ sim_min_feature_gen_distance

double ov_msckf::VioManagerOptions::sim_min_feature_gen_distance = 5

Feature distance we generate features from (minimum)

Definition at line 534 of file VioManagerOptions.h.

◆ sim_seed_measurements

int ov_msckf::VioManagerOptions::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 515 of file VioManagerOptions.h.

◆ sim_seed_preturb

int ov_msckf::VioManagerOptions::sim_seed_preturb = 0

Seed for calibration perturbations. Change this to perturb by different random values if perturbations are enabled.

Definition at line 511 of file VioManagerOptions.h.

◆ sim_seed_state_init

int ov_msckf::VioManagerOptions::sim_seed_state_init = 0

Seed for initial states (i.e. random feature 3d positions in the generated map)

Definition at line 508 of file VioManagerOptions.h.

◆ sim_traj_path

std::string ov_msckf::VioManagerOptions::sim_traj_path = "src/open_vins/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 521 of file VioManagerOptions.h.

◆ slam_options

UpdaterOptions ov_msckf::VioManagerOptions::slam_options

Update options for SLAM features (pixel noise and chi2 multiplier)

Definition at line 142 of file VioManagerOptions.h.

◆ state_options

StateOptions ov_msckf::VioManagerOptions::state_options

Core state options (e.g. number of cameras, use fej, stereo, what calibration to enable etc)

Definition at line 74 of file VioManagerOptions.h.

◆ track_frequency

double ov_msckf::VioManagerOptions::track_frequency = 20.0

Frequency we want to track images at (higher freq ones will be dropped)

Definition at line 442 of file VioManagerOptions.h.

◆ try_zupt

bool ov_msckf::VioManagerOptions::try_zupt = false

If we should try to use zero velocity update.

Definition at line 83 of file VioManagerOptions.h.

◆ use_aruco

bool ov_msckf::VioManagerOptions::use_aruco = true

If should extract aruco tags and estimate them.

Definition at line 403 of file VioManagerOptions.h.

◆ use_klt

bool ov_msckf::VioManagerOptions::use_klt = true

If we should use KLT tracking, or descriptor matcher.

Definition at line 400 of file VioManagerOptions.h.

◆ use_mask

bool ov_msckf::VioManagerOptions::use_mask = false

If we should try to load a mask and use it to reject invalid features.

Definition at line 217 of file VioManagerOptions.h.

◆ use_multi_threading_pubs

bool ov_msckf::VioManagerOptions::use_multi_threading_pubs = true

If our ROS image publisher should be async (if sim this should be no!)

Definition at line 415 of file VioManagerOptions.h.

◆ use_multi_threading_subs

bool ov_msckf::VioManagerOptions::use_multi_threading_subs = false

If our ROS subscriber callbacks should be async (if sim and serial then this should be no!)

Definition at line 418 of file VioManagerOptions.h.

◆ use_stereo

bool ov_msckf::VioManagerOptions::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 397 of file VioManagerOptions.h.

◆ vec_da

Eigen::Matrix<double, 6, 1> ov_msckf::VioManagerOptions::vec_da

Accelerometer IMU intrinsics (scale imperfection and axis misalignment, column-wise, inverse)

Definition at line 196 of file VioManagerOptions.h.

◆ vec_dw

Eigen::Matrix<double, 6, 1> ov_msckf::VioManagerOptions::vec_dw

Gyroscope IMU intrinsics (scale imperfection and axis misalignment, column-wise, inverse)

Definition at line 193 of file VioManagerOptions.h.

◆ vec_tg

Eigen::Matrix<double, 9, 1> ov_msckf::VioManagerOptions::vec_tg

Gyroscope gravity sensitivity (scale imperfection and axis misalignment, column-wise)

Definition at line 199 of file VioManagerOptions.h.

◆ zupt_max_disparity

double ov_msckf::VioManagerOptions::zupt_max_disparity = 1.0

Max disparity we will consider to try to do a zupt (i.e. if above this, don't do zupt)

Definition at line 92 of file VioManagerOptions.h.

◆ zupt_max_velocity

double ov_msckf::VioManagerOptions::zupt_max_velocity = 1.0

Max velocity we will consider to try to do a zupt (i.e. if above this, don't do zupt)

Definition at line 86 of file VioManagerOptions.h.

◆ zupt_noise_multiplier

double ov_msckf::VioManagerOptions::zupt_noise_multiplier = 1.0

Multiplier of our zupt measurement IMU noise matrix (default should be 1.0)

Definition at line 89 of file VioManagerOptions.h.

◆ zupt_only_at_beginning

bool ov_msckf::VioManagerOptions::zupt_only_at_beginning = false

If we should only use the zupt at the very beginning static initialization phase.

Definition at line 95 of file VioManagerOptions.h.

◆ zupt_options

UpdaterOptions ov_msckf::VioManagerOptions::zupt_options

Update options for zero velocity (chi2 multiplier)

Definition at line 148 of file VioManagerOptions.h.


The documentation for this struct was generated from the following file:


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