22 #ifndef OV_MSCKF_UPDATER_HELPER_H 23 #define OV_MSCKF_UPDATER_HELPER_H 25 #include <Eigen/Eigen> 27 #include <unordered_map> 60 std::unordered_map<size_t, std::vector<Eigen::VectorXf>>
uvs;
63 std::unordered_map<size_t, std::vector<Eigen::VectorXf>>
uvs_norm;
66 std::unordered_map<size_t, std::vector<double>>
timestamps;
72 int anchor_cam_id = -1;
75 double anchor_clone_timestamp = -1;
99 static void get_feature_jacobian_representation(std::shared_ptr<State> state,
UpdaterHelperFeature &feature, Eigen::MatrixXd &H_f,
100 std::vector<Eigen::MatrixXd> &H_x, std::vector<std::shared_ptr<ov_type::Type>> &x_order);
112 static void get_feature_jacobian_full(std::shared_ptr<State> state,
UpdaterHelperFeature &feature, Eigen::MatrixXd &H_f,
113 Eigen::MatrixXd &H_x, Eigen::VectorXd &res, std::vector<std::shared_ptr<ov_type::Type>> &x_order);
126 static void nullspace_project_inplace(Eigen::MatrixXd &H_f, Eigen::MatrixXd &H_x, Eigen::VectorXd &res);
137 static void measurement_compress_inplace(Eigen::MatrixXd &H_x, Eigen::VectorXd &res);
142 #endif // OV_MSCKF_UPDATER_HELPER_H Class that has helper functions for our updaters.
Extended Kalman Filter estimator.
size_t featid
Unique ID of this feature.
Eigen::Vector3d p_FinA
Triangulated position of this feature, in the anchor frame.
ov_type::LandmarkRepresentation::Representation feat_representation
What representation our feature is in.
Eigen::Vector3d p_FinA_fej
Triangulated position of this feature, in the anchor frame first estimate.
Eigen::Vector3d p_FinG_fej
Triangulated position of this feature, in the global frame first estimate.
Feature object that our UpdaterHelper leverages, has all measurements and means.
std::unordered_map< size_t, std::vector< Eigen::VectorXf > > uvs
UV coordinates that this feature has been seen from (mapped by camera ID)
std::unordered_map< size_t, std::vector< double > > timestamps
Timestamps of each UV measurement (mapped by camera ID)
std::unordered_map< size_t, std::vector< Eigen::VectorXf > > uvs_norm
Eigen::Vector3d p_FinG
Triangulated position of this feature, in the global frame.