0.5.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 <cstdint>
12#include <exception>
13#include <limits>
17#include <vn/types.h>
18
19#include "util/Logger.hpp"
20#include "util/Assert.h"
21#include "util/StringUtil.hpp"
23
25
28
39
44
46{
47 return "VectorNavFile";
48}
49
50std::string NAV::VectorNavFile::type() const
51{
52 return typeStatic();
53}
54
56{
57 return "Data Provider";
58}
59
61{
62 if (auto res = FileReader::guiConfig("Supported types (*.csv *.vnb){.csv,.vnb},.*", { ".csv", ".vnb" }, size_t(id), nameId()))
63 {
64 LOG_DEBUG("{}: Path changed to {}", nameId(), _path);
66 if (res == FileReader::PATH_CHANGED)
67 {
69 }
70 else
71 {
73 }
74 }
75
77
78 // Header info
79 if (ImGui::BeginTable(fmt::format("##VectorNavHeaders ({})", id.AsPointer()).c_str(), 6,
80 ImGuiTableFlags_Borders | ImGuiTableFlags_RowBg | ImGuiTableFlags_NoHostExtendX | ImGuiTableFlags_SizingFixedFit))
81 {
82 ImGui::TableSetupColumn("Time", ImGuiTableColumnFlags_WidthFixed);
83 ImGui::TableSetupColumn("IMU", ImGuiTableColumnFlags_WidthFixed);
84 ImGui::TableSetupColumn("GNSS1", ImGuiTableColumnFlags_WidthFixed);
85 ImGui::TableSetupColumn("Attitude", ImGuiTableColumnFlags_WidthFixed);
86 ImGui::TableSetupColumn("INS", ImGuiTableColumnFlags_WidthFixed);
87 ImGui::TableSetupColumn("GNSS2", ImGuiTableColumnFlags_WidthFixed);
88 ImGui::TableHeadersRow();
89
90 auto TextColored = [](int index, const char* label, bool enabled) {
91 ImGui::TableSetColumnIndex(index);
92 if (enabled)
93 {
94 ImGui::TextUnformatted(label);
95 }
96 else
97 {
98 ImGui::TextDisabled("%s", label);
99 }
100 };
101
102 for (size_t i = 0; i < 16; i++)
103 {
104 if (i < std::max({ /* VectorNavSensor::_binaryGroupCommon.size(), */ VectorNavSensor::_binaryGroupTime.size(), VectorNavSensor::_binaryGroupIMU.size(),
106 {
107 ImGui::TableNextRow();
108 }
110 {
111 const auto& binaryGroupItem = VectorNavSensor::_binaryGroupTime.at(i);
112 TextColored(0, binaryGroupItem.name, _binaryOutputRegister.timeField & binaryGroupItem.flagsValue);
113 if (ImGui::IsItemHovered() && binaryGroupItem.tooltip != nullptr)
114 {
115 ImGui::BeginTooltip();
116 binaryGroupItem.tooltip();
117 ImGui::EndTooltip();
118 }
119 }
121 {
122 const auto& binaryGroupItem = VectorNavSensor::_binaryGroupIMU.at(i);
123 TextColored(1, binaryGroupItem.name, _binaryOutputRegister.imuField & binaryGroupItem.flagsValue);
124 if (ImGui::IsItemHovered() && binaryGroupItem.tooltip != nullptr)
125 {
126 ImGui::BeginTooltip();
127 binaryGroupItem.tooltip();
128 ImGui::EndTooltip();
129 }
130 }
132 {
133 const auto& binaryGroupItem = VectorNavSensor::_binaryGroupGNSS.at(i);
134 TextColored(2, binaryGroupItem.name, _binaryOutputRegister.gpsField & binaryGroupItem.flagsValue);
135 if (ImGui::IsItemHovered() && binaryGroupItem.tooltip != nullptr)
136 {
137 ImGui::BeginTooltip();
138 binaryGroupItem.tooltip();
139 ImGui::EndTooltip();
140 }
141 }
143 {
144 const auto& binaryGroupItem = VectorNavSensor::_binaryGroupAttitude.at(i);
145 TextColored(3, binaryGroupItem.name, _binaryOutputRegister.attitudeField & binaryGroupItem.flagsValue);
146 if (ImGui::IsItemHovered() && binaryGroupItem.tooltip != nullptr)
147 {
148 ImGui::BeginTooltip();
149 binaryGroupItem.tooltip();
150 ImGui::EndTooltip();
151 }
152 }
154 {
155 const auto& binaryGroupItem = VectorNavSensor::_binaryGroupINS.at(i);
156 TextColored(4, binaryGroupItem.name, _binaryOutputRegister.insField & binaryGroupItem.flagsValue);
157 if (ImGui::IsItemHovered() && binaryGroupItem.tooltip != nullptr)
158 {
159 ImGui::BeginTooltip();
160 binaryGroupItem.tooltip();
161 ImGui::EndTooltip();
162 }
163 }
165 {
166 const auto& binaryGroupItem = VectorNavSensor::_binaryGroupGNSS.at(i);
167 TextColored(5, binaryGroupItem.name, _binaryOutputRegister.gps2Field & binaryGroupItem.flagsValue);
168 if (ImGui::IsItemHovered() && binaryGroupItem.tooltip != nullptr)
169 {
170 ImGui::BeginTooltip();
171 binaryGroupItem.tooltip();
172 ImGui::EndTooltip();
173 }
174 }
175 }
176
177 ImGui::EndTable();
178 }
179}
180
181[[nodiscard]] json NAV::VectorNavFile::save() const
182{
183 LOG_TRACE("{}: called", nameId());
184
185 json j;
186
187 j["FileReader"] = FileReader::save();
188 j["Imu"] = Imu::save();
189
190 return j;
191}
192
194{
195 LOG_TRACE("{}: called", nameId());
196
197 if (j.contains("FileReader"))
198 {
199 FileReader::restore(j.at("FileReader"));
200 }
201 if (j.contains("Imu"))
202 {
203 Imu::restore(j.at("Imu"));
204 }
205}
206
208{
209 LOG_TRACE("{}: called", nameId());
210
211 return FileReader::initialize();
212}
213
215{
216 LOG_TRACE("{}: called", nameId());
217
219}
220
222{
224
225 _messageCount = 0;
226
227 return true;
228}
229
231{
232 LOG_TRACE("called");
233
234 std::filesystem::path filepath = getFilepath();
235
236 auto filestreamHeader = std::ifstream(filepath);
237 if (good())
238 {
239 std::array<char, std::string_view("GpsCycle,GpsWeek,GpsTow").length()> buffer{};
240 filestreamHeader.read(buffer.data(), buffer.size());
241 filestreamHeader.close();
242
243 if (std::string(buffer.data(), buffer.size()).starts_with("Time [s]"))
244 {
245 _hasTimeColumn = true;
246 return FileType::ASCII;
247 }
248 if (std::string(buffer.data(), buffer.size()).starts_with("GpsCycle,GpsWeek,GpsTow"))
249 {
250 _hasTimeColumn = false;
251 return FileType::ASCII;
252 }
253
254 return FileType::BINARY;
255 }
256
257 LOG_ERROR("Could not open file {}", filepath);
258 return FileType::NONE;
259}
260
262{
264 {
265 _binaryOutputRegister.timeField = vn::protocol::uart::TimeGroup::TIMEGROUP_NONE;
266 _binaryOutputRegister.imuField = vn::protocol::uart::ImuGroup::IMUGROUP_NONE;
267 _binaryOutputRegister.gpsField = vn::protocol::uart::GpsGroup::GPSGROUP_NONE;
268 _binaryOutputRegister.attitudeField = vn::protocol::uart::AttitudeGroup::ATTITUDEGROUP_NONE;
269 _binaryOutputRegister.insField = vn::protocol::uart::InsGroup::INSGROUP_NONE;
270 _binaryOutputRegister.gps2Field = vn::protocol::uart::GpsGroup::GPSGROUP_NONE;
271
272 // Read header line
273 std::string line;
274 getline(line);
275 // Remove any starting non text characters
276 line.erase(line.begin(), std::ranges::find_if(line, [](int ch) { return std::isalnum(ch); }));
277 // Convert line into stream
278 std::stringstream lineStream(line);
279 std::string cell;
280
281 int column = 0;
282 // Split line at comma
283 LOG_DATA("{}: Reading CSV header", nameId());
284 while (std::getline(lineStream, cell, ','))
285 {
286 // Remove any trailing non text characters
287 cell.erase(std::ranges::find_if(cell, [](int ch) { return std::iscntrl(ch); }), cell.end());
288
289 LOG_DATA("{}: {}", nameId(), cell);
290 _headerColumns.push_back(cell);
291 if (column++ > (_hasTimeColumn ? 3 : 2))
292 {
293 std::string group = cell.substr(0, cell.find("::")); // Extract the group (Time::TimeUTC::year -> 'Time')
294
295 cell = cell.substr(cell.find("::") + 2); // Remove the group -> 'TimeUTC::year'
296 if (cell.find("::") != std::string::npos)
297 {
298 cell = cell.substr(0, cell.find("::")); // Remove subgroups ('TimeUTC::year' -> 'TimeUTC')
299 }
300 if (cell.find(' ') != std::string::npos)
301 {
302 cell = cell.substr(0, cell.find(' ')); // Remove everything after a blank, which is the unit ('TimeStartup [ns]' -> 'TimeStartup')
303 }
304
305 bool identified = false;
306 if (group == "Time")
307 {
308 for (const auto& binaryGroupItem : VectorNavSensor::_binaryGroupTime)
309 {
310 if (cell == binaryGroupItem.name)
311 {
312 _binaryOutputRegister.timeField |= static_cast<vn::protocol::uart::TimeGroup>(binaryGroupItem.flagsValue);
313 identified = true;
314 break;
315 }
316 }
317 }
318 else if (group == "IMU")
319 {
320 for (const auto& binaryGroupItem : VectorNavSensor::_binaryGroupIMU)
321 {
322 if (cell == binaryGroupItem.name)
323 {
324 _binaryOutputRegister.imuField |= static_cast<vn::protocol::uart::ImuGroup>(binaryGroupItem.flagsValue);
325 identified = true;
326 break;
327 }
328 if (cell == "DeltaTime")
329 {
330 _binaryOutputRegister.imuField |= vn::protocol::uart::ImuGroup::IMUGROUP_DELTATHETA;
331 identified = true;
332 break;
333 }
334 }
335 }
336 else if (group == "GNSS1")
337 {
338 for (const auto& binaryGroupItem : VectorNavSensor::_binaryGroupGNSS)
339 {
340 if (cell == binaryGroupItem.name)
341 {
342 _binaryOutputRegister.gpsField |= static_cast<vn::protocol::uart::GpsGroup>(binaryGroupItem.flagsValue);
343 identified = true;
344 break;
345 }
346 }
347 }
348 else if (group == "Att")
349 {
350 for (const auto& binaryGroupItem : VectorNavSensor::_binaryGroupAttitude)
351 {
352 if (cell == binaryGroupItem.name)
353 {
354 _binaryOutputRegister.attitudeField |= static_cast<vn::protocol::uart::AttitudeGroup>(binaryGroupItem.flagsValue);
355 identified = true;
356 break;
357 }
358 }
359 }
360 else if (group == "INS")
361 {
362 for (const auto& binaryGroupItem : VectorNavSensor::_binaryGroupINS)
363 {
364 if (cell == binaryGroupItem.name)
365 {
366 _binaryOutputRegister.insField |= static_cast<vn::protocol::uart::InsGroup>(binaryGroupItem.flagsValue);
367 identified = true;
368 break;
369 }
370 }
371 }
372 else if (group == "GNSS2")
373 {
374 for (const auto& binaryGroupItem : VectorNavSensor::_binaryGroupGNSS)
375 {
376 if (cell == binaryGroupItem.name)
377 {
378 _binaryOutputRegister.gps2Field |= static_cast<vn::protocol::uart::GpsGroup>(binaryGroupItem.flagsValue);
379 identified = true;
380 break;
381 }
382 }
383 }
384 else
385 {
386 LOG_ERROR("{}: Could not identify the group in CSV header - {}::{}", nameId(), group, cell);
388 break;
389 }
390
391 if (!identified)
392 {
393 LOG_ERROR("{}: Could not identify the field in CSV header - {}::{}", nameId(), group, cell);
395 break;
396 }
397 }
398 }
399 }
400 else // if (fileType == FileType::BINARY)
401 {
402 read(reinterpret_cast<char*>(&_binaryOutputRegister.timeField), sizeof(vn::protocol::uart::TimeGroup));
403 read(reinterpret_cast<char*>(&_binaryOutputRegister.imuField), sizeof(vn::protocol::uart::ImuGroup));
404 read(reinterpret_cast<char*>(&_binaryOutputRegister.gpsField), sizeof(vn::protocol::uart::GpsGroup));
405 read(reinterpret_cast<char*>(&_binaryOutputRegister.attitudeField), sizeof(vn::protocol::uart::AttitudeGroup));
406 read(reinterpret_cast<char*>(&_binaryOutputRegister.insField), sizeof(vn::protocol::uart::InsGroup));
407 read(reinterpret_cast<char*>(&_binaryOutputRegister.gps2Field), sizeof(vn::protocol::uart::GpsGroup));
408 }
409}
410
411std::shared_ptr<const NAV::NodeData> NAV::VectorNavFile::pollData()
412{
413 auto obs = std::make_shared<VectorNavBinaryOutput>(_imuPos);
414
416 {
417 // Read line
418 std::string line;
419 getline(line);
421 // Remove any starting non text characters
422 line.erase(line.begin(), std::ranges::find_if(line, [](int ch) { return std::isgraph(ch); }));
423 LOG_DATA("{}: Reading line {}: {}", nameId(), _messageCount + 1, line);
424
425 if (line.empty())
426 {
427 LOG_DEBUG("{}: End of file reached after {} lines", nameId(), _messageCount);
428 return nullptr;
429 }
430
431 // Convert line into stream
432 std::stringstream lineStream(line);
433
434 size_t col = 0;
435 auto extractCell = [&lineStream, &col]() {
436 if (lineStream.eof())
437 {
438 throw std::runtime_error("End of file");
439 }
440 col++;
441 if (std::string cell; std::getline(lineStream, cell, ','))
442 {
443 // Remove any trailing non text characters
444 cell.erase(std::ranges::find_if(cell, [](int ch) { return std::iscntrl(ch); }), cell.end());
445
446 // LOG_DEBUG(" extractCell: {}", cell);
447 return cell;
448 }
449 return std::string("");
450 };
451 auto extractRemoveTillDelimiter = [](std::string& str, const std::string& delimiter) {
452 std::string extract;
453 if (size_t pos = str.find(delimiter);
454 pos != std::string::npos)
455 {
456 extract = str.substr(0, pos);
457 str = str.substr(pos + 1);
458 }
459
460 return extract;
461 };
462
463 auto extractSingleValue = [&](auto& field, auto flag, auto& out) {
464 static_assert(std::is_same_v<bool&, decltype(out)> || 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)>
465 || std::is_same_v<int8_t&, decltype(out)> || std::is_same_v<int16_t&, decltype(out)> || std::is_same_v<int32_t&, decltype(out)>
466 || std::is_same_v<float&, decltype(out)> || std::is_same_v<double&, decltype(out)>
467 || std::is_same_v<std::string&, decltype(out)>);
468
469 auto cell = extractCell();
470 LOG_DATA("{}: Extracting {}: {}", nameId(), vn::protocol::uart::to_string(flag), cell);
471
472 if (cell.empty()) { return; }
473
474 field |= flag; // set the flag
475 if constexpr (std::is_same_v<bool&, decltype(out)>
476 || std::is_same_v<uint8_t&, decltype(out)>
477 || std::is_same_v<uint16_t&, decltype(out)>
478 || std::is_same_v<uint32_t&, decltype(out)>)
479 {
480 out = static_cast<std::remove_reference_t<decltype(out)>>(std::stoul(cell));
481 }
482 else if constexpr (std::is_same_v<uint64_t&, decltype(out)>)
483 {
484 out = static_cast<std::remove_reference_t<decltype(out)>>(std::stoull(cell));
485 }
486 else if constexpr (std::is_same_v<int8_t&, decltype(out)>
487 || std::is_same_v<int16_t&, decltype(out)>
488 || std::is_same_v<int32_t&, decltype(out)>)
489 {
490 out = static_cast<std::remove_reference_t<decltype(out)>>(std::stoi(cell));
491 }
492 else if constexpr (std::is_same_v<float&, decltype(out)>)
493 {
494 out = static_cast<std::remove_reference_t<decltype(out)>>(std::stof(cell));
495 }
496 else if constexpr (std::is_same_v<double&, decltype(out)>)
497 {
498 out = static_cast<std::remove_reference_t<decltype(out)>>(std::stod(cell));
499 }
500 else if constexpr (std::is_same_v<std::string&, decltype(out)>)
501 {
502 out = cell;
503 }
504 };
505
506 auto extractValue = [&](auto& field, auto flag, auto&... out) {
507 (extractSingleValue(field, flag, out), ...);
508 };
509
510 try
511 {
512 if (_hasTimeColumn) { extractCell(); } // Time [s]
513 std::string gpsCycle = extractCell();
514 std::string gpsWeek = extractCell();
515 std::string gpsTow = extractCell();
516 if (!gpsCycle.empty() && !gpsWeek.empty() && !gpsTow.empty())
517 {
518 obs->insTime = InsTime(std::stoi(gpsCycle), std::stoi(gpsWeek), std::stold(gpsTow));
519 }
520 else
521 {
522 LOG_DATA("{}: Skipping message {}, as no InsTime set.", nameId(), _messageCount + 1);
523 return obs;
524 }
525
526 for (; col < _headerColumns.size();)
527 {
528 const auto& column = _headerColumns.at(col);
529 // Group 2 (Time)
530 if (_binaryOutputRegister.timeField != vn::protocol::uart::TimeGroup::TIMEGROUP_NONE)
531 {
532 if (!obs->timeOutputs) { obs->timeOutputs = std::make_shared<NAV::vendor::vectornav::TimeOutputs>(); }
533
534 if (column == "Time::TimeStartup [ns]")
535 {
536 extractValue(obs->timeOutputs->timeField, vn::protocol::uart::TimeGroup::TIMEGROUP_TIMESTARTUP, obs->timeOutputs->timeStartup);
537 continue;
538 }
539 if (column == "Time::TimeGps [ns]")
540 {
541 extractValue(obs->timeOutputs->timeField, vn::protocol::uart::TimeGroup::TIMEGROUP_TIMEGPS, obs->timeOutputs->timeGps);
542 continue;
543 }
544 if (column == "Time::GpsTow [ns]")
545 {
546 extractValue(obs->timeOutputs->timeField, vn::protocol::uart::TimeGroup::TIMEGROUP_GPSTOW, obs->timeOutputs->gpsTow);
547 continue;
548 }
549 if (column == "Time::GpsWeek")
550 {
551 extractValue(obs->timeOutputs->timeField, vn::protocol::uart::TimeGroup::TIMEGROUP_GPSWEEK, obs->timeOutputs->gpsWeek);
552 continue;
553 }
554 if (column == "Time::TimeSyncIn [ns]")
555 {
556 extractValue(obs->timeOutputs->timeField, vn::protocol::uart::TimeGroup::TIMEGROUP_TIMESYNCIN, obs->timeOutputs->timeSyncIn);
557 continue;
558 }
559 if (column == "Time::TimeGpsPps [ns]")
560 {
561 extractValue(obs->timeOutputs->timeField, vn::protocol::uart::TimeGroup::TIMEGROUP_TIMEGPSPPS, obs->timeOutputs->timePPS);
562 continue;
563 }
564 if (column == "Time::TimeUTC::year")
565 {
566 extractValue(obs->timeOutputs->timeField, vn::protocol::uart::TimeGroup::TIMEGROUP_TIMEUTC,
567 obs->timeOutputs->timeUtc.year, obs->timeOutputs->timeUtc.month, obs->timeOutputs->timeUtc.day,
568 obs->timeOutputs->timeUtc.hour, obs->timeOutputs->timeUtc.min, obs->timeOutputs->timeUtc.sec, obs->timeOutputs->timeUtc.ms);
569 continue;
570 }
571 if (column == "Time::SyncInCnt")
572 {
573 extractValue(obs->timeOutputs->timeField, vn::protocol::uart::TimeGroup::TIMEGROUP_SYNCINCNT, obs->timeOutputs->syncInCnt);
574 continue;
575 }
576 if (column == "Time::SyncOutCnt")
577 {
578 extractValue(obs->timeOutputs->timeField, vn::protocol::uart::TimeGroup::TIMEGROUP_SYNCOUTCNT, obs->timeOutputs->syncOutCnt);
579 continue;
580 }
581 if (column == "Time::TimeStatus::timeOk") // "Time::TimeStatus::dateOk", "Time::TimeStatus::utcTimeValid"
582 {
583 uint8_t timeOk{};
584 uint8_t dateOk{};
585 uint8_t utcTimeValid{};
586 extractValue(obs->timeOutputs->timeField, vn::protocol::uart::TimeGroup::TIMEGROUP_TIMESTATUS, timeOk, dateOk, utcTimeValid);
587 obs->timeOutputs->timeStatus = static_cast<uint8_t>(timeOk << 0U | dateOk << 1U | utcTimeValid << 2U);
588 continue;
589 }
590 }
591 // Group 3 (IMU)
592 if (_binaryOutputRegister.imuField != vn::protocol::uart::ImuGroup::IMUGROUP_NONE)
593 {
594 if (!obs->imuOutputs) { obs->imuOutputs = std::make_shared<NAV::vendor::vectornav::ImuOutputs>(); }
595
596 if (column == "IMU::ImuStatus")
597 {
598 extractValue(obs->imuOutputs->imuField, vn::protocol::uart::ImuGroup::IMUGROUP_IMUSTATUS, obs->imuOutputs->imuStatus);
599 continue;
600 }
601 if (column.starts_with("IMU::UncompMag::X")) // "IMU::UncompMag::Y [Gauss]", "IMU::UncompMag::Z [Gauss]"
602 {
603 extractValue(obs->imuOutputs->imuField, vn::protocol::uart::ImuGroup::IMUGROUP_UNCOMPMAG,
604 obs->imuOutputs->uncompMag.x(), obs->imuOutputs->uncompMag.y(), obs->imuOutputs->uncompMag.z());
605 continue;
606 }
607 if (column.starts_with("IMU::UncompAccel::X")) // "IMU::UncompAccel::Y [m/s^2]", "IMU::UncompAccel::Z [m/s^2]"
608 {
609 extractValue(obs->imuOutputs->imuField, vn::protocol::uart::ImuGroup::IMUGROUP_UNCOMPACCEL,
610 obs->imuOutputs->uncompAccel.x(), obs->imuOutputs->uncompAccel.y(), obs->imuOutputs->uncompAccel.z());
611 continue;
612 }
613 if (column.starts_with("IMU::UncompGyro::X")) // "IMU::UncompGyro::Y [rad/s]", "IMU::UncompGyro::Z [rad/s]"
614 {
615 extractValue(obs->imuOutputs->imuField, vn::protocol::uart::ImuGroup::IMUGROUP_UNCOMPGYRO,
616 obs->imuOutputs->uncompGyro.x(), obs->imuOutputs->uncompGyro.y(), obs->imuOutputs->uncompGyro.z());
617 continue;
618 }
619 if (column.starts_with("IMU::Temp"))
620 {
621 extractValue(obs->imuOutputs->imuField, vn::protocol::uart::ImuGroup::IMUGROUP_TEMP, obs->imuOutputs->temp);
622 continue;
623 }
624 if (column.starts_with("IMU::Pres"))
625 {
626 extractValue(obs->imuOutputs->imuField, vn::protocol::uart::ImuGroup::IMUGROUP_PRES, obs->imuOutputs->pres);
627 continue;
628 }
629 if (column.starts_with("IMU::DeltaTime")) // "IMU::DeltaTheta::X [deg]", "IMU::DeltaTheta::Y [deg]", "IMU::DeltaTheta::Z [deg]"
630 {
631 extractValue(obs->imuOutputs->imuField, vn::protocol::uart::ImuGroup::IMUGROUP_DELTATHETA,
632 obs->imuOutputs->deltaTime, obs->imuOutputs->deltaTheta.x(), obs->imuOutputs->deltaTheta.y(), obs->imuOutputs->deltaTheta.z());
633 continue;
634 }
635 if (column.starts_with("IMU::DeltaVel::X")) // "IMU::DeltaVel::Y [m/s]", "IMU::DeltaVel::Z [m/s]"
636 {
637 extractValue(obs->imuOutputs->imuField, vn::protocol::uart::ImuGroup::IMUGROUP_DELTAVEL,
638 obs->imuOutputs->deltaV.x(), obs->imuOutputs->deltaV.y(), obs->imuOutputs->deltaV.z());
639 continue;
640 }
641 if (column.starts_with("IMU::Mag::X")) // "IMU::Mag::Y [Gauss]", "IMU::Mag::Z [Gauss]"
642 {
643 extractValue(obs->imuOutputs->imuField, vn::protocol::uart::ImuGroup::IMUGROUP_MAG,
644 obs->imuOutputs->mag.x(), obs->imuOutputs->mag.y(), obs->imuOutputs->mag.z());
645 continue;
646 }
647 if (column.starts_with("IMU::Accel::X")) // "IMU::Accel::Y [m/s^2]", "IMU::Accel::Z [m/s^2]"
648 {
649 extractValue(obs->imuOutputs->imuField, vn::protocol::uart::ImuGroup::IMUGROUP_ACCEL,
650 obs->imuOutputs->accel.x(), obs->imuOutputs->accel.y(), obs->imuOutputs->accel.z());
651 continue;
652 }
653 if (column.starts_with("IMU::AngularRate::X")) // "IMU::AngularRate::Y [rad/s]", "IMU::AngularRate::Z [rad/s]"
654 {
655 extractValue(obs->imuOutputs->imuField, vn::protocol::uart::ImuGroup::IMUGROUP_ANGULARRATE,
656 obs->imuOutputs->angularRate.x(), obs->imuOutputs->angularRate.y(), obs->imuOutputs->angularRate.z());
657 continue;
658 }
659 }
660 // Group 4 (GNSS1)
661 if (_binaryOutputRegister.gpsField != vn::protocol::uart::GpsGroup::GPSGROUP_NONE)
662 {
663 if (!obs->gnss1Outputs) { obs->gnss1Outputs = std::make_shared<NAV::vendor::vectornav::GnssOutputs>(); }
664
665 if (column == "GNSS1::UTC::year") // "GNSS1::UTC::month", "GNSS1::UTC::day", "GNSS1::UTC::hour", "GNSS1::UTC::min", "GNSS1::UTC::sec", "GNSS1::UTC::ms"
666 {
667 extractValue(obs->gnss1Outputs->gnssField, vn::protocol::uart::GpsGroup::GPSGROUP_UTC,
668 obs->gnss1Outputs->timeUtc.year, obs->gnss1Outputs->timeUtc.month, obs->gnss1Outputs->timeUtc.day,
669 obs->gnss1Outputs->timeUtc.hour, obs->gnss1Outputs->timeUtc.min, obs->gnss1Outputs->timeUtc.sec, obs->gnss1Outputs->timeUtc.ms);
670 continue;
671 }
672 if (column == "GNSS1::Tow [ns]")
673 {
674 extractValue(obs->gnss1Outputs->gnssField, vn::protocol::uart::GpsGroup::GPSGROUP_TOW, obs->gnss1Outputs->tow);
675 continue;
676 }
677 if (column == "GNSS1::Week")
678 {
679 extractValue(obs->gnss1Outputs->gnssField, vn::protocol::uart::GpsGroup::GPSGROUP_WEEK, obs->gnss1Outputs->week);
680 continue;
681 }
682 if (column == "GNSS1::NumSats")
683 {
684 extractValue(obs->gnss1Outputs->gnssField, vn::protocol::uart::GpsGroup::GPSGROUP_NUMSATS, obs->gnss1Outputs->numSats);
685 continue;
686 }
687 if (column == "GNSS1::Fix")
688 {
689 extractValue(obs->gnss1Outputs->gnssField, vn::protocol::uart::GpsGroup::GPSGROUP_FIX, obs->gnss1Outputs->fix);
690 continue;
691 }
692 if (column == "GNSS1::PosLla::latitude [deg]") // "GNSS1::PosLla::longitude [deg]", "GNSS1::PosLla::altitude [m]"
693 {
694 extractValue(obs->gnss1Outputs->gnssField, vn::protocol::uart::GpsGroup::GPSGROUP_POSLLA,
695 obs->gnss1Outputs->posLla.x(), obs->gnss1Outputs->posLla.y(), obs->gnss1Outputs->posLla.z());
696 continue;
697 }
698 if (column == "GNSS1::PosEcef::X [m]") // "GNSS1::PosEcef::Y [m]", "GNSS1::PosEcef::Z [m]"
699 {
700 extractValue(obs->gnss1Outputs->gnssField, vn::protocol::uart::GpsGroup::GPSGROUP_POSECEF,
701 obs->gnss1Outputs->posEcef.x(), obs->gnss1Outputs->posEcef.y(), obs->gnss1Outputs->posEcef.z());
702 continue;
703 }
704 if (column == "GNSS1::VelNed::N [m/s]") // "GNSS1::VelNed::E [m/s]", "GNSS1::VelNed::D [m/s]"
705 {
706 extractValue(obs->gnss1Outputs->gnssField, vn::protocol::uart::GpsGroup::GPSGROUP_VELNED,
707 obs->gnss1Outputs->velNed.x(), obs->gnss1Outputs->velNed.y(), obs->gnss1Outputs->velNed.z());
708 continue;
709 }
710 if (column == "GNSS1::VelEcef::X [m/s]") // "GNSS1::VelEcef::Y [m/s]", "GNSS1::VelEcef::Z [m/s]"
711 {
712 extractValue(obs->gnss1Outputs->gnssField, vn::protocol::uart::GpsGroup::GPSGROUP_VELECEF,
713 obs->gnss1Outputs->velEcef.x(), obs->gnss1Outputs->velEcef.y(), obs->gnss1Outputs->velEcef.z());
714 continue;
715 }
716 if (column == "GNSS1::PosU::N [m]") // "GNSS1::PosU::E [m]", "GNSS1::PosU::D [m]"
717 {
718 extractValue(obs->gnss1Outputs->gnssField, vn::protocol::uart::GpsGroup::GPSGROUP_POSU,
719 obs->gnss1Outputs->posU.x(), obs->gnss1Outputs->posU.y(), obs->gnss1Outputs->posU.z());
720 continue;
721 }
722 if (column == "GNSS1::VelU [m/s]")
723 {
724 extractValue(obs->gnss1Outputs->gnssField, vn::protocol::uart::GpsGroup::GPSGROUP_VELU, obs->gnss1Outputs->velU);
725 continue;
726 }
727 if (column == "GNSS1::TimeU [s]")
728 {
729 extractValue(obs->gnss1Outputs->gnssField, vn::protocol::uart::GpsGroup::GPSGROUP_TIMEU, obs->gnss1Outputs->timeU);
730 continue;
731 }
732 if (column == "GNSS1::TimeInfo::Status::timeOk") // "GNSS1::TimeInfo::Status::dateOk", "GNSS1::TimeInfo::Status::utcTimeValid", "GNSS1::TimeInfo::LeapSeconds"
733 {
734 uint8_t timeOk{};
735 uint8_t dateOk{};
736 uint8_t utcTimeValid{};
737 extractValue(obs->gnss1Outputs->gnssField, vn::protocol::uart::GpsGroup::GPSGROUP_TIMEINFO, timeOk, dateOk, utcTimeValid, obs->gnss1Outputs->timeInfo.leapSeconds);
738 obs->gnss1Outputs->timeInfo.status = static_cast<uint8_t>(timeOk << 0U | dateOk << 1U | utcTimeValid << 2U);
739 continue;
740 }
741 if (column == "GNSS1::DOP::g") // "GNSS1::DOP::p","GNSS1::DOP::t","GNSS1::DOP::v","GNSS1::DOP::h","GNSS1::DOP::n","GNSS1::DOP::e"
742 {
743 extractValue(obs->gnss1Outputs->gnssField, vn::protocol::uart::GpsGroup::GPSGROUP_DOP,
744 obs->gnss1Outputs->dop.gDop, obs->gnss1Outputs->dop.pDop, obs->gnss1Outputs->dop.tDop, obs->gnss1Outputs->dop.vDop,
745 obs->gnss1Outputs->dop.hDop, obs->gnss1Outputs->dop.nDop, obs->gnss1Outputs->dop.eDop);
746 continue;
747 }
748 if (column == "GNSS1::SatInfo::NumSats")
749 {
750 extractValue(obs->gnss1Outputs->gnssField, vn::protocol::uart::GpsGroup::GPSGROUP_SATINFO, obs->gnss1Outputs->satInfo.numSats);
751 continue;
752 }
753 if (column == "GNSS1::SatInfo::Satellites")
754 {
755 std::string satellites;
756 extractValue(obs->gnss1Outputs->gnssField, vn::protocol::uart::GpsGroup::GPSGROUP_SATINFO, satellites);
757
758 for (size_t i = 0; i < obs->gnss1Outputs->satInfo.numSats; i++)
759 {
760 satellites = satellites.substr(1); // Remove leading '['
761 auto sys = static_cast<int8_t>(std::stoi(extractRemoveTillDelimiter(satellites, "|")));
762 auto svId = static_cast<uint8_t>(std::stoul(extractRemoveTillDelimiter(satellites, "|")));
763 auto flagHealthy = static_cast<uint8_t>(std::stoul(extractRemoveTillDelimiter(satellites, "|")));
764 auto flagAlmanac = static_cast<uint8_t>(std::stoul(extractRemoveTillDelimiter(satellites, "|")));
765 auto flagEphemeris = static_cast<uint8_t>(std::stoul(extractRemoveTillDelimiter(satellites, "|")));
766 auto flagDifferentialCorrection = static_cast<uint8_t>(std::stoul(extractRemoveTillDelimiter(satellites, "|")));
767 auto flagUsedForNavigation = static_cast<uint8_t>(std::stoul(extractRemoveTillDelimiter(satellites, "|")));
768 auto flagAzimuthElevationValid = static_cast<uint8_t>(std::stoul(extractRemoveTillDelimiter(satellites, "|")));
769 auto flagUsedForRTK = static_cast<uint8_t>(std::stoul(extractRemoveTillDelimiter(satellites, "|")));
770 auto flags = static_cast<uint8_t>(flagHealthy << 0U
771 | flagAlmanac << 1U
772 | flagEphemeris << 2U
773 | flagDifferentialCorrection << 3U
774 | flagUsedForNavigation << 4U
775 | flagAzimuthElevationValid << 5U
776 | flagUsedForRTK << 6U);
777 auto cno = static_cast<uint8_t>(std::stoul(extractRemoveTillDelimiter(satellites, "|")));
778 auto qi = static_cast<uint8_t>(std::stoul(extractRemoveTillDelimiter(satellites, "|")));
779 auto el = static_cast<int8_t>(std::stoi(extractRemoveTillDelimiter(satellites, "|")));
780 auto az = static_cast<int16_t>(std::stoi(extractRemoveTillDelimiter(satellites, "]")));
781 obs->gnss1Outputs->satInfo.satellites.emplace_back(sys, svId, flags, cno, qi, el, az);
782 }
783 continue;
784 }
785 if (column.starts_with("GNSS1::SatInfo::") && column.ends_with(" - flag Healthy"))
786 {
787 std::string columnText = column.substr(16);
788 SatId satId(extractRemoveTillDelimiter(columnText, " -"));
789 LOG_DATA("{}: SatInfo {}", nameId(), satId);
790 bool flagHealthy{};
791 bool flagAlmanac{};
792 bool flagEphemeris{};
793 bool flagDifferentialCorrection{};
794 bool flagUsedForNavigation{};
795 bool flagAzimuthElevationValid{};
796 bool flagUsedForRTK{};
797 auto cno = std::numeric_limits<uint8_t>::max();
798 uint8_t qi{};
799 int8_t el{};
800 int16_t az{};
801 extractValue(obs->gnss1Outputs->gnssField, vn::protocol::uart::GpsGroup::GPSGROUP_SATINFO,
802 flagHealthy, flagAlmanac, flagEphemeris, flagDifferentialCorrection,
803 flagUsedForNavigation, flagAzimuthElevationValid, flagUsedForRTK,
804 cno, qi, el, az);
805 if (cno == std::numeric_limits<uint8_t>::max())
806 {
807 LOG_DATA("{}: Skipping {} as empty", nameId(), satId);
808 continue;
809 }
810 auto flags = static_cast<uint8_t>(flagHealthy << 0U
811 | flagAlmanac << 1U
812 | flagEphemeris << 2U
813 | flagDifferentialCorrection << 3U
814 | flagUsedForNavigation << 4U
815 | flagAzimuthElevationValid << 5U
816 | flagUsedForRTK << 6U);
817 obs->gnss1Outputs->satInfo.satellites.emplace_back(static_cast<uint8_t>(vendor::vectornav::fromSatelliteSystem(satId.satSys)),
818 static_cast<uint8_t>(satId.satNum), flags, cno, qi, el, az);
819 continue;
820 }
821 if (column == "GNSS1::RawMeas::Tow [s]")
822 {
823 extractValue(obs->gnss1Outputs->gnssField, vn::protocol::uart::GpsGroup::GPSGROUP_RAWMEAS, obs->gnss1Outputs->raw.tow);
824 continue;
825 }
826 if (column == "GNSS1::RawMeas::Week")
827 {
828 extractValue(obs->gnss1Outputs->gnssField, vn::protocol::uart::GpsGroup::GPSGROUP_RAWMEAS, obs->gnss1Outputs->raw.week);
829 continue;
830 }
831 if (column == "GNSS1::RawMeas::NumSats")
832 {
833 extractValue(obs->gnss1Outputs->gnssField, vn::protocol::uart::GpsGroup::GPSGROUP_RAWMEAS, obs->gnss1Outputs->raw.numSats);
834 continue;
835 }
836 if (column == "GNSS1::RawMeas::Satellites")
837 {
838 std::string satellites;
839 extractValue(obs->gnss1Outputs->gnssField, vn::protocol::uart::GpsGroup::GPSGROUP_RAWMEAS, satellites);
840
841 for (size_t i = 0; i < obs->gnss1Outputs->raw.numSats; i++)
842 {
843 satellites = satellites.substr(1); // Remove leading '['
844 auto sys = static_cast<uint8_t>(std::stoul(extractRemoveTillDelimiter(satellites, "|")));
845 auto svId = static_cast<uint8_t>(std::stoul(extractRemoveTillDelimiter(satellites, "|")));
846 auto freq = static_cast<uint8_t>(std::stoul(extractRemoveTillDelimiter(satellites, "|")));
847 auto chan = static_cast<uint8_t>(std::stoul(extractRemoveTillDelimiter(satellites, "|")));
848 auto slot = static_cast<int8_t>(std::stoi(extractRemoveTillDelimiter(satellites, "|")));
849 auto cno = static_cast<uint8_t>(std::stoul(extractRemoveTillDelimiter(satellites, "|")));
850 auto flagSearching = static_cast<uint8_t>(std::stoul(extractRemoveTillDelimiter(satellites, "|")));
851 auto flagTracking = static_cast<uint8_t>(std::stoul(extractRemoveTillDelimiter(satellites, "|")));
852 auto flagTimeValid = static_cast<uint8_t>(std::stoul(extractRemoveTillDelimiter(satellites, "|")));
853 auto flagCodeLock = static_cast<uint8_t>(std::stoul(extractRemoveTillDelimiter(satellites, "|")));
854 auto flagPhaseLock = static_cast<uint8_t>(std::stoul(extractRemoveTillDelimiter(satellites, "|")));
855 auto flagPhaseHalfAmbiguity = static_cast<uint8_t>(std::stoul(extractRemoveTillDelimiter(satellites, "|")));
856 auto flagPhaseHalfSub = static_cast<uint8_t>(std::stoul(extractRemoveTillDelimiter(satellites, "|")));
857 auto flagPhaseSlip = static_cast<uint8_t>(std::stoul(extractRemoveTillDelimiter(satellites, "|")));
858 auto flagPseudorangeSmoothed = static_cast<uint8_t>(std::stoul(extractRemoveTillDelimiter(satellites, "|")));
859 auto flags = static_cast<uint16_t>(flagSearching << 0U
860 | flagTracking << 1U
861 | flagTimeValid << 2U
862 | flagCodeLock << 3U
863 | flagPhaseLock << 4U
864 | flagPhaseHalfAmbiguity << 5U
865 | flagPhaseHalfSub << 6U
866 | flagPhaseSlip << 7U
867 | flagPseudorangeSmoothed << 8U);
868 auto pr = std::stod(extractRemoveTillDelimiter(satellites, "|"));
869 auto cp = std::stod(extractRemoveTillDelimiter(satellites, "|"));
870 auto dp = std::stof(extractRemoveTillDelimiter(satellites, "]"));
871 obs->gnss1Outputs->raw.satellites.emplace_back(sys, svId, freq, chan, slot, cno, flags, pr, cp, dp);
872 }
873 continue;
874 }
875 if (column.starts_with("GNSS1::RawMeas::") && column.ends_with(" - freq"))
876 {
877 std::string columnText = column.substr(16);
878 auto identifier = extractRemoveTillDelimiter(columnText, " - freq");
879 LOG_DATA("{}: RawMeas {}", nameId(), identifier);
880 SatelliteSystem satSys;
881 uint16_t satNum{};
882 if (identifier.length() == 6)
883 {
884 SatSigId satSigId(identifier);
885 satSys = satSigId.toSatId().satSys;
886 satNum = satSigId.satNum;
887 }
888 else
889 {
890 SatId satId(identifier);
891 satSys = satId.satSys;
892 satNum = satId.satNum;
893 }
894 auto freq = std::numeric_limits<uint8_t>::max();
895 uint8_t chan{};
896 int8_t slot{};
897 uint8_t cno{};
898 uint8_t flagSearching{};
899 uint8_t flagTracking{};
900 uint8_t flagTimeValid{};
901 uint8_t flagCodeLock{};
902 uint8_t flagPhaseLock{};
903 uint8_t flagPhaseHalfAmbiguity{};
904 uint8_t flagPhaseHalfSub{};
905 uint8_t flagPhaseSlip{};
906 uint8_t flagPseudorangeSmoothed{};
907 double pr{};
908 double cp{};
909 float dp{};
910 extractValue(obs->gnss1Outputs->gnssField, vn::protocol::uart::GpsGroup::GPSGROUP_RAWMEAS,
911 freq, chan, slot, cno,
912 flagSearching, flagTracking, flagTimeValid, flagCodeLock, flagPhaseLock,
913 flagPhaseHalfAmbiguity, flagPhaseHalfSub, flagPhaseSlip, flagPseudorangeSmoothed,
914 pr, cp, dp);
915 if (freq == std::numeric_limits<uint8_t>::max())
916 {
917 LOG_DATA("{}: Skipping {} as empty", nameId(), identifier);
918 continue;
919 }
920 auto flags = static_cast<uint16_t>(flagSearching << 0U
921 | flagTracking << 1U
922 | flagTimeValid << 2U
923 | flagCodeLock << 3U
924 | flagPhaseLock << 4U
925 | flagPhaseHalfAmbiguity << 5U
926 | flagPhaseHalfSub << 6U
927 | flagPhaseSlip << 7U
928 | flagPseudorangeSmoothed << 8U);
929 obs->gnss1Outputs->raw.satellites.emplace_back(static_cast<uint8_t>(vendor::vectornav::fromSatelliteSystem(satSys)),
930 static_cast<uint8_t>(satNum), freq, chan, slot, cno, flags, pr, cp, dp);
931 if (obs->gnss1Outputs->raw.satellites.back().toCode() == Code::None)
932 {
933 LOG_ERROR("{}: Line {}: Could not convert to valid Code. Skipping item. (sys {}, freq {}, chan {})", nameId(), _messageCount + 1,
934 obs->gnss1Outputs->raw.satellites.back().sys, obs->gnss1Outputs->raw.satellites.back().freq, obs->gnss1Outputs->raw.satellites.back().chan);
935 obs->gnss1Outputs->raw.satellites.pop_back();
936 }
937 if (identifier.length() == 6 && SatSigId(identifier) != obs->gnss1Outputs->raw.satellites.back().toSatSigId())
938 {
939 LOG_ERROR("{}: Line {}: Could not convert to valid SatSigId. Skipping item. (sys {}, freq {}, chan {} = [{}], column was [{}])", nameId(), _messageCount + 1,
940 obs->gnss1Outputs->raw.satellites.back().sys, obs->gnss1Outputs->raw.satellites.back().freq, obs->gnss1Outputs->raw.satellites.back().chan,
941 obs->gnss1Outputs->raw.satellites.back().toSatSigId(), identifier);
942 obs->gnss1Outputs->raw.satellites.pop_back();
943 }
944 continue;
945 }
946 }
947 // Group 5 (Attitude)
948 if (_binaryOutputRegister.attitudeField != vn::protocol::uart::AttitudeGroup::ATTITUDEGROUP_NONE)
949 {
950 if (!obs->attitudeOutputs) { obs->attitudeOutputs = std::make_shared<NAV::vendor::vectornav::AttitudeOutputs>(); }
951
952 if (column == "Att::VpeStatus::AttitudeQuality") // "Att::VpeStatus::GyroSaturation", "Att::VpeStatus::GyroSaturationRecovery", "Att::VpeStatus::MagDisturbance", "Att::VpeStatus::MagSaturation", "Att::VpeStatus::AccDisturbance", "Att::VpeStatus::AccSaturation", "Att::VpeStatus::KnownMagDisturbance", "Att::VpeStatus::KnownAccelDisturbance"
953 {
954 uint8_t attitudeQuality{}; // return ((_status & (1U << 0U | 1U << 1U)) >> 0U);
955 uint8_t gyroSaturation{}; // return ((_status & (1U << 2U)) >> 2U);
956 uint8_t gyroSaturationRecovery{}; // return ((_status & (1U << 3U)) >> 3U);
957 uint8_t magDisturbance{}; // return ((_status & (1U << 4U | 1U << 5U)) >> 4U);
958 uint8_t magSaturation{}; // return ((_status & (1U << 6U)) >> 6U);
959 uint8_t accDisturbance{}; // return ((_status & (1U << 7U | 1U << 8U)) >> 7U);
960 uint8_t accSaturation{}; // return ((_status & (1U << 9U)) >> 9U);
961 uint8_t knownMagDisturbance{}; // return ((_status & (1U << 11U)) >> 11U);
962 uint8_t knownAccelDisturbance{}; // return ((_status & (1U << 12U)) >> 12U);
963 extractValue(obs->attitudeOutputs->attitudeField, vn::protocol::uart::AttitudeGroup::ATTITUDEGROUP_VPESTATUS,
964 attitudeQuality, gyroSaturation, gyroSaturationRecovery, magDisturbance, magSaturation, accDisturbance, accSaturation, knownMagDisturbance, knownAccelDisturbance);
965 obs->attitudeOutputs->vpeStatus = static_cast<uint16_t>(attitudeQuality << 0U
966 | gyroSaturation << 2U
967 | gyroSaturationRecovery << 3U
968 | magDisturbance << 4U
969 | magSaturation << 6U
970 | accDisturbance << 7U
971 | accSaturation << 9U
972 | knownMagDisturbance << 11U
973 | knownAccelDisturbance << 12U);
974 continue;
975 }
976 if (column == "Att::YawPitchRoll::Y [deg]") // "Att::YawPitchRoll::P [deg]", "Att::YawPitchRoll::R [deg]"
977 {
978 extractValue(obs->attitudeOutputs->attitudeField, vn::protocol::uart::AttitudeGroup::ATTITUDEGROUP_YAWPITCHROLL,
979 obs->attitudeOutputs->ypr.x(), obs->attitudeOutputs->ypr.y(), obs->attitudeOutputs->ypr.z());
980 continue;
981 }
982 if (column == "Att::Quaternion::w") // "Att::Quaternion::x", "Att::Quaternion::y", "Att::Quaternion::z"
983 {
984 extractValue(obs->attitudeOutputs->attitudeField, vn::protocol::uart::AttitudeGroup::ATTITUDEGROUP_QUATERNION,
985 obs->attitudeOutputs->qtn.w(), obs->attitudeOutputs->qtn.x(), obs->attitudeOutputs->qtn.y(), obs->attitudeOutputs->qtn.z());
986 continue;
987 }
988 if (column == "Att::DCM::0-0") // "Att::DCM::0-1", "Att::DCM::0-2", "Att::DCM::1-0", "Att::DCM::1-1", "Att::DCM::1-2", "Att::DCM::2-0", "Att::DCM::2-1", "Att::DCM::2-2"
989 {
990 extractValue(obs->attitudeOutputs->attitudeField, vn::protocol::uart::AttitudeGroup::ATTITUDEGROUP_DCM,
991 obs->attitudeOutputs->dcm(0, 0), obs->attitudeOutputs->dcm(0, 1), obs->attitudeOutputs->dcm(0, 2),
992 obs->attitudeOutputs->dcm(1, 0), obs->attitudeOutputs->dcm(1, 1), obs->attitudeOutputs->dcm(1, 2),
993 obs->attitudeOutputs->dcm(2, 0), obs->attitudeOutputs->dcm(2, 1), obs->attitudeOutputs->dcm(2, 2));
994 continue;
995 }
996 if (column == "Att::MagNed::N [Gauss]") // "Att::MagNed::E [Gauss]", "Att::MagNed::D [Gauss]"
997 {
998 extractValue(obs->attitudeOutputs->attitudeField, vn::protocol::uart::AttitudeGroup::ATTITUDEGROUP_MAGNED,
999 obs->attitudeOutputs->magNed.x(), obs->attitudeOutputs->magNed.y(), obs->attitudeOutputs->magNed.z());
1000 continue;
1001 }
1002 if (column == "Att::AccelNed::N [m/s^2]") // "Att::AccelNed::E [m/s^2]", "Att::AccelNed::D [m/s^2]"
1003 {
1004 extractValue(obs->attitudeOutputs->attitudeField, vn::protocol::uart::AttitudeGroup::ATTITUDEGROUP_ACCELNED,
1005 obs->attitudeOutputs->accelNed.x(), obs->attitudeOutputs->accelNed.y(), obs->attitudeOutputs->accelNed.z());
1006 continue;
1007 }
1008 if (column == "Att::LinearAccelBody::X [m/s^2]") // "Att::LinearAccelBody::Y [m/s^2]", "Att::LinearAccelBody::Z [m/s^2]"
1009 {
1010 extractValue(obs->attitudeOutputs->attitudeField, vn::protocol::uart::AttitudeGroup::ATTITUDEGROUP_LINEARACCELBODY,
1011 obs->attitudeOutputs->linearAccelBody.x(), obs->attitudeOutputs->linearAccelBody.y(), obs->attitudeOutputs->linearAccelBody.z());
1012 continue;
1013 }
1014 if (column == "Att::LinearAccelNed::N [m/s^2]") // "Att::LinearAccelNed::E [m/s^2]", "Att::LinearAccelNed::D [m/s^2]"
1015 {
1016 extractValue(obs->attitudeOutputs->attitudeField, vn::protocol::uart::AttitudeGroup::ATTITUDEGROUP_LINEARACCELNED,
1017 obs->attitudeOutputs->linearAccelNed.x(), obs->attitudeOutputs->linearAccelNed.y(), obs->attitudeOutputs->linearAccelNed.z());
1018 continue;
1019 }
1020 if (column == "Att::YprU::Y [deg]") // "Att::YprU::P [deg]", "Att::YprU::R [deg]"
1021 {
1022 extractValue(obs->attitudeOutputs->attitudeField, vn::protocol::uart::AttitudeGroup::ATTITUDEGROUP_YPRU,
1023 obs->attitudeOutputs->yprU.x(), obs->attitudeOutputs->yprU.y(), obs->attitudeOutputs->yprU.z());
1024 continue;
1025 }
1026 }
1027 // Group 6 (INS)
1028 if (_binaryOutputRegister.insField != vn::protocol::uart::InsGroup::INSGROUP_NONE)
1029 {
1030 if (!obs->insOutputs) { obs->insOutputs = std::make_shared<NAV::vendor::vectornav::InsOutputs>(); }
1031
1032 if (column == "INS::InsStatus::Mode") // "INS::InsStatus::GpsFix", "INS::InsStatus::Error::IMU", "INS::InsStatus::Error::MagPres", "INS::InsStatus::Error::GNSS", "INS::InsStatus::GpsHeadingIns", "INS::InsStatus::GpsCompass"
1033 {
1034 uint8_t mode{};
1035 uint8_t gpsFix{};
1036 uint8_t errorImu{};
1037 uint8_t errorMagPres{};
1038 uint8_t errorGnss{};
1039 uint8_t gpsHeadingIns{};
1040 uint8_t gpsCompass{};
1041 extractValue(obs->insOutputs->insField, vn::protocol::uart::InsGroup::INSGROUP_INSSTATUS,
1042 mode, gpsFix, errorImu, errorMagPres, errorGnss, gpsHeadingIns, gpsCompass);
1043 obs->insOutputs->insStatus.status() = static_cast<uint16_t>(mode << 0U | gpsFix << 2U
1044 | errorImu << 4U | errorMagPres << 5U | errorGnss << 6U
1045 | gpsHeadingIns << 8U | gpsCompass << 9U);
1046 continue;
1047 }
1048 if (column == "INS::PosLla::latitude [deg]") // "INS::PosLla::longitude [deg]", "INS::PosLla::altitude [m]"
1049 {
1050 extractValue(obs->insOutputs->insField, vn::protocol::uart::InsGroup::INSGROUP_POSLLA,
1051 obs->insOutputs->posLla.x(), obs->insOutputs->posLla.y(), obs->insOutputs->posLla.z());
1052 continue;
1053 }
1054 if (column == "INS::PosEcef::X [m]") // "INS::PosEcef::Y [m]", "INS::PosEcef::Z [m]"
1055 {
1056 extractValue(obs->insOutputs->insField, vn::protocol::uart::InsGroup::INSGROUP_POSECEF,
1057 obs->insOutputs->posEcef.x(), obs->insOutputs->posEcef.y(), obs->insOutputs->posEcef.z());
1058 continue;
1059 }
1060 if (column == "INS::VelBody::X [m/s]") // "INS::VelBody::Y [m/s]", "INS::VelBody::Z [m/s]"
1061 {
1062 extractValue(obs->insOutputs->insField, vn::protocol::uart::InsGroup::INSGROUP_VELBODY,
1063 obs->insOutputs->velBody.x(), obs->insOutputs->velBody.y(), obs->insOutputs->velBody.z());
1064 continue;
1065 }
1066 if (column == "INS::VelNed::N [m/s]") // "INS::VelNed::E [m/s]", "INS::VelNed::D [m/s]"
1067 {
1068 extractValue(obs->insOutputs->insField, vn::protocol::uart::InsGroup::INSGROUP_VELNED,
1069 obs->insOutputs->velNed.x(), obs->insOutputs->velNed.y(), obs->insOutputs->velNed.z());
1070 continue;
1071 }
1072 if (column == "INS::VelEcef::X [m/s]") // "INS::VelEcef::Y [m/s]", "INS::VelEcef::Z [m/s]"
1073 {
1074 extractValue(obs->insOutputs->insField, vn::protocol::uart::InsGroup::INSGROUP_VELECEF,
1075 obs->insOutputs->velEcef.x(), obs->insOutputs->velEcef.y(), obs->insOutputs->velEcef.z());
1076 continue;
1077 }
1078 if (column == "INS::MagEcef::X [Gauss]") // "INS::MagEcef::Y [Gauss]", "INS::MagEcef::Z [Gauss]"
1079 {
1080 extractValue(obs->insOutputs->insField, vn::protocol::uart::InsGroup::INSGROUP_MAGECEF,
1081 obs->insOutputs->magEcef.x(), obs->insOutputs->magEcef.y(), obs->insOutputs->magEcef.z());
1082 continue;
1083 }
1084 if (column == "INS::AccelEcef::X [m/s^2]") // "INS::AccelEcef::Y [m/s^2]", "INS::AccelEcef::Z [m/s^2]"
1085 {
1086 extractValue(obs->insOutputs->insField, vn::protocol::uart::InsGroup::INSGROUP_ACCELECEF,
1087 obs->insOutputs->accelEcef.x(), obs->insOutputs->accelEcef.y(), obs->insOutputs->accelEcef.z());
1088 continue;
1089 }
1090 if (column == "INS::LinearAccelEcef::X [m/s^2]") // "INS::LinearAccelEcef::Y [m/s^2]", "INS::LinearAccelEcef::Z [m/s^2]"
1091 {
1092 extractValue(obs->insOutputs->insField, vn::protocol::uart::InsGroup::INSGROUP_LINEARACCELECEF,
1093 obs->insOutputs->linearAccelEcef.x(), obs->insOutputs->linearAccelEcef.y(), obs->insOutputs->linearAccelEcef.z());
1094 continue;
1095 }
1096 if (column == "INS::PosU [m]")
1097 {
1098 extractValue(obs->insOutputs->insField, vn::protocol::uart::InsGroup::INSGROUP_POSU, obs->insOutputs->posU);
1099 continue;
1100 }
1101 if (column == "INS::VelU [m/s]")
1102 {
1103 extractValue(obs->insOutputs->insField, vn::protocol::uart::InsGroup::INSGROUP_VELU, obs->insOutputs->velU);
1104 continue;
1105 }
1106 }
1107 // Group 7 (GNSS2)
1108 if (_binaryOutputRegister.gps2Field != vn::protocol::uart::GpsGroup::GPSGROUP_NONE)
1109 {
1110 if (!obs->gnss2Outputs) { obs->gnss2Outputs = std::make_shared<NAV::vendor::vectornav::GnssOutputs>(); }
1111
1112 if (column == "GNSS2::UTC::year") // "GNSS2::UTC::month", "GNSS2::UTC::day", "GNSS2::UTC::hour", "GNSS2::UTC::min", "GNSS2::UTC::sec", "GNSS2::UTC::ms"
1113 {
1114 extractValue(obs->gnss2Outputs->gnssField, vn::protocol::uart::GpsGroup::GPSGROUP_UTC,
1115 obs->gnss2Outputs->timeUtc.year, obs->gnss2Outputs->timeUtc.month, obs->gnss2Outputs->timeUtc.day,
1116 obs->gnss2Outputs->timeUtc.hour, obs->gnss2Outputs->timeUtc.min, obs->gnss2Outputs->timeUtc.sec, obs->gnss2Outputs->timeUtc.ms);
1117 continue;
1118 }
1119 if (column == "GNSS2::Tow [ns]")
1120 {
1121 extractValue(obs->gnss2Outputs->gnssField, vn::protocol::uart::GpsGroup::GPSGROUP_TOW, obs->gnss2Outputs->tow);
1122 continue;
1123 }
1124 if (column == "GNSS2::Week")
1125 {
1126 extractValue(obs->gnss2Outputs->gnssField, vn::protocol::uart::GpsGroup::GPSGROUP_WEEK, obs->gnss2Outputs->week);
1127 continue;
1128 }
1129 if (column == "GNSS2::NumSats")
1130 {
1131 extractValue(obs->gnss2Outputs->gnssField, vn::protocol::uart::GpsGroup::GPSGROUP_NUMSATS, obs->gnss2Outputs->numSats);
1132 continue;
1133 }
1134 if (column == "GNSS2::Fix")
1135 {
1136 extractValue(obs->gnss2Outputs->gnssField, vn::protocol::uart::GpsGroup::GPSGROUP_FIX, obs->gnss2Outputs->fix);
1137 continue;
1138 }
1139 if (column == "GNSS2::PosLla::latitude [deg]") // "GNSS2::PosLla::longitude [deg]", "GNSS2::PosLla::altitude [m]"
1140 {
1141 extractValue(obs->gnss2Outputs->gnssField, vn::protocol::uart::GpsGroup::GPSGROUP_POSLLA,
1142 obs->gnss2Outputs->posLla.x(), obs->gnss2Outputs->posLla.y(), obs->gnss2Outputs->posLla.z());
1143 continue;
1144 }
1145 if (column == "GNSS2::PosEcef::X [m]") // "GNSS2::PosEcef::Y [m]", "GNSS2::PosEcef::Z [m]"
1146 {
1147 extractValue(obs->gnss2Outputs->gnssField, vn::protocol::uart::GpsGroup::GPSGROUP_POSECEF,
1148 obs->gnss2Outputs->posEcef.x(), obs->gnss2Outputs->posEcef.y(), obs->gnss2Outputs->posEcef.z());
1149 continue;
1150 }
1151 if (column == "GNSS2::VelNed::N [m/s]") // "GNSS2::VelNed::E [m/s]", "GNSS2::VelNed::D [m/s]"
1152 {
1153 extractValue(obs->gnss2Outputs->gnssField, vn::protocol::uart::GpsGroup::GPSGROUP_VELNED,
1154 obs->gnss2Outputs->velNed.x(), obs->gnss2Outputs->velNed.y(), obs->gnss2Outputs->velNed.z());
1155 continue;
1156 }
1157 if (column == "GNSS2::VelEcef::X [m/s]") // "GNSS2::VelEcef::Y [m/s]", "GNSS2::VelEcef::Z [m/s]"
1158 {
1159 extractValue(obs->gnss2Outputs->gnssField, vn::protocol::uart::GpsGroup::GPSGROUP_VELECEF,
1160 obs->gnss2Outputs->velEcef.x(), obs->gnss2Outputs->velEcef.y(), obs->gnss2Outputs->velEcef.z());
1161 continue;
1162 }
1163 if (column == "GNSS2::PosU::N [m]") // "GNSS2::PosU::E [m]", "GNSS2::PosU::D [m]"
1164 {
1165 extractValue(obs->gnss2Outputs->gnssField, vn::protocol::uart::GpsGroup::GPSGROUP_POSU,
1166 obs->gnss2Outputs->posU.x(), obs->gnss2Outputs->posU.y(), obs->gnss2Outputs->posU.z());
1167 continue;
1168 }
1169 if (column == "GNSS2::VelU [m/s]")
1170 {
1171 extractValue(obs->gnss2Outputs->gnssField, vn::protocol::uart::GpsGroup::GPSGROUP_VELU, obs->gnss2Outputs->velU);
1172 continue;
1173 }
1174 if (column == "GNSS2::TimeU [s]")
1175 {
1176 extractValue(obs->gnss2Outputs->gnssField, vn::protocol::uart::GpsGroup::GPSGROUP_TIMEU, obs->gnss2Outputs->timeU);
1177 continue;
1178 }
1179 if (column == "GNSS2::TimeInfo::Status::timeOk") // "GNSS2::TimeInfo::Status::dateOk", "GNSS2::TimeInfo::Status::utcTimeValid", "GNSS2::TimeInfo::LeapSeconds"
1180 {
1181 uint8_t timeOk{};
1182 uint8_t dateOk{};
1183 uint8_t utcTimeValid{};
1184 extractValue(obs->gnss2Outputs->gnssField, vn::protocol::uart::GpsGroup::GPSGROUP_TIMEINFO, timeOk, dateOk, utcTimeValid, obs->gnss2Outputs->timeInfo.leapSeconds);
1185 obs->gnss2Outputs->timeInfo.status = static_cast<uint8_t>(timeOk << 0U | dateOk << 1U | utcTimeValid << 2U);
1186 continue;
1187 }
1188 if (column == "GNSS2::DOP::g") // "GNSS2::DOP::p","GNSS2::DOP::t","GNSS2::DOP::v","GNSS2::DOP::h","GNSS2::DOP::n","GNSS2::DOP::e"
1189 {
1190 extractValue(obs->gnss2Outputs->gnssField, vn::protocol::uart::GpsGroup::GPSGROUP_DOP,
1191 obs->gnss2Outputs->dop.gDop, obs->gnss2Outputs->dop.pDop, obs->gnss2Outputs->dop.tDop, obs->gnss2Outputs->dop.vDop,
1192 obs->gnss2Outputs->dop.hDop, obs->gnss2Outputs->dop.nDop, obs->gnss2Outputs->dop.eDop);
1193 continue;
1194 }
1195 if (column == "GNSS2::SatInfo::NumSats")
1196 {
1197 extractValue(obs->gnss2Outputs->gnssField, vn::protocol::uart::GpsGroup::GPSGROUP_SATINFO, obs->gnss2Outputs->satInfo.numSats);
1198 continue;
1199 }
1200 if (column == "GNSS2::SatInfo::Satellites")
1201 {
1202 std::string satellites;
1203 extractValue(obs->gnss2Outputs->gnssField, vn::protocol::uart::GpsGroup::GPSGROUP_SATINFO, satellites);
1204
1205 for (size_t i = 0; i < obs->gnss2Outputs->satInfo.numSats; i++)
1206 {
1207 satellites = satellites.substr(1); // Remove leading '['
1208 auto sys = static_cast<int8_t>(std::stoi(extractRemoveTillDelimiter(satellites, "|")));
1209 auto svId = static_cast<uint8_t>(std::stoul(extractRemoveTillDelimiter(satellites, "|")));
1210 auto flagHealthy = static_cast<uint8_t>(std::stoul(extractRemoveTillDelimiter(satellites, "|")));
1211 auto flagAlmanac = static_cast<uint8_t>(std::stoul(extractRemoveTillDelimiter(satellites, "|")));
1212 auto flagEphemeris = static_cast<uint8_t>(std::stoul(extractRemoveTillDelimiter(satellites, "|")));
1213 auto flagDifferentialCorrection = static_cast<uint8_t>(std::stoul(extractRemoveTillDelimiter(satellites, "|")));
1214 auto flagUsedForNavigation = static_cast<uint8_t>(std::stoul(extractRemoveTillDelimiter(satellites, "|")));
1215 auto flagAzimuthElevationValid = static_cast<uint8_t>(std::stoul(extractRemoveTillDelimiter(satellites, "|")));
1216 auto flagUsedForRTK = static_cast<uint8_t>(std::stoul(extractRemoveTillDelimiter(satellites, "|")));
1217 auto flags = static_cast<uint8_t>(flagHealthy << 0U
1218 | flagAlmanac << 1U
1219 | flagEphemeris << 2U
1220 | flagDifferentialCorrection << 3U
1221 | flagUsedForNavigation << 4U
1222 | flagAzimuthElevationValid << 5U
1223 | flagUsedForRTK << 6U);
1224 auto cno = static_cast<uint8_t>(std::stoul(extractRemoveTillDelimiter(satellites, "|")));
1225 auto qi = static_cast<uint8_t>(std::stoul(extractRemoveTillDelimiter(satellites, "|")));
1226 auto el = static_cast<int8_t>(std::stoi(extractRemoveTillDelimiter(satellites, "|")));
1227 auto az = static_cast<int16_t>(std::stoi(extractRemoveTillDelimiter(satellites, "]")));
1228 obs->gnss2Outputs->satInfo.satellites.emplace_back(sys, svId, flags, cno, qi, el, az);
1229 }
1230 continue;
1231 }
1232 if (column.starts_with("GNSS2::SatInfo::") && column.ends_with(" - flag Healthy"))
1233 {
1234 std::string columnText = column.substr(16);
1235 SatId satId(extractRemoveTillDelimiter(columnText, " -"));
1236 LOG_DATA("{}: SatInfo {}", nameId(), satId);
1237 bool flagHealthy{};
1238 bool flagAlmanac{};
1239 bool flagEphemeris{};
1240 bool flagDifferentialCorrection{};
1241 bool flagUsedForNavigation{};
1242 bool flagAzimuthElevationValid{};
1243 bool flagUsedForRTK{};
1244 auto cno = std::numeric_limits<uint8_t>::max();
1245 uint8_t qi{};
1246 int8_t el{};
1247 int16_t az{};
1248 extractValue(obs->gnss2Outputs->gnssField, vn::protocol::uart::GpsGroup::GPSGROUP_SATINFO,
1249 flagHealthy, flagAlmanac, flagEphemeris, flagDifferentialCorrection,
1250 flagUsedForNavigation, flagAzimuthElevationValid, flagUsedForRTK,
1251 cno, qi, el, az);
1252 if (cno == std::numeric_limits<uint8_t>::max())
1253 {
1254 LOG_DATA("{}: Skipping {} as empty", nameId(), satId);
1255 continue;
1256 }
1257 auto flags = static_cast<uint8_t>(flagHealthy << 0U
1258 | flagAlmanac << 1U
1259 | flagEphemeris << 2U
1260 | flagDifferentialCorrection << 3U
1261 | flagUsedForNavigation << 4U
1262 | flagAzimuthElevationValid << 5U
1263 | flagUsedForRTK << 6U);
1264 obs->gnss2Outputs->satInfo.satellites.emplace_back(static_cast<uint8_t>(vendor::vectornav::fromSatelliteSystem(satId.satSys)),
1265 static_cast<uint8_t>(satId.satNum), flags, cno, qi, el, az);
1266 continue;
1267 }
1268 if (column == "GNSS2::RawMeas::Tow [s]")
1269 {
1270 extractValue(obs->gnss2Outputs->gnssField, vn::protocol::uart::GpsGroup::GPSGROUP_RAWMEAS, obs->gnss2Outputs->raw.tow);
1271 continue;
1272 }
1273 if (column == "GNSS2::RawMeas::Week")
1274 {
1275 extractValue(obs->gnss2Outputs->gnssField, vn::protocol::uart::GpsGroup::GPSGROUP_RAWMEAS, obs->gnss2Outputs->raw.week);
1276 continue;
1277 }
1278 if (column == "GNSS2::RawMeas::NumSats")
1279 {
1280 extractValue(obs->gnss2Outputs->gnssField, vn::protocol::uart::GpsGroup::GPSGROUP_RAWMEAS, obs->gnss2Outputs->raw.numSats);
1281 LOG_DATA("{}: GNSS2::NumSats: {}", nameId(), obs->gnss2Outputs->raw.numSats); // HACK
1282 continue;
1283 }
1284 if (column == "GNSS2::RawMeas::Satellites")
1285 {
1286 std::string satellites;
1287 extractValue(obs->gnss2Outputs->gnssField, vn::protocol::uart::GpsGroup::GPSGROUP_RAWMEAS, satellites);
1288 LOG_DATA("{}: numSats: {}", nameId(), obs->gnss2Outputs->raw.numSats); // HACK
1289 LOG_DATA("{}: satellites: {}", nameId(), satellites); // HACK
1290
1291 for (size_t i = 0; i < obs->gnss2Outputs->raw.numSats; i++)
1292 {
1293 satellites = satellites.substr(1); // Remove leading '['
1294 auto sys = static_cast<uint8_t>(std::stoul(extractRemoveTillDelimiter(satellites, "|")));
1295 auto svId = static_cast<uint8_t>(std::stoul(extractRemoveTillDelimiter(satellites, "|")));
1296 auto freq = static_cast<uint8_t>(std::stoul(extractRemoveTillDelimiter(satellites, "|")));
1297 auto chan = static_cast<uint8_t>(std::stoul(extractRemoveTillDelimiter(satellites, "|")));
1298 auto slot = static_cast<int8_t>(std::stoi(extractRemoveTillDelimiter(satellites, "|")));
1299 auto cno = static_cast<uint8_t>(std::stoul(extractRemoveTillDelimiter(satellites, "|")));
1300 auto flagSearching = static_cast<uint8_t>(std::stoul(extractRemoveTillDelimiter(satellites, "|")));
1301 auto flagTracking = static_cast<uint8_t>(std::stoul(extractRemoveTillDelimiter(satellites, "|")));
1302 auto flagTimeValid = static_cast<uint8_t>(std::stoul(extractRemoveTillDelimiter(satellites, "|")));
1303 auto flagCodeLock = static_cast<uint8_t>(std::stoul(extractRemoveTillDelimiter(satellites, "|")));
1304 auto flagPhaseLock = static_cast<uint8_t>(std::stoul(extractRemoveTillDelimiter(satellites, "|")));
1305 auto flagPhaseHalfAmbiguity = static_cast<uint8_t>(std::stoul(extractRemoveTillDelimiter(satellites, "|")));
1306 auto flagPhaseHalfSub = static_cast<uint8_t>(std::stoul(extractRemoveTillDelimiter(satellites, "|")));
1307 auto flagPhaseSlip = static_cast<uint8_t>(std::stoul(extractRemoveTillDelimiter(satellites, "|")));
1308 auto flagPseudorangeSmoothed = static_cast<uint8_t>(std::stoul(extractRemoveTillDelimiter(satellites, "|")));
1309 auto flags = static_cast<uint16_t>(flagSearching << 0U
1310 | flagTracking << 1U
1311 | flagTimeValid << 2U
1312 | flagCodeLock << 3U
1313 | flagPhaseLock << 4U
1314 | flagPhaseHalfAmbiguity << 5U
1315 | flagPhaseHalfSub << 6U
1316 | flagPhaseSlip << 7U
1317 | flagPseudorangeSmoothed << 8U);
1318 auto pr = std::stod(extractRemoveTillDelimiter(satellites, "|"));
1319 auto cp = std::stod(extractRemoveTillDelimiter(satellites, "|"));
1320 auto dp = std::stof(extractRemoveTillDelimiter(satellites, "]"));
1321 obs->gnss2Outputs->raw.satellites.emplace_back(sys, svId, freq, chan, slot, cno, flags, pr, cp, dp);
1322 }
1323 continue;
1324 }
1325 if (column.starts_with("GNSS2::RawMeas::") && column.ends_with(" - freq"))
1326 {
1327 std::string columnText = column.substr(16);
1328 auto identifier = extractRemoveTillDelimiter(columnText, " - freq");
1329 LOG_DATA("{}: RawMeas {}", nameId(), identifier);
1330 SatelliteSystem satSys;
1331 uint16_t satNum{};
1332 if (identifier.length() == 6)
1333 {
1334 SatSigId satSigId(identifier);
1335 satSys = satSigId.toSatId().satSys;
1336 satNum = satSigId.satNum;
1337 }
1338 else
1339 {
1340 SatId satId(identifier);
1341 satSys = satId.satSys;
1342 satNum = satId.satNum;
1343 }
1344 auto freq = std::numeric_limits<uint8_t>::max();
1345 uint8_t chan{};
1346 int8_t slot{};
1347 uint8_t cno{};
1348 uint8_t flagSearching{};
1349 uint8_t flagTracking{};
1350 uint8_t flagTimeValid{};
1351 uint8_t flagCodeLock{};
1352 uint8_t flagPhaseLock{};
1353 uint8_t flagPhaseHalfAmbiguity{};
1354 uint8_t flagPhaseHalfSub{};
1355 uint8_t flagPhaseSlip{};
1356 uint8_t flagPseudorangeSmoothed{};
1357 double pr{};
1358 double cp{};
1359 float dp{};
1360 extractValue(obs->gnss2Outputs->gnssField, vn::protocol::uart::GpsGroup::GPSGROUP_RAWMEAS,
1361 freq, chan, slot, cno,
1362 flagSearching, flagTracking, flagTimeValid, flagCodeLock, flagPhaseLock,
1363 flagPhaseHalfAmbiguity, flagPhaseHalfSub, flagPhaseSlip, flagPseudorangeSmoothed,
1364 pr, cp, dp);
1365 if (freq == std::numeric_limits<uint8_t>::max())
1366 {
1367 LOG_DATA("{}: Skipping {} as empty", nameId(), identifier);
1368 continue;
1369 }
1370 auto flags = static_cast<uint16_t>(flagSearching << 0U
1371 | flagTracking << 1U
1372 | flagTimeValid << 2U
1373 | flagCodeLock << 3U
1374 | flagPhaseLock << 4U
1375 | flagPhaseHalfAmbiguity << 5U
1376 | flagPhaseHalfSub << 6U
1377 | flagPhaseSlip << 7U
1378 | flagPseudorangeSmoothed << 8U);
1379 obs->gnss2Outputs->raw.satellites.emplace_back(static_cast<uint8_t>(vendor::vectornav::fromSatelliteSystem(satSys)),
1380 static_cast<uint8_t>(satNum), freq, chan, slot, cno, flags, pr, cp, dp);
1381 if (obs->gnss2Outputs->raw.satellites.back().toCode() == Code::None)
1382 {
1383 LOG_ERROR("{}: Line {}: Could not convert to valid Code. Skipping item. (sys {}, freq {}, chan {})", nameId(), _messageCount + 1,
1384 obs->gnss2Outputs->raw.satellites.back().sys, obs->gnss2Outputs->raw.satellites.back().freq, obs->gnss2Outputs->raw.satellites.back().chan);
1385 obs->gnss2Outputs->raw.satellites.pop_back();
1386 }
1387 if (identifier.length() == 6 && SatSigId(identifier) != obs->gnss2Outputs->raw.satellites.back().toSatSigId())
1388 {
1389 LOG_ERROR("{}: Line {}: Could not convert to valid SatSigId. Skipping item. (sys {}, freq {}, chan {} = [{}], column was [{}])", nameId(), _messageCount + 1,
1390 obs->gnss2Outputs->raw.satellites.back().sys, obs->gnss2Outputs->raw.satellites.back().freq, obs->gnss2Outputs->raw.satellites.back().chan,
1391 obs->gnss2Outputs->raw.satellites.back().toSatSigId(), identifier);
1392 obs->gnss2Outputs->raw.satellites.pop_back();
1393 }
1394 continue;
1395 }
1396 }
1397
1398 extractCell();
1399 }
1400 if (obs->gnss1Outputs) { obs->gnss1Outputs->raw.numSats = static_cast<uint8_t>(obs->gnss1Outputs->raw.satellites.size()); }
1401 if (obs->gnss2Outputs) { obs->gnss2Outputs->raw.numSats = static_cast<uint8_t>(obs->gnss2Outputs->raw.satellites.size()); }
1402 }
1403 catch (const std::exception& e)
1404 {
1405 LOG_ERROR("{}: Could not read line {} completely: {}", nameId(), _messageCount + 1, e.what());
1406 return nullptr;
1407 }
1408 }
1409 else // if (fileType == FileType::BINARY)
1410 {
1411 auto readFromFilestream = [&, this](char* __s, std::streamsize __n) {
1412 read(__s, __n);
1413 if (!good())
1414 {
1415 throw std::runtime_error("End of file reached");
1416 }
1417 };
1418
1419 try
1420 {
1421 _messageCount++;
1422 LOG_DATA("{}: Reading message {}", nameId(), _messageCount);
1423 int32_t gpsCycle = 0;
1424 int32_t gpsWeek = 0;
1425 double tow = 0.0;
1426 readFromFilestream(reinterpret_cast<char*>(&gpsCycle), sizeof(gpsCycle));
1427 readFromFilestream(reinterpret_cast<char*>(&gpsWeek), sizeof(gpsWeek));
1428 readFromFilestream(reinterpret_cast<char*>(&tow), sizeof(tow));
1429 if (gpsCycle || gpsWeek)
1430 {
1431 obs->insTime = InsTime(gpsCycle, gpsWeek, tow);
1432 }
1433
1434 // Group 2 (Time)
1435 if (_binaryOutputRegister.timeField != vn::protocol::uart::TimeGroup::TIMEGROUP_NONE)
1436 {
1437 if (!obs->timeOutputs)
1438 {
1439 obs->timeOutputs = std::make_shared<NAV::vendor::vectornav::TimeOutputs>();
1440 obs->timeOutputs->timeField |= _binaryOutputRegister.timeField;
1441 }
1442
1443 if (obs->timeOutputs->timeField & vn::protocol::uart::TimeGroup::TIMEGROUP_TIMESTARTUP)
1444 {
1445 read(reinterpret_cast<char*>(&obs->timeOutputs->timeStartup), sizeof(obs->timeOutputs->timeStartup));
1446 }
1447 if (obs->timeOutputs->timeField & vn::protocol::uart::TimeGroup::TIMEGROUP_TIMEGPS)
1448 {
1449 read(reinterpret_cast<char*>(&obs->timeOutputs->timeGps), sizeof(obs->timeOutputs->timeGps));
1450 }
1451 if (obs->timeOutputs->timeField & vn::protocol::uart::TimeGroup::TIMEGROUP_GPSTOW)
1452 {
1453 read(reinterpret_cast<char*>(&obs->timeOutputs->gpsTow), sizeof(obs->timeOutputs->gpsTow));
1454 }
1455 if (obs->timeOutputs->timeField & vn::protocol::uart::TimeGroup::TIMEGROUP_GPSWEEK)
1456 {
1457 read(reinterpret_cast<char*>(&obs->timeOutputs->gpsWeek), sizeof(obs->timeOutputs->gpsWeek));
1458 }
1459 if (obs->timeOutputs->timeField & vn::protocol::uart::TimeGroup::TIMEGROUP_TIMESYNCIN)
1460 {
1461 read(reinterpret_cast<char*>(&obs->timeOutputs->timeSyncIn), sizeof(obs->timeOutputs->timeSyncIn));
1462 }
1463 if (obs->timeOutputs->timeField & vn::protocol::uart::TimeGroup::TIMEGROUP_TIMEGPSPPS)
1464 {
1465 read(reinterpret_cast<char*>(&obs->timeOutputs->timePPS), sizeof(obs->timeOutputs->timePPS));
1466 }
1467 if (obs->timeOutputs->timeField & vn::protocol::uart::TimeGroup::TIMEGROUP_TIMEUTC)
1468 {
1469 read(reinterpret_cast<char*>(&obs->timeOutputs->timeUtc.year), sizeof(obs->timeOutputs->timeUtc.year));
1470 read(reinterpret_cast<char*>(&obs->timeOutputs->timeUtc.month), sizeof(obs->timeOutputs->timeUtc.month));
1471 read(reinterpret_cast<char*>(&obs->timeOutputs->timeUtc.day), sizeof(obs->timeOutputs->timeUtc.day));
1472 read(reinterpret_cast<char*>(&obs->timeOutputs->timeUtc.hour), sizeof(obs->timeOutputs->timeUtc.hour));
1473 read(reinterpret_cast<char*>(&obs->timeOutputs->timeUtc.min), sizeof(obs->timeOutputs->timeUtc.min));
1474 read(reinterpret_cast<char*>(&obs->timeOutputs->timeUtc.sec), sizeof(obs->timeOutputs->timeUtc.sec));
1475 read(reinterpret_cast<char*>(&obs->timeOutputs->timeUtc.ms), sizeof(obs->timeOutputs->timeUtc.ms));
1476 }
1477 if (obs->timeOutputs->timeField & vn::protocol::uart::TimeGroup::TIMEGROUP_SYNCINCNT)
1478 {
1479 read(reinterpret_cast<char*>(&obs->timeOutputs->syncInCnt), sizeof(obs->timeOutputs->syncInCnt));
1480 }
1481 if (obs->timeOutputs->timeField & vn::protocol::uart::TimeGroup::TIMEGROUP_SYNCOUTCNT)
1482 {
1483 read(reinterpret_cast<char*>(&obs->timeOutputs->syncOutCnt), sizeof(obs->timeOutputs->syncOutCnt));
1484 }
1485 if (obs->timeOutputs->timeField & vn::protocol::uart::TimeGroup::TIMEGROUP_TIMESTATUS)
1486 {
1487 read(reinterpret_cast<char*>(&obs->timeOutputs->timeStatus.status()), sizeof(obs->timeOutputs->timeStatus.status()));
1488 }
1489 }
1490 // Group 3 (IMU)
1491 if (_binaryOutputRegister.imuField != vn::protocol::uart::ImuGroup::IMUGROUP_NONE)
1492 {
1493 if (!obs->imuOutputs)
1494 {
1495 obs->imuOutputs = std::make_shared<NAV::vendor::vectornav::ImuOutputs>();
1496 obs->imuOutputs->imuField |= _binaryOutputRegister.imuField;
1497 }
1498
1499 if (obs->imuOutputs->imuField & vn::protocol::uart::ImuGroup::IMUGROUP_IMUSTATUS)
1500 {
1501 read(reinterpret_cast<char*>(&obs->imuOutputs->imuStatus), sizeof(obs->imuOutputs->imuStatus));
1502 }
1503 if (obs->imuOutputs->imuField & vn::protocol::uart::ImuGroup::IMUGROUP_UNCOMPMAG)
1504 {
1505 read(reinterpret_cast<char*>(obs->imuOutputs->uncompMag.data()), sizeof(obs->imuOutputs->uncompMag));
1506 }
1507 if (obs->imuOutputs->imuField & vn::protocol::uart::ImuGroup::IMUGROUP_UNCOMPACCEL)
1508 {
1509 read(reinterpret_cast<char*>(obs->imuOutputs->uncompAccel.data()), sizeof(obs->imuOutputs->uncompAccel));
1510 }
1511 if (obs->imuOutputs->imuField & vn::protocol::uart::ImuGroup::IMUGROUP_UNCOMPGYRO)
1512 {
1513 read(reinterpret_cast<char*>(obs->imuOutputs->uncompGyro.data()), sizeof(obs->imuOutputs->uncompGyro));
1514 }
1515 if (obs->imuOutputs->imuField & vn::protocol::uart::ImuGroup::IMUGROUP_TEMP)
1516 {
1517 read(reinterpret_cast<char*>(&obs->imuOutputs->temp), sizeof(obs->imuOutputs->temp));
1518 }
1519 if (obs->imuOutputs->imuField & vn::protocol::uart::ImuGroup::IMUGROUP_PRES)
1520 {
1521 read(reinterpret_cast<char*>(&obs->imuOutputs->pres), sizeof(obs->imuOutputs->pres));
1522 }
1523 if (obs->imuOutputs->imuField & vn::protocol::uart::ImuGroup::IMUGROUP_DELTATHETA)
1524 {
1525 read(reinterpret_cast<char*>(&obs->imuOutputs->deltaTime), sizeof(obs->imuOutputs->deltaTime));
1526 read(reinterpret_cast<char*>(obs->imuOutputs->deltaTheta.data()), sizeof(obs->imuOutputs->deltaTheta));
1527 }
1528 if (obs->imuOutputs->imuField & vn::protocol::uart::ImuGroup::IMUGROUP_DELTAVEL)
1529 {
1530 read(reinterpret_cast<char*>(obs->imuOutputs->deltaV.data()), sizeof(obs->imuOutputs->deltaV));
1531 }
1532 if (obs->imuOutputs->imuField & vn::protocol::uart::ImuGroup::IMUGROUP_MAG)
1533 {
1534 read(reinterpret_cast<char*>(obs->imuOutputs->mag.data()), sizeof(obs->imuOutputs->mag));
1535 }
1536 if (obs->imuOutputs->imuField & vn::protocol::uart::ImuGroup::IMUGROUP_ACCEL)
1537 {
1538 read(reinterpret_cast<char*>(obs->imuOutputs->accel.data()), sizeof(obs->imuOutputs->accel));
1539 }
1540 if (obs->imuOutputs->imuField & vn::protocol::uart::ImuGroup::IMUGROUP_ANGULARRATE)
1541 {
1542 read(reinterpret_cast<char*>(obs->imuOutputs->angularRate.data()), sizeof(obs->imuOutputs->angularRate));
1543 }
1544 }
1545 // Group 4 (GNSS1)
1546 if (_binaryOutputRegister.gpsField != vn::protocol::uart::GpsGroup::GPSGROUP_NONE)
1547 {
1548 if (!obs->gnss1Outputs)
1549 {
1550 obs->gnss1Outputs = std::make_shared<NAV::vendor::vectornav::GnssOutputs>();
1551 obs->gnss1Outputs->gnssField |= _binaryOutputRegister.gpsField;
1552 }
1553
1554 if (obs->gnss1Outputs->gnssField & vn::protocol::uart::GpsGroup::GPSGROUP_UTC)
1555 {
1556 read(reinterpret_cast<char*>(&obs->gnss1Outputs->timeUtc.year), sizeof(obs->gnss1Outputs->timeUtc.year));
1557 read(reinterpret_cast<char*>(&obs->gnss1Outputs->timeUtc.month), sizeof(obs->gnss1Outputs->timeUtc.month));
1558 read(reinterpret_cast<char*>(&obs->gnss1Outputs->timeUtc.day), sizeof(obs->gnss1Outputs->timeUtc.day));
1559 read(reinterpret_cast<char*>(&obs->gnss1Outputs->timeUtc.hour), sizeof(obs->gnss1Outputs->timeUtc.hour));
1560 read(reinterpret_cast<char*>(&obs->gnss1Outputs->timeUtc.min), sizeof(obs->gnss1Outputs->timeUtc.min));
1561 read(reinterpret_cast<char*>(&obs->gnss1Outputs->timeUtc.sec), sizeof(obs->gnss1Outputs->timeUtc.sec));
1562 read(reinterpret_cast<char*>(&obs->gnss1Outputs->timeUtc.ms), sizeof(obs->gnss1Outputs->timeUtc.ms));
1563 }
1564 if (obs->gnss1Outputs->gnssField & vn::protocol::uart::GpsGroup::GPSGROUP_TOW)
1565 {
1566 read(reinterpret_cast<char*>(&obs->gnss1Outputs->tow), sizeof(obs->gnss1Outputs->tow));
1567 }
1568 if (obs->gnss1Outputs->gnssField & vn::protocol::uart::GpsGroup::GPSGROUP_WEEK)
1569 {
1570 read(reinterpret_cast<char*>(&obs->gnss1Outputs->week), sizeof(obs->gnss1Outputs->week));
1571 }
1572 if (obs->gnss1Outputs->gnssField & vn::protocol::uart::GpsGroup::GPSGROUP_NUMSATS)
1573 {
1574 read(reinterpret_cast<char*>(&obs->gnss1Outputs->numSats), sizeof(obs->gnss1Outputs->numSats));
1575 }
1576 if (obs->gnss1Outputs->gnssField & vn::protocol::uart::GpsGroup::GPSGROUP_FIX)
1577 {
1578 read(reinterpret_cast<char*>(&obs->gnss1Outputs->fix), sizeof(obs->gnss1Outputs->fix));
1579 }
1580 if (obs->gnss1Outputs->gnssField & vn::protocol::uart::GpsGroup::GPSGROUP_POSLLA)
1581 {
1582 read(reinterpret_cast<char*>(obs->gnss1Outputs->posLla.data()), sizeof(obs->gnss1Outputs->posLla));
1583 }
1584 if (obs->gnss1Outputs->gnssField & vn::protocol::uart::GpsGroup::GPSGROUP_POSECEF)
1585 {
1586 read(reinterpret_cast<char*>(obs->gnss1Outputs->posEcef.data()), sizeof(obs->gnss1Outputs->posEcef));
1587 }
1588 if (obs->gnss1Outputs->gnssField & vn::protocol::uart::GpsGroup::GPSGROUP_VELNED)
1589 {
1590 read(reinterpret_cast<char*>(obs->gnss1Outputs->velNed.data()), sizeof(obs->gnss1Outputs->velNed));
1591 }
1592 if (obs->gnss1Outputs->gnssField & vn::protocol::uart::GpsGroup::GPSGROUP_VELECEF)
1593 {
1594 read(reinterpret_cast<char*>(obs->gnss1Outputs->velEcef.data()), sizeof(obs->gnss1Outputs->velEcef));
1595 }
1596 if (obs->gnss1Outputs->gnssField & vn::protocol::uart::GpsGroup::GPSGROUP_POSU)
1597 {
1598 read(reinterpret_cast<char*>(obs->gnss1Outputs->posU.data()), sizeof(obs->gnss1Outputs->posU));
1599 }
1600 if (obs->gnss1Outputs->gnssField & vn::protocol::uart::GpsGroup::GPSGROUP_VELU)
1601 {
1602 read(reinterpret_cast<char*>(&obs->gnss1Outputs->velU), sizeof(obs->gnss1Outputs->velU));
1603 }
1604 if (obs->gnss1Outputs->gnssField & vn::protocol::uart::GpsGroup::GPSGROUP_TIMEU)
1605 {
1606 read(reinterpret_cast<char*>(&obs->gnss1Outputs->timeU), sizeof(obs->gnss1Outputs->timeU));
1607 }
1608 if (obs->gnss1Outputs->gnssField & vn::protocol::uart::GpsGroup::GPSGROUP_TIMEINFO)
1609 {
1610 read(reinterpret_cast<char*>(&obs->gnss1Outputs->timeInfo.status.status()), sizeof(obs->gnss1Outputs->timeInfo.status.status()));
1611 read(reinterpret_cast<char*>(&obs->gnss1Outputs->timeInfo.leapSeconds), sizeof(obs->gnss1Outputs->timeInfo.leapSeconds));
1612 }
1613 if (obs->gnss1Outputs->gnssField & vn::protocol::uart::GpsGroup::GPSGROUP_DOP)
1614 {
1615 read(reinterpret_cast<char*>(&obs->gnss1Outputs->dop.gDop), sizeof(obs->gnss1Outputs->dop.gDop));
1616 read(reinterpret_cast<char*>(&obs->gnss1Outputs->dop.pDop), sizeof(obs->gnss1Outputs->dop.pDop));
1617 read(reinterpret_cast<char*>(&obs->gnss1Outputs->dop.tDop), sizeof(obs->gnss1Outputs->dop.tDop));
1618 read(reinterpret_cast<char*>(&obs->gnss1Outputs->dop.vDop), sizeof(obs->gnss1Outputs->dop.vDop));
1619 read(reinterpret_cast<char*>(&obs->gnss1Outputs->dop.hDop), sizeof(obs->gnss1Outputs->dop.hDop));
1620 read(reinterpret_cast<char*>(&obs->gnss1Outputs->dop.nDop), sizeof(obs->gnss1Outputs->dop.nDop));
1621 read(reinterpret_cast<char*>(&obs->gnss1Outputs->dop.eDop), sizeof(obs->gnss1Outputs->dop.eDop));
1622 }
1623 if (obs->gnss1Outputs->gnssField & vn::protocol::uart::GpsGroup::GPSGROUP_SATINFO)
1624 {
1625 read(reinterpret_cast<char*>(&obs->gnss1Outputs->satInfo.numSats), sizeof(obs->gnss1Outputs->satInfo.numSats));
1626 obs->gnss1Outputs->satInfo.satellites.resize(obs->gnss1Outputs->satInfo.numSats);
1627
1628 for (auto& satellite : obs->gnss1Outputs->satInfo.satellites)
1629 {
1630 read(reinterpret_cast<char*>(&satellite.sys), sizeof(satellite.sys));
1631 read(reinterpret_cast<char*>(&satellite.svId), sizeof(satellite.svId));
1632 read(reinterpret_cast<char*>(&satellite.flags), sizeof(satellite.flags));
1633 read(reinterpret_cast<char*>(&satellite.cno), sizeof(satellite.cno));
1634 read(reinterpret_cast<char*>(&satellite.qi), sizeof(satellite.qi));
1635 read(reinterpret_cast<char*>(&satellite.el), sizeof(satellite.el));
1636 read(reinterpret_cast<char*>(&satellite.az), sizeof(satellite.az));
1637 }
1638 }
1639 if (obs->gnss1Outputs->gnssField & vn::protocol::uart::GpsGroup::GPSGROUP_RAWMEAS)
1640 {
1641 read(reinterpret_cast<char*>(&obs->gnss1Outputs->raw.tow), sizeof(obs->gnss1Outputs->raw.tow));
1642 read(reinterpret_cast<char*>(&obs->gnss1Outputs->raw.week), sizeof(obs->gnss1Outputs->raw.week));
1643 read(reinterpret_cast<char*>(&obs->gnss1Outputs->raw.numSats), sizeof(obs->gnss1Outputs->raw.numSats));
1644 obs->gnss1Outputs->raw.satellites.resize(obs->gnss1Outputs->raw.numSats);
1645
1646 for (auto& satellite : obs->gnss1Outputs->raw.satellites)
1647 {
1648 read(reinterpret_cast<char*>(&satellite.sys), sizeof(satellite.sys));
1649 read(reinterpret_cast<char*>(&satellite.svId), sizeof(satellite.svId));
1650 read(reinterpret_cast<char*>(&satellite.freq), sizeof(satellite.freq));
1651 read(reinterpret_cast<char*>(&satellite.chan), sizeof(satellite.chan));
1652 read(reinterpret_cast<char*>(&satellite.slot), sizeof(satellite.slot));
1653 read(reinterpret_cast<char*>(&satellite.cno), sizeof(satellite.cno));
1654 read(reinterpret_cast<char*>(&satellite.flags), sizeof(satellite.flags));
1655 read(reinterpret_cast<char*>(&satellite.pr), sizeof(satellite.pr));
1656 read(reinterpret_cast<char*>(&satellite.cp), sizeof(satellite.cp));
1657 read(reinterpret_cast<char*>(&satellite.dp), sizeof(satellite.dp));
1658 }
1659 }
1660 }
1661 // Group 5 (Attitude)
1662 if (_binaryOutputRegister.attitudeField != vn::protocol::uart::AttitudeGroup::ATTITUDEGROUP_NONE)
1663 {
1664 if (!obs->attitudeOutputs)
1665 {
1666 obs->attitudeOutputs = std::make_shared<NAV::vendor::vectornav::AttitudeOutputs>();
1667 obs->attitudeOutputs->attitudeField |= _binaryOutputRegister.attitudeField;
1668 }
1669
1670 if (obs->attitudeOutputs->attitudeField & vn::protocol::uart::AttitudeGroup::ATTITUDEGROUP_VPESTATUS)
1671 {
1672 read(reinterpret_cast<char*>(&obs->attitudeOutputs->vpeStatus.status()), sizeof(obs->attitudeOutputs->vpeStatus.status()));
1673 }
1674 if (obs->attitudeOutputs->attitudeField & vn::protocol::uart::AttitudeGroup::ATTITUDEGROUP_YAWPITCHROLL)
1675 {
1676 read(reinterpret_cast<char*>(obs->attitudeOutputs->ypr.data()), sizeof(obs->attitudeOutputs->ypr));
1677 }
1678 if (obs->attitudeOutputs->attitudeField & vn::protocol::uart::AttitudeGroup::ATTITUDEGROUP_QUATERNION)
1679 {
1680 read(reinterpret_cast<char*>(obs->attitudeOutputs->qtn.coeffs().data()), sizeof(obs->attitudeOutputs->qtn));
1681 }
1682 if (obs->attitudeOutputs->attitudeField & vn::protocol::uart::AttitudeGroup::ATTITUDEGROUP_DCM)
1683 {
1684 read(reinterpret_cast<char*>(obs->attitudeOutputs->dcm.data()), sizeof(obs->attitudeOutputs->dcm));
1685 }
1686 if (obs->attitudeOutputs->attitudeField & vn::protocol::uart::AttitudeGroup::ATTITUDEGROUP_MAGNED)
1687 {
1688 read(reinterpret_cast<char*>(obs->attitudeOutputs->magNed.data()), sizeof(obs->attitudeOutputs->magNed));
1689 }
1690 if (obs->attitudeOutputs->attitudeField & vn::protocol::uart::AttitudeGroup::ATTITUDEGROUP_ACCELNED)
1691 {
1692 read(reinterpret_cast<char*>(obs->attitudeOutputs->accelNed.data()), sizeof(obs->attitudeOutputs->accelNed));
1693 }
1694 if (obs->attitudeOutputs->attitudeField & vn::protocol::uart::AttitudeGroup::ATTITUDEGROUP_LINEARACCELBODY)
1695 {
1696 read(reinterpret_cast<char*>(obs->attitudeOutputs->linearAccelBody.data()), sizeof(obs->attitudeOutputs->linearAccelBody));
1697 }
1698 if (obs->attitudeOutputs->attitudeField & vn::protocol::uart::AttitudeGroup::ATTITUDEGROUP_LINEARACCELNED)
1699 {
1700 read(reinterpret_cast<char*>(obs->attitudeOutputs->linearAccelNed.data()), sizeof(obs->attitudeOutputs->linearAccelNed));
1701 }
1702 if (obs->attitudeOutputs->attitudeField & vn::protocol::uart::AttitudeGroup::ATTITUDEGROUP_YPRU)
1703 {
1704 read(reinterpret_cast<char*>(obs->attitudeOutputs->yprU.data()), sizeof(obs->attitudeOutputs->yprU));
1705 }
1706 }
1707 // Group 6 (INS)
1708 if (_binaryOutputRegister.insField != vn::protocol::uart::InsGroup::INSGROUP_NONE)
1709 {
1710 if (!obs->insOutputs)
1711 {
1712 obs->insOutputs = std::make_shared<NAV::vendor::vectornav::InsOutputs>();
1713 obs->insOutputs->insField |= _binaryOutputRegister.insField;
1714 }
1715
1716 if (obs->insOutputs->insField & vn::protocol::uart::InsGroup::INSGROUP_INSSTATUS)
1717 {
1718 read(reinterpret_cast<char*>(&obs->insOutputs->insStatus.status()), sizeof(obs->insOutputs->insStatus.status()));
1719 }
1720 if (obs->insOutputs->insField & vn::protocol::uart::InsGroup::INSGROUP_POSLLA)
1721 {
1722 read(reinterpret_cast<char*>(obs->insOutputs->posLla.data()), sizeof(obs->insOutputs->posLla));
1723 }
1724 if (obs->insOutputs->insField & vn::protocol::uart::InsGroup::INSGROUP_POSECEF)
1725 {
1726 read(reinterpret_cast<char*>(obs->insOutputs->posEcef.data()), sizeof(obs->insOutputs->posEcef));
1727 }
1728 if (obs->insOutputs->insField & vn::protocol::uart::InsGroup::INSGROUP_VELBODY)
1729 {
1730 read(reinterpret_cast<char*>(obs->insOutputs->velBody.data()), sizeof(obs->insOutputs->velBody));
1731 }
1732 if (obs->insOutputs->insField & vn::protocol::uart::InsGroup::INSGROUP_VELNED)
1733 {
1734 read(reinterpret_cast<char*>(obs->insOutputs->velNed.data()), sizeof(obs->insOutputs->velNed));
1735 }
1736 if (obs->insOutputs->insField & vn::protocol::uart::InsGroup::INSGROUP_VELECEF)
1737 {
1738 read(reinterpret_cast<char*>(obs->insOutputs->velEcef.data()), sizeof(obs->insOutputs->velEcef));
1739 }
1740 if (obs->insOutputs->insField & vn::protocol::uart::InsGroup::INSGROUP_MAGECEF)
1741 {
1742 read(reinterpret_cast<char*>(obs->insOutputs->magEcef.data()), sizeof(obs->insOutputs->magEcef));
1743 }
1744 if (obs->insOutputs->insField & vn::protocol::uart::InsGroup::INSGROUP_ACCELECEF)
1745 {
1746 read(reinterpret_cast<char*>(obs->insOutputs->accelEcef.data()), sizeof(obs->insOutputs->accelEcef));
1747 }
1748 if (obs->insOutputs->insField & vn::protocol::uart::InsGroup::INSGROUP_LINEARACCELECEF)
1749 {
1750 read(reinterpret_cast<char*>(obs->insOutputs->linearAccelEcef.data()), sizeof(obs->insOutputs->linearAccelEcef));
1751 }
1752 if (obs->insOutputs->insField & vn::protocol::uart::InsGroup::INSGROUP_POSU)
1753 {
1754 read(reinterpret_cast<char*>(&obs->insOutputs->posU), sizeof(obs->insOutputs->posU));
1755 }
1756 if (obs->insOutputs->insField & vn::protocol::uart::InsGroup::INSGROUP_VELU)
1757 {
1758 read(reinterpret_cast<char*>(&obs->insOutputs->velU), sizeof(obs->insOutputs->velU));
1759 }
1760 }
1761 // Group 7 (GNSS2)
1762 if (_binaryOutputRegister.gps2Field != vn::protocol::uart::GpsGroup::GPSGROUP_NONE)
1763 {
1764 if (!obs->gnss2Outputs)
1765 {
1766 obs->gnss2Outputs = std::make_shared<NAV::vendor::vectornav::GnssOutputs>();
1767 obs->gnss2Outputs->gnssField |= _binaryOutputRegister.gps2Field;
1768 }
1769
1770 if (obs->gnss2Outputs->gnssField & vn::protocol::uart::GpsGroup::GPSGROUP_UTC)
1771 {
1772 read(reinterpret_cast<char*>(&obs->gnss2Outputs->timeUtc.year), sizeof(obs->gnss2Outputs->timeUtc.year));
1773 read(reinterpret_cast<char*>(&obs->gnss2Outputs->timeUtc.month), sizeof(obs->gnss2Outputs->timeUtc.month));
1774 read(reinterpret_cast<char*>(&obs->gnss2Outputs->timeUtc.day), sizeof(obs->gnss2Outputs->timeUtc.day));
1775 read(reinterpret_cast<char*>(&obs->gnss2Outputs->timeUtc.hour), sizeof(obs->gnss2Outputs->timeUtc.hour));
1776 read(reinterpret_cast<char*>(&obs->gnss2Outputs->timeUtc.min), sizeof(obs->gnss2Outputs->timeUtc.min));
1777 read(reinterpret_cast<char*>(&obs->gnss2Outputs->timeUtc.sec), sizeof(obs->gnss2Outputs->timeUtc.sec));
1778 read(reinterpret_cast<char*>(&obs->gnss2Outputs->timeUtc.ms), sizeof(obs->gnss2Outputs->timeUtc.ms));
1779 }
1780 if (obs->gnss2Outputs->gnssField & vn::protocol::uart::GpsGroup::GPSGROUP_TOW)
1781 {
1782 read(reinterpret_cast<char*>(&obs->gnss2Outputs->tow), sizeof(obs->gnss2Outputs->tow));
1783 }
1784 if (obs->gnss2Outputs->gnssField & vn::protocol::uart::GpsGroup::GPSGROUP_WEEK)
1785 {
1786 read(reinterpret_cast<char*>(&obs->gnss2Outputs->week), sizeof(obs->gnss2Outputs->week));
1787 }
1788 if (obs->gnss2Outputs->gnssField & vn::protocol::uart::GpsGroup::GPSGROUP_NUMSATS)
1789 {
1790 read(reinterpret_cast<char*>(&obs->gnss2Outputs->numSats), sizeof(obs->gnss2Outputs->numSats));
1791 }
1792 if (obs->gnss2Outputs->gnssField & vn::protocol::uart::GpsGroup::GPSGROUP_FIX)
1793 {
1794 read(reinterpret_cast<char*>(&obs->gnss2Outputs->fix), sizeof(obs->gnss2Outputs->fix));
1795 }
1796 if (obs->gnss2Outputs->gnssField & vn::protocol::uart::GpsGroup::GPSGROUP_POSLLA)
1797 {
1798 read(reinterpret_cast<char*>(obs->gnss2Outputs->posLla.data()), sizeof(obs->gnss2Outputs->posLla));
1799 }
1800 if (obs->gnss2Outputs->gnssField & vn::protocol::uart::GpsGroup::GPSGROUP_POSECEF)
1801 {
1802 read(reinterpret_cast<char*>(obs->gnss2Outputs->posEcef.data()), sizeof(obs->gnss2Outputs->posEcef));
1803 }
1804 if (obs->gnss2Outputs->gnssField & vn::protocol::uart::GpsGroup::GPSGROUP_VELNED)
1805 {
1806 read(reinterpret_cast<char*>(obs->gnss2Outputs->velNed.data()), sizeof(obs->gnss2Outputs->velNed));
1807 }
1808 if (obs->gnss2Outputs->gnssField & vn::protocol::uart::GpsGroup::GPSGROUP_VELECEF)
1809 {
1810 read(reinterpret_cast<char*>(obs->gnss2Outputs->velEcef.data()), sizeof(obs->gnss2Outputs->velEcef));
1811 }
1812 if (obs->gnss2Outputs->gnssField & vn::protocol::uart::GpsGroup::GPSGROUP_POSU)
1813 {
1814 read(reinterpret_cast<char*>(obs->gnss2Outputs->posU.data()), sizeof(obs->gnss2Outputs->posU));
1815 }
1816 if (obs->gnss2Outputs->gnssField & vn::protocol::uart::GpsGroup::GPSGROUP_VELU)
1817 {
1818 read(reinterpret_cast<char*>(&obs->gnss2Outputs->velU), sizeof(obs->gnss2Outputs->velU));
1819 }
1820 if (obs->gnss2Outputs->gnssField & vn::protocol::uart::GpsGroup::GPSGROUP_TIMEU)
1821 {
1822 read(reinterpret_cast<char*>(&obs->gnss2Outputs->timeU), sizeof(obs->gnss2Outputs->timeU));
1823 }
1824 if (obs->gnss2Outputs->gnssField & vn::protocol::uart::GpsGroup::GPSGROUP_TIMEINFO)
1825 {
1826 read(reinterpret_cast<char*>(&obs->gnss2Outputs->timeInfo.status.status()), sizeof(obs->gnss2Outputs->timeInfo.status.status()));
1827 read(reinterpret_cast<char*>(&obs->gnss2Outputs->timeInfo.leapSeconds), sizeof(obs->gnss2Outputs->timeInfo.leapSeconds));
1828 }
1829 if (obs->gnss2Outputs->gnssField & vn::protocol::uart::GpsGroup::GPSGROUP_DOP)
1830 {
1831 read(reinterpret_cast<char*>(&obs->gnss2Outputs->dop.gDop), sizeof(obs->gnss2Outputs->dop.gDop));
1832 read(reinterpret_cast<char*>(&obs->gnss2Outputs->dop.pDop), sizeof(obs->gnss2Outputs->dop.pDop));
1833 read(reinterpret_cast<char*>(&obs->gnss2Outputs->dop.tDop), sizeof(obs->gnss2Outputs->dop.tDop));
1834 read(reinterpret_cast<char*>(&obs->gnss2Outputs->dop.vDop), sizeof(obs->gnss2Outputs->dop.vDop));
1835 read(reinterpret_cast<char*>(&obs->gnss2Outputs->dop.hDop), sizeof(obs->gnss2Outputs->dop.hDop));
1836 read(reinterpret_cast<char*>(&obs->gnss2Outputs->dop.nDop), sizeof(obs->gnss2Outputs->dop.nDop));
1837 read(reinterpret_cast<char*>(&obs->gnss2Outputs->dop.eDop), sizeof(obs->gnss2Outputs->dop.eDop));
1838 }
1839 if (obs->gnss2Outputs->gnssField & vn::protocol::uart::GpsGroup::GPSGROUP_SATINFO)
1840 {
1841 read(reinterpret_cast<char*>(&obs->gnss2Outputs->satInfo.numSats), sizeof(obs->gnss2Outputs->satInfo.numSats));
1842 obs->gnss2Outputs->satInfo.satellites.resize(obs->gnss2Outputs->satInfo.numSats);
1843
1844 for (auto& satellite : obs->gnss2Outputs->satInfo.satellites)
1845 {
1846 read(reinterpret_cast<char*>(&satellite.sys), sizeof(satellite.sys));
1847 read(reinterpret_cast<char*>(&satellite.svId), sizeof(satellite.svId));
1848 read(reinterpret_cast<char*>(&satellite.flags), sizeof(satellite.flags));
1849 read(reinterpret_cast<char*>(&satellite.cno), sizeof(satellite.cno));
1850 read(reinterpret_cast<char*>(&satellite.qi), sizeof(satellite.qi));
1851 read(reinterpret_cast<char*>(&satellite.el), sizeof(satellite.el));
1852 read(reinterpret_cast<char*>(&satellite.az), sizeof(satellite.az));
1853 }
1854 }
1855 if (obs->gnss2Outputs->gnssField & vn::protocol::uart::GpsGroup::GPSGROUP_RAWMEAS)
1856 {
1857 read(reinterpret_cast<char*>(&obs->gnss2Outputs->raw.tow), sizeof(obs->gnss2Outputs->raw.tow));
1858 read(reinterpret_cast<char*>(&obs->gnss2Outputs->raw.week), sizeof(obs->gnss2Outputs->raw.week));
1859 read(reinterpret_cast<char*>(&obs->gnss2Outputs->raw.numSats), sizeof(obs->gnss2Outputs->raw.numSats));
1860 obs->gnss2Outputs->raw.satellites.resize(obs->gnss2Outputs->raw.numSats);
1861
1862 for (auto& satellite : obs->gnss2Outputs->raw.satellites)
1863 {
1864 read(reinterpret_cast<char*>(&satellite.sys), sizeof(satellite.sys));
1865 read(reinterpret_cast<char*>(&satellite.svId), sizeof(satellite.svId));
1866 read(reinterpret_cast<char*>(&satellite.freq), sizeof(satellite.freq));
1867 read(reinterpret_cast<char*>(&satellite.chan), sizeof(satellite.chan));
1868 read(reinterpret_cast<char*>(&satellite.slot), sizeof(satellite.slot));
1869 read(reinterpret_cast<char*>(&satellite.cno), sizeof(satellite.cno));
1870 read(reinterpret_cast<char*>(&satellite.flags), sizeof(satellite.flags));
1871 read(reinterpret_cast<char*>(&satellite.pr), sizeof(satellite.pr));
1872 read(reinterpret_cast<char*>(&satellite.cp), sizeof(satellite.cp));
1873 read(reinterpret_cast<char*>(&satellite.dp), sizeof(satellite.dp));
1874 }
1875 }
1876 }
1877 }
1878 catch (const std::exception& e)
1879 {
1880 LOG_DEBUG("{}: {} after {} messages", nameId(), e.what(), _messageCount);
1881 return nullptr;
1882 }
1883 }
1884
1885 if (!obs->timeOutputs && !obs->imuOutputs && !obs->gnss1Outputs && !obs->attitudeOutputs && !obs->insOutputs && !obs->gnss2Outputs)
1886 {
1887 LOG_DATA("{}: Nothing read at message {}. Ending reading.", nameId(), _messageCount);
1888 return nullptr;
1889 }
1890 if (obs->insTime.empty())
1891 {
1892 LOG_DATA("{}: Skipping message {}, as no InsTime set.", nameId(), _messageCount);
1893 return obs;
1894 }
1895
1897 return obs;
1898}
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
Structs identifying a unique satellite.
GNSS Satellite System.
Utility functions for working with std::strings.
Binary Outputs from VectorNav Sensors.
File Reader for Vector Nav log files.
Vector Nav Sensors.
Type Definitions for VectorNav messages.
@ None
None.
Definition Code.hpp:94
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.
std::vector< std::string > _headerColumns
Header Columns of a CSV file.
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:465
ImVec2 _guiConfigDefaultWindowSize
Definition Node.hpp:522
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
bool doReinitialize(bool wait=false)
Asks the node worker to reinitialize the node.
Definition Node.cpp:420
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 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...
void ApplyChanges()
Signals that there have been changes to the flow.
SatSys fromSatelliteSystem(SatelliteSystem sys)
Converts the INSTINCT satellite system to the VectorNav representation.
@ Flow
NodeData Trigger.
Definition Pin.hpp:52
Identifies a satellite (satellite system and number)
SatelliteSystem satSys
Satellite system (GPS, GLONASS, GALILEO, QZSS, BDS, IRNSS, SBAS)
uint16_t satNum
Number of the satellite.
Identifies a satellite signal (satellite frequency and number)
uint16_t satNum
Number of the satellite.
SatId toSatId() const
Returns a satellite identifier for the satellite signal.
Satellite System type.