57template<
typename StateKeyType>
74 template<
typename Scalar,
int Size>
81 for (
const auto& key : F.
rowKeys())
83 if (
const auto* biasKey = std::get_if<Keys::RecvClkBias>(&key))
88 F(*biasKey, driftKey) = 1;
89 G(*biasKey, *biasKey) = 1;
90 G(driftKey, driftKey) = 1;
105 template<
typename Scalar,
int Size>
114 for (
const auto& key : Phi.
rowKeys())
116 if (
const auto* bias = std::get_if<Keys::RecvClkBias>(&key))
121 std::vector<StateKeyType> keys = { *bias, drift };
125 F.template block<2>(keys, keys),
126 G.template block<2>(keys, keys),
127 W.template block<2>(keys, keys),
129 Phi.template block<2>(keys, keys) = PhiMot;
130 Q.template block<2>(keys, keys) = QMot;
140 Phi(*bias, *bias) = 1;
155 std::vector<StateKeyType> keys = {
177 bool ShowGui(
float itemWidth,
float unitWidth,
const char*
id)
179 bool changed =
false;
190 0.0, 0.0,
"%.2e", ImGuiInputTextFlags_CharsScientific))
211 0.0, 0.0,
"%.2e", ImGuiInputTextFlags_CharsScientific))
234 double dt2 = std::pow(dt, 2);
235 double dt3 = dt2 * dt;
243 Q(drift, bias) = Q(bias, drift);
308struct hash<
NAV::Keys::RecvClkBias>
314 return std::hash<NAV::SatelliteSystem>()(recvClkErr.
satSys);
319struct hash<
NAV::Keys::RecvClkDrift>
325 return std::hash<NAV::SatelliteSystem>()(recvClkDrift.
satSys);
331#ifndef DOXYGEN_IGNORE
335struct fmt::formatter<
NAV::Keys::RecvClkBias> : fmt::formatter<std::string>
341 template<
typename FormatContext>
342 auto format(
const NAV::Keys::RecvClkBias& recvClkBias, FormatContext& ctx)
const
344 return fmt::formatter<std::string>::format(fmt::format(
"RecvClkBias({})", recvClkBias.
satSys), ctx);
350struct fmt::formatter<
NAV::Keys::RecvClkDrift> : fmt::formatter<std::string>
356 template<
typename FormatContext>
357 auto format(
const NAV::Keys::RecvClkDrift& recvClkDrift, FormatContext& ctx)
const
359 return fmt::formatter<std::string>::format(fmt::format(
"RecvClkDrift({})", recvClkDrift.
satSys), ctx);
#define INS_ASSERT_USER_ERROR(_EXP, _MSG)
Assert function with message.
nlohmann::json json
json namespace
Units used by the system model parameters.
Text Help Marker (?) with Tooltip.
#define LOG_DEBUG
Debug information. Should not be called on functions which receive observations (spamming)
Generalized Kalman Filter class.
std::ostream & operator<<(std::ostream &os, const NAV::Keys::RecvClkBias &obj)
Stream insertion operator overload.
Van Loan Method loan1978.
Static sized KeyedMatrix.
Receiver Clock System Model.
friend void from_json(const json &j, ReceiverClockModel &data)
Converts the provided json object into the data object.
Units::CovarianceClkFrequencyDriftUnits _gui_covarianceClkFrequencyDriftUnit
Gui selection for the Unit of the input covarianceClkFrequencyDrift parameter.
friend void to_json(json &j, const ReceiverClockModel &data)
Converts the provided data into a json object.
double _gui_covarianceClkPhaseDrift
GUI selection for the Standard deviation of the clock phase drift.
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.
std::pair< KeyedMatrix2d< StateKeyType >, KeyedMatrix2d< StateKeyType > > calcPhiAndQ(double dt, SatelliteSystem satSys, SystemModelCalcAlgorithm algorithm)
Calculates the state transition matrix (𝚽) and the process noise covariance matrix (𝐐)
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.
double _covarianceClkPhaseDrift
Covariance of the clock phase drift [m²/s].
double _covarianceClkFrequencyDrift
Covariance of the clock frequency drift [m²/s³].
Units::CovarianceClkPhaseDriftUnits _gui_covarianceClkPhaseDriftUnit
Gui selection for the Unit of the input covarianceClkPhaseDrift parameter.
double _gui_covarianceClkFrequencyDrift
GUI selection for the Standard deviation of the clock frequency drift.
void initialize()
Initializes the receiver clock model.
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.
bool ShowGui(float itemWidth, float unitWidth, const char *id)
Shows a GUI.
bool hasRow(const RowKeyType &key) const
Checks if the matrix has the key.
const std::vector< RowKeyType > & rowKeys() const
Returns the row keys.
CovarianceClkPhaseDriftUnits
Possible Units for the Standard deviation of the clock phase drift.
CovarianceClkFrequencyDriftUnits
Possible Units for the Standard deviation of the clock frequency drift.
std::pair< typename DerivedF::PlainObject, typename DerivedF::PlainObject > calcPhiAndQWithVanLoanMethod(const Eigen::MatrixBase< DerivedF > &F, const Eigen::MatrixBase< DerivedG > &G, const Eigen::MatrixBase< DerivedW > &W, double dt)
Numerical Method to calculate the State transition matrix 𝚽 and System/Process noise covariance matri...
const char * to_string(gui::widgets::PositionWithFrame::ReferenceFrame refFrame)
Converts the enum to a string.
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 𝐅𝜏ₛ
KeyedMatrix< double, RowKeyType, ColKeyType, 2, 2 > KeyedMatrix2d
Static 2x2 squared size KeyedMatrix with double types.
double convertUnit(const double &value, Units::PositionUncertaintyUnits unit)
Converts the value depending on the unit provided.
std::string MakeComboItems()
Units separated by '\0' and terminated by double '\0'.
static const internal::all_t all
Used to request all rows or columns in KeyedMatrices.
SystemModelCalcAlgorithm
Algorithms to calculate the system model with.
Receiver clock error [m].
SatelliteSystem satSys
Satellite system.
bool operator==(const RecvClkBias &rhs) const
Equal comparison operator.
Receiver clock drift [m/s].
SatelliteSystem satSys
Satellite system.
bool operator==(const RecvClkDrift &rhs) const
Equal comparison operator.
size_t operator()(const NAV::Keys::RecvClkBias &recvClkErr) const
Hash function.
size_t operator()(const NAV::Keys::RecvClkDrift &recvClkDrift) const
Hash function.
Matrix which can be accessed by keys.