0.2.0
Loading...
Searching...
No Matches
LooselyCoupledKF.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
14
15#pragma once
16
18
21
24
26
27namespace NAV
28{
30class LooselyCoupledKF : public Node
31{
32 public:
46 [[nodiscard]] static std::string typeStatic();
47
49 [[nodiscard]] std::string type() const override;
50
52 [[nodiscard]] static std::string category();
53
56 void guiConfig() override;
57
59 [[nodiscard]] json save() const override;
60
63 void restore(const json& j) override;
64
94
112
113 private:
114 constexpr static size_t INPUT_PORT_INDEX_IMU = 0;
115 constexpr static size_t INPUT_PORT_INDEX_GNSS = 1;
116 constexpr static size_t INPUT_PORT_INDEX_POS_VEL_ATT_INIT = 2;
117 constexpr static size_t OUTPUT_PORT_INDEX_SOLUTION = 0;
118
120 bool initialize() override;
121
123 void deinitialize() override;
124
127 void invokeCallbackWithPosVelAtt(const PosVelAtt& posVelAtt);
128
132 void recvImuObservation(InputPin::NodeDataQueue& queue, size_t pinIdx);
133
137 void recvPosVelObservation(InputPin::NodeDataQueue& queue, size_t pinIdx);
138
142 void recvPosVelAttInit(InputPin::NodeDataQueue& queue, size_t pinIdx);
143
148 void looselyCoupledPrediction(const std::shared_ptr<const PosVelAtt>& inertialNavSol, double tau_i, const ImuPos& imuPos);
149
152 void looselyCoupledUpdate(const std::shared_ptr<const PosVel>& posVelObs);
153
155 void updateExternalPvaInitPin();
156
158 InertialIntegrator _inertialIntegrator;
160 bool _preferAccelerationOverDeltaMeasurements = false;
161
163 std::shared_ptr<const ImuObs> _lastImuObs = nullptr;
164
166 std::array<double, 3> _initalRollPitchYaw{};
168 bool _initializeStateOverExternalPin{};
170 InsTime _externalInitTime;
171
173 inline static const std::vector<KFStates> States = { KFStates::Roll, KFStates::Pitch, KFStates::Yaw,
179 inline static const std::vector<KFStates> Pos = { KFStates::PosLat, KFStates::PosLon, KFStates::PosAlt };
181 inline static const std::vector<KFStates> Vel = { KFStates::VelN, KFStates::VelE, KFStates::VelD };
183 inline static const std::vector<KFStates> Att = { KFStates::Roll, KFStates::Pitch, KFStates::Yaw };
185 inline static const std::vector<KFStates> AccBias = { KFStates::AccBiasX, KFStates::AccBiasY, KFStates::AccBiasZ };
187 inline static const std::vector<KFStates> GyrBias = { KFStates::GyrBiasX, KFStates::GyrBiasY, KFStates::GyrBiasZ };
188
190 inline static const std::vector<KFMeas> Meas = { KFMeas::dPosLat, KFMeas::dPosLon, KFMeas::dPosAlt, KFMeas::dVelN, KFMeas::dVelE, KFMeas::dVelD };
192 inline static const std::vector<KFMeas> dPos = { KFMeas::dPosLat, KFMeas::dPosLon, KFMeas::dPosAlt };
194 inline static const std::vector<KFMeas> dVel = { KFMeas::dVelN, KFMeas::dVelE, KFMeas::dVelD };
195
197 KeyedKalmanFilterD<KFStates, KFMeas> _kalmanFilter{ States, Meas };
198
199 // #########################################################################################################################################
200 // GUI settings
201 // #########################################################################################################################################
202
204 bool _checkKalmanMatricesRanks = true;
205
206 // ###########################################################################################################
207 // Parameters
208 // ###########################################################################################################
209
211 Eigen::Vector3d _b_leverArm_InsGnss{ 0.0, 0.0, 0.0 };
212
213 // ###########################################################################################################
214
216 enum class StdevAccelNoiseUnits
217 {
218 mg_sqrtHz,
219 m_s2_sqrtHz,
220 };
222 StdevAccelNoiseUnits _stdevAccelNoiseUnits = StdevAccelNoiseUnits::mg_sqrtHz;
223
226 Eigen::Vector3d _stdev_ra = 0.04 /* [mg/โˆš(Hz)] */ * Eigen::Vector3d::Ones();
227
228 // ###########################################################################################################
229
231 enum class StdevGyroNoiseUnits
232 {
233 deg_hr_sqrtHz,
234 rad_s_sqrtHz,
235 };
237 StdevGyroNoiseUnits _stdevGyroNoiseUnits = StdevGyroNoiseUnits::deg_hr_sqrtHz;
238
241 Eigen::Vector3d _stdev_rg = 5 /* [deg/hr/โˆš(Hz)]^2 */ * Eigen::Vector3d::Ones();
242
243 // ###########################################################################################################
244
246 enum class StdevAccelBiasUnits
247 {
248 microg,
249 m_s2,
250 };
252 StdevAccelBiasUnits _stdevAccelBiasUnits = StdevAccelBiasUnits::microg;
253
256 Eigen::Vector3d _stdev_bad = 10 /* [ยตg] */ * Eigen::Vector3d::Ones();
257
259 Eigen::Vector3d _tau_bad = 0.1 * Eigen::Vector3d::Ones();
260
261 // ###########################################################################################################
262
264 enum class StdevGyroBiasUnits
265 {
266 deg_h,
267 rad_s,
268 };
270 StdevGyroBiasUnits _stdevGyroBiasUnits = StdevGyroBiasUnits::deg_h;
271
274 Eigen::Vector3d _stdev_bgd = 1 /* [ยฐ/h] */ * Eigen::Vector3d::Ones();
275
277 Eigen::Vector3d _tau_bgd = 0.1 * Eigen::Vector3d::Ones();
278
279 // ###########################################################################################################
280
282 enum class RandomProcess
283 {
284 // WhiteNoise, ///< White noise
285 // RandomConstant, ///< Random constant
286
287 RandomWalk,
288 GaussMarkov1,
289
290 // GaussMarkov2, ///< Gauss-Markov 2nd Order
291 // GaussMarkov3, ///< Gauss-Markov 3rd Order
292 };
293
295 RandomProcess _randomProcessAccel = RandomProcess::RandomWalk;
297 RandomProcess _randomProcessGyro = RandomProcess::RandomWalk;
298
299 // ###########################################################################################################
300
302 enum class GnssMeasurementUncertaintyPositionUnit
303 {
304 rad2_rad2_m2,
305 rad_rad_m,
306 meter2,
307 meter,
308 };
310 GnssMeasurementUncertaintyPositionUnit _gnssMeasurementUncertaintyPositionUnit = GnssMeasurementUncertaintyPositionUnit::meter;
311
314 Eigen::Vector3d _gnssMeasurementUncertaintyPosition{ 0.3, 0.3, 0.3 * 3 };
315
317 bool _gnssMeasurementUncertaintyPositionOverride = false;
318
319 // ###########################################################################################################
320
322 enum class GnssMeasurementUncertaintyVelocityUnit
323 {
324 m2_s2,
325 m_s,
326 };
328 GnssMeasurementUncertaintyVelocityUnit _gnssMeasurementUncertaintyVelocityUnit = GnssMeasurementUncertaintyVelocityUnit::m_s;
329
331 Eigen::Vector3d _gnssMeasurementUncertaintyVelocity{ 0.5, 0.5, 0.5 };
332
334 bool _gnssMeasurementUncertaintyVelocityOverride = false;
335
336 // ###########################################################################################################
337
339 enum class InitCovariancePositionUnit
340 {
341 rad2_rad2_m2,
342 rad_rad_m,
343 meter2,
344 meter,
345 };
347 InitCovariancePositionUnit _initCovariancePositionUnit = InitCovariancePositionUnit::meter;
348
350 Eigen::Vector3d _initCovariancePosition{ 100.0, 100.0, 100.0 };
351
352 // ###########################################################################################################
353
355 enum class InitCovarianceVelocityUnit
356 {
357 m2_s2,
358 m_s,
359 };
361 InitCovarianceVelocityUnit _initCovarianceVelocityUnit = InitCovarianceVelocityUnit::m_s;
362
364 Eigen::Vector3d _initCovarianceVelocity{ 10.0, 10.0, 10.0 };
365
366 // ###########################################################################################################
367
369 enum class InitCovarianceAttitudeAnglesUnit
370 {
371 rad2,
372 deg2,
373 rad,
374 deg,
375 };
377 InitCovarianceAttitudeAnglesUnit _initCovarianceAttitudeAnglesUnit = InitCovarianceAttitudeAnglesUnit::deg;
378
380 Eigen::Vector3d _initCovarianceAttitudeAngles{ 10.0, 10.0, 10.0 };
381
382 // ###########################################################################################################
383
385 enum class InitCovarianceBiasAccelUnit
386 {
387 m2_s4,
388 m_s2,
389 };
391 InitCovarianceBiasAccelUnit _initCovarianceBiasAccelUnit = InitCovarianceBiasAccelUnit::m_s2;
392
394 Eigen::Vector3d _initCovarianceBiasAccel{ 1.0, 1.0, 1.0 };
395
396 // ###########################################################################################################
397
399 enum class InitCovarianceBiasGyroUnit
400 {
401 rad2_s2,
402 deg2_s2,
403 rad_s,
404 deg_s,
405 };
407 InitCovarianceBiasGyroUnit _initCovarianceBiasGyroUnit = InitCovarianceBiasGyroUnit::deg_s;
408
410 Eigen::Vector3d _initCovarianceBiasGyro{ 0.5, 0.5, 0.5 };
411
412 // ###########################################################################################################
413
415 enum class InitBiasAccelUnit
416 {
417 m_s2,
418 };
420 InitBiasAccelUnit _initBiasAccelUnit = InitBiasAccelUnit::m_s2;
421
423 Eigen::Vector3d _initBiasAccel{ 0.0, 0.0, 0.0 };
424
425 // ###########################################################################################################
426
428 enum class InitBiasGyroUnit
429 {
430 rad_s,
431 deg_s,
432 };
434 InitBiasGyroUnit _initBiasGyroUnit = InitBiasGyroUnit::deg_s;
435
437 Eigen::Vector3d _initBiasGyro{ 0.0, 0.0, 0.0 };
438
439 // ###########################################################################################################
440
442 enum class PhiCalculationAlgorithm
443 {
444 Exponential,
445 Taylor,
446 };
448 PhiCalculationAlgorithm _phiCalculationAlgorithm = PhiCalculationAlgorithm::Taylor;
449
451 int _phiCalculationTaylorOrder = 2;
452
454 enum class QCalculationAlgorithm
455 {
456 VanLoan,
457 Taylor1,
458 };
460 QCalculationAlgorithm _qCalculationAlgorithm = QCalculationAlgorithm::Taylor1;
461
462 // ###########################################################################################################
463 // Prediction
464 // ###########################################################################################################
465
466 // ###########################################################################################################
467 // System matrix ๐…
468 // ###########################################################################################################
469
483 [[nodiscard]] KeyedMatrix<double, KFStates, KFStates, 15, 15> n_systemMatrix_F(const Eigen::Quaterniond& n_Quat_b,
484 const Eigen::Vector3d& b_specForce_ib,
485 const Eigen::Vector3d& n_omega_in,
486 const Eigen::Vector3d& n_velocity,
487 const Eigen::Vector3d& lla_position,
488 double R_N,
489 double R_E,
490 double g_0,
491 double r_eS_e,
492 const Eigen::Vector3d& tau_bad,
493 const Eigen::Vector3d& tau_bgd) const;
494
505 [[nodiscard]] KeyedMatrix<double, KFStates, KFStates, 15, 15> e_systemMatrix_F(const Eigen::Quaterniond& e_Quat_b,
506 const Eigen::Vector3d& b_specForce_ib,
507 const Eigen::Vector3d& e_position,
508 const Eigen::Vector3d& e_gravitation,
509 double r_eS_e,
510 const Eigen::Vector3d& e_omega_ie,
511 const Eigen::Vector3d& tau_bad,
512 const Eigen::Vector3d& tau_bgd) const;
513
514 // ###########################################################################################################
515 // Noise input matrix ๐† & Noise scale matrix ๐–
516 // System noise covariance matrix ๐
517 // ###########################################################################################################
518
522 [[nodiscard]] static KeyedMatrix<double, KFStates, KFStates, 15, 15> noiseInputMatrix_G(const Eigen::Quaterniond& ien_Quat_b);
523
532 [[nodiscard]] Eigen::Matrix<double, 15, 15> noiseScaleMatrix_W(const Eigen::Vector3d& sigma_ra, const Eigen::Vector3d& sigma_rg,
533 const Eigen::Vector3d& sigma_bad, const Eigen::Vector3d& sigma_bgd,
534 const Eigen::Vector3d& tau_bad, const Eigen::Vector3d& tau_bgd);
535
548 [[nodiscard]] static KeyedMatrix<double, KFStates, KFStates, 15, 15> n_systemNoiseCovarianceMatrix_Q(const Eigen::Vector3d& sigma2_ra, const Eigen::Vector3d& sigma2_rg,
549 const Eigen::Vector3d& sigma2_bad, const Eigen::Vector3d& sigma2_bgd,
550 const Eigen::Vector3d& tau_bad, const Eigen::Vector3d& tau_bgd,
551 const Eigen::Matrix3d& n_F_21, const Eigen::Matrix3d& T_rn_p,
552 const Eigen::Matrix3d& n_Dcm_b, const double& tau_s);
553
565 [[nodiscard]] static KeyedMatrix<double, KFStates, KFStates, 15, 15> e_systemNoiseCovarianceMatrix_Q(const Eigen::Vector3d& sigma2_ra, const Eigen::Vector3d& sigma2_rg,
566 const Eigen::Vector3d& sigma2_bad, const Eigen::Vector3d& sigma2_bgd,
567 const Eigen::Vector3d& tau_bad, const Eigen::Vector3d& tau_bgd,
568 const Eigen::Matrix3d& e_F_21,
569 const Eigen::Matrix3d& e_Dcm_b, const double& tau_s);
570
571 // ###########################################################################################################
572 // Error covariance matrix P
573 // ###########################################################################################################
574
582 [[nodiscard]] KeyedMatrix<double, KFStates, KFStates, 15, 15> initialErrorCovarianceMatrix_P0(const Eigen::Vector3d& variance_angles,
583 const Eigen::Vector3d& variance_vel,
584 const Eigen::Vector3d& variance_pos,
585 const Eigen::Vector3d& variance_accelBias,
586 const Eigen::Vector3d& variance_gyroBias) const;
587
588 // ###########################################################################################################
589 // Correction
590 // ###########################################################################################################
591
599 [[nodiscard]] static KeyedMatrix<double, KFMeas, KFStates, 6, 15> n_measurementMatrix_H(const Eigen::Matrix3d& T_rn_p,
600 const Eigen::Matrix3d& n_Dcm_b,
601 const Eigen::Vector3d& b_omega_ib,
602 const Eigen::Vector3d& b_leverArm_InsGnss,
603 const Eigen::Matrix3d& n_Omega_ie);
604
611 [[nodiscard]] static KeyedMatrix<double, KFMeas, KFStates, 6, 15> e_measurementMatrix_H(const Eigen::Matrix3d& e_Dcm_b,
612 const Eigen::Vector3d& b_omega_ib,
613 const Eigen::Vector3d& b_leverArm_InsGnss,
614 const Eigen::Matrix3d& e_Omega_ie);
615
620 [[nodiscard]] static KeyedMatrix<double, KFMeas, KFMeas, 6, 6> n_measurementNoiseCovariance_R(const Eigen::Vector3d& gnssVarianceLatLonAlt,
621 const Eigen::Vector3d& gnssVarianceVelocity);
622
627 [[nodiscard]] static KeyedMatrix<double, KFMeas, KFMeas, 6, 6> e_measurementNoiseCovariance_R(const Eigen::Vector3d& gnssVariancePosition,
628 const Eigen::Vector3d& gnssVarianceVelocity);
629
641 [[nodiscard]] static KeyedVector<double, KFMeas, 6> n_measurementInnovation_dz(const Eigen::Vector3d& lla_positionMeasurement, const Eigen::Vector3d& lla_positionEstimate,
642 const Eigen::Vector3d& n_velocityMeasurement, const Eigen::Vector3d& n_velocityEstimate,
643 const Eigen::Matrix3d& T_rn_p, const Eigen::Quaterniond& n_Quat_b, const Eigen::Vector3d& b_leverArm_InsGnss,
644 const Eigen::Vector3d& b_omega_ib, const Eigen::Matrix3d& n_Omega_ie);
645
656 [[nodiscard]] static KeyedVector<double, KFMeas, 6> e_measurementInnovation_dz(const Eigen::Vector3d& e_positionMeasurement, const Eigen::Vector3d& e_positionEstimate,
657 const Eigen::Vector3d& e_velocityMeasurement, const Eigen::Vector3d& e_velocityEstimate,
658 const Eigen::Quaterniond& e_Quat_b, const Eigen::Vector3d& b_leverArm_InsGnss,
659 const Eigen::Vector3d& b_omega_ib, const Eigen::Matrix3d& e_Omega_ie);
660};
661
662} // namespace NAV
663
664#ifndef DOXYGEN_IGNORE
665
666template<>
667struct fmt::formatter<NAV::LooselyCoupledKF::KFStates> : fmt::formatter<const char*>
668{
673 template<typename FormatContext>
674 auto format(const NAV::LooselyCoupledKF::KFStates& st, FormatContext& ctx)
675 {
676 switch (st)
677 {
679 return fmt::formatter<const char*>::format("Roll/Psi_eb_1", ctx);
681 return fmt::formatter<const char*>::format("Pitch/Psi_eb_2", ctx);
683 return fmt::formatter<const char*>::format("Yaw/Psi_eb_3", ctx);
685 return fmt::formatter<const char*>::format("VelN/VelX", ctx);
687 return fmt::formatter<const char*>::format("VelE/VelY", ctx);
689 return fmt::formatter<const char*>::format("VelD/VelZ", ctx);
691 return fmt::formatter<const char*>::format("PosLat/PosX", ctx);
693 return fmt::formatter<const char*>::format("PosLon/PosY", ctx);
695 return fmt::formatter<const char*>::format("PosAlt/PosZ", ctx);
697 return fmt::formatter<const char*>::format("AccBiasX", ctx);
699 return fmt::formatter<const char*>::format("AccBiasY", ctx);
701 return fmt::formatter<const char*>::format("AccBiasZ", ctx);
703 return fmt::formatter<const char*>::format("GyrBiasX", ctx);
705 return fmt::formatter<const char*>::format("GyrBiasY", ctx);
707 return fmt::formatter<const char*>::format("GyrBiasZ", ctx);
708 }
709
710 return fmt::formatter<const char*>::format("ERROR", ctx);
711 }
712};
713template<>
714struct fmt::formatter<NAV::LooselyCoupledKF::KFMeas> : fmt::formatter<const char*>
715{
720 template<typename FormatContext>
721 auto format(const NAV::LooselyCoupledKF::KFMeas& st, FormatContext& ctx)
722 {
723 switch (st)
724 {
726 return fmt::formatter<const char*>::format("dPosLat/dPosX", ctx);
728 return fmt::formatter<const char*>::format("dPosLon/dPosY", ctx);
730 return fmt::formatter<const char*>::format("dPosAlt/dPosZ", ctx);
732 return fmt::formatter<const char*>::format("dVelN/dVelX", ctx);
734 return fmt::formatter<const char*>::format("dVelE/dVelY", ctx);
736 return fmt::formatter<const char*>::format("dVelD/dVelZ", ctx);
737 }
738
739 return fmt::formatter<const char*>::format("ERROR", ctx);
740 }
741};
742
743#endif
744
749std::ostream& operator<<(std::ostream& os, const NAV::LooselyCoupledKF::KFStates& obj);
750
755std::ostream& operator<<(std::ostream& os, const NAV::LooselyCoupledKF::KFMeas& obj);
nlohmann::json json
json namespace
Definition FlowManager.hpp:21
Parent Class for all IMU Observations.
Inertial Measurement Integrator.
The class is responsible for all time-related tasks.
Kalman Filter with keyed states.
std::ostream & operator<<(std::ostream &os, const NAV::LooselyCoupledKF::KFStates &obj)
Stream insertion operator overload.
Node Class.
Position, Velocity and Attitude Storage Class.
IMU Position.
Definition ImuPos.hpp:26
Inertial Measurement Integrator.
Definition InertialIntegrator.hpp:37
Loosely-coupled Kalman Filter for INS/GNSS integration.
Definition LooselyCoupledKF.hpp:31
json save() const override
Saves the node into a json object.
LooselyCoupledKF & operator=(const LooselyCoupledKF &)=delete
Copy assignment operator.
LooselyCoupledKF(const LooselyCoupledKF &)=delete
Copy constructor.
LooselyCoupledKF & operator=(LooselyCoupledKF &&)=delete
Move assignment operator.
KFMeas
Measurement Keys of the Kalman filter.
Definition LooselyCoupledKF.hpp:97
@ dPosLat
Latitude difference.
Definition LooselyCoupledKF.hpp:98
@ dPosLon
Longitude difference.
Definition LooselyCoupledKF.hpp:99
@ dPosY
ECEF Position Y difference.
Definition LooselyCoupledKF.hpp:106
@ dPosX
ECEF Position X difference.
Definition LooselyCoupledKF.hpp:105
@ dVelE
Velocity East difference.
Definition LooselyCoupledKF.hpp:102
@ dPosZ
ECEF Position Z difference.
Definition LooselyCoupledKF.hpp:107
@ dPosAlt
Altitude difference.
Definition LooselyCoupledKF.hpp:100
@ dVelN
Velocity North difference.
Definition LooselyCoupledKF.hpp:101
@ dVelZ
ECEF Velocity Z difference.
Definition LooselyCoupledKF.hpp:110
@ dVelX
ECEF Velocity X difference.
Definition LooselyCoupledKF.hpp:108
@ dVelY
ECEF Velocity Y difference.
Definition LooselyCoupledKF.hpp:109
@ dVelD
Velocity Down difference.
Definition LooselyCoupledKF.hpp:103
~LooselyCoupledKF() override
Destructor.
LooselyCoupledKF(LooselyCoupledKF &&)=delete
Move constructor.
void restore(const json &j) override
Restores the node from a json object.
static std::string typeStatic()
String representation of the class type.
std::string type() const override
String representation of the class type.
KFStates
State Keys of the Kalman filter.
Definition LooselyCoupledKF.hpp:67
@ Pitch
Pitch.
Definition LooselyCoupledKF.hpp:69
@ VelY
ECEF Velocity Y.
Definition LooselyCoupledKF.hpp:88
@ GyrBiasX
Gyroscope Bias X.
Definition LooselyCoupledKF.hpp:80
@ PosLat
Latitude.
Definition LooselyCoupledKF.hpp:74
@ VelE
Velocity East.
Definition LooselyCoupledKF.hpp:72
@ Roll
Roll.
Definition LooselyCoupledKF.hpp:68
@ Psi_eb_3
Angle between Earth and Body frame around 3. axis.
Definition LooselyCoupledKF.hpp:86
@ AccBiasZ
Accelerometer Bias Z.
Definition LooselyCoupledKF.hpp:79
@ VelX
ECEF Velocity X.
Definition LooselyCoupledKF.hpp:87
@ PosAlt
Altitude.
Definition LooselyCoupledKF.hpp:76
@ GyrBiasZ
Gyroscope Bias Z.
Definition LooselyCoupledKF.hpp:82
@ GyrBiasY
Gyroscope Bias Y.
Definition LooselyCoupledKF.hpp:81
@ VelD
Velocity Down.
Definition LooselyCoupledKF.hpp:73
@ AccBiasX
Accelerometer Bias X.
Definition LooselyCoupledKF.hpp:77
@ VelN
Velocity North.
Definition LooselyCoupledKF.hpp:71
@ PosLon
Longitude.
Definition LooselyCoupledKF.hpp:75
@ VelZ
ECEF Velocity Z.
Definition LooselyCoupledKF.hpp:89
@ PosX
ECEF Position X.
Definition LooselyCoupledKF.hpp:90
@ Yaw
Yaw.
Definition LooselyCoupledKF.hpp:70
@ AccBiasY
Accelerometer Bias Y.
Definition LooselyCoupledKF.hpp:78
@ PosZ
ECEF Position Z.
Definition LooselyCoupledKF.hpp:92
@ PosY
ECEF Position Y.
Definition LooselyCoupledKF.hpp:91
@ Psi_eb_2
Angle between Earth and Body frame around 2. axis.
Definition LooselyCoupledKF.hpp:85
@ Psi_eb_1
Angle between Earth and Body frame around 1. axis.
Definition LooselyCoupledKF.hpp:84
LooselyCoupledKF()
Default constructor.
void guiConfig() override
ImGui config window which is shown on double click.
static std::string category()
String representation of the class category.
Abstract parent class for all nodes.
Definition Node.hpp:86
Position, Velocity and Attitude Storage Class.
Definition PosVelAtt.hpp:25