MSCEqF 1.0
Multi State Constraint Equivariant Filter for visual inertial navigation
Loading...
Searching...
No Matches
msceqf_options.hpp
1// Copyright (C) 2023 Alessandro Fornasier.
2// Control of Networked Systems, University of Klagenfurt, Austria.
3//
4// All rights reserved.
5//
6// This software is licensed under the terms of the BSD-2-Clause-License with
7// no commercial use allowed, the full terms of which are made available
8// in the LICENSE file. No license in patents is granted.
9//
10// You can contact the authors at <alessandro.fornasier@ieee.org>
11
12#ifndef OPTIONS_HPP
13#define OPTIONS_HPP
14
15#include <opencv2/opencv.hpp>
16
17#include "types/fptypes.hpp"
18
19namespace msceqf
20{
25enum class FeatureRepresentation
26{
27 ANCHORED_EUCLIDEAN,
28 ANCHORED_POLAR,
29 ANCHORED_INVERSE_DEPTH,
30};
31
36enum class ProjectionMethod
37{
38 UNIT_SPHERE,
39 UNIT_PLANE,
40};
41
46enum class DistortionModel
47{
48 RADTAN,
49 EQUIDISTANT,
50};
51
56enum class EqualizationMethod
57{
58 HISTOGRAM,
59 CLAHE,
60 NONE,
61};
62
67enum class FeatureDetector
68{
69 FAST,
70 GFTT,
71};
72
77enum class ZeroVelocityUpdate
78{
79 DISABLE,
80 ENABLE,
81 BEGINNING,
82};
83
89enum class MaskType
90{
91 STATIC,
92 DYNAMIC,
93};
94
110
120
135
141
153
159
168
170{
172};
173
175{
177};
178
198
204
215
216} // namespace msceqf
217
218#endif // OPTIONS_HPP
Definition msceqf_options.hpp:161
fp timeshift_cam_imu_
The time shift between camera and imu (t_imu = t_cam + shift)
Definition msceqf_options.hpp:164
cv::Mat static_mask_
The static image mask.
Definition msceqf_options.hpp:165
VectorX distortion_coefficients_
Distortion coefficients.
Definition msceqf_options.hpp:162
Vector2 resolution_
Width, Height.
Definition msceqf_options.hpp:163
MaskType mask_type_
The mask type.
Definition msceqf_options.hpp:166
Definition msceqf_options.hpp:155
fp disparity_window_
The window is seconds used to check disparity.
Definition msceqf_options.hpp:157
fp disparity_threshold_
the disparity threshold for the disparity check
Definition msceqf_options.hpp:156
Definition msceqf_options.hpp:170
int fast_threshold_
Fast detector threshold (The lower the more feature are detected/accepted)
Definition msceqf_options.hpp:171
Definition msceqf_options.hpp:175
fp quality_level_
Shi-Tomasi detector quality level (The lower the more feature are detected/accepted)
Definition msceqf_options.hpp:176
Definition msceqf_options.hpp:143
fp imu_init_window_
The window in seconds used to check for acceleration spikes.
Definition msceqf_options.hpp:145
SE23 initial_extended_pose_
Initial extended pose.
Definition msceqf_options.hpp:149
bool identity_b0_
Boolean to fix identity bias origin (b0)git.
Definition msceqf_options.hpp:147
fp acc_threshold_
The acceleration threshold for the static initializer.
Definition msceqf_options.hpp:144
fp initial_timestamp_
Initial timestamp.
Definition msceqf_options.hpp:151
bool init_with_given_state_
Boolean to initialize the state with the given state.
Definition msceqf_options.hpp:148
Vector6 initial_bias_
Initial bias.
Definition msceqf_options.hpp:150
fp gravity_
The magnitude of the gravity vector in m/s^2.
Definition msceqf_options.hpp:146
Definition msceqf_options.hpp:206
TrackManagerOptions track_manager_options_
The track manager options.
Definition msceqf_options.hpp:207
StateOptions state_options_
The state options.
Definition msceqf_options.hpp:208
InitializerOptions init_options_
The initializer options.
Definition msceqf_options.hpp:210
ZeroVelocityUpdaterOptions zvupdater_options_
The zero velocity updater options.
Definition msceqf_options.hpp:213
UpdaterOptions updater_options_
The updater options.
Definition msceqf_options.hpp:212
PropagatorOptions propagator_options_
The propagator options.
Definition msceqf_options.hpp:211
CheckerOptions checker_options_
The checker options.
Definition msceqf_options.hpp:209
Definition msceqf_options.hpp:112
fp acceleration_bias_std_
Continuous time acceleration bias (random walk) standard deviation.
Definition msceqf_options.hpp:116
fp angular_velocity_std_
Continuous time angular velocity standard deviation.
Definition msceqf_options.hpp:113
int state_transition_order_
The order for the computation of the state transition matrix.
Definition msceqf_options.hpp:118
uint imu_buffer_max_size_
The maximum size of the propagator's imu buffer.
Definition msceqf_options.hpp:117
fp acceleration_std_
Continuous time acceleration standard deviation.
Definition msceqf_options.hpp:114
fp angular_velocity_bias_std_
Continuous time angular velocity bias (random walk) standard deviation.
Definition msceqf_options.hpp:115
Definition msceqf_options.hpp:98
fp gravity_
The magnitude of the gravity vector in m/s^2.
Definition msceqf_options.hpp:106
Matrix6 E_init_cov_
Initial covariance of the E element of the state.
Definition msceqf_options.hpp:101
bool enable_camera_intrinsics_calibration_
Boolean to enable intinsic camera calibration.
Definition msceqf_options.hpp:105
Matrix9 D_init_cov_
Initial covariance of the D element of the state.
Definition msceqf_options.hpp:99
uint num_persistent_features_
The maximum number of persistent (SLAM) features.
Definition msceqf_options.hpp:108
uint num_clones_
The maximum number of stochastic clones.
Definition msceqf_options.hpp:107
Matrix4 L_init_cov_
Initial covariance of the L element of the state.
Definition msceqf_options.hpp:102
In initial_camera_intrinsics_
Initial camera intrinsics.
Definition msceqf_options.hpp:104
Matrix6 delta_init_cov_
Initial covariance of the delta element of the state.
Definition msceqf_options.hpp:100
SE3 initial_camera_extrinsics_
Initial camera extrinsics.
Definition msceqf_options.hpp:103
Definition msceqf_options.hpp:200
size_t max_track_length_
The maximul length of a track.
Definition msceqf_options.hpp:202
TrackerOptions tracker_options_
The vision tracker options.
Definition msceqf_options.hpp:201
Definition msceqf_options.hpp:180
uint optical_flow_win_size_
Window size for optical flow.
Definition msceqf_options.hpp:192
uint min_px_dist_
Minimum pixel distance between features.
Definition msceqf_options.hpp:189
uint min_features_
Minimum feature to track/detect.
Definition msceqf_options.hpp:186
FastOptions fast_opts_
Fast feature detector options.
Definition msceqf_options.hpp:195
uint grid_y_size_
y size of the grid
Definition msceqf_options.hpp:188
uint max_features_
Maximum feature to track/detect.
Definition msceqf_options.hpp:185
fp ransac_reprojection_
RANSAC reprojection threshold.
Definition msceqf_options.hpp:194
FeatureDetector detector_
The feature detector.
Definition msceqf_options.hpp:184
int opencv_threads_
Number of threads for opencv.
Definition msceqf_options.hpp:193
CameraOptions cam_options_
The camera options.
Definition msceqf_options.hpp:181
uint optical_flow_pyramid_levels_
Pyramids levels for optical flow (1-based)
Definition msceqf_options.hpp:190
DistortionModel distortion_model_
Distortion Model.
Definition msceqf_options.hpp:182
uint grid_x_size_
x size of the grid
Definition msceqf_options.hpp:187
EqualizationMethod equalizer_
The image equalization method.
Definition msceqf_options.hpp:183
GFTTOptions gftt_opts_
Shi-Tomasi feature detector options.
Definition msceqf_options.hpp:196
uint detector_pyramid_levels_
Pyramids levels for feature detection (1-based)
Definition msceqf_options.hpp:191
Definition msceqf_options.hpp:122
FeatureRepresentation msc_features_representation_
Multi State Constraint features representation.
Definition msceqf_options.hpp:128
fp min_depth_
Minimum depth of triangulated features.
Definition msceqf_options.hpp:124
ProjectionMethod projection_method_
The feature projection method.
Definition msceqf_options.hpp:129
fp pixel_std_
The pixel standard deviation.
Definition msceqf_options.hpp:132
bool curvature_correction_
Boolean to enable the curvature correction.
Definition msceqf_options.hpp:133
fp tollerance_
Tollerance for features triangulation refinement.
Definition msceqf_options.hpp:127
fp min_angle_
Minimum angle (in degrees) between views for trianglulation.
Definition msceqf_options.hpp:131
uint max_iterations_
Maximum number of iteration for features triangulation refinement.
Definition msceqf_options.hpp:126
bool refine_traingulation_
Boolean to enable feature triangulation refinement via nonlinear optimization.
Definition msceqf_options.hpp:123
fp max_depth_
Maximum depth of triangulated features.
Definition msceqf_options.hpp:125
uint min_track_lenght_
Minimum track length for triangulation.
Definition msceqf_options.hpp:130
Definition msceqf_options.hpp:137
bool curvature_correction_
Boolean to enable the curvature correction on the zero velocity update.
Definition msceqf_options.hpp:139
ZeroVelocityUpdate zero_velocity_update_
The zero velocity update method.
Definition msceqf_options.hpp:138