Line | Branch | Exec | Source |
---|---|---|---|
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 | |||
9 | /// @file InterFrequencyBiasModel.hpp | ||
10 | /// @brief Inter Frequency Bias System Model | ||
11 | /// @author T. Topp (topp@ins.uni-stuttgart.de) | ||
12 | /// @date 2024-08-20 | ||
13 | |||
14 | #pragma once | ||
15 | |||
16 | #include "Units.hpp" | ||
17 | |||
18 | #include "Navigation/GNSS/SystemModel/SystemModel.hpp" | ||
19 | #include "util/Container/KeyedMatrix.hpp" | ||
20 | #include <fmt/format.h> | ||
21 | #include "Navigation/GNSS/SystemModel/Units.hpp" | ||
22 | #include "internal/gui/widgets/InputWithUnit.hpp" | ||
23 | #include "Navigation/GNSS/Core/Frequency.hpp" | ||
24 | |||
25 | #include "util/Logger.hpp" | ||
26 | |||
27 | namespace NAV | ||
28 | { | ||
29 | |||
30 | namespace Keys | ||
31 | { | ||
32 | |||
33 | /// @brief Inter-frequency bias | ||
34 | struct InterFreqBias | ||
35 | { | ||
36 | /// @brief Equal comparison operator | ||
37 | /// @param rhs Right-hand side | ||
38 | 21848 | bool operator==(const InterFreqBias& rhs) const { return freq == rhs.freq; } | |
39 | /// @brief Frequency | ||
40 | Frequency freq; | ||
41 | }; | ||
42 | |||
43 | } // namespace Keys | ||
44 | |||
45 | /// Inter Frequency Bias System Model | ||
46 | template<typename StateKeyType> | ||
47 | class InterFrequencyBiasModel | ||
48 | { | ||
49 | public: | ||
50 | /// @brief Initializes the inter-frequency bias | ||
51 | /// @param[in] bias Bias to init | ||
52 | /// @param[in, out] F System model matrix | ||
53 | /// @param[in, out] G Noise input matrix | ||
54 | /// @param[in, out] W Noise scale matrix | ||
55 | template<typename Scalar, int Size> | ||
56 | 10 | void initialize(Keys::InterFreqBias bias, | |
57 | KeyedMatrix<Scalar, StateKeyType, StateKeyType, Size, Size>& F, | ||
58 | KeyedMatrix<Scalar, StateKeyType, StateKeyType, Size, Size>& G, | ||
59 | KeyedMatrix<Scalar, StateKeyType, StateKeyType, Size, Size>& W) | ||
60 | { | ||
61 | // Covariance of the inter-frequency bias [m²/s] | ||
62 | 10 | _covarianceInterFrequencyBias = convertUnit(_gui_covarianceInterFrequencyBias, _gui_covarianceInterFrequencyBiasUnit); | |
63 | |||
64 |
1/2✓ Branch 3 taken 10 times.
✗ Branch 4 not taken.
|
10 | F(bias, bias) = 0; |
65 |
1/2✓ Branch 3 taken 10 times.
✗ Branch 4 not taken.
|
10 | G(bias, bias) = 1; |
66 |
1/2✓ Branch 3 taken 10 times.
✗ Branch 4 not taken.
|
10 | W(bias, bias) = _covarianceInterFrequencyBias; |
67 | 10 | } | |
68 | |||
69 | /// @brief Updates the provided Phi and Q matrix | ||
70 | /// @param[in, out] Phi State transition matrix | ||
71 | /// @param[in, out] Q System/Process noise covariance matrix | ||
72 | /// @param[in] dt Time step size in [s] | ||
73 | template<typename Scalar, int Size> | ||
74 | ✗ | void updatePhiAndQ(KeyedMatrix<Scalar, StateKeyType, StateKeyType, Size, Size>& Phi, | |
75 | KeyedMatrix<Scalar, StateKeyType, StateKeyType, Size, Size>& Q, | ||
76 | double dt) | ||
77 | { | ||
78 | ✗ | for (const auto& key : Phi.rowKeys()) | |
79 | { | ||
80 | ✗ | if (const auto* bias = std::get_if<Keys::InterFreqBias>(&key)) | |
81 | { | ||
82 | ✗ | Phi(*bias, *bias) = 1; | |
83 | ✗ | Q(*bias, *bias) = _covarianceInterFrequencyBias * dt; | |
84 | } | ||
85 | } | ||
86 | ✗ | } | |
87 | |||
88 | /// @brief Calculates the state transition matrix (𝚽) and the process noise covariance matrix (𝐐) | ||
89 | /// @param[in] dt Time step size in [s] | ||
90 | /// @param[in] freq Frequency to use | ||
91 | /// @return Phi and Q matrix | ||
92 | [[nodiscard]] std::pair<double, double> calcPhiAndQ(double dt, const Frequency& freq) | ||
93 | { | ||
94 | std::vector<StateKeyType> key = { Keys::InterFreqBias{ freq } }; | ||
95 | |||
96 | KeyedMatrix<double, StateKeyType, StateKeyType, 1, 1> Phi(Eigen::Matrix<double, 1, 1>::Zero(), key, key); | ||
97 | KeyedMatrix<double, StateKeyType, StateKeyType, 1, 1> Q(Eigen::Matrix<double, 1, 1>::Zero(), key, key); | ||
98 | updatePhiAndQ(Phi, Q, dt); | ||
99 | |||
100 | return { Phi(all, all)(0), Q(all, all)(0) }; | ||
101 | } | ||
102 | |||
103 | /// @brief Shows a GUI | ||
104 | /// @param[in] itemWidth Width of the space for the config items | ||
105 | /// @param[in] unitWidth Width of the units | ||
106 | /// @param[in] id Unique id for ImGui | ||
107 | /// @return True if something was changed | ||
108 | ✗ | bool ShowGui(float itemWidth, float unitWidth, const char* id) | |
109 | { | ||
110 | ✗ | bool changed = false; | |
111 | |||
112 | ✗ | if (gui::widgets::InputDoubleWithUnit(fmt::format("{} of the inter-frequency bias (RW)##{}", | |
113 | ✗ | _gui_covarianceInterFrequencyBiasUnit == Units::CovarianceClkPhaseDriftUnits::m_sqrts | |
114 | ✗ | ? "StdDev" | |
115 | : "Variance", | ||
116 | id) | ||
117 | .c_str(), | ||
118 | itemWidth, unitWidth, &_gui_covarianceInterFrequencyBias, | ||
119 | ✗ | _gui_covarianceInterFrequencyBiasUnit, | |
120 | MakeComboItems<Units::CovarianceClkPhaseDriftUnits>().c_str(), | ||
121 | 0.0, 0.0, "%.2e", ImGuiInputTextFlags_CharsScientific)) | ||
122 | { | ||
123 | ✗ | LOG_DEBUG("{}: _gui_covarianceInterFrequencyBias changed to {}", id, _gui_covarianceInterFrequencyBias); | |
124 | ✗ | LOG_DEBUG("{}: _gui_covarianceInterFrequencyBiasUnit changed to {}", id, to_string(_gui_covarianceInterFrequencyBiasUnit)); | |
125 | ✗ | changed = true; | |
126 | } | ||
127 | |||
128 | ✗ | return changed; | |
129 | } | ||
130 | |||
131 | private: | ||
132 | /// Gui selection for the Unit of the inter-frequency covarianceInterFrequencyBias parameter | ||
133 | Units::CovarianceClkPhaseDriftUnits _gui_covarianceInterFrequencyBiasUnit = Units::CovarianceClkPhaseDriftUnits::m2_s; | ||
134 | |||
135 | /// @brief GUI selection for the Standard deviation of the inter-frequency bias | ||
136 | double _gui_covarianceInterFrequencyBias = 1e-6 /* [m²/s] */; | ||
137 | /// @brief Covariance of the inter-frequency bias [m²/s] | ||
138 | double _covarianceInterFrequencyBias = 1e-6; | ||
139 | |||
140 | /// @brief Converts the provided data into a json object | ||
141 | /// @param[out] j Json object which gets filled with the info | ||
142 | /// @param[in] data Data to convert into json | ||
143 | ✗ | friend void to_json(json& j, const InterFrequencyBiasModel& data) | |
144 | { | ||
145 | ✗ | j = { | |
146 | ✗ | { "covarianceInterFrequencyBiasUnit", data._gui_covarianceInterFrequencyBiasUnit }, | |
147 | ✗ | { "covarianceInterFrequencyBias", data._gui_covarianceInterFrequencyBias }, | |
148 | }; | ||
149 | ✗ | } | |
150 | |||
151 | /// @brief Converts the provided json object into the data object | ||
152 | /// @param[in] j Json object with the needed values | ||
153 | /// @param[out] data Object to fill from the json | ||
154 | 1 | friend void from_json(const json& j, InterFrequencyBiasModel& data) | |
155 | { | ||
156 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
1 | if (j.contains("covarianceInterFrequencyBiasUnit")) { j.at("covarianceInterFrequencyBiasUnit").get_to(data._gui_covarianceInterFrequencyBiasUnit); } |
157 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
1 | if (j.contains("covarianceInterFrequencyBias")) { j.at("covarianceInterFrequencyBias").get_to(data._gui_covarianceInterFrequencyBias); } |
158 | 1 | } | |
159 | }; | ||
160 | |||
161 | } // namespace NAV | ||
162 | |||
163 | /// @brief Stream insertion operator overload | ||
164 | /// @param[in, out] os Output stream object to stream the time into | ||
165 | /// @param[in] obj Object to print | ||
166 | /// @return Returns the output stream object in order to chain stream insertions | ||
167 | std::ostream& operator<<(std::ostream& os, const NAV::Keys::InterFreqBias& obj); | ||
168 | |||
169 | namespace std | ||
170 | { | ||
171 | |||
172 | /// @brief Hash function (needed for unordered_map) | ||
173 | template<> | ||
174 | struct hash<NAV::Keys::InterFreqBias> | ||
175 | { | ||
176 | /// @brief Hash function | ||
177 | /// @param[in] interFreqBias Inter-frequency bias | ||
178 | 38518 | size_t operator()(const NAV::Keys::InterFreqBias& interFreqBias) const | |
179 | { | ||
180 | 38518 | return std::hash<NAV::Frequency>()(interFreqBias.freq); | |
181 | } | ||
182 | }; | ||
183 | |||
184 | } // namespace std | ||
185 | |||
186 | #ifndef DOXYGEN_IGNORE | ||
187 | |||
188 | /// @brief Formatter | ||
189 | template<> | ||
190 | struct fmt::formatter<NAV::Keys::InterFreqBias> : fmt::formatter<std::string> | ||
191 | { | ||
192 | /// @brief Defines how to format structs | ||
193 | /// @param[in] interFreqBias Struct to format | ||
194 | /// @param[in, out] ctx Format context | ||
195 | /// @return Output iterator | ||
196 | template<typename FormatContext> | ||
197 | ✗ | auto format(const NAV::Keys::InterFreqBias& interFreqBias, FormatContext& ctx) const | |
198 | { | ||
199 | ✗ | return fmt::formatter<std::string>::format(fmt::format("InterFreqBias({})", interFreqBias.freq), ctx); | |
200 | } | ||
201 | }; | ||
202 | |||
203 | #endif | ||
204 |