struct
InertialInitializerOptionsStruct which stores all options needed for state estimation.
Contents
- Reference
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_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_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
- 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.
- bool init_dyn_use
- If we should perform dynamic initialization.
- bool init_dyn_mle_opt_calib
- If we should optimize and recover the calibration in our MLE.
- int init_dyn_mle_max_iter
- Max number of MLE iterations for dynamic initialization.
- int init_dyn_mle_max_threads
- Max number of MLE threads for dynamic initialization.
- double init_dyn_mle_max_time
- Max time for MLE optimization (seconds)
- int init_dyn_num_pose
- Number of poses to use during initialization (max should be cam freq * window)
- double init_dyn_min_deg
- Minimum degrees we need to rotate before we try to init (sum of norm)
- double init_dyn_inflation_orientation
- Magnitude we will inflate initial covariance of orientation.
- double init_dyn_inflation_velocity
- Magnitude we will inflate initial covariance of velocity.
- double init_dyn_inflation_bias_gyro
- Magnitude we will inflate initial covariance of gyroscope bias.
- double init_dyn_inflation_bias_accel
- Magnitude we will inflate initial covariance of accelerometer bias.
- double init_dyn_min_rec_cond
- Eigen::Vector3d init_dyn_bias_g
- Initial IMU gyroscope bias values for dynamic initialization (will be optimized)
- Eigen::Vector3d init_dyn_bias_a
- Initial IMU accelerometer bias values for dynamic initialization (will be optimized)
- double sigma_w
- Gyroscope white noise (rad/s/sqrt(hz))
- double sigma_wb
- Gyroscope random walk (rad/s^2/sqrt(hz))
- double sigma_a
- Accelerometer white noise (m/s^2/sqrt(hz))
- double sigma_ab
- Accelerometer random walk (m/s^3/sqrt(hz))
- double sigma_pix
- Noise sigma for our raw pixel measurements.
- 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.
- 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 downsample_cameras
- Will half the resolution all tracking image (aruco will be 1/4 instead of halved if dowsize_aruoc also enabled)
- double calib_camimu_dt
- Time offset between camera and IMU (t_imu = t_cam + t_off)
-
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).
- 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_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_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_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 |
void ov_init:: InertialInitializerOptions:: 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
double ov_init:: InertialInitializerOptions:: init_dyn_min_rec_cond
Minimum reciprocal condition number acceptable for our covariance recovery (min_sigma / max_sigma < sqrt(min_reciprocal_condition_number))
int ov_init:: InertialInitializerOptions:: 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_init:: InertialInitializerOptions:: 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.