0.3.0
Loading...
Searching...
No Matches
ErrorModel.cpp
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
9#include "ErrorModel.hpp"
10
11#include <algorithm>
12#include <imgui.h>
13#include <imgui_internal.h>
14#include <limits>
15#include <set>
16#include <type_traits>
17
18#include "NodeRegistry.hpp"
21namespace nm = NAV::NodeManager;
23
26
30
35
36#include "util/Eigen.hpp"
37#include "util/StringUtil.hpp"
38
39// ---------------------------------------------------------- Private variabels ------------------------------------------------------------
40
41namespace NAV
42{
43/// List of supported data identifiers
44const std::vector<std::string> supportedDataIdentifier{
48};
49
50} // namespace NAV
51
52// ---------------------------------------------------------- Member functions -------------------------------------------------------------
53
55 : Node(typeStatic())
56{
57 LOG_TRACE("{}: called", name);
58 _hasConfig = true;
59 _guiConfigDefaultWindowSize = { 812, 530 };
60
62
64
65 std::mt19937_64 gen(static_cast<uint64_t>(std::chrono::system_clock::now().time_since_epoch().count()));
66 std::uniform_int_distribution<uint64_t> dist(0, std::numeric_limits<uint64_t>::max() / 2);
67
68 _imuAccelerometerRng.seed = dist(gen);
69 _imuGyroscopeRng.seed = dist(gen);
70
71 _imuAccelerometerRWRng.seed = dist(gen);
72 _imuGyroscopeRWRng.seed = dist(gen);
73 _imuAccelerometerIRWRng.seed = dist(gen);
74 _imuGyroscopeIRWRng.seed = dist(gen);
75
76 _positionRng.seed = dist(gen);
77 _velocityRng.seed = dist(gen);
78 _attitudeRng.seed = dist(gen);
79
80 _pseudorangeRng.seed = dist(gen);
81 _carrierPhaseRng.seed = dist(gen);
82 _dopplerRng.seed = dist(gen);
83 _ambiguityRng.seed = dist(gen);
84 _cycleSlipRng.seed = dist(gen);
85}
86
88{
89 LOG_TRACE("{}: called", nameId());
90}
91
93{
94 return "ErrorModel";
95}
96
97std::string NAV::ErrorModel::type() const
98{
99 return typeStatic();
100}
101
103{
104 return "Data Processor";
105}
106
108{
109 if (outputPins.front().dataIdentifier.size() != 1
110 || !inputPins.front().isPinLinked())
111 {
112 ImGui::TextUnformatted("Please connect the input pin to show the options");
113 return;
114 }
115
116 float itemWidth = 470 * gui::NodeEditorApplication::windowFontRatio();
117 float unitWidth = 180 * gui::NodeEditorApplication::windowFontRatio();
118
119 auto inputDoubleWithUnit = [&](const char* title, double& data, auto& unit, const char* combo_items_separated_by_zeros, const char* format) {
120 if (auto response = gui::widgets::InputDoubleWithUnit(fmt::format("{}##{}", title, size_t(id)).c_str(), itemWidth, unitWidth,
121 &data, unit, combo_items_separated_by_zeros, 0.0, 0.0,
122 format, ImGuiInputTextFlags_CharsScientific))
123 {
124 if (response == gui::widgets::InputWithUnitChange_Input) { LOG_DEBUG("{}: {} changed to {}", nameId(), title, data); }
125 if (response == gui::widgets::InputWithUnitChange_Unit) { LOG_DEBUG("{}: {} unit changed to {}", nameId(), title, fmt::underlying(unit)); }
127 }
128 };
129
130 auto inputVector3WithUnit = [&](const char* title, Eigen::Vector3d& data, auto& unit, const char* combo_items_separated_by_zeros, const char* format) {
131 if (auto response = gui::widgets::InputDouble3WithUnit(fmt::format("{}##{}", title, size_t(id)).c_str(), itemWidth, unitWidth,
132 data.data(), unit, combo_items_separated_by_zeros,
133 format, ImGuiInputTextFlags_CharsScientific))
134 {
135 if (response == gui::widgets::InputWithUnitChange_Input) { LOG_DEBUG("{}: {} changed to {}", nameId(), title, data.transpose()); }
136 if (response == gui::widgets::InputWithUnitChange_Unit) { LOG_DEBUG("{}: {} unit changed to {}", nameId(), title, fmt::underlying(unit)); }
138 }
139 };
140
141 auto rngInput = [&](const char* title, RandomNumberGenerator& rng) {
142 float currentCursorX = ImGui::GetCursorPosX();
143 if (ImGui::Checkbox(fmt::format("##rng.useSeed {} {}", title, size_t(id)).c_str(), &rng.useSeed))
144 {
145 LOG_DEBUG("{}: {} rng.useSeed changed to {}", nameId(), title, rng.useSeed);
147 }
148 if (ImGui::IsItemHovered()) { ImGui::SetTooltip("Use seed?"); }
149 ImGui::SameLine();
150 if (!rng.useSeed)
151 {
152 ImGui::BeginDisabled();
153 }
154 ImGui::SetNextItemWidth(itemWidth - (ImGui::GetCursorPosX() - currentCursorX));
155 if (ImGui::SliderULong(fmt::format("{} Seed##{}", title, size_t(id)).c_str(), &rng.seed, 0, std::numeric_limits<uint64_t>::max() / 2, "%lu"))
156 {
157 LOG_DEBUG("{}: {} rng.seed changed to {}", nameId(), title, rng.seed);
159 }
160 if (!rng.useSeed)
161 {
162 ImGui::EndDisabled();
163 }
164 };
165
166 auto noiseGuiInput = [&]<typename T>(const char* title, T& data, auto& unit, const char* combo_items_separated_by_zeros, const char* format, RandomNumberGenerator& rng) {
167 if constexpr (std::is_same_v<T, double>) { inputDoubleWithUnit(title, data, unit, combo_items_separated_by_zeros, format); }
168 else if constexpr (std::is_same_v<T, Eigen::Vector3d>) { inputVector3WithUnit(title, data, unit, combo_items_separated_by_zeros, format); }
169
170 rngInput(title, rng);
171 };
172
173 if (NAV::NodeRegistry::NodeDataTypeAnyIsChildOf(outputPins.front().dataIdentifier, { ImuObs::type() })
174 || NAV::NodeRegistry::NodeDataTypeAnyIsChildOf(outputPins.front().dataIdentifier, { Pos::type() }))
175 {
176 ImGui::TextUnformatted("Offsets:");
177 ImGui::Indent();
178 {
179 if (NAV::NodeRegistry::NodeDataTypeAnyIsChildOf(outputPins.front().dataIdentifier, { ImuObs::type() }))
180 {
181 inputVector3WithUnit("Accelerometer Bias (platform)", _imuAccelerometerBias_p, _imuAccelerometerBiasUnit, MakeComboItems<Units::ImuAccelerometerUnits>().c_str(), "%.2g");
182 inputVector3WithUnit("Gyroscope Bias (platform)", _imuGyroscopeBias_p, _imuGyroscopeBiasUnit, MakeComboItems<Units::ImuGyroscopeUnits>().c_str(), "%.2g");
183 }
184 else if (NAV::NodeRegistry::NodeDataTypeAnyIsChildOf(outputPins.front().dataIdentifier, { Pos::type() }))
185 {
186 inputVector3WithUnit(fmt::format("Position Bias ({})", _positionBiasUnit == PositionBiasUnits::meter ? "NED" : "LatLonAlt").c_str(),
187 _positionBias, _positionBiasUnit, "m, m, m\0\0", "%.2g");
188 if (NAV::NodeRegistry::NodeDataTypeAnyIsChildOf(outputPins.front().dataIdentifier, { PosVel::type() }))
189 {
190 inputVector3WithUnit("Velocity Bias (NED)", _velocityBias, _velocityBiasUnit, "m/s\0\0", "%.2g");
191 if (NAV::NodeRegistry::NodeDataTypeAnyIsChildOf(outputPins.front().dataIdentifier, { PosVelAtt::type() }))
192 {
193 inputVector3WithUnit("RollPitchYaw Bias", _attitudeBias, _attitudeBiasUnit, "rad\0deg\0\0", "%.2g");
194 }
195 }
196 }
197 }
198 ImGui::Unindent();
199 }
200
201 if (NAV::NodeRegistry::NodeDataTypeAnyIsChildOf(outputPins.front().dataIdentifier, { ImuObs::type() })
202 || NAV::NodeRegistry::NodeDataTypeAnyIsChildOf(outputPins.front().dataIdentifier, { Pos::type() })
203 || NAV::NodeRegistry::NodeDataTypeAnyIsChildOf(outputPins.front().dataIdentifier, { GnssObs::type() }))
204 {
205 ImGui::TextUnformatted("Measurement noise:");
206 ImGui::Indent();
207 {
208 if (NAV::NodeRegistry::NodeDataTypeAnyIsChildOf(outputPins.front().dataIdentifier, { ImuObs::type() }))
209 {
210 noiseGuiInput("Accelerometer Noise (Std. dev)", _imuAccelerometerNoise, _imuAccelerometerNoiseUnit, MakeComboItems<Units::ImuAccelerometerNoiseUnits>().c_str(), "%.2g", _imuAccelerometerRng);
211 noiseGuiInput("Gyroscope Noise (Std. dev)", _imuGyroscopeNoise, _imuGyroscopeNoiseUnit, MakeComboItems<Units::ImuGyroscopeNoiseUnits>().c_str(), "%.2g", _imuGyroscopeRng);
212 }
213 else if (NAV::NodeRegistry::NodeDataTypeAnyIsChildOf(outputPins.front().dataIdentifier, { Pos::type() }))
214 {
215 noiseGuiInput(fmt::format("Position Noise ({})", _positionNoiseUnit == PositionNoiseUnits::meter
216 ? "Standard deviation"
217 : "Variance")
218 .c_str(),
219 _positionNoise, _positionNoiseUnit, "m, m, m\0m^2, m^2, m^2\0\0",
220 "%.2g", _positionRng);
221 if (NAV::NodeRegistry::NodeDataTypeAnyIsChildOf(outputPins.front().dataIdentifier, { PosVel::type() }))
222 {
223 noiseGuiInput(fmt::format("Velocity Noise ({})", _velocityNoiseUnit == VelocityNoiseUnits::m_s ? "Standard deviation"
224 : "Variance")
225 .c_str(),
226 _velocityNoise, _velocityNoiseUnit, "m/s\0m^2/s^2\0\0", "%.2g", _velocityRng);
227 if (NAV::NodeRegistry::NodeDataTypeAnyIsChildOf(outputPins.front().dataIdentifier, { PosVelAtt::type() }))
228 {
229 noiseGuiInput(fmt::format("Attitude Noise ({})", _attitudeNoiseUnit == AttitudeNoiseUnits::rad || _attitudeNoiseUnit == AttitudeNoiseUnits::deg
230 ? "Standard deviation"
231 : "Variance")
232 .c_str(),
233 _attitudeNoise, _attitudeNoiseUnit, "rad\0deg\0rad^2\0deg^2\0\0", "%.2g", _attitudeRng);
234 }
235 }
236 }
237 else if (NAV::NodeRegistry::NodeDataTypeAnyIsChildOf(outputPins.front().dataIdentifier, { GnssObs::type() }))
238 {
239 noiseGuiInput("Pseudorange Noise", _gui_pseudorangeNoise, _gui_pseudorangeNoiseUnit, "m\0\0", "%.3g", _pseudorangeRng);
240 noiseGuiInput("Carrier-phase Noise", _gui_carrierPhaseNoise, _gui_carrierPhaseNoiseUnit, "m\0\0", "%.3g", _carrierPhaseRng);
241 noiseGuiInput("Doppler/Range-rate Noise", _gui_dopplerNoise, _gui_dopplerNoiseUnit, "m/s\0\0", "%.3g", _dopplerRng);
242 }
243 }
244 ImGui::Unindent();
245 }
246 if (NAV::NodeRegistry::NodeDataTypeAnyIsChildOf(outputPins.front().dataIdentifier, { ImuObs::type() }))
247 {
248 ImGui::TextUnformatted("Random walk noise:");
249 ImGui::Indent();
250 noiseGuiInput("Accelerometer RW (Std. dev)", _imuAccelerometerRW, _imuAccelerometerRWUnit, MakeComboItems<Units::ImuAccelerometerNoiseUnits>().c_str(), "%.2g", _imuAccelerometerRWRng);
251 noiseGuiInput("Gyroscope RW (Std. dev)", _imuGyroscopeRW, _imuGyroscopeRWUnit, MakeComboItems<Units::ImuGyroscopeNoiseUnits>().c_str(), "%.2g", _imuGyroscopeRWRng);
252 ImGui::Unindent();
253 ImGui::TextUnformatted("Integrated Random walk noise:");
254 ImGui::Indent();
255 noiseGuiInput("Accelerometer IRW (Std. dev)", _imuAccelerometerIRW, _imuAccelerometerIRWUnit, MakeComboItems<Units::ImuAccelerometerIRWUnits>().c_str(), "%.2g", _imuAccelerometerIRWRng);
256 noiseGuiInput("Gyroscope IRW (Std. dev)", _imuGyroscopeIRW, _imuGyroscopeIRWUnit, MakeComboItems<Units::ImuGyroscopeIRWUnits>().c_str(), "%.2g", _imuGyroscopeIRWRng);
257 ImGui::Unindent();
258 }
259
260 if (NAV::NodeRegistry::NodeDataTypeAnyIsChildOf(outputPins.front().dataIdentifier, { GnssObs::type() }))
261 {
262 ImGui::TextUnformatted("Ambiguities:");
263 ImGui::Indent();
264 {
265 ImGui::SetNextItemWidth((itemWidth - ImGui::GetStyle().ItemInnerSpacing.x) / 2.0F);
266 if (ImGui::InputIntL(fmt::format("##Ambiguity Bounds lower {}", size_t(id)).c_str(), _gui_ambiguityLimits.data(),
267 std::numeric_limits<int>::lowest(), _gui_ambiguityLimits[1], 0, 0))
268 {
269 LOG_DEBUG("{}: Ambiguity lower bound changed to {}", nameId(), _gui_ambiguityLimits[0]);
271 }
272 ImGui::SameLine();
273 ImGui::SetCursorPosX(ImGui::GetCursorPosX() - ImGui::GetStyle().ItemSpacing.x + ImGui::GetStyle().ItemInnerSpacing.x);
274 ImGui::SetNextItemWidth((itemWidth - ImGui::GetStyle().ItemInnerSpacing.x) / 2.0F);
275 if (ImGui::InputIntL(fmt::format("Ambiguity Bounds##Ambiguity Bounds upper{}", size_t(id)).c_str(), &_gui_ambiguityLimits[1],
276 _gui_ambiguityLimits[0], std::numeric_limits<int>::max(), 0, 0))
277 {
278 LOG_DEBUG("{}: Ambiguity upper bound changed to {}", nameId(), _gui_ambiguityLimits[1]);
280 }
281 rngInput("Ambiguity", _ambiguityRng);
282 }
283 ImGui::Unindent();
284
285 ImGui::TextUnformatted("Cycle-slip:");
286 ImGui::Indent();
287 {
288 noiseGuiInput("Frequency", _gui_cycleSlipFrequency, _gui_cycleSlipFrequencyUnit, "/ day\0/ hour\0/ minute\0\0", "%.2g", _cycleSlipRng);
289
290 if (auto response = gui::widgets::SliderDoubleWithUnit(fmt::format("Detection probability (LLI)##{}", size_t(id)).c_str(), itemWidth, unitWidth,
293 {
294 if (response == gui::widgets::InputWithUnitChange_Input) { LOG_DEBUG("{}: Detection probability (LLI) changed to {}", nameId(), _gui_cycleSlipDetectionProbability); }
295 if (response == gui::widgets::InputWithUnitChange_Unit) { LOG_DEBUG("{}: Detection probability (LLI) unit changed to {}", nameId(), fmt::underlying(_gui_cycleSlipDetectionProbabilityUnit)); }
297 }
298 ImGui::SameLine();
299 gui::widgets::HelpMarker("The chance that the Lock-of-Loss (LLI) indicator is set, when a cycle-slip occurs");
300
301 ImGui::SetNextItemWidth(itemWidth);
302 if (ImGui::DragInt(fmt::format("Ambiguity Range to slip to##{}", size_t(id)).c_str(), &_gui_cycleSlipRange,
303 1.0F, 1, std::numeric_limits<int>::max(), "+/- %d"))
304 {
305 LOG_DEBUG("{}: Cycle-slip ambiguity range changed to {}", nameId(), _gui_cycleSlipRange);
307 }
308 ImGui::SameLine();
309 gui::widgets::HelpMarker("If the ambiguity range is set, the cycle-slips are bound by it too");
310
311 ImGui::SetNextItemWidth(itemWidth);
312 if (ShowFrequencySelector(fmt::format("Satellite Frequencies##{}", size_t(id)).c_str(), _filterFreq))
313 {
315 }
316 ImGui::SameLine();
317 gui::widgets::HelpMarker("Frequency and code selection only affects the cycle-slip simulation");
318
319 ImGui::SetNextItemWidth(itemWidth);
320 if (ShowCodeSelector(fmt::format("Signal Codes##{}", size_t(id)).c_str(), _filterCode, _filterFreq))
321 {
323 }
324 }
325 ImGui::Unindent();
326
327 ImGui::SetNextItemOpen(true, ImGuiCond_FirstUseEver);
328 if (ImGui::TreeNode(fmt::format("Simulated Ambiguities and Cycle-slips##{}", size_t(id)).c_str()))
329 {
330 auto nAmb = static_cast<int>(_ambiguities.size());
331 if (nAmb > 0)
332 {
333 std::set<InsTime> ambiguityTimes;
334 for (int i = 0; i < nAmb; i++)
335 {
336 const auto& ambVec = std::next(_ambiguities.begin(), i)->second;
337 for (const auto& amb : ambVec)
338 {
339 ambiguityTimes.insert(amb.first);
340 }
341 }
342 if (ambiguityTimes.size() < 64 - 1)
343 {
344 ImGui::PushFont(Application::MonoFont());
345
346 if (ImGui::BeginTable(fmt::format("Ambiguities##{}", size_t(id)).c_str(), static_cast<int>(ambiguityTimes.size() + 1),
347 ImGuiTableFlags_Borders | ImGuiTableFlags_NoHostExtendX | ImGuiTableFlags_SizingFixedFit | ImGuiTableFlags_ScrollX | ImGuiTableFlags_ScrollY,
348 ImVec2(0.0F, 300.0F * gui::NodeEditorApplication::monoFontRatio())))
349 {
350 ImGui::TableSetupColumn("");
351 for (const auto& time : ambiguityTimes)
352 {
353 auto t = time.toYMDHMS(GPST);
354 t.sec = std::round(t.sec * 1e2) / 1e2;
355 ImGui::TableSetupColumn(str::replaceAll_copy(fmt::format("{}", t), " ", "\n").c_str());
356 }
357 ImGui::TableSetupScrollFreeze(1, 1);
358 ImGui::TableHeadersRow();
359
360 for (int i = 0; i < nAmb; i++)
361 {
362 ImGui::TableNextRow();
363 ImGui::TableNextColumn();
364 const auto& ambiguities = std::next(_ambiguities.begin(), i);
365 if (ambiguities == _ambiguities.end()) { break; }
366 ImGui::TextUnformatted(fmt::format("{}", ambiguities->first).c_str());
367 ImGui::TableSetBgColor(ImGuiTableBgTarget_CellBg, ImGui::GetColorU32(ImGui::GetStyle().Colors[ImGuiCol_TableHeaderBg]));
368
369 for (const auto& time : ambiguityTimes)
370 {
371 ImGui::TableNextColumn();
372 auto iter = std::ranges::find_if(ambiguities->second, [&time](const auto& timeAndAmb) {
373 return timeAndAmb.first == time;
374 });
375 if (iter != ambiguities->second.end())
376 {
377 ImVec4 color;
378 auto cycleIter = std::ranges::find_if(_cycleSlips, [&](const CycleSlipInfo& cycleSlip) {
379 return cycleSlip.time == time && cycleSlip.satSigId == ambiguities->first;
380 });
381 if (cycleIter != _cycleSlips.end()) { color = ImColor(240, 128, 128); }
382 else if (ambiguities->second.back().first == time) { color = ImGui::GetStyle().Colors[ImGuiCol_Text]; }
383 else { color = ImGui::GetStyle().Colors[ImGuiCol_TextDisabled]; }
384 ImGui::TextColored(color, "%s%s",
385 fmt::format("{}", iter->second).c_str(),
386 cycleIter != _cycleSlips.end() && cycleIter->LLI ? " (LLI)" : "");
387 if (ImGui::IsItemHovered() && cycleIter != _cycleSlips.end()) { ImGui::SetTooltip("Cycle-slip"); }
388 }
389 else if (time < ambiguities->second.front().first)
390 {
391 ImGui::TableSetBgColor(ImGuiTableBgTarget_CellBg, ImColor(70, 70, 70));
392 }
393 }
394 }
395
396 ImGui::EndTable();
397 }
398 ImGui::PopFont();
399 }
400 else
401 {
402 ImGui::TextColored(ImColor(255, 0, 0), "More than 64 timestamps for ambiguities, which cannot be displayed in a table");
403 }
404 }
405
406 ImGui::TreePop();
407 }
408 }
409}
410
412{
413 LOG_TRACE("{}: called", nameId());
414
415 json j;
416
417 j["imuAccelerometerBiasUnit"] = _imuAccelerometerBiasUnit;
418 j["imuAccelerometerBias_p"] = _imuAccelerometerBias_p;
419 j["imuGyroscopeBiasUnit"] = _imuGyroscopeBiasUnit;
420 j["imuGyroscopeBias_p"] = _imuGyroscopeBias_p;
421 j["imuAccelerometerNoiseUnit"] = _imuAccelerometerNoiseUnit;
422 j["imuAccelerometerNoise"] = _imuAccelerometerNoise;
423 j["imuAccelerometerRng"] = _imuAccelerometerRng;
424 j["imuGyroscopeNoiseUnit"] = _imuGyroscopeNoiseUnit;
425 j["imuGyroscopeNoise"] = _imuGyroscopeNoise;
426 j["imuGyroscopeRng"] = _imuGyroscopeRng;
427 j["imuAccelerometerRWUnit"] = _imuAccelerometerRWUnit;
428 j["imuAccelerometerRW"] = _imuAccelerometerRW;
429 j["imuAccelerometerRWRng"] = _imuAccelerometerRWRng;
430
431 j["imuGyroscopeRWUnit"] = _imuGyroscopeRWUnit;
432 j["imuGyroscopeRW"] = _imuGyroscopeRW;
433 j["imuGyroscopeRWRng"] = _imuGyroscopeRWRng;
434 j["imuAccelerometerIRWUnit"] = _imuAccelerometerIRWUnit;
435 j["imuAccelerometerIRW"] = _imuAccelerometerIRW;
436 j["imuAccelerometerIRWRng"] = _imuAccelerometerIRWRng;
437 j["imuGyroscopeIRWUnit"] = _imuGyroscopeIRWUnit;
438 j["imuGyroscopeIRW"] = _imuGyroscopeIRW;
439 j["imuGyroscopeIRWRng"] = _imuGyroscopeIRWRng;
440
441 // #########################################################################################################################################
442 j["positionBiasUnit"] = _positionBiasUnit;
443 j["positionBias"] = _positionBias;
444 j["velocityBiasUnit"] = _velocityBiasUnit;
445 j["velocityBias"] = _velocityBias;
446 j["attitudeBiasUnit"] = _attitudeBiasUnit;
447 j["attitudeBias"] = _attitudeBias;
448 j["positionNoiseUnit"] = _positionNoiseUnit;
449 j["positionNoise"] = _positionNoise;
450 j["positionRng"] = _positionRng;
451 j["velocityNoiseUnit"] = _velocityNoiseUnit;
452 j["velocityNoise"] = _velocityNoise;
453 j["velocityRng"] = _velocityRng;
454 j["attitudeNoiseUnit"] = _attitudeNoiseUnit;
455 j["attitudeNoise"] = _attitudeNoise;
456 j["attitudeRng"] = _attitudeRng;
457 // #########################################################################################################################################
458 j["pseudorangeNoiseUnit"] = _gui_pseudorangeNoiseUnit;
459 j["pseudorangeNoise"] = _gui_pseudorangeNoise;
460 j["pseudorangeRng"] = _pseudorangeRng;
461 j["carrierPhaseNoiseUnit"] = _gui_carrierPhaseNoiseUnit;
462 j["carrierPhaseNoise"] = _gui_carrierPhaseNoise;
463 j["carrierPhaseRng"] = _carrierPhaseRng;
464 j["dopplerNoiseUnit"] = _gui_dopplerNoiseUnit;
465 j["dopplerNoise"] = _gui_dopplerNoise;
466 j["dopplerRng"] = _dopplerRng;
467 j["ambiguityLimits"] = _gui_ambiguityLimits;
468 j["ambiguityRng"] = _ambiguityRng;
469 j["cycleSlipFrequencyUnit"] = _gui_cycleSlipFrequencyUnit;
470 j["cycleSlipFrequency"] = _gui_cycleSlipFrequency;
471 j["cycleSlipRange"] = _gui_cycleSlipRange;
472 j["cycleSlipDetectionProbabilityUnit"] = _gui_cycleSlipDetectionProbabilityUnit;
473 j["cycleSlipDetectionProbability"] = _gui_cycleSlipDetectionProbability;
474 j["cycleSlipRng"] = _cycleSlipRng;
475
476 j["filterFreq"] = Frequency_(_filterFreq);
477 j["filterCode"] = _filterCode;
478
479 return j;
480}
481
483{
484 LOG_TRACE("{}: called", nameId());
485
486 if (j.contains("imuAccelerometerBiasUnit")) { j.at("imuAccelerometerBiasUnit").get_to(_imuAccelerometerBiasUnit); }
487 if (j.contains("imuAccelerometerBias_p")) { j.at("imuAccelerometerBias_p").get_to(_imuAccelerometerBias_p); }
488 if (j.contains("imuGyroscopeBiasUnit")) { j.at("imuGyroscopeBiasUnit").get_to(_imuGyroscopeBiasUnit); }
489 if (j.contains("imuGyroscopeBias_p")) { j.at("imuGyroscopeBias_p").get_to(_imuGyroscopeBias_p); }
490 if (j.contains("imuAccelerometerNoiseUnit")) { j.at("imuAccelerometerNoiseUnit").get_to(_imuAccelerometerNoiseUnit); }
491 if (j.contains("imuAccelerometerNoise")) { j.at("imuAccelerometerNoise").get_to(_imuAccelerometerNoise); }
492 if (j.contains("imuAccelerometerRng")) { j.at("imuAccelerometerRng").get_to(_imuAccelerometerRng); }
493 if (j.contains("imuGyroscopeNoiseUnit")) { j.at("imuGyroscopeNoiseUnit").get_to(_imuGyroscopeNoiseUnit); }
494 if (j.contains("imuGyroscopeNoise")) { j.at("imuGyroscopeNoise").get_to(_imuGyroscopeNoise); }
495 if (j.contains("imuGyroscopeRng")) { j.at("imuGyroscopeRng").get_to(_imuGyroscopeRng); }
496
497 if (j.contains("imuAccelerometerRWUnit")) { j.at("imuAccelerometerRWUnit").get_to(_imuAccelerometerRWUnit); }
498 if (j.contains("imuAccelerometerRW")) { j.at("imuAccelerometerRW").get_to(_imuAccelerometerRW); }
499 if (j.contains("imuAccelerometerRWRng")) { j.at("imuAccelerometerRWRng").get_to(_imuAccelerometerRWRng); }
500 if (j.contains("imuGyroscopeRWUnit")) { j.at("imuGyroscopeRWUnit").get_to(_imuGyroscopeRWUnit); }
501 if (j.contains("imuGyroscopeRW")) { j.at("imuGyroscopeRW").get_to(_imuGyroscopeRW); }
502 if (j.contains("imuGyroscopeRWRng")) { j.at("imuGyroscopeRWRng").get_to(_imuGyroscopeRWRng); }
503 if (j.contains("imuAccelerometerIRWUnit")) { j.at("imuAccelerometerIRWUnit").get_to(_imuAccelerometerIRWUnit); }
504 if (j.contains("imuAccelerometerIRW")) { j.at("imuAccelerometerIRW").get_to(_imuAccelerometerIRW); }
505 if (j.contains("imuAccelerometerIRWRng")) { j.at("imuAccelerometerIRWRng").get_to(_imuAccelerometerIRWRng); }
506 if (j.contains("imuGyroscopeIRWUnit")) { j.at("imuGyroscopeIRWUnit").get_to(_imuGyroscopeIRWUnit); }
507 if (j.contains("imuGyroscopeIRW")) { j.at("imuGyroscopeIRW").get_to(_imuGyroscopeIRW); }
508 if (j.contains("imuGyroscopeIRWRng")) { j.at("imuGyroscopeIRWRng").get_to(_imuGyroscopeIRWRng); }
509 // #########################################################################################################################################
510 if (j.contains("positionBiasUnit")) { j.at("positionBiasUnit").get_to(_positionBiasUnit); }
511 if (j.contains("positionBias")) { j.at("positionBias").get_to(_positionBias); }
512 if (j.contains("velocityBiasUnit")) { j.at("velocityBiasUnit").get_to(_velocityBiasUnit); }
513 if (j.contains("velocityBias")) { j.at("velocityBias").get_to(_velocityBias); }
514 if (j.contains("attitudeBiasUnit")) { j.at("attitudeBiasUnit").get_to(_attitudeBiasUnit); }
515 if (j.contains("attitudeBias")) { j.at("attitudeBias").get_to(_attitudeBias); }
516 if (j.contains("positionNoiseUnit")) { j.at("positionNoiseUnit").get_to(_positionNoiseUnit); }
517 if (j.contains("positionNoise")) { j.at("positionNoise").get_to(_positionNoise); }
518 if (j.contains("positionRng")) { j.at("positionRng").get_to(_positionRng); }
519 if (j.contains("velocityNoiseUnit")) { j.at("velocityNoiseUnit").get_to(_velocityNoiseUnit); }
520 if (j.contains("velocityNoise")) { j.at("velocityNoise").get_to(_velocityNoise); }
521 if (j.contains("velocityRng")) { j.at("velocityRng").get_to(_velocityRng); }
522 if (j.contains("attitudeNoiseUnit")) { j.at("attitudeNoiseUnit").get_to(_attitudeNoiseUnit); }
523 if (j.contains("attitudeNoise")) { j.at("attitudeNoise").get_to(_attitudeNoise); }
524 if (j.contains("attitudeRng")) { j.at("attitudeRng").get_to(_attitudeRng); }
525 // #########################################################################################################################################
526 if (j.contains("pseudorangeNoiseUnit")) { j.at("pseudorangeNoiseUnit").get_to(_gui_pseudorangeNoiseUnit); }
527 if (j.contains("pseudorangeNoise")) { j.at("pseudorangeNoise").get_to(_gui_pseudorangeNoise); }
528 if (j.contains("pseudorangeRng")) { j.at("pseudorangeRng").get_to(_pseudorangeRng); }
529 if (j.contains("carrierPhaseNoiseUnit")) { j.at("carrierPhaseNoiseUnit").get_to(_gui_carrierPhaseNoiseUnit); }
530 if (j.contains("carrierPhaseNoise")) { j.at("carrierPhaseNoise").get_to(_gui_carrierPhaseNoise); }
531 if (j.contains("carrierPhaseRng")) { j.at("carrierPhaseRng").get_to(_carrierPhaseRng); }
532 if (j.contains("dopplerNoiseUnit")) { j.at("dopplerNoiseUnit").get_to(_gui_dopplerNoiseUnit); }
533 if (j.contains("dopplerNoise")) { j.at("dopplerNoise").get_to(_gui_dopplerNoise); }
534 if (j.contains("dopplerRng")) { j.at("dopplerRng").get_to(_dopplerRng); }
535 if (j.contains("ambiguityLimits")) { j.at("ambiguityLimits").get_to(_gui_ambiguityLimits); }
536 if (j.contains("ambiguityRng")) { j.at("ambiguityRng").get_to(_ambiguityRng); }
537 if (j.contains("cycleSlipFrequencyUnit")) { j.at("cycleSlipFrequencyUnit").get_to(_gui_cycleSlipFrequencyUnit); }
538 if (j.contains("cycleSlipFrequency")) { j.at("cycleSlipFrequency").get_to(_gui_cycleSlipFrequency); }
539 if (j.contains("cycleSlipRange")) { j.at("cycleSlipRange").get_to(_gui_cycleSlipRange); }
540 if (j.contains("cycleSlipDetectionProbabilityUnit")) { j.at("cycleSlipDetectionProbabilityUnit").get_to(_gui_cycleSlipDetectionProbabilityUnit); }
541 if (j.contains("cycleSlipDetectionProbability")) { j.at("cycleSlipDetectionProbability").get_to(_gui_cycleSlipDetectionProbability); }
542 if (j.contains("cycleSlipRng")) { j.at("cycleSlipRng").get_to(_cycleSlipRng); }
543 if (j.contains("filterFreq"))
544 {
545 uint64_t value = 0;
546 j.at("filterFreq").get_to(value);
547 _filterFreq = Frequency_(value);
548 }
549 if (j.contains("filterCode")) { j.at("filterCode").get_to(_filterCode); }
550}
551
553{
554 LOG_TRACE("{}: called", nameId());
555
556 _lastObservationTime.reset();
557 _dt = 0.0;
558
559 // ImuObs
560 _imuAccelerometerRng.resetSeed(size_t(id));
561 _imuGyroscopeRng.resetSeed(size_t(id));
562 _imuAccelerometerRWRng.resetSeed(size_t(id));
563 _imuGyroscopeRWRng.resetSeed(size_t(id));
564 _imuAccelerometerIRWRng.resetSeed(size_t(id));
565 _imuGyroscopeIRWRng.resetSeed(size_t(id));
566 _randomWalkAccelerometer.setZero();
567 _randomWalkGyroscope.setZero();
572
573 // PosVelAtt
574 _positionRng.resetSeed(size_t(id));
575 _velocityRng.resetSeed(size_t(id));
576 _attitudeRng.resetSeed(size_t(id));
577
578 // GnssObs
579 _pseudorangeRng.resetSeed(size_t(id));
580 _carrierPhaseRng.resetSeed(size_t(id));
581 _dopplerRng.resetSeed(size_t(id));
582 _ambiguityRng.resetSeed(size_t(id));
583 _ambiguities.clear();
584 _cycleSlips.clear();
585 _cycleSlipRng.resetSeed(size_t(id));
587
588 return true;
589}
590
592{
593 LOG_TRACE("{}: called for {} ==> {}", nameId(), size_t(startPin.id), size_t(endPin.id));
594
595 if (endPin.parentNode->id != id)
596 {
597 return; // Link on Output Port
598 }
599
600 // Store previous output pin identifier
601 auto previousOutputPinDataIdentifier = outputPins.front().dataIdentifier;
602 // Overwrite output pin identifier with input pin identifier
603 outputPins.front().dataIdentifier = startPin.dataIdentifier;
604
605 if (previousOutputPinDataIdentifier != outputPins.front().dataIdentifier) // If the identifier changed
606 {
607 // Check if connected links on output port are still valid
608 for (auto& link : outputPins.front().links)
609 {
610 if (auto* endPin = link.getConnectedPin())
611 {
612 if (!outputPins.front().canCreateLink(*endPin))
613 {
614 // If the link is not valid anymore, delete it
615 outputPins.front().deleteLink(*endPin);
616 }
617 }
618 }
619
620 // Refresh all links connected to the output pin if the type changed
621 if (outputPins.front().dataIdentifier != previousOutputPinDataIdentifier)
622 {
623 for (auto& link : outputPins.front().links)
624 {
625 if (auto* connectedPin = link.getConnectedPin())
626 {
627 outputPins.front().recreateLink(*connectedPin);
628 }
629 }
630 }
631 }
632}
633
635{
636 LOG_TRACE("{}: called for {} ==> {}", nameId(), size_t(startPin.id), size_t(endPin.id));
637
638 if ((endPin.parentNode->id != id // Link on Output port is removed
639 && !inputPins.front().isPinLinked()) // and the Input port is not linked
640 || (startPin.parentNode->id != id // Link on Input port is removed
641 && !outputPins.front().isPinLinked())) // and the Output port is not linked
642 {
643 outputPins.front().dataIdentifier = supportedDataIdentifier;
644 }
645}
646
648{
649 auto obs = queue.extract_front();
650 if (!_lastObservationTime.empty()) { _dt = static_cast<double>((obs->insTime - _lastObservationTime).count()); }
651
652 // Accelerometer Bias in platform frame coordinates [m/s^2]
653 Eigen::Vector3d accelerometerBias_p = convertUnit(_imuAccelerometerBias_p, _imuAccelerometerBiasUnit);
654 LOG_DATA("{}: accelerometerBias_p = {} [m/s^2]", nameId(), accelerometerBias_p.transpose());
655
656 // Gyroscope Bias in platform frame coordinates [rad/s]
657 Eigen::Vector3d gyroscopeBias_p = convertUnit(_imuGyroscopeBias_p, _imuGyroscopeBiasUnit);
658 LOG_DATA("{}: gyroscopeBias_p = {} [rad/s]", nameId(), gyroscopeBias_p.transpose());
659
660 // #########################################################################################################################################
661
662 // Accelerometer Noise standard deviation in platform frame coordinates [m/s^2/sqrt(s)]
663 Eigen::Vector3d accelerometerNoiseStd = convertUnit(_imuAccelerometerNoise, _imuAccelerometerNoiseUnit);
664 LOG_DATA("{}: accelerometerNoiseStd = {} [m/s^2/sqrt(s)]", nameId(), accelerometerNoiseStd.transpose());
665
666 // Gyroscope Noise standard deviation in platform frame coordinates [rad/s/sqrt(s)]
667 Eigen::Vector3d gyroscopeNoiseStd = convertUnit(_imuGyroscopeNoise, _imuGyroscopeNoiseUnit);
668 LOG_DATA("{}: gyroscopeNoiseStd = {} [rad/s/sqrt(s)]", nameId(), gyroscopeNoiseStd.transpose());
669
670 // Select the correct data type and make a copy of the node data to modify
671 if (NAV::NodeRegistry::NodeDataTypeAnyIsChildOf(outputPins.front().dataIdentifier, { ImuObsSimulated::type() }))
672 {
674 receiveImuObsWDelta(std::make_shared<ImuObsSimulated>(*std::static_pointer_cast<const ImuObsSimulated>(obs)),
675 accelerometerBias_p,
676 gyroscopeBias_p,
677 accelerometerNoiseStd,
678 gyroscopeNoiseStd));
679 }
680 else if (NAV::NodeRegistry::NodeDataTypeAnyIsChildOf(outputPins.front().dataIdentifier, { ImuObsWDelta::type() }))
681 {
683 receiveImuObsWDelta(std::make_shared<ImuObsWDelta>(*std::static_pointer_cast<const ImuObsWDelta>(obs)),
684 accelerometerBias_p,
685 gyroscopeBias_p,
686 accelerometerNoiseStd,
687 gyroscopeNoiseStd));
688 }
689 else if (NAV::NodeRegistry::NodeDataTypeAnyIsChildOf(outputPins.front().dataIdentifier, { ImuObs::type() }))
690 {
692 receiveImuObs(std::make_shared<ImuObs>(*std::static_pointer_cast<const ImuObs>(obs)),
693 accelerometerBias_p,
694 gyroscopeBias_p,
695 accelerometerNoiseStd,
696 gyroscopeNoiseStd));
697 }
698 else if (NAV::NodeRegistry::NodeDataTypeAnyIsChildOf(outputPins.front().dataIdentifier, { PosVelAtt::type() }))
699 {
700 invokeCallbacks(OUTPUT_PORT_INDEX_FLOW, receivePosVelAtt(std::make_shared<PosVelAtt>(*std::static_pointer_cast<const PosVelAtt>(obs))));
701 }
702 else if (NAV::NodeRegistry::NodeDataTypeAnyIsChildOf(outputPins.front().dataIdentifier, { PosVel::type() }))
703 {
704 invokeCallbacks(OUTPUT_PORT_INDEX_FLOW, receivePosVel(std::make_shared<PosVel>(*std::static_pointer_cast<const PosVel>(obs))));
705 }
706 else if (NAV::NodeRegistry::NodeDataTypeAnyIsChildOf(outputPins.front().dataIdentifier, { Pos::type() }))
707 {
708 invokeCallbacks(OUTPUT_PORT_INDEX_FLOW, receivePos(std::make_shared<Pos>(*std::static_pointer_cast<const Pos>(obs))));
709 }
710 else if (NAV::NodeRegistry::NodeDataTypeAnyIsChildOf(outputPins.front().dataIdentifier, { GnssObs::type() }))
711 {
712 invokeCallbacks(OUTPUT_PORT_INDEX_FLOW, receiveGnssObs(std::make_shared<GnssObs>(*std::static_pointer_cast<const GnssObs>(obs))));
713 }
714
715 _lastObservationTime = obs->insTime;
716}
717
718std::shared_ptr<NAV::ImuObs> NAV::ErrorModel::receiveImuObs(const std::shared_ptr<ImuObs>& imuObs,
719 const Eigen::Vector3d& accelerometerBias_p,
720 const Eigen::Vector3d& gyroscopeBias_p,
721 const Eigen::Vector3d& accelerometerNoiseStd,
722 const Eigen::Vector3d& gyroscopeNoiseStd)
723{
724 if (!_lastObservationTime.empty())
725 {
726 {
727 // Accelerometer RW standard deviation in platform frame coordinates [m/s^2/sqrt(s)]
728 Eigen::Vector3d accelerometerRWStd = convertUnit(_imuAccelerometerRW, _imuAccelerometerRWUnit);
729 LOG_DATA("{}: accelerometerRWStd = {} [m/s^2/sqrt(s)]", nameId(), accelerometerRWStd.transpose());
730
731 _randomWalkAccelerometer += Eigen::Vector3d{
732 _imuAccelerometerRWRng.getRand_normalDist(0.0, accelerometerRWStd(0)),
733 _imuAccelerometerRWRng.getRand_normalDist(0.0, accelerometerRWStd(1)),
734 _imuAccelerometerRWRng.getRand_normalDist(0.0, accelerometerRWStd(2))
735 } * sqrt(_dt);
736 }
737 {
738 // Accelerometer IRW standard deviation in platform frame coordinates [m/s^3/sqrt(s)]
739 Eigen::Vector3d accelerometerIRWStd = convertUnit(_imuAccelerometerIRW, _imuAccelerometerIRWUnit);
740 LOG_DATA("{}: accelerometerIRWStd = {} [m/s^3/sqrt(s)]", nameId(), accelerometerIRWStd.transpose());
741
742 // compute velocity RW first
744 _imuAccelerometerIRWRng.getRand_normalDist(0.0, accelerometerIRWStd(0)),
745 _imuAccelerometerIRWRng.getRand_normalDist(0.0, accelerometerIRWStd(1)),
746 _imuAccelerometerIRWRng.getRand_normalDist(0.0, accelerometerIRWStd(2))
747 } * sqrt(_dt);
748
749 // then compute IRW
751 }
752 {
753 // Gyro RW standard deviation in platform frame coordinates [rad/s/sqrt(s)]
754 Eigen::Vector3d gyroscopeRWStd = convertUnit(_imuGyroscopeRW, _imuGyroscopeRWUnit);
755 LOG_DATA("{}: gyroscopeRWStd = {} [rad/s/sqrt(s)]", nameId(), gyroscopeRWStd.transpose());
756
757 _randomWalkGyroscope += Eigen::Vector3d{
758 _imuGyroscopeRWRng.getRand_normalDist(0.0, gyroscopeRWStd(0)),
759 _imuGyroscopeRWRng.getRand_normalDist(0.0, gyroscopeRWStd(1)),
760 _imuGyroscopeRWRng.getRand_normalDist(0.0, gyroscopeRWStd(2))
761 } * sqrt(_dt);
762 }
763 {
764 // Gyro RW standard deviation in platform frame coordinates [rad/s^2/sqrt(s)]
765 Eigen::Vector3d gyroscopeIRWStd = convertUnit(_imuGyroscopeIRW, _imuGyroscopeIRWUnit);
766 LOG_DATA("{}: gyroscopeIRWStd = {} [rad/s^2/sqrt(s)]", nameId(), gyroscopeIRWStd.transpose());
767
768 // compute velocity RW first
770 _imuGyroscopeIRWRng.getRand_normalDist(0.0, gyroscopeIRWStd(0)),
771 _imuGyroscopeIRWRng.getRand_normalDist(0.0, gyroscopeIRWStd(1)),
772 _imuGyroscopeIRWRng.getRand_normalDist(0.0, gyroscopeIRWStd(2))
773 } * sqrt(_dt);
774
775 // then compute IRW
777 }
778 }
779
780 // #########################################################################################################################################
781
782 imuObs->p_acceleration += accelerometerBias_p
785
786 imuObs->p_angularRate += gyroscopeBias_p
789 if (_dt > 1e-9)
790 {
791 imuObs->p_acceleration += Eigen::Vector3d{ _imuAccelerometerRng.getRand_normalDist(0.0, accelerometerNoiseStd(0)),
792 _imuAccelerometerRng.getRand_normalDist(0.0, accelerometerNoiseStd(1)),
793 _imuAccelerometerRng.getRand_normalDist(0.0, accelerometerNoiseStd(2)) }
794 / std::sqrt(_dt); // Scale with input frequency
795 imuObs->p_angularRate += Eigen::Vector3d{ _imuGyroscopeRng.getRand_normalDist(0.0, gyroscopeNoiseStd(0)),
796 _imuGyroscopeRng.getRand_normalDist(0.0, gyroscopeNoiseStd(1)),
797 _imuGyroscopeRng.getRand_normalDist(0.0, gyroscopeNoiseStd(2)) }
798 / std::sqrt(_dt); // Scale with input frequency
799 }
800
801 return imuObs;
802}
803
804std::shared_ptr<NAV::ImuObsWDelta> NAV::ErrorModel::receiveImuObsWDelta(const std::shared_ptr<ImuObsWDelta>& imuObsWDelta,
805 const Eigen::Vector3d& accelerometerBias_p,
806 const Eigen::Vector3d& gyroscopeBias_p,
807 const Eigen::Vector3d& accelerometerNoiseStd,
808 const Eigen::Vector3d& gyroscopeNoiseStd)
809{
810 receiveImuObs(imuObsWDelta, accelerometerBias_p, gyroscopeBias_p, accelerometerNoiseStd, gyroscopeNoiseStd);
811
812 double imuObsWDeltaAverageWindow = _dt != 0.0 ? _dt / imuObsWDelta->dtime : 1.0;
813
814 imuObsWDelta->dvel += imuObsWDelta->dtime * (accelerometerBias_p + _randomWalkAccelerometer + _integratedRandomWalkAccelerometer);
815 imuObsWDelta->dtheta += imuObsWDelta->dtime * (gyroscopeBias_p + _randomWalkGyroscope + _integratedRandomWalkGyroscope);
816 if (_dt > 1e-9)
817 {
818 imuObsWDelta->dvel += Eigen::Vector3d{ _imuAccelerometerRng.getRand_normalDist(0.0, accelerometerNoiseStd(0) / std::sqrt(imuObsWDeltaAverageWindow)),
819 _imuAccelerometerRng.getRand_normalDist(0.0, accelerometerNoiseStd(1) / std::sqrt(imuObsWDeltaAverageWindow)),
820 _imuAccelerometerRng.getRand_normalDist(0.0, accelerometerNoiseStd(2) / std::sqrt(imuObsWDeltaAverageWindow)) }
821 * imuObsWDelta->dtime / std::sqrt(_dt); // Scale with input frequency
822 imuObsWDelta->dtheta += Eigen::Vector3d{ _imuGyroscopeRng.getRand_normalDist(0.0, gyroscopeNoiseStd(0) / std::sqrt(imuObsWDeltaAverageWindow)),
823 _imuGyroscopeRng.getRand_normalDist(0.0, gyroscopeNoiseStd(1) / std::sqrt(imuObsWDeltaAverageWindow)),
824 _imuGyroscopeRng.getRand_normalDist(0.0, gyroscopeNoiseStd(2) / std::sqrt(imuObsWDeltaAverageWindow)) }
825 * imuObsWDelta->dtime / std::sqrt(_dt); // Scale with input frequency
826 }
827
828 return imuObsWDelta;
829}
830
831std::shared_ptr<NAV::Pos> NAV::ErrorModel::receivePos(const std::shared_ptr<Pos>& pos)
832{
833 // Position Bias in latLonAlt in [rad, rad, m]
834 Eigen::Vector3d lla_positionBias = Eigen::Vector3d::Zero();
835 switch (_positionBiasUnit)
836 {
838 {
839 Eigen::Vector3d e_positionBias = trafo::e_Quat_n(pos->latitude(), pos->longitude()) * _positionBias;
840 if (!e_positionBias.isZero())
841 {
842 lla_positionBias = trafo::ecef2lla_WGS84(pos->e_position() + e_positionBias) - pos->lla_position();
843 }
844 break;
845 }
846 }
847 LOG_DATA("{}: lla_positionBias = {} [rad, rad, m]", nameId(), lla_positionBias.transpose());
848
849 // Velocity bias in local-navigation coordinates in [m/s]
850 Eigen::Vector3d n_velocityBias = Eigen::Vector3d::Zero();
851 switch (_velocityBiasUnit)
852 {
854 n_velocityBias = _velocityBias;
855 break;
856 }
857 LOG_DATA("{}: n_velocityBias = {} [m/s]", nameId(), n_velocityBias.transpose());
858
859 // Roll, pitch, yaw bias in [rad]
860 Eigen::Vector3d attitudeBias = Eigen::Vector3d::Zero();
861 switch (_attitudeBiasUnit)
862 {
864 attitudeBias = _attitudeBias;
865 break;
867 attitudeBias = deg2rad(_attitudeBias);
868 break;
869 }
870 LOG_DATA("{}: attitudeBias = {} [rad]", nameId(), attitudeBias.transpose());
871
872 // #########################################################################################################################################
873
874 // Position Noise standard deviation in latitude, longitude and altitude [rad, rad, m]
875 Eigen::Vector3d lla_positionNoiseStd = Eigen::Vector3d::Zero();
876 Eigen::Vector3d NED_pos_variance = Eigen::Vector3d::Zero();
877 switch (_positionNoiseUnit)
878 {
880 {
881 Eigen::Vector3d e_positionNoiseStd = trafo::e_Quat_n(pos->latitude(), pos->longitude()) * _positionNoise;
882 if (!e_positionNoiseStd.isZero())
883 {
884 lla_positionNoiseStd = trafo::ecef2lla_WGS84(pos->e_position() + e_positionNoiseStd) - pos->lla_position();
885 }
886 NED_pos_variance = _positionNoise.cwiseAbs2();
887 break;
888 }
890 {
891 Eigen::Vector3d e_positionNoiseStd = trafo::e_Quat_n(pos->latitude(), pos->longitude()) * _positionNoise.cwiseSqrt();
892 if (!e_positionNoiseStd.isZero())
893 {
894 lla_positionNoiseStd = trafo::ecef2lla_WGS84(pos->e_position() + e_positionNoiseStd) - pos->lla_position();
895 }
896 NED_pos_variance = _positionNoise;
897 break;
898 }
899 }
900 LOG_DATA("{}: lla_positionNoiseStd = {} [rad, rad, m]", nameId(), lla_positionNoiseStd.transpose());
901
902 // #########################################################################################################################################
903
904 pos->setPositionAndCov_n(pos->lla_position()
905 + lla_positionBias
906 + Eigen::Vector3d{ _positionRng.getRand_normalDist(0.0, lla_positionNoiseStd(0)),
907 _positionRng.getRand_normalDist(0.0, lla_positionNoiseStd(1)),
908 _positionRng.getRand_normalDist(0.0, lla_positionNoiseStd(2)) },
909 NED_pos_variance.asDiagonal().toDenseMatrix());
910
911 return pos;
912}
913
914std::shared_ptr<NAV::PosVel> NAV::ErrorModel::receivePosVel(const std::shared_ptr<PosVel>& posVel)
915{
916 // Position Bias in latLonAlt in [rad, rad, m]
917 Eigen::Vector3d lla_positionBias = Eigen::Vector3d::Zero();
918 switch (_positionBiasUnit)
919 {
921 {
922 Eigen::Vector3d e_positionBias = trafo::e_Quat_n(posVel->latitude(), posVel->longitude()) * _positionBias;
923 if (!e_positionBias.isZero())
924 {
925 lla_positionBias = trafo::ecef2lla_WGS84(posVel->e_position() + e_positionBias) - posVel->lla_position();
926 }
927 break;
928 }
929 }
930 LOG_DATA("{}: lla_positionBias = {} [rad, rad, m]", nameId(), lla_positionBias.transpose());
931
932 // Velocity bias in local-navigation coordinates in [m/s]
933 Eigen::Vector3d n_velocityBias = Eigen::Vector3d::Zero();
934 switch (_velocityBiasUnit)
935 {
937 n_velocityBias = _velocityBias;
938 break;
939 }
940 LOG_DATA("{}: n_velocityBias = {} [m/s]", nameId(), n_velocityBias.transpose());
941
942 // #########################################################################################################################################
943
944 // Position Noise standard deviation in latitude, longitude and altitude [rad, rad, m]
945 Eigen::Vector3d lla_positionNoiseStd = Eigen::Vector3d::Zero();
946 Eigen::Vector3d NED_pos_variance = Eigen::Vector3d::Zero();
947 Eigen::Vector3d NED_velocity_variance = Eigen::Vector3d::Zero();
948 switch (_positionNoiseUnit)
949 {
951 {
952 Eigen::Vector3d e_positionNoiseStd = trafo::e_Quat_n(posVel->latitude(), posVel->longitude()) * _positionNoise;
953 if (!e_positionNoiseStd.isZero())
954 {
955 lla_positionNoiseStd = trafo::ecef2lla_WGS84(posVel->e_position() + e_positionNoiseStd) - posVel->lla_position();
956 }
957 NED_pos_variance = _positionNoise.cwiseAbs2();
958 break;
959 }
961 {
962 Eigen::Vector3d e_positionNoiseStd = trafo::e_Quat_n(posVel->latitude(), posVel->longitude()) * _positionNoise.cwiseSqrt();
963 if (!e_positionNoiseStd.isZero())
964 {
965 lla_positionNoiseStd = trafo::ecef2lla_WGS84(posVel->e_position() + e_positionNoiseStd) - posVel->lla_position();
966 }
967 NED_pos_variance = _positionNoise;
968 break;
969 }
970 }
971 LOG_DATA("{}: lla_positionNoiseStd = {} [rad, rad, m]", nameId(), lla_positionNoiseStd.transpose());
972
973 // Velocity Noise standard deviation in local-navigation coordinates in [m/s]
974 Eigen::Vector3d n_velocityNoiseStd = Eigen::Vector3d::Zero();
975 switch (_velocityNoiseUnit)
976 {
978 n_velocityNoiseStd = _velocityNoise;
979 NED_velocity_variance = _velocityNoise.cwiseAbs2();
980 break;
982 n_velocityNoiseStd = _velocityNoise.cwiseSqrt();
983 NED_velocity_variance = _velocityNoise;
984 break;
985 }
986 LOG_DATA("{}: n_velocityNoiseStd = {} [m/s]", nameId(), n_velocityNoiseStd.transpose());
987
988 // #########################################################################################################################################
989
990 Eigen::Matrix<double, 6, 6> cov_n = Eigen::Matrix<double, 6, 6>::Zero();
991 cov_n.block<3, 3>(0, 0).diagonal() = NED_pos_variance;
992 cov_n.block<3, 3>(3, 3).diagonal() = NED_velocity_variance;
993
994 posVel->setPosVelAndCov_n(posVel->lla_position()
995 + lla_positionBias
996 + Eigen::Vector3d{ _positionRng.getRand_normalDist(0.0, lla_positionNoiseStd(0)),
997 _positionRng.getRand_normalDist(0.0, lla_positionNoiseStd(1)),
998 _positionRng.getRand_normalDist(0.0, lla_positionNoiseStd(2)) },
999 posVel->n_velocity()
1000 + n_velocityBias
1001 + Eigen::Vector3d{ _velocityRng.getRand_normalDist(0.0, n_velocityNoiseStd(0)),
1002 _velocityRng.getRand_normalDist(0.0, n_velocityNoiseStd(1)),
1003 _velocityRng.getRand_normalDist(0.0, n_velocityNoiseStd(2)) },
1004 cov_n);
1005
1006 return posVel;
1007}
1008
1009std::shared_ptr<NAV::PosVelAtt> NAV::ErrorModel::receivePosVelAtt(const std::shared_ptr<PosVelAtt>& posVelAtt)
1010{
1011 // Position Bias in latLonAlt in [rad, rad, m]
1012 Eigen::Vector3d lla_positionBias = Eigen::Vector3d::Zero();
1013 switch (_positionBiasUnit)
1014 {
1016 {
1017 Eigen::Vector3d e_positionBias = trafo::e_Quat_n(posVelAtt->latitude(), posVelAtt->longitude()) * _positionBias;
1018 if (!e_positionBias.isZero())
1019 {
1020 lla_positionBias = trafo::ecef2lla_WGS84(posVelAtt->e_position() + e_positionBias) - posVelAtt->lla_position();
1021 }
1022 break;
1023 }
1024 }
1025 LOG_DATA("{}: lla_positionBias = {} [rad, rad, m]", nameId(), lla_positionBias.transpose());
1026
1027 // Velocity bias in local-navigation coordinates in [m/s]
1028 Eigen::Vector3d n_velocityBias = Eigen::Vector3d::Zero();
1029 switch (_velocityBiasUnit)
1030 {
1032 n_velocityBias = _velocityBias;
1033 break;
1034 }
1035 LOG_DATA("{}: n_velocityBias = {} [m/s]", nameId(), n_velocityBias.transpose());
1036
1037 // Roll, pitch, yaw bias in [rad]
1038 Eigen::Vector3d attitudeBias = Eigen::Vector3d::Zero();
1039 switch (_attitudeBiasUnit)
1040 {
1042 attitudeBias = _attitudeBias;
1043 break;
1045 attitudeBias = deg2rad(_attitudeBias);
1046 break;
1047 }
1048 LOG_DATA("{}: attitudeBias = {} [rad]", nameId(), attitudeBias.transpose());
1049
1050 // #########################################################################################################################################
1051
1052 // Position Noise standard deviation in latitude, longitude and altitude [rad, rad, m]
1053 Eigen::Vector3d lla_positionNoiseStd = Eigen::Vector3d::Zero();
1054 Eigen::Vector3d NED_pos_variance = Eigen::Vector3d::Zero();
1055 Eigen::Vector3d NED_velocity_variance = Eigen::Vector3d::Zero();
1056 Eigen::Vector3d RPY_attitude_variance = Eigen::Vector3d::Zero();
1057 switch (_positionNoiseUnit)
1058 {
1060 {
1061 Eigen::Vector3d e_positionNoiseStd = trafo::e_Quat_n(posVelAtt->latitude(), posVelAtt->longitude()) * _positionNoise;
1062 if (!e_positionNoiseStd.isZero())
1063 {
1064 lla_positionNoiseStd = trafo::ecef2lla_WGS84(posVelAtt->e_position() + e_positionNoiseStd) - posVelAtt->lla_position();
1065 }
1066 NED_pos_variance = _positionNoise.cwiseAbs2();
1067 break;
1068 }
1070 {
1071 Eigen::Vector3d e_positionNoiseStd = trafo::e_Quat_n(posVelAtt->latitude(), posVelAtt->longitude()) * _positionNoise.cwiseSqrt();
1072 if (!e_positionNoiseStd.isZero())
1073 {
1074 lla_positionNoiseStd = trafo::ecef2lla_WGS84(posVelAtt->e_position() + e_positionNoiseStd) - posVelAtt->lla_position();
1075 }
1076 NED_pos_variance = _positionNoise;
1077 break;
1078 }
1079 }
1080 LOG_DATA("{}: lla_positionNoiseStd = {} [rad, rad, m]", nameId(), lla_positionNoiseStd.transpose());
1081
1082 // Velocity Noise standard deviation in local-navigation coordinates in [m/s]
1083 Eigen::Vector3d n_velocityNoiseStd = Eigen::Vector3d::Zero();
1084 switch (_velocityNoiseUnit)
1085 {
1087 n_velocityNoiseStd = _velocityNoise;
1088 NED_velocity_variance = _velocityNoise.cwiseAbs2();
1089 break;
1091 n_velocityNoiseStd = _velocityNoise.cwiseSqrt();
1092 NED_velocity_variance = _velocityNoise;
1093 break;
1094 }
1095 LOG_DATA("{}: n_velocityNoiseStd = {} [m/s]", nameId(), n_velocityNoiseStd.transpose());
1096
1097 // Attitude Noise standard deviation in [rad]
1098 Eigen::Vector3d attitudeNoiseStd = Eigen::Vector3d::Zero();
1099 switch (_attitudeNoiseUnit)
1100 {
1102 attitudeNoiseStd = _attitudeNoise;
1103 RPY_attitude_variance = _attitudeNoise.cwiseAbs2();
1104 break;
1106 attitudeNoiseStd = deg2rad(_attitudeNoise);
1107 RPY_attitude_variance = deg2rad(_attitudeNoise).cwiseAbs2();
1108 break;
1110 attitudeNoiseStd = _attitudeNoise.cwiseSqrt();
1111 RPY_attitude_variance = _attitudeNoise;
1112 break;
1114 attitudeNoiseStd = deg2rad(_attitudeNoise.cwiseSqrt());
1115 RPY_attitude_variance = deg2rad(deg2rad(_attitudeNoise));
1116 break;
1117 }
1118 LOG_DATA("{}: attitudeNoiseStd = {} [rad]", nameId(), attitudeNoiseStd.transpose());
1119
1120 // #########################################################################################################################################
1121
1122 Eigen::Matrix<double, 9, 9> cov_n = Eigen::Matrix<double, 9, 9>::Zero();
1123 cov_n.block<3, 3>(0, 0).diagonal() = NED_pos_variance;
1124 cov_n.block<3, 3>(3, 3).diagonal() = NED_velocity_variance;
1125 cov_n.block<3, 3>(6, 6).diagonal() = RPY_attitude_variance;
1126
1127 Eigen::Matrix<double, 10, 9> J = Eigen::Matrix<double, 10, 9>::Zero();
1128 J.topLeftCorner<6, 6>().setIdentity();
1129 J.bottomRightCorner<4, 3>() = trafo::covRPY2quatJacobian(posVelAtt->n_Quat_b());
1130
1131 posVelAtt->setPosVelAttAndCov_n(posVelAtt->lla_position()
1132 + lla_positionBias
1133 + Eigen::Vector3d{ _positionRng.getRand_normalDist(0.0, lla_positionNoiseStd(0)),
1134 _positionRng.getRand_normalDist(0.0, lla_positionNoiseStd(1)),
1135 _positionRng.getRand_normalDist(0.0, lla_positionNoiseStd(2)) },
1136 posVelAtt->n_velocity()
1137 + n_velocityBias
1138 + Eigen::Vector3d{ _velocityRng.getRand_normalDist(0.0, n_velocityNoiseStd(0)),
1139 _velocityRng.getRand_normalDist(0.0, n_velocityNoiseStd(1)),
1140 _velocityRng.getRand_normalDist(0.0, n_velocityNoiseStd(2)) },
1141 trafo::n_Quat_b(posVelAtt->rollPitchYaw()
1142 + attitudeBias
1143 + Eigen::Vector3d{ _attitudeRng.getRand_normalDist(0.0, attitudeNoiseStd(0)),
1144 _attitudeRng.getRand_normalDist(0.0, attitudeNoiseStd(1)),
1145 _attitudeRng.getRand_normalDist(0.0, attitudeNoiseStd(2)) }),
1146 J * cov_n * J.transpose());
1147
1148 return posVelAtt;
1149}
1150
1151std::shared_ptr<NAV::GnssObs> NAV::ErrorModel::receiveGnssObs(const std::shared_ptr<GnssObs>& gnssObs)
1152{
1153 LOG_DATA("{}: [{}] Simulating error on GnssObs", nameId(), gnssObs->insTime.toYMDHMS(GPST));
1154 double pseudorangeNoise{}; // [m]
1156 {
1158 pseudorangeNoise = _gui_pseudorangeNoise;
1159 break;
1160 }
1161 double carrierPhaseNoise{}; // [m]
1163 {
1165 carrierPhaseNoise = _gui_carrierPhaseNoise;
1166 break;
1167 }
1168 double dopplerNoise{}; // [m/s]
1169 switch (_gui_dopplerNoiseUnit)
1170 {
1172 dopplerNoise = _gui_dopplerNoise;
1173 break;
1174 }
1175
1176 double dtCycleSlipSeconds{}; // [s]
1178 {
1181 break;
1184 break;
1187 break;
1188 }
1189 auto dtCycleSlip = std::chrono::nanoseconds(static_cast<int64_t>(dtCycleSlipSeconds * 1e9));
1190
1191 double cycleSlipDetectionProbability{}; // [0, 1]
1193 {
1195 cycleSlipDetectionProbability = _gui_cycleSlipDetectionProbability / 100.0;
1196 break;
1197 }
1198
1199 if (_cycleSlipWindowStartTime.empty()
1200 || gnssObs->insTime >= _cycleSlipWindowStartTime + dtCycleSlip)
1201 {
1202 _cycleSlipWindowStartTime = gnssObs->insTime;
1203 LOG_DATA("{}: [{}] Starting new cycle-slip window", nameId(), _cycleSlipWindowStartTime.toYMDHMS(GPST));
1204 }
1205
1206 size_t nObs = 0;
1207 for (auto& obs : gnssObs->data)
1208 {
1209 if (obs.satSigId.freq() & _filterFreq
1210 && obs.satSigId.code & _filterCode)
1211 {
1212 nObs++;
1213 }
1214 }
1215
1216 for (auto& obs : gnssObs->data)
1217 {
1218 if (obs.pseudorange) { obs.pseudorange.value().value += _pseudorangeRng.getRand_normalDist(0.0, pseudorangeNoise); }
1219 if (obs.doppler) { obs.doppler.value() += rangeRate2doppler(_dopplerRng.getRand_normalDist(0.0, dopplerNoise), obs.satSigId.freq(), 0); } // TODO: Add frequency number here for GLONASS
1220
1221 if (obs.carrierPhase)
1222 {
1223 // ------------------------------------------- Noise ---------------------------------------------
1224 auto lambda = InsConst::C / obs.satSigId.freq().getFrequency(0); // wave-length [m] // TODO: Add frequency number here for GLONASS
1225 obs.carrierPhase.value().value += _carrierPhaseRng.getRand_normalDist(0.0, carrierPhaseNoise) / lambda;
1226
1227 // ---------------------------------------- Cycle-slip -------------------------------------------
1228
1229 if (obs.satSigId.freq() & _filterFreq // GUI selected frequencies
1230 && obs.satSigId.code & _filterCode // GUI selected codes
1231 && _gui_cycleSlipFrequency != 0.0 // 0 Frequency means disabled
1232 && !_lastObservationTime.empty() // Do not apply a cycle slip on the first message
1233 && (_cycleSlips.empty() || _cycleSlips.back().time < _cycleSlipWindowStartTime)) // In the current window, there was no cycle-slip yet
1234 {
1235 double probabilityCycleSlip = _dt / (dtCycleSlipSeconds * static_cast<double>(nObs)) * 2.0; // Double chance, because often does not happen otherwise
1236 if (_cycleSlipRng.getRand_uniformRealDist(0.0, 1.0) <= probabilityCycleSlip
1237 || (gnssObs->insTime >= _cycleSlipWindowStartTime + dtCycleSlip - std::chrono::nanoseconds(static_cast<int64_t>((_dt + 0.001) * 1e9)))) // Last message this window
1238 {
1239 int newAmbiguity = 0;
1240 int oldAmbiguity = !_ambiguities[obs.satSigId].empty()
1241 ? _ambiguities[obs.satSigId].back().second
1242 : static_cast<int>(_ambiguityRng.getRand_uniformIntDist(_gui_ambiguityLimits[0], _gui_ambiguityLimits[1]));
1243 auto deltaAmbiguity = static_cast<int>(_cycleSlipRng.getRand_uniformIntDist(1, _gui_cycleSlipRange));
1244 auto signAmbiguity = _cycleSlipRng.getRand_uniformIntDist(0, 1) == 0.0 ? 1 : -1;
1245
1246 if (_gui_ambiguityLimits[0] == _gui_ambiguityLimits[1]) // Ambiguities disabled
1247 {
1248 newAmbiguity = oldAmbiguity + signAmbiguity * deltaAmbiguity;
1249 }
1250 else if (oldAmbiguity == _gui_ambiguityLimits[0])
1251 {
1252 newAmbiguity = std::min(oldAmbiguity + deltaAmbiguity, _gui_ambiguityLimits[1]);
1253 }
1254 else if (oldAmbiguity == _gui_ambiguityLimits[1])
1255 {
1256 newAmbiguity = std::max(oldAmbiguity - deltaAmbiguity, _gui_ambiguityLimits[0]);
1257 }
1258 else
1259 {
1260 newAmbiguity = std::clamp(oldAmbiguity + signAmbiguity * deltaAmbiguity, _gui_ambiguityLimits[0], _gui_ambiguityLimits[1]);
1261 }
1262
1263 _ambiguities[obs.satSigId].emplace_back(gnssObs->insTime, newAmbiguity);
1264
1265 if (_cycleSlipRng.getRand_uniformRealDist(0.0, 1.0) <= cycleSlipDetectionProbability)
1266 {
1267 obs.carrierPhase.value().LLI = 1;
1268 }
1269 _cycleSlips.push_back(CycleSlipInfo{ .time = gnssObs->insTime, .satSigId = obs.satSigId, .LLI = obs.carrierPhase.value().LLI != 0 });
1270 LOG_DEBUG("{}: [{}] Simulating cycle-slip for satellite [{}] with LLI {}", nameId(), gnssObs->insTime.toYMDHMS(GPST),
1271 obs.satSigId, obs.carrierPhase.value().LLI);
1272 }
1273 }
1274
1275 // ----------------------------------------- Ambiguity -------------------------------------------
1276 if (!_ambiguities.contains(obs.satSigId) && _gui_ambiguityLimits[0] != _gui_ambiguityLimits[1])
1277 {
1278 _ambiguities[obs.satSigId].emplace_back(gnssObs->insTime, _ambiguityRng.getRand_uniformIntDist(_gui_ambiguityLimits[0], _gui_ambiguityLimits[1]));
1279 }
1280 if (_ambiguities.contains(obs.satSigId))
1281 {
1282 obs.carrierPhase.value().value += _ambiguities.at(obs.satSigId).back().second;
1283 }
1284 }
1285 }
1286
1287 return gnssObs;
1288}
Transformation collection.
Vector space operations.
Adds errors (biases and noise) to measurements.
Save/Load the Nodes.
nlohmann::json json
json namespace
GNSS helper functions.
Text Help Marker (?) with Tooltip.
Units used by INS.
Data storage class for simulated IMU observations.
Data storage class for one VectorNavImu observation.
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
#define LOG_DATA
All output which occurs repeatedly every time observations are received.
Definition Logger.hpp:29
#define LOG_TRACE
Detailled info to trace the execution of the program. Should not be called on functions which receive...
Definition Logger.hpp:65
Manages all Nodes.
Utility class which specifies available nodes.
Utility functions for working with std::strings.
Frequency _filterFreq
Frequencies used for calculation (GUI filter)
std::shared_ptr< PosVel > receivePosVel(const std::shared_ptr< PosVel > &posVel)
Callback when receiving an PosVelObs.
RandomNumberGenerator _imuAccelerometerRng
Random number generator for the accelerometer noise.
int _gui_cycleSlipRange
Ambiguity limits cycle-slip.
RandomNumberGenerator _carrierPhaseRng
Random number generator for the carrier-phase noise.
Units::ImuAccelerometerUnits _imuAccelerometerBiasUnit
Selected unit for the accelerometer bias in the GUI.
std::shared_ptr< ImuObs > receiveImuObs(const std::shared_ptr< ImuObs > &imuObs, const Eigen::Vector3d &accelerometerBias_p, const Eigen::Vector3d &gyroscopeBias_p, const Eigen::Vector3d &accelerometerNoiseStd, const Eigen::Vector3d &gyroscopeNoiseStd)
Callback when receiving an ImuObs.
VelocityBiasUnits _velocityBiasUnit
Selected unit for the velocity bias in the GUI.
std::array< int, 2 > _gui_ambiguityLimits
Ambiguity limits.
CarrierPhaseNoiseUnits _gui_carrierPhaseNoiseUnit
Selected unit for the carrier-phase noise in the GUI.
RandomNumberGenerator _imuGyroscopeRng
Random number generator for the gyroscope noise.
RandomNumberGenerator _imuAccelerometerIRWRng
Random number generator for the accelerometer IRW noise.
Units::ImuGyroscopeIRWUnits _imuGyroscopeIRWUnit
Selected unit for the accelerometer IRW noise in the GUI.
RandomNumberGenerator _imuGyroscopeRWRng
Random number generator for the accelerometer RW noise.
RandomNumberGenerator _imuAccelerometerRWRng
Random number generator for the accelerometer RW noise.
~ErrorModel() override
Destructor.
PositionNoiseUnits _positionNoiseUnit
Selected unit for the position noise in the GUI.
Eigen::Vector3d _positionNoise
Noise of the position (Unit as selected)
Units::ImuGyroscopeUnits _imuGyroscopeBiasUnit
Selected unit for the gyroscope bias in the GUI.
static std::string typeStatic()
String representation of the Class Type.
Eigen::Vector3d _imuAccelerometerNoise
Noise of the accelerometer (Unit as selected)
static constexpr size_t OUTPUT_PORT_INDEX_FLOW
Flow.
VelocityNoiseUnits _velocityNoiseUnit
Selected unit for the velocity noise in the GUI.
void restore(const json &j) override
Restores the node from a json object.
void afterDeleteLink(OutputPin &startPin, InputPin &endPin) override
Called when a link was deleted.
Eigen::Vector3d _integratedRandomWalkGyroscope
3D array which allow to accumulate IRW for gyro
Units::ImuAccelerometerNoiseUnits _imuAccelerometerNoiseUnit
Selected unit for the accelerometer noise in the GUI.
std::shared_ptr< GnssObs > receiveGnssObs(const std::shared_ptr< GnssObs > &gnssObs)
Callback when receiving an GnssObs.
RandomNumberGenerator _attitudeRng
Random number generator for the attitude noise.
AttitudeBiasUnits _attitudeBiasUnit
Selected unit for the attitude bias in the GUI.
@ rad
[rad] (Standard deviation)
@ deg
[deg] (Standard deviation)
json save() const override
Saves the node into a json object.
std::string type() const override
String representation of the Class Type.
RandomNumberGenerator _imuGyroscopeIRWRng
Random number generator for the accelerometer RW noise.
Eigen::Vector3d _velocityBias
Bias of the velocity (Unit as selected)
InsTime _lastObservationTime
Last observation time.
RandomNumberGenerator _cycleSlipRng
Random number generator for the cycle-slip.
double _gui_cycleSlipDetectionProbability
The chance to detect a cycle slip and set the Loss-of-Lock indicator.
Eigen::Vector3d _integratedRandomWalkGyroscope_velocity
3D array which allow to accumulate IRW veloctiy noise for gyro
CycleSlipDetectionProbabilityUnits _gui_cycleSlipDetectionProbabilityUnit
Selected unit for the cycle-slip detection probability in the GUI.
Eigen::Vector3d _velocityNoise
Noise of the velocity (Unit as selected)
std::shared_ptr< Pos > receivePos(const std::shared_ptr< Pos > &pos)
Callback when receiving an PosObs.
CycleSlipFrequencyUnits _gui_cycleSlipFrequencyUnit
Selected unit for the cycle-slip frequency in the GUI.
Eigen::Vector3d _imuAccelerometerRW
RW noise of the accelerometer (Unit as selected)
double _gui_pseudorangeNoise
Noise of the pseudorange (Unit as selected)
double _gui_carrierPhaseNoise
Noise of the carrier-phase (Unit as selected)
double _dt
Time interval of the messages [s].
RandomNumberGenerator _pseudorangeRng
Random number generator for the pseudorange noise.
Eigen::Vector3d _integratedRandomWalkAccelerometer
3D array which allow to accumulate IRW for accelerometer
std::shared_ptr< PosVelAtt > receivePosVelAtt(const std::shared_ptr< PosVelAtt > &posVelAtt)
Callback when receiving an PosVelAttObs.
Units::ImuGyroscopeNoiseUnits _imuGyroscopeRWUnit
Selected unit for the accelerometer RW noise in the GUI.
@ meter2
NED [m^2 m^2 m^2] (Variance)
@ meter
NED [m m m] (Standard deviation)
DopplerNoiseUnits _gui_dopplerNoiseUnit
Selected unit for the range-rate noise in the GUI.
RandomNumberGenerator _ambiguityRng
Random number generator for the ambiguity.
@ m_s
[m/s] (Standard deviation)
Eigen::Vector3d _imuAccelerometerBias_p
Bias of the accelerometer in platform coordinates (Unit as selected)
RandomNumberGenerator _positionRng
Random number generator for the position noise.
Eigen::Vector3d _imuGyroscopeBias_p
Bias of the gyroscope in platform coordinates (Unit as selected)
Code _filterCode
Codes used for calculation (GUI filter)
double _gui_dopplerNoise
Noise of the range-rate (Unit as selected)
void receiveObs(InputPin::NodeDataQueue &queue, size_t pinIdx)
Callback when receiving data on a port.
Units::ImuAccelerometerNoiseUnits _imuAccelerometerRWUnit
Selected unit for the accelerometer RW noise in the GUI.
Eigen::Vector3d _imuGyroscopeNoise
Noise of the gyroscope (Unit as selected)
static std::string category()
String representation of the Class Category.
Eigen::Vector3d _positionBias
Bias of the position (Unit as selected)
void afterCreateLink(OutputPin &startPin, InputPin &endPin) override
Called when a new link was established.
@ meter
[m] (Standard deviation)
Eigen::Vector3d _imuGyroscopeIRW
RW noise of the accelerometer (Unit as selected)
Units::ImuAccelerometerIRWUnits _imuAccelerometerIRWUnit
Selected unit for the accelerometer IRW noise in the GUI.
Eigen::Vector3d _randomWalkGyroscope
3D array which allow to accumulate RW noise for gyro
Eigen::Vector3d _attitudeBias
Bias of the attitude (Unit as selected)
void guiConfig() override
ImGui config window which is shown on double click.
Eigen::Vector3d _imuAccelerometerIRW
IRW noise of the accelerometer (Unit as selected)
PositionBiasUnits _positionBiasUnit
Selected unit for the position bias in the GUI.
Eigen::Vector3d _imuGyroscopeRW
RW noise of the accelerometer (Unit as selected)
AttitudeNoiseUnits _attitudeNoiseUnit
Selected unit for the attitude noise in the GUI.
ErrorModel()
Default constructor.
Eigen::Vector3d _randomWalkAccelerometer
3D array which allow to accumulate RW noise for accelerometer
@ m_s
[m/s] (Standard deviation)
Eigen::Vector3d _integratedRandomWalkAccelerometer_velocity
3D array which allow to accumulate IRW veloctiy noise for accelerometer
InsTime _cycleSlipWindowStartTime
The time frame which is considered for a cycle slip.
double _gui_cycleSlipFrequency
The cycle-slip frequency (Unit as selected)
std::shared_ptr< ImuObsWDelta > receiveImuObsWDelta(const std::shared_ptr< ImuObsWDelta > &imuObs, const Eigen::Vector3d &accelerometerBias_p, const Eigen::Vector3d &gyroscopeBias_p, const Eigen::Vector3d &accelerometerNoiseStd, const Eigen::Vector3d &gyroscopeNoiseStd)
Callback when receiving an ImuObsWDelta.
RandomNumberGenerator _velocityRng
Random number generator for the velocity noise.
std::vector< CycleSlipInfo > _cycleSlips
List of produced cycle-slips.
RandomNumberGenerator _dopplerRng
Random number generator for the range-rate noise.
Units::ImuGyroscopeNoiseUnits _imuGyroscopeNoiseUnit
Selected unit for the gyroscope noise in the GUI.
Eigen::Vector3d _attitudeNoise
Noise of the attitude (Unit as selected)
std::map< SatSigId, std::vector< std::pair< InsTime, int > > > _ambiguities
Ambiguity map.
bool resetNode() override
Resets the node. It is guaranteed that the node is initialized when this is called.
PseudorangeNoiseUnits _gui_pseudorangeNoiseUnit
Selected unit for the pseudorange noise in the GUI.
static std::string type()
Returns the type of the data class.
Definition GnssObs.hpp:150
static std::string type()
Returns the type of the data class.
static std::string type()
Returns the type of the data class.
Definition ImuObs.hpp:33
Input pins of nodes.
Definition Pin.hpp:491
TsDeque< std::shared_ptr< const NAV::NodeData > > NodeDataQueue
Node data queue type.
Definition Pin.hpp:707
static constexpr double C
Speed of light [m/s].
Definition Constants.hpp:34
ImVec2 _guiConfigDefaultWindowSize
Definition Node.hpp:410
std::vector< OutputPin > outputPins
List of output pins.
Definition Node.hpp:399
Node(std::string name)
Constructor.
Definition Node.cpp:30
std::vector< InputPin > inputPins
List of input pins.
Definition Node.hpp:397
std::string nameId() const
Node name and id.
Definition Node.cpp:253
std::string name
Name of the Node.
Definition Node.hpp:395
void invokeCallbacks(size_t portIndex, const std::shared_ptr< const NodeData > &data)
Calls all registered callbacks on the specified output port.
Definition Node.cpp:180
ax::NodeEditor::NodeId id
Unique Id of the Node.
Definition Node.hpp:391
bool _hasConfig
Flag if the config window should be shown.
Definition Node.hpp:413
Output pins of nodes.
Definition Pin.hpp:338
Node * parentNode
Reference to the parent node.
Definition Pin.hpp:307
ax::NodeEditor::PinId id
Unique Id of the Pin.
Definition Pin.hpp:297
std::vector< std::string > dataIdentifier
One or multiple Data Identifiers (Unique name which is used for data flows)
Definition Pin.hpp:305
static std::string type()
Returns the type of the data class.
Definition PosVelAtt.hpp:29
static std::string type()
Returns the type of the data class.
Definition PosVel.hpp:27
static std::string type()
Returns the type of the data class.
Definition Pos.hpp:36
Manages a thread which calls a specified function at a specified interval.
auto extract_front()
Returns a copy of the first element in the container and removes it from the container.
Definition TsDeque.hpp:494
static float windowFontRatio()
Ratio to multiply for GUI window elements.
static float monoFontRatio()
Ratio to multiply for log output GUI elements.
ImGui extensions.
bool InputIntL(const char *label, int *v, int v_min, int v_max, int step, int step_fast, ImGuiInputTextFlags flags)
Shows a value limited InputText GUI element for 'int'.
Definition imgui_ex.cpp:242
bool SliderULong(const char *label, uint64_t *v, uint64_t v_min, uint64_t v_max, const char *format, ImGuiSliderFlags flags)
Shows a Slider GUI element for 'uint64'.
Definition imgui_ex.cpp:129
constexpr int32_t SECONDS_PER_DAY
Seconds / Day.
Definition InsTime.hpp:60
constexpr int32_t SECONDS_PER_HOUR
Seconds / Hour.
Definition InsTime.hpp:59
constexpr int32_t SECONDS_PER_MINUTE
Seconds / Minute.
Definition InsTime.hpp:58
OutputPin * CreateOutputPin(Node *node, const char *name, Pin::Type pinType, const std::vector< std::string > &dataIdentifier, OutputPin::PinData data=static_cast< void * >(nullptr), int idx=-1)
Create an Output Pin object.
InputPin * CreateInputPin(Node *node, const char *name, Pin::Type pinType, const std::vector< std::string > &dataIdentifier={}, InputPin::Callback callback=static_cast< InputPin::FlowFirableCallbackFunc >(nullptr), InputPin::FlowFirableCheckFunc firable=nullptr, int priority=0, int idx=-1)
Create an Input Pin object.
bool NodeDataTypeAnyIsChildOf(const std::vector< std::string > &childTypes, const std::vector< std::string > &parentTypes)
Checks if any of the provided child types is a child of any of the provided parent types.
void ApplyChanges()
Signals that there have been changes to the flow.
InputWithUnitChange InputDoubleWithUnit(const char *label, float itemWidth, float unitWidth, double *v, U &combo_current_item, const char *combo_items_separated_by_zeros, double step=0.0, double step_fast=0.0, const char *format="%.6f", ImGuiInputTextFlags flags=0, int combo_popup_max_height_in_items=-1)
Shows an InputText GUI element to modify the provided value and also set its unit.
InputWithUnitChange SliderDoubleWithUnit(const char *label, float itemWidth, float unitWidth, double *v, double v_min, double v_max, U &combo_current_item, const char *combo_items_separated_by_zeros, const char *format="%.6f", ImGuiSliderFlags flags=0, int combo_popup_max_height_in_items=-1)
Shows an Slider GUI element to modify the provided value and also set its unit.
@ InputWithUnitChange_Unit
The Unit changed.
@ InputWithUnitChange_Input
The Input changed.
InputWithUnitChange InputDouble3WithUnit(const char *label, float itemWidth, float unitWidth, double v[3], U &combo_current_item, const char *combo_items_separated_by_zeros, const char *format="%.6f", ImGuiInputTextFlags flags=0, int combo_popup_max_height_in_items=-1)
Shows an InputText GUI element to modify the provided value and also set its unit.
void HelpMarker(const char *desc, const char *symbol="(?)")
Text Help Marker, e.g. '(?)', with Tooltip.
static std::string replaceAll_copy(std::string str, const std::string &from, const std::string &to, CaseSensitivity cs)
Replaces all occurrence of a search pattern with another sequence.
Eigen::Vector3< typename Derived::Scalar > ecef2lla_WGS84(const Eigen::MatrixBase< Derived > &e_position)
Converts Earth-centered-Earth-fixed coordinates into latitude, longitude and altitude using WGS84.
Eigen::Quaternion< Scalar > e_Quat_n(const Scalar &latitude, const Scalar &longitude)
Quaternion for rotations from navigation to Earth-fixed frame.
Eigen::Matrix< typename Derived::Scalar, 4, 3 > covRPY2quatJacobian(const Eigen::QuaternionBase< Derived > &n_quat_b)
Calculates the Jacobian to convert an attitude represented in Euler angels (roll, pitch,...
Eigen::Quaternion< Scalar > n_Quat_b(Scalar roll, Scalar pitch, Scalar yaw)
Quaternion for rotations from body to navigation frame.
@ GPST
GPS Time.
Frequency_
Enumerate for GNSS frequencies.
Definition Frequency.hpp:26
bool ShowFrequencySelector(const char *label, Frequency &frequency, bool singleSelect)
Shows a ComboBox to select GNSS frequencies.
bool ShowCodeSelector(const char *label, Code &code, const Frequency &filterFreq, bool singleSelect)
Shows a ComboBox to select signal codes.
Definition Code.cpp:1199
double convertUnit(const double &value, Units::PositionUncertaintyUnits unit)
Converts the value depending on the unit provided.
Definition Units.cpp:135
constexpr auto deg2rad(const T &deg)
Convert Degree to Radians.
Definition Units.hpp:21
std::string MakeComboItems()
Units separated by '\0' and terminated by double '\0'.
const std::vector< std::string > supportedDataIdentifier
List of supported data identifiers.
double rangeRate2doppler(double rangeRate, Frequency freq, int8_t num)
Transforms a range-rate into a doppler-shift.
Definition Functions.cpp:19
Cycle-slip information.
InsTime time
Time of the cycle-slip.
SatSigId satSigId
Satellite Signal identifier.
@ Flow
NodeData Trigger.
Definition Pin.hpp:52