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

Struct which stores all our filter options. More...

#include <StateOptions.h>

Public Types

enum  ImuModel { KALIBR, RPNG }
 IMU intrinsic models. More...
 
enum  IntegrationMethod { DISCRETE, RK4, ANALYTICAL }
 Numerical integration methods. More...
 

Public Member Functions

void print (const std::shared_ptr< ov_core::YamlParser > &parser=nullptr)
 Nice print function of what parameters we have loaded. More...
 

Public Attributes

bool do_calib_camera_intrinsics = false
 Bool to determine whether or not to calibrate camera intrinsics. More...
 
bool do_calib_camera_pose = false
 Bool to determine whether or not to calibrate imu-to-camera pose. More...
 
bool do_calib_camera_timeoffset = false
 Bool to determine whether or not to calibrate camera to IMU time offset. More...
 
bool do_calib_imu_g_sensitivity = false
 Bool to determine whether or not to calibrate the Gravity sensitivity. More...
 
bool do_calib_imu_intrinsics = false
 Bool to determine whether or not to calibrate the IMU intrinsics. More...
 
bool do_fej = true
 Bool to determine whether or not to do first estimate Jacobians. More...
 
ov_type::LandmarkRepresentation::Representation feat_rep_aruco = ov_type::LandmarkRepresentation::Representation::GLOBAL_3D
 What representation our features are in (aruco tag features) More...
 
ov_type::LandmarkRepresentation::Representation feat_rep_msckf = ov_type::LandmarkRepresentation::Representation::GLOBAL_3D
 What representation our features are in (msckf features) More...
 
ov_type::LandmarkRepresentation::Representation feat_rep_slam = ov_type::LandmarkRepresentation::Representation::GLOBAL_3D
 What representation our features are in (slam features) More...
 
ImuModel imu_model = ImuModel::KALIBR
 What model our IMU intrinsics are. More...
 
IntegrationMethod integration_method = IntegrationMethod::RK4
 What type of numerical integration is used during propagation. More...
 
int max_aruco_features = 1024
 Max number of estimated ARUCO features. More...
 
int max_clone_size = 11
 Max clone size of sliding window. More...
 
int max_msckf_in_update = 1000
 Max number of MSCKF features we will use at a given image timestep. More...
 
int max_slam_features = 25
 Max number of estimated SLAM features. More...
 
int max_slam_in_update = 1000
 Max number of SLAM features we allow to be included in a single EKF update. More...
 
int num_cameras = 1
 Number of distinct cameras that we will observe features in. More...
 

Detailed Description

Struct which stores all our filter options.

Definition at line 35 of file StateOptions.h.

Member Enumeration Documentation

◆ ImuModel

IMU intrinsic models.

Enumerator
KALIBR 
RPNG 

Definition at line 62 of file StateOptions.h.

◆ IntegrationMethod

Numerical integration methods.

Enumerator
DISCRETE 
RK4 
ANALYTICAL 

Definition at line 41 of file StateOptions.h.

Member Function Documentation

◆ print()

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

Nice print function of what parameters we have loaded.

Definition at line 95 of file StateOptions.h.

Member Data Documentation

◆ do_calib_camera_intrinsics

bool ov_msckf::StateOptions::do_calib_camera_intrinsics = false

Bool to determine whether or not to calibrate camera intrinsics.

Definition at line 50 of file StateOptions.h.

◆ do_calib_camera_pose

bool ov_msckf::StateOptions::do_calib_camera_pose = false

Bool to determine whether or not to calibrate imu-to-camera pose.

Definition at line 47 of file StateOptions.h.

◆ do_calib_camera_timeoffset

bool ov_msckf::StateOptions::do_calib_camera_timeoffset = false

Bool to determine whether or not to calibrate camera to IMU time offset.

Definition at line 53 of file StateOptions.h.

◆ do_calib_imu_g_sensitivity

bool ov_msckf::StateOptions::do_calib_imu_g_sensitivity = false

Bool to determine whether or not to calibrate the Gravity sensitivity.

Definition at line 59 of file StateOptions.h.

◆ do_calib_imu_intrinsics

bool ov_msckf::StateOptions::do_calib_imu_intrinsics = false

Bool to determine whether or not to calibrate the IMU intrinsics.

Definition at line 56 of file StateOptions.h.

◆ do_fej

bool ov_msckf::StateOptions::do_fej = true

Bool to determine whether or not to do first estimate Jacobians.

Definition at line 38 of file StateOptions.h.

◆ feat_rep_aruco

ov_type::LandmarkRepresentation::Representation ov_msckf::StateOptions::feat_rep_aruco = ov_type::LandmarkRepresentation::Representation::GLOBAL_3D

What representation our features are in (aruco tag features)

Definition at line 92 of file StateOptions.h.

◆ feat_rep_msckf

ov_type::LandmarkRepresentation::Representation ov_msckf::StateOptions::feat_rep_msckf = ov_type::LandmarkRepresentation::Representation::GLOBAL_3D

What representation our features are in (msckf features)

Definition at line 86 of file StateOptions.h.

◆ feat_rep_slam

ov_type::LandmarkRepresentation::Representation ov_msckf::StateOptions::feat_rep_slam = ov_type::LandmarkRepresentation::Representation::GLOBAL_3D

What representation our features are in (slam features)

Definition at line 89 of file StateOptions.h.

◆ imu_model

ImuModel ov_msckf::StateOptions::imu_model = ImuModel::KALIBR

What model our IMU intrinsics are.

Definition at line 65 of file StateOptions.h.

◆ integration_method

IntegrationMethod ov_msckf::StateOptions::integration_method = IntegrationMethod::RK4

What type of numerical integration is used during propagation.

Definition at line 44 of file StateOptions.h.

◆ max_aruco_features

int ov_msckf::StateOptions::max_aruco_features = 1024

Max number of estimated ARUCO features.

Definition at line 80 of file StateOptions.h.

◆ max_clone_size

int ov_msckf::StateOptions::max_clone_size = 11

Max clone size of sliding window.

Definition at line 68 of file StateOptions.h.

◆ max_msckf_in_update

int ov_msckf::StateOptions::max_msckf_in_update = 1000

Max number of MSCKF features we will use at a given image timestep.

Definition at line 77 of file StateOptions.h.

◆ max_slam_features

int ov_msckf::StateOptions::max_slam_features = 25

Max number of estimated SLAM features.

Definition at line 71 of file StateOptions.h.

◆ max_slam_in_update

int ov_msckf::StateOptions::max_slam_in_update = 1000

Max number of SLAM features we allow to be included in a single EKF update.

Definition at line 74 of file StateOptions.h.

◆ num_cameras

int ov_msckf::StateOptions::num_cameras = 1

Number of distinct cameras that we will observe features in.

Definition at line 83 of file StateOptions.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