ov_msckf::VioManagerOptions struct

Struct which stores all options needed for state estimation.

Contents

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.

Public 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.
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.
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.
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.
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.
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.

Public variables

StateOptions state_options
Core state options (e.g. number of cameras, use fej, stereo, what calibration to enable etc)
ov_init::InertialInitializerOptions init_options
Our state initialization options (e.g. window size, num features, if we should get the calibration)
double dt_slam_delay
Delay, in seconds, that we should wait from init before we start estimating SLAM features.
bool try_zupt
If we should try to use zero velocity update.
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 zupt_noise_multiplier
Multiplier of our zupt measurement IMU noise matrix (default should be 1.0)
double zupt_max_disparity
Max disparity we will consider to try to do a zupt (i.e. if above this, don't do zupt)
bool zupt_only_at_beginning
If we should only use the zupt at the very beginning static initialization phase.
bool record_timing_information
If we should record the timing performance to file.
std::string record_timing_filepath
The path to the file we will record the timing information into.
NoiseManager imu_noises
Continuous-time IMU noise (gyroscope and accelerometer)
UpdaterOptions msckf_options
Update options for MSCKF features (pixel noise and chi2 multiplier)
UpdaterOptions slam_options
Update options for SLAM features (pixel noise and chi2 multiplier)
UpdaterOptions aruco_options
Update options for ARUCO features (pixel noise and chi2 multiplier)
UpdaterOptions zupt_options
Update options for zero velocity (chi2 multiplier)
double gravity_mag
Gravity magnitude in the global frame (i.e. should be 9.81 typically)
Eigen::Matrix<double, 6, 1> vec_dw
Gyroscope IMU intrinsics (scale imperfection and axis misalignment, column-wise, inverse)
Eigen::Matrix<double, 6, 1> vec_da
Accelerometer IMU intrinsics (scale imperfection and axis misalignment, column-wise, inverse)
Eigen::Matrix<double, 9, 1> vec_tg
Gyroscope gravity sensitivity (scale imperfection and axis misalignment, column-wise)
Eigen::Matrix<double, 4, 1> q_ACCtoIMU
Rotation from gyroscope frame to the "IMU" accelerometer frame.
Eigen::Matrix<double, 4, 1> q_GYROtoIMU
Rotation from accelerometer to the "IMU" gyroscope frame frame.
double calib_camimu_dt
Time offset between camera and IMU.
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)
std::map<size_t, Eigen::VectorXd> camera_extrinsics
Map between camid and camera extrinsics (q_ItoC, p_IinC).
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.
bool use_stereo
If we should process two cameras are being stereo or binocular. If binocular, we do monocular feature tracking on each image.
bool use_klt
If we should use KLT tracking, or descriptor matcher.
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)
bool downsample_cameras
Will half the resolution all tracking image (aruco will be 1/4 instead of halved if dowsize_aruoc also enabled)
int num_opencv_threads
Threads our front-end should try to use (opencv uses this also)
bool use_multi_threading_pubs
If our ROS image publisher should be async (if sim this should be no!)
bool use_multi_threading_subs
If our ROS subscriber callbacks should be async (if sim and serial then this should be no!)
int num_pts
The number of points we should extract and track in each image frame. This highly effects the computation required for tracking.
int fast_threshold
Fast extraction threshold.
int grid_x
Number of grids we should split column-wise to do feature extraction in.
int grid_y
Number of grids we should split row-wise to do feature extraction in.
int min_px_dist
Will check after doing KLT track and remove any features closer than this.
ov_core::TrackBase::HistogramMethod histogram_method
What type of pre-processing histogram method should be applied to images.
double knn_ratio
KNN ration between top two descriptor matcher which is required to be a good match.
double track_frequency
Frequency we want to track images at (higher freq ones will be dropped)
ov_core::FeatureInitializerOptions featinit_options
Parameters used by our feature initialize / triangulator.
int sim_seed_state_init
Seed for initial states (i.e. random feature 3d positions in the generated map)
int sim_seed_preturb
Seed for calibration perturbations. Change this to perturb by different random values if perturbations are enabled.
int sim_seed_measurements
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),ori(xyzw) format.
double sim_distance_threshold
double sim_freq_cam
Frequency (Hz) that we will simulate our cameras.
double sim_freq_imu
Frequency (Hz) that we will simulate our inertial measurement unit.
double sim_min_feature_gen_distance
Feature distance we generate features from (minimum)
double sim_max_feature_gen_distance
Feature distance we generate features from (maximum)

Function documentation

void ov_msckf::VioManagerOptions::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.

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

void ov_msckf::VioManagerOptions::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.

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

void ov_msckf::VioManagerOptions::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.

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

void ov_msckf::VioManagerOptions::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.

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

void ov_msckf::VioManagerOptions::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.

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

void ov_msckf::VioManagerOptions::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.

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

Variable documentation

int ov_msckf::VioManagerOptions::sim_seed_measurements

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.

double ov_msckf::VioManagerOptions::sim_distance_threshold

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.