ov_init::InertialInitializerOptions 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_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.
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.

Public variables

double init_window_time
Amount of time we will initialize over (seconds)
double init_imu_thresh
Variance threshold on our acceleration to be classified as moving.
double init_max_disparity
Max disparity we will consider the unit to be stationary.
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 num_cameras
Number of distinct cameras that we will observe features in.

Function documentation

void ov_init::InertialInitializerOptions::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_init::InertialInitializerOptions::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.

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

void ov_init::InertialInitializerOptions::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