17#include "msceqf/filter/initializer/static_initializer.hpp"
18#include "msceqf/filter/propagator/propagator.hpp"
19#include "msceqf/filter/updater/updater.hpp"
20#include "msceqf/filter/updater/zero_velocity_updater.hpp"
21#include "msceqf/options/msceqf_option_parser.hpp"
22#include "msceqf/state/state.hpp"
23#include "vision/track_manager.hpp"
24#include "utils/visualizer.hpp"
36 MSCEqF(
const std::string& params_filepath);
129 [[nodiscard]]
const bool&
isInit()
const;
145 void processImuMeasurement(
const Imu& imu);
158 void processCameraMeasurement(
Camera& cam);
180 void initialize(
Camera& cam);
201 void logInit()
const;
218 std::unordered_set<uint> ids_to_update_;
222 bool is_filter_initialized_;
Simple class to perform various checks.
Definition checker.hpp:27
void setGivenOrigin(const SE23 &T0, const Vector6 &b0, const fp ×tamp)
Set origin xi0 with given state programatically.
void processMeasurement(TriangulatedFeatures &meas)
Process triangulated features measurement.
Definition msceqf.hpp:57
void visualizeImageWithTracks(const Camera &cam) const
Visualize the processed image with overlayed tracks.
const bool & zvuPerformed() const
Check if a zero velocity update has been performed.
const MatrixX & covariance() const
Get a constant reference to the covariance matrix of the MSCEqF state.
const StateOptions & stateOptions() const
Get a constant reference to the MSCEqF state options.
void processMeasurement(const Imu &meas)
Process IMU measurement.
Definition msceqf.hpp:43
const bool & isInit() const
Check if the filter is initialized.
const MatrixX coreCovariance() const
Get the covariance of the navigation states (D, delta)
const cv::Mat3b imageWithTracks(const Camera &cam) const
Get the processed image with overlayed tracks.
MSCEqF(const std::string ¶ms_filepath)
MSCEqF Constructor.
void processMeasurement(Camera &meas)
Process camera measurement.
Definition msceqf.hpp:50
const MSCEqFOptions & options() const
Get a constant reference to the MSCEqF options.
const SystemState & stateEstimate() const
Get a constant reference to the estimated state.
const SystemState & stateOrigin() const
Get a constant reference to the origin state.
this class represent the state of the MSCEqF. This includes the state of the lifted system (element o...
Definition state.hpp:30
Definition msceqf_option_parser.hpp:29
Definition propagator.hpp:25
Definition static_initializer.hpp:21
The SystemState class represent the state of the system posed on the Homogenous space.
Definition system.hpp:29
This class manages the multiple tracks of feature traked in time.
Definition track_manager.hpp:28
Updater class. This class implements the Multi State Constraint update step of the MSCEqF filter.
Definition updater.hpp:30
Definition visualizer.hpp:23
Zero velocity updater class. This class implements the Equivariant Zero Velocity Update (ZVU) of the ...
Definition zero_velocity_updater.hpp:26
Definition sensor_data.hpp:78
Struct for one IMU reading. It includes timestamp, angular velocity and linear acceleration....
Definition sensor_data.hpp:29
Definition msceqf_options.hpp:206
Definition msceqf_options.hpp:98
Definition sensor_data.hpp:98