VioManager.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_VIOMANAGER_H
23 #define OV_MSCKF_VIOMANAGER_H
24 
25 #include <Eigen/StdVector>
26 #include <algorithm>
27 #include <atomic>
28 #include <boost/filesystem.hpp>
29 #include <fstream>
30 #include <memory>
31 #include <mutex>
32 #include <string>
33 
34 #include "VioManagerOptions.h"
35 
36 namespace ov_core {
37 struct ImuData;
38 struct CameraData;
39 class TrackBase;
40 class FeatureInitializer;
41 } // namespace ov_core
42 namespace ov_init {
43 class InertialInitializer;
44 } // namespace ov_init
45 
46 namespace ov_msckf {
47 
48 class State;
49 class StateHelper;
50 class UpdaterMSCKF;
51 class UpdaterSLAM;
53 class Propagator;
54 
62 class VioManager {
63 
64 public:
69  VioManager(VioManagerOptions &params_);
70 
75  void feed_measurement_imu(const ov_core::ImuData &message);
76 
82 
89  void feed_measurement_simulation(double timestamp, const std::vector<int> &camids,
90  const std::vector<std::vector<std::pair<size_t, Eigen::VectorXf>>> &feats);
91 
96  void initialize_with_gt(Eigen::Matrix<double, 17, 1> imustate);
97 
99  bool initialized() { return is_initialized_vio && timelastupdate != -1; }
100 
102  double initialized_time() { return startup_time; }
103 
106 
108  std::shared_ptr<State> get_state() { return state; }
109 
111  std::shared_ptr<Propagator> get_propagator() { return propagator; }
112 
114  cv::Mat get_historical_viz_image();
115 
117  std::vector<Eigen::Vector3d> get_features_SLAM();
118 
120  std::vector<Eigen::Vector3d> get_features_ARUCO();
121 
123  std::vector<Eigen::Vector3d> get_good_features_MSCKF() { return good_features_MSCKF; }
124 
126  void get_active_image(double &timestamp, cv::Mat &image) {
127  timestamp = active_tracks_time;
128  image = active_image;
129  }
130 
132  void get_active_tracks(double &timestamp, std::unordered_map<size_t, Eigen::Vector3d> &feat_posinG,
133  std::unordered_map<size_t, Eigen::Vector3d> &feat_tracks_uvd) {
134  timestamp = active_tracks_time;
135  feat_posinG = active_tracks_posinG;
136  feat_tracks_uvd = active_tracks_uvd;
137  }
138 
139 protected:
148  void track_image_and_update(const ov_core::CameraData &message);
149 
155 
166  bool try_to_initialize(const ov_core::CameraData &message);
167 
178 
181 
183  std::shared_ptr<State> state;
184 
186  std::shared_ptr<Propagator> propagator;
187 
189  std::shared_ptr<ov_core::TrackBase> trackFEATS;
190 
192  std::shared_ptr<ov_core::TrackBase> trackARUCO;
193 
195  std::shared_ptr<ov_init::InertialInitializer> initializer;
196 
198  bool is_initialized_vio = false;
199 
201  std::shared_ptr<UpdaterMSCKF> updaterMSCKF;
202 
204  std::shared_ptr<UpdaterSLAM> updaterSLAM;
205 
207  std::shared_ptr<UpdaterZeroVelocity> updaterZUPT;
208 
211  std::vector<double> camera_queue_init;
213 
214  // Timing statistic file and variables
215  std::ofstream of_statistics;
216  boost::posix_time::ptime rT1, rT2, rT3, rT4, rT5, rT6, rT7;
217 
218  // Track how much distance we have traveled
219  double timelastupdate = -1;
220  double distance = 0;
221 
222  // Startup time of the filter
223  double startup_time = -1;
224 
225  // Threads and their atomics
227 
228  // If we did a zero velocity update
229  bool did_zupt_update = false;
230  bool has_moved_since_zupt = false;
231 
232  // Good features that where used in the last update (used in visualization)
233  std::vector<Eigen::Vector3d> good_features_MSCKF;
234 
235  // Re-triangulated features 3d positions seen from the current frame (used in visualization)
236  // For each feature we have a linear system A * p_FinG = b we create and increment their costs
237  double active_tracks_time = -1;
238  std::unordered_map<size_t, Eigen::Vector3d> active_tracks_posinG;
239  std::unordered_map<size_t, Eigen::Vector3d> active_tracks_uvd;
240  cv::Mat active_image;
241  std::map<size_t, Eigen::Matrix3d> active_feat_linsys_A;
242  std::map<size_t, Eigen::Vector3d> active_feat_linsys_b;
243  std::map<size_t, int> active_feat_linsys_count;
244 };
245 
246 } // namespace ov_msckf
247 
248 #endif // OV_MSCKF_VIOMANAGER_H
ov_msckf::VioManager::did_zupt_update
bool did_zupt_update
Definition: VioManager.h:229
ov_msckf::VioManager::trackFEATS
std::shared_ptr< ov_core::TrackBase > trackFEATS
Our sparse feature tracker (klt or descriptor)
Definition: VioManager.h:189
ov_msckf::VioManager::has_moved_since_zupt
bool has_moved_since_zupt
Definition: VioManager.h:230
ov_msckf::VioManager::active_feat_linsys_count
std::map< size_t, int > active_feat_linsys_count
Definition: VioManager.h:243
ov_msckf::VioManager::get_active_tracks
void get_active_tracks(double &timestamp, std::unordered_map< size_t, Eigen::Vector3d > &feat_posinG, std::unordered_map< size_t, Eigen::Vector3d > &feat_tracks_uvd)
Returns active tracked features in the current frame.
Definition: VioManager.h:132
ov_msckf::VioManager::initializer
std::shared_ptr< ov_init::InertialInitializer > initializer
State initializer.
Definition: VioManager.h:195
ov_msckf::VioManager::params
VioManagerOptions params
Manager parameters.
Definition: VioManager.h:180
ov_msckf::VioManager::state
std::shared_ptr< State > state
Our master state object :D.
Definition: VioManager.h:183
ov_msckf::VioManager::rT4
boost::posix_time::ptime rT4
Definition: VioManager.h:216
ov_msckf
Extended Kalman Filter estimator.
Definition: VioManager.h:46
ov_msckf::VioManager::rT1
boost::posix_time::ptime rT1
Definition: VioManager.h:216
ov_msckf::VioManager::updaterZUPT
std::shared_ptr< UpdaterZeroVelocity > updaterZUPT
Our zero velocity tracker.
Definition: VioManager.h:207
ov_msckf::VioManager::camera_queue_init
std::vector< double > camera_queue_init
Definition: VioManager.h:211
ov_msckf::VioManager::do_feature_propagate_update
void do_feature_propagate_update(const ov_core::CameraData &message)
This will do the propagation and feature updates to the state.
Definition: VioManager.cpp:323
ov_msckf::VioManager::feed_measurement_imu
void feed_measurement_imu(const ov_core::ImuData &message)
Feed function for inertial data.
Definition: VioManager.cpp:166
ov_msckf::VioManager::feed_measurement_camera
void feed_measurement_camera(const ov_core::CameraData &message)
Feed function for camera measurements.
Definition: VioManager.h:81
ov_core::CameraData
ov_msckf::VioManager::thread_init_running
std::atomic< bool > thread_init_running
Definition: VioManager.h:226
ov_msckf::VioManager::get_state
std::shared_ptr< State > get_state()
Accessor to get the current state.
Definition: VioManager.h:108
ov_msckf::VioManager::rT3
boost::posix_time::ptime rT3
Definition: VioManager.h:216
ov_msckf::VioManager::rT5
boost::posix_time::ptime rT5
Definition: VioManager.h:216
ov_msckf::VioManager::good_features_MSCKF
std::vector< Eigen::Vector3d > good_features_MSCKF
Definition: VioManager.h:233
ov_msckf::VioManager::get_historical_viz_image
cv::Mat get_historical_viz_image()
Get a nice visualization image of what tracks we have.
Definition: VioManagerHelper.cpp:389
ov_msckf::VioManager::VioManager
VioManager(VioManagerOptions &params_)
Default constructor, will load all configuration variables.
Definition: VioManager.cpp:50
ov_msckf::Propagator
Performs the state covariance and mean propagation using imu measurements.
Definition: Propagator.h:44
ov_msckf::VioManager::active_feat_linsys_A
std::map< size_t, Eigen::Matrix3d > active_feat_linsys_A
Definition: VioManager.h:241
ov_msckf::VioManager
Core class that manages the entire system.
Definition: VioManager.h:62
ov_msckf::VioManager::get_good_features_MSCKF
std::vector< Eigen::Vector3d > get_good_features_MSCKF()
Returns 3d features used in the last update in global frame.
Definition: VioManager.h:123
ov_msckf::VioManager::initialized_time
double initialized_time()
Timestamp that the system was initialized at.
Definition: VioManager.h:102
ov_msckf::VioManager::rT2
boost::posix_time::ptime rT2
Definition: VioManager.h:216
ov_msckf::VioManager::trackARUCO
std::shared_ptr< ov_core::TrackBase > trackARUCO
Our aruoc tracker.
Definition: VioManager.h:192
ov_msckf::VioManager::feed_measurement_simulation
void feed_measurement_simulation(double timestamp, const std::vector< int > &camids, const std::vector< std::vector< std::pair< size_t, Eigen::VectorXf >>> &feats)
Feed function for a synchronized simulated cameras.
Definition: VioManager.cpp:191
ov_msckf::VioManager::active_feat_linsys_b
std::map< size_t, Eigen::Vector3d > active_feat_linsys_b
Definition: VioManager.h:242
ov_msckf::VioManager::get_propagator
std::shared_ptr< Propagator > get_propagator()
Accessor to get the current propagator.
Definition: VioManager.h:111
ov_msckf::VioManager::startup_time
double startup_time
Definition: VioManager.h:223
ov_msckf::VioManager::active_tracks_uvd
std::unordered_map< size_t, Eigen::Vector3d > active_tracks_uvd
Definition: VioManager.h:239
ov_msckf::VioManager::track_image_and_update
void track_image_and_update(const ov_core::CameraData &message)
Given a new set of camera images, this will track them.
Definition: VioManager.cpp:256
ov_init
VioManagerOptions.h
ov_msckf::VioManager::is_initialized_vio
bool is_initialized_vio
Boolean if we are initialized or not.
Definition: VioManager.h:198
ov_msckf::VioManager::thread_init_success
std::atomic< bool > thread_init_success
Definition: VioManager.h:226
ov_msckf::VioManager::rT6
boost::posix_time::ptime rT6
Definition: VioManager.h:216
ov_core::ImuData
ov_msckf::VioManager::initialize_with_gt
void initialize_with_gt(Eigen::Matrix< double, 17, 1 > imustate)
Given a state, this will initialize our IMU state.
Definition: VioManagerHelper.cpp:40
ov_msckf::VioManager::of_statistics
std::ofstream of_statistics
Definition: VioManager.h:215
ov_msckf::UpdaterZeroVelocity
Will try to detect and then update using zero velocity assumption.
Definition: UpdaterZeroVelocity.h:54
ov_msckf::VioManager::try_to_initialize
bool try_to_initialize(const ov_core::CameraData &message)
This function will try to initialize the state.
Definition: VioManagerHelper.cpp:78
ov_msckf::VioManager::get_params
VioManagerOptions get_params()
Accessor for current system parameters.
Definition: VioManager.h:105
ov_msckf::VioManager::active_tracks_time
double active_tracks_time
Definition: VioManager.h:237
ov_msckf::UpdaterMSCKF
Will compute the system for our sparse features and update the filter.
Definition: UpdaterMSCKF.h:48
ov_msckf::StateHelper
Helper which manipulates the State and its covariance.
Definition: StateHelper.h:45
ov_msckf::VioManager::distance
double distance
Definition: VioManager.h:220
ov_msckf::VioManager::rT7
boost::posix_time::ptime rT7
Definition: VioManager.h:216
ov_msckf::VioManager::get_features_SLAM
std::vector< Eigen::Vector3d > get_features_SLAM()
Returns 3d SLAM features in the global frame.
Definition: VioManagerHelper.cpp:417
ov_msckf::VioManager::camera_queue_init_mtx
std::mutex camera_queue_init_mtx
Definition: VioManager.h:212
ov_msckf::VioManager::active_image
cv::Mat active_image
Definition: VioManager.h:240
ov_msckf::VioManagerOptions
Struct which stores all options needed for state estimation.
Definition: VioManagerOptions.h:56
ov_msckf::VioManager::updaterSLAM
std::shared_ptr< UpdaterSLAM > updaterSLAM
Our SLAM/ARUCO feature updater.
Definition: VioManager.h:204
ov_msckf::VioManager::timelastupdate
double timelastupdate
Definition: VioManager.h:219
ov_msckf::VioManager::updaterMSCKF
std::shared_ptr< UpdaterMSCKF > updaterMSCKF
Our MSCKF feature updater.
Definition: VioManager.h:201
ov_msckf::State
State of our filter.
Definition: State.h:49
ov_msckf::VioManager::active_tracks_posinG
std::unordered_map< size_t, Eigen::Vector3d > active_tracks_posinG
Definition: VioManager.h:238
ov_msckf::UpdaterSLAM
Will compute the system for our sparse SLAM features and update the filter.
Definition: UpdaterSLAM.h:50
ov_msckf::VioManager::initialized
bool initialized()
If we are initialized or not.
Definition: VioManager.h:99
ov_msckf::VioManager::get_features_ARUCO
std::vector< Eigen::Vector3d > get_features_ARUCO()
Returns 3d ARUCO features in the global frame.
Definition: VioManagerHelper.cpp:440
ov_msckf::VioManager::get_active_image
void get_active_image(double &timestamp, cv::Mat &image)
Return the image used when projecting the active tracks.
Definition: VioManager.h:126
ov_core
ov_msckf::VioManager::retriangulate_active_tracks
void retriangulate_active_tracks(const ov_core::CameraData &message)
This function will will re-triangulate all features in the current frame.
Definition: VioManagerHelper.cpp:190
ov_msckf::VioManager::propagator
std::shared_ptr< Propagator > propagator
Propagator of our state.
Definition: VioManager.h:186


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