Go to the documentation of this file.
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;
90 const std::vector<std::vector<std::pair<size_t, Eigen::VectorXf>>> &feats);
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) {
248 #endif // OV_MSCKF_VIOMANAGER_H
std::shared_ptr< ov_core::TrackBase > trackFEATS
Our sparse feature tracker (klt or descriptor)
bool has_moved_since_zupt
std::map< size_t, int > active_feat_linsys_count
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.
std::shared_ptr< ov_init::InertialInitializer > initializer
State initializer.
VioManagerOptions params
Manager parameters.
std::shared_ptr< State > state
Our master state object :D.
boost::posix_time::ptime rT4
Extended Kalman Filter estimator.
boost::posix_time::ptime rT1
std::shared_ptr< UpdaterZeroVelocity > updaterZUPT
Our zero velocity tracker.
std::vector< double > camera_queue_init
void do_feature_propagate_update(const ov_core::CameraData &message)
This will do the propagation and feature updates to the state.
void feed_measurement_imu(const ov_core::ImuData &message)
Feed function for inertial data.
void feed_measurement_camera(const ov_core::CameraData &message)
Feed function for camera measurements.
std::atomic< bool > thread_init_running
std::shared_ptr< State > get_state()
Accessor to get the current state.
boost::posix_time::ptime rT3
boost::posix_time::ptime rT5
std::vector< Eigen::Vector3d > good_features_MSCKF
cv::Mat get_historical_viz_image()
Get a nice visualization image of what tracks we have.
VioManager(VioManagerOptions ¶ms_)
Default constructor, will load all configuration variables.
Performs the state covariance and mean propagation using imu measurements.
std::map< size_t, Eigen::Matrix3d > active_feat_linsys_A
Core class that manages the entire system.
std::vector< Eigen::Vector3d > get_good_features_MSCKF()
Returns 3d features used in the last update in global frame.
double initialized_time()
Timestamp that the system was initialized at.
boost::posix_time::ptime rT2
std::shared_ptr< ov_core::TrackBase > trackARUCO
Our aruoc tracker.
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.
std::map< size_t, Eigen::Vector3d > active_feat_linsys_b
std::shared_ptr< Propagator > get_propagator()
Accessor to get the current propagator.
std::unordered_map< size_t, Eigen::Vector3d > active_tracks_uvd
void track_image_and_update(const ov_core::CameraData &message)
Given a new set of camera images, this will track them.
bool is_initialized_vio
Boolean if we are initialized or not.
std::atomic< bool > thread_init_success
boost::posix_time::ptime rT6
void initialize_with_gt(Eigen::Matrix< double, 17, 1 > imustate)
Given a state, this will initialize our IMU state.
std::ofstream of_statistics
Will try to detect and then update using zero velocity assumption.
bool try_to_initialize(const ov_core::CameraData &message)
This function will try to initialize the state.
VioManagerOptions get_params()
Accessor for current system parameters.
double active_tracks_time
Will compute the system for our sparse features and update the filter.
Helper which manipulates the State and its covariance.
boost::posix_time::ptime rT7
std::vector< Eigen::Vector3d > get_features_SLAM()
Returns 3d SLAM features in the global frame.
std::mutex camera_queue_init_mtx
Struct which stores all options needed for state estimation.
std::shared_ptr< UpdaterSLAM > updaterSLAM
Our SLAM/ARUCO feature updater.
std::shared_ptr< UpdaterMSCKF > updaterMSCKF
Our MSCKF feature updater.
std::unordered_map< size_t, Eigen::Vector3d > active_tracks_posinG
Will compute the system for our sparse SLAM features and update the filter.
bool initialized()
If we are initialized or not.
std::vector< Eigen::Vector3d > get_features_ARUCO()
Returns 3d ARUCO features in the global frame.
void get_active_image(double ×tamp, cv::Mat &image)
Return the image used when projecting the active tracks.
void retriangulate_active_tracks(const ov_core::CameraData &message)
This function will will re-triangulate all features in the current frame.
std::shared_ptr< Propagator > propagator
Propagator of our state.
ov_msckf
Author(s): Patrick Geneva
, Kevin Eckenhoff , Guoquan Huang
autogenerated on Mon Dec 16 2024 03:06:54