MSCEqF 1.0
Multi State Constraint Equivariant Filter for visual inertial navigation
Loading...
Searching...
No Matches
msceqf.hpp
1// Copyright (C) 2023 Alessandro Fornasier.
2// Control of Networked Systems, University of Klagenfurt, Austria.
3//
4// All rights reserved.
5//
6// This software is licensed under the terms of the BSD-2-Clause-License with
7// no commercial use allowed, the full terms of which are made available
8// in the LICENSE file. No license in patents is granted.
9//
10// You can contact the authors at <alessandro.fornasier@ieee.org>
11
12#ifndef MSCEQF_HPP
13#define MSCEQF_HPP
14
15#include <future>
16
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"
25
26namespace msceqf
27{
28class MSCEqF
29{
30 public:
36 MSCEqF(const std::string& params_filepath);
37
43 void processMeasurement(const Imu& meas) { processImuMeasurement(meas); }
44
50 void processMeasurement(Camera& meas) { processCameraMeasurement(meas); }
51
57 void processMeasurement(TriangulatedFeatures& meas) { processFeaturesMeasurement(meas); }
58
64 const MSCEqFOptions& options() const;
65
71 const StateOptions& stateOptions() const;
72
78 const MatrixX& covariance() const;
79
85 const MatrixX coreCovariance() const;
86
92 const SystemState& stateEstimate() const;
93
99 const SystemState& stateOrigin() const;
100
108 void setGivenOrigin(const SE23& T0, const Vector6& b0, const fp& timestamp);
109
115 const cv::Mat3b imageWithTracks(const Camera& cam) const;
116
122 void visualizeImageWithTracks(const Camera& cam) const;
123
129 [[nodiscard]] const bool& isInit() const;
130
136 [[nodiscard]] const bool& zvuPerformed() const;
137
138 private:
145 void processImuMeasurement(const Imu& imu);
146
158 void processCameraMeasurement(Camera& cam);
159
171 void processFeaturesMeasurement(TriangulatedFeatures& features);
172
180 void initialize(Camera& cam);
181
189 void initialize(TriangulatedFeatures& features);
190
195 void setGivenOrigin();
196
201 void logInit() const;
202
203 OptionParser parser_;
204 MSCEqFOptions opts_;
205
206 SystemState xi0_;
207 MSCEqFState X_;
208 SystemState xi_;
209
210 TrackManager track_manager_;
211 Checker checker_;
212 StaticInitializer initializer_;
213 Propagator propagator_;
214 Updater updater_;
215 ZeroVelocityUpdater zvupdater_;
216 Visualizer visualizer_; //<! The MSCEqF visualizer
217
218 std::unordered_set<uint> ids_to_update_;
219
220 fp timestamp_;
221
222 bool is_filter_initialized_;
223 bool zvu_performed_;
224};
225
226} // namespace msceqf
227
228#endif // MSCEQF_HPP
Simple class to perform various checks.
Definition checker.hpp:27
Definition msceqf.hpp:29
void setGivenOrigin(const SE23 &T0, const Vector6 &b0, const fp &timestamp)
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 &params_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