0.5.1
Loading...
Searching...
No Matches
MultiImuFile.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 "MultiImuFile.hpp"
10
11#include "util/Logger.hpp"
12
15
20
22 : Node(typeStatic())
23{
24 LOG_TRACE("{}: called", name);
25
26 _hasConfig = true;
27 _guiConfigDefaultWindowSize = { 528, 379 };
28
30}
31
33{
34 LOG_TRACE("{}: called", nameId());
35}
36
38{
39 return "MultiImuFile";
40}
41
42std::string NAV::MultiImuFile::type() const
43{
44 return typeStatic();
45}
46
48{
49 return "Data Provider";
50}
51
53{
54 float columnWidth = 130.0F * gui::NodeEditorApplication::windowFontRatio();
55
56 if (FileReader::guiConfig(".txt", { ".txt" }, size_t(id), nameId()))
57 {
60 }
61
62 ImGui::SetNextItemWidth(columnWidth);
63
64 if (gui::widgets::EnumCombo(fmt::format("NMEA message type##{}", size_t(id)).c_str(), _nmeaType))
65 {
66 LOG_DEBUG("{}: nmeaType changed to {}", nameId(), fmt::underlying(_nmeaType));
67
70 }
71 ImGui::SameLine();
72 gui::widgets::HelpMarker("Until June 2023, NMEA messages in the Multi-IMU file's header were of the 'GPGGA' type. Since this type does not provide an absolute time reference, it was changed to 'GPZDA'.\n\n");
73
75 {
76 if (gui::widgets::TimeEdit(fmt::format("{}", size_t(id)).c_str(), _startTime, _startTimeEditFormat))
77 {
78 LOG_DEBUG("{}: startTime changed to {}", nameId(), _startTime);
80 }
81 }
82
83 ImGui::Separator();
84 // Set Imu Position and Rotation (from 'Imu::guiConfig();')
85 bool showRotation = true;
86 for (size_t i = 0; i < _nSensors; ++i)
87 {
88 ImGui::SetNextItemOpen(showRotation, ImGuiCond_FirstUseEver);
89 if (i == 0) { showRotation = false; }
90 if (ImGui::TreeNode(fmt::format("Imu #{} Position & Rotation##{}", i + 1, size_t(id)).c_str()))
91 {
92 ImGui::BeginDisabled(); // FIXME Not properly simulated and accounted for in the algorithms
93 std::array<float, 3> imuPos = { static_cast<float>(_imuPosAll[i].b_positionIMU_p().x()), static_cast<float>(_imuPosAll[i].b_positionIMU_p().y()), static_cast<float>(_imuPosAll[i].b_positionIMU_p().z()) };
94 if (ImGui::InputFloat3(fmt::format("Position [m]##{}", size_t(id)).c_str(), imuPos.data()))
95 {
97 _imuPosAll[i]._b_positionIMU_p = Eigen::Vector3d(imuPos.at(0), imuPos.at(1), imuPos.at(2));
98 }
99 ImGui::EndDisabled();
100 ImGui::SameLine();
101 gui::widgets::HelpMarker("Position of the IMU sensor relative to the vehicle center of mass in the body coordinate frame.");
102
103 Eigen::Vector3d eulerAnglesIMU = rad2deg(trafo::quat2eulerZYX(_imuPosAll[i].p_quat_b()));
104 std::array<float, 3> imuRot = { static_cast<float>(eulerAnglesIMU.x()), static_cast<float>(eulerAnglesIMU.y()), static_cast<float>(eulerAnglesIMU.z()) };
105 if (ImGui::InputFloat3(fmt::format("Rotation [deg]##{}", size_t(id)).c_str(), imuRot.data()))
106 {
107 // (-180:180] x (-90:90] x (-180:180]
108 imuRot.at(0) = std::max(imuRot.at(0), -179.9999F);
109 imuRot.at(0) = std::min(imuRot.at(0), 180.0F);
110 imuRot.at(1) = std::max(imuRot.at(1), -89.9999F);
111 imuRot.at(1) = std::min(imuRot.at(1), 90.0F);
112 imuRot.at(2) = std::max(imuRot.at(2), -179.9999F);
113 imuRot.at(2) = std::min(imuRot.at(2), 180.0F);
114
116 _imuPosAll[i]._b_quat_p = trafo::b_Quat_p(deg2rad(imuRot.at(0)), deg2rad(imuRot.at(1)), deg2rad(imuRot.at(2)));
117 }
118
119 ImGui::TreePop();
120 }
121 }
122}
123
124[[nodiscard]] json NAV::MultiImuFile::save() const
125{
126 LOG_TRACE("{}: called", nameId());
127
128 json j;
129
130 j["FileReader"] = FileReader::save();
131 j["imuPos"] = _imuPosAll;
132 j["nmeaType"] = _nmeaType;
133 j["startTime"] = _startTime;
134 j["delim"] = _delim;
135
136 return j;
137}
138
140{
141 LOG_TRACE("{}: called", nameId());
142
143 if (j.contains("FileReader"))
144 {
145 FileReader::restore(j.at("FileReader"));
146 }
147 if (j.contains("imuPos"))
148 {
149 j.at("imuPos").get_to(_imuPosAll);
150 }
151 if (j.contains("nmeaType"))
152 {
153 j.at("nmeaType").get_to(_nmeaType);
154 }
155 if (j.contains("startTime"))
156 {
157 j.at("startTime").get_to(_startTime);
158 }
159 if (j.contains("delim"))
160 {
161 j.at("delim").get_to(_delim);
162 }
163}
164
166{
167 LOG_TRACE("{}: called", nameId());
168
169 return FileReader::initialize();
170}
171
173{
174 LOG_TRACE("{}: called", nameId());
175
177}
178
180{
181 _lastFiltObs.reset();
182 _lineCounter = 0;
183
185
186 for (auto& sensor : _messages)
187 {
188 sensor.clear();
189 }
190 for (auto& cnt : _messageCnt)
191 {
192 cnt = 0;
193 }
194
195 return true;
196}
197
199{
200 while (outputPins.size() < _nSensors)
201 {
202 CreateOutputPin(fmt::format("ImuObs {}", outputPins.size() + 1).c_str(), Pin::Type::Flow, { NAV::ImuObs::type() }, &MultiImuFile::pollData);
203 _imuPosAll.resize(_nSensors);
204
205 _messages.resize(_nSensors);
206 _messageCnt.resize(_nSensors);
207 }
208}
209
211{
212 LOG_TRACE("called");
213
214 if (good())
215 {
216 return FileType::ASCII;
217 }
218
219 LOG_ERROR("Could not open file {}", getFilepath().string());
220 return FileType::NONE;
221}
222
224{
225 LOG_TRACE("called");
226
227 _gpzdaFound = false;
228 _gpggaFound = false;
229 const char* gpzda = "GPZDA";
230 const char* gpgga = "GPGGA";
231
232 std::string line;
233 auto len = tellg();
234
235 // Find first line of data
236 while (getline(line))
237 {
238 _lineCounter++;
239
240 // Remove any trailing non text characters
241 line.erase(std::ranges::find_if(line, [](int ch) { return std::iscntrl(ch); }), line.end());
242
243 if ((line.find(gpzda)) != std::string::npos)
244 {
245 _gpzdaFound = true;
246
247 int32_t year{};
248 int32_t month{};
249 int32_t day{};
250 int32_t hour{};
251 int32_t min{};
252 long double sec{};
253
254 // Convert line into stream
255 std::stringstream lineStream(line);
256 std::string cell;
257
258 // Split line at comma
259 for (const auto& col : _headerColumns)
260 {
261 if (std::getline(lineStream, cell, ','))
262 {
263 // Remove any trailing non text characters
264 cell.erase(std::ranges::find_if(cell, [](int ch) { return std::iscntrl(ch); }), cell.end());
265 while (cell.empty())
266 {
267 std::getline(lineStream, cell, ',');
268 }
269
270 if (col == "nmeaMsgType")
271 {
272 LOG_DEBUG("{}: nmeaMsgType read.", nameId());
273 continue;
274 }
275 if (col == "UTC_HMS")
276 {
277 hour = std::stoi(cell.substr(0, 2));
278 min = std::stoi(cell.substr(2, 2));
279 sec = std::stold(cell.substr(4, 5));
280 continue;
281 }
282 if (col == "day")
283 {
284 day = std::stoi(cell);
285 continue;
286 }
287 if (col == "month")
288 {
289 month = std::stoi(cell);
290 continue;
291 }
292 if (col == "year")
293 {
294 year = std::stoi(cell);
295 }
296
297 _startTime = InsTime(year, month, day, hour, min, sec + 1. / _gpsRate, UTC); // GPS has a rate of 1 Hz, actual starttime is one message after the last GPZDA msg in the header
298
299 len = tellg();
300 continue;
301 }
302 }
303 }
304 if (line.find(gpgga) != std::string::npos)
305 {
306 _gpggaFound = true;
307 }
308 else if ((std::find_if(line.begin(), line.begin() + 1, [](int ch) { return std::isdigit(ch); }) != (std::begin(line) + 1)) && (_gpggaFound || _gpzdaFound))
309 {
310 LOG_DEBUG("{}: Found first line of data: {}", nameId(), line);
311 seekg(len, std::ios_base::beg); // Reset the read cursor, otherwise we skip the first message
312 break;
313 }
314 len = tellg();
315 }
317 {
318 LOG_WARN("{}: NMEA message type was set to 'GPZDA', but the file contains only 'GPGGA'. Make sure that the absolute time reference is set correctly.", nameId());
320 }
322 {
323 LOG_WARN("{}: NMEA message type was set to 'GPGGA', but the file contains 'GPZDA'. The absolute time reference was read from the header, not the GUI input.", nameId());
325 }
326 _delim = _gpzdaFound ? ',' : ' ';
327}
328
329std::shared_ptr<const NAV::NodeData> NAV::MultiImuFile::pollData(size_t pinIdx, bool peek)
330{
331 std::shared_ptr<ImuObs> obs = nullptr;
332
333 if (!_messages.at(pinIdx).empty()) // Another pin was reading a message for this pin
334 {
335 obs = _messages.at(pinIdx).begin()->second;
336 if (!peek) // When peeking, we leave the message in the buffer, so we can remove it when polling
337 {
338 _messages.at(pinIdx).erase(_messages.at(pinIdx).begin());
339 }
340 }
341 else
342 {
343 // Read line
344 std::string line;
345 while (getline(line))
346 {
347 _lineCounter++;
348
349 // Remove any starting non text characters
350 line.erase(line.begin(), std::ranges::find_if(line, [](int ch) { return std::isgraph(ch); }));
351
352 if (line.empty())
353 {
354 continue;
355 }
356
357 // Convert line into stream
358 std::stringstream lineStream(line);
359 std::string cell;
360
361 size_t sensorId{};
362 double gpsSecond{};
363 double timeNumerator{};
364 double timeDenominator{};
365 std::optional<double> accelX;
366 std::optional<double> accelY;
367 std::optional<double> accelZ;
368 std::optional<double> gyroX;
369 std::optional<double> gyroY;
370 std::optional<double> gyroZ;
371
372 // Split line at comma
373 for (const auto& col : _columns)
374 {
375 if (std::getline(lineStream, cell, _delim))
376 {
377 // Remove any trailing non text characters
378 cell.erase(std::ranges::find_if(cell, [](int ch) { return std::iscntrl(ch); }), cell.end());
379 while (cell.empty())
380 {
381 std::getline(lineStream, cell, ' ');
382 }
383
384 if (col == "sensorId")
385 {
386 sensorId = std::stoul(cell); // NOLINT(clang-diagnostic-implicit-int-conversion)
387 }
388 else if (col == "gpsSecond")
389 {
390 gpsSecond = std::stod(cell); // [s]
391 if (_startupGpsSecond == 0)
392 {
393 _startupGpsSecond = gpsSecond;
394 }
395 }
396 else if (col == "timeNumerator")
397 {
398 timeNumerator = std::stod(cell);
399 }
400 else if (col == "timeDenominator")
401 {
402 timeDenominator = std::stod(cell);
403 }
404 else if (col == "accelX")
405 {
406 accelX = 0.001 * std::stod(cell); // [m/s²]
407 }
408 else if (col == "accelY")
409 {
410 accelY = 0.001 * std::stod(cell); // [m/s²]
411 }
412 else if (col == "accelZ")
413 {
414 accelZ = 0.001 * std::stod(cell); // [m/s²]
415 }
416 else if (col == "gyroX")
417 {
418 gyroX = deg2rad(std::stod(cell) / 131); // [deg/s]
419 }
420 else if (col == "gyroY")
421 {
422 gyroY = deg2rad(std::stod(cell)) / 131; // [deg/s]
423 }
424 else if (col == "gyroZ")
425 {
426 gyroZ = deg2rad(std::stod(cell)) / 131; // [deg/s]
427 }
428 }
429 }
430
431 auto timeStamp = gpsSecond + timeNumerator / timeDenominator - _startupGpsSecond;
432 if (!peek)
433 {
434 LOG_DEBUG("line: {}", line);
435 LOG_DEBUG("timeStamp: {}", timeStamp);
436 }
437
438 obs = std::make_shared<ImuObs>(_imuPosAll[sensorId - 1]);
439
440 obs->insTime = _startTime + std::chrono::duration<double>(timeStamp);
441
442 if (!accelX || !accelY || !accelZ)
443 {
444 LOG_ERROR("{}: Fields 'accelX', 'accelY', 'accelZ' are needed.", nameId());
445 return nullptr;
446 }
447 if (!gyroX || !gyroY || !gyroZ)
448 {
449 LOG_ERROR("{}: Fields 'gyroX', 'gyroY', 'gyroZ' are needed.", nameId());
450 return nullptr;
451 }
452
453 obs->p_acceleration = { accelX.value(), accelY.value(), accelZ.value() };
454 obs->p_angularRate = { gyroX.value(), gyroY.value(), gyroZ.value() };
455
456 if (sensorId - 1 != pinIdx)
457 {
458 // Write message into buffer to process later on correct pin
459 _messages.at(sensorId - 1).insert(std::make_pair(obs->insTime, obs));
460
461 continue; // Read next line in file and search for correct sensor
462 }
463 if (peek)
464 {
465 // Write message into buffer to process later in poll step
466 _messages.at(pinIdx).insert(std::make_pair(obs->insTime, obs));
467 }
468 break;
469 }
470 }
471
472 // Calls all the callbacks
473 if (obs && !peek)
474 {
475 _messageCnt.at(pinIdx)++;
476
477 // Detect jumps back in time
478 if (obs->insTime < _lastFiltObs)
479 {
480 LOG_ERROR("{}: Jumped back in time on line {} (at {}), by {} s", nameId(), _lineCounter, obs->insTime.toYMDHMS(), static_cast<double>((obs->insTime - _lastFiltObs).count()));
481 return obs;
482 }
483 _lastFiltObs = obs->insTime;
484
485 invokeCallbacks(pinIdx, obs);
486 }
487 if (obs == nullptr)
488 {
489 LOG_DEBUG("{}: Finished reading on pinIdx {}. Read a total of {} messages.", nameId(), pinIdx, _messageCnt.at(pinIdx));
490 }
491 return obs;
492}
Transformation collection.
Combo representing an enumeration.
Save/Load the Nodes.
nlohmann::json json
json namespace
Text Help Marker (?) with Tooltip.
Utility class for logging to console and file.
#define LOG_DEBUG
Debug information. Should not be called on functions which receive observations (spamming)
Definition Logger.hpp:67
#define LOG_ERROR
Error occurred, which stops part of the program to work, but not everything.
Definition Logger.hpp:73
#define LOG_WARN
Error occurred, but a fallback option exists and program continues to work normally.
Definition Logger.hpp:71
#define LOG_TRACE
Detailled info to trace the execution of the program. Should not be called on functions which receive...
Definition Logger.hpp:65
File reader for Multi-IMU data log files.
bool initialize()
Initialize the file reader.
void restore(const json &j)
Restores the node from a json object.
auto peek()
Looking ahead in the stream.
bool good() const
Fast error checking.
FileType
File Type Enumeration.
@ ASCII
Ascii text data.
@ NONE
Not specified.
std::filesystem::path getFilepath()
Returns the path of the file.
std::streampos tellg()
Getting the current read position.
GuiResult guiConfig(const char *vFilters, const std::vector< std::string > &extensions, size_t id, const std::string &nameId)
ImGui config.
void resetReader()
Moves the read cursor to the start.
auto & getline(std::string &str)
Reads a line from the filestream.
json save() const
Saves the node into a json object.
auto & seekg(std::streamoff pos, std::ios_base::seekdir dir)
Changing the current read position.
void deinitialize()
Deinitialize the file reader.
The class is responsible for all time-related tasks.
Definition InsTime.hpp:710
char _delim
Delimiter: ',' for GPZDA and ' ' for GPGGA messages (NMEA)
std::vector< std::string > _headerColumns
Container of header column names.
NmeaType _nmeaType
Selected NMEA type in the GUI.
std::vector< std::string > _columns
Container of column names.
MultiImuFile()
Default constructor.
bool resetNode() override
Resets the node. Moves the read cursor to the start.
size_t _lineCounter
Counter for lines.
std::vector< std::map< InsTime, std::shared_ptr< ImuObs > > > _messages
Read messages. Vector idx: Sensor Id,.
static std::string category()
String representation of the Class Category.
void updateNumberOfOutputPins()
Adds/Deletes Output Pins depending on the variable _nOutputPins.
InsTime _startTime
Absolute start time.
bool _gpggaFound
Flag that indicates whether a 'GPGGA' message was found in the Multi-IMU-Logs header.
std::shared_ptr< const NodeData > pollData(size_t pinIdx, bool peek)
Polls data from the file.
static std::string typeStatic()
String representation of the Class Type.
std::vector< size_t > _messageCnt
Counter for messages.
double _gpsRate
GPS data rate [Hz].
json save() const override
Saves the node into a json object.
void restore(const json &j) override
Restores the node from a json object.
std::vector< ImuPos > _imuPosAll
Container for individual sensor orientations of a Multi-IMU.
gui::widgets::TimeEditFormat _startTimeEditFormat
Time Format to input the init time with.
bool initialize() override
Initialize the node.
size_t _nSensors
Number of connected sensors.
~MultiImuFile() override
Destructor.
InsTime _lastFiltObs
Previous observation (for timestamp)
void guiConfig() override
ImGui config window which is shown on double click.
@ GPGGA
NMEA message type.
@ GPZDA
NMEA message type.
std::string type() const override
String representation of the Class Type.
bool _gpzdaFound
Flag that indicates whether a 'GPZDA' message was found in the Multi-IMU-Logs header.
NAV::FileReader::FileType determineFileType() override
Function to determine the File Type.
void deinitialize() override
Deinitialize the node.
double _startupGpsSecond
First 'gpsSecond', s.t. measurements start at time = 0.
void readHeader() override
Function to read the Header of a file.
bool doDeinitialize(bool wait=false)
Asks the node worker to deinitialize the node.
Definition Node.cpp:465
ImVec2 _guiConfigDefaultWindowSize
Definition Node.hpp:522
std::vector< OutputPin > outputPins
List of output pins.
Definition Node.hpp:511
Node(std::string name)
Constructor.
Definition Node.cpp:29
OutputPin * CreateOutputPin(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.
Definition Node.cpp:278
std::string nameId() const
Node name and id.
Definition Node.cpp:323
std::string name
Name of the Node.
Definition Node.hpp:507
void invokeCallbacks(size_t portIndex, const std::shared_ptr< const NodeData > &data)
Calls all registered callbacks on the specified output port.
Definition Node.cpp:179
bool _hasConfig
Flag if the config window should be shown.
Definition Node.hpp:525
static float windowFontRatio()
Ratio to multiply for GUI window elements.
void ApplyChanges()
Signals that there have been changes to the flow.
bool TimeEdit(const char *str_id, InsTime &insTime, TimeEditFormat &timeEditFormat, float itemWidth=170.0F, int columns=1)
Inputs to edit an InsTime object.
Definition TimeEdit.cpp:52
bool EnumCombo(const char *label, T &enumeration, size_t startIdx=0)
Combo representing an enumeration.
Definition EnumCombo.hpp:30
void HelpMarker(const char *desc, const char *symbol="(?)")
Text Help Marker, e.g. '(?)', with Tooltip.
Eigen::Quaternion< Scalar > b_Quat_p(Scalar mountingAngleX, Scalar mountingAngleY, Scalar mountingAngleZ)
Quaternion for rotations from platform to body frame.
Eigen::Vector3< typename Derived::Scalar > quat2eulerZYX(const Eigen::QuaternionBase< Derived > &q)
Converts the quaternion to Euler rotation angles with rotation sequence ZYX.
@ UTC
Coordinated Universal Time.
constexpr auto deg2rad(const T &deg)
Convert Degree to Radians.
Definition Units.hpp:21
constexpr auto rad2deg(const T &rad)
Convert Radians to Degree.
Definition Units.hpp:39
@ Flow
NodeData Trigger.
Definition Pin.hpp:52