0.3.0
Loading...
Searching...
No Matches
ReceiverClockModel.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
16#include <set>
17#include <vector>
18
19#include "Units.hpp"
22#include "util/Assert.h"
29
30namespace NAV
31{
32namespace Keys
33{
34
37{
40 bool operator==(const RecvClkBias& rhs) const { return satSys == rhs.satSys; }
43};
46{
49 bool operator==(const RecvClkDrift& rhs) const { return satSys == rhs.satSys; }
52};
53
54} // namespace Keys
55
57template<typename StateKeyType>
59{
60 public:
65 template<typename Scalar, int Size>
69 {
70 // Covariance of the clock phase drift [m²/s]
72 // Covariance of the frequency phase drift [m²/s³]
74
75 for (const auto& key : F.rowKeys())
76 {
77 if (const auto* biasKey = std::get_if<Keys::RecvClkBias>(&key))
78 {
79 auto driftKey = Keys::RecvClkDrift{ biasKey->satSys };
80 INS_ASSERT_USER_ERROR(F.hasRow(driftKey), "The model should have bias and drift");
81
82 F(*biasKey, driftKey) = 1;
83 G(*biasKey, *biasKey) = 1;
84 G(driftKey, driftKey) = 1;
85 W(*biasKey, *biasKey) = _covarianceClkPhaseDrift;
86 W(driftKey, driftKey) = _covarianceClkFrequencyDrift;
87 }
88 }
89 }
90
99 template<typename Scalar, int Size>
105 double dt,
106 SystemModelCalcAlgorithm algorithm) const
107 {
108 for (const auto& key : Phi.rowKeys())
109 {
110 if (const auto* bias = std::get_if<Keys::RecvClkBias>(&key))
111 {
112 auto drift = Keys::RecvClkDrift{ bias->satSys };
113 if (Phi.hasRow(drift))
114 {
115 std::vector<StateKeyType> keys = { *bias, drift };
116 if (algorithm == SystemModelCalcAlgorithm::VanLoan)
117 {
118 auto [PhiMot, QMot] = NAV::calcPhiAndQWithVanLoanMethod(
119 F.template block<2>(keys, keys),
120 G.template block<2>(keys, keys),
121 W.template block<2>(keys, keys),
122 dt);
123 Phi.template block<2>(keys, keys) = PhiMot;
124 Q.template block<2>(keys, keys) = QMot;
125 }
126 else // QCalculationAlgorithm::Taylor1
127 {
128 Phi.template block<2>(keys, keys) = transitionMatrix_Phi_Taylor(F.template block<2>(keys, keys), dt, 1);
129 Q.template block<2>(keys, keys) = calcProcessNoiseMatrixTaylor(dt, bias->satSys, keys)(all, all);
130 }
131 }
132 else
133 {
134 Phi(*bias, *bias) = 1;
135 Q(*bias, *bias) = _covarianceClkPhaseDrift * dt;
136 }
137 }
138 }
139 }
140
146 [[nodiscard]] std::pair<KeyedMatrix2d<StateKeyType>, KeyedMatrix2d<StateKeyType>>
148 {
149 std::vector<StateKeyType> keys = {
150 Keys::RecvClkBias{ satSys },
151 Keys::RecvClkDrift{ satSys },
152 };
153
154 KeyedMatrix2d<StateKeyType> F(Eigen::Matrix2d::Zero(), keys, keys);
155 KeyedMatrix2d<StateKeyType> G(Eigen::Matrix2d::Zero(), keys, keys);
156 KeyedMatrix2d<StateKeyType> W(Eigen::Matrix2d::Zero(), keys, keys);
157 initialize(F, G, W);
158
159 KeyedMatrix2d<StateKeyType> Phi(Eigen::Matrix2d::Zero(), keys, keys);
160 KeyedMatrix2d<StateKeyType> Q(Eigen::Matrix2d::Zero(), keys, keys);
161 updatePhiAndQ(Phi, Q, F, G, W, dt, algorithm);
162
163 return { Phi, Q };
164 }
165
171 bool ShowGui(float itemWidth, float unitWidth, const char* id)
172 {
173 bool changed = false;
174
175 if (gui::widgets::InputDoubleWithUnit(fmt::format("{} of the receiver clock phase drift (RW)##{}",
176 _gui_covarianceClkPhaseDriftUnit == Units::CovarianceClkPhaseDriftUnits::m_sqrts
177 ? "StdDev"
178 : "Variance",
179 id)
180 .c_str(),
181 itemWidth, unitWidth, &_gui_covarianceClkPhaseDrift,
183 MakeComboItems<Units::CovarianceClkPhaseDriftUnits>().c_str(),
184 0.0, 0.0, "%.2e", ImGuiInputTextFlags_CharsScientific))
185 {
186 LOG_DEBUG("{}: _gui_covarianceClkPhaseDrift changed to {}", id, _gui_covarianceClkPhaseDrift);
187 LOG_DEBUG("{}: _gui_covarianceClkPhaseDriftUnit changed to {}", id, to_string(_gui_covarianceClkPhaseDriftUnit));
188 changed = true;
189 }
190 ImGui::SameLine();
191 gui::widgets::HelpMarker(fmt::format("Typical values for a TCXO are {} {}",
192 _gui_covarianceClkPhaseDriftUnit == Units::CovarianceClkPhaseDriftUnits::m_sqrts ? 0.1 : 0.01,
194 .c_str());
195
196 if (gui::widgets::InputDoubleWithUnit(fmt::format("{} of the receiver clock frequency drift (IRW)##{}",
197 _gui_covarianceClkFrequencyDriftUnit == Units::CovarianceClkFrequencyDriftUnits::m_sqrts3
198 ? "StdDev"
199 : "Variance",
200 id)
201 .c_str(),
202 itemWidth, unitWidth, &_gui_covarianceClkFrequencyDrift,
204 MakeComboItems<Units::CovarianceClkFrequencyDriftUnits>().c_str(),
205 0.0, 0.0, "%.2e", ImGuiInputTextFlags_CharsScientific))
206 {
207 LOG_DEBUG("{}: _gui_covarianceClkFrequencyDrift changed to {}", id, _gui_covarianceClkFrequencyDrift);
208 LOG_DEBUG("{}: _gui_covarianceClkFrequencyDriftUnit changed to {}", id, to_string(_gui_covarianceClkFrequencyDriftUnit));
209 changed = true;
210 }
211 ImGui::SameLine();
212 gui::widgets::HelpMarker(fmt::format("Typical values for a TCXO are {} {}",
213 _gui_covarianceClkFrequencyDriftUnit == Units::CovarianceClkFrequencyDriftUnits::m_sqrts3 ? 0.2 : 0.04,
215 .c_str());
216
217 return changed;
218 }
219
220 private:
226 calcProcessNoiseMatrixTaylor(double dt, const SatelliteSystem& satSys, const std::vector<StateKeyType>& keys) const
227 {
228 double dt2 = std::pow(dt, 2);
229 double dt3 = dt2 * dt;
230
231 KeyedMatrix<double, StateKeyType, StateKeyType, 2, 2> Q(Eigen::Matrix<double, 2, 2>::Zero(), keys, keys);
232
233 auto bias = Keys::RecvClkBias{ satSys };
234 auto drift = Keys::RecvClkDrift{ satSys };
235 Q(bias, bias) = _covarianceClkPhaseDrift * dt + _covarianceClkFrequencyDrift * dt3 / 3.0;
236 Q(bias, drift) = _covarianceClkFrequencyDrift * dt2 / 2.0;
237 Q(drift, bias) = Q(bias, drift);
238 Q(drift, drift) = _covarianceClkFrequencyDrift * dt;
239
240 return Q;
241 }
245 double _gui_covarianceClkPhaseDrift = 0.01 /*[ m^2 / s ] */;
246
249
253 double _gui_covarianceClkFrequencyDrift = 0.04 /* [ m^2 / s^3 ] */;
254
257
261 friend void to_json(json& j, const ReceiverClockModel& data)
262 {
263 j = {
264 { "covarianceClkPhaseDriftUnit", data._gui_covarianceClkPhaseDriftUnit },
265 { "covarianceClkPhaseDrift", data._gui_covarianceClkPhaseDrift },
266 { "covarianceClkFrequencyDriftUnit", data._gui_covarianceClkFrequencyDriftUnit },
267 { "covarianceClkFrequencyDrift", data._gui_covarianceClkFrequencyDrift },
268 };
269 }
270
274 friend void from_json(const json& j, ReceiverClockModel& data)
275 {
276 if (j.contains("covarianceClkPhaseDriftUnit")) { j.at("covarianceClkPhaseDriftUnit").get_to(data._gui_covarianceClkPhaseDriftUnit); }
277 if (j.contains("covarianceClkPhaseDrift")) { j.at("covarianceClkPhaseDrift").get_to(data._gui_covarianceClkPhaseDrift); }
278 if (j.contains("covarianceClkFrequencyDriftUnit")) { j.at("covarianceClkFrequencyDriftUnit").get_to(data._gui_covarianceClkFrequencyDriftUnit); }
279 if (j.contains("covarianceClkFrequencyDrift")) { j.at("covarianceClkFrequencyDrift").get_to(data._gui_covarianceClkFrequencyDrift); }
280 }
281};
282
283} // namespace NAV
284
289std::ostream& operator<<(std::ostream& os, const NAV::Keys::RecvClkBias& obj);
290
295std::ostream& operator<<(std::ostream& os, const NAV::Keys::RecvClkDrift& obj);
296
297namespace std
298{
299
301template<>
302struct hash<NAV::Keys::RecvClkBias>
303{
306 size_t operator()(const NAV::Keys::RecvClkBias& recvClkErr) const
307 {
308 return std::hash<NAV::SatelliteSystem>()(recvClkErr.satSys);
309 }
310};
312template<>
313struct hash<NAV::Keys::RecvClkDrift>
314{
317 size_t operator()(const NAV::Keys::RecvClkDrift& recvClkDrift) const
318 {
319 return std::hash<NAV::SatelliteSystem>()(recvClkDrift.satSys);
320 }
321};
322
323} // namespace std
324
325#ifndef DOXYGEN_IGNORE
326
328template<>
329struct fmt::formatter<NAV::Keys::RecvClkBias> : fmt::formatter<std::string>
330{
335 template<typename FormatContext>
336 auto format(const NAV::Keys::RecvClkBias& recvClkBias, FormatContext& ctx) const
337 {
338 return fmt::formatter<std::string>::format(fmt::format("RecvClkBias({})", recvClkBias.satSys), ctx);
339 }
340};
341
343template<>
344struct fmt::formatter<NAV::Keys::RecvClkDrift> : fmt::formatter<std::string>
345{
350 template<typename FormatContext>
351 auto format(const NAV::Keys::RecvClkDrift& recvClkDrift, FormatContext& ctx) const
352 {
353 return fmt::formatter<std::string>::format(fmt::format("RecvClkDrift({})", recvClkDrift.satSys), ctx);
354 }
355};
356
357#endif
Assertion helpers.
#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.
Defines Widgets which allow the input of values and the selection of the unit.
#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
const char * to_string(gui::widgets::PositionWithFrame::ReferenceFrame refFrame)
Converts the enum to a string.
std::ostream & operator<<(std::ostream &os, const NAV::Keys::RecvClkBias &obj)
Stream insertion operator overload.
GNSS Satellite System.
System Model.
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.