0.3.0
Loading...
Searching...
No Matches
ImuFusion.hpp
Go to the documentation of this file.
1// This file is part of INSTINCT, the INS Toolkit for Integrated
2// Navigation Concepts and Training by the Institute of Navigation of
3// the University of Stuttgart, Germany.
4//
5// This Source Code Form is subject to the terms of the Mozilla Public
6// License, v. 2.0. If a copy of the MPL was not distributed with this
7// file, You can obtain one at https://mozilla.org/MPL/2.0/.
8
13
14#pragma once
15
18
20
22
24
25#include <deque>
26#include <utility>
27
28namespace NAV
29{
31class ImuFusion : public Imu
32{
33 public:
37 ~ImuFusion() override;
39 ImuFusion(const ImuFusion&) = delete;
41 ImuFusion(ImuFusion&&) = delete;
43 ImuFusion& operator=(const ImuFusion&) = delete;
46
48 [[nodiscard]] static std::string typeStatic();
49
51 [[nodiscard]] std::string type() const override;
52
54 [[nodiscard]] static std::string category();
55
58 void guiConfig() override;
59
61 [[nodiscard]] json save() const override;
62
65 void restore(const json& j) override;
66
67 protected:
70
71 private:
72 constexpr static size_t OUTPUT_PORT_INDEX_COMBINED_SIGNAL = 0;
73 constexpr static size_t OUTPUT_PORT_INDEX_BIASES = 1;
74
76 bool initialize() override;
77
79 void deinitialize() override;
80
83
86
90 void recvSignal(InputPin::NodeDataQueue& queue, size_t pinIdx);
91
100 [[nodiscard]] static Eigen::MatrixXd measurementNoiseMatrix_R_adaptive(double alpha,
101 const Eigen::MatrixXd& R,
102 const Eigen::VectorXd& e,
103 const Eigen::MatrixXd& H,
104 const Eigen::MatrixXd& P);
105
108
112 void measurementNoiseMatrix_R(Eigen::MatrixXd& R, size_t pinIndex = 0) const;
113
116 void combineSignals(const std::shared_ptr<const ImuObs>& imuObs);
117
118 // --------------------------------------- Kalman filter config ------------------------------------------
120 size_t _nInputPins = 2;
121
123 const uint8_t _numStatesEstIRWKF = 12;
124
126 const uint8_t _numStatesEstBsplineKF = 18;
127
129 const uint8_t _numBsplines = 9;
130
132 const uint8_t _numStatesPerPin = 6;
133
135 const uint8_t _numMeasurements = 6;
136
138 uint8_t _numStatesEst{};
139
141 uint8_t _numStates = 12;
142
145
146 // ---------------------------------------- Kalman filter init -------------------------------------------
148 double _imuFrequency{ 100 };
149
151 double _averageEndTime{ 1 };
152
155
157 bool _autoInitKF = true;
158
161
164
166 std::vector<std::shared_ptr<const NAV::ImuObs>> _cumulatedImuObs;
167
169 std::vector<size_t> _cumulatedPinIds;
170
172 bool _initJerkAngAcc = true;
173
175 bool _kfInitialized = false;
176
177 // -------------------------------------------- Sensor info ----------------------------------------------
179 std::vector<PinData> _pinData;
184
186 Eigen::Vector3d _initCoeffsAngRateTemp;
188 Eigen::Vector3d _initCoeffsAccelTemp;
197
199 std::vector<Eigen::Vector3d> _biasCovariances;
201 std::vector<Eigen::VectorXd> _processNoiseVariances;
203 std::vector<Eigen::Vector3d> _measurementNoiseVariances;
204
206 std::vector<Eigen::Matrix3d> _imuRotations_accel;
207
209 std::vector<Eigen::Matrix3d> _imuRotations_gyro;
210
211 // ----------------------------------------------- Time --------------------------------------------------
214
217
220
222 double _latestKnot{};
223
225 double _splineSpacing = 1.0;
226
227 // ------------------------------------------- Miscellaneous ---------------------------------------------
230
232 bool _imuPosSet = false;
233
235 enum class ImuFusionType : uint8_t
236 {
237 IRWKF,
238 Bspline,
239 COUNT,
240 };
244 friend constexpr const char* to_string(ImuFusionType value);
245
248};
249
250constexpr const char* to_string(NAV::ImuFusion::ImuFusionType value)
251{
252 switch (value)
253 {
255 return "IRW KF";
257 return "B-spline KF";
259 return "";
260 }
261 return "";
262}
263
264} // namespace NAV
nlohmann::json json
json namespace
Definition FlowManager.hpp:21
Parent Class for all IMU Observations.
Abstract IMU Class.
Generalized Kalman Filter class.
Information about a sensor which is connected to a certain pin.
const char * to_string(gui::widgets::PositionWithFrame::ReferenceFrame refFrame)
Converts the enum to a string.
Widget to modify time point values.
Combines signals of sensors that provide the same signal-type to one signal.
Definition ImuFusion.hpp:32
KalmanFilter _kalmanFilter
Kalman Filter representation.
Definition ImuFusion.hpp:144
void updateNumberOfInputPins()
Adds/Deletes Input Pins depending on the variable _nInputPins.
std::vector< Eigen::Matrix3d > _imuRotations_accel
Rotations of all connected accelerometers - key: pinIndex, value: Rotation matrix of the acceleromete...
Definition ImuFusion.hpp:206
uint8_t _numStatesEst
Number of estimated states (depends on imuFusionType)
Definition ImuFusion.hpp:138
friend constexpr const char * to_string(ImuFusionType value)
Converts the enum to a string.
Definition ImuFusion.hpp:250
const uint8_t _numStatesEstIRWKF
Number of states estimated by the IRW-KF (angular rate, angular acceleration, specific force,...
Definition ImuFusion.hpp:123
void initializeMountingAngles()
Initializes the rotation matrices used for the mounting angles of the sensors.
std::string type() const override
String representation of the Class Type.
bool initialize() override
Initialize the node.
Eigen::Vector3d _procNoiseCoeffsAccelTemp
Temporary vector for the initial coefficients' process noise for the acceleration.
Definition ImuFusion.hpp:196
bool _kfInitialized
flag to check whether KF has been auto-initialized
Definition ImuFusion.hpp:175
bool _checkKalmanMatricesRanks
Check the rank of the Kalman matrices every iteration (computationally expensive)
Definition ImuFusion.hpp:229
bool _imuCharacteristicsIdentical
If the multiple IMUs have the same characteristics, GUI input cells can be reduced considerably.
Definition ImuFusion.hpp:160
std::vector< Eigen::Matrix3d > _imuRotations_gyro
Rotations of all connected gyros - key: pinIndex, value: Rotation matrix of the gyro platform to body...
Definition ImuFusion.hpp:209
Eigen::Vector3d _initCovarianceCoeffsAngRateTemp
Temporary vector for the initial coefficients' initial covariance for the angular rate.
Definition ImuFusion.hpp:190
std::vector< Eigen::Vector3d > _measurementNoiseVariances
Container for measurement noises of each sensor.
Definition ImuFusion.hpp:203
ImuFusion(const ImuFusion &)=delete
Copy constructor.
const uint8_t _numBsplines
Number of quadratic B-splines that make up the entire 3D stacked B-spline.
Definition ImuFusion.hpp:129
json save() const override
Saves the node into a json object.
void recvSignal(InputPin::NodeDataQueue &queue, size_t pinIdx)
Receive Function for the signal at the time tâ‚–
const uint8_t _numMeasurements
Number of measurements overall.
Definition ImuFusion.hpp:135
size_t _nInputPins
Number of input pins.
Definition ImuFusion.hpp:120
InsTime _lastFiltObs
Previous observation (for timestamp)
Definition ImuFusion.hpp:107
ImuFusion & operator=(const ImuFusion &)=delete
Copy assignment operator.
~ImuFusion() override
Destructor.
void measurementNoiseMatrix_R(Eigen::MatrixXd &R, size_t pinIndex=0) const
Calculates the initial measurement noise matrix R.
ImuPos _imuPos
Position and rotation information for conversion from platform to body frame.
Definition ImuFusion.hpp:69
InsTime _firstTimestamp
Saves the first timestamp in [s].
Definition ImuFusion.hpp:216
PinDataIRWKF _pinDataIRWKF
Stores IRW-KF specific parameter data.
Definition ImuFusion.hpp:181
Eigen::Vector3d _initCoeffsAccelTemp
Temporary vector for the initial coefficients for acceleration.
Definition ImuFusion.hpp:188
double _imuFrequency
Highest IMU sample rate in [Hz] (for time step in KF prediction)
Definition ImuFusion.hpp:148
std::vector< Eigen::Vector3d > _biasCovariances
Container for the bias covariances.
Definition ImuFusion.hpp:199
double _averageEndTime
Time until averaging ends and filtering starts in [s].
Definition ImuFusion.hpp:151
static std::string typeStatic()
String representation of the Class Type.
bool _imuPosSet
Check whether the combined solution has an '_imuPos' set.
Definition ImuFusion.hpp:232
static constexpr size_t OUTPUT_PORT_INDEX_BIASES
Flow (ImuBiases)
Definition ImuFusion.hpp:73
static constexpr size_t OUTPUT_PORT_INDEX_COMBINED_SIGNAL
Flow (ImuObs)
Definition ImuFusion.hpp:72
void guiConfig() override
ImGui config window which is shown on double click.
ImuFusion()
Default constructor.
std::vector< std::shared_ptr< const NAV::ImuObs > > _cumulatedImuObs
Container that collects all imuObs for averaging for auto-init of the KF.
Definition ImuFusion.hpp:166
void restore(const json &j) override
Restores the node from a json object.
Eigen::Vector3d _initCovarianceCoeffsAccelTemp
Temporary vector for the initial coefficients' initial covariance for the acceleration.
Definition ImuFusion.hpp:192
ImuFusion & operator=(ImuFusion &&)=delete
Move assignment operator.
std::vector< size_t > _cumulatedPinIds
Container that collects all pinIds for averaging for auto-init of the KF.
Definition ImuFusion.hpp:169
uint8_t _numStates
Number of states overall.
Definition ImuFusion.hpp:141
const uint8_t _numStatesEstBsplineKF
Number of states estimated by the B-spline KF (3 stacked B-splines in 3D for angular rate and specifi...
Definition ImuFusion.hpp:126
double _timeSinceStartup
Time since startup in [s].
Definition ImuFusion.hpp:219
bool _initJerkAngAcc
flag to determine how jerk and angular acceleration states are initialized if '_autoInitKF = true'
Definition ImuFusion.hpp:172
std::vector< Eigen::VectorXd > _processNoiseVariances
Container for process noise of each state.
Definition ImuFusion.hpp:201
void deinitialize() override
Deinitialize the node.
double _latestKnot
Latest knot in [s].
Definition ImuFusion.hpp:222
const uint8_t _numStatesPerPin
Number of states per pin (biases of accel and gyro)
Definition ImuFusion.hpp:132
ImuFusionType _imuFusionType
KF-type for the IMU fusion, selected in the GUI.
Definition ImuFusion.hpp:247
static Eigen::MatrixXd measurementNoiseMatrix_R_adaptive(double alpha, const Eigen::MatrixXd &R, const Eigen::VectorXd &e, const Eigen::MatrixXd &H, const Eigen::MatrixXd &P)
Calculates the adaptive measurement noise matrix R.
bool _autoInitKF
Auto-initialize the Kalman Filter - GUI setting.
Definition ImuFusion.hpp:157
ImuFusionType
Possible KF-types for the IMU fusion.
Definition ImuFusion.hpp:236
@ Bspline
B-spline Kalman filter.
@ IRWKF
IRW Kalman filter.
@ COUNT
Number of items in the enum.
double _splineSpacing
Time difference between two quadratic B-splines in the stacked B-spline.
Definition ImuFusion.hpp:225
std::vector< PinData > _pinData
Stores parameter data for each connected sensor.
Definition ImuFusion.hpp:179
Eigen::Vector3d _procNoiseCoeffsAngRateTemp
Temporary vector for the initial coefficients' process noise for the angular rate.
Definition ImuFusion.hpp:194
static std::string category()
String representation of the Class Category.
ImuFusion(ImuFusion &&)=delete
Move constructor.
void combineSignals(const std::shared_ptr< const ImuObs > &imuObs)
Combines the signals.
PinDataBsplineKF _pinDataBsplineKF
Stores Bspline-KF specific parameter data.
Definition ImuFusion.hpp:183
bool _imuBiasesIdentical
If the multiple IMUs have the same bias, GUI input cells can be reduced considerably.
Definition ImuFusion.hpp:163
InsTime _latestTimestamp
Saves the timestamp of the measurement before in [s].
Definition ImuFusion.hpp:213
InsTime _avgEndTime
Time until averaging ends and filtering starts as 'InsTime'.
Definition ImuFusion.hpp:154
Eigen::Vector3d _initCoeffsAngRateTemp
Temporary vector for the initial coefficients for angular rate.
Definition ImuFusion.hpp:186
IMU Position.
Definition ImuPos.hpp:26
Abstract IMU Class.
Definition Imu.hpp:24
The class is responsible for all time-related tasks.
Definition InsTime.hpp:668
Generalized Kalman Filter class.
Definition KalmanFilter.hpp:25
Sensor information specific to the Bspline-KF.
Definition PinData.hpp:179
Sensor information specific to the IRW-KF.
Definition PinData.hpp:105