Go to the documentation of this file.
22 #ifndef OV_MSCKF_STATE_OPTIONS_H
23 #define OV_MSCKF_STATE_OPTIONS_H
95 void print(
const std::shared_ptr<ov_core::YamlParser> &parser =
nullptr) {
96 if (parser !=
nullptr) {
97 parser->parse_config(
"use_fej",
do_fej);
100 std::string integration_str =
"rk4";
101 parser->parse_config(
"integration", integration_str);
102 if (integration_str ==
"discrete") {
104 }
else if (integration_str ==
"rk4") {
106 }
else if (integration_str ==
"analytical") {
111 std::exit(EXIT_FAILURE);
131 parser->parse_config(
"feat_rep_msckf", rep1);
134 parser->parse_config(
"feat_rep_slam", rep2);
137 parser->parse_config(
"feat_rep_aruco", rep3);
141 std::string imu_model_str =
"kalibr";
142 parser->parse_external(
"relative_config_imu",
"imu0",
"model", imu_model_str);
143 if (imu_model_str ==
"kalibr" || imu_model_str ==
"calibrated") {
145 }
else if (imu_model_str ==
"rpng") {
150 std::exit(EXIT_FAILURE);
155 std::exit(EXIT_FAILURE);
180 #endif // OV_MSCKF_STATE_OPTIONS_H
ov_type::LandmarkRepresentation::Representation feat_rep_slam
What representation our features are in (slam features)
static Representation from_string(const std::string &feat_representation)
#define PRINT_DEBUG(x...)
ImuModel
IMU intrinsic models.
Extended Kalman Filter estimator.
int max_slam_features
Max number of estimated SLAM features.
int max_clone_size
Max clone size of sliding window.
#define PRINT_ERROR(x...)
ov_type::LandmarkRepresentation::Representation feat_rep_msckf
What representation our features are in (msckf features)
bool do_calib_camera_pose
Bool to determine whether or not to calibrate imu-to-camera pose.
bool do_calib_imu_intrinsics
Bool to determine whether or not to calibrate the IMU intrinsics.
bool do_calib_camera_timeoffset
Bool to determine whether or not to calibrate camera to IMU time offset.
int max_slam_in_update
Max number of SLAM features we allow to be included in a single EKF update.
int max_aruco_features
Max number of estimated ARUCO features.
void print(const std::shared_ptr< ov_core::YamlParser > &parser=nullptr)
Nice print function of what parameters we have loaded.
IntegrationMethod
Numerical integration methods.
Struct which stores all our filter options.
ImuModel imu_model
What model our IMU intrinsics are.
ov_type::LandmarkRepresentation::Representation feat_rep_aruco
What representation our features are in (aruco tag features)
IntegrationMethod integration_method
What type of numerical integration is used during propagation.
bool do_calib_camera_intrinsics
Bool to determine whether or not to calibrate camera intrinsics.
int num_cameras
Number of distinct cameras that we will observe features in.
bool do_calib_imu_g_sensitivity
Bool to determine whether or not to calibrate the Gravity sensitivity.
bool do_fej
Bool to determine whether or not to do first estimate Jacobians.
int max_msckf_in_update
Max number of MSCKF features we will use at a given image timestep.
static std::string as_string(Representation feat_representation)
ov_msckf
Author(s): Patrick Geneva
, Kevin Eckenhoff , Guoquan Huang
autogenerated on Mon Dec 16 2024 03:06:54