22 #ifndef OV_MSCKF_STATE_HELPER_H 23 #define OV_MSCKF_STATE_HELPER_H 25 #include <Eigen/Eigen> 76 static void EKFPropagation(std::shared_ptr<State> state,
const std::vector<std::shared_ptr<ov_type::Type>> &order_NEW,
77 const std::vector<std::shared_ptr<ov_type::Type>> &order_OLD,
const Eigen::MatrixXd &Phi,
78 const Eigen::MatrixXd &Q);
88 static void EKFUpdate(std::shared_ptr<State> state,
const std::vector<std::shared_ptr<ov_type::Type>> &H_order,
const Eigen::MatrixXd &H,
89 const Eigen::VectorXd &res,
const Eigen::MatrixXd &R);
98 static void set_initial_covariance(std::shared_ptr<State> state,
const Eigen::MatrixXd &covariance,
99 const std::vector<std::shared_ptr<ov_type::Type>> &order);
112 static Eigen::MatrixXd get_marginal_covariance(std::shared_ptr<State> state,
113 const std::vector<std::shared_ptr<ov_type::Type>> &small_variables);
125 static Eigen::MatrixXd get_full_covariance(std::shared_ptr<State> state);
139 static void marginalize(std::shared_ptr<State> state, std::shared_ptr<ov_type::Type> marg);
146 static std::shared_ptr<ov_type::Type> clone(std::shared_ptr<State> state, std::shared_ptr<ov_type::Type> variable_to_clone);
165 static bool initialize(std::shared_ptr<State> state, std::shared_ptr<ov_type::Type> new_variable,
166 const std::vector<std::shared_ptr<ov_type::Type>> &H_order, Eigen::MatrixXd &H_R, Eigen::MatrixXd &H_L,
167 Eigen::MatrixXd &R, Eigen::VectorXd &res,
double chi_2_mult);
183 static void initialize_invertible(std::shared_ptr<State> state, std::shared_ptr<ov_type::Type> new_variable,
184 const std::vector<std::shared_ptr<ov_type::Type>> &H_order,
const Eigen::MatrixXd &H_R,
185 const Eigen::MatrixXd &H_L,
const Eigen::MatrixXd &R,
const Eigen::VectorXd &res);
213 static void augment_clone(std::shared_ptr<State> state, Eigen::Matrix<double, 3, 1> last_w);
224 static void marginalize_old_clone(std::shared_ptr<State> state);
230 static void marginalize_slam(std::shared_ptr<State> state);
242 #endif // OV_MSCKF_STATE_HELPER_H Extended Kalman Filter estimator.
Helper which manipulates the State and its covariance.
ROSCONSOLE_DECL void initialize()