INSTINCT Code Coverage Report


Directory: src/
File: Navigation/GNSS/SystemModel/InterFrequencyBiasModel.hpp
Date: 2025-06-02 15:19:59
Exec Total Coverage
Lines: 12 39 30.8%
Functions: 4 9 44.4%
Branches: 3 36 8.3%

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