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