0.4.1
Loading...
Searching...
No Matches
VectorNavFile.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 "VectorNavFile.hpp"
10
11#include <exception>
12#include <vn/types.h>
13
14#include "util/Logger.hpp"
15#include "util/Assert.h"
16#include "util/StringUtil.hpp"
18
20namespace nm = NAV::NodeManager;
22
25
36
41
43{
44 return "VectorNavFile";
45}
46
47std::string NAV::VectorNavFile::type() const
48{
49 return typeStatic();
50}
51
53{
54 return "Data Provider";
55}
56
58{
59 if (auto res = FileReader::guiConfig("Supported types (*.csv *.vnb){.csv,.vnb},.*", { ".csv", ".vnb" }, size_t(id), nameId()))
60 {
61 LOG_DEBUG("{}: Path changed to {}", nameId(), _path);
63 if (res == FileReader::PATH_CHANGED)
64 {
66 }
67 else
68 {
70 }
71 }
72
74
75 // Header info
76 if (ImGui::BeginTable(fmt::format("##VectorNavHeaders ({})", id.AsPointer()).c_str(), 6,
77 ImGuiTableFlags_Borders | ImGuiTableFlags_RowBg | ImGuiTableFlags_NoHostExtendX | ImGuiTableFlags_SizingFixedFit))
78 {
79 ImGui::TableSetupColumn("Time", ImGuiTableColumnFlags_WidthFixed);
80 ImGui::TableSetupColumn("IMU", ImGuiTableColumnFlags_WidthFixed);
81 ImGui::TableSetupColumn("GNSS1", ImGuiTableColumnFlags_WidthFixed);
82 ImGui::TableSetupColumn("Attitude", ImGuiTableColumnFlags_WidthFixed);
83 ImGui::TableSetupColumn("INS", ImGuiTableColumnFlags_WidthFixed);
84 ImGui::TableSetupColumn("GNSS2", ImGuiTableColumnFlags_WidthFixed);
85 ImGui::TableHeadersRow();
86
87 auto TextColored = [](int index, const char* label, bool enabled) {
88 ImGui::TableSetColumnIndex(index);
89 if (enabled)
90 {
91 ImGui::TextUnformatted(label);
92 }
93 else
94 {
95 ImGui::TextDisabled("%s", label);
96 }
97 };
98
99 for (size_t i = 0; i < 16; i++)
100 {
101 if (i < std::max({ /* VectorNavSensor::_binaryGroupCommon.size(), */ VectorNavSensor::_binaryGroupTime.size(), VectorNavSensor::_binaryGroupIMU.size(),
103 {
104 ImGui::TableNextRow();
105 }
107 {
108 const auto& binaryGroupItem = VectorNavSensor::_binaryGroupTime.at(i);
109 TextColored(0, binaryGroupItem.name, _binaryOutputRegister.timeField & binaryGroupItem.flagsValue);
110 if (ImGui::IsItemHovered() && binaryGroupItem.tooltip != nullptr)
111 {
112 ImGui::BeginTooltip();
113 binaryGroupItem.tooltip();
114 ImGui::EndTooltip();
115 }
116 }
118 {
119 const auto& binaryGroupItem = VectorNavSensor::_binaryGroupIMU.at(i);
120 TextColored(1, binaryGroupItem.name, _binaryOutputRegister.imuField & binaryGroupItem.flagsValue);
121 if (ImGui::IsItemHovered() && binaryGroupItem.tooltip != nullptr)
122 {
123 ImGui::BeginTooltip();
124 binaryGroupItem.tooltip();
125 ImGui::EndTooltip();
126 }
127 }
129 {
130 const auto& binaryGroupItem = VectorNavSensor::_binaryGroupGNSS.at(i);
131 TextColored(2, binaryGroupItem.name, _binaryOutputRegister.gpsField & binaryGroupItem.flagsValue);
132 if (ImGui::IsItemHovered() && binaryGroupItem.tooltip != nullptr)
133 {
134 ImGui::BeginTooltip();
135 binaryGroupItem.tooltip();
136 ImGui::EndTooltip();
137 }
138 }
140 {
141 const auto& binaryGroupItem = VectorNavSensor::_binaryGroupAttitude.at(i);
142 TextColored(3, binaryGroupItem.name, _binaryOutputRegister.attitudeField & binaryGroupItem.flagsValue);
143 if (ImGui::IsItemHovered() && binaryGroupItem.tooltip != nullptr)
144 {
145 ImGui::BeginTooltip();
146 binaryGroupItem.tooltip();
147 ImGui::EndTooltip();
148 }
149 }
151 {
152 const auto& binaryGroupItem = VectorNavSensor::_binaryGroupINS.at(i);
153 TextColored(4, binaryGroupItem.name, _binaryOutputRegister.insField & binaryGroupItem.flagsValue);
154 if (ImGui::IsItemHovered() && binaryGroupItem.tooltip != nullptr)
155 {
156 ImGui::BeginTooltip();
157 binaryGroupItem.tooltip();
158 ImGui::EndTooltip();
159 }
160 }
162 {
163 const auto& binaryGroupItem = VectorNavSensor::_binaryGroupGNSS.at(i);
164 TextColored(5, binaryGroupItem.name, _binaryOutputRegister.gps2Field & binaryGroupItem.flagsValue);
165 if (ImGui::IsItemHovered() && binaryGroupItem.tooltip != nullptr)
166 {
167 ImGui::BeginTooltip();
168 binaryGroupItem.tooltip();
169 ImGui::EndTooltip();
170 }
171 }
172 }
173
174 ImGui::EndTable();
175 }
176}
177
178[[nodiscard]] json NAV::VectorNavFile::save() const
179{
180 LOG_TRACE("{}: called", nameId());
181
182 json j;
183
184 j["FileReader"] = FileReader::save();
185 j["Imu"] = Imu::save();
186
187 return j;
188}
189
191{
192 LOG_TRACE("{}: called", nameId());
193
194 if (j.contains("FileReader"))
195 {
196 FileReader::restore(j.at("FileReader"));
197 }
198 if (j.contains("Imu"))
199 {
200 Imu::restore(j.at("Imu"));
201 }
202}
203
205{
206 LOG_TRACE("{}: called", nameId());
207
208 return FileReader::initialize();
209}
210
212{
213 LOG_TRACE("{}: called", nameId());
214
216}
217
219{
221
222 _messageCount = 0;
223
224 return true;
225}
226
228{
229 LOG_TRACE("called");
230
231 std::filesystem::path filepath = getFilepath();
232
233 auto filestreamHeader = std::ifstream(filepath);
234 if (good())
235 {
236 std::array<char, std::string_view("GpsCycle,GpsWeek,GpsTow").length()> buffer{};
237 filestreamHeader.read(buffer.data(), buffer.size());
238 filestreamHeader.close();
239
240 if (std::string(buffer.data(), buffer.size()).starts_with("Time [s]"))
241 {
242 _hasTimeColumn = true;
243 return FileType::ASCII;
244 }
245 if (std::string(buffer.data(), buffer.size()).starts_with("GpsCycle,GpsWeek,GpsTow"))
246 {
247 _hasTimeColumn = false;
248 return FileType::ASCII;
249 }
250
251 return FileType::BINARY;
252 }
253
254 LOG_ERROR("Could not open file {}", filepath);
255 return FileType::NONE;
256}
257
259{
261 {
262 _binaryOutputRegister.timeField = vn::protocol::uart::TimeGroup::TIMEGROUP_NONE;
263 _binaryOutputRegister.imuField = vn::protocol::uart::ImuGroup::IMUGROUP_NONE;
264 _binaryOutputRegister.gpsField = vn::protocol::uart::GpsGroup::GPSGROUP_NONE;
265 _binaryOutputRegister.attitudeField = vn::protocol::uart::AttitudeGroup::ATTITUDEGROUP_NONE;
266 _binaryOutputRegister.insField = vn::protocol::uart::InsGroup::INSGROUP_NONE;
267 _binaryOutputRegister.gps2Field = vn::protocol::uart::GpsGroup::GPSGROUP_NONE;
268
269 // Read header line
270 std::string line;
271 getline(line);
272 // Remove any starting non text characters
273 line.erase(line.begin(), std::ranges::find_if(line, [](int ch) { return std::isalnum(ch); }));
274 // Convert line into stream
275 std::stringstream lineStream(line);
276 std::string cell;
277
278 int column = 0;
279 // Split line at comma
280 while (std::getline(lineStream, cell, ','))
281 {
282 if (column++ > (_hasTimeColumn ? 3 : 2))
283 {
284 // Remove any trailing non text characters
285 cell.erase(std::ranges::find_if(cell, [](int ch) { return std::iscntrl(ch); }), cell.end());
286
287 std::string group = cell.substr(0, cell.find("::")); // Extract the group (Time::TimeUTC::year -> 'Time')
288
289 cell = cell.substr(cell.find("::") + 2); // Remove the group -> 'TimeUTC::year'
290 if (cell.find("::") != std::string::npos)
291 {
292 cell = cell.substr(0, cell.find("::")); // Remove subgroups ('TimeUTC::year' -> 'TimeUTC')
293 }
294 if (cell.find(' ') != std::string::npos)
295 {
296 cell = cell.substr(0, cell.find(' ')); // Remove everything after a blank, which is the unit ('TimeStartup [ns]' -> 'TimeStartup')
297 }
298
299 bool identified = false;
300 if (group == "Time")
301 {
302 for (const auto& binaryGroupItem : VectorNavSensor::_binaryGroupTime)
303 {
304 if (cell == binaryGroupItem.name)
305 {
306 _binaryOutputRegister.timeField |= static_cast<vn::protocol::uart::TimeGroup>(binaryGroupItem.flagsValue);
307 identified = true;
308 break;
309 }
310 }
311 }
312 else if (group == "IMU")
313 {
314 for (const auto& binaryGroupItem : VectorNavSensor::_binaryGroupIMU)
315 {
316 if (cell == binaryGroupItem.name)
317 {
318 _binaryOutputRegister.imuField |= static_cast<vn::protocol::uart::ImuGroup>(binaryGroupItem.flagsValue);
319 identified = true;
320 break;
321 }
322 if (cell == "DeltaTime")
323 {
324 _binaryOutputRegister.imuField |= vn::protocol::uart::ImuGroup::IMUGROUP_DELTATHETA;
325 identified = true;
326 break;
327 }
328 }
329 }
330 else if (group == "GNSS1")
331 {
332 for (const auto& binaryGroupItem : VectorNavSensor::_binaryGroupGNSS)
333 {
334 if (cell == binaryGroupItem.name)
335 {
336 _binaryOutputRegister.gpsField |= static_cast<vn::protocol::uart::GpsGroup>(binaryGroupItem.flagsValue);
337 identified = true;
338 break;
339 }
340 }
341 }
342 else if (group == "Att")
343 {
344 for (const auto& binaryGroupItem : VectorNavSensor::_binaryGroupAttitude)
345 {
346 if (cell == binaryGroupItem.name)
347 {
348 _binaryOutputRegister.attitudeField |= static_cast<vn::protocol::uart::AttitudeGroup>(binaryGroupItem.flagsValue);
349 identified = true;
350 break;
351 }
352 }
353 }
354 else if (group == "INS")
355 {
356 for (const auto& binaryGroupItem : VectorNavSensor::_binaryGroupINS)
357 {
358 if (cell == binaryGroupItem.name)
359 {
360 _binaryOutputRegister.insField |= static_cast<vn::protocol::uart::InsGroup>(binaryGroupItem.flagsValue);
361 identified = true;
362 break;
363 }
364 }
365 }
366 else if (group == "GNSS2")
367 {
368 for (const auto& binaryGroupItem : VectorNavSensor::_binaryGroupGNSS)
369 {
370 if (cell == binaryGroupItem.name)
371 {
372 _binaryOutputRegister.gps2Field |= static_cast<vn::protocol::uart::GpsGroup>(binaryGroupItem.flagsValue);
373 identified = true;
374 break;
375 }
376 }
377 }
378 else
379 {
380 LOG_ERROR("{}: Could not identify the group in CSV header - {}::{}", nameId(), group, cell);
382 break;
383 }
384
385 if (!identified)
386 {
387 LOG_ERROR("{}: Could not identify the field in CSV header - {}::{}", nameId(), group, cell);
389 break;
390 }
391 }
392 }
393 }
394 else // if (fileType == FileType::BINARY)
395 {
396 read(reinterpret_cast<char*>(&_binaryOutputRegister.timeField), sizeof(vn::protocol::uart::TimeGroup));
397 read(reinterpret_cast<char*>(&_binaryOutputRegister.imuField), sizeof(vn::protocol::uart::ImuGroup));
398 read(reinterpret_cast<char*>(&_binaryOutputRegister.gpsField), sizeof(vn::protocol::uart::GpsGroup));
399 read(reinterpret_cast<char*>(&_binaryOutputRegister.attitudeField), sizeof(vn::protocol::uart::AttitudeGroup));
400 read(reinterpret_cast<char*>(&_binaryOutputRegister.insField), sizeof(vn::protocol::uart::InsGroup));
401 read(reinterpret_cast<char*>(&_binaryOutputRegister.gps2Field), sizeof(vn::protocol::uart::GpsGroup));
402 }
403}
404
405std::shared_ptr<const NAV::NodeData> NAV::VectorNavFile::pollData()
406{
407 auto obs = std::make_shared<VectorNavBinaryOutput>(_imuPos);
408
410 {
411 // Read line
412 std::string line;
413 getline(line);
414 // Remove any starting non text characters
415 line.erase(line.begin(), std::ranges::find_if(line, [](int ch) { return std::isgraph(ch); }));
416
417 if (line.empty())
418 {
419 LOG_DEBUG("{}: End of file reached after {} lines", nameId(), _messageCount);
420 return nullptr;
421 }
422
423 // Convert line into stream
424 std::stringstream lineStream(line);
425 LOG_DATA("{}: Reading line {}: {}", nameId(), _messageCount + 2, line);
426
427 auto extractCell = [&lineStream]() {
428 if (lineStream.eof())
429 {
430 throw std::runtime_error("End of file");
431 }
432 if (std::string cell; std::getline(lineStream, cell, ','))
433 {
434 // Remove any trailing non text characters
435 cell.erase(std::ranges::find_if(cell, [](int ch) { return std::iscntrl(ch); }), cell.end());
436
437 // LOG_DEBUG(" extractCell: {}", cell);
438 return cell;
439 }
440 return std::string("");
441 };
442 auto extractRemoveTillDelimiter = [](std::string& str, const std::string& delimiter) {
443 std::string extract;
444 if (size_t pos = str.find(delimiter);
445 pos != std::string::npos)
446 {
447 extract = str.substr(0, pos);
448 str = str.substr(pos + 1);
449 }
450
451 return extract;
452 };
453
454 auto extractSingleValue = [&](auto& field, auto flag, auto& out) {
455 static_assert(std::is_same_v<uint8_t&, decltype(out)> || std::is_same_v<uint16_t&, decltype(out)> || std::is_same_v<uint32_t&, decltype(out)> || std::is_same_v<uint64_t&, decltype(out)>
456 || std::is_same_v<int8_t&, decltype(out)> || std::is_same_v<int16_t&, decltype(out)> || std::is_same_v<int32_t&, decltype(out)>
457 || std::is_same_v<float&, decltype(out)> || std::is_same_v<double&, decltype(out)>
458 || std::is_same_v<std::string&, decltype(out)>);
459
460 // LOG_DEBUG("Extracting {}", vn::protocol::uart::to_string(flag));
461 auto cell = extractCell();
462
463 if (cell.empty())
464 {
465 field &= ~flag; // unset the flag
466 }
467 else
468 {
469 if constexpr (std::is_same_v<uint8_t&, decltype(out)>
470 || std::is_same_v<uint16_t&, decltype(out)>
471 || std::is_same_v<uint32_t&, decltype(out)>)
472 {
473 out = static_cast<std::remove_reference_t<decltype(out)>>(std::stoul(cell));
474 }
475 else if constexpr (std::is_same_v<uint64_t&, decltype(out)>)
476 {
477 out = static_cast<std::remove_reference_t<decltype(out)>>(std::stoull(cell));
478 }
479 else if constexpr (std::is_same_v<int8_t&, decltype(out)>
480 || std::is_same_v<int16_t&, decltype(out)>
481 || std::is_same_v<int32_t&, decltype(out)>)
482 {
483 out = static_cast<std::remove_reference_t<decltype(out)>>(std::stoi(cell));
484 }
485 else if constexpr (std::is_same_v<float&, decltype(out)>)
486 {
487 out = static_cast<std::remove_reference_t<decltype(out)>>(std::stof(cell));
488 }
489 else if constexpr (std::is_same_v<double&, decltype(out)>)
490 {
491 out = static_cast<std::remove_reference_t<decltype(out)>>(std::stod(cell));
492 }
493 else if constexpr (std::is_same_v<std::string&, decltype(out)>)
494 {
495 out = cell;
496 }
497 }
498 };
499
500 auto extractValue = [&](auto& field, auto flag, auto&... out) {
501 if (field & flag)
502 {
503 (extractSingleValue(field, flag, out), ...);
504 }
505 };
506
507 try
508 {
509 if (_hasTimeColumn) { extractCell(); } // Time [s]
510 std::string gpsCycle = extractCell();
511 std::string gpsWeek = extractCell();
512 std::string gpsTow = extractCell();
513 if (!gpsCycle.empty() && !gpsWeek.empty() && !gpsTow.empty())
514 {
515 obs->insTime = InsTime(std::stoi(gpsCycle), std::stoi(gpsWeek), std::stold(gpsTow));
516 }
517
518 // Group 2 (Time)
519 if (_binaryOutputRegister.timeField != vn::protocol::uart::TimeGroup::TIMEGROUP_NONE)
520 {
521 if (!obs->timeOutputs)
522 {
523 obs->timeOutputs = std::make_shared<NAV::vendor::vectornav::TimeOutputs>();
524 obs->timeOutputs->timeField |= _binaryOutputRegister.timeField;
525 }
526
527 extractValue(obs->timeOutputs->timeField, vn::protocol::uart::TimeGroup::TIMEGROUP_TIMESTARTUP, obs->timeOutputs->timeStartup);
528 extractValue(obs->timeOutputs->timeField, vn::protocol::uart::TimeGroup::TIMEGROUP_TIMEGPS, obs->timeOutputs->timeGps);
529 extractValue(obs->timeOutputs->timeField, vn::protocol::uart::TimeGroup::TIMEGROUP_GPSTOW, obs->timeOutputs->gpsTow);
530 extractValue(obs->timeOutputs->timeField, vn::protocol::uart::TimeGroup::TIMEGROUP_GPSWEEK, obs->timeOutputs->gpsWeek);
531 extractValue(obs->timeOutputs->timeField, vn::protocol::uart::TimeGroup::TIMEGROUP_TIMESYNCIN, obs->timeOutputs->timeSyncIn);
532 extractValue(obs->timeOutputs->timeField, vn::protocol::uart::TimeGroup::TIMEGROUP_TIMEGPSPPS, obs->timeOutputs->timePPS);
533 extractValue(obs->timeOutputs->timeField, vn::protocol::uart::TimeGroup::TIMEGROUP_TIMEUTC,
534 obs->timeOutputs->timeUtc.year, obs->timeOutputs->timeUtc.month, obs->timeOutputs->timeUtc.day,
535 obs->timeOutputs->timeUtc.hour, obs->timeOutputs->timeUtc.min, obs->timeOutputs->timeUtc.sec, obs->timeOutputs->timeUtc.ms);
536 extractValue(obs->timeOutputs->timeField, vn::protocol::uart::TimeGroup::TIMEGROUP_SYNCINCNT, obs->timeOutputs->syncInCnt);
537 extractValue(obs->timeOutputs->timeField, vn::protocol::uart::TimeGroup::TIMEGROUP_SYNCOUTCNT, obs->timeOutputs->syncOutCnt);
538 uint8_t timeOk{};
539 uint8_t dateOk{};
540 uint8_t utcTimeValid{};
541 extractValue(obs->timeOutputs->timeField, vn::protocol::uart::TimeGroup::TIMEGROUP_TIMESTATUS, timeOk, dateOk, utcTimeValid);
542 if (obs->timeOutputs->timeField & vn::protocol::uart::TimeGroup::TIMEGROUP_TIMESTATUS)
543 {
544 obs->timeOutputs->timeStatus = static_cast<uint8_t>(timeOk << 0U | dateOk << 1U | utcTimeValid << 2U);
545 }
546
547 if (obs->timeOutputs->timeField == vn::protocol::uart::TimeGroup::TIMEGROUP_NONE) { obs->timeOutputs.reset(); }
548 }
549 // Group 3 (IMU)
550 if (_binaryOutputRegister.imuField != vn::protocol::uart::ImuGroup::IMUGROUP_NONE)
551 {
552 if (!obs->imuOutputs)
553 {
554 obs->imuOutputs = std::make_shared<NAV::vendor::vectornav::ImuOutputs>();
555 obs->imuOutputs->imuField |= _binaryOutputRegister.imuField;
556 }
557
558 extractValue(obs->imuOutputs->imuField, vn::protocol::uart::ImuGroup::IMUGROUP_IMUSTATUS, obs->imuOutputs->imuStatus);
559 extractValue(obs->imuOutputs->imuField, vn::protocol::uart::ImuGroup::IMUGROUP_UNCOMPMAG,
560 obs->imuOutputs->uncompMag.x(), obs->imuOutputs->uncompMag.y(), obs->imuOutputs->uncompMag.z());
561 extractValue(obs->imuOutputs->imuField, vn::protocol::uart::ImuGroup::IMUGROUP_UNCOMPACCEL,
562 obs->imuOutputs->uncompAccel.x(), obs->imuOutputs->uncompAccel.y(), obs->imuOutputs->uncompAccel.z());
563 extractValue(obs->imuOutputs->imuField, vn::protocol::uart::ImuGroup::IMUGROUP_UNCOMPGYRO,
564 obs->imuOutputs->uncompGyro.x(), obs->imuOutputs->uncompGyro.y(), obs->imuOutputs->uncompGyro.z());
565 extractValue(obs->imuOutputs->imuField, vn::protocol::uart::ImuGroup::IMUGROUP_TEMP, obs->imuOutputs->temp);
566 extractValue(obs->imuOutputs->imuField, vn::protocol::uart::ImuGroup::IMUGROUP_PRES, obs->imuOutputs->pres);
567 extractValue(obs->imuOutputs->imuField, vn::protocol::uart::ImuGroup::IMUGROUP_DELTATHETA,
568 obs->imuOutputs->deltaTime, obs->imuOutputs->deltaTheta.x(), obs->imuOutputs->deltaTheta.y(), obs->imuOutputs->deltaTheta.z());
569 extractValue(obs->imuOutputs->imuField, vn::protocol::uart::ImuGroup::IMUGROUP_DELTAVEL,
570 obs->imuOutputs->deltaV.x(), obs->imuOutputs->deltaV.y(), obs->imuOutputs->deltaV.z());
571 extractValue(obs->imuOutputs->imuField, vn::protocol::uart::ImuGroup::IMUGROUP_MAG,
572 obs->imuOutputs->mag.x(), obs->imuOutputs->mag.y(), obs->imuOutputs->mag.z());
573 extractValue(obs->imuOutputs->imuField, vn::protocol::uart::ImuGroup::IMUGROUP_ACCEL,
574 obs->imuOutputs->accel.x(), obs->imuOutputs->accel.y(), obs->imuOutputs->accel.z());
575 extractValue(obs->imuOutputs->imuField, vn::protocol::uart::ImuGroup::IMUGROUP_ANGULARRATE,
576 obs->imuOutputs->angularRate.x(), obs->imuOutputs->angularRate.y(), obs->imuOutputs->angularRate.z());
577
578 if (obs->imuOutputs->imuField == vn::protocol::uart::ImuGroup::IMUGROUP_NONE) { obs->imuOutputs.reset(); }
579 }
580 // Group 4 (GNSS1)
581 if (_binaryOutputRegister.gpsField != vn::protocol::uart::GpsGroup::GPSGROUP_NONE)
582 {
583 if (!obs->gnss1Outputs)
584 {
585 obs->gnss1Outputs = std::make_shared<NAV::vendor::vectornav::GnssOutputs>();
586 obs->gnss1Outputs->gnssField |= _binaryOutputRegister.gpsField;
587 }
588
589 extractValue(obs->gnss1Outputs->gnssField, vn::protocol::uart::GpsGroup::GPSGROUP_UTC,
590 obs->gnss1Outputs->timeUtc.year, obs->gnss1Outputs->timeUtc.month, obs->gnss1Outputs->timeUtc.day,
591 obs->gnss1Outputs->timeUtc.hour, obs->gnss1Outputs->timeUtc.min, obs->gnss1Outputs->timeUtc.sec, obs->gnss1Outputs->timeUtc.ms);
592 extractValue(obs->gnss1Outputs->gnssField, vn::protocol::uart::GpsGroup::GPSGROUP_TOW, obs->gnss1Outputs->tow);
593 extractValue(obs->gnss1Outputs->gnssField, vn::protocol::uart::GpsGroup::GPSGROUP_WEEK, obs->gnss1Outputs->week);
594 extractValue(obs->gnss1Outputs->gnssField, vn::protocol::uart::GpsGroup::GPSGROUP_NUMSATS, obs->gnss1Outputs->numSats);
595 extractValue(obs->gnss1Outputs->gnssField, vn::protocol::uart::GpsGroup::GPSGROUP_FIX, obs->gnss1Outputs->fix);
596 extractValue(obs->gnss1Outputs->gnssField, vn::protocol::uart::GpsGroup::GPSGROUP_POSLLA,
597 obs->gnss1Outputs->posLla.x(), obs->gnss1Outputs->posLla.y(), obs->gnss1Outputs->posLla.z());
598 extractValue(obs->gnss1Outputs->gnssField, vn::protocol::uart::GpsGroup::GPSGROUP_POSECEF,
599 obs->gnss1Outputs->posEcef.x(), obs->gnss1Outputs->posEcef.y(), obs->gnss1Outputs->posEcef.z());
600 extractValue(obs->gnss1Outputs->gnssField, vn::protocol::uart::GpsGroup::GPSGROUP_VELNED,
601 obs->gnss1Outputs->velNed.x(), obs->gnss1Outputs->velNed.y(), obs->gnss1Outputs->velNed.z());
602 extractValue(obs->gnss1Outputs->gnssField, vn::protocol::uart::GpsGroup::GPSGROUP_VELECEF,
603 obs->gnss1Outputs->velEcef.x(), obs->gnss1Outputs->velEcef.y(), obs->gnss1Outputs->velEcef.z());
604 extractValue(obs->gnss1Outputs->gnssField, vn::protocol::uart::GpsGroup::GPSGROUP_POSU,
605 obs->gnss1Outputs->posU.x(), obs->gnss1Outputs->posU.y(), obs->gnss1Outputs->posU.z());
606 extractValue(obs->gnss1Outputs->gnssField, vn::protocol::uart::GpsGroup::GPSGROUP_VELU, obs->gnss1Outputs->velU);
607 extractValue(obs->gnss1Outputs->gnssField, vn::protocol::uart::GpsGroup::GPSGROUP_TIMEU, obs->gnss1Outputs->timeU);
608
609 uint8_t timeOk{};
610 uint8_t dateOk{};
611 uint8_t utcTimeValid{};
612 int8_t leapSeconds{};
613 extractValue(obs->gnss1Outputs->gnssField, vn::protocol::uart::GpsGroup::GPSGROUP_TIMEINFO, timeOk, dateOk, utcTimeValid, leapSeconds);
614 if (obs->gnss1Outputs->gnssField & vn::protocol::uart::GpsGroup::GPSGROUP_TIMEINFO)
615 {
616 obs->gnss1Outputs->timeInfo.status = static_cast<uint8_t>(timeOk << 0U | dateOk << 1U | utcTimeValid << 2U);
617 obs->gnss1Outputs->timeInfo.leapSeconds = leapSeconds;
618 }
619 extractValue(obs->gnss1Outputs->gnssField, vn::protocol::uart::GpsGroup::GPSGROUP_DOP,
620 obs->gnss1Outputs->dop.gDop, obs->gnss1Outputs->dop.pDop, obs->gnss1Outputs->dop.tDop, obs->gnss1Outputs->dop.vDop,
621 obs->gnss1Outputs->dop.hDop, obs->gnss1Outputs->dop.nDop, obs->gnss1Outputs->dop.eDop);
622
623 std::string satellites;
624 bool flag = obs->gnss1Outputs->gnssField & vn::protocol::uart::GpsGroup::GPSGROUP_SATINFO;
625 extractValue(obs->gnss1Outputs->gnssField, vn::protocol::uart::GpsGroup::GPSGROUP_SATINFO,
626 obs->gnss1Outputs->satInfo.numSats, satellites);
627 if (obs->gnss1Outputs->gnssField & vn::protocol::uart::GpsGroup::GPSGROUP_SATINFO)
628 {
629 for (size_t i = 0; i < obs->gnss1Outputs->satInfo.numSats; i++)
630 {
631 satellites = satellites.substr(1); // Remove leading '['
632 auto sys = static_cast<int8_t>(std::stoi(extractRemoveTillDelimiter(satellites, "|")));
633 auto svId = static_cast<uint8_t>(std::stoul(extractRemoveTillDelimiter(satellites, "|")));
634 auto flagHealthy = static_cast<uint8_t>(std::stoul(extractRemoveTillDelimiter(satellites, "|")));
635 auto flagAlmanac = static_cast<uint8_t>(std::stoul(extractRemoveTillDelimiter(satellites, "|")));
636 auto flagEphemeris = static_cast<uint8_t>(std::stoul(extractRemoveTillDelimiter(satellites, "|")));
637 auto flagDifferentialCorrection = static_cast<uint8_t>(std::stoul(extractRemoveTillDelimiter(satellites, "|")));
638 auto flagUsedForNavigation = static_cast<uint8_t>(std::stoul(extractRemoveTillDelimiter(satellites, "|")));
639 auto flagAzimuthElevationValid = static_cast<uint8_t>(std::stoul(extractRemoveTillDelimiter(satellites, "|")));
640 auto flagUsedForRTK = static_cast<uint8_t>(std::stoul(extractRemoveTillDelimiter(satellites, "|")));
641 auto flags = static_cast<uint8_t>(flagHealthy << 0U
642 | flagAlmanac << 1U
643 | flagEphemeris << 2U
644 | flagDifferentialCorrection << 3U
645 | flagUsedForNavigation << 4U
646 | flagAzimuthElevationValid << 5U
647 | flagUsedForRTK << 6U);
648 auto cno = static_cast<uint8_t>(std::stoul(extractRemoveTillDelimiter(satellites, "|")));
649 auto qi = static_cast<uint8_t>(std::stoul(extractRemoveTillDelimiter(satellites, "|")));
650 auto el = static_cast<int8_t>(std::stoi(extractRemoveTillDelimiter(satellites, "|")));
651 auto az = static_cast<int16_t>(std::stoi(extractRemoveTillDelimiter(satellites, "]")));
652 obs->gnss1Outputs->satInfo.satellites.emplace_back(sys, svId, flags, cno, qi, el, az);
653 }
654 }
655 if (flag && satellites.empty() && !(obs->gnss1Outputs->gnssField & vn::protocol::uart::GpsGroup::GPSGROUP_SATINFO))
656 {
657 obs->gnss1Outputs->gnssField |= vn::protocol::uart::GpsGroup::GPSGROUP_SATINFO;
658 }
659
660 satellites.clear();
661 flag = obs->gnss1Outputs->gnssField & vn::protocol::uart::GpsGroup::GPSGROUP_RAWMEAS;
662 extractValue(obs->gnss1Outputs->gnssField, vn::protocol::uart::GpsGroup::GPSGROUP_RAWMEAS,
663 obs->gnss1Outputs->raw.tow, obs->gnss1Outputs->raw.week, obs->gnss1Outputs->raw.numSats, satellites);
664 if (obs->gnss1Outputs->gnssField & vn::protocol::uart::GpsGroup::GPSGROUP_RAWMEAS)
665 {
666 for (size_t i = 0; i < obs->gnss1Outputs->raw.numSats; i++)
667 {
668 satellites = satellites.substr(1); // Remove leading '['
669 auto sys = static_cast<uint8_t>(std::stoul(extractRemoveTillDelimiter(satellites, "|")));
670 auto svId = static_cast<uint8_t>(std::stoul(extractRemoveTillDelimiter(satellites, "|")));
671 auto freq = static_cast<uint8_t>(std::stoul(extractRemoveTillDelimiter(satellites, "|")));
672 auto chan = static_cast<uint8_t>(std::stoul(extractRemoveTillDelimiter(satellites, "|")));
673 auto slot = static_cast<int8_t>(std::stoi(extractRemoveTillDelimiter(satellites, "|")));
674 auto cno = static_cast<uint8_t>(std::stoul(extractRemoveTillDelimiter(satellites, "|")));
675 auto flagSearching = static_cast<uint8_t>(std::stoul(extractRemoveTillDelimiter(satellites, "|")));
676 auto flagTracking = static_cast<uint8_t>(std::stoul(extractRemoveTillDelimiter(satellites, "|")));
677 auto flagTimeValid = static_cast<uint8_t>(std::stoul(extractRemoveTillDelimiter(satellites, "|")));
678 auto flagCodeLock = static_cast<uint8_t>(std::stoul(extractRemoveTillDelimiter(satellites, "|")));
679 auto flagPhaseLock = static_cast<uint8_t>(std::stoul(extractRemoveTillDelimiter(satellites, "|")));
680 auto flagPhaseHalfAmbiguity = static_cast<uint8_t>(std::stoul(extractRemoveTillDelimiter(satellites, "|")));
681 auto flagPhaseHalfSub = static_cast<uint8_t>(std::stoul(extractRemoveTillDelimiter(satellites, "|")));
682 auto flagPhaseSlip = static_cast<uint8_t>(std::stoul(extractRemoveTillDelimiter(satellites, "|")));
683 auto flagPseudorangeSmoothed = static_cast<uint8_t>(std::stoul(extractRemoveTillDelimiter(satellites, "|")));
684 auto flags = static_cast<uint16_t>(flagSearching << 0U
685 | flagTracking << 1U
686 | flagTimeValid << 2U
687 | flagCodeLock << 3U
688 | flagPhaseLock << 4U
689 | flagPhaseHalfAmbiguity << 5U
690 | flagPhaseHalfSub << 6U
691 | flagPhaseSlip << 7U
692 | flagPseudorangeSmoothed << 8U);
693 auto pr = std::stod(extractRemoveTillDelimiter(satellites, "|"));
694 auto cp = std::stod(extractRemoveTillDelimiter(satellites, "|"));
695 auto dp = std::stof(extractRemoveTillDelimiter(satellites, "]"));
696 obs->gnss1Outputs->raw.satellites.emplace_back(sys, svId, freq, chan, slot, cno, flags, pr, cp, dp);
697 }
698 }
699 if (flag && satellites.empty() && !(obs->gnss1Outputs->gnssField & vn::protocol::uart::GpsGroup::GPSGROUP_RAWMEAS))
700 {
701 obs->gnss1Outputs->gnssField |= vn::protocol::uart::GpsGroup::GPSGROUP_RAWMEAS;
702 }
703
704 if (obs->gnss1Outputs->gnssField == vn::protocol::uart::GpsGroup::GPSGROUP_NONE) { obs->gnss1Outputs.reset(); }
705 }
706 // Group 5 (Attitude)
707 if (_binaryOutputRegister.attitudeField != vn::protocol::uart::AttitudeGroup::ATTITUDEGROUP_NONE)
708 {
709 if (!obs->attitudeOutputs)
710 {
711 obs->attitudeOutputs = std::make_shared<NAV::vendor::vectornav::AttitudeOutputs>();
712 obs->attitudeOutputs->attitudeField |= _binaryOutputRegister.attitudeField;
713 }
714
715 uint16_t vpeStatus{};
716 extractValue(obs->attitudeOutputs->attitudeField, vn::protocol::uart::AttitudeGroup::ATTITUDEGROUP_VPESTATUS, vpeStatus);
717 obs->attitudeOutputs->vpeStatus = vpeStatus;
718 extractValue(obs->attitudeOutputs->attitudeField, vn::protocol::uart::AttitudeGroup::ATTITUDEGROUP_YAWPITCHROLL,
719 obs->attitudeOutputs->ypr.x(), obs->attitudeOutputs->ypr.y(), obs->attitudeOutputs->ypr.z());
720 extractValue(obs->attitudeOutputs->attitudeField, vn::protocol::uart::AttitudeGroup::ATTITUDEGROUP_QUATERNION,
721 obs->attitudeOutputs->qtn.w(), obs->attitudeOutputs->qtn.x(), obs->attitudeOutputs->qtn.y(), obs->attitudeOutputs->qtn.z());
722 extractValue(obs->attitudeOutputs->attitudeField, vn::protocol::uart::AttitudeGroup::ATTITUDEGROUP_DCM,
723 obs->attitudeOutputs->dcm(0, 0), obs->attitudeOutputs->dcm(0, 1), obs->attitudeOutputs->dcm(0, 2),
724 obs->attitudeOutputs->dcm(1, 0), obs->attitudeOutputs->dcm(1, 1), obs->attitudeOutputs->dcm(1, 2),
725 obs->attitudeOutputs->dcm(2, 0), obs->attitudeOutputs->dcm(2, 1), obs->attitudeOutputs->dcm(2, 2));
726 extractValue(obs->attitudeOutputs->attitudeField, vn::protocol::uart::AttitudeGroup::ATTITUDEGROUP_MAGNED,
727 obs->attitudeOutputs->magNed.x(), obs->attitudeOutputs->magNed.y(), obs->attitudeOutputs->magNed.z());
728 extractValue(obs->attitudeOutputs->attitudeField, vn::protocol::uart::AttitudeGroup::ATTITUDEGROUP_ACCELNED,
729 obs->attitudeOutputs->accelNed.x(), obs->attitudeOutputs->accelNed.y(), obs->attitudeOutputs->accelNed.z());
730 extractValue(obs->attitudeOutputs->attitudeField, vn::protocol::uart::AttitudeGroup::ATTITUDEGROUP_LINEARACCELBODY,
731 obs->attitudeOutputs->linearAccelBody.x(), obs->attitudeOutputs->linearAccelBody.y(), obs->attitudeOutputs->linearAccelBody.z());
732 extractValue(obs->attitudeOutputs->attitudeField, vn::protocol::uart::AttitudeGroup::ATTITUDEGROUP_LINEARACCELNED,
733 obs->attitudeOutputs->linearAccelNed.x(), obs->attitudeOutputs->linearAccelNed.y(), obs->attitudeOutputs->linearAccelNed.z());
734 extractValue(obs->attitudeOutputs->attitudeField, vn::protocol::uart::AttitudeGroup::ATTITUDEGROUP_YPRU,
735 obs->attitudeOutputs->yprU.x(), obs->attitudeOutputs->yprU.y(), obs->attitudeOutputs->yprU.z());
736
737 if (obs->attitudeOutputs->attitudeField == vn::protocol::uart::AttitudeGroup::ATTITUDEGROUP_NONE) { obs->attitudeOutputs.reset(); }
738 }
739 // Group 6 (INS)
740 if (_binaryOutputRegister.insField != vn::protocol::uart::InsGroup::INSGROUP_NONE)
741 {
742 if (!obs->insOutputs)
743 {
744 obs->insOutputs = std::make_shared<NAV::vendor::vectornav::InsOutputs>();
745 obs->insOutputs->insField |= _binaryOutputRegister.insField;
746 }
747
748 uint8_t mode{};
749 uint8_t gpsFix{};
750 uint8_t errorImu{};
751 uint8_t errorMagPres{};
752 uint8_t errorGnss{};
753 uint8_t gpsHeadingIns{};
754 uint8_t gpsCompass{};
755 extractValue(obs->insOutputs->insField, vn::protocol::uart::InsGroup::INSGROUP_INSSTATUS,
756 mode, gpsFix, errorImu, errorMagPres, errorGnss, gpsHeadingIns, gpsCompass);
757 if (obs->insOutputs->insField & vn::protocol::uart::InsGroup::INSGROUP_INSSTATUS)
758 {
759 obs->insOutputs->insStatus.status() = static_cast<uint16_t>(mode << 0U | gpsFix << 2U
760 | errorImu << 4U | errorMagPres << 5U | errorGnss << 6U
761 | gpsHeadingIns << 8U | gpsCompass << 9U);
762 }
763 extractValue(obs->insOutputs->insField, vn::protocol::uart::InsGroup::INSGROUP_POSLLA,
764 obs->insOutputs->posLla.x(), obs->insOutputs->posLla.y(), obs->insOutputs->posLla.z());
765 extractValue(obs->insOutputs->insField, vn::protocol::uart::InsGroup::INSGROUP_POSECEF,
766 obs->insOutputs->posEcef.x(), obs->insOutputs->posEcef.y(), obs->insOutputs->posEcef.z());
767 extractValue(obs->insOutputs->insField, vn::protocol::uart::InsGroup::INSGROUP_VELBODY,
768 obs->insOutputs->velBody.x(), obs->insOutputs->velBody.y(), obs->insOutputs->velBody.z());
769 extractValue(obs->insOutputs->insField, vn::protocol::uart::InsGroup::INSGROUP_VELNED,
770 obs->insOutputs->velNed.x(), obs->insOutputs->velNed.y(), obs->insOutputs->velNed.z());
771 extractValue(obs->insOutputs->insField, vn::protocol::uart::InsGroup::INSGROUP_VELECEF,
772 obs->insOutputs->velEcef.x(), obs->insOutputs->velEcef.y(), obs->insOutputs->velEcef.z());
773 extractValue(obs->insOutputs->insField, vn::protocol::uart::InsGroup::INSGROUP_MAGECEF,
774 obs->insOutputs->magEcef.x(), obs->insOutputs->magEcef.y(), obs->insOutputs->magEcef.z());
775 extractValue(obs->insOutputs->insField, vn::protocol::uart::InsGroup::INSGROUP_ACCELECEF,
776 obs->insOutputs->accelEcef.x(), obs->insOutputs->accelEcef.y(), obs->insOutputs->accelEcef.z());
777 extractValue(obs->insOutputs->insField, vn::protocol::uart::InsGroup::INSGROUP_LINEARACCELECEF,
778 obs->insOutputs->linearAccelEcef.x(), obs->insOutputs->linearAccelEcef.y(), obs->insOutputs->linearAccelEcef.z());
779 extractValue(obs->insOutputs->insField, vn::protocol::uart::InsGroup::INSGROUP_POSU, obs->insOutputs->posU);
780 extractValue(obs->insOutputs->insField, vn::protocol::uart::InsGroup::INSGROUP_VELU, obs->insOutputs->velU);
781
782 if (obs->insOutputs->insField == vn::protocol::uart::InsGroup::INSGROUP_NONE) { obs->insOutputs.reset(); }
783 }
784 // Group 7 (GNSS2)
785 if (_binaryOutputRegister.gps2Field != vn::protocol::uart::GpsGroup::GPSGROUP_NONE)
786 {
787 if (!obs->gnss2Outputs)
788 {
789 obs->gnss2Outputs = std::make_shared<NAV::vendor::vectornav::GnssOutputs>();
790 obs->gnss2Outputs->gnssField |= _binaryOutputRegister.gps2Field;
791 }
792
793 extractValue(obs->gnss2Outputs->gnssField, vn::protocol::uart::GpsGroup::GPSGROUP_UTC,
794 obs->gnss2Outputs->timeUtc.year, obs->gnss2Outputs->timeUtc.month, obs->gnss2Outputs->timeUtc.day,
795 obs->gnss2Outputs->timeUtc.hour, obs->gnss2Outputs->timeUtc.min, obs->gnss2Outputs->timeUtc.sec, obs->gnss2Outputs->timeUtc.ms);
796 extractValue(obs->gnss2Outputs->gnssField, vn::protocol::uart::GpsGroup::GPSGROUP_TOW, obs->gnss2Outputs->tow);
797 extractValue(obs->gnss2Outputs->gnssField, vn::protocol::uart::GpsGroup::GPSGROUP_WEEK, obs->gnss2Outputs->week);
798 extractValue(obs->gnss2Outputs->gnssField, vn::protocol::uart::GpsGroup::GPSGROUP_NUMSATS, obs->gnss2Outputs->numSats);
799 extractValue(obs->gnss2Outputs->gnssField, vn::protocol::uart::GpsGroup::GPSGROUP_FIX, obs->gnss2Outputs->fix);
800 extractValue(obs->gnss2Outputs->gnssField, vn::protocol::uart::GpsGroup::GPSGROUP_POSLLA,
801 obs->gnss2Outputs->posLla.x(), obs->gnss2Outputs->posLla.y(), obs->gnss2Outputs->posLla.z());
802 extractValue(obs->gnss2Outputs->gnssField, vn::protocol::uart::GpsGroup::GPSGROUP_POSECEF,
803 obs->gnss2Outputs->posEcef.x(), obs->gnss2Outputs->posEcef.y(), obs->gnss2Outputs->posEcef.z());
804 extractValue(obs->gnss2Outputs->gnssField, vn::protocol::uart::GpsGroup::GPSGROUP_VELNED,
805 obs->gnss2Outputs->velNed.x(), obs->gnss2Outputs->velNed.y(), obs->gnss2Outputs->velNed.z());
806 extractValue(obs->gnss2Outputs->gnssField, vn::protocol::uart::GpsGroup::GPSGROUP_VELECEF,
807 obs->gnss2Outputs->velEcef.x(), obs->gnss2Outputs->velEcef.y(), obs->gnss2Outputs->velEcef.z());
808 extractValue(obs->gnss2Outputs->gnssField, vn::protocol::uart::GpsGroup::GPSGROUP_POSU,
809 obs->gnss2Outputs->posU.x(), obs->gnss2Outputs->posU.y(), obs->gnss2Outputs->posU.z());
810 extractValue(obs->gnss2Outputs->gnssField, vn::protocol::uart::GpsGroup::GPSGROUP_VELU, obs->gnss2Outputs->velU);
811 extractValue(obs->gnss2Outputs->gnssField, vn::protocol::uart::GpsGroup::GPSGROUP_TIMEU, obs->gnss2Outputs->timeU);
812
813 uint8_t timeOk{};
814 uint8_t dateOk{};
815 uint8_t utcTimeValid{};
816 int8_t leapSeconds{};
817 extractValue(obs->gnss2Outputs->gnssField, vn::protocol::uart::GpsGroup::GPSGROUP_TIMEINFO, timeOk, dateOk, utcTimeValid, leapSeconds);
818 if (obs->gnss2Outputs->gnssField & vn::protocol::uart::GpsGroup::GPSGROUP_TIMEINFO)
819 {
820 obs->gnss2Outputs->timeInfo.status = static_cast<uint8_t>(timeOk << 0U | dateOk << 1U | utcTimeValid << 2U);
821 obs->gnss2Outputs->timeInfo.leapSeconds = leapSeconds;
822 }
823 extractValue(obs->gnss2Outputs->gnssField, vn::protocol::uart::GpsGroup::GPSGROUP_DOP,
824 obs->gnss2Outputs->dop.gDop, obs->gnss2Outputs->dop.pDop, obs->gnss2Outputs->dop.tDop, obs->gnss2Outputs->dop.vDop,
825 obs->gnss2Outputs->dop.hDop, obs->gnss2Outputs->dop.nDop, obs->gnss2Outputs->dop.eDop);
826
827 std::string satellites;
828 bool flag = obs->gnss2Outputs->gnssField & vn::protocol::uart::GpsGroup::GPSGROUP_SATINFO;
829 extractValue(obs->gnss2Outputs->gnssField, vn::protocol::uart::GpsGroup::GPSGROUP_SATINFO,
830 obs->gnss2Outputs->satInfo.numSats, satellites);
831 if (obs->gnss2Outputs->gnssField & vn::protocol::uart::GpsGroup::GPSGROUP_SATINFO)
832 {
833 for (size_t i = 0; i < obs->gnss2Outputs->satInfo.numSats; i++)
834 {
835 satellites = satellites.substr(1); // Remove leading '['
836 auto sys = static_cast<int8_t>(std::stoi(extractRemoveTillDelimiter(satellites, "|")));
837 auto svId = static_cast<uint8_t>(std::stoul(extractRemoveTillDelimiter(satellites, "|")));
838 auto flagHealthy = static_cast<uint8_t>(std::stoul(extractRemoveTillDelimiter(satellites, "|")));
839 auto flagAlmanac = static_cast<uint8_t>(std::stoul(extractRemoveTillDelimiter(satellites, "|")));
840 auto flagEphemeris = static_cast<uint8_t>(std::stoul(extractRemoveTillDelimiter(satellites, "|")));
841 auto flagDifferentialCorrection = static_cast<uint8_t>(std::stoul(extractRemoveTillDelimiter(satellites, "|")));
842 auto flagUsedForNavigation = static_cast<uint8_t>(std::stoul(extractRemoveTillDelimiter(satellites, "|")));
843 auto flagAzimuthElevationValid = static_cast<uint8_t>(std::stoul(extractRemoveTillDelimiter(satellites, "|")));
844 auto flagUsedForRTK = static_cast<uint8_t>(std::stoul(extractRemoveTillDelimiter(satellites, "|")));
845 auto flags = static_cast<uint8_t>(flagHealthy << 0U
846 | flagAlmanac << 1U
847 | flagEphemeris << 2U
848 | flagDifferentialCorrection << 3U
849 | flagUsedForNavigation << 4U
850 | flagAzimuthElevationValid << 5U
851 | flagUsedForRTK << 6U);
852 auto cno = static_cast<uint8_t>(std::stoul(extractRemoveTillDelimiter(satellites, "|")));
853 auto qi = static_cast<uint8_t>(std::stoul(extractRemoveTillDelimiter(satellites, "|")));
854 auto el = static_cast<int8_t>(std::stoi(extractRemoveTillDelimiter(satellites, "|")));
855 auto az = static_cast<int16_t>(std::stoi(extractRemoveTillDelimiter(satellites, "]")));
856 obs->gnss2Outputs->satInfo.satellites.emplace_back(sys, svId, flags, cno, qi, el, az);
857 }
858 }
859 if (flag && satellites.empty() && !(obs->gnss2Outputs->gnssField & vn::protocol::uart::GpsGroup::GPSGROUP_SATINFO))
860 {
861 obs->gnss2Outputs->gnssField |= vn::protocol::uart::GpsGroup::GPSGROUP_SATINFO;
862 }
863
864 satellites.clear();
865 flag = obs->gnss2Outputs->gnssField & vn::protocol::uart::GpsGroup::GPSGROUP_RAWMEAS;
866 extractValue(obs->gnss2Outputs->gnssField, vn::protocol::uart::GpsGroup::GPSGROUP_RAWMEAS,
867 obs->gnss2Outputs->raw.tow, obs->gnss2Outputs->raw.week, obs->gnss2Outputs->raw.numSats, satellites);
868 if (obs->gnss2Outputs->gnssField & vn::protocol::uart::GpsGroup::GPSGROUP_RAWMEAS)
869 {
870 for (size_t i = 0; i < obs->gnss2Outputs->raw.numSats; i++)
871 {
872 satellites = satellites.substr(1); // Remove leading '['
873 auto sys = static_cast<uint8_t>(std::stoul(extractRemoveTillDelimiter(satellites, "|")));
874 auto svId = static_cast<uint8_t>(std::stoul(extractRemoveTillDelimiter(satellites, "|")));
875 auto freq = static_cast<uint8_t>(std::stoul(extractRemoveTillDelimiter(satellites, "|")));
876 auto chan = static_cast<uint8_t>(std::stoul(extractRemoveTillDelimiter(satellites, "|")));
877 auto slot = static_cast<int8_t>(std::stoi(extractRemoveTillDelimiter(satellites, "|")));
878 auto cno = static_cast<uint8_t>(std::stoul(extractRemoveTillDelimiter(satellites, "|")));
879 auto flagSearching = static_cast<uint8_t>(std::stoul(extractRemoveTillDelimiter(satellites, "|")));
880 auto flagTracking = static_cast<uint8_t>(std::stoul(extractRemoveTillDelimiter(satellites, "|")));
881 auto flagTimeValid = static_cast<uint8_t>(std::stoul(extractRemoveTillDelimiter(satellites, "|")));
882 auto flagCodeLock = static_cast<uint8_t>(std::stoul(extractRemoveTillDelimiter(satellites, "|")));
883 auto flagPhaseLock = static_cast<uint8_t>(std::stoul(extractRemoveTillDelimiter(satellites, "|")));
884 auto flagPhaseHalfAmbiguity = static_cast<uint8_t>(std::stoul(extractRemoveTillDelimiter(satellites, "|")));
885 auto flagPhaseHalfSub = static_cast<uint8_t>(std::stoul(extractRemoveTillDelimiter(satellites, "|")));
886 auto flagPhaseSlip = static_cast<uint8_t>(std::stoul(extractRemoveTillDelimiter(satellites, "|")));
887 auto flagPseudorangeSmoothed = static_cast<uint8_t>(std::stoul(extractRemoveTillDelimiter(satellites, "|")));
888 auto flags = static_cast<uint16_t>(flagSearching << 0U
889 | flagTracking << 1U
890 | flagTimeValid << 2U
891 | flagCodeLock << 3U
892 | flagPhaseLock << 4U
893 | flagPhaseHalfAmbiguity << 5U
894 | flagPhaseHalfSub << 6U
895 | flagPhaseSlip << 7U
896 | flagPseudorangeSmoothed << 8U);
897 auto pr = std::stod(extractRemoveTillDelimiter(satellites, "|"));
898 auto cp = std::stod(extractRemoveTillDelimiter(satellites, "|"));
899 auto dp = std::stof(extractRemoveTillDelimiter(satellites, "]"));
900 obs->gnss2Outputs->raw.satellites.emplace_back(sys, svId, freq, chan, slot, cno, flags, pr, cp, dp);
901 }
902 }
903 if (flag && satellites.empty() && !(obs->gnss2Outputs->gnssField & vn::protocol::uart::GpsGroup::GPSGROUP_RAWMEAS))
904 {
905 obs->gnss2Outputs->gnssField |= vn::protocol::uart::GpsGroup::GPSGROUP_RAWMEAS;
906 }
907
908 if (obs->gnss2Outputs->gnssField == vn::protocol::uart::GpsGroup::GPSGROUP_NONE) { obs->gnss2Outputs.reset(); }
909 }
910 }
911 catch (const std::exception& e)
912 {
913 LOG_ERROR("{}: Could not read line {} completely: {}", nameId(), _messageCount + 2, e.what());
914 return nullptr;
915 }
916 }
917 else // if (fileType == FileType::BINARY)
918 {
919 auto readFromFilestream = [&, this](char* __s, std::streamsize __n) {
920 read(__s, __n);
921 if (!good())
922 {
923 throw std::runtime_error("End of file reached");
924 }
925 };
926
927 try
928 {
929 int32_t gpsCycle = 0;
930 int32_t gpsWeek = 0;
931 double tow = 0.0;
932 readFromFilestream(reinterpret_cast<char*>(&gpsCycle), sizeof(gpsCycle));
933 readFromFilestream(reinterpret_cast<char*>(&gpsWeek), sizeof(gpsWeek));
934 readFromFilestream(reinterpret_cast<char*>(&tow), sizeof(tow));
935 if (gpsCycle || gpsWeek)
936 {
937 obs->insTime = InsTime(gpsCycle, gpsWeek, tow);
938 }
939
940 // Group 2 (Time)
941 if (_binaryOutputRegister.timeField != vn::protocol::uart::TimeGroup::TIMEGROUP_NONE)
942 {
943 if (!obs->timeOutputs)
944 {
945 obs->timeOutputs = std::make_shared<NAV::vendor::vectornav::TimeOutputs>();
946 obs->timeOutputs->timeField |= _binaryOutputRegister.timeField;
947 }
948
949 if (obs->timeOutputs->timeField & vn::protocol::uart::TimeGroup::TIMEGROUP_TIMESTARTUP)
950 {
951 read(reinterpret_cast<char*>(&obs->timeOutputs->timeStartup), sizeof(obs->timeOutputs->timeStartup));
952 }
953 if (obs->timeOutputs->timeField & vn::protocol::uart::TimeGroup::TIMEGROUP_TIMEGPS)
954 {
955 read(reinterpret_cast<char*>(&obs->timeOutputs->timeGps), sizeof(obs->timeOutputs->timeGps));
956 }
957 if (obs->timeOutputs->timeField & vn::protocol::uart::TimeGroup::TIMEGROUP_GPSTOW)
958 {
959 read(reinterpret_cast<char*>(&obs->timeOutputs->gpsTow), sizeof(obs->timeOutputs->gpsTow));
960 }
961 if (obs->timeOutputs->timeField & vn::protocol::uart::TimeGroup::TIMEGROUP_GPSWEEK)
962 {
963 read(reinterpret_cast<char*>(&obs->timeOutputs->gpsWeek), sizeof(obs->timeOutputs->gpsWeek));
964 }
965 if (obs->timeOutputs->timeField & vn::protocol::uart::TimeGroup::TIMEGROUP_TIMESYNCIN)
966 {
967 read(reinterpret_cast<char*>(&obs->timeOutputs->timeSyncIn), sizeof(obs->timeOutputs->timeSyncIn));
968 }
969 if (obs->timeOutputs->timeField & vn::protocol::uart::TimeGroup::TIMEGROUP_TIMEGPSPPS)
970 {
971 read(reinterpret_cast<char*>(&obs->timeOutputs->timePPS), sizeof(obs->timeOutputs->timePPS));
972 }
973 if (obs->timeOutputs->timeField & vn::protocol::uart::TimeGroup::TIMEGROUP_TIMEUTC)
974 {
975 read(reinterpret_cast<char*>(&obs->timeOutputs->timeUtc.year), sizeof(obs->timeOutputs->timeUtc.year));
976 read(reinterpret_cast<char*>(&obs->timeOutputs->timeUtc.month), sizeof(obs->timeOutputs->timeUtc.month));
977 read(reinterpret_cast<char*>(&obs->timeOutputs->timeUtc.day), sizeof(obs->timeOutputs->timeUtc.day));
978 read(reinterpret_cast<char*>(&obs->timeOutputs->timeUtc.hour), sizeof(obs->timeOutputs->timeUtc.hour));
979 read(reinterpret_cast<char*>(&obs->timeOutputs->timeUtc.min), sizeof(obs->timeOutputs->timeUtc.min));
980 read(reinterpret_cast<char*>(&obs->timeOutputs->timeUtc.sec), sizeof(obs->timeOutputs->timeUtc.sec));
981 read(reinterpret_cast<char*>(&obs->timeOutputs->timeUtc.ms), sizeof(obs->timeOutputs->timeUtc.ms));
982 }
983 if (obs->timeOutputs->timeField & vn::protocol::uart::TimeGroup::TIMEGROUP_SYNCINCNT)
984 {
985 read(reinterpret_cast<char*>(&obs->timeOutputs->syncInCnt), sizeof(obs->timeOutputs->syncInCnt));
986 }
987 if (obs->timeOutputs->timeField & vn::protocol::uart::TimeGroup::TIMEGROUP_SYNCOUTCNT)
988 {
989 read(reinterpret_cast<char*>(&obs->timeOutputs->syncOutCnt), sizeof(obs->timeOutputs->syncOutCnt));
990 }
991 if (obs->timeOutputs->timeField & vn::protocol::uart::TimeGroup::TIMEGROUP_TIMESTATUS)
992 {
993 read(reinterpret_cast<char*>(&obs->timeOutputs->timeStatus.status()), sizeof(obs->timeOutputs->timeStatus.status()));
994 }
995 }
996 // Group 3 (IMU)
997 if (_binaryOutputRegister.imuField != vn::protocol::uart::ImuGroup::IMUGROUP_NONE)
998 {
999 if (!obs->imuOutputs)
1000 {
1001 obs->imuOutputs = std::make_shared<NAV::vendor::vectornav::ImuOutputs>();
1002 obs->imuOutputs->imuField |= _binaryOutputRegister.imuField;
1003 }
1004
1005 if (obs->imuOutputs->imuField & vn::protocol::uart::ImuGroup::IMUGROUP_IMUSTATUS)
1006 {
1007 read(reinterpret_cast<char*>(&obs->imuOutputs->imuStatus), sizeof(obs->imuOutputs->imuStatus));
1008 }
1009 if (obs->imuOutputs->imuField & vn::protocol::uart::ImuGroup::IMUGROUP_UNCOMPMAG)
1010 {
1011 read(reinterpret_cast<char*>(obs->imuOutputs->uncompMag.data()), sizeof(obs->imuOutputs->uncompMag));
1012 }
1013 if (obs->imuOutputs->imuField & vn::protocol::uart::ImuGroup::IMUGROUP_UNCOMPACCEL)
1014 {
1015 read(reinterpret_cast<char*>(obs->imuOutputs->uncompAccel.data()), sizeof(obs->imuOutputs->uncompAccel));
1016 }
1017 if (obs->imuOutputs->imuField & vn::protocol::uart::ImuGroup::IMUGROUP_UNCOMPGYRO)
1018 {
1019 read(reinterpret_cast<char*>(obs->imuOutputs->uncompGyro.data()), sizeof(obs->imuOutputs->uncompGyro));
1020 }
1021 if (obs->imuOutputs->imuField & vn::protocol::uart::ImuGroup::IMUGROUP_TEMP)
1022 {
1023 read(reinterpret_cast<char*>(&obs->imuOutputs->temp), sizeof(obs->imuOutputs->temp));
1024 }
1025 if (obs->imuOutputs->imuField & vn::protocol::uart::ImuGroup::IMUGROUP_PRES)
1026 {
1027 read(reinterpret_cast<char*>(&obs->imuOutputs->pres), sizeof(obs->imuOutputs->pres));
1028 }
1029 if (obs->imuOutputs->imuField & vn::protocol::uart::ImuGroup::IMUGROUP_DELTATHETA)
1030 {
1031 read(reinterpret_cast<char*>(&obs->imuOutputs->deltaTime), sizeof(obs->imuOutputs->deltaTime));
1032 read(reinterpret_cast<char*>(obs->imuOutputs->deltaTheta.data()), sizeof(obs->imuOutputs->deltaTheta));
1033 }
1034 if (obs->imuOutputs->imuField & vn::protocol::uart::ImuGroup::IMUGROUP_DELTAVEL)
1035 {
1036 read(reinterpret_cast<char*>(obs->imuOutputs->deltaV.data()), sizeof(obs->imuOutputs->deltaV));
1037 }
1038 if (obs->imuOutputs->imuField & vn::protocol::uart::ImuGroup::IMUGROUP_MAG)
1039 {
1040 read(reinterpret_cast<char*>(obs->imuOutputs->mag.data()), sizeof(obs->imuOutputs->mag));
1041 }
1042 if (obs->imuOutputs->imuField & vn::protocol::uart::ImuGroup::IMUGROUP_ACCEL)
1043 {
1044 read(reinterpret_cast<char*>(obs->imuOutputs->accel.data()), sizeof(obs->imuOutputs->accel));
1045 }
1046 if (obs->imuOutputs->imuField & vn::protocol::uart::ImuGroup::IMUGROUP_ANGULARRATE)
1047 {
1048 read(reinterpret_cast<char*>(obs->imuOutputs->angularRate.data()), sizeof(obs->imuOutputs->angularRate));
1049 }
1050 }
1051 // Group 4 (GNSS1)
1052 if (_binaryOutputRegister.gpsField != vn::protocol::uart::GpsGroup::GPSGROUP_NONE)
1053 {
1054 if (!obs->gnss1Outputs)
1055 {
1056 obs->gnss1Outputs = std::make_shared<NAV::vendor::vectornav::GnssOutputs>();
1057 obs->gnss1Outputs->gnssField |= _binaryOutputRegister.gpsField;
1058 }
1059
1060 if (obs->gnss1Outputs->gnssField & vn::protocol::uart::GpsGroup::GPSGROUP_UTC)
1061 {
1062 read(reinterpret_cast<char*>(&obs->gnss1Outputs->timeUtc.year), sizeof(obs->gnss1Outputs->timeUtc.year));
1063 read(reinterpret_cast<char*>(&obs->gnss1Outputs->timeUtc.month), sizeof(obs->gnss1Outputs->timeUtc.month));
1064 read(reinterpret_cast<char*>(&obs->gnss1Outputs->timeUtc.day), sizeof(obs->gnss1Outputs->timeUtc.day));
1065 read(reinterpret_cast<char*>(&obs->gnss1Outputs->timeUtc.hour), sizeof(obs->gnss1Outputs->timeUtc.hour));
1066 read(reinterpret_cast<char*>(&obs->gnss1Outputs->timeUtc.min), sizeof(obs->gnss1Outputs->timeUtc.min));
1067 read(reinterpret_cast<char*>(&obs->gnss1Outputs->timeUtc.sec), sizeof(obs->gnss1Outputs->timeUtc.sec));
1068 read(reinterpret_cast<char*>(&obs->gnss1Outputs->timeUtc.ms), sizeof(obs->gnss1Outputs->timeUtc.ms));
1069 }
1070 if (obs->gnss1Outputs->gnssField & vn::protocol::uart::GpsGroup::GPSGROUP_TOW)
1071 {
1072 read(reinterpret_cast<char*>(&obs->gnss1Outputs->tow), sizeof(obs->gnss1Outputs->tow));
1073 }
1074 if (obs->gnss1Outputs->gnssField & vn::protocol::uart::GpsGroup::GPSGROUP_WEEK)
1075 {
1076 read(reinterpret_cast<char*>(&obs->gnss1Outputs->week), sizeof(obs->gnss1Outputs->week));
1077 }
1078 if (obs->gnss1Outputs->gnssField & vn::protocol::uart::GpsGroup::GPSGROUP_NUMSATS)
1079 {
1080 read(reinterpret_cast<char*>(&obs->gnss1Outputs->numSats), sizeof(obs->gnss1Outputs->numSats));
1081 }
1082 if (obs->gnss1Outputs->gnssField & vn::protocol::uart::GpsGroup::GPSGROUP_FIX)
1083 {
1084 read(reinterpret_cast<char*>(&obs->gnss1Outputs->fix), sizeof(obs->gnss1Outputs->fix));
1085 }
1086 if (obs->gnss1Outputs->gnssField & vn::protocol::uart::GpsGroup::GPSGROUP_POSLLA)
1087 {
1088 read(reinterpret_cast<char*>(obs->gnss1Outputs->posLla.data()), sizeof(obs->gnss1Outputs->posLla));
1089 }
1090 if (obs->gnss1Outputs->gnssField & vn::protocol::uart::GpsGroup::GPSGROUP_POSECEF)
1091 {
1092 read(reinterpret_cast<char*>(obs->gnss1Outputs->posEcef.data()), sizeof(obs->gnss1Outputs->posEcef));
1093 }
1094 if (obs->gnss1Outputs->gnssField & vn::protocol::uart::GpsGroup::GPSGROUP_VELNED)
1095 {
1096 read(reinterpret_cast<char*>(obs->gnss1Outputs->velNed.data()), sizeof(obs->gnss1Outputs->velNed));
1097 }
1098 if (obs->gnss1Outputs->gnssField & vn::protocol::uart::GpsGroup::GPSGROUP_VELECEF)
1099 {
1100 read(reinterpret_cast<char*>(obs->gnss1Outputs->velEcef.data()), sizeof(obs->gnss1Outputs->velEcef));
1101 }
1102 if (obs->gnss1Outputs->gnssField & vn::protocol::uart::GpsGroup::GPSGROUP_POSU)
1103 {
1104 read(reinterpret_cast<char*>(obs->gnss1Outputs->posU.data()), sizeof(obs->gnss1Outputs->posU));
1105 }
1106 if (obs->gnss1Outputs->gnssField & vn::protocol::uart::GpsGroup::GPSGROUP_VELU)
1107 {
1108 read(reinterpret_cast<char*>(&obs->gnss1Outputs->velU), sizeof(obs->gnss1Outputs->velU));
1109 }
1110 if (obs->gnss1Outputs->gnssField & vn::protocol::uart::GpsGroup::GPSGROUP_TIMEU)
1111 {
1112 read(reinterpret_cast<char*>(&obs->gnss1Outputs->timeU), sizeof(obs->gnss1Outputs->timeU));
1113 }
1114 if (obs->gnss1Outputs->gnssField & vn::protocol::uart::GpsGroup::GPSGROUP_TIMEINFO)
1115 {
1116 read(reinterpret_cast<char*>(&obs->gnss1Outputs->timeInfo.status.status()), sizeof(obs->gnss1Outputs->timeInfo.status.status()));
1117 read(reinterpret_cast<char*>(&obs->gnss1Outputs->timeInfo.leapSeconds), sizeof(obs->gnss1Outputs->timeInfo.leapSeconds));
1118 }
1119 if (obs->gnss1Outputs->gnssField & vn::protocol::uart::GpsGroup::GPSGROUP_DOP)
1120 {
1121 read(reinterpret_cast<char*>(&obs->gnss1Outputs->dop.gDop), sizeof(obs->gnss1Outputs->dop.gDop));
1122 read(reinterpret_cast<char*>(&obs->gnss1Outputs->dop.pDop), sizeof(obs->gnss1Outputs->dop.pDop));
1123 read(reinterpret_cast<char*>(&obs->gnss1Outputs->dop.tDop), sizeof(obs->gnss1Outputs->dop.tDop));
1124 read(reinterpret_cast<char*>(&obs->gnss1Outputs->dop.vDop), sizeof(obs->gnss1Outputs->dop.vDop));
1125 read(reinterpret_cast<char*>(&obs->gnss1Outputs->dop.hDop), sizeof(obs->gnss1Outputs->dop.hDop));
1126 read(reinterpret_cast<char*>(&obs->gnss1Outputs->dop.nDop), sizeof(obs->gnss1Outputs->dop.nDop));
1127 read(reinterpret_cast<char*>(&obs->gnss1Outputs->dop.eDop), sizeof(obs->gnss1Outputs->dop.eDop));
1128 }
1129 if (obs->gnss1Outputs->gnssField & vn::protocol::uart::GpsGroup::GPSGROUP_SATINFO)
1130 {
1131 read(reinterpret_cast<char*>(&obs->gnss1Outputs->satInfo.numSats), sizeof(obs->gnss1Outputs->satInfo.numSats));
1132 obs->gnss1Outputs->satInfo.satellites.resize(obs->gnss1Outputs->satInfo.numSats);
1133
1134 for (auto& satellite : obs->gnss1Outputs->satInfo.satellites)
1135 {
1136 read(reinterpret_cast<char*>(&satellite.sys), sizeof(satellite.sys));
1137 read(reinterpret_cast<char*>(&satellite.svId), sizeof(satellite.svId));
1138 read(reinterpret_cast<char*>(&satellite.flags), sizeof(satellite.flags));
1139 read(reinterpret_cast<char*>(&satellite.cno), sizeof(satellite.cno));
1140 read(reinterpret_cast<char*>(&satellite.qi), sizeof(satellite.qi));
1141 read(reinterpret_cast<char*>(&satellite.el), sizeof(satellite.el));
1142 read(reinterpret_cast<char*>(&satellite.az), sizeof(satellite.az));
1143 }
1144 }
1145 if (obs->gnss1Outputs->gnssField & vn::protocol::uart::GpsGroup::GPSGROUP_RAWMEAS)
1146 {
1147 read(reinterpret_cast<char*>(&obs->gnss1Outputs->raw.tow), sizeof(obs->gnss1Outputs->raw.tow));
1148 read(reinterpret_cast<char*>(&obs->gnss1Outputs->raw.week), sizeof(obs->gnss1Outputs->raw.week));
1149 read(reinterpret_cast<char*>(&obs->gnss1Outputs->raw.numSats), sizeof(obs->gnss1Outputs->raw.numSats));
1150 obs->gnss1Outputs->raw.satellites.resize(obs->gnss1Outputs->raw.numSats);
1151
1152 for (auto& satellite : obs->gnss1Outputs->raw.satellites)
1153 {
1154 read(reinterpret_cast<char*>(&satellite.sys), sizeof(satellite.sys));
1155 read(reinterpret_cast<char*>(&satellite.svId), sizeof(satellite.svId));
1156 read(reinterpret_cast<char*>(&satellite.freq), sizeof(satellite.freq));
1157 read(reinterpret_cast<char*>(&satellite.chan), sizeof(satellite.chan));
1158 read(reinterpret_cast<char*>(&satellite.slot), sizeof(satellite.slot));
1159 read(reinterpret_cast<char*>(&satellite.cno), sizeof(satellite.cno));
1160 read(reinterpret_cast<char*>(&satellite.flags), sizeof(satellite.flags));
1161 read(reinterpret_cast<char*>(&satellite.pr), sizeof(satellite.pr));
1162 read(reinterpret_cast<char*>(&satellite.cp), sizeof(satellite.cp));
1163 read(reinterpret_cast<char*>(&satellite.dp), sizeof(satellite.dp));
1164 }
1165 }
1166 }
1167 // Group 5 (Attitude)
1168 if (_binaryOutputRegister.attitudeField != vn::protocol::uart::AttitudeGroup::ATTITUDEGROUP_NONE)
1169 {
1170 if (!obs->attitudeOutputs)
1171 {
1172 obs->attitudeOutputs = std::make_shared<NAV::vendor::vectornav::AttitudeOutputs>();
1173 obs->attitudeOutputs->attitudeField |= _binaryOutputRegister.attitudeField;
1174 }
1175
1176 if (obs->attitudeOutputs->attitudeField & vn::protocol::uart::AttitudeGroup::ATTITUDEGROUP_VPESTATUS)
1177 {
1178 read(reinterpret_cast<char*>(&obs->attitudeOutputs->vpeStatus.status()), sizeof(obs->attitudeOutputs->vpeStatus.status()));
1179 }
1180 if (obs->attitudeOutputs->attitudeField & vn::protocol::uart::AttitudeGroup::ATTITUDEGROUP_YAWPITCHROLL)
1181 {
1182 read(reinterpret_cast<char*>(obs->attitudeOutputs->ypr.data()), sizeof(obs->attitudeOutputs->ypr));
1183 }
1184 if (obs->attitudeOutputs->attitudeField & vn::protocol::uart::AttitudeGroup::ATTITUDEGROUP_QUATERNION)
1185 {
1186 read(reinterpret_cast<char*>(obs->attitudeOutputs->qtn.coeffs().data()), sizeof(obs->attitudeOutputs->qtn));
1187 }
1188 if (obs->attitudeOutputs->attitudeField & vn::protocol::uart::AttitudeGroup::ATTITUDEGROUP_DCM)
1189 {
1190 read(reinterpret_cast<char*>(obs->attitudeOutputs->dcm.data()), sizeof(obs->attitudeOutputs->dcm));
1191 }
1192 if (obs->attitudeOutputs->attitudeField & vn::protocol::uart::AttitudeGroup::ATTITUDEGROUP_MAGNED)
1193 {
1194 read(reinterpret_cast<char*>(obs->attitudeOutputs->magNed.data()), sizeof(obs->attitudeOutputs->magNed));
1195 }
1196 if (obs->attitudeOutputs->attitudeField & vn::protocol::uart::AttitudeGroup::ATTITUDEGROUP_ACCELNED)
1197 {
1198 read(reinterpret_cast<char*>(obs->attitudeOutputs->accelNed.data()), sizeof(obs->attitudeOutputs->accelNed));
1199 }
1200 if (obs->attitudeOutputs->attitudeField & vn::protocol::uart::AttitudeGroup::ATTITUDEGROUP_LINEARACCELBODY)
1201 {
1202 read(reinterpret_cast<char*>(obs->attitudeOutputs->linearAccelBody.data()), sizeof(obs->attitudeOutputs->linearAccelBody));
1203 }
1204 if (obs->attitudeOutputs->attitudeField & vn::protocol::uart::AttitudeGroup::ATTITUDEGROUP_LINEARACCELNED)
1205 {
1206 read(reinterpret_cast<char*>(obs->attitudeOutputs->linearAccelNed.data()), sizeof(obs->attitudeOutputs->linearAccelNed));
1207 }
1208 if (obs->attitudeOutputs->attitudeField & vn::protocol::uart::AttitudeGroup::ATTITUDEGROUP_YPRU)
1209 {
1210 read(reinterpret_cast<char*>(obs->attitudeOutputs->yprU.data()), sizeof(obs->attitudeOutputs->yprU));
1211 }
1212 }
1213 // Group 6 (INS)
1214 if (_binaryOutputRegister.insField != vn::protocol::uart::InsGroup::INSGROUP_NONE)
1215 {
1216 if (!obs->insOutputs)
1217 {
1218 obs->insOutputs = std::make_shared<NAV::vendor::vectornav::InsOutputs>();
1219 obs->insOutputs->insField |= _binaryOutputRegister.insField;
1220 }
1221
1222 if (obs->insOutputs->insField & vn::protocol::uart::InsGroup::INSGROUP_INSSTATUS)
1223 {
1224 read(reinterpret_cast<char*>(&obs->insOutputs->insStatus.status()), sizeof(obs->insOutputs->insStatus.status()));
1225 }
1226 if (obs->insOutputs->insField & vn::protocol::uart::InsGroup::INSGROUP_POSLLA)
1227 {
1228 read(reinterpret_cast<char*>(obs->insOutputs->posLla.data()), sizeof(obs->insOutputs->posLla));
1229 }
1230 if (obs->insOutputs->insField & vn::protocol::uart::InsGroup::INSGROUP_POSECEF)
1231 {
1232 read(reinterpret_cast<char*>(obs->insOutputs->posEcef.data()), sizeof(obs->insOutputs->posEcef));
1233 }
1234 if (obs->insOutputs->insField & vn::protocol::uart::InsGroup::INSGROUP_VELBODY)
1235 {
1236 read(reinterpret_cast<char*>(obs->insOutputs->velBody.data()), sizeof(obs->insOutputs->velBody));
1237 }
1238 if (obs->insOutputs->insField & vn::protocol::uart::InsGroup::INSGROUP_VELNED)
1239 {
1240 read(reinterpret_cast<char*>(obs->insOutputs->velNed.data()), sizeof(obs->insOutputs->velNed));
1241 }
1242 if (obs->insOutputs->insField & vn::protocol::uart::InsGroup::INSGROUP_VELECEF)
1243 {
1244 read(reinterpret_cast<char*>(obs->insOutputs->velEcef.data()), sizeof(obs->insOutputs->velEcef));
1245 }
1246 if (obs->insOutputs->insField & vn::protocol::uart::InsGroup::INSGROUP_MAGECEF)
1247 {
1248 read(reinterpret_cast<char*>(obs->insOutputs->magEcef.data()), sizeof(obs->insOutputs->magEcef));
1249 }
1250 if (obs->insOutputs->insField & vn::protocol::uart::InsGroup::INSGROUP_ACCELECEF)
1251 {
1252 read(reinterpret_cast<char*>(obs->insOutputs->accelEcef.data()), sizeof(obs->insOutputs->accelEcef));
1253 }
1254 if (obs->insOutputs->insField & vn::protocol::uart::InsGroup::INSGROUP_LINEARACCELECEF)
1255 {
1256 read(reinterpret_cast<char*>(obs->insOutputs->linearAccelEcef.data()), sizeof(obs->insOutputs->linearAccelEcef));
1257 }
1258 if (obs->insOutputs->insField & vn::protocol::uart::InsGroup::INSGROUP_POSU)
1259 {
1260 read(reinterpret_cast<char*>(&obs->insOutputs->posU), sizeof(obs->insOutputs->posU));
1261 }
1262 if (obs->insOutputs->insField & vn::protocol::uart::InsGroup::INSGROUP_VELU)
1263 {
1264 read(reinterpret_cast<char*>(&obs->insOutputs->velU), sizeof(obs->insOutputs->velU));
1265 }
1266 }
1267 // Group 7 (GNSS2)
1268 if (_binaryOutputRegister.gps2Field != vn::protocol::uart::GpsGroup::GPSGROUP_NONE)
1269 {
1270 if (!obs->gnss2Outputs)
1271 {
1272 obs->gnss2Outputs = std::make_shared<NAV::vendor::vectornav::GnssOutputs>();
1273 obs->gnss2Outputs->gnssField |= _binaryOutputRegister.gps2Field;
1274 }
1275
1276 if (obs->gnss2Outputs->gnssField & vn::protocol::uart::GpsGroup::GPSGROUP_UTC)
1277 {
1278 read(reinterpret_cast<char*>(&obs->gnss2Outputs->timeUtc.year), sizeof(obs->gnss2Outputs->timeUtc.year));
1279 read(reinterpret_cast<char*>(&obs->gnss2Outputs->timeUtc.month), sizeof(obs->gnss2Outputs->timeUtc.month));
1280 read(reinterpret_cast<char*>(&obs->gnss2Outputs->timeUtc.day), sizeof(obs->gnss2Outputs->timeUtc.day));
1281 read(reinterpret_cast<char*>(&obs->gnss2Outputs->timeUtc.hour), sizeof(obs->gnss2Outputs->timeUtc.hour));
1282 read(reinterpret_cast<char*>(&obs->gnss2Outputs->timeUtc.min), sizeof(obs->gnss2Outputs->timeUtc.min));
1283 read(reinterpret_cast<char*>(&obs->gnss2Outputs->timeUtc.sec), sizeof(obs->gnss2Outputs->timeUtc.sec));
1284 read(reinterpret_cast<char*>(&obs->gnss2Outputs->timeUtc.ms), sizeof(obs->gnss2Outputs->timeUtc.ms));
1285 }
1286 if (obs->gnss2Outputs->gnssField & vn::protocol::uart::GpsGroup::GPSGROUP_TOW)
1287 {
1288 read(reinterpret_cast<char*>(&obs->gnss2Outputs->tow), sizeof(obs->gnss2Outputs->tow));
1289 }
1290 if (obs->gnss2Outputs->gnssField & vn::protocol::uart::GpsGroup::GPSGROUP_WEEK)
1291 {
1292 read(reinterpret_cast<char*>(&obs->gnss2Outputs->week), sizeof(obs->gnss2Outputs->week));
1293 }
1294 if (obs->gnss2Outputs->gnssField & vn::protocol::uart::GpsGroup::GPSGROUP_NUMSATS)
1295 {
1296 read(reinterpret_cast<char*>(&obs->gnss2Outputs->numSats), sizeof(obs->gnss2Outputs->numSats));
1297 }
1298 if (obs->gnss2Outputs->gnssField & vn::protocol::uart::GpsGroup::GPSGROUP_FIX)
1299 {
1300 read(reinterpret_cast<char*>(&obs->gnss2Outputs->fix), sizeof(obs->gnss2Outputs->fix));
1301 }
1302 if (obs->gnss2Outputs->gnssField & vn::protocol::uart::GpsGroup::GPSGROUP_POSLLA)
1303 {
1304 read(reinterpret_cast<char*>(obs->gnss2Outputs->posLla.data()), sizeof(obs->gnss2Outputs->posLla));
1305 }
1306 if (obs->gnss2Outputs->gnssField & vn::protocol::uart::GpsGroup::GPSGROUP_POSECEF)
1307 {
1308 read(reinterpret_cast<char*>(obs->gnss2Outputs->posEcef.data()), sizeof(obs->gnss2Outputs->posEcef));
1309 }
1310 if (obs->gnss2Outputs->gnssField & vn::protocol::uart::GpsGroup::GPSGROUP_VELNED)
1311 {
1312 read(reinterpret_cast<char*>(obs->gnss2Outputs->velNed.data()), sizeof(obs->gnss2Outputs->velNed));
1313 }
1314 if (obs->gnss2Outputs->gnssField & vn::protocol::uart::GpsGroup::GPSGROUP_VELECEF)
1315 {
1316 read(reinterpret_cast<char*>(obs->gnss2Outputs->velEcef.data()), sizeof(obs->gnss2Outputs->velEcef));
1317 }
1318 if (obs->gnss2Outputs->gnssField & vn::protocol::uart::GpsGroup::GPSGROUP_POSU)
1319 {
1320 read(reinterpret_cast<char*>(obs->gnss2Outputs->posU.data()), sizeof(obs->gnss2Outputs->posU));
1321 }
1322 if (obs->gnss2Outputs->gnssField & vn::protocol::uart::GpsGroup::GPSGROUP_VELU)
1323 {
1324 read(reinterpret_cast<char*>(&obs->gnss2Outputs->velU), sizeof(obs->gnss2Outputs->velU));
1325 }
1326 if (obs->gnss2Outputs->gnssField & vn::protocol::uart::GpsGroup::GPSGROUP_TIMEU)
1327 {
1328 read(reinterpret_cast<char*>(&obs->gnss2Outputs->timeU), sizeof(obs->gnss2Outputs->timeU));
1329 }
1330 if (obs->gnss2Outputs->gnssField & vn::protocol::uart::GpsGroup::GPSGROUP_TIMEINFO)
1331 {
1332 read(reinterpret_cast<char*>(&obs->gnss2Outputs->timeInfo.status.status()), sizeof(obs->gnss2Outputs->timeInfo.status.status()));
1333 read(reinterpret_cast<char*>(&obs->gnss2Outputs->timeInfo.leapSeconds), sizeof(obs->gnss2Outputs->timeInfo.leapSeconds));
1334 }
1335 if (obs->gnss2Outputs->gnssField & vn::protocol::uart::GpsGroup::GPSGROUP_DOP)
1336 {
1337 read(reinterpret_cast<char*>(&obs->gnss2Outputs->dop.gDop), sizeof(obs->gnss2Outputs->dop.gDop));
1338 read(reinterpret_cast<char*>(&obs->gnss2Outputs->dop.pDop), sizeof(obs->gnss2Outputs->dop.pDop));
1339 read(reinterpret_cast<char*>(&obs->gnss2Outputs->dop.tDop), sizeof(obs->gnss2Outputs->dop.tDop));
1340 read(reinterpret_cast<char*>(&obs->gnss2Outputs->dop.vDop), sizeof(obs->gnss2Outputs->dop.vDop));
1341 read(reinterpret_cast<char*>(&obs->gnss2Outputs->dop.hDop), sizeof(obs->gnss2Outputs->dop.hDop));
1342 read(reinterpret_cast<char*>(&obs->gnss2Outputs->dop.nDop), sizeof(obs->gnss2Outputs->dop.nDop));
1343 read(reinterpret_cast<char*>(&obs->gnss2Outputs->dop.eDop), sizeof(obs->gnss2Outputs->dop.eDop));
1344 }
1345 if (obs->gnss2Outputs->gnssField & vn::protocol::uart::GpsGroup::GPSGROUP_SATINFO)
1346 {
1347 read(reinterpret_cast<char*>(&obs->gnss2Outputs->satInfo.numSats), sizeof(obs->gnss2Outputs->satInfo.numSats));
1348 obs->gnss2Outputs->satInfo.satellites.resize(obs->gnss2Outputs->satInfo.numSats);
1349
1350 for (auto& satellite : obs->gnss2Outputs->satInfo.satellites)
1351 {
1352 read(reinterpret_cast<char*>(&satellite.sys), sizeof(satellite.sys));
1353 read(reinterpret_cast<char*>(&satellite.svId), sizeof(satellite.svId));
1354 read(reinterpret_cast<char*>(&satellite.flags), sizeof(satellite.flags));
1355 read(reinterpret_cast<char*>(&satellite.cno), sizeof(satellite.cno));
1356 read(reinterpret_cast<char*>(&satellite.qi), sizeof(satellite.qi));
1357 read(reinterpret_cast<char*>(&satellite.el), sizeof(satellite.el));
1358 read(reinterpret_cast<char*>(&satellite.az), sizeof(satellite.az));
1359 }
1360 }
1361 if (obs->gnss2Outputs->gnssField & vn::protocol::uart::GpsGroup::GPSGROUP_RAWMEAS)
1362 {
1363 read(reinterpret_cast<char*>(&obs->gnss2Outputs->raw.tow), sizeof(obs->gnss2Outputs->raw.tow));
1364 read(reinterpret_cast<char*>(&obs->gnss2Outputs->raw.week), sizeof(obs->gnss2Outputs->raw.week));
1365 read(reinterpret_cast<char*>(&obs->gnss2Outputs->raw.numSats), sizeof(obs->gnss2Outputs->raw.numSats));
1366 obs->gnss2Outputs->raw.satellites.resize(obs->gnss2Outputs->raw.numSats);
1367
1368 for (auto& satellite : obs->gnss2Outputs->raw.satellites)
1369 {
1370 read(reinterpret_cast<char*>(&satellite.sys), sizeof(satellite.sys));
1371 read(reinterpret_cast<char*>(&satellite.svId), sizeof(satellite.svId));
1372 read(reinterpret_cast<char*>(&satellite.freq), sizeof(satellite.freq));
1373 read(reinterpret_cast<char*>(&satellite.chan), sizeof(satellite.chan));
1374 read(reinterpret_cast<char*>(&satellite.slot), sizeof(satellite.slot));
1375 read(reinterpret_cast<char*>(&satellite.cno), sizeof(satellite.cno));
1376 read(reinterpret_cast<char*>(&satellite.flags), sizeof(satellite.flags));
1377 read(reinterpret_cast<char*>(&satellite.pr), sizeof(satellite.pr));
1378 read(reinterpret_cast<char*>(&satellite.cp), sizeof(satellite.cp));
1379 read(reinterpret_cast<char*>(&satellite.dp), sizeof(satellite.dp));
1380 }
1381 }
1382 }
1383 }
1384 catch (const std::exception& e)
1385 {
1386 LOG_DEBUG("{}: {} after {} messages", nameId(), e.what(), _messageCount);
1387 return nullptr;
1388 }
1389 }
1390
1391 if (!obs->timeOutputs && !obs->imuOutputs && !obs->gnss1Outputs && !obs->attitudeOutputs && !obs->insOutputs && !obs->gnss2Outputs)
1392 {
1393 return nullptr;
1394 }
1395
1396 _messageCount++;
1397
1399 return obs;
1400}
Assertion helpers.
Transformation collection.
Save/Load the Nodes.
nlohmann::json json
json namespace
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_DATA
All output which occurs repeatedly every time observations are received.
Definition Logger.hpp:29
#define LOG_ERROR
Error occurred, which stops part of the program to work, but not everything.
Definition Logger.hpp:73
#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 functions for working with std::strings.
Binary Outputs from VectorNav Sensors.
File Reader for Vector Nav log files.
Vector Nav Sensors.
bool initialize()
Initialize the file reader.
void restore(const json &j)
Restores the node from a json object.
bool good() const
Fast error checking.
std::string _path
Path to the file.
FileType
File Type Enumeration.
@ ASCII
Ascii text data.
@ BINARY
Binary data.
@ NONE
Not specified.
FileType _fileType
File Type.
auto & read(char *__s, std::streamsize __n)
Extraction without delimiters.
std::filesystem::path getFilepath()
Returns the path of the file.
@ PATH_CHANGED
The path changed and exists.
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.
void deinitialize()
Deinitialize the file reader.
json save() const override
Saves the node into a json object.
Definition Imu.cpp:93
void restore(const json &j) override
Restores the node from a json object.
Definition Imu.cpp:104
void guiConfig() override
ImGui config window which is shown on double click.
Definition Imu.cpp:55
Imu(const Imu &)=delete
Copy constructor.
ImuPos _imuPos
Position and rotation information for conversion from platform to body frame.
Definition Imu.hpp:57
The class is responsible for all time-related tasks.
Definition InsTime.hpp:710
bool doDeinitialize(bool wait=false)
Asks the node worker to deinitialize the node.
Definition Node.cpp:395
ImVec2 _guiConfigDefaultWindowSize
Definition Node.hpp:410
std::string nameId() const
Node name and id.
Definition Node.cpp:253
std::string name
Name of the Node.
Definition Node.hpp:395
bool doReinitialize(bool wait=false)
Asks the node worker to reinitialize the node.
Definition Node.cpp:350
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
bool _hasConfig
Flag if the config window should be shown.
Definition Node.hpp:413
static std::string type()
Returns the type of the data class.
static constexpr size_t OUTPUT_PORT_INDEX_VECTORNAV_BINARY_OUTPUT
Flow (VectorNavBinaryOutput)
bool resetNode() override
Resets the node. Moves the read cursor to the start.
VectorNavFile()
Default constructor.
bool _hasTimeColumn
Flag whether the file has the 'Time [s]' column. Backwards compatibility to older files.
vn::sensors::BinaryOutputRegister _binaryOutputRegister
Binary Output Register 1 - 3.
bool initialize() override
Initialize the node.
json save() const override
Saves the node into a json object.
~VectorNavFile() override
Destructor.
void readHeader() override
Read the Header of the file.
std::shared_ptr< const NodeData > pollData()
Polls data from the file.
void deinitialize() override
Deinitialize the node.
static std::string typeStatic()
String representation of the Class Type.
void guiConfig() override
ImGui config window which is shown on double click.
FileType determineFileType() override
Virtual Function to determine the File Type.
static std::string category()
String representation of the Class Category.
uint32_t _messageCount
Amount of messages read.
std::string type() const override
String representation of the Class Type.
void restore(const json &j) override
Restores the node from a json object.
static const std::array< BinaryGroupData, 10 > _binaryGroupTime
Binary group 1 contains a wide assortment of commonly used data required for most applications.
static const std::array< BinaryGroupData, 11 > _binaryGroupIMU
Binary group 3 provides all outputs which are dependent upon the measurements collected from the onbo...
static const std::array< BinaryGroupData, 11 > _binaryGroupINS
Binary group 6 provides all estimated outputs which are dependent upon the onboard INS state solution...
static const std::array< BinaryGroupData, 9 > _binaryGroupAttitude
Binary group 5 provides all estimated outputs which are dependent upon the estimated attitude solutio...
static const std::array< BinaryGroupData, 16 > _binaryGroupGNSS
Binary group 4 provides all outputs which are dependent upon the measurements collected from the prim...
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.
void ApplyChanges()
Signals that there have been changes to the flow.
@ Flow
NodeData Trigger.
Definition Pin.hpp:52