57template<
typename StateKeyType>
65 template<
typename Scalar,
int Size>
75 for (
const auto& key : F.
rowKeys())
77 if (
const auto* biasKey = std::get_if<Keys::RecvClkBias>(&key))
82 F(*biasKey, driftKey) = 1;
83 G(*biasKey, *biasKey) = 1;
84 G(driftKey, driftKey) = 1;
99 template<
typename Scalar,
int Size>
108 for (
const auto& key : Phi.
rowKeys())
110 if (
const auto* bias = std::get_if<Keys::RecvClkBias>(&key))
115 std::vector<StateKeyType> keys = { *bias, drift };
116 if (algorithm == SystemModelCalcAlgorithm::VanLoan)
119 F.template block<2>(keys, keys),
120 G.template block<2>(keys, keys),
121 W.template block<2>(keys, keys),
123 Phi.template block<2>(keys, keys) = PhiMot;
124 Q.template block<2>(keys, keys) = QMot;
134 Phi(*bias, *bias) = 1;
149 std::vector<StateKeyType> keys = {
171 bool ShowGui(
float itemWidth,
float unitWidth,
const char*
id)
173 bool changed =
false;
175 if (gui::widgets::InputDoubleWithUnit(fmt::format(
"{} of the receiver clock phase drift (RW)##{}",
183 MakeComboItems<Units::CovarianceClkPhaseDriftUnits>().c_str(),
184 0.0, 0.0,
"%.2e", ImGuiInputTextFlags_CharsScientific))
191 gui::widgets::HelpMarker(fmt::format(
"Typical values for a TCXO are {} {}",
196 if (gui::widgets::InputDoubleWithUnit(fmt::format(
"{} of the receiver clock frequency drift (IRW)##{}",
204 MakeComboItems<Units::CovarianceClkFrequencyDriftUnits>().c_str(),
205 0.0, 0.0,
"%.2e", ImGuiInputTextFlags_CharsScientific))
212 gui::widgets::HelpMarker(fmt::format(
"Typical values for a TCXO are {} {}",
228 double dt2 = std::pow(dt, 2);
229 double dt3 = dt2 * dt;
237 Q(drift, bias) = Q(bias, drift);
302struct hash<NAV::Keys::RecvClkBias>
308 return std::hash<NAV::SatelliteSystem>()(recvClkErr.
satSys);
313struct hash<NAV::Keys::RecvClkDrift>
319 return std::hash<NAV::SatelliteSystem>()(recvClkDrift.
satSys);
325#ifndef DOXYGEN_IGNORE
329struct fmt::formatter<NAV::Keys::RecvClkBias> : fmt::formatter<std::string>
335 template<
typename FormatContext>
338 return fmt::formatter<std::string>::format(fmt::format(
"RecvClkBias({})", recvClkBias.
satSys), ctx);
344struct fmt::formatter<NAV::Keys::RecvClkDrift> : fmt::formatter<std::string>
350 template<
typename FormatContext>
353 return fmt::formatter<std::string>::format(fmt::format(
"RecvClkDrift({})", recvClkDrift.
satSys), ctx);
#define INS_ASSERT_USER_ERROR(_EXP, _MSG)
Assert function with message.
Definition Assert.h:21
nlohmann::json json
json namespace
Definition FlowManager.hpp:21
Units used by the system model parameters.
CovarianceClkPhaseDriftUnits
Possible Units for the Standard deviation of the clock phase drift.
Definition Units.hpp:37
double convertUnit(const double &value, Units::CovarianceAccelUnits unit)
Converts the value depending on the unit provided.
CovarianceClkFrequencyDriftUnits
Possible Units for the Standard deviation of the clock frequency drift.
Definition Units.hpp:45
Text Help Marker (?) with Tooltip.
#define LOG_DEBUG
Debug information. Should not be called on functions which receive observations (spamming)
Definition Logger.hpp:67
Generalized Kalman Filter class.
Derived::PlainObject transitionMatrix_Phi_Taylor(const Eigen::MatrixBase< Derived > &F, double tau_s, size_t order)
Calculates the state transition matrix 𝚽 limited to specified order in 𝐅𝜏ₛ
Definition KalmanFilter.hpp:195
std::ostream & operator<<(std::ostream &os, const NAV::Keys::RecvClkBias &obj)
Stream insertion operator overload.
SystemModelCalcAlgorithm
Algorithms to calculate the system model with.
Definition SystemModel.hpp:23
Van Loan Method loan1978.
std::pair< typename DerivedF::PlainObject, typename DerivedF::PlainObject > calcPhiAndQWithVanLoanMethod(const Eigen::MatrixBase< DerivedF > &F, const Eigen::MatrixBase< DerivedG > &G, const Eigen::MatrixBase< DerivedW > &W, typename DerivedF::Scalar dt)
Numerical Method to calculate the State transition matrix 𝚽 and System/Process noise covariance matri...
Definition VanLoan.hpp:62
Static sized KeyedMatrix.
Definition KeyedMatrix.hpp:1910
Receiver Clock System Model.
Definition ReceiverClockModel.hpp:59
friend void from_json(const json &j, ReceiverClockModel &data)
Converts the provided json object into the data object.
Definition ReceiverClockModel.hpp:274
Units::CovarianceClkFrequencyDriftUnits _gui_covarianceClkFrequencyDriftUnit
Gui selection for the Unit of the input covarianceClkFrequencyDrift parameter.
Definition ReceiverClockModel.hpp:251
friend void to_json(json &j, const ReceiverClockModel &data)
Converts the provided data into a json object.
Definition ReceiverClockModel.hpp:261
double _gui_covarianceClkPhaseDrift
GUI selection for the Standard deviation of the clock phase drift.
Definition ReceiverClockModel.hpp:245
void updatePhiAndQ(KeyedMatrix< Scalar, StateKeyType, StateKeyType, Size, Size > &Phi, KeyedMatrix< Scalar, StateKeyType, StateKeyType, Size, Size > &Q, const KeyedMatrix< Scalar, StateKeyType, StateKeyType, Size, Size > &F, const KeyedMatrix< Scalar, StateKeyType, StateKeyType, Size, Size > &G, const KeyedMatrix< Scalar, StateKeyType, StateKeyType, Size, Size > &W, double dt, SystemModelCalcAlgorithm algorithm) const
Updates the provided Phi and Q matrix.
Definition ReceiverClockModel.hpp:100
std::pair< KeyedMatrix2d< StateKeyType >, KeyedMatrix2d< StateKeyType > > calcPhiAndQ(double dt, SatelliteSystem satSys, SystemModelCalcAlgorithm algorithm)
Calculates the state transition matrix (𝚽) and the process noise covariance matrix (𝐐)
Definition ReceiverClockModel.hpp:147
void initialize(KeyedMatrix< Scalar, StateKeyType, StateKeyType, Size, Size > &F, KeyedMatrix< Scalar, StateKeyType, StateKeyType, Size, Size > &G, KeyedMatrix< Scalar, StateKeyType, StateKeyType, Size, Size > &W)
Initializes the receiver clock model.
Definition ReceiverClockModel.hpp:66
double _covarianceClkPhaseDrift
Covariance of the clock phase drift [m²/s].
Definition ReceiverClockModel.hpp:248
double _covarianceClkFrequencyDrift
Covariance of the clock frequency drift [m²/s³].
Definition ReceiverClockModel.hpp:256
Units::CovarianceClkPhaseDriftUnits _gui_covarianceClkPhaseDriftUnit
Gui selection for the Unit of the input covarianceClkPhaseDrift parameter.
Definition ReceiverClockModel.hpp:243
double _gui_covarianceClkFrequencyDrift
GUI selection for the Standard deviation of the clock frequency drift.
Definition ReceiverClockModel.hpp:253
KeyedMatrix< double, StateKeyType, StateKeyType, 2, 2 > calcProcessNoiseMatrixTaylor(double dt, const SatelliteSystem &satSys, const std::vector< StateKeyType > &keys) const
Calculates the process noise covariance matrix with Taylor first order.
Definition ReceiverClockModel.hpp:226
bool ShowGui(float itemWidth, float unitWidth, const char *id)
Shows a GUI.
Definition ReceiverClockModel.hpp:171
bool hasRow(const RowKeyType &key) const
Checks if the matrix has the key.
Definition KeyedMatrix.hpp:81
const std::vector< RowKeyType > & rowKeys() const
Returns the row keys.
Definition KeyedMatrix.hpp:77
Receiver clock error [m].
Definition ReceiverClockModel.hpp:37
SatelliteSystem satSys
Satellite system.
Definition ReceiverClockModel.hpp:42
bool operator==(const RecvClkBias &rhs) const
Equal comparison operator.
Definition ReceiverClockModel.hpp:40
Receiver clock drift [m/s].
Definition ReceiverClockModel.hpp:46
SatelliteSystem satSys
Satellite system.
Definition ReceiverClockModel.hpp:51
bool operator==(const RecvClkDrift &rhs) const
Equal comparison operator.
Definition ReceiverClockModel.hpp:49
Satellite System type.
Definition SatelliteSystem.hpp:44
size_t operator()(const NAV::Keys::RecvClkBias &recvClkErr) const
Hash function.
Definition ReceiverClockModel.hpp:306
size_t operator()(const NAV::Keys::RecvClkDrift &recvClkDrift) const
Hash function.
Definition ReceiverClockModel.hpp:317
Matrix which can be accessed by keys.