49 [[nodiscard]] std::string
type()
const override;
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;
120 bool initialize()
override;
123 void deinitialize()
override;
127 void invokeCallbackWithPosVelAtt(
const PosVelAtt& posVelAtt);
148 void looselyCoupledPrediction(
const std::shared_ptr<const PosVelAtt>& inertialNavSol,
double tau_i,
const ImuPos& imuPos);
152 void looselyCoupledUpdate(
const std::shared_ptr<const PosVel>& posVelObs);
155 void updateExternalPvaInitPin();
160 bool _preferAccelerationOverDeltaMeasurements =
false;
163 std::shared_ptr<const ImuObs> _lastImuObs =
nullptr;
166 std::array<double, 3> _initalRollPitchYaw{};
168 bool _initializeStateOverExternalPin{};
170 InsTime _externalInitTime;
197 KeyedKalmanFilterD<KFStates, KFMeas> _kalmanFilter{ States, Meas };
204 bool _checkKalmanMatricesRanks =
true;
211 Eigen::Vector3d _b_leverArm_InsGnss{ 0.0, 0.0, 0.0 };
216 enum class StdevAccelNoiseUnits
222 StdevAccelNoiseUnits _stdevAccelNoiseUnits = StdevAccelNoiseUnits::mg_sqrtHz;
226 Eigen::Vector3d _stdev_ra = 0.04 * Eigen::Vector3d::Ones();
231 enum class StdevGyroNoiseUnits
237 StdevGyroNoiseUnits _stdevGyroNoiseUnits = StdevGyroNoiseUnits::deg_hr_sqrtHz;
241 Eigen::Vector3d _stdev_rg = 5 * Eigen::Vector3d::Ones();
246 enum class StdevAccelBiasUnits
252 StdevAccelBiasUnits _stdevAccelBiasUnits = StdevAccelBiasUnits::microg;
256 Eigen::Vector3d _stdev_bad = 10 * Eigen::Vector3d::Ones();
259 Eigen::Vector3d _tau_bad = 0.1 * Eigen::Vector3d::Ones();
264 enum class StdevGyroBiasUnits
270 StdevGyroBiasUnits _stdevGyroBiasUnits = StdevGyroBiasUnits::deg_h;
274 Eigen::Vector3d _stdev_bgd = 1 * Eigen::Vector3d::Ones();
277 Eigen::Vector3d _tau_bgd = 0.1 * Eigen::Vector3d::Ones();
282 enum class RandomProcess
295 RandomProcess _randomProcessAccel = RandomProcess::RandomWalk;
297 RandomProcess _randomProcessGyro = RandomProcess::RandomWalk;
302 enum class GnssMeasurementUncertaintyPositionUnit
310 GnssMeasurementUncertaintyPositionUnit _gnssMeasurementUncertaintyPositionUnit = GnssMeasurementUncertaintyPositionUnit::meter;
314 Eigen::Vector3d _gnssMeasurementUncertaintyPosition{ 0.3, 0.3, 0.3 * 3 };
317 bool _gnssMeasurementUncertaintyPositionOverride =
false;
322 enum class GnssMeasurementUncertaintyVelocityUnit
328 GnssMeasurementUncertaintyVelocityUnit _gnssMeasurementUncertaintyVelocityUnit = GnssMeasurementUncertaintyVelocityUnit::m_s;
331 Eigen::Vector3d _gnssMeasurementUncertaintyVelocity{ 0.5, 0.5, 0.5 };
334 bool _gnssMeasurementUncertaintyVelocityOverride =
false;
339 enum class InitCovariancePositionUnit
347 InitCovariancePositionUnit _initCovariancePositionUnit = InitCovariancePositionUnit::meter;
350 Eigen::Vector3d _initCovariancePosition{ 100.0, 100.0, 100.0 };
355 enum class InitCovarianceVelocityUnit
361 InitCovarianceVelocityUnit _initCovarianceVelocityUnit = InitCovarianceVelocityUnit::m_s;
364 Eigen::Vector3d _initCovarianceVelocity{ 10.0, 10.0, 10.0 };
369 enum class InitCovarianceAttitudeAnglesUnit
377 InitCovarianceAttitudeAnglesUnit _initCovarianceAttitudeAnglesUnit = InitCovarianceAttitudeAnglesUnit::deg;
380 Eigen::Vector3d _initCovarianceAttitudeAngles{ 10.0, 10.0, 10.0 };
385 enum class InitCovarianceBiasAccelUnit
391 InitCovarianceBiasAccelUnit _initCovarianceBiasAccelUnit = InitCovarianceBiasAccelUnit::m_s2;
394 Eigen::Vector3d _initCovarianceBiasAccel{ 1.0, 1.0, 1.0 };
399 enum class InitCovarianceBiasGyroUnit
407 InitCovarianceBiasGyroUnit _initCovarianceBiasGyroUnit = InitCovarianceBiasGyroUnit::deg_s;
410 Eigen::Vector3d _initCovarianceBiasGyro{ 0.5, 0.5, 0.5 };
415 enum class InitBiasAccelUnit
420 InitBiasAccelUnit _initBiasAccelUnit = InitBiasAccelUnit::m_s2;
423 Eigen::Vector3d _initBiasAccel{ 0.0, 0.0, 0.0 };
428 enum class InitBiasGyroUnit
434 InitBiasGyroUnit _initBiasGyroUnit = InitBiasGyroUnit::deg_s;
437 Eigen::Vector3d _initBiasGyro{ 0.0, 0.0, 0.0 };
442 enum class PhiCalculationAlgorithm
448 PhiCalculationAlgorithm _phiCalculationAlgorithm = PhiCalculationAlgorithm::Taylor;
451 int _phiCalculationTaylorOrder = 2;
454 enum class QCalculationAlgorithm
460 QCalculationAlgorithm _qCalculationAlgorithm = QCalculationAlgorithm::Taylor1;
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,
492 const Eigen::Vector3d& tau_bad,
493 const Eigen::Vector3d& tau_bgd)
const;
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,
510 const Eigen::Vector3d& e_omega_ie,
511 const Eigen::Vector3d& tau_bad,
512 const Eigen::Vector3d& tau_bgd)
const;
522 [[nodiscard]]
static KeyedMatrix<double, KFStates, KFStates, 15, 15> noiseInputMatrix_G(
const Eigen::Quaterniond& ien_Quat_b);
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);
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);
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);
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;
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);
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);
620 [[nodiscard]]
static KeyedMatrix<double, KFMeas, KFMeas, 6, 6> n_measurementNoiseCovariance_R(
const Eigen::Vector3d& gnssVarianceLatLonAlt,
621 const Eigen::Vector3d& gnssVarianceVelocity);
627 [[nodiscard]]
static KeyedMatrix<double, KFMeas, KFMeas, 6, 6> e_measurementNoiseCovariance_R(
const Eigen::Vector3d& gnssVariancePosition,
628 const Eigen::Vector3d& gnssVarianceVelocity);
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);
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);