22 #ifndef OV_MSCKF_VIOMANAGER_H 23 #define OV_MSCKF_VIOMANAGER_H 25 #include <Eigen/StdVector> 28 #include <boost/filesystem.hpp> 40 class FeatureInitializer;
43 class InertialInitializer;
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);
96 void initialize_with_gt(Eigen::Matrix<double, 17, 1> imustate);
99 bool initialized() {
return is_initialized_vio && timelastupdate != -1; }
114 cv::Mat get_historical_viz_image();
117 std::vector<Eigen::Vector3d> get_features_SLAM();
120 std::vector<Eigen::Vector3d> get_features_ARUCO();
127 timestamp = active_tracks_time;
128 image = active_image;
132 void get_active_tracks(
double ×tamp, 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;
198 bool is_initialized_vio =
false;
216 boost::posix_time::ptime rT1, rT2, rT3, rT4, rT5, rT6,
rT7;
219 double timelastupdate = -1;
223 double startup_time = -1;
229 bool did_zupt_update =
false;
230 bool has_moved_since_zupt =
false;
237 double active_tracks_time = -1;
248 #endif // OV_MSCKF_VIOMANAGER_H bool initialized()
If we are initialized or not.
Extended Kalman Filter estimator.
Helper which manipulates the State and its covariance.
std::unordered_map< size_t, Eigen::Vector3d > active_tracks_uvd
std::shared_ptr< Propagator > propagator
Propagator of our state.
VioManagerOptions get_params()
Accessor for current system parameters.
std::atomic< bool > thread_init_success
Performs the state covariance and mean propagation using imu measurements.
boost::posix_time::ptime rT7
std::ofstream of_statistics
std::shared_ptr< Propagator > get_propagator()
Accessor to get the current propagator.
std::map< size_t, Eigen::Matrix3d > active_feat_linsys_A
VioManagerOptions params
Manager parameters.
double initialized_time()
Timestamp that the system was initialized at.
void get_active_image(double ×tamp, cv::Mat &image)
Return the image used when projecting the active tracks.
std::vector< double > camera_queue_init
std::map< size_t, Eigen::Vector3d > active_feat_linsys_b
Will compute the system for our sparse SLAM features and update the filter.
std::shared_ptr< UpdaterMSCKF > updaterMSCKF
Our MSCKF feature updater.
Will try to detect and then update using zero velocity assumption.
std::shared_ptr< State > get_state()
Accessor to get the current state.
std::shared_ptr< ov_core::TrackBase > trackFEATS
Our sparse feature tracker (klt or descriptor)
std::shared_ptr< ov_init::InertialInitializer > initializer
State initializer.
std::mutex camera_queue_init_mtx
Struct which stores all options needed for state estimation.
std::map< size_t, int > active_feat_linsys_count
std::unordered_map< size_t, Eigen::Vector3d > active_tracks_posinG
std::shared_ptr< UpdaterSLAM > updaterSLAM
Our SLAM/ARUCO feature updater.
Will compute the system for our sparse features and update the filter.
std::shared_ptr< State > state
Our master state object :D.
Core class that manages the entire system.
std::shared_ptr< UpdaterZeroVelocity > updaterZUPT
Our zero velocity tracker.
void feed_measurement_camera(const ov_core::CameraData &message)
Feed function for camera measurements.
std::vector< Eigen::Vector3d > good_features_MSCKF
std::shared_ptr< ov_core::TrackBase > trackARUCO
Our aruoc tracker.
std::vector< Eigen::Vector3d > get_good_features_MSCKF()
Returns 3d features used in the last update in global frame.
void get_active_tracks(double ×tamp, 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.