| 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 | #include "WiFiObsLogger.hpp" | ||
| 10 | |||
| 11 | #include "NodeData/WiFi/WiFiObs.hpp" | ||
| 12 | |||
| 13 | #include "Navigation/Transformations/Units.hpp" | ||
| 14 | |||
| 15 | #include "util/Logger.hpp" | ||
| 16 | |||
| 17 | #include <iomanip> // std::setprecision | ||
| 18 | |||
| 19 | #include "internal/NodeManager.hpp" | ||
| 20 | namespace nm = NAV::NodeManager; | ||
| 21 | #include "internal/FlowManager.hpp" | ||
| 22 | |||
| 23 | 114 | NAV::WiFiObsLogger::WiFiObsLogger() | |
| 24 |
4/8✓ Branch 1 taken 114 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 114 times.
✗ Branch 5 not taken.
✓ Branch 8 taken 114 times.
✗ Branch 9 not taken.
✓ Branch 11 taken 114 times.
✗ Branch 12 not taken.
|
114 | : Node(typeStatic()) |
| 25 | { | ||
| 26 | LOG_TRACE("{}: called", name); | ||
| 27 | |||
| 28 | 114 | _fileType = FileType::ASCII; | |
| 29 | |||
| 30 | 114 | _hasConfig = true; | |
| 31 | 114 | _guiConfigDefaultWindowSize = { 380, 70 }; | |
| 32 | |||
| 33 |
4/8✓ Branch 1 taken 114 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 114 times.
✗ Branch 6 not taken.
✓ Branch 8 taken 114 times.
✓ Branch 9 taken 114 times.
✗ Branch 12 not taken.
✗ Branch 13 not taken.
|
342 | nm::CreateInputPin(this, "writeObservation", Pin::Type::Flow, { WiFiObs::type() }, &WiFiObsLogger::writeObservation); |
| 34 | 228 | } | |
| 35 | |||
| 36 | 228 | NAV::WiFiObsLogger::~WiFiObsLogger() | |
| 37 | { | ||
| 38 | LOG_TRACE("{}: called", nameId()); | ||
| 39 | 228 | } | |
| 40 | |||
| 41 | 228 | std::string NAV::WiFiObsLogger::typeStatic() | |
| 42 | { | ||
| 43 |
1/2✓ Branch 1 taken 228 times.
✗ Branch 2 not taken.
|
456 | return "WiFiObsLogger"; |
| 44 | } | ||
| 45 | |||
| 46 | ✗ | std::string NAV::WiFiObsLogger::type() const | |
| 47 | { | ||
| 48 | ✗ | return typeStatic(); | |
| 49 | } | ||
| 50 | |||
| 51 | 114 | std::string NAV::WiFiObsLogger::category() | |
| 52 | { | ||
| 53 |
1/2✓ Branch 1 taken 114 times.
✗ Branch 2 not taken.
|
228 | return "Data Logger"; |
| 54 | } | ||
| 55 | |||
| 56 | ✗ | void NAV::WiFiObsLogger::guiConfig() | |
| 57 | { | ||
| 58 | ✗ | if (FileWriter::guiConfig(".csv", { ".csv" }, size_t(id), nameId())) | |
| 59 | { | ||
| 60 | ✗ | flow::ApplyChanges(); | |
| 61 | ✗ | doDeinitialize(); | |
| 62 | } | ||
| 63 | |||
| 64 | ✗ | if (CommonLog::ShowOriginInput(nameId().c_str())) | |
| 65 | { | ||
| 66 | ✗ | flow::ApplyChanges(); | |
| 67 | } | ||
| 68 | ✗ | } | |
| 69 | |||
| 70 | ✗ | [[nodiscard]] json NAV::WiFiObsLogger::save() const | |
| 71 | { | ||
| 72 | LOG_TRACE("{}: called", nameId()); | ||
| 73 | |||
| 74 | ✗ | json j; | |
| 75 | |||
| 76 | ✗ | j["FileWriter"] = FileWriter::save(); | |
| 77 | |||
| 78 | ✗ | return j; | |
| 79 | ✗ | } | |
| 80 | |||
| 81 | ✗ | void NAV::WiFiObsLogger::restore(json const& j) | |
| 82 | { | ||
| 83 | LOG_TRACE("{}: called", nameId()); | ||
| 84 | |||
| 85 | ✗ | if (j.contains("FileWriter")) | |
| 86 | { | ||
| 87 | ✗ | FileWriter::restore(j.at("FileWriter")); | |
| 88 | } | ||
| 89 | ✗ | } | |
| 90 | |||
| 91 | ✗ | void NAV::WiFiObsLogger::flush() | |
| 92 | { | ||
| 93 | ✗ | _filestream.flush(); | |
| 94 | ✗ | } | |
| 95 | |||
| 96 | ✗ | bool NAV::WiFiObsLogger::initialize() | |
| 97 | { | ||
| 98 | LOG_TRACE("{}: called", nameId()); | ||
| 99 | |||
| 100 | ✗ | if (!FileWriter::initialize()) | |
| 101 | { | ||
| 102 | ✗ | return false; | |
| 103 | } | ||
| 104 | |||
| 105 | ✗ | CommonLog::initialize(); | |
| 106 | |||
| 107 | _filestream << "Time [s],GpsCycle,GpsWeek,GpsToW [s]," | ||
| 108 | << "MacAddress," | ||
| 109 | << "Distance [m]," | ||
| 110 | ✗ | << "DistanceStd [m]\n"; | |
| 111 | |||
| 112 | ✗ | return true; | |
| 113 | } | ||
| 114 | |||
| 115 | ✗ | void NAV::WiFiObsLogger::deinitialize() | |
| 116 | { | ||
| 117 | LOG_TRACE("{}: called", nameId()); | ||
| 118 | |||
| 119 | ✗ | FileWriter::deinitialize(); | |
| 120 | ✗ | } | |
| 121 | |||
| 122 | ✗ | void NAV::WiFiObsLogger::writeObservation(NAV::InputPin::NodeDataQueue& queue, size_t pinIdx) | |
| 123 | { | ||
| 124 | ✗ | if ([[maybe_unused]] auto* sourcePin = inputPins[pinIdx].link.getConnectedPin()) | |
| 125 | { | ||
| 126 | ✗ | constexpr int gpsCyclePrecision = 3; | |
| 127 | ✗ | constexpr int gpsTimePrecision = 12; | |
| 128 | ✗ | constexpr int valuePrecision = 15; | |
| 129 | |||
| 130 | ✗ | auto nodeData = queue.extract_front(); | |
| 131 | |||
| 132 | // -------------------------------------------------------- Time ----------------------------------------------------------- | ||
| 133 | |||
| 134 | ✗ | auto obs = std::static_pointer_cast<const WiFiObs>(nodeData); | |
| 135 | ✗ | if (!obs->insTime.empty()) | |
| 136 | { | ||
| 137 | ✗ | _filestream << std::setprecision(valuePrecision) << std::round(calcTimeIntoRun(obs->insTime) * 1e9) / 1e9; | |
| 138 | } | ||
| 139 | ✗ | _filestream << ","; | |
| 140 | ✗ | if (!obs->insTime.empty()) | |
| 141 | { | ||
| 142 | ✗ | _filestream << std::fixed << std::setprecision(gpsCyclePrecision) << obs->insTime.toGPSweekTow().gpsCycle; | |
| 143 | } | ||
| 144 | ✗ | _filestream << ","; | |
| 145 | ✗ | if (!obs->insTime.empty()) | |
| 146 | { | ||
| 147 | ✗ | _filestream << std::defaultfloat << std::setprecision(gpsTimePrecision) << obs->insTime.toGPSweekTow().gpsWeek; | |
| 148 | } | ||
| 149 | ✗ | _filestream << ","; | |
| 150 | ✗ | if (!obs->insTime.empty()) | |
| 151 | { | ||
| 152 | ✗ | _filestream << std::defaultfloat << std::setprecision(gpsTimePrecision) << obs->insTime.toGPSweekTow().tow; | |
| 153 | } | ||
| 154 | ✗ | _filestream << "," << std::setprecision(valuePrecision); | |
| 155 | |||
| 156 | // ------------------------------------------------------ MacAddress ---------------------------------------------------------- | ||
| 157 | ✗ | if (!obs->macAddress.empty()) | |
| 158 | { | ||
| 159 | ✗ | _filestream << obs->macAddress; | |
| 160 | } | ||
| 161 | ✗ | _filestream << ","; | |
| 162 | |||
| 163 | // ------------------------------------------------------- Distance ----------------------------------------------------------- | ||
| 164 | ✗ | _filestream << obs->distance; | |
| 165 | ✗ | _filestream << ","; | |
| 166 | // --------------------------------------------------------- Standard deviation --------------------------------------------------- | ||
| 167 | ✗ | _filestream << obs->distanceStd; | |
| 168 | |||
| 169 | ✗ | _filestream << '\n'; | |
| 170 | ✗ | } | |
| 171 | ✗ | } | |
| 172 |