UpdaterSLAM.h
Go to the documentation of this file.
1 /*
2  * OpenVINS: An Open Platform for Visual-Inertial Research
3  * Copyright (C) 2018-2023 Patrick Geneva
4  * Copyright (C) 2018-2023 Guoquan Huang
5  * Copyright (C) 2018-2023 OpenVINS Contributors
6  * Copyright (C) 2018-2019 Kevin Eckenhoff
7  *
8  * This program is free software: you can redistribute it and/or modify
9  * it under the terms of the GNU General Public License as published by
10  * the Free Software Foundation, either version 3 of the License, or
11  * (at your option) any later version.
12  *
13  * This program is distributed in the hope that it will be useful,
14  * but WITHOUT ANY WARRANTY; without even the implied warranty of
15  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
16  * GNU General Public License for more details.
17  *
18  * You should have received a copy of the GNU General Public License
19  * along with this program. If not, see <https://www.gnu.org/licenses/>.
20  */
21 
22 #ifndef OV_MSCKF_UPDATER_SLAM_H
23 #define OV_MSCKF_UPDATER_SLAM_H
24 
25 #include <Eigen/Eigen>
26 #include <memory>
27 
29 
30 #include "UpdaterOptions.h"
31 
32 namespace ov_core {
33 class Feature;
34 class FeatureInitializer;
35 } // namespace ov_core
36 namespace ov_type {
37 class Landmark;
38 } // namespace ov_type
39 
40 namespace ov_msckf {
41 
42 class State;
43 
50 class UpdaterSLAM {
51 
52 public:
63  UpdaterSLAM(UpdaterOptions &options_slam, UpdaterOptions &options_aruco, ov_core::FeatureInitializerOptions &feat_init_options);
64 
70  void update(std::shared_ptr<State> state, std::vector<std::shared_ptr<ov_core::Feature>> &feature_vec);
71 
77  void delayed_init(std::shared_ptr<State> state, std::vector<std::shared_ptr<ov_core::Feature>> &feature_vec);
78 
87  void change_anchors(std::shared_ptr<State> state);
88 
89 protected:
97  void perform_anchor_change(std::shared_ptr<State> state, std::shared_ptr<ov_type::Landmark> landmark, double new_anchor_timestamp,
98  size_t new_cam_id);
99 
102 
105 
107  std::shared_ptr<ov_core::FeatureInitializer> initializer_feat;
108 
110  std::map<int, double> chi_squared_table;
111 };
112 
113 } // namespace ov_msckf
114 
115 #endif // OV_MSCKF_UPDATER_SLAM_H
ov_msckf::UpdaterSLAM::delayed_init
void delayed_init(std::shared_ptr< State > state, std::vector< std::shared_ptr< ov_core::Feature >> &feature_vec)
Given max track features, this will try to use them to initialize them in the state.
Definition: UpdaterSLAM.cpp:61
ov_msckf::UpdaterSLAM::initializer_feat
std::shared_ptr< ov_core::FeatureInitializer > initializer_feat
Feature initializer class object.
Definition: UpdaterSLAM.h:107
ov_msckf::UpdaterSLAM::chi_squared_table
std::map< int, double > chi_squared_table
Chi squared 95th percentile table (lookup would be size of residual)
Definition: UpdaterSLAM.h:110
ov_msckf::UpdaterOptions
Struct which stores general updater options.
Definition: UpdaterOptions.h:32
FeatureInitializerOptions.h
ov_msckf
Extended Kalman Filter estimator.
Definition: VioManager.h:46
ov_msckf::UpdaterSLAM::update
void update(std::shared_ptr< State > state, std::vector< std::shared_ptr< ov_core::Feature >> &feature_vec)
Given tracked SLAM features, this will try to use them to update the state.
Definition: UpdaterSLAM.cpp:253
ov_core::FeatureInitializerOptions
ov_msckf::UpdaterSLAM::_options_aruco
UpdaterOptions _options_aruco
Options used during update for aruco features.
Definition: UpdaterSLAM.h:104
ov_msckf::UpdaterSLAM::change_anchors
void change_anchors(std::shared_ptr< State > state)
Will change SLAM feature anchors if it will be marginalized.
Definition: UpdaterSLAM.cpp:481
ov_msckf::UpdaterSLAM::UpdaterSLAM
UpdaterSLAM(UpdaterOptions &options_slam, UpdaterOptions &options_aruco, ov_core::FeatureInitializerOptions &feat_init_options)
Default constructor for our SLAM updater.
Definition: UpdaterSLAM.cpp:43
ov_msckf::UpdaterSLAM::perform_anchor_change
void perform_anchor_change(std::shared_ptr< State > state, std::shared_ptr< ov_type::Landmark > landmark, double new_anchor_timestamp, size_t new_cam_id)
Shifts landmark anchor to new clone.
Definition: UpdaterSLAM.cpp:505
ov_msckf::UpdaterSLAM::_options_slam
UpdaterOptions _options_slam
Options used during update for slam features.
Definition: UpdaterSLAM.h:101
ov_type
ov_msckf::UpdaterSLAM
Will compute the system for our sparse SLAM features and update the filter.
Definition: UpdaterSLAM.h:50
UpdaterOptions.h
ov_core


ov_msckf
Author(s): Patrick Geneva , Kevin Eckenhoff , Guoquan Huang
autogenerated on Mon Dec 16 2024 03:06:54