12#include "vn/searcher.h"
23#include <imgui_internal.h>
70static void to_json(
json& j,
const SynchronizationControlRegister& synchronizationControlRegister)
73 {
"syncInMode", synchronizationControlRegister.syncInMode },
74 {
"syncInEdge", synchronizationControlRegister.syncInEdge },
75 {
"syncInSkipFactor", synchronizationControlRegister.syncInSkipFactor },
76 {
"syncOutMode", synchronizationControlRegister.syncOutMode },
77 {
"syncOutPolarity", synchronizationControlRegister.syncOutPolarity },
78 {
"syncOutSkipFactor", synchronizationControlRegister.syncOutSkipFactor },
79 {
"syncOutPulseWidth", synchronizationControlRegister.syncOutPulseWidth },
70static void to_json(
json& j,
const SynchronizationControlRegister& synchronizationControlRegister) {
…}
82static void from_json(
const json& j, SynchronizationControlRegister& synchronizationControlRegister)
84 if (j.contains(
"syncInMode"))
86 j.at(
"syncInMode").get_to(synchronizationControlRegister.syncInMode);
88 if (j.contains(
"syncInEdge"))
90 j.at(
"syncInEdge").get_to(synchronizationControlRegister.syncInEdge);
92 if (j.contains(
"syncInSkipFactor"))
94 j.at(
"syncInSkipFactor").get_to(synchronizationControlRegister.syncInSkipFactor);
96 if (j.contains(
"syncOutMode"))
98 j.at(
"syncOutMode").get_to(synchronizationControlRegister.syncOutMode);
100 if (j.contains(
"syncOutPolarity"))
102 j.at(
"syncOutPolarity").get_to(synchronizationControlRegister.syncOutPolarity);
104 if (j.contains(
"syncOutSkipFactor"))
106 j.at(
"syncOutSkipFactor").get_to(synchronizationControlRegister.syncOutSkipFactor);
108 if (j.contains(
"syncOutPulseWidth"))
110 j.at(
"syncOutPulseWidth").get_to(synchronizationControlRegister.syncOutPulseWidth);
82static void from_json(
const json& j, SynchronizationControlRegister& synchronizationControlRegister) {
…}
114static void to_json(
json& j,
const CommunicationProtocolControlRegister& communicationProtocolControlRegister)
117 {
"serialCount", communicationProtocolControlRegister.serialCount },
118 {
"serialStatus", communicationProtocolControlRegister.serialStatus },
119 {
"spiCount", communicationProtocolControlRegister.spiCount },
120 {
"spiStatus", communicationProtocolControlRegister.spiStatus },
121 {
"serialChecksum", communicationProtocolControlRegister.serialChecksum },
122 {
"spiChecksum", communicationProtocolControlRegister.spiChecksum },
123 {
"errorMode", communicationProtocolControlRegister.errorMode },
114static void to_json(
json& j,
const CommunicationProtocolControlRegister& communicationProtocolControlRegister) {
…}
126static void from_json(
const json& j, CommunicationProtocolControlRegister& communicationProtocolControlRegister)
128 if (j.contains(
"serialCount"))
130 j.at(
"serialCount").get_to(communicationProtocolControlRegister.serialCount);
132 if (j.contains(
"serialStatus"))
134 j.at(
"serialStatus").get_to(communicationProtocolControlRegister.serialStatus);
136 if (j.contains(
"spiCount"))
138 j.at(
"spiCount").get_to(communicationProtocolControlRegister.spiCount);
140 if (j.contains(
"spiStatus"))
142 j.at(
"spiStatus").get_to(communicationProtocolControlRegister.spiStatus);
144 if (j.contains(
"serialChecksum"))
146 j.at(
"serialChecksum").get_to(communicationProtocolControlRegister.serialChecksum);
148 if (j.contains(
"spiChecksum"))
150 j.at(
"spiChecksum").get_to(communicationProtocolControlRegister.spiChecksum);
152 if (j.contains(
"errorMode"))
154 j.at(
"errorMode").get_to(communicationProtocolControlRegister.errorMode);
126static void from_json(
const json& j, CommunicationProtocolControlRegister& communicationProtocolControlRegister) {
…}
158static void to_json(
json& j,
const BinaryOutputRegister& binaryOutputRegister)
161 {
"asyncMode", binaryOutputRegister.asyncMode },
162 {
"rateDivisor", binaryOutputRegister.rateDivisor },
163 {
"commonField", binaryOutputRegister.commonField },
164 {
"timeField", binaryOutputRegister.timeField },
165 {
"imuField", binaryOutputRegister.imuField },
166 {
"gpsField", binaryOutputRegister.gpsField },
167 {
"attitudeField", binaryOutputRegister.attitudeField },
168 {
"insField", binaryOutputRegister.insField },
169 {
"gps2Field", binaryOutputRegister.gps2Field },
158static void to_json(
json& j,
const BinaryOutputRegister& binaryOutputRegister) {
…}
172static void from_json(
const json& j, BinaryOutputRegister& binaryOutputRegister)
174 if (j.contains(
"asyncMode"))
176 j.at(
"asyncMode").get_to(binaryOutputRegister.asyncMode);
178 if (j.contains(
"rateDivisor"))
180 j.at(
"rateDivisor").get_to(binaryOutputRegister.rateDivisor);
182 if (j.contains(
"commonField"))
184 j.at(
"commonField").get_to(binaryOutputRegister.commonField);
186 if (j.contains(
"timeField"))
188 j.at(
"timeField").get_to(binaryOutputRegister.timeField);
190 if (j.contains(
"imuField"))
192 j.at(
"imuField").get_to(binaryOutputRegister.imuField);
194 if (j.contains(
"gpsField"))
196 j.at(
"gpsField").get_to(binaryOutputRegister.gpsField);
198 if (j.contains(
"attitudeField"))
200 j.at(
"attitudeField").get_to(binaryOutputRegister.attitudeField);
202 if (j.contains(
"insField"))
204 j.at(
"insField").get_to(binaryOutputRegister.insField);
206 if (j.contains(
"gps2Field"))
208 j.at(
"gps2Field").get_to(binaryOutputRegister.gps2Field);
172static void from_json(
const json& j, BinaryOutputRegister& binaryOutputRegister) {
…}
216static void to_json(
json& j,
const ImuFilteringConfigurationRegister& imuFilteringConfigurationRegister)
219 {
"magWindowSize", imuFilteringConfigurationRegister.magWindowSize },
220 {
"accelWindowSize", imuFilteringConfigurationRegister.accelWindowSize },
221 {
"gyroWindowSize", imuFilteringConfigurationRegister.gyroWindowSize },
222 {
"tempWindowSize", imuFilteringConfigurationRegister.tempWindowSize },
223 {
"presWindowSize", imuFilteringConfigurationRegister.presWindowSize },
224 {
"magFilterMode", imuFilteringConfigurationRegister.magFilterMode },
225 {
"accelFilterMode", imuFilteringConfigurationRegister.accelFilterMode },
226 {
"gyroFilterMode", imuFilteringConfigurationRegister.gyroFilterMode },
227 {
"tempFilterMode", imuFilteringConfigurationRegister.tempFilterMode },
228 {
"presFilterMode", imuFilteringConfigurationRegister.presFilterMode },
216static void to_json(
json& j,
const ImuFilteringConfigurationRegister& imuFilteringConfigurationRegister) {
…}
231static void from_json(
const json& j, ImuFilteringConfigurationRegister& imuFilteringConfigurationRegister)
233 if (j.contains(
"magWindowSize"))
235 j.at(
"magWindowSize").get_to(imuFilteringConfigurationRegister.magWindowSize);
237 if (j.contains(
"accelWindowSize"))
239 j.at(
"accelWindowSize").get_to(imuFilteringConfigurationRegister.accelWindowSize);
241 if (j.contains(
"gyroWindowSize"))
243 j.at(
"gyroWindowSize").get_to(imuFilteringConfigurationRegister.gyroWindowSize);
245 if (j.contains(
"tempWindowSize"))
247 j.at(
"tempWindowSize").get_to(imuFilteringConfigurationRegister.tempWindowSize);
249 if (j.contains(
"presWindowSize"))
251 j.at(
"presWindowSize").get_to(imuFilteringConfigurationRegister.presWindowSize);
253 if (j.contains(
"magFilterMode"))
255 j.at(
"magFilterMode").get_to(imuFilteringConfigurationRegister.magFilterMode);
257 if (j.contains(
"accelFilterMode"))
259 j.at(
"accelFilterMode").get_to(imuFilteringConfigurationRegister.accelFilterMode);
261 if (j.contains(
"gyroFilterMode"))
263 j.at(
"gyroFilterMode").get_to(imuFilteringConfigurationRegister.gyroFilterMode);
265 if (j.contains(
"tempFilterMode"))
267 j.at(
"tempFilterMode").get_to(imuFilteringConfigurationRegister.tempFilterMode);
269 if (j.contains(
"presFilterMode"))
271 j.at(
"presFilterMode").get_to(imuFilteringConfigurationRegister.presFilterMode);
231static void from_json(
const json& j, ImuFilteringConfigurationRegister& imuFilteringConfigurationRegister) {
…}
275static void to_json(
json& j,
const DeltaThetaAndDeltaVelocityConfigurationRegister& deltaThetaAndDeltaVelocityConfigurationRegister)
278 {
"integrationFrame", deltaThetaAndDeltaVelocityConfigurationRegister.integrationFrame },
279 {
"gyroCompensation", deltaThetaAndDeltaVelocityConfigurationRegister.gyroCompensation },
280 {
"accelCompensation", deltaThetaAndDeltaVelocityConfigurationRegister.accelCompensation },
281 {
"earthRateCorrection", deltaThetaAndDeltaVelocityConfigurationRegister.earthRateCorrection },
275static void to_json(
json& j,
const DeltaThetaAndDeltaVelocityConfigurationRegister& deltaThetaAndDeltaVelocityConfigurationRegister) {
…}
284static void from_json(
const json& j, DeltaThetaAndDeltaVelocityConfigurationRegister& deltaThetaAndDeltaVelocityConfigurationRegister)
286 if (j.contains(
"integrationFrame"))
288 j.at(
"integrationFrame").get_to(deltaThetaAndDeltaVelocityConfigurationRegister.integrationFrame);
290 if (j.contains(
"gyroCompensation"))
292 j.at(
"gyroCompensation").get_to(deltaThetaAndDeltaVelocityConfigurationRegister.gyroCompensation);
294 if (j.contains(
"accelCompensation"))
296 j.at(
"accelCompensation").get_to(deltaThetaAndDeltaVelocityConfigurationRegister.accelCompensation);
298 if (j.contains(
"earthRateCorrection"))
300 j.at(
"earthRateCorrection").get_to(deltaThetaAndDeltaVelocityConfigurationRegister.earthRateCorrection);
284static void from_json(
const json& j, DeltaThetaAndDeltaVelocityConfigurationRegister& deltaThetaAndDeltaVelocityConfigurationRegister) {
…}
308static void to_json(
json& j,
const GpsConfigurationRegister& gpsConfigurationRegister)
311 {
"mode", gpsConfigurationRegister.mode },
312 {
"ppsSource", gpsConfigurationRegister.ppsSource },
313 {
"rate", gpsConfigurationRegister.rate },
314 {
"antPow", gpsConfigurationRegister.antPow },
308static void to_json(
json& j,
const GpsConfigurationRegister& gpsConfigurationRegister) {
…}
317static void from_json(
const json& j, GpsConfigurationRegister& gpsConfigurationRegister)
319 if (j.contains(
"mode"))
321 j.at(
"mode").get_to(gpsConfigurationRegister.mode);
323 if (j.contains(
"ppsSource"))
325 j.at(
"ppsSource").get_to(gpsConfigurationRegister.ppsSource);
327 if (j.contains(
"rate"))
329 j.at(
"rate").get_to(gpsConfigurationRegister.rate);
331 if (j.contains(
"antPow"))
333 j.at(
"antPow").get_to(gpsConfigurationRegister.antPow);
317static void from_json(
const json& j, GpsConfigurationRegister& gpsConfigurationRegister) {
…}
337static void to_json(
json& j,
const GpsCompassBaselineRegister& gpsCompassBaselineRegister)
340 {
"position", gpsCompassBaselineRegister.position },
341 {
"uncertainty", gpsCompassBaselineRegister.uncertainty },
337static void to_json(
json& j,
const GpsCompassBaselineRegister& gpsCompassBaselineRegister) {
…}
344static void from_json(
const json& j, GpsCompassBaselineRegister& gpsCompassBaselineRegister)
346 if (j.contains(
"position"))
348 j.at(
"position").get_to(gpsCompassBaselineRegister.position);
350 if (j.contains(
"uncertainty"))
352 j.at(
"uncertainty").get_to(gpsCompassBaselineRegister.uncertainty);
344static void from_json(
const json& j, GpsCompassBaselineRegister& gpsCompassBaselineRegister) {
…}
360static void to_json(
json& j,
const VpeBasicControlRegister& vpeBasicControlRegister)
363 {
"enable", vpeBasicControlRegister.enable },
364 {
"headingMode", vpeBasicControlRegister.headingMode },
365 {
"filteringMode", vpeBasicControlRegister.filteringMode },
366 {
"tuningMode", vpeBasicControlRegister.tuningMode },
360static void to_json(
json& j,
const VpeBasicControlRegister& vpeBasicControlRegister) {
…}
369static void from_json(
const json& j, VpeBasicControlRegister& vpeBasicControlRegister)
371 if (j.contains(
"enable"))
373 j.at(
"enable").get_to(vpeBasicControlRegister.enable);
375 if (j.contains(
"headingMode"))
377 j.at(
"headingMode").get_to(vpeBasicControlRegister.headingMode);
379 if (j.contains(
"filteringMode"))
381 j.at(
"filteringMode").get_to(vpeBasicControlRegister.filteringMode);
383 if (j.contains(
"tuningMode"))
385 j.at(
"tuningMode").get_to(vpeBasicControlRegister.tuningMode);
369static void from_json(
const json& j, VpeBasicControlRegister& vpeBasicControlRegister) {
…}
389static void to_json(
json& j,
const VpeMagnetometerBasicTuningRegister& vpeMagnetometerBasicTuningRegister)
392 {
"baseTuning", vpeMagnetometerBasicTuningRegister.baseTuning },
393 {
"adaptiveTuning", vpeMagnetometerBasicTuningRegister.adaptiveTuning },
394 {
"adaptiveFiltering", vpeMagnetometerBasicTuningRegister.adaptiveFiltering },
389static void to_json(
json& j,
const VpeMagnetometerBasicTuningRegister& vpeMagnetometerBasicTuningRegister) {
…}
397static void from_json(
const json& j, VpeMagnetometerBasicTuningRegister& vpeMagnetometerBasicTuningRegister)
399 if (j.contains(
"baseTuning"))
401 j.at(
"baseTuning").get_to(vpeMagnetometerBasicTuningRegister.baseTuning);
403 if (j.contains(
"adaptiveTuning"))
405 j.at(
"adaptiveTuning").get_to(vpeMagnetometerBasicTuningRegister.adaptiveTuning);
407 if (j.contains(
"adaptiveFiltering"))
409 j.at(
"adaptiveFiltering").get_to(vpeMagnetometerBasicTuningRegister.adaptiveFiltering);
397static void from_json(
const json& j, VpeMagnetometerBasicTuningRegister& vpeMagnetometerBasicTuningRegister) {
…}
413static void to_json(
json& j,
const VpeAccelerometerBasicTuningRegister& vpeAccelerometerBasicTuningRegister)
416 {
"baseTuning", vpeAccelerometerBasicTuningRegister.baseTuning },
417 {
"adaptiveTuning", vpeAccelerometerBasicTuningRegister.adaptiveTuning },
418 {
"adaptiveFiltering", vpeAccelerometerBasicTuningRegister.adaptiveFiltering },
413static void to_json(
json& j,
const VpeAccelerometerBasicTuningRegister& vpeAccelerometerBasicTuningRegister) {
…}
421static void from_json(
const json& j, VpeAccelerometerBasicTuningRegister& vpeAccelerometerBasicTuningRegister)
423 if (j.contains(
"baseTuning"))
425 j.at(
"baseTuning").get_to(vpeAccelerometerBasicTuningRegister.baseTuning);
427 if (j.contains(
"adaptiveTuning"))
429 j.at(
"adaptiveTuning").get_to(vpeAccelerometerBasicTuningRegister.adaptiveTuning);
431 if (j.contains(
"adaptiveFiltering"))
433 j.at(
"adaptiveFiltering").get_to(vpeAccelerometerBasicTuningRegister.adaptiveFiltering);
421static void from_json(
const json& j, VpeAccelerometerBasicTuningRegister& vpeAccelerometerBasicTuningRegister) {
…}
437static void to_json(
json& j,
const VpeGyroBasicTuningRegister& vpeGyroBasicTuningRegister)
440 {
"angularWalkVariance", vpeGyroBasicTuningRegister.angularWalkVariance },
441 {
"baseTuning", vpeGyroBasicTuningRegister.baseTuning },
442 {
"adaptiveTuning", vpeGyroBasicTuningRegister.adaptiveTuning },
437static void to_json(
json& j,
const VpeGyroBasicTuningRegister& vpeGyroBasicTuningRegister) {
…}
445static void from_json(
const json& j, VpeGyroBasicTuningRegister& vpeGyroBasicTuningRegister)
447 if (j.contains(
"angularWalkVariance"))
449 j.at(
"angularWalkVariance").get_to(vpeGyroBasicTuningRegister.angularWalkVariance);
451 if (j.contains(
"baseTuning"))
453 j.at(
"baseTuning").get_to(vpeGyroBasicTuningRegister.baseTuning);
455 if (j.contains(
"adaptiveTuning"))
457 j.at(
"adaptiveTuning").get_to(vpeGyroBasicTuningRegister.adaptiveTuning);
445static void from_json(
const json& j, VpeGyroBasicTuningRegister& vpeGyroBasicTuningRegister) {
…}
465static void to_json(
json& j,
const InsBasicConfigurationRegisterVn300& insBasicConfigurationRegisterVn300)
468 {
"scenario", insBasicConfigurationRegisterVn300.scenario },
469 {
"ahrsAiding", insBasicConfigurationRegisterVn300.ahrsAiding },
470 {
"estBaseline", insBasicConfigurationRegisterVn300.estBaseline },
465static void to_json(
json& j,
const InsBasicConfigurationRegisterVn300& insBasicConfigurationRegisterVn300) {
…}
473static void from_json(
const json& j, InsBasicConfigurationRegisterVn300& insBasicConfigurationRegisterVn300)
475 if (j.contains(
"scenario"))
477 j.at(
"scenario").get_to(insBasicConfigurationRegisterVn300.scenario);
479 if (j.contains(
"ahrsAiding"))
481 j.at(
"ahrsAiding").get_to(insBasicConfigurationRegisterVn300.ahrsAiding);
483 if (j.contains(
"estBaseline"))
485 j.at(
"estBaseline").get_to(insBasicConfigurationRegisterVn300.estBaseline);
473static void from_json(
const json& j, InsBasicConfigurationRegisterVn300& insBasicConfigurationRegisterVn300) {
…}
489static void to_json(
json& j,
const StartupFilterBiasEstimateRegister& startupFilterBiasEstimateRegister)
492 {
"gyroBias", startupFilterBiasEstimateRegister.gyroBias },
493 {
"accelBias", startupFilterBiasEstimateRegister.accelBias },
494 {
"pressureBias", startupFilterBiasEstimateRegister.pressureBias },
489static void to_json(
json& j,
const StartupFilterBiasEstimateRegister& startupFilterBiasEstimateRegister) {
…}
497static void from_json(
const json& j, StartupFilterBiasEstimateRegister& startupFilterBiasEstimateRegister)
499 if (j.contains(
"gyroBias"))
501 j.at(
"gyroBias").get_to(startupFilterBiasEstimateRegister.gyroBias);
503 if (j.contains(
"accelBias"))
505 j.at(
"accelBias").get_to(startupFilterBiasEstimateRegister.accelBias);
507 if (j.contains(
"pressureBias"))
509 j.at(
"pressureBias").get_to(startupFilterBiasEstimateRegister.pressureBias);
497static void from_json(
const json& j, StartupFilterBiasEstimateRegister& startupFilterBiasEstimateRegister) {
…}
517static void to_json(
json& j,
const MagnetometerCalibrationControlRegister& magnetometerCalibrationControlRegister)
520 {
"hsiMode", magnetometerCalibrationControlRegister.hsiMode },
521 {
"hsiOutput", magnetometerCalibrationControlRegister.hsiOutput },
522 {
"convergeRate", magnetometerCalibrationControlRegister.convergeRate },
517static void to_json(
json& j,
const MagnetometerCalibrationControlRegister& magnetometerCalibrationControlRegister) {
…}
525static void from_json(
const json& j, MagnetometerCalibrationControlRegister& magnetometerCalibrationControlRegister)
527 if (j.contains(
"hsiMode"))
529 j.at(
"hsiMode").get_to(magnetometerCalibrationControlRegister.hsiMode);
531 if (j.contains(
"hsiOutput"))
533 j.at(
"hsiOutput").get_to(magnetometerCalibrationControlRegister.hsiOutput);
535 if (j.contains(
"convergeRate"))
537 j.at(
"convergeRate").get_to(magnetometerCalibrationControlRegister.convergeRate);
525static void from_json(
const json& j, MagnetometerCalibrationControlRegister& magnetometerCalibrationControlRegister) {
…}
545static void to_json(
json& j,
const MagneticAndGravityReferenceVectorsRegister& magneticAndGravityReferenceVectorsRegister)
548 {
"magRef", magneticAndGravityReferenceVectorsRegister.magRef },
549 {
"accRef", magneticAndGravityReferenceVectorsRegister.accRef },
545static void to_json(
json& j,
const MagneticAndGravityReferenceVectorsRegister& magneticAndGravityReferenceVectorsRegister) {
…}
552static void from_json(
const json& j, MagneticAndGravityReferenceVectorsRegister& magneticAndGravityReferenceVectorsRegister)
554 if (j.contains(
"magRef"))
556 j.at(
"magRef").get_to(magneticAndGravityReferenceVectorsRegister.magRef);
558 if (j.contains(
"accRef"))
560 j.at(
"accRef").get_to(magneticAndGravityReferenceVectorsRegister.accRef);
552static void from_json(
const json& j, MagneticAndGravityReferenceVectorsRegister& magneticAndGravityReferenceVectorsRegister) {
…}
564static void to_json(
json& j,
const ReferenceVectorConfigurationRegister& referenceVectorConfigurationRegister)
567 {
"useMagModel", referenceVectorConfigurationRegister.useMagModel },
568 {
"useGravityModel", referenceVectorConfigurationRegister.useGravityModel },
569 {
"recalcThreshold", referenceVectorConfigurationRegister.recalcThreshold },
570 {
"year", referenceVectorConfigurationRegister.year },
571 {
"position", referenceVectorConfigurationRegister.position },
564static void to_json(
json& j,
const ReferenceVectorConfigurationRegister& referenceVectorConfigurationRegister) {
…}
574static void from_json(
const json& j, ReferenceVectorConfigurationRegister& referenceVectorConfigurationRegister)
576 if (j.contains(
"useMagModel"))
578 j.at(
"useMagModel").get_to(referenceVectorConfigurationRegister.useMagModel);
580 if (j.contains(
"useGravityModel"))
582 j.at(
"useGravityModel").get_to(referenceVectorConfigurationRegister.useGravityModel);
584 if (j.contains(
"recalcThreshold"))
586 j.at(
"recalcThreshold").get_to(referenceVectorConfigurationRegister.recalcThreshold);
588 if (j.contains(
"year"))
590 j.at(
"year").get_to(referenceVectorConfigurationRegister.year);
592 if (j.contains(
"position"))
594 j.at(
"position").get_to(referenceVectorConfigurationRegister.position);
574static void from_json(
const json& j, ReferenceVectorConfigurationRegister& referenceVectorConfigurationRegister) {
…}
602static void to_json(
json& j,
const VelocityCompensationControlRegister& velocityCompensationControlRegister)
605 {
"mode", velocityCompensationControlRegister.mode },
606 {
"velocityTuning", velocityCompensationControlRegister.velocityTuning },
607 {
"rateTuning", velocityCompensationControlRegister.rateTuning },
602static void to_json(
json& j,
const VelocityCompensationControlRegister& velocityCompensationControlRegister) {
…}
610static void from_json(
const json& j, VelocityCompensationControlRegister& velocityCompensationControlRegister)
612 if (j.contains(
"mode"))
614 j.at(
"mode").get_to(velocityCompensationControlRegister.mode);
616 if (j.contains(
"velocityTuning"))
618 j.at(
"velocityTuning").get_to(velocityCompensationControlRegister.velocityTuning);
620 if (j.contains(
"rateTuning"))
622 j.at(
"rateTuning").get_to(velocityCompensationControlRegister.rateTuning);
610static void from_json(
const json& j, VelocityCompensationControlRegister& velocityCompensationControlRegister) {
…}
632 (bor.timeField |= vn::protocol::uart::TimeGroup::TIMEGROUP_TIMESTARTUP) && (bor.timeField |= vn::protocol::uart::TimeGroup::TIMEGROUP_TIMESTATUS);
636 (bor.timeField |= vn::protocol::uart::TimeGroup::TIMEGROUP_GPSTOW) && (bor.timeField |= vn::protocol::uart::TimeGroup::TIMEGROUP_GPSWEEK);
641 if (bor.imuField & (vn::protocol::uart::IMUGROUP_ACCEL | vn::protocol::uart::IMUGROUP_UNCOMPACCEL))
645 if (bor.imuField & (vn::protocol::uart::IMUGROUP_ANGULARRATE | vn::protocol::uart::IMUGROUP_UNCOMPGYRO))
649 if (bor.imuField & (vn::protocol::uart::IMUGROUP_MAG | vn::protocol::uart::IMUGROUP_UNCOMPMAG))
653 if (bor.imuField & (vn::protocol::uart::IMUGROUP_MAG | vn::protocol::uart::IMUGROUP_UNCOMPMAG))
657 if (bor.imuField & vn::protocol::uart::IMUGROUP_TEMP)
661 if (bor.imuField & vn::protocol::uart::IMUGROUP_PRES)
665 LOG_DATA(
"Frequency of ImuFilter matches output frequency (coupled 'rateDivisor' and 'windowSize' of moving average filter.)");
667 if (sensor->
isInitialized() && sensor->
_vs.isConnected() && sensor->
_vs.verifySensorConnectivity())
673 catch (
const std::exception& e)
675 LOG_ERROR(
"Could not configure the imuFilteringConfigurationRegister: {}", e.what());
732 {
"TimeStartup", vn::protocol::uart::TimeGroup::TIMEGROUP_TIMESTARTUP,
733 []() { ImGui::TextUnformatted(
"Time since startup.\n\nThe system time since startup measured in nano seconds. The time since startup is based upon the internal\nTXCO oscillator for the MCU. The accuracy of the internal TXCO is +/- 20ppm (-40C to 85C)."); },
734 [](VectorNavModel sensorModel,
const vn::sensors::BinaryOutputRegister& bor, uint32_t ) {
return (sensorModel != VectorNavModel::VN310
735 || !((bor.gpsField & vn::protocol::uart::GpsGroup::GPSGROUP_TOW)
736 || (bor.gpsField & vn::protocol::uart::GpsGroup::GPSGROUP_WEEK)
737 || (bor.gps2Field & vn::protocol::uart::GpsGroup::GPSGROUP_TOW)
738 || (bor.gps2Field & vn::protocol::uart::GpsGroup::GPSGROUP_WEEK)))
739 && !(bor.imuField & vn::protocol::uart::ImuGroup::IMUGROUP_UNCOMPMAG)
740 && !(bor.imuField & vn::protocol::uart::ImuGroup::IMUGROUP_UNCOMPACCEL)
741 && !(bor.imuField & vn::protocol::uart::ImuGroup::IMUGROUP_UNCOMPGYRO)
742 && !(bor.imuField & vn::protocol::uart::ImuGroup::IMUGROUP_TEMP)
743 && !(bor.imuField & vn::protocol::uart::ImuGroup::IMUGROUP_PRES)
744 && !(bor.imuField & vn::protocol::uart::ImuGroup::IMUGROUP_DELTATHETA)
745 && !(bor.imuField & vn::protocol::uart::ImuGroup::IMUGROUP_DELTAVEL)
746 && !(bor.imuField & vn::protocol::uart::ImuGroup::IMUGROUP_MAG)
747 && !(bor.imuField & vn::protocol::uart::ImuGroup::IMUGROUP_ACCEL)
748 && !(bor.imuField & vn::protocol::uart::ImuGroup::IMUGROUP_ANGULARRATE)
749 && !(bor.attitudeField & vn::protocol::uart::AttitudeGroup::ATTITUDEGROUP_YAWPITCHROLL)
750 && !(bor.attitudeField & vn::protocol::uart::AttitudeGroup::ATTITUDEGROUP_QUATERNION)
751 && !(bor.attitudeField & vn::protocol::uart::AttitudeGroup::ATTITUDEGROUP_DCM)
752 && !(bor.attitudeField & vn::protocol::uart::AttitudeGroup::ATTITUDEGROUP_MAGNED)
753 && !(bor.attitudeField & vn::protocol::uart::AttitudeGroup::ATTITUDEGROUP_ACCELNED)
754 && !(bor.attitudeField & vn::protocol::uart::AttitudeGroup::ATTITUDEGROUP_LINEARACCELBODY)
755 && !(bor.attitudeField & vn::protocol::uart::AttitudeGroup::ATTITUDEGROUP_LINEARACCELNED)
756 && !(bor.attitudeField & vn::protocol::uart::AttitudeGroup::ATTITUDEGROUP_YPRU)
757 && !(bor.insField & vn::protocol::uart::InsGroup::INSGROUP_INSSTATUS)
758 && !(bor.insField & vn::protocol::uart::InsGroup::INSGROUP_POSLLA)
759 && !(bor.insField & vn::protocol::uart::InsGroup::INSGROUP_POSECEF)
760 && !(bor.insField & vn::protocol::uart::InsGroup::INSGROUP_VELBODY)
761 && !(bor.insField & vn::protocol::uart::InsGroup::INSGROUP_VELNED)
762 && !(bor.insField & vn::protocol::uart::InsGroup::INSGROUP_VELECEF)
763 && !(bor.insField & vn::protocol::uart::InsGroup::INSGROUP_MAGECEF)
764 && !(bor.insField & vn::protocol::uart::InsGroup::INSGROUP_ACCELECEF)
765 && !(bor.insField & vn::protocol::uart::InsGroup::INSGROUP_LINEARACCELECEF)
766 && !(bor.insField & vn::protocol::uart::InsGroup::INSGROUP_POSU)
767 && !(bor.insField & vn::protocol::uart::InsGroup::INSGROUP_VELU); } },
768 {
"TimeGps", vn::protocol::uart::TimeGroup::TIMEGROUP_TIMEGPS,
769 []() { ImGui::TextUnformatted(
"Absolute GPS time.\n\nThe absolute GPS time since start of GPS epoch 1980 expressed in nano seconds."); },
770 [](VectorNavModel sensorModel,
const vn::sensors::BinaryOutputRegister& , uint32_t ) {
return sensorModel == VectorNavModel::VN310; },
771 [](
VectorNavSensor* , vn::sensors::BinaryOutputRegister& bor, uint32_t& ) { (bor.timeField & vn::protocol::uart::TimeGroup::TIMEGROUP_TIMEGPS) && (bor.timeField |= vn::protocol::uart::TimeGroup::TIMEGROUP_TIMESTATUS); } },
772 {
"GpsTow", vn::protocol::uart::TimeGroup::TIMEGROUP_GPSTOW,
773 []() { ImGui::TextUnformatted(
"Time since start of GPS week.\n\nThe time since the start of the current GPS time week expressed in nano seconds."); },
774 [](VectorNavModel sensorModel,
const vn::sensors::BinaryOutputRegister& bor, uint32_t ) {
return (sensorModel == VectorNavModel::VN310)
775 && !(bor.imuField & vn::protocol::uart::ImuGroup::IMUGROUP_UNCOMPMAG)
776 && !(bor.imuField & vn::protocol::uart::ImuGroup::IMUGROUP_UNCOMPACCEL)
777 && !(bor.imuField & vn::protocol::uart::ImuGroup::IMUGROUP_UNCOMPGYRO)
778 && !(bor.imuField & vn::protocol::uart::ImuGroup::IMUGROUP_TEMP)
779 && !(bor.imuField & vn::protocol::uart::ImuGroup::IMUGROUP_PRES)
780 && !(bor.imuField & vn::protocol::uart::ImuGroup::IMUGROUP_DELTATHETA)
781 && !(bor.imuField & vn::protocol::uart::ImuGroup::IMUGROUP_DELTAVEL)
782 && !(bor.imuField & vn::protocol::uart::ImuGroup::IMUGROUP_MAG)
783 && !(bor.imuField & vn::protocol::uart::ImuGroup::IMUGROUP_ACCEL)
784 && !(bor.imuField & vn::protocol::uart::ImuGroup::IMUGROUP_ANGULARRATE)
785 && !(bor.attitudeField & vn::protocol::uart::AttitudeGroup::ATTITUDEGROUP_YAWPITCHROLL)
786 && !(bor.attitudeField & vn::protocol::uart::AttitudeGroup::ATTITUDEGROUP_QUATERNION)
787 && !(bor.attitudeField & vn::protocol::uart::AttitudeGroup::ATTITUDEGROUP_DCM)
788 && !(bor.attitudeField & vn::protocol::uart::AttitudeGroup::ATTITUDEGROUP_MAGNED)
789 && !(bor.attitudeField & vn::protocol::uart::AttitudeGroup::ATTITUDEGROUP_ACCELNED)
790 && !(bor.attitudeField & vn::protocol::uart::AttitudeGroup::ATTITUDEGROUP_LINEARACCELBODY)
791 && !(bor.attitudeField & vn::protocol::uart::AttitudeGroup::ATTITUDEGROUP_LINEARACCELNED)
792 && !(bor.attitudeField & vn::protocol::uart::AttitudeGroup::ATTITUDEGROUP_YPRU)
793 && !(bor.insField & vn::protocol::uart::InsGroup::INSGROUP_INSSTATUS)
794 && !(bor.insField & vn::protocol::uart::InsGroup::INSGROUP_POSLLA)
795 && !(bor.insField & vn::protocol::uart::InsGroup::INSGROUP_POSECEF)
796 && !(bor.insField & vn::protocol::uart::InsGroup::INSGROUP_VELBODY)
797 && !(bor.insField & vn::protocol::uart::InsGroup::INSGROUP_VELNED)
798 && !(bor.insField & vn::protocol::uart::InsGroup::INSGROUP_VELECEF)
799 && !(bor.insField & vn::protocol::uart::InsGroup::INSGROUP_MAGECEF)
800 && !(bor.insField & vn::protocol::uart::InsGroup::INSGROUP_ACCELECEF)
801 && !(bor.insField & vn::protocol::uart::InsGroup::INSGROUP_LINEARACCELECEF)
802 && !(bor.insField & vn::protocol::uart::InsGroup::INSGROUP_POSU)
803 && !(bor.insField & vn::protocol::uart::InsGroup::INSGROUP_VELU); },
804 [](
VectorNavSensor* , vn::sensors::BinaryOutputRegister& bor, uint32_t& ) { (bor.timeField & vn::protocol::uart::TimeGroup::TIMEGROUP_GPSTOW) && (bor.timeField |= vn::protocol::uart::TimeGroup::TIMEGROUP_TIMESTATUS); } },
805 {
"GpsWeek", vn::protocol::uart::TimeGroup::TIMEGROUP_GPSWEEK,
806 []() { ImGui::TextUnformatted(
"GPS week.\n\nThe current GPS week."); },
807 [](VectorNavModel sensorModel,
const vn::sensors::BinaryOutputRegister& bor, uint32_t ) {
return (sensorModel == VectorNavModel::VN310)
808 && !(bor.imuField & vn::protocol::uart::ImuGroup::IMUGROUP_UNCOMPMAG)
809 && !(bor.imuField & vn::protocol::uart::ImuGroup::IMUGROUP_UNCOMPACCEL)
810 && !(bor.imuField & vn::protocol::uart::ImuGroup::IMUGROUP_UNCOMPGYRO)
811 && !(bor.imuField & vn::protocol::uart::ImuGroup::IMUGROUP_TEMP)
812 && !(bor.imuField & vn::protocol::uart::ImuGroup::IMUGROUP_PRES)
813 && !(bor.imuField & vn::protocol::uart::ImuGroup::IMUGROUP_DELTATHETA)
814 && !(bor.imuField & vn::protocol::uart::ImuGroup::IMUGROUP_DELTAVEL)
815 && !(bor.imuField & vn::protocol::uart::ImuGroup::IMUGROUP_MAG)
816 && !(bor.imuField & vn::protocol::uart::ImuGroup::IMUGROUP_ACCEL)
817 && !(bor.imuField & vn::protocol::uart::ImuGroup::IMUGROUP_ANGULARRATE)
818 && !(bor.attitudeField & vn::protocol::uart::AttitudeGroup::ATTITUDEGROUP_YAWPITCHROLL)
819 && !(bor.attitudeField & vn::protocol::uart::AttitudeGroup::ATTITUDEGROUP_QUATERNION)
820 && !(bor.attitudeField & vn::protocol::uart::AttitudeGroup::ATTITUDEGROUP_DCM)
821 && !(bor.attitudeField & vn::protocol::uart::AttitudeGroup::ATTITUDEGROUP_MAGNED)
822 && !(bor.attitudeField & vn::protocol::uart::AttitudeGroup::ATTITUDEGROUP_ACCELNED)
823 && !(bor.attitudeField & vn::protocol::uart::AttitudeGroup::ATTITUDEGROUP_LINEARACCELBODY)
824 && !(bor.attitudeField & vn::protocol::uart::AttitudeGroup::ATTITUDEGROUP_LINEARACCELNED)
825 && !(bor.attitudeField & vn::protocol::uart::AttitudeGroup::ATTITUDEGROUP_YPRU)
826 && !(bor.insField & vn::protocol::uart::InsGroup::INSGROUP_INSSTATUS)
827 && !(bor.insField & vn::protocol::uart::InsGroup::INSGROUP_POSLLA)
828 && !(bor.insField & vn::protocol::uart::InsGroup::INSGROUP_POSECEF)
829 && !(bor.insField & vn::protocol::uart::InsGroup::INSGROUP_VELBODY)
830 && !(bor.insField & vn::protocol::uart::InsGroup::INSGROUP_VELNED)
831 && !(bor.insField & vn::protocol::uart::InsGroup::INSGROUP_VELECEF)
832 && !(bor.insField & vn::protocol::uart::InsGroup::INSGROUP_MAGECEF)
833 && !(bor.insField & vn::protocol::uart::InsGroup::INSGROUP_ACCELECEF)
834 && !(bor.insField & vn::protocol::uart::InsGroup::INSGROUP_LINEARACCELECEF)
835 && !(bor.insField & vn::protocol::uart::InsGroup::INSGROUP_POSU)
836 && !(bor.insField & vn::protocol::uart::InsGroup::INSGROUP_VELU); },
837 [](
VectorNavSensor* , vn::sensors::BinaryOutputRegister& bor, uint32_t& ) { (bor.timeField & vn::protocol::uart::TimeGroup::TIMEGROUP_GPSWEEK) && (bor.timeField |= vn::protocol::uart::TimeGroup::TIMEGROUP_TIMESTATUS); } },
838 {
"TimeSyncIn", vn::protocol::uart::TimeGroup::TIMEGROUP_TIMESYNCIN,
839 []() { ImGui::TextUnformatted(
"Time since last SyncIn trigger.\n\nThe time since the last SyncIn event trigger expressed in nano seconds."); } },
840 {
"TimeGpsPps", vn::protocol::uart::TimeGroup::TIMEGROUP_TIMEGPSPPS,
841 []() { ImGui::TextUnformatted(
"Time since last GPS PPS trigger.\n\nThe time since the last GPS PPS trigger event expressed in nano seconds."); },
842 [](VectorNavModel sensorModel,
const vn::sensors::BinaryOutputRegister& , uint32_t ) {
return sensorModel == VectorNavModel::VN310; } },
843 {
"TimeUTC", vn::protocol::uart::TimeGroup::TIMEGROUP_TIMEUTC,
844 []() { ImGui::TextUnformatted(
"UTC time.\n\nThe current UTC time. The year is given as a signed byte year offset from the year 2000. For example the\nyear 2013 would be given as year 13."); },
845 [](VectorNavModel ,
const vn::sensors::BinaryOutputRegister& , uint32_t ) {
return false; },
846 [](
VectorNavSensor* , vn::sensors::BinaryOutputRegister& bor, uint32_t& ) { (bor.timeField & vn::protocol::uart::TimeGroup::TIMEGROUP_TIMEUTC) && (bor.timeField |= vn::protocol::uart::TimeGroup::TIMEGROUP_TIMESTATUS); } },
847 {
"SyncInCnt", vn::protocol::uart::TimeGroup::TIMEGROUP_SYNCINCNT,
848 []() { ImGui::TextUnformatted(
"SyncIn trigger count.\n\nThe number of SyncIn trigger events that have occurred."); } },
849 {
"SyncOutCnt", vn::protocol::uart::TimeGroup::TIMEGROUP_SYNCOUTCNT,
850 []() { ImGui::TextUnformatted(
"SyncOut trigger count.\n\nThe number of SyncOut trigger events that have occurred."); } },
851 {
"TimeStatus", vn::protocol::uart::TimeGroup::TIMEGROUP_TIMESTATUS,
852 []() { ImGui::TextUnformatted(
"Time valid status flags.");
853 if (ImGui::BeginTable(
"VectorNavTimeStatusTooltip", 3, ImGuiTableFlags_Borders | ImGuiTableFlags_RowBg))
855 ImGui::TableSetupColumn(
"Bit Offset", ImGuiTableColumnFlags_WidthFixed);
856 ImGui::TableSetupColumn(
"Field", ImGuiTableColumnFlags_WidthFixed);
857 ImGui::TableSetupColumn(
"Description", ImGuiTableColumnFlags_WidthFixed);
858 ImGui::TableHeadersRow();
860 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"0");
861 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"timeOk");
862 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"1 - GpsTow is valid");
864 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"1");
865 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"dateOk");
866 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"1 - TimeGps and GpsWeek are valid");
868 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"2");
869 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"utcTimeValid");
870 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"1 - UTC time is valid");
872 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"3 - 7");
873 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"resv");
874 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"Reserved for future use");
878 [](VectorNavModel ,
const vn::sensors::BinaryOutputRegister& bor, uint32_t ) {
return !(bor.commonField & vn::protocol::uart::CommonGroup::COMMONGROUP_TIMEGPS)
879 && !(bor.timeField & vn::protocol::uart::TimeGroup::TIMEGROUP_GPSTOW)
880 && !(bor.timeField & vn::protocol::uart::TimeGroup::TIMEGROUP_GPSWEEK)
881 && !(bor.timeField & vn::protocol::uart::TimeGroup::TIMEGROUP_TIMEGPS)
882 && !(bor.timeField & vn::protocol::uart::TimeGroup::TIMEGROUP_TIMEUTC)
883 && !(bor.imuField & vn::protocol::uart::ImuGroup::IMUGROUP_UNCOMPMAG)
884 && !(bor.imuField & vn::protocol::uart::ImuGroup::IMUGROUP_UNCOMPACCEL)
885 && !(bor.imuField & vn::protocol::uart::ImuGroup::IMUGROUP_UNCOMPGYRO)
886 && !(bor.imuField & vn::protocol::uart::ImuGroup::IMUGROUP_TEMP)
887 && !(bor.imuField & vn::protocol::uart::ImuGroup::IMUGROUP_PRES)
888 && !(bor.imuField & vn::protocol::uart::ImuGroup::IMUGROUP_DELTATHETA)
889 && !(bor.imuField & vn::protocol::uart::ImuGroup::IMUGROUP_DELTAVEL)
890 && !(bor.imuField & vn::protocol::uart::ImuGroup::IMUGROUP_MAG)
891 && !(bor.imuField & vn::protocol::uart::ImuGroup::IMUGROUP_ACCEL)
892 && !(bor.imuField & vn::protocol::uart::ImuGroup::IMUGROUP_ANGULARRATE); } },
896 {
"ImuStatus", vn::protocol::uart::ImuGroup::IMUGROUP_IMUSTATUS,
897 []() { ImGui::TextUnformatted(
"Status is reserved for future use. Not currently used in the current code, as such will always report 0."); },
898 [](VectorNavModel ,
const vn::sensors::BinaryOutputRegister& , uint32_t ) {
return false; } },
899 {
"UncompMag", vn::protocol::uart::ImuGroup::IMUGROUP_UNCOMPMAG,
900 []() { ImGui::TextUnformatted(
"Uncompensated magnetic measurement.\n\nThe IMU magnetic field measured in units of Gauss, given in the body frame. This measurement is\ncompensated by the static calibration (individual factory calibration stored in flash), and the user\ncompensation, however it is not compensated by the onboard Hard/Soft Iron estimator."); },
901 [](VectorNavModel ,
const vn::sensors::BinaryOutputRegister& , uint32_t ) {
return true; }, coupleImuFilterRates },
902 {
"UncompAccel", vn::protocol::uart::ImuGroup::IMUGROUP_UNCOMPACCEL,
903 []() { ImGui::TextUnformatted(
"Uncompensated acceleration measurement.\n\nThe IMU acceleration measured in units of m/s^2, given in the body frame. This measurement is\ncompensated by the static calibration (individual factory calibration stored in flash), however it is not\ncompensated by any dynamic calibration such as bias compensation from the onboard INS Kalman filter."); },
904 [](VectorNavModel ,
const vn::sensors::BinaryOutputRegister& , uint32_t ) {
return true; }, coupleImuFilterRates },
905 {
"UncompGyro", vn::protocol::uart::ImuGroup::IMUGROUP_UNCOMPGYRO,
906 []() { ImGui::TextUnformatted(
"Uncompensated angular rate measurement.\n\nThe IMU angular rate measured in units of rad/s, given in the body frame. This measurement is compensated\nby the static calibration (individual factory calibration stored in flash), however it is not compensated by any\ndynamic calibration such as the bias compensation from the onboard AHRS/INS Kalman filters."); },
907 [](VectorNavModel ,
const vn::sensors::BinaryOutputRegister& , uint32_t ) {
return true; }, coupleImuFilterRates },
908 {
"Temp", vn::protocol::uart::ImuGroup::IMUGROUP_TEMP,
909 []() { ImGui::TextUnformatted(
"Temperature measurement.\n\nThe IMU temperature measured in units of Celsius."); },
910 [](VectorNavModel ,
const vn::sensors::BinaryOutputRegister& , uint32_t ) {
return true; }, coupleImuFilterRates },
911 {
"Pres", vn::protocol::uart::ImuGroup::IMUGROUP_PRES,
912 []() { ImGui::TextUnformatted(
"Pressure measurement.\n\nThe IMU pressure measured in kilopascals. This is an absolute pressure measurement. Typical pressure at sea level would be around 100 kPa."); },
913 [](VectorNavModel ,
const vn::sensors::BinaryOutputRegister& , uint32_t ) {
return true; }, coupleImuFilterRates },
914 {
"DeltaTheta", vn::protocol::uart::ImuGroup::IMUGROUP_DELTATHETA,
915 []() { ImGui::TextUnformatted(
"Delta theta angles.\n\nThe delta time (dtime) is the time interval that the delta angle and velocities are integrated over. The delta\ntheta (dtheta) is the delta rotation angles incurred due to rotation, by the local body reference frame, since\nthe last time the values were outputted by the device. The delta velocity (dvel) is the delta velocity incurred\ndue to motion, by the local body reference frame, since the last time the values were outputted by the device.\nThe frame of reference of these delta measurements are determined by the IntegrationFrame field in the\nDelta Theta and Delta Velocity Configuration Register (Register 82). These delta angles and delta velocities\nare calculated based upon the onboard coning and sculling integration performed onboard the sensor at the\nfull IMU rate (default 800Hz). The integration for both the delta angles and velocities are reset each time\neither of the values are either polled or sent out due to a scheduled asynchronous ASCII or binary output.\nDelta Theta and Delta Velocity values correctly capture the nonlinearities involved in measuring motion from\na rotating strapdown platform (as opposed to the older mechanically inertial navigation systems), thus\nproviding you with the ability to integrate velocity and angular rate at much lower speeds (say for example\n10 Hz, reducing bandwidth and computational complexity), while still maintaining the same numeric\nprecision as if you had performed the integration at the full IMU measurement rate of 800Hz. Time is given\nin seconds. Delta angles are given in degrees."); } },
916 {
"DeltaVel", vn::protocol::uart::ImuGroup::IMUGROUP_DELTAVEL,
917 []() { ImGui::TextUnformatted(
"Delta velocity.\n\nThe delta velocity (dvel) is the delta velocity incurred due to motion, since the last time the values were output\nby the device. The delta velocities are calculated based upon the onboard conning and sculling integration\nperformed onboard the sensor at the IMU sampling rate (nominally 800Hz). The integration for the delta\nvelocities are reset each time the values are either polled or sent out due to a scheduled asynchronous ASCII\nor binary output. Delta velocity is given in meters per second."); } },
918 {
"Mag", vn::protocol::uart::ImuGroup::IMUGROUP_MAG,
919 []() { ImGui::TextUnformatted(
"Compensated magnetic measurement.\n\nThe IMU compensated magnetic field measured units of Gauss, and given in the body frame. This\nmeasurement is compensated by the static calibration (individual factory calibration stored in flash), the user\ncompensation, and the dynamic calibration from the onboard Hard/Soft Iron estimator."); },
920 [](VectorNavModel ,
const vn::sensors::BinaryOutputRegister& , uint32_t ) {
return true; }, coupleImuFilterRates },
921 {
"Accel", vn::protocol::uart::ImuGroup::IMUGROUP_ACCEL,
922 []() { ImGui::TextUnformatted(
"Compensated acceleration measurement.\n\nThe compensated acceleration measured in units of m/s^2, and given in the body frame. This measurement\nis compensated by the static calibration (individual factory calibration stored in flash), the user\ncompensation, and the dynamic bias compensation from the onboard INS Kalman filter."); },
923 [](VectorNavModel ,
const vn::sensors::BinaryOutputRegister& , uint32_t ) {
return true; }, coupleImuFilterRates },
924 {
"AngularRate", vn::protocol::uart::ImuGroup::IMUGROUP_ANGULARRATE,
925 []() { ImGui::TextUnformatted(
"Compensated angular rate measurement.\n\nThe compensated angular rate measured in units of rad/s, and given in the body frame. This measurement\nis compensated by the static calibration (individual factor calibration stored in flash), the user compensation,\nand the dynamic bias compensation from the onboard INS Kalman filter."); },
926 [](VectorNavModel ,
const vn::sensors::BinaryOutputRegister& , uint32_t ) {
return true; }, coupleImuFilterRates },
930 {
"UTC", vn::protocol::uart::GpsGroup::GPSGROUP_UTC,
931 []() { ImGui::TextUnformatted(
"GPS UTC Time\n\nThe current UTC time. The year is given as a signed byte year offset from the year 2000. For example the\nyear 2013 would be given as year 13."); },
932 [](VectorNavModel ,
const vn::sensors::BinaryOutputRegister& , uint32_t ) {
return false; },
933 [](
VectorNavSensor* , vn::sensors::BinaryOutputRegister& , uint32_t& binaryField) { (
static_cast<vn::protocol::uart::GpsGroup
>(binaryField) & vn::protocol::uart::GpsGroup::GPSGROUP_UTC) && (binaryField |= vn::protocol::uart::GpsGroup::GPSGROUP_TIMEINFO); } },
934 {
"Tow", vn::protocol::uart::GpsGroup::GPSGROUP_TOW,
935 []() { ImGui::TextUnformatted(
"GPS time of week\n\nThe GPS time of week given in nano seconds."); },
936 [](VectorNavModel sensorModel,
const vn::sensors::BinaryOutputRegister& , uint32_t binaryField) {
return sensorModel == VectorNavModel::VN310
937 && !(
static_cast<vn::protocol::uart::GpsGroup
>(binaryField) & vn::protocol::uart::GpsGroup::GPSGROUP_POSLLA)
938 && !(
static_cast<vn::protocol::uart::GpsGroup
>(binaryField) & vn::protocol::uart::GpsGroup::GPSGROUP_POSECEF)
939 && !(
static_cast<vn::protocol::uart::GpsGroup
>(binaryField) & vn::protocol::uart::GpsGroup::GPSGROUP_VELNED)
940 && !(
static_cast<vn::protocol::uart::GpsGroup
>(binaryField) & vn::protocol::uart::GpsGroup::GPSGROUP_VELECEF)
941 && !(
static_cast<vn::protocol::uart::GpsGroup
>(binaryField) & vn::protocol::uart::GpsGroup::GPSGROUP_POSU)
942 && !(
static_cast<vn::protocol::uart::GpsGroup
>(binaryField) & vn::protocol::uart::GpsGroup::GPSGROUP_VELU); },
943 [](
VectorNavSensor* , vn::sensors::BinaryOutputRegister& bor, uint32_t& binaryField) { (
static_cast<vn::protocol::uart::GpsGroup
>(binaryField) & vn::protocol::uart::GpsGroup::GPSGROUP_TOW) && (binaryField |= vn::protocol::uart::GpsGroup::GPSGROUP_TIMEINFO) && ((bor.commonField & vn::protocol::uart::CommonGroup::COMMONGROUP_TIMESTARTUP) || (bor.timeField |= vn::protocol::uart::TimeGroup::TIMEGROUP_TIMESTARTUP)); } },
944 {
"Week", vn::protocol::uart::GpsGroup::GPSGROUP_WEEK,
945 []() { ImGui::TextUnformatted(
"GPS week\n\nThe current GPS week."); },
946 [](VectorNavModel sensorModel,
const vn::sensors::BinaryOutputRegister& , uint32_t binaryField) {
return sensorModel == VectorNavModel::VN310
947 && !(
static_cast<vn::protocol::uart::GpsGroup
>(binaryField) & vn::protocol::uart::GpsGroup::GPSGROUP_POSLLA)
948 && !(
static_cast<vn::protocol::uart::GpsGroup
>(binaryField) & vn::protocol::uart::GpsGroup::GPSGROUP_POSECEF)
949 && !(
static_cast<vn::protocol::uart::GpsGroup
>(binaryField) & vn::protocol::uart::GpsGroup::GPSGROUP_VELNED)
950 && !(
static_cast<vn::protocol::uart::GpsGroup
>(binaryField) & vn::protocol::uart::GpsGroup::GPSGROUP_VELECEF)
951 && !(
static_cast<vn::protocol::uart::GpsGroup
>(binaryField) & vn::protocol::uart::GpsGroup::GPSGROUP_POSU)
952 && !(
static_cast<vn::protocol::uart::GpsGroup
>(binaryField) & vn::protocol::uart::GpsGroup::GPSGROUP_VELU); },
953 [](
VectorNavSensor* , vn::sensors::BinaryOutputRegister& bor, uint32_t& binaryField) { (
static_cast<vn::protocol::uart::GpsGroup
>(binaryField) & vn::protocol::uart::GpsGroup::GPSGROUP_WEEK) && (binaryField |= vn::protocol::uart::GpsGroup::GPSGROUP_TIMEINFO) && ((bor.commonField & vn::protocol::uart::CommonGroup::COMMONGROUP_TIMESTARTUP) || (bor.timeField |= vn::protocol::uart::TimeGroup::TIMEGROUP_TIMESTARTUP)); } },
954 {
"NumSats", vn::protocol::uart::GpsGroup::GPSGROUP_NUMSATS,
955 []() { ImGui::TextUnformatted(
"Number of tracked satellites\n\nThe number of tracked GNSS satellites."); },
956 [](VectorNavModel sensorModel,
const vn::sensors::BinaryOutputRegister& , uint32_t ) {
return sensorModel == VectorNavModel::VN310; } },
957 {
"Fix", vn::protocol::uart::GpsGroup::GPSGROUP_FIX,
958 []() { ImGui::TextUnformatted(
"GNSS fix\n\nThe current GNSS fix.");
959 if (ImGui::BeginTable(
"VectorNavFixTooltip", 2, ImGuiTableFlags_Borders | ImGuiTableFlags_RowBg))
961 ImGui::TableSetupColumn(
"Value", ImGuiTableColumnFlags_WidthFixed);
962 ImGui::TableSetupColumn(
"Description", ImGuiTableColumnFlags_WidthFixed);
963 ImGui::TableHeadersRow();
965 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"0");
966 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"No fix");
968 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"1");
969 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"Time only");
971 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"2");
972 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"2D");
974 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"3");
975 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"3D");
977 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"4");
978 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"SBAS");
980 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"7");
981 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"RTK Float (only GNSS1)");
983 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"8");
984 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"RTK Fixed (only GNSS1)");
988 [](VectorNavModel sensorModel,
const vn::sensors::BinaryOutputRegister& , uint32_t binaryField) {
return sensorModel == VectorNavModel::VN310
989 && !(
static_cast<vn::protocol::uart::GpsGroup
>(binaryField) & vn::protocol::uart::GpsGroup::GPSGROUP_POSLLA)
990 && !(
static_cast<vn::protocol::uart::GpsGroup
>(binaryField) & vn::protocol::uart::GpsGroup::GPSGROUP_POSECEF)
991 && !(
static_cast<vn::protocol::uart::GpsGroup
>(binaryField) & vn::protocol::uart::GpsGroup::GPSGROUP_VELNED)
992 && !(
static_cast<vn::protocol::uart::GpsGroup
>(binaryField) & vn::protocol::uart::GpsGroup::GPSGROUP_VELECEF)
993 && !(
static_cast<vn::protocol::uart::GpsGroup
>(binaryField) & vn::protocol::uart::GpsGroup::GPSGROUP_POSU)
994 && !(
static_cast<vn::protocol::uart::GpsGroup
>(binaryField) & vn::protocol::uart::GpsGroup::GPSGROUP_VELU); } },
995 {
"PosLla", vn::protocol::uart::GpsGroup::GPSGROUP_POSLLA,
996 []() { ImGui::TextUnformatted(
"GNSS position (latitude, longitude, altitude)\n\nThe current GNSS position measurement given as the geodetic latitude, longitude and altitude above the\nellipsoid. The units are in [deg, deg, m] respectively."); },
997 [](VectorNavModel sensorModel,
const vn::sensors::BinaryOutputRegister& , uint32_t ) {
return sensorModel == VectorNavModel::VN310; },
998 [](
VectorNavSensor* , vn::sensors::BinaryOutputRegister& bor, uint32_t& binaryField) {
999 (
static_cast<vn::protocol::uart::GpsGroup
>(binaryField) & vn::protocol::uart::GpsGroup::GPSGROUP_POSLLA)
1000 && (binaryField |= vn::protocol::uart::GpsGroup::GPSGROUP_FIX)
1001 && (binaryField |= vn::protocol::uart::GpsGroup::GPSGROUP_TOW)
1002 && (binaryField |= vn::protocol::uart::GpsGroup::GPSGROUP_WEEK)
1003 && (binaryField |= vn::protocol::uart::GpsGroup::GPSGROUP_TIMEINFO);
1004 bor.timeField |= vn::protocol::uart::TimeGroup::TIMEGROUP_TIMESTARTUP;
1006 {
"PosEcef", vn::protocol::uart::GpsGroup::GPSGROUP_POSECEF,
1007 []() { ImGui::TextUnformatted(
"GNSS position (ECEF)\n\nThe current GNSS position given in the Earth centered Earth fixed (ECEF) coordinate frame, given in meters."); },
1008 [](VectorNavModel sensorModel,
const vn::sensors::BinaryOutputRegister& , uint32_t ) {
return sensorModel == VectorNavModel::VN310; },
1009 [](
VectorNavSensor* , vn::sensors::BinaryOutputRegister& bor, uint32_t& binaryField) {
1010 (
static_cast<vn::protocol::uart::GpsGroup
>(binaryField) & vn::protocol::uart::GpsGroup::GPSGROUP_POSECEF)
1011 && (binaryField |= vn::protocol::uart::GpsGroup::GPSGROUP_FIX)
1012 && (binaryField |= vn::protocol::uart::GpsGroup::GPSGROUP_TOW)
1013 && (binaryField |= vn::protocol::uart::GpsGroup::GPSGROUP_WEEK)
1014 && (binaryField |= vn::protocol::uart::GpsGroup::GPSGROUP_TIMEINFO);
1015 bor.timeField |= vn::protocol::uart::TimeGroup::TIMEGROUP_TIMESTARTUP;
1017 {
"VelNed", vn::protocol::uart::GpsGroup::GPSGROUP_VELNED,
1018 []() { ImGui::TextUnformatted(
"GNSS velocity (NED)\n\nThe current GNSS velocity in the North East Down (NED) coordinate frame, given in m/s."); },
1019 [](VectorNavModel sensorModel,
const vn::sensors::BinaryOutputRegister& , uint32_t ) {
return sensorModel == VectorNavModel::VN310; },
1020 [](
VectorNavSensor* , vn::sensors::BinaryOutputRegister& bor, uint32_t& binaryField) {
1021 (
static_cast<vn::protocol::uart::GpsGroup
>(binaryField) & vn::protocol::uart::GpsGroup::GPSGROUP_VELNED)
1022 && (binaryField |= vn::protocol::uart::GpsGroup::GPSGROUP_FIX)
1023 && (binaryField |= vn::protocol::uart::GpsGroup::GPSGROUP_TOW)
1024 && (binaryField |= vn::protocol::uart::GpsGroup::GPSGROUP_WEEK)
1025 && (binaryField |= vn::protocol::uart::GpsGroup::GPSGROUP_TIMEINFO);
1026 bor.timeField |= vn::protocol::uart::TimeGroup::TIMEGROUP_TIMESTARTUP;
1028 {
"VelEcef", vn::protocol::uart::GpsGroup::GPSGROUP_VELECEF,
1029 []() { ImGui::TextUnformatted(
"GNSS velocity (ECEF)\n\nThe current GNSS velocity in the Earth centered Earth fixed (ECEF) coordinate frame, given in m/s."); },
1030 [](VectorNavModel sensorModel,
const vn::sensors::BinaryOutputRegister& , uint32_t ) {
return sensorModel == VectorNavModel::VN310; },
1031 [](
VectorNavSensor* , vn::sensors::BinaryOutputRegister& bor, uint32_t& binaryField) {
1032 (
static_cast<vn::protocol::uart::GpsGroup
>(binaryField) & vn::protocol::uart::GpsGroup::GPSGROUP_VELECEF)
1033 && (binaryField |= vn::protocol::uart::GpsGroup::GPSGROUP_FIX)
1034 && (binaryField |= vn::protocol::uart::GpsGroup::GPSGROUP_TOW)
1035 && (binaryField |= vn::protocol::uart::GpsGroup::GPSGROUP_WEEK)
1036 && (binaryField |= vn::protocol::uart::GpsGroup::GPSGROUP_TIMEINFO);
1037 bor.timeField |= vn::protocol::uart::TimeGroup::TIMEGROUP_TIMESTARTUP;
1039 {
"PosU", vn::protocol::uart::GpsGroup::GPSGROUP_POSU,
1040 []() { ImGui::TextUnformatted(
"GNSS position uncertainty (NED)\n\nThe current GNSS position uncertainty in the North East Down (NED) coordinate frame, given in meters (1 Sigma)."); },
1041 [](VectorNavModel sensorModel,
const vn::sensors::BinaryOutputRegister& , uint32_t ) {
return sensorModel == VectorNavModel::VN310; },
1042 [](
VectorNavSensor* , vn::sensors::BinaryOutputRegister& bor, uint32_t& binaryField) {
1043 (
static_cast<vn::protocol::uart::GpsGroup
>(binaryField) & vn::protocol::uart::GpsGroup::GPSGROUP_POSU)
1044 && (binaryField |= vn::protocol::uart::GpsGroup::GPSGROUP_FIX)
1045 && (binaryField |= vn::protocol::uart::GpsGroup::GPSGROUP_TOW)
1046 && (binaryField |= vn::protocol::uart::GpsGroup::GPSGROUP_WEEK)
1047 && (binaryField |= vn::protocol::uart::GpsGroup::GPSGROUP_TIMEINFO);
1048 bor.timeField |= vn::protocol::uart::TimeGroup::TIMEGROUP_TIMESTARTUP;
1050 {
"VelU", vn::protocol::uart::GpsGroup::GPSGROUP_VELU,
1051 []() { ImGui::TextUnformatted(
"GNSS velocity uncertainty\n\nThe current GNSS velocity uncertainty, given in m/s (1 Sigma)."); },
1052 [](VectorNavModel sensorModel,
const vn::sensors::BinaryOutputRegister& , uint32_t ) {
return sensorModel == VectorNavModel::VN310; },
1053 [](
VectorNavSensor* , vn::sensors::BinaryOutputRegister& bor, uint32_t& binaryField) {
1054 (
static_cast<vn::protocol::uart::GpsGroup
>(binaryField) & vn::protocol::uart::GpsGroup::GPSGROUP_VELU)
1055 && (binaryField |= vn::protocol::uart::GpsGroup::GPSGROUP_FIX)
1056 && (binaryField |= vn::protocol::uart::GpsGroup::GPSGROUP_TOW)
1057 && (binaryField |= vn::protocol::uart::GpsGroup::GPSGROUP_WEEK)
1058 && (binaryField |= vn::protocol::uart::GpsGroup::GPSGROUP_TIMEINFO);
1059 bor.timeField |= vn::protocol::uart::TimeGroup::TIMEGROUP_TIMESTARTUP;
1061 {
"TimeU", vn::protocol::uart::GpsGroup::GPSGROUP_TIMEU,
1062 []() { ImGui::TextUnformatted(
"GNSS time uncertainty\n\nThe current GPS time uncertainty, given in seconds (1 Sigma)."); },
1063 [](VectorNavModel sensorModel,
const vn::sensors::BinaryOutputRegister& , uint32_t ) {
return sensorModel == VectorNavModel::VN310; },
1064 [](
VectorNavSensor* , vn::sensors::BinaryOutputRegister& , uint32_t& binaryField) { (
static_cast<vn::protocol::uart::GpsGroup
>(binaryField) & vn::protocol::uart::GpsGroup::GPSGROUP_TIMEU) && (binaryField |= vn::protocol::uart::GpsGroup::GPSGROUP_TIMEINFO); } },
1065 {
"TimeInfo", vn::protocol::uart::GpsGroup::GPSGROUP_TIMEINFO,
1066 []() { ImGui::TextUnformatted(
"GNSS time status and leap seconds\n\nFlags for valid GPS TOW, week number and UTC and current leap seconds.");
1067 if (ImGui::BeginTable(
"VectorNavTimeInfoTooltip", 3, ImGuiTableFlags_Borders | ImGuiTableFlags_RowBg | ImGuiTableFlags_SizingFixedFit | ImGuiTableFlags_NoHostExtendX, ImVec2(0.0F, 0.0F)))
1069 ImGui::TableSetupColumn(
"Bit Offset");
1070 ImGui::TableSetupColumn(
"Field");
1071 ImGui::TableSetupColumn(
"Description");
1072 ImGui::TableHeadersRow();
1074 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"0");
1075 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"timeOk");
1076 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"1 - GpsTow is valid");
1078 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"1");
1079 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"dateOk");
1080 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"1 - TimeGps and GpsWeek are valid");
1082 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"2");
1083 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"utcTimeValid");
1084 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"1 - UTC time is valid");
1086 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"3 - 7");
1087 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"resv");
1088 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"Reserved for future use");
1092 [](VectorNavModel sensorModel,
const vn::sensors::BinaryOutputRegister& , uint32_t binaryField) {
return sensorModel == VectorNavModel::VN310
1093 && !(
static_cast<vn::protocol::uart::GpsGroup
>(binaryField) & vn::protocol::uart::GpsGroup::GPSGROUP_TOW)
1094 && !(
static_cast<vn::protocol::uart::GpsGroup
>(binaryField) & vn::protocol::uart::GpsGroup::GPSGROUP_WEEK)
1095 && !(
static_cast<vn::protocol::uart::GpsGroup
>(binaryField) & vn::protocol::uart::GpsGroup::GPSGROUP_UTC)
1096 && !(
static_cast<vn::protocol::uart::GpsGroup
>(binaryField) & vn::protocol::uart::GpsGroup::GPSGROUP_TIMEU)
1097 && !(
static_cast<vn::protocol::uart::GpsGroup
>(binaryField) & vn::protocol::uart::GpsGroup::GPSGROUP_RAWMEAS); } },
1098 {
"DOP", vn::protocol::uart::GpsGroup::GPSGROUP_DOP,
1099 []() { ImGui::TextUnformatted(
"Dilution of precision"); },
1100 [](VectorNavModel sensorModel,
const vn::sensors::BinaryOutputRegister& , uint32_t ) {
return sensorModel == VectorNavModel::VN310; } },
1101 {
"SatInfo", vn::protocol::uart::GpsGroup::GPSGROUP_SATINFO,
1102 []() { ImGui::TextUnformatted(
"Satellite Information\n\nInformation and measurements pertaining to each GNSS satellite in view.\n\nSatInfo Element:");
1103 if (ImGui::BeginTable(
"VectorNavSatInfoTooltip", 2, ImGuiTableFlags_Borders | ImGuiTableFlags_RowBg | ImGuiTableFlags_SizingFixedFit | ImGuiTableFlags_NoHostExtendX, ImVec2(0.0F, 0.0F)))
1105 ImGui::TableSetupColumn(
"Name");
1106 ImGui::TableSetupColumn(
"Description");
1107 ImGui::TableHeadersRow();
1109 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"sys");
1110 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"GNSS constellation indicator. See table below for details.");
1112 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"svId");
1113 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"Space vehicle Id");
1115 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"flags");
1116 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"Tracking info flags. See table below for details.");
1118 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"cno");
1119 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"Carrier-to-noise density ratio (signal strength) [dB-Hz]");
1121 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"qi");
1122 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"Quality Indicator. See table below for details.");
1124 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"el");
1125 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"Elevation in degrees");
1127 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"az");
1128 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"Azimuth angle in degrees");
1132 ImGui::BeginChild(
"VectorNavSatInfoTooltipGNSSConstelationChild", ImVec2(230, 217));
1133 ImGui::TextUnformatted(
"\nGNSS constellation indicator:");
1134 if (ImGui::BeginTable(
"VectorNavSatInfoTooltipGNSSConstelation", 2, ImGuiTableFlags_Borders | ImGuiTableFlags_RowBg | ImGuiTableFlags_SizingFixedFit | ImGuiTableFlags_NoHostExtendX, ImVec2(0.0F, 0.0F)))
1136 ImGui::TableSetupColumn(
"Value");
1137 ImGui::TableSetupColumn(
"Description");
1138 ImGui::TableHeadersRow();
1140 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"0");
1141 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"GPS");
1143 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"1");
1144 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"SBAS");
1146 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"2");
1147 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"Galileo");
1149 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"3");
1150 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"BeiDou");
1152 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"4");
1153 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"IMES");
1155 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"5");
1156 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"QZSS");
1158 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"6");
1159 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"GLONASS");
1165 ImGui::BeginChild(
"VectorNavSatInfoTooltipFlagsChild", ImVec2(260, 217));
1166 ImGui::TextUnformatted(
"\nTracking info flags:");
1167 if (ImGui::BeginTable(
"VectorNavSatInfoTooltipFlags", 2, ImGuiTableFlags_Borders | ImGuiTableFlags_RowBg | ImGuiTableFlags_SizingFixedFit | ImGuiTableFlags_NoHostExtendX, ImVec2(0.0F, 0.0F)))
1169 ImGui::TableSetupColumn(
"Bit Offset");
1170 ImGui::TableSetupColumn(
"Description");
1171 ImGui::TableHeadersRow();
1173 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"0");
1174 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"Healthy");
1176 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"1");
1177 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"Almanac");
1179 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"2");
1180 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"Ephemeris");
1182 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"3");
1183 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"Differential Correction");
1185 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"4");
1186 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"Used for Navigation");
1188 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"5");
1189 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"Azimuth / Elevation Valid");
1191 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"6");
1192 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"Used for RTK");
1197 ImGui::TextUnformatted(
"\nQuality Indicators:");
1198 if (ImGui::BeginTable(
"VectorNavSatInfoTooltipQuality", 2, ImGuiTableFlags_Borders | ImGuiTableFlags_RowBg | ImGuiTableFlags_SizingFixedFit | ImGuiTableFlags_NoHostExtendX, ImVec2(0.0F, 0.0F)))
1200 ImGui::TableSetupColumn(
"Value");
1201 ImGui::TableSetupColumn(
"Description");
1202 ImGui::TableHeadersRow();
1204 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"0");
1205 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"No signal");
1207 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"1");
1208 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"Searching signal");
1210 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"2");
1211 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"Signal acquired");
1213 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"3");
1214 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"Signal detected but unstable");
1216 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"4");
1217 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"Code locked and time synchronized");
1219 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"5, 6, 7");
1220 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"Code and carrier locked and time synchronized");
1224 [](VectorNavModel sensorModel,
const vn::sensors::BinaryOutputRegister& , uint32_t ) {
return sensorModel == VectorNavModel::VN310; } },
1225 {
"RawMeas", vn::protocol::uart::GpsGroup::GPSGROUP_RAWMEAS,
1226 []() { ImGui::TextUnformatted(
"GNSS Raw Measurements.\n\nSatRaw Element:");
1227 if (ImGui::BeginTable(
"VectorNavSatRawTooltip", 2, ImGuiTableFlags_Borders | ImGuiTableFlags_RowBg | ImGuiTableFlags_SizingFixedFit | ImGuiTableFlags_NoHostExtendX, ImVec2(0.0F, 0.0F)))
1229 ImGui::TableSetupColumn(
"Name");
1230 ImGui::TableSetupColumn(
"Description");
1231 ImGui::TableHeadersRow();
1233 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"sys");
1234 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"GNSS constellation indicator. See table below for details.");
1236 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"svId");
1237 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"Space vehicle Id");
1239 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"freq");
1240 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"Frequency indicator. See table below for details.");
1242 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"chan");
1243 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"Channel Indicator. See table below for details.");
1245 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"slot");
1246 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"Slot Id");
1248 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"cno");
1249 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"Carrier-to-noise density ratio (signal strength) [dB-Hz]");
1251 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"flags");
1252 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"Tracking info flags. See table below for details.");
1254 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"pr");
1255 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"Pseudorange measurement in meters.");
1257 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"cp");
1258 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"Carrier phase measurement in cycles.");
1260 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"dp");
1261 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"Doppler measurement in Hz. Positive sign for approaching satellites.");
1265 ImGui::BeginChild(
"VectorNavSatRawTooltipGNSSConstelationChild", ImVec2(180, 217));
1266 ImGui::TextUnformatted(
"\nConstellation indicator:");
1267 if (ImGui::BeginTable(
"VectorNavSatRawTooltipGNSSConstelation", 2, ImGuiTableFlags_Borders | ImGuiTableFlags_RowBg | ImGuiTableFlags_SizingFixedFit | ImGuiTableFlags_NoHostExtendX, ImVec2(0.0F, 0.0F)))
1269 ImGui::TableSetupColumn(
"Value");
1270 ImGui::TableSetupColumn(
"Description");
1271 ImGui::TableHeadersRow();
1273 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"0");
1274 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"GPS");
1276 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"1");
1277 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"SBAS");
1279 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"2");
1280 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"Galileo");
1282 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"3");
1283 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"BeiDou");
1285 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"4");
1286 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"IMES");
1288 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"5");
1289 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"QZSS");
1291 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"6");
1292 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"GLONASS");
1298 ImGui::BeginChild(
"VectorNavSatRawTooltipFreqChild", ImVec2(270, 235));
1299 ImGui::TextUnformatted(
"\nFrequency indicator:");
1300 if (ImGui::BeginTable(
"VectorNavSatRawTooltipFreq", 2, ImGuiTableFlags_Borders | ImGuiTableFlags_RowBg | ImGuiTableFlags_SizingFixedFit | ImGuiTableFlags_NoHostExtendX, ImVec2(0.0F, 0.0F)))
1302 ImGui::TableSetupColumn(
"Value");
1303 ImGui::TableSetupColumn(
"Description");
1304 ImGui::TableHeadersRow();
1306 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"0");
1307 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"Rx Channel");
1309 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"1");
1310 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"L1(GPS,QZSS,SBAS), G1(GLO),\nE2-L1-E1(GAL), B1(BDS)");
1312 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"2");
1313 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"L2(GPS,QZSS), G2(GLO)");
1315 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"3");
1316 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"L5(GPS,QZSS,SBAS), E5a(GAL)");
1318 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"4");
1319 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"E6(GAL), LEX(QZSS), B3(BDS)");
1321 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"5");
1322 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"E5b(GAL), B2(BDS)");
1324 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"6");
1325 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"E5a+b(GAL)");
1331 ImGui::BeginChild(
"VectorNavSatRawTooltipFlagChild", ImVec2(255, 260));
1332 ImGui::TextUnformatted(
"\nTracking info flags:");
1333 if (ImGui::BeginTable(
"VectorNavSatRawTooltipFlags", 2, ImGuiTableFlags_Borders | ImGuiTableFlags_RowBg | ImGuiTableFlags_SizingFixedFit | ImGuiTableFlags_NoHostExtendX, ImVec2(0.0F, 0.0F)))
1335 ImGui::TableSetupColumn(
"Bit Offset");
1336 ImGui::TableSetupColumn(
"Description");
1337 ImGui::TableHeadersRow();
1339 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"0");
1340 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"Searching");
1342 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"1");
1343 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"Tracking");
1345 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"2");
1346 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"Time Valid");
1348 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"3");
1349 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"Code Lock");
1351 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"4");
1352 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"Phase Lock");
1354 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"5");
1355 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"Phase Half Ambiguity");
1357 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"6");
1358 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"Phase Half Sub");
1360 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"7");
1361 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"Phase Slip");
1363 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"8");
1364 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"Pseudorange Smoothed");
1369 ImGui::TextUnformatted(
"\nChannel indicator:");
1370 if (ImGui::BeginTable(
"VectorNavSatRawTooltipChan", 2, ImGuiTableFlags_Borders | ImGuiTableFlags_RowBg | ImGuiTableFlags_SizingFixedFit | ImGuiTableFlags_NoHostExtendX, ImVec2(0.0F, 0.0F)))
1372 ImGui::TableSetupColumn(
"Value");
1373 ImGui::TableSetupColumn(
"Description");
1374 ImGui::TableHeadersRow();
1376 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"0");
1377 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"P-code (GPS,GLO)");
1379 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"1");
1380 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"C/A-code (GPS,GLO,SBAS,QZSS), C chan (GAL)");
1382 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"2");
1383 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"semi-codeless (GPS)");
1385 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"3");
1386 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"Y-code (GPS)");
1388 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"4");
1389 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"M-code (GPS)");
1391 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"5");
1392 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"codeless (GPS)");
1394 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"6");
1395 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"A chan (GAL)");
1397 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"7");
1398 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"B chan (GAL)");
1400 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"8");
1401 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"I chan (GPS,GAL,QZSS,BDS)");
1403 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"9");
1404 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"Q chan (GPS,GAL,QZSS,BDS)");
1406 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"10");
1407 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"M chan (L2CGPS, L2CQZSS), D chan (GPS,QZSS)");
1409 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"11");
1410 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"L chan (L2CGPS, L2CQZSS), P chan (GPS,QZSS)");
1412 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"12");
1413 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"B+C chan (GAL), I+Q chan (GPS,GAL,QZSS,BDS),\nM+L chan (GPS,QZSS), D+P chan (GPS,QZSS)");
1415 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"13");
1416 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"based on Z-tracking (GPS)");
1418 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"14");
1419 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"A+B+C (GAL)");
1423 [](VectorNavModel sensorModel,
const vn::sensors::BinaryOutputRegister& , uint32_t ) {
return sensorModel == VectorNavModel::VN310; },
1424 [](
VectorNavSensor* , vn::sensors::BinaryOutputRegister& , uint32_t& binaryField) { (
static_cast<vn::protocol::uart::GpsGroup
>(binaryField) & vn::protocol::uart::GpsGroup::GPSGROUP_RAWMEAS) && (binaryField |= vn::protocol::uart::GpsGroup::GPSGROUP_TIMEINFO); } },
1428 {
"VpeStatus", vn::protocol::uart::AttitudeGroup::ATTITUDEGROUP_VPESTATUS,
1429 []() { ImGui::TextUnformatted(
"VPE Status bitfield\n\n");
1430 if (ImGui::BeginTable(
"VectorNavSatRawTooltipChan", 4, ImGuiTableFlags_Borders | ImGuiTableFlags_RowBg))
1432 ImGui::TableSetupColumn(
"Name", ImGuiTableColumnFlags_WidthFixed);
1433 ImGui::TableSetupColumn(
"Bit Offset", ImGuiTableColumnFlags_WidthFixed);
1434 ImGui::TableSetupColumn(
"Format", ImGuiTableColumnFlags_WidthFixed);
1435 ImGui::TableSetupColumn(
"Description", ImGuiTableColumnFlags_WidthFixed);
1436 ImGui::TableHeadersRow();
1438 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"AttitudeQuality");
1439 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"0");
1440 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"2 bits");
1441 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"Provides an indication of the quality of the attitude solution.\n0 - Excellent\n1 - Good\n2 - Bad\n3 - Not tracking");
1443 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"GyroSaturation");
1444 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"2");
1445 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"1 bits");
1446 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"At least one gyro axis is currently saturated.");
1448 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"GyroSaturationRecovery");
1449 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"3");
1450 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"1 bits");
1451 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"Filter is in the process of recovering from a gyro\nsaturation event.");
1453 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"MagDisturbance");
1454 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"4");
1455 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"2 bits");
1456 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"A magnetic DC disturbance has been detected.\n0 - No magnetic disturbance\n1 to 3 - Magnetic disturbance is present.");
1458 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"MagSaturation");
1459 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"6");
1460 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"1 bits");
1461 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"At least one magnetometer axis is currently saturated.");
1463 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"AccDisturbance");
1464 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"7");
1465 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"2 bits");
1466 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"A strong acceleration disturbance has been detected.\n0 - No acceleration disturbance.\n1 to 3 - Acceleration disturbance has been detected.");
1468 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"AccSaturation");
1469 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"9");
1470 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"1 bits");
1471 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"At least one accelerometer axis is currently saturated.");
1473 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"Reserved");
1474 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"10");
1475 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"1 bits");
1476 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"Reserved for internal use. May change state at run- time.");
1478 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"KnownMagDisturbance");
1479 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"11");
1480 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"1 bits");
1481 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"A known magnetic disturbance has been reported by\nthe user and the magnetometer is currently tuned out.");
1483 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"KnownAccelDisturbance");
1484 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"12");
1485 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"1 bits");
1486 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"A known acceleration disturbance has been reported by\nthe user and the accelerometer is currently tuned out.");
1488 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"Reserved");
1489 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"13");
1490 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"3 bits");
1491 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"Reserved for future use.");
1495 [](VectorNavModel sensorModel,
const vn::sensors::BinaryOutputRegister& , uint32_t ) {
return sensorModel == VectorNavModel::VN100_VN110; } },
1496 {
"YawPitchRoll", vn::protocol::uart::AttitudeGroup::ATTITUDEGROUP_YAWPITCHROLL,
1497 []() { ImGui::TextUnformatted(
"Yaw Pitch Roll\n\nThe estimated attitude Yaw, Pitch, and Roll angles measured in degrees. The attitude is given as a 3,2,1\nEuler angle sequence describing the body frame with respect to the local North East Down (NED) frame.\n\nYaw [+/- 180°]\nPitch [+/- 90°]\nRoll [+/- 180°]"); },
1498 [](VectorNavModel ,
const vn::sensors::BinaryOutputRegister& , uint32_t ) {
return true; },
1499 [](
VectorNavSensor* sensor, vn::sensors::BinaryOutputRegister& bor, uint32_t& binaryField) { (
static_cast<vn::protocol::uart::AttitudeGroup
>(binaryField) & vn::protocol::uart::AttitudeGroup::ATTITUDEGROUP_YAWPITCHROLL) && (bor.timeField |= vn::protocol::uart::TimeGroup::TIMEGROUP_TIMESTARTUP) && (bor.timeField |= vn::protocol::uart::TimeGroup::TIMEGROUP_TIMESTATUS)
1500 && ((sensor->_sensorModel == VectorNavModel::VN310) && (bor.timeField |= vn::protocol::uart::TimeGroup::TIMEGROUP_GPSWEEK) && (bor.timeField |= vn::protocol::uart::TimeGroup::TIMEGROUP_GPSTOW)); } },
1501 {
"Quaternion", vn::protocol::uart::AttitudeGroup::ATTITUDEGROUP_QUATERNION,
1502 []() { ImGui::TextUnformatted(
"Quaternion\n\nThe estimated attitude quaternion. The last term is the scalar value. The attitude is given as the body\nframe with respect to the local North East Down (NED) frame."); },
1503 [](VectorNavModel ,
const vn::sensors::BinaryOutputRegister& , uint32_t ) {
return true; },
1504 [](
VectorNavSensor* sensor, vn::sensors::BinaryOutputRegister& bor, uint32_t& binaryField) { (
static_cast<vn::protocol::uart::AttitudeGroup
>(binaryField) & vn::protocol::uart::AttitudeGroup::ATTITUDEGROUP_QUATERNION) && (bor.timeField |= vn::protocol::uart::TimeGroup::TIMEGROUP_TIMESTARTUP) && (bor.timeField |= vn::protocol::uart::TimeGroup::TIMEGROUP_TIMESTATUS)
1505 && ((sensor->_sensorModel == VectorNavModel::VN310) && (bor.timeField |= vn::protocol::uart::TimeGroup::TIMEGROUP_GPSWEEK) && (bor.timeField |= vn::protocol::uart::TimeGroup::TIMEGROUP_GPSTOW)); } },
1506 {
"DCM", vn::protocol::uart::AttitudeGroup::ATTITUDEGROUP_DCM,
1507 []() { ImGui::TextUnformatted(
"Directional Cosine Matrix\n\nThe estimated attitude directional cosine matrix given in column major order. The DCM maps vectors\nfrom the North East Down (NED) frame into the body frame."); },
1508 [](VectorNavModel ,
const vn::sensors::BinaryOutputRegister& , uint32_t ) {
return true; },
1509 [](
VectorNavSensor* sensor, vn::sensors::BinaryOutputRegister& bor, uint32_t& binaryField) { (
static_cast<vn::protocol::uart::AttitudeGroup
>(binaryField) & vn::protocol::uart::AttitudeGroup::ATTITUDEGROUP_DCM) && (bor.timeField |= vn::protocol::uart::TimeGroup::TIMEGROUP_TIMESTARTUP) && (bor.timeField |= vn::protocol::uart::TimeGroup::TIMEGROUP_TIMESTATUS)
1510 && ((sensor->_sensorModel == VectorNavModel::VN310) && (bor.timeField |= vn::protocol::uart::TimeGroup::TIMEGROUP_GPSWEEK) && (bor.timeField |= vn::protocol::uart::TimeGroup::TIMEGROUP_GPSTOW)); } },
1511 {
"MagNed", vn::protocol::uart::AttitudeGroup::ATTITUDEGROUP_MAGNED,
1512 []() { ImGui::TextUnformatted(
"Compensated magnetic (NED)\n\nThe current estimated magnetic field (Gauss), given in the North East Down (NED) frame. The current\nattitude solution is used to map the measurement from the measured body frame to the inertial (NED)\nframe. This measurement is compensated by both the static calibration (individual factory calibration\nstored in flash), and the dynamic calibration such as the user or onboard Hard/Soft Iron compensation\nregisters."); },
1513 [](VectorNavModel ,
const vn::sensors::BinaryOutputRegister& , uint32_t ) {
return true; },
1514 [](
VectorNavSensor* sensor, vn::sensors::BinaryOutputRegister& bor, uint32_t& binaryField) { (
static_cast<vn::protocol::uart::AttitudeGroup
>(binaryField) & vn::protocol::uart::AttitudeGroup::ATTITUDEGROUP_MAGNED) && (bor.timeField |= vn::protocol::uart::TimeGroup::TIMEGROUP_TIMESTARTUP) && (bor.timeField |= vn::protocol::uart::TimeGroup::TIMEGROUP_TIMESTATUS)
1515 && ((sensor->_sensorModel == VectorNavModel::VN310) && (bor.timeField |= vn::protocol::uart::TimeGroup::TIMEGROUP_GPSWEEK) && (bor.timeField |= vn::protocol::uart::TimeGroup::TIMEGROUP_GPSTOW)); } },
1516 {
"AccelNed", vn::protocol::uart::AttitudeGroup::ATTITUDEGROUP_ACCELNED,
1517 []() { ImGui::TextUnformatted(
"Compensated acceleration (NED)\n\nThe estimated acceleration (with gravity) reported in m/s^2, given in the North East Down (NED) frame.\nThe acceleration measurement has been bias compensated by the onboard INS filter. This measurement\nis attitude dependent, since the attitude is used to map the measurement from the body frame into the\ninertial (NED) frame. If the device is stationary and the INS filter is tracking, the measurement should be\nnominally equivalent to the gravity reference vector in the inertial frame (NED)."); },
1518 [](VectorNavModel ,
const vn::sensors::BinaryOutputRegister& , uint32_t ) {
return true; },
1519 [](
VectorNavSensor* sensor, vn::sensors::BinaryOutputRegister& bor, uint32_t& binaryField) { (
static_cast<vn::protocol::uart::AttitudeGroup
>(binaryField) & vn::protocol::uart::AttitudeGroup::ATTITUDEGROUP_ACCELNED) && (bor.timeField |= vn::protocol::uart::TimeGroup::TIMEGROUP_TIMESTARTUP) && (bor.timeField |= vn::protocol::uart::TimeGroup::TIMEGROUP_TIMESTATUS)
1520 && ((sensor->_sensorModel == VectorNavModel::VN310) && (bor.timeField |= vn::protocol::uart::TimeGroup::TIMEGROUP_GPSWEEK) && (bor.timeField |= vn::protocol::uart::TimeGroup::TIMEGROUP_GPSTOW)); } },
1521 {
"LinearAccelBody", vn::protocol::uart::AttitudeGroup::ATTITUDEGROUP_LINEARACCELBODY,
1522 []() { ImGui::TextUnformatted(
"Compensated linear acceleration (no gravity)\n\nThe estimated linear acceleration (without gravity) reported in m/s^2, and given in the body frame. The\nacceleration measurement has been bias compensated by the onboard INS filter, and the gravity\ncomponent has been removed using the current gravity reference vector model. This measurement is\nattitude dependent, since the attitude solution is required to map the gravity reference vector (known in\nthe inertial NED frame), into the body frame so that it can be removed from the measurement. If the\ndevice is stationary and the onboard INS filter is tracking, the measurement nominally will read 0 in all\nthree axes."); },
1523 [](VectorNavModel ,
const vn::sensors::BinaryOutputRegister& , uint32_t ) {
return true; },
1524 [](
VectorNavSensor* sensor, vn::sensors::BinaryOutputRegister& bor, uint32_t& binaryField) { (
static_cast<vn::protocol::uart::AttitudeGroup
>(binaryField) & vn::protocol::uart::AttitudeGroup::ATTITUDEGROUP_LINEARACCELBODY) && (bor.timeField |= vn::protocol::uart::TimeGroup::TIMEGROUP_TIMESTARTUP) && (bor.timeField |= vn::protocol::uart::TimeGroup::TIMEGROUP_TIMESTATUS)
1525 && ((sensor->_sensorModel == VectorNavModel::VN310) && (bor.timeField |= vn::protocol::uart::TimeGroup::TIMEGROUP_GPSWEEK) && (bor.timeField |= vn::protocol::uart::TimeGroup::TIMEGROUP_GPSTOW)); } },
1526 {
"LinearAccelNed", vn::protocol::uart::AttitudeGroup::ATTITUDEGROUP_LINEARACCELNED,
1527 []() { ImGui::TextUnformatted(
"Compensated linear acceleration (no gravity) (NED)\n\nThe estimated linear acceleration (without gravity) reported in m/s^2, and given in the North East Down\n(NED) frame. This measurement is attitude dependent as the attitude solution is used to map the\nmeasurement from the body frame into the inertial (NED) frame. This acceleration measurement has\nbeen bias compensated by the onboard INS filter, and the gravity component has been removed using the\ncurrent gravity reference vector estimate. If the device is stationary and the onboard INS filter is tracking,\nthe measurement nominally will read 0 in all three axes."); },
1528 [](VectorNavModel ,
const vn::sensors::BinaryOutputRegister& , uint32_t ) {
return true; },
1529 [](
VectorNavSensor* sensor, vn::sensors::BinaryOutputRegister& bor, uint32_t& binaryField) { (
static_cast<vn::protocol::uart::AttitudeGroup
>(binaryField) & vn::protocol::uart::AttitudeGroup::ATTITUDEGROUP_LINEARACCELNED) && (bor.timeField |= vn::protocol::uart::TimeGroup::TIMEGROUP_TIMESTARTUP) && (bor.timeField |= vn::protocol::uart::TimeGroup::TIMEGROUP_TIMESTATUS)
1530 && ((sensor->_sensorModel == VectorNavModel::VN310) && (bor.timeField |= vn::protocol::uart::TimeGroup::TIMEGROUP_GPSWEEK) && (bor.timeField |= vn::protocol::uart::TimeGroup::TIMEGROUP_GPSTOW)); } },
1531 {
"YprU", vn::protocol::uart::AttitudeGroup::ATTITUDEGROUP_YPRU,
1532 []() { ImGui::TextUnformatted(
"Yaw Pitch Roll uncertainty\n\nThe estimated attitude (Yaw, Pitch, Roll) uncertainty (1 Sigma), reported in degrees.\n\nThe estimated attitude (YprU) field is not valid when the INS Scenario mode in the INS Basic\nConfiguration register is set to AHRS mode. See the INS Basic Configuration Register in the INS\nsection for more details."); },
1533 [](VectorNavModel ,
const vn::sensors::BinaryOutputRegister& , uint32_t ) {
return true; },
1534 [](
VectorNavSensor* sensor, vn::sensors::BinaryOutputRegister& bor, uint32_t& binaryField) { (
static_cast<vn::protocol::uart::AttitudeGroup
>(binaryField) & vn::protocol::uart::AttitudeGroup::ATTITUDEGROUP_YPRU) && (bor.timeField |= vn::protocol::uart::TimeGroup::TIMEGROUP_TIMESTARTUP) && (bor.timeField |= vn::protocol::uart::TimeGroup::TIMEGROUP_TIMESTATUS)
1535 && ((sensor->_sensorModel == VectorNavModel::VN310) && (bor.timeField |= vn::protocol::uart::TimeGroup::TIMEGROUP_GPSWEEK) && (bor.timeField |= vn::protocol::uart::TimeGroup::TIMEGROUP_GPSTOW)); } },
1539 {
"InsStatus", vn::protocol::uart::InsGroup::INSGROUP_INSSTATUS,
1540 []() { ImGui::TextUnformatted(
"Ins Status bitfield:");
1541 if (ImGui::BeginTable(
"VectorNavInsStatusTooltip", 4, ImGuiTableFlags_Borders | ImGuiTableFlags_RowBg))
1543 ImGui::TableSetupColumn(
"Name", ImGuiTableColumnFlags_WidthFixed);
1544 ImGui::TableSetupColumn(
"Bit Offset", ImGuiTableColumnFlags_WidthFixed);
1545 ImGui::TableSetupColumn(
"Format", ImGuiTableColumnFlags_WidthFixed);
1546 ImGui::TableSetupColumn(
"Description", ImGuiTableColumnFlags_WidthFixed);
1547 ImGui::TableHeadersRow();
1549 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"Mode");
1550 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"0");
1551 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"2 bits");
1552 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"Indicates the current mode of the INS filter.\n\n0 = Not tracking. GNSS Compass is initializing. Output heading is based on\nmagnetometer measurements.\n1 = Aligning.\nINS Filter is dynamically aligning.\nFor a stationary startup: GNSS Compass has initialized and INS Filter is\naligning from the magnetic heading to the GNSS Compass heading.\nFor a dynamic startup: INS Filter has initialized and is dynamically aligning to\nTrue North heading.\nIn operation, if the INS Filter drops from INS Mode 2 back down to 1, the\nattitude uncertainty has increased above 2 degrees.\n2 = Tracking. The INS Filter is tracking and operating within specification.\n3 = Loss of GNSS. A GNSS outage has lasted more than 45 seconds. The INS\nFilter will no longer update the position and velocity outputs, but the attitude\nremains valid.");
1554 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"GpsFix");
1555 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"2");
1556 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"1 bits");
1557 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"Indicates whether the GNSS has a proper fix.");
1559 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"Error");
1560 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"3");
1561 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"4 bits");
1562 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"Sensor measurement error code. See table below.\n0 = No errors detected.");
1564 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"Reserved");
1565 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"7");
1566 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"1 bits");
1567 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"Reserved for internal use. May toggle state during runtime and should be ignored.");
1569 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"GpsHeadingIns");
1570 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"8");
1571 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"1 bits");
1572 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"In stationary operation, if set the INS Filter has fully aligned to the GNSS\nCompass solution.\nIn dynamic operation, the GNSS Compass solution is currently aiding the INS\nFilter heading solution.");
1574 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"GpsCompass");
1575 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"9");
1576 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"1 bits");
1577 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"Indicates if the GNSS compass is operational and reporting a heading\nsolution.");
1579 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"Reserved");
1580 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"10");
1581 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"6 bits");
1582 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"Reserved for internal use. These bits will toggle state and should be ignored.");
1586 ImGui::TextUnformatted(
"\nError Bitfield:");
1587 if (ImGui::BeginTable(
"VectorNavInsStatusTooltipError", 2, ImGuiTableFlags_Borders | ImGuiTableFlags_RowBg | ImGuiTableFlags_SizingFixedFit | ImGuiTableFlags_NoHostExtendX, ImVec2(0.0F, 0.0F)))
1589 ImGui::TableSetupColumn(
"Name");
1590 ImGui::TableSetupColumn(
"Description");
1591 ImGui::TableHeadersRow();
1593 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"Reserved");
1594 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"Reserved for future use and not currently used.");
1596 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"IMU Error");
1597 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"High if IMU communication error is detected.");
1599 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"Mag/Pres Error");
1600 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"High if Magnetometer or Pressure sensor error is detected.");
1602 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"GNSS Error");
1603 ImGui::TableNextColumn(); ImGui::TextUnformatted(
"High if GNSS communication error is detected.");
1607 [](VectorNavModel sensorModel,
const vn::sensors::BinaryOutputRegister& , uint32_t ) {
return sensorModel == VectorNavModel::VN310; },
1608 [](
VectorNavSensor* , vn::sensors::BinaryOutputRegister& bor, uint32_t& binaryField) { (
static_cast<vn::protocol::uart::InsGroup
>(binaryField) & vn::protocol::uart::InsGroup::INSGROUP_INSSTATUS) && (bor.timeField |= vn::protocol::uart::TimeGroup::TIMEGROUP_TIMESTARTUP) && (bor.timeField |= vn::protocol::uart::TimeGroup::TIMEGROUP_TIMESTATUS) && (bor.timeField |= vn::protocol::uart::TimeGroup::TIMEGROUP_GPSWEEK) && (bor.timeField |= vn::protocol::uart::TimeGroup::TIMEGROUP_GPSTOW); } },
1609 {
"PosLla", vn::protocol::uart::InsGroup::INSGROUP_POSLLA,
1610 []() { ImGui::TextUnformatted(
"Ins Position (latitude, longitude, altitude)\n\nThe estimated position given as latitude, longitude, and altitude given in [deg, deg, m] respectively."); },
1611 [](VectorNavModel sensorModel,
const vn::sensors::BinaryOutputRegister& , uint32_t ) {
return sensorModel == VectorNavModel::VN310; },
1612 [](
VectorNavSensor* , vn::sensors::BinaryOutputRegister& bor, uint32_t& binaryField) { (
static_cast<vn::protocol::uart::InsGroup
>(binaryField) & vn::protocol::uart::InsGroup::INSGROUP_POSLLA) && (bor.timeField |= vn::protocol::uart::TimeGroup::TIMEGROUP_TIMESTARTUP) && (bor.timeField |= vn::protocol::uart::TimeGroup::TIMEGROUP_TIMESTATUS) && (bor.timeField |= vn::protocol::uart::TimeGroup::TIMEGROUP_GPSWEEK) && (bor.timeField |= vn::protocol::uart::TimeGroup::TIMEGROUP_GPSTOW); } },
1613 {
"PosEcef", vn::protocol::uart::InsGroup::INSGROUP_POSECEF,
1614 []() { ImGui::TextUnformatted(
"Ins Position (ECEF)\n\nThe estimated position given in the Earth centered Earth fixed (ECEF) frame, reported in meters."); },
1615 [](VectorNavModel sensorModel,
const vn::sensors::BinaryOutputRegister& , uint32_t ) {
return sensorModel == VectorNavModel::VN310; },
1616 [](
VectorNavSensor* , vn::sensors::BinaryOutputRegister& bor, uint32_t& binaryField) { (
static_cast<vn::protocol::uart::InsGroup
>(binaryField) & vn::protocol::uart::InsGroup::INSGROUP_POSECEF) && (bor.timeField |= vn::protocol::uart::TimeGroup::TIMEGROUP_TIMESTARTUP) && (bor.timeField |= vn::protocol::uart::TimeGroup::TIMEGROUP_TIMESTATUS) && (bor.timeField |= vn::protocol::uart::TimeGroup::TIMEGROUP_GPSWEEK) && (bor.timeField |= vn::protocol::uart::TimeGroup::TIMEGROUP_GPSTOW); } },
1617 {
"VelBody", vn::protocol::uart::InsGroup::INSGROUP_VELBODY,
1618 []() { ImGui::TextUnformatted(
"Ins Velocity (Body)\n\nThe estimated velocity in the body frame, given in m/s."); },
1619 [](VectorNavModel sensorModel,
const vn::sensors::BinaryOutputRegister& , uint32_t ) {
return sensorModel == VectorNavModel::VN310; },
1620 [](
VectorNavSensor* , vn::sensors::BinaryOutputRegister& bor, uint32_t& binaryField) { (
static_cast<vn::protocol::uart::InsGroup
>(binaryField) & vn::protocol::uart::InsGroup::INSGROUP_VELBODY) && (bor.timeField |= vn::protocol::uart::TimeGroup::TIMEGROUP_TIMESTARTUP) && (bor.timeField |= vn::protocol::uart::TimeGroup::TIMEGROUP_TIMESTATUS) && (bor.timeField |= vn::protocol::uart::TimeGroup::TIMEGROUP_GPSWEEK) && (bor.timeField |= vn::protocol::uart::TimeGroup::TIMEGROUP_GPSTOW); } },
1621 {
"VelNed", vn::protocol::uart::InsGroup::INSGROUP_VELNED,
1622 []() { ImGui::TextUnformatted(
"Ins Velocity (NED)\n\nThe estimated velocity in the North East Down (NED) frame, given in m/s."); },
1623 [](VectorNavModel sensorModel,
const vn::sensors::BinaryOutputRegister& , uint32_t ) {
return sensorModel == VectorNavModel::VN310; },
1624 [](
VectorNavSensor* , vn::sensors::BinaryOutputRegister& bor, uint32_t& binaryField) { (
static_cast<vn::protocol::uart::InsGroup
>(binaryField) & vn::protocol::uart::InsGroup::INSGROUP_VELNED) && (bor.timeField |= vn::protocol::uart::TimeGroup::TIMEGROUP_TIMESTARTUP) && (bor.timeField |= vn::protocol::uart::TimeGroup::TIMEGROUP_TIMESTATUS) && (bor.timeField |= vn::protocol::uart::TimeGroup::TIMEGROUP_GPSWEEK) && (bor.timeField |= vn::protocol::uart::TimeGroup::TIMEGROUP_GPSTOW); } },
1625 {
"VelEcef", vn::protocol::uart::InsGroup::INSGROUP_VELECEF,
1626 []() { ImGui::TextUnformatted(
"Ins Velocity (ECEF)\n\nThe estimated velocity in the Earth centered Earth fixed (ECEF) frame, given in m/s."); },
1627 [](VectorNavModel sensorModel,
const vn::sensors::BinaryOutputRegister& , uint32_t ) {
return sensorModel == VectorNavModel::VN310; },
1628 [](
VectorNavSensor* , vn::sensors::BinaryOutputRegister& bor, uint32_t& binaryField) { (
static_cast<vn::protocol::uart::InsGroup
>(binaryField) & vn::protocol::uart::InsGroup::INSGROUP_VELECEF) && (bor.timeField |= vn::protocol::uart::TimeGroup::TIMEGROUP_TIMESTARTUP) && (bor.timeField |= vn::protocol::uart::TimeGroup::TIMEGROUP_TIMESTATUS) && (bor.timeField |= vn::protocol::uart::TimeGroup::TIMEGROUP_GPSWEEK) && (bor.timeField |= vn::protocol::uart::TimeGroup::TIMEGROUP_GPSTOW); } },
1629 {
"MagEcef", vn::protocol::uart::InsGroup::INSGROUP_MAGECEF,
1630 []() { ImGui::TextUnformatted(
"Compensated magnetic (ECEF)\n\nThe compensated magnetic measurement in the Earth centered Earth fixed (ECEF) frame, given in Gauss."); },
1631 [](VectorNavModel sensorModel,
const vn::sensors::BinaryOutputRegister& , uint32_t ) {
return sensorModel == VectorNavModel::VN310; },
1632 [](
VectorNavSensor* , vn::sensors::BinaryOutputRegister& bor, uint32_t& binaryField) { (
static_cast<vn::protocol::uart::InsGroup
>(binaryField) & vn::protocol::uart::InsGroup::INSGROUP_MAGECEF) && (bor.timeField |= vn::protocol::uart::TimeGroup::TIMEGROUP_TIMESTARTUP) && (bor.timeField |= vn::protocol::uart::TimeGroup::TIMEGROUP_TIMESTATUS) && (bor.timeField |= vn::protocol::uart::TimeGroup::TIMEGROUP_GPSWEEK) && (bor.timeField |= vn::protocol::uart::TimeGroup::TIMEGROUP_GPSTOW); } },
1633 {
"AccelEcef", vn::protocol::uart::InsGroup::INSGROUP_ACCELECEF,
1634 []() { ImGui::TextUnformatted(
"Compensated acceleration (ECEF)\n\nThe estimated acceleration (with gravity) reported in m/s^2, given in the Earth centered Earth fixed (ECEF)\nframe. The acceleration measurement has been bias compensated by the onboard INS filter. This\nmeasurement is attitude dependent, since the attitude is used to map the measurement from the body frame\ninto the inertial (ECEF) frame. If the device is stationary and the INS filter is tracking, the measurement\nshould be nominally equivalent to the gravity reference vector in the inertial frame (ECEF)."); },
1635 [](VectorNavModel sensorModel,
const vn::sensors::BinaryOutputRegister& , uint32_t ) {
return sensorModel == VectorNavModel::VN310; },
1636 [](
VectorNavSensor* , vn::sensors::BinaryOutputRegister& bor, uint32_t& binaryField) { (
static_cast<vn::protocol::uart::InsGroup
>(binaryField) & vn::protocol::uart::InsGroup::INSGROUP_ACCELECEF) && (bor.timeField |= vn::protocol::uart::TimeGroup::TIMEGROUP_TIMESTARTUP) && (bor.timeField |= vn::protocol::uart::TimeGroup::TIMEGROUP_TIMESTATUS) && (bor.timeField |= vn::protocol::uart::TimeGroup::TIMEGROUP_GPSWEEK) && (bor.timeField |= vn::protocol::uart::TimeGroup::TIMEGROUP_GPSTOW); } },
1637 {
"LinearAccelEcef", vn::protocol::uart::InsGroup::INSGROUP_LINEARACCELECEF,
1638 []() { ImGui::TextUnformatted(
"Compensated linear acceleration (no gravity) (ECEF)\n\nThe estimated linear acceleration (without gravity) reported in m/s^2, and given in the Earth centered Earth\nfixed (ECEF) frame. This measurement is attitude dependent as the attitude solution is used to map the\nmeasurement from the body frame into the inertial (ECEF) frame. This acceleration measurement has been\nbias compensated by the onboard INS filter, and the gravity component has been removed using the current\ngravity reference vector estimate. If the device is stationary and the onboard INS filter is tracking, the\nmeasurement will nominally read 0 in all three axes."); },
1639 [](VectorNavModel sensorModel,
const vn::sensors::BinaryOutputRegister& , uint32_t ) {
return sensorModel == VectorNavModel::VN310; },
1640 [](
VectorNavSensor* , vn::sensors::BinaryOutputRegister& bor, uint32_t& binaryField) { (
static_cast<vn::protocol::uart::InsGroup
>(binaryField) & vn::protocol::uart::InsGroup::INSGROUP_LINEARACCELECEF) && (bor.timeField |= vn::protocol::uart::TimeGroup::TIMEGROUP_TIMESTARTUP) && (bor.timeField |= vn::protocol::uart::TimeGroup::TIMEGROUP_TIMESTATUS) && (bor.timeField |= vn::protocol::uart::TimeGroup::TIMEGROUP_GPSWEEK) && (bor.timeField |= vn::protocol::uart::TimeGroup::TIMEGROUP_GPSTOW); } },
1641 {
"PosU", vn::protocol::uart::InsGroup::INSGROUP_POSU,
1642 []() { ImGui::TextUnformatted(
"Ins Position Uncertainty\n\nThe estimated uncertainty (1 Sigma) in the current position estimate, given in meters."); },
1643 [](VectorNavModel sensorModel,
const vn::sensors::BinaryOutputRegister& , uint32_t ) {
return sensorModel == VectorNavModel::VN310; },
1644 [](
VectorNavSensor* , vn::sensors::BinaryOutputRegister& bor, uint32_t& binaryField) { (
static_cast<vn::protocol::uart::InsGroup
>(binaryField) & vn::protocol::uart::InsGroup::INSGROUP_POSU) && (bor.timeField |= vn::protocol::uart::TimeGroup::TIMEGROUP_TIMESTARTUP) && (bor.timeField |= vn::protocol::uart::TimeGroup::TIMEGROUP_TIMESTATUS) && (bor.timeField |= vn::protocol::uart::TimeGroup::TIMEGROUP_GPSWEEK) && (bor.timeField |= vn::protocol::uart::TimeGroup::TIMEGROUP_GPSTOW); } },
1645 {
"VelU", vn::protocol::uart::InsGroup::INSGROUP_VELU,
1646 []() { ImGui::TextUnformatted(
"Ins Velocity Uncertainty\n\nThe estimated uncertainty (1 Sigma) in the current velocity estimate, given in m/s."); },
1647 [](VectorNavModel sensorModel,
const vn::sensors::BinaryOutputRegister& , uint32_t ) {
return sensorModel == VectorNavModel::VN310; },
1648 [](
VectorNavSensor* , vn::sensors::BinaryOutputRegister& bor, uint32_t& binaryField) { (
static_cast<vn::protocol::uart::InsGroup
>(binaryField) & vn::protocol::uart::InsGroup::INSGROUP_VELU) && (bor.timeField |= vn::protocol::uart::TimeGroup::TIMEGROUP_TIMESTARTUP) && (bor.timeField |= vn::protocol::uart::TimeGroup::TIMEGROUP_TIMESTATUS) && (bor.timeField |= vn::protocol::uart::TimeGroup::TIMEGROUP_GPSWEEK) && (bor.timeField |= vn::protocol::uart::TimeGroup::TIMEGROUP_GPSTOW); } },
1668 std::map<int, int, std::greater<>> divFreq;
1673 if (!divFreq.contains(divider)
1676 divFreq[divider] = freq;
1679 std::vector<uint16_t> divs;
1680 std::vector<std::string> freqs;
1681 for (
auto& [divider, freq] : divFreq)
1683 divs.push_back(
static_cast<uint16_t
>(divider));
1684 freqs.push_back(std::to_string(freq) +
" Hz");
1685 LOG_DATA(
"VectorNavSensor: RateDivisor {} = {}", divs.back(), freqs.back());
1687 return std::make_pair(divs, freqs);
1698 return "VectorNavSensor";
1708 return "Data Provider";
1714 ImGui::Combo(
"Sensor", &sensorModel,
"VN-100 / VN-110\0VN-310\0\0"))
1754 if (i == 0 || i == 9 ) {
continue; }
1757 if ((i == 2 || i == 3 )
1759 && binaryOutput.timeField & vn::protocol::uart::TIMEGROUP_TIMESTARTUP
1762 binaryOutput.timeField |= vn::protocol::uart::TimeGroup(item.flagsValue);
1766 if (!item.isEnabled(
_sensorModel, binaryOutput,
static_cast<uint32_t
>(binaryOutput.timeField)))
1768 binaryOutput.timeField &=
~vn::protocol::uart::TimeGroup(item.flagsValue);
1773 if (!item.isEnabled(
_sensorModel, binaryOutput,
static_cast<uint32_t
>(binaryOutput.imuField)))
1775 binaryOutput.imuField &=
~vn::protocol::uart::ImuGroup(item.flagsValue);
1780 if (!item.isEnabled(
_sensorModel, binaryOutput,
static_cast<uint32_t
>(binaryOutput.gpsField)))
1782 binaryOutput.gpsField &=
~vn::protocol::uart::GpsGroup(item.flagsValue);
1784 if (!item.isEnabled(
_sensorModel, binaryOutput,
static_cast<uint32_t
>(binaryOutput.gps2Field)))
1786 binaryOutput.gps2Field &=
~vn::protocol::uart::GpsGroup(item.flagsValue);
1791 if (!item.isEnabled(
_sensorModel, binaryOutput,
static_cast<uint32_t
>(binaryOutput.attitudeField)))
1793 binaryOutput.attitudeField &=
~vn::protocol::uart::AttitudeGroup(item.flagsValue);
1798 if (!item.isEnabled(
_sensorModel, binaryOutput,
static_cast<uint32_t
>(binaryOutput.insField)))
1800 binaryOutput.insField &=
~vn::protocol::uart::InsGroup(item.flagsValue);
1817 "- \"COM1\" (Windows format for physical and virtual (USB) serial port)\n"
1818 "- \"/dev/ttyS1\" (Linux format for physical serial port)\n"
1819 "- \"/dev/ttyUSB0\" (Linux format for virtual (USB) serial port)\n"
1820 "- \"/dev/tty.usbserial-FTXXXXXX\" (Mac OS X format for virtual (USB) serial port)\n"
1821 "- \"/dev/ttyS0\" (CYGWIN format. Usually the Windows COM port number minus 1. This would connect to COM1)");
1824 if (!isNodeInitialized)
1826 ImGui::BeginDisabled();
1828 if (ImGui::Button(
"Write settings"))
1832 _vs.writeSettings();
1834 catch (
const std::exception& e)
1836 LOG_ERROR(
"{}: Write settings threw an exception: {}",
nameId(), e.what());
1839 if (!isNodeInitialized)
1841 ImGui::EndDisabled();
1843 if (ImGui::IsItemHovered())
1845 ImGui::SetTooltip(
"This command will write the current register settings into non-volatile memory. Once the settings are stored\n"
1846 "in non-volatile (Flash) memory, the VN-310E module can be power cycled or reset, and the register will be\n"
1847 "reloaded from non-volatile memory.\n\n"
1848 "Due to limitations in the flash write speed the write settings command takes ~ 500ms to\n"
1849 "complete. Any commands that are sent to the sensor during this time will be responded to after\n"
1850 "the operation is complete.\n\n"
1851 "The sensor must be stationary when issuing a Write Settings Command otherwise a Reset\n"
1852 "command must also be issued to prevent the Kalman Filter from diverging during the write\n"
1853 "settings process.\n\n"
1854 "A write settings command is automatically send after initializing the node.");
1857 if (!isNodeInitialized)
1859 ImGui::BeginDisabled();
1861 if (ImGui::Button(
"Restore factory settings"))
1865 _vs.restoreFactorySettings();
1867 catch (
const std::exception& e)
1869 LOG_ERROR(
"{}: Restore factory settings threw an exception: {}",
nameId(), e.what());
1872 if (!isNodeInitialized)
1874 ImGui::EndDisabled();
1876 if (ImGui::IsItemHovered())
1878 ImGui::SetTooltip(
"This command will restore the VN-310E module's factory default settings and will reset the module. There\n"
1879 "are no parameters for this command. The module will respond to this command before restoring the factory\n"
1883 if (!isNodeInitialized)
1885 ImGui::BeginDisabled();
1887 if (ImGui::Button(
"Reset sensor"))
1893 catch (
const std::exception& e)
1895 LOG_ERROR(
"{}: Resetting threw an exception: {}",
nameId(), e.what());
1898 if (!isNodeInitialized)
1900 ImGui::EndDisabled();
1902 if (ImGui::IsItemHovered())
1904 ImGui::SetTooltip(
"This command will reset the module. There are no parameters required for this command. The module will\n"
1905 "first respond to the command and will then perform a reset. Upon a reset all registers will be reloaded with\n"
1906 "the values saved in non-volatile memory. If no values are stored in non-volatile memory, the device will default\n"
1907 "to factory settings. Also upon reset the VN-310E will re-initialize its Kalman filter, thus the filter will take a\n"
1908 "few seconds to completely converge on the correct attitude and correct for gyro bias.");
1915 ImGui::SetNextItemOpen(
true, ImGuiCond_FirstUseEver);
1916 if (ImGui::CollapsingHeader(fmt::format(
"System Module##{}",
size_t(
id)).c_str()))
1920 std::array<const char*, 10> items = {
"Fastest",
"9600",
"19200",
"38400",
"57600",
"115200",
"128000",
"230400",
"460800",
"921600" };
1928 if (ImGui::TreeNode(fmt::format(
"Async Ascii Output##{}",
size_t(
id)).c_str()))
1930 std::vector<std::pair<vn::protocol::uart::AsciiAsync, const char*>> asciiAsyncItems{
1931 { vn::protocol::uart::AsciiAsync::VNOFF,
"Asynchronous output turned off" },
1932 { vn::protocol::uart::AsciiAsync::VNYPR,
"Yaw, Pitch, Roll" },
1933 { vn::protocol::uart::AsciiAsync::VNQTN,
"Quaternion" },
1934 { vn::protocol::uart::AsciiAsync::VNQMR,
"Quaternion, Magnetic, Acceleration and Angular Rates" },
1935 { vn::protocol::uart::AsciiAsync::VNMAG,
"Magnetic Measurements" },
1936 { vn::protocol::uart::AsciiAsync::VNACC,
"Acceleration Measurements" },
1937 { vn::protocol::uart::AsciiAsync::VNGYR,
"Angular Rate Measurements" },
1938 { vn::protocol::uart::AsciiAsync::VNMAR,
"Magnetic, Acceleration, and Angular Rate Measurements" },
1939 { vn::protocol::uart::AsciiAsync::VNYMR,
"Yaw, Pitch, Roll, Magnetic, Acceleration, and Angular Rate Measurements" },
1940 { vn::protocol::uart::AsciiAsync::VNYBA,
"Yaw, Pitch, Roll, Body True Acceleration, and Angular Rates" },
1941 { vn::protocol::uart::AsciiAsync::VNYIA,
"Yaw, Pitch, Roll, Inertial True Acceleration, and Angular Rates" },
1942 { vn::protocol::uart::AsciiAsync::VNIMU,
"IMU Measurements" }
1946 asciiAsyncItems.emplace_back(vn::protocol::uart::AsciiAsync::VNGPS,
"GNSS LLA");
1947 asciiAsyncItems.emplace_back(vn::protocol::uart::AsciiAsync::VNGPE,
"GNSS ECEF");
1948 asciiAsyncItems.emplace_back(vn::protocol::uart::AsciiAsync::VNINS,
"INS LLA");
1949 asciiAsyncItems.emplace_back(vn::protocol::uart::AsciiAsync::VNINE,
"INS ECEF");
1950 asciiAsyncItems.emplace_back(vn::protocol::uart::AsciiAsync::VNISL,
"INS LLA 2");
1951 asciiAsyncItems.emplace_back(vn::protocol::uart::AsciiAsync::VNISE,
"INS ECEF 2");
1953 asciiAsyncItems.emplace_back(vn::protocol::uart::AsciiAsync::VNDTV,
"Delta theta and delta velocity");
1956 asciiAsyncItems.emplace_back(vn::protocol::uart::AsciiAsync::VNG2S,
"GNSS2 LLA");
1957 asciiAsyncItems.emplace_back(vn::protocol::uart::AsciiAsync::VNG2E,
"GNSS2 ECEF");
1960 if (ImGui::BeginCombo(fmt::format(
"Async Ascii Output Type##{}",
size_t(
id)).c_str(), vn::protocol::uart::str(
_asyncDataOutputType).c_str()))
1962 for (
const auto& asciiAsyncItem : asciiAsyncItems)
1965 if (ImGui::Selectable(vn::protocol::uart::str(asciiAsyncItem.first).c_str(), isSelected))
1976 catch (
const std::exception& e)
1978 LOG_ERROR(
"{}: Could not configure the asyncDataOutputType: {}",
nameId(), e.what());
1987 if (ImGui::IsItemHovered())
1989 ImGui::BeginTooltip();
1990 ImGui::TextUnformatted(asciiAsyncItem.second);
1991 ImGui::EndTooltip();
1997 ImGui::SetItemDefaultFocus();
2003 gui::widgets::HelpMarker(
"This register controls the type of data that will be asynchronously outputted by the module. With this "
2004 "register, the user can specify which data register will be automatically outputted when it gets updated "
2005 "with a new reading. The table below lists which registers can be set to asynchronously output, the value "
2006 "to specify which register to output, and the header of the asynchronous data packet. Asynchronous data "
2007 "output can be disabled by setting this register to zero. The asynchronous data output will be sent out "
2008 "automatically at a frequency specified by the Async Data Output Frequency Register.");
2010 if (ImGui::SliderInt(fmt::format(
"Async Ascii Output Frequency##{}",
size_t(
id)).c_str(),
2024 catch (
const std::exception& e)
2026 LOG_ERROR(
"{}: Could not configure the asyncDataOutputFrequency: {}",
nameId(), e.what());
2036 gui::widgets::HelpMarker(
"Asynchronous data output frequency.\nThe ADOF will be changed for the active serial port.");
2038 if (ImGui::DragInt(fmt::format(
"Async Ascii Output buffer size##{}",
size_t(
id)).c_str(), &
_asciiOutputBufferSize, 1.0F, 0, INT32_MAX / 2))
2045 std::string messages;
2048 messages.append(msg);
2050 ImGui::TextUnformatted(
"Async Ascii Messages:");
2051 ImGui::BeginChild(fmt::format(
"##Ascii Mesages {}",
size_t(
id)).c_str(), ImVec2(0, 300),
true);
2052 ImGui::PushTextWrapPos();
2053 ImGui::TextUnformatted(messages.c_str());
2054 ImGui::PopTextWrapPos();
2060 if (ImGui::TreeNode(fmt::format(
"Synchronization Control##{}",
size_t(
id)).c_str()))
2062 ImGui::TextUnformatted(
"Contains parameters which allow the timing of the VN-310E to be\n"
2063 "synchronized with external devices.");
2065 if (ImGui::Checkbox(fmt::format(
"Show SyncIn Pin##{}",
size_t(
id)).c_str(), &
_syncInPin))
2084 static constexpr std::array<std::pair<vn::protocol::uart::SyncInMode, const char*>, 4> synchronizationControlSyncInModes = {
2085 { { vn::protocol::uart::SyncInMode::SYNCINMODE_COUNT,
"Count number of trigger events on SYNC_IN" },
2086 { vn::protocol::uart::SyncInMode::SYNCINMODE_IMU,
"Start IMU sampling on trigger of SYNC_IN" },
2087 { vn::protocol::uart::SyncInMode::SYNCINMODE_ASYNC,
"Output asynchronous message on trigger of SYNC_IN" },
2088 { vn::protocol::uart::SyncInMode::SYNCINMODE_ASYNC3,
"Output asynchronous or binary messages configured with a rate of 0 to output on trigger of SYNC_IN\n\n"
2089 "In ASYNC3 mode messages configured with an output rate = 0 are output each time the appropriate\n"
2090 "transistion edge of the SyncIn pin is captured according to the edge settings in the SyncInEdge field.\n"
2091 "Messages configured with output rate > 0 are not affected by the SyncIn pulse. This applies to the ASCII\n"
2092 "Async message set by the Async Data Output Register, the user configurate binary output messages set\n"
2093 "by the Binary Output Registers, as well as the NMEA messages configured by the NMEA Output Registers." } }
2097 ImGui::BeginDisabled();
2100 if (ImGui::BeginCombo(fmt::format(
"SyncIn Mode##{}",
size_t(
id)).c_str(), vn::protocol::uart::str(
_synchronizationControlRegister.syncInMode).c_str()))
2102 for (
const auto& synchronizationControlSyncInMode : synchronizationControlSyncInModes)
2105 if (ImGui::Selectable(vn::protocol::uart::str(synchronizationControlSyncInMode.first).c_str(), isSelected))
2116 catch (
const std::exception& e)
2118 LOG_ERROR(
"{}: Could not configure the synchronizationControlRegister: {}",
nameId(), e.what());
2127 if (ImGui::IsItemHovered())
2129 ImGui::BeginTooltip();
2130 ImGui::TextUnformatted(synchronizationControlSyncInMode.second);
2131 ImGui::EndTooltip();
2136 ImGui::SetItemDefaultFocus();
2142 gui::widgets::HelpMarker(
"The SyncInMode register controls the behavior of the SyncIn event. If the mode is set to COUNT then the "
2143 "internal clock will be used to control the IMU sampling. If SyncInMode is set to IMU then the IMU sampling "
2144 "loop will run on a SyncIn event. The relationship between the SyncIn event and a SyncIn trigger is defined "
2145 "by the SyncInEdge and SyncInSkipFactor parameters. If set to ASYNC then the VN-100 will output "
2146 "asynchronous serial messages upon each trigger event.");
2149 ImGui::EndDisabled();
2152 static constexpr std::array<std::pair<vn::protocol::uart::SyncInEdge, const char*>, 2> synchronizationControlSyncInEdges = {
2153 { { vn::protocol::uart::SyncInEdge::SYNCINEDGE_RISING,
"Trigger on rising edge" },
2154 { vn::protocol::uart::SyncInEdge::SYNCINEDGE_FALLING,
"Trigger on falling edge" } }
2156 if (ImGui::BeginCombo(fmt::format(
"SyncIn Edge##{}",
size_t(
id)).c_str(), vn::protocol::uart::str(
_synchronizationControlRegister.syncInEdge).c_str()))
2158 for (
const auto& synchronizationControlSyncInEdge : synchronizationControlSyncInEdges)
2161 if (ImGui::Selectable(vn::protocol::uart::str(synchronizationControlSyncInEdge.first).c_str(), isSelected))
2172 catch (
const std::exception& e)
2174 LOG_ERROR(
"{}: Could not configure the synchronizationControlRegister: {}",
nameId(), e.what());
2183 if (ImGui::IsItemHovered())
2185 ImGui::BeginTooltip();
2186 ImGui::TextUnformatted(synchronizationControlSyncInEdge.second);
2187 ImGui::EndTooltip();
2192 ImGui::SetItemDefaultFocus();
2199 "The factory default state is to trigger on a rising edge.");
2202 if (ImGui::InputInt(fmt::format(
"SyncIn Skip Factor##{}",
size_t(
id)).c_str(), &syncInSkipFactor))
2204 if (syncInSkipFactor < 0)
2206 syncInSkipFactor = 0;
2208 else if (syncInSkipFactor > std::numeric_limits<uint16_t>::max())
2210 syncInSkipFactor = std::numeric_limits<uint16_t>::max();
2221 catch (
const std::exception& e)
2223 LOG_ERROR(
"{}: Could not configure the synchronizationControlRegister: {}",
nameId(), e.what());
2233 gui::widgets::HelpMarker(
"The SyncInSkipFactor defines how many times trigger edges defined by SyncInEdge should occur prior to "
2234 "triggering a SyncIn event. The action performed on a SyncIn event is determined by the SyncIn mode. As an "
2235 "example if the SyncInSkipFactor was set to 4 and a 1 kHz signal was attached to the SyncIn pin, then the "
2236 "SyncIn event would only occur at 200 Hz.");
2238 static constexpr std::array<std::pair<vn::protocol::uart::SyncOutMode, const char*>, 5> synchronizationControlSyncOutModes = {
2239 { { vn::protocol::uart::SyncOutMode::SYNCOUTMODE_NONE,
"None" },
2240 { vn::protocol::uart::SyncOutMode::SYNCOUTMODE_IMUSTART,
"Trigger at start of IMU sampling" },
2241 { vn::protocol::uart::SyncOutMode::SYNCOUTMODE_IMUREADY,
"Trigger when IMU measurements are available" },
2242 { vn::protocol::uart::SyncOutMode::SYNCOUTMODE_INS,
"Trigger when attitude measurements are available" },
2243 { vn::protocol::uart::SyncOutMode::SYNCOUTMODE_GPSPPS,
"Trigger on a GPS PPS event (1 Hz) when a 3D fix is valid." } }
2245 if (ImGui::BeginCombo(fmt::format(
"SyncOut Mode##{}",
size_t(
id)).c_str(), vn::protocol::uart::str(
_synchronizationControlRegister.syncOutMode).c_str()))
2247 for (
const auto& synchronizationControlSyncOutMode : synchronizationControlSyncOutModes)
2250 if (ImGui::Selectable(vn::protocol::uart::str(synchronizationControlSyncOutMode.first).c_str(), isSelected))
2273 catch (
const std::exception& e)
2275 LOG_ERROR(
"{}: Could not configure the synchronizationControlRegister: {}",
nameId(), e.what());
2284 if (ImGui::IsItemHovered())
2286 ImGui::BeginTooltip();
2287 ImGui::TextUnformatted(synchronizationControlSyncOutMode.second);
2288 ImGui::EndTooltip();
2293 ImGui::SetItemDefaultFocus();
2299 gui::widgets::HelpMarker(
"The SyncOutMode register controls the behavior of the SyncOut pin. If this is set to IMU then the SyncOut "
2300 "will start the pulse when the internal IMU sample loop starts. This mode is used to make a sensor the Master "
2301 "in a multi-sensor network array. If this is set to IMU_READY mode then the pulse will start when IMU "
2302 "measurements become available. If this is set to INS mode then the pulse will start when attitude "
2303 "measurements are made available. Changes to this register take effect immediately.");
2305 static constexpr std::array<std::pair<vn::protocol::uart::SyncOutPolarity, const char*>, 2> synchronizationControlSyncOutPolarities = {
2306 { { vn::protocol::uart::SyncOutPolarity::SYNCOUTPOLARITY_NEGATIVE,
"Negative Pulse" },
2307 { vn::protocol::uart::SyncOutPolarity::SYNCOUTPOLARITY_POSITIVE,
"Positive Pulse" } }
2309 if (ImGui::BeginCombo(fmt::format(
"SyncOut Polarity##{}",
size_t(
id)).c_str(), vn::protocol::uart::str(
_synchronizationControlRegister.syncOutPolarity).c_str()))
2311 for (
const auto& synchronizationControlSyncOutPolarity : synchronizationControlSyncOutPolarities)
2314 if (ImGui::Selectable(vn::protocol::uart::str(synchronizationControlSyncOutPolarity.first).c_str(), isSelected))
2325 catch (
const std::exception& e)
2327 LOG_ERROR(
"{}: Could not configure the synchronizationControlRegister: {}",
nameId(), e.what());
2336 if (ImGui::IsItemHovered())
2338 ImGui::BeginTooltip();
2339 ImGui::TextUnformatted(synchronizationControlSyncOutPolarity.second);
2340 ImGui::EndTooltip();
2345 ImGui::SetItemDefaultFocus();
2351 gui::widgets::HelpMarker(
"The SyncOutPolarity register controls the polarity of the output pulse on the SyncOut pin.\n"
2352 "Changes to this register take effect immediately.");
2355 if (ImGui::InputInt(fmt::format(
"SyncOut Skip Factor##{}",
size_t(
id)).c_str(), &syncOutSkipFactor))
2357 if (syncOutSkipFactor < 0)
2359 syncOutSkipFactor = 0;
2361 else if (syncOutSkipFactor > std::numeric_limits<uint16_t>::max())
2363 syncOutSkipFactor = std::numeric_limits<uint16_t>::max();
2374 catch (
const std::exception& e)
2376 LOG_ERROR(
"{}: Could not configure the synchronizationControlRegister: {}",
nameId(), e.what());
2386 gui::widgets::HelpMarker(
"The SyncOutSkipFactor defines how many times the sync out event should be skipped before actually triggering the SyncOut pin.");
2389 if (ImGui::InputInt(fmt::format(
"SyncOut Pulse Width##{}",
size_t(
id)).c_str(), &syncOutPulseWidth))
2391 syncOutPulseWidth = std::max(syncOutPulseWidth, 0);
2401 catch (
const std::exception& e)
2403 LOG_ERROR(
"{}: Could not configure the synchronizationControlRegister: {}",
nameId(), e.what());
2414 "The default value is 100,000,000 (100 ms).");
2419 if (ImGui::TreeNode(fmt::format(
"Communication Protocol Control##{}",
size_t(
id)).c_str()))
2421 ImGui::TextUnformatted(
"Contains parameters that controls the communication protocol used by the sensor.");
2423 static constexpr std::array<std::pair<vn::protocol::uart::CountMode, const char*>, 5> communicationProtocolControlSerialCounts = {
2424 { { vn::protocol::uart::CountMode::COUNTMODE_NONE,
"OFF" },
2425 { vn::protocol::uart::CountMode::COUNTMODE_SYNCINCOUNT,
"SyncIn Counter" },
2426 { vn::protocol::uart::CountMode::COUNTMODE_SYNCINTIME,
"SyncIn Time" },
2427 { vn::protocol::uart::CountMode::COUNTMODE_SYNCOUTCOUNTER,
"SyncOut Counter" },
2428 { vn::protocol::uart::CountMode::COUNTMODE_GPSPPS,
"Gps Pps Time" } }
2432 for (
const auto& communicationProtocolControlSerialCount : communicationProtocolControlSerialCounts)
2435 if (ImGui::Selectable(vn::protocol::uart::str(communicationProtocolControlSerialCount.first).c_str(), isSelected))
2446 catch (
const std::exception& e)
2448 LOG_ERROR(
"{}: Could not configure the communicationProtocolControlRegister: {}",
nameId(), e.what());
2457 if (ImGui::IsItemHovered())
2459 ImGui::BeginTooltip();
2460 ImGui::TextUnformatted(communicationProtocolControlSerialCount.second);
2461 ImGui::EndTooltip();
2466 ImGui::SetItemDefaultFocus();
2472 gui::widgets::HelpMarker(
"The SerialCount field provides a means of appending a time or counter to the end of all asynchronous "
2473 "communication messages transmitted on the serial interface. The values for each of these counters come "
2474 "directly from the Synchronization Status Register in the System subsystem.\n\n"
2475 "With the SerialCount field set to OFF a typical serial asynchronous message would appear as the following:\n"
2476 "$VNYPR,+010.071,+000.278,-002.026*60\n\n"
2477 "With the SerialCount field set to one of the non-zero values the same asynchronous message would appear "
2479 "$VNYPR,+010.071,+000.278,-002.026,T1162704*2F\n\n"
2480 "When the SerialCount field is enabled the counter will always be appended to the end of the message just "
2481 "prior to the checksum. The counter will be preceded by the T character to distinguish it from the status field.");
2483 static constexpr std::array<std::pair<vn::protocol::uart::StatusMode, const char*>, 3> communicationProtocolControlSerialStatuses = {
2484 { { vn::protocol::uart::StatusMode::STATUSMODE_OFF,
"OFF" },
2485 { vn::protocol::uart::StatusMode::STATUSMODE_VPESTATUS,
"VPE Status" },
2486 { vn::protocol::uart::StatusMode::STATUSMODE_INSSTATUS,
"INS Status" } }
2490 for (
const auto& communicationProtocolControlSerialStatus : communicationProtocolControlSerialStatuses)
2493 if (ImGui::Selectable(vn::protocol::uart::str(communicationProtocolControlSerialStatus.first).c_str(), isSelected))
2504 catch (
const std::exception& e)
2506 LOG_ERROR(
"{}: Could not configure the communicationProtocolControlRegister: {}",
nameId(), e.what());
2515 if (ImGui::IsItemHovered())
2517 ImGui::BeginTooltip();
2518 ImGui::TextUnformatted(communicationProtocolControlSerialStatus.second);
2519 ImGui::EndTooltip();
2524 ImGui::SetItemDefaultFocus();
2530 gui::widgets::HelpMarker(
"The SerialStatus field provides a means of tracking real-time status information pertain to the overall state "
2531 "of the sensor measurements and onboard filtering algorithm. As with the SerialCount, a typical serial "
2532 "asynchronous message would appear as the following:\n"
2533 "$VNYPR,+010.071,+000.278,-002.026*60\n\n"
2534 "With the SerialStatus field set to one of the non-zero values, the same asynchronous message would appear "
2536 "$VNYPR,+010.071,+000.278,-002.026,S0000*1F\n\n"
2537 "When the SerialStatus field is enabled the status will always be appended to the end of the message just "
2538 "prior to the checksum. If both the SerialCount and SerialStatus are enabled then the SerialStatus will be "
2539 "displayed first. The counter will be preceded by the S character to distinguish it from the counter field. The "
2540 "status consists of 4 hexadecimal characters.");
2546 for (
const auto& communicationProtocolControlSpiCount : communicationProtocolControlSerialCounts)
2549 if (ImGui::Selectable(vn::protocol::uart::str(communicationProtocolControlSpiCount.first).c_str(), isSelected))
2560 catch (
const std::exception& e)
2562 LOG_ERROR(
"{}: Could not configure the communicationProtocolControlRegister: {}",
nameId(), e.what());
2571 if (ImGui::IsItemHovered())
2573 ImGui::BeginTooltip();
2574 ImGui::TextUnformatted(communicationProtocolControlSpiCount.second);
2575 ImGui::EndTooltip();
2580 ImGui::SetItemDefaultFocus();
2586 gui::widgets::HelpMarker(
"The SPICount field provides a means of appending a time or counter to the end of all SPI packets. The "
2587 "values for each of these counters come directly from the Synchronization Status Register.");
2594 for (
const auto& communicationProtocolControlSpiStatus : communicationProtocolControlSerialStatuses)
2597 if (ImGui::Selectable(vn::protocol::uart::str(communicationProtocolControlSpiStatus.first).c_str(), isSelected))
2608 catch (
const std::exception& e)
2610 LOG_ERROR(
"{}: Could not configure the communicationProtocolControlRegister: {}",
nameId(), e.what());
2619 if (ImGui::IsItemHovered())
2621 ImGui::BeginTooltip();
2622 ImGui::TextUnformatted(communicationProtocolControlSpiStatus.second);
2623 ImGui::EndTooltip();
2628 ImGui::SetItemDefaultFocus();
2634 gui::widgets::HelpMarker(
"The AsyncStatus field provides a means of tracking real-time status information pertaining to the overall "
2635 "state of the sensor measurements and onboard filtering algorithm. This information is very useful in "
2636 "situations where action must be taken when certain crucial events happen such as the detection of gyro "
2637 "saturation or magnetic interference.");
2640 static constexpr std::array<std::pair<vn::protocol::uart::ChecksumMode, const char*>, 2> communicationProtocolControlSerialChecksums = {
2641 { { vn::protocol::uart::ChecksumMode::CHECKSUMMODE_CHECKSUM,
"8-Bit Checksum" },
2642 { vn::protocol::uart::ChecksumMode::CHECKSUMMODE_CRC,
"16-Bit CRC" } }
2646 for (
const auto& communicationProtocolControlSerialChecksum : communicationProtocolControlSerialChecksums)
2649 if (ImGui::Selectable(vn::protocol::uart::str(communicationProtocolControlSerialChecksum.first).c_str(), isSelected))
2660 catch (
const std::exception& e)
2662 LOG_ERROR(
"{}: Could not configure the communicationProtocolControlRegister: {}",
nameId(), e.what());
2671 if (ImGui::IsItemHovered())
2673 ImGui::BeginTooltip();
2674 ImGui::TextUnformatted(communicationProtocolControlSerialChecksum.second);
2675 ImGui::EndTooltip();
2680 ImGui::SetItemDefaultFocus();
2686 gui::widgets::HelpMarker(
"This field controls the type of checksum used for the serial communications. Normally the VN-310E uses an "
2687 "8-bit checksum identical to the type used for normal GPS NMEA packets. This form of checksum however "
2688 "offers only a limited means of error checking. As an alternative a full 16-bit CRC (CRC16-CCITT with "
2689 "polynomial = 0x07) is also offered. The 2-byte CRC value is printed using 4 hexadecimal digits.");
2693 static constexpr std::array<std::pair<vn::protocol::uart::ChecksumMode, const char*>, 3> communicationProtocolControlSpiChecksums = {
2694 { { vn::protocol::uart::ChecksumMode::CHECKSUMMODE_OFF,
"OFF" },
2695 { vn::protocol::uart::ChecksumMode::CHECKSUMMODE_CHECKSUM,
"8-Bit Checksum" },
2696 { vn::protocol::uart::ChecksumMode::CHECKSUMMODE_CRC,
"16-Bit CRC" } }
2700 for (
const auto& communicationProtocolControlSpiChecksum : communicationProtocolControlSpiChecksums)
2703 if (ImGui::Selectable(vn::protocol::uart::str(communicationProtocolControlSpiChecksum.first).c_str(), isSelected))
2714 catch (
const std::exception& e)
2716 LOG_ERROR(
"{}: Could not configure the communicationProtocolControlRegister: {}",
nameId(), e.what());
2725 if (ImGui::IsItemHovered())
2727 ImGui::BeginTooltip();
2728 ImGui::TextUnformatted(communicationProtocolControlSpiChecksum.second);
2729 ImGui::EndTooltip();
2734 ImGui::SetItemDefaultFocus();
2740 gui::widgets::HelpMarker(
"This field controls the type of checksum used for the SPI communications. The checksum is appended to "
2741 "the end of the binary data packet. The 16-bit CRC is identical to the one described above for the "
2745 static constexpr std::array<std::pair<vn::protocol::uart::ErrorMode, const char*>, 3> communicationProtocolControlErrorModes = {
2746 { { vn::protocol::uart::ErrorMode::ERRORMODE_IGNORE,
"Ignore Error" },
2747 { vn::protocol::uart::ErrorMode::ERRORMODE_SEND,
"Send Error" },
2748 { vn::protocol::uart::ErrorMode::ERRORMODE_SENDANDOFF,
"Send Error and set ADOR register to OFF" } }
2752 for (
const auto& communicationProtocolControlErrorMode : communicationProtocolControlErrorModes)
2755 if (ImGui::Selectable(vn::protocol::uart::str(communicationProtocolControlErrorMode.first).c_str(), isSelected))
2766 catch (
const std::exception& e)
2768 LOG_ERROR(
"{}: Could not configure the communicationProtocolControlRegister: {}",
nameId(), e.what());
2777 if (ImGui::IsItemHovered())
2779 ImGui::BeginTooltip();
2780 ImGui::TextUnformatted(communicationProtocolControlErrorMode.second);
2781 ImGui::EndTooltip();
2786 ImGui::SetItemDefaultFocus();
2792 gui::widgets::HelpMarker(
"This field controls the type of action taken by the VectorNav when an error event occurs. If the send error "
2793 "mode is enabled then a message similar to the one shown below will be sent on the serial bus when an error "
2796 "Regardless of the state of the ErrorMode, the number of error events is always recorded and is made available "
2797 "in the SysErrors field of the Communication Protocol Status Register in the System subsystem.");
2799 if (ImGui::TreeNode(fmt::format(
"Example Async Messages##{}",
size_t(
id)).c_str()))
2801 ImGui::TextUnformatted(
"The following table shows example asynchronous messages with the\nAsyncCount and the AsyncStatus values appended to the end.");
2803 if (ImGui::BeginTable(
"Example Async Messages Table", 2, ImGuiTableFlags_Borders | ImGuiTableFlags_RowBg | ImGuiTableFlags_SizingFixedFit | ImGuiTableFlags_NoHostExtendX, ImVec2(0.0F, 0.0F)))
2805 ImGui::TableSetupColumn(
"Example Type");
2806 ImGui::TableSetupColumn(
"Message");
2807 ImGui::TableHeadersRow();
2809 ImGui::TableNextColumn();
2810 ImGui::TextUnformatted(
"Async Message with\nAsyncCount Enabled");
2811 ImGui::TableNextColumn();
2812 ImGui::TextUnformatted(
"$VNYPR,+010.071,+000.278,-002.026,T1162704*2F");
2814 ImGui::TableNextColumn();
2815 ImGui::TextUnformatted(
"Async Message with\nAsyncStatus Enabled");
2816 ImGui::TableNextColumn();
2817 ImGui::TextUnformatted(
"$VNYPR,+010.071,+000.278,-002.026,S0000*1F");
2819 ImGui::TableNextColumn();
2820 ImGui::TextUnformatted(
"Async Message with\nAsyncCount and\nAsyncStatus Enabled");
2821 ImGui::TableNextColumn();
2822 ImGui::TextUnformatted(
"$VNYPR,+010.071,+000.278,-002.026,T1162704,S0000*50");
2835 if (ImGui::TreeNode(fmt::format(
"Binary Output {}##{}", b + 1,
size_t(
id)).c_str()))
2837 static constexpr std::array<std::pair<vn::protocol::uart::AsyncMode, const char*>, 4> asyncModes = {
2838 { { vn::protocol::uart::AsyncMode::ASYNCMODE_NONE,
" User message is not automatically sent out either serial port" },
2839 { vn::protocol::uart::AsyncMode::ASYNCMODE_PORT1,
"Message is sent out serial port 1 at a fixed rate" },
2840 { vn::protocol::uart::AsyncMode::ASYNCMODE_PORT2,
"Message is sent out serial port 2 at a fixed rate" },
2841 { vn::protocol::uart::AsyncMode::ASYNCMODE_BOTH,
"Message is sent out both serial ports at a fixed rate" } }
2847 ImGui::BeginDisabled();
2850 if (ImGui::BeginCombo(fmt::format(
"Async Mode##{}",
size_t(
id)).c_str(), vn::protocol::uart::str(
_binaryOutputRegister.at(b).asyncMode).c_str()))
2852 for (
const auto& asyncMode : asyncModes)
2855 if (ImGui::Selectable(vn::protocol::uart::str(asyncMode.first).c_str(), isSelected))
2860 std::vector<size_t> binaryOutputRegistersToUpdate;
2861 binaryOutputRegistersToUpdate.push_back(b);
2866 binaryOutputRegistersToUpdate.push_back(1);
2873 binaryOutputRegistersToUpdate.push_back(2);
2879 for (
const auto& binUpdate : binaryOutputRegistersToUpdate)
2898 catch (
const std::exception& e)
2900 LOG_ERROR(
"{}: Could not configure the binaryOutputRegister {}: {}",
nameId(), binUpdate + 1, e.what());
2910 if (ImGui::IsItemHovered())
2912 ImGui::BeginTooltip();
2913 ImGui::TextUnformatted(asyncMode.second);
2914 ImGui::EndTooltip();
2919 ImGui::SetItemDefaultFocus();
2926 "out on the serial port(s) at a fixed rate.");
2932 ImGui::SliderInt(fmt::format(
"Frequency##{} {}",
size_t(
id), b).c_str(),
2942 if (
_binaryOutputRegister.at(b).imuField & (vn::protocol::uart::IMUGROUP_ACCEL | vn::protocol::uart::IMUGROUP_UNCOMPACCEL))
2946 if (
_binaryOutputRegister.at(b).imuField & (vn::protocol::uart::IMUGROUP_ANGULARRATE | vn::protocol::uart::IMUGROUP_UNCOMPGYRO))
2950 if (
_binaryOutputRegister.at(b).imuField & (vn::protocol::uart::IMUGROUP_MAG | vn::protocol::uart::IMUGROUP_UNCOMPMAG))
2954 if (
_binaryOutputRegister.at(b).imuField & (vn::protocol::uart::IMUGROUP_MAG | vn::protocol::uart::IMUGROUP_UNCOMPMAG))
2966 LOG_DATA(
"{}: Frequency of ImuFilter matches output frequency (coupled 'rateDivisor' and 'windowSize' of moving average filter.)",
nameId());
2974 catch (
const std::exception& e)
2976 LOG_ERROR(
"{}: Could not configure the imuFilteringConfigurationRegister: {}",
nameId(), e.what());
2986 std::vector<size_t> binaryOutputRegistersToUpdate;
2987 binaryOutputRegistersToUpdate.push_back(b);
2993 binaryOutputRegistersToUpdate.push_back(1);
3001 binaryOutputRegistersToUpdate.push_back(2);
3007 for (
const auto& binUpdate : binaryOutputRegistersToUpdate)
3026 catch (
const std::exception& e)
3028 LOG_ERROR(
"{}: Could not configure the binaryOutputRegister {}: {}",
nameId(), binUpdate + 1, e.what());
3042 ImGui::EndDisabled();
3045 if (ImGui::BeginTable(fmt::format(
"##VectorNavSensorConfig ({})",
size_t(
id)).c_str(), 6,
3046 ImGuiTableFlags_Borders | ImGuiTableFlags_RowBg))
3049 ImGui::TableSetupColumn(
"Time", ImGuiTableColumnFlags_WidthFixed);
3050 ImGui::TableSetupColumn(
"IMU", ImGuiTableColumnFlags_WidthFixed);
3051 ImGui::TableSetupColumn(
"GNSS1", ImGuiTableColumnFlags_WidthFixed);
3052 ImGui::TableSetupColumn(
"Attitude", ImGuiTableColumnFlags_WidthFixed);
3053 ImGui::TableSetupColumn(
"INS", ImGuiTableColumnFlags_WidthFixed);
3054 ImGui::TableSetupColumn(
"GNSS2", ImGuiTableColumnFlags_WidthFixed);
3055 ImGui::TableHeadersRow();
3057 auto CheckboxFlags = [&,
this](
int index,
const char* label,
int* flags,
int flags_value,
bool enabled, void (*toggleFields)(
VectorNavSensor*, vn::sensors::BinaryOutputRegister&, uint32_t&)) {
3058 ImGui::TableSetColumnIndex(index);
3062 ImGui::BeginDisabled();
3065 if (ImGui::CheckboxFlags(label, flags, flags_value))
3067 LOG_DEBUG(
"{}: Field '{}' of Binary Group {} is now {}",
nameId(), std::string(label).substr(0, std::string(label).find(
'#')), b + 1, (*flags & flags_value) ?
"checked" :
"unchecked");
3090 for (
auto& link :
outputPins.at(b + 2).links)
3092 if (
auto* connectedPin = link.getConnectedPin())
3094 outputPins.at(b + 2).recreateLink(*connectedPin);
3098 catch (
const std::exception& e)
3100 LOG_ERROR(
"{}: Could not configure the binaryOutputRegister {}: {}",
nameId(), b + 1, e.what());
3112 ImGui::EndDisabled();
3116 for (
size_t i = 0; i < 16; i++)
3121 ImGui::TableNextRow();
3141 CheckboxFlags(0, fmt::format(
"{}##Time {} {}", binaryGroupItem.name,
size_t(
id), b).c_str(),
3143 binaryGroupItem.flagsValue,
3145 binaryGroupItem.toggleFields);
3146 if (ImGui::IsItemHovered(ImGuiHoveredFlags_AllowWhenDisabled) && binaryGroupItem.tooltip !=
nullptr)
3148 ImGui::BeginTooltip();
3149 binaryGroupItem.tooltip();
3150 ImGui::EndTooltip();
3156 CheckboxFlags(1, fmt::format(
"{}##IMU {} {}", binaryGroupItem.name,
size_t(
id), b).c_str(),
3158 binaryGroupItem.flagsValue,
3160 binaryGroupItem.toggleFields);
3161 if (ImGui::IsItemHovered(ImGuiHoveredFlags_AllowWhenDisabled) && binaryGroupItem.tooltip !=
nullptr)
3163 ImGui::BeginTooltip();
3164 binaryGroupItem.tooltip();
3165 ImGui::EndTooltip();
3171 CheckboxFlags(2, fmt::format(
"{}##GNSS1 {} {}", binaryGroupItem.name,
size_t(
id), b).c_str(),
3173 binaryGroupItem.flagsValue,
3175 binaryGroupItem.toggleFields);
3176 if (ImGui::IsItemHovered(ImGuiHoveredFlags_AllowWhenDisabled) && binaryGroupItem.tooltip !=
nullptr)
3178 ImGui::BeginTooltip();
3179 binaryGroupItem.tooltip();
3180 ImGui::EndTooltip();
3186 CheckboxFlags(3, fmt::format(
"{}##Attitude {} {}", binaryGroupItem.name,
size_t(
id), b).c_str(),
3188 binaryGroupItem.flagsValue,
3190 binaryGroupItem.toggleFields);
3191 if (ImGui::IsItemHovered(ImGuiHoveredFlags_AllowWhenDisabled) && binaryGroupItem.tooltip !=
nullptr)
3193 ImGui::BeginTooltip();
3194 binaryGroupItem.tooltip();
3195 ImGui::EndTooltip();
3201 CheckboxFlags(4, fmt::format(
"{}##INS {} {}", binaryGroupItem.name,
size_t(
id), b).c_str(),
3203 binaryGroupItem.flagsValue,
3205 binaryGroupItem.toggleFields);
3206 if (ImGui::IsItemHovered(ImGuiHoveredFlags_AllowWhenDisabled) && binaryGroupItem.tooltip !=
nullptr)
3208 ImGui::BeginTooltip();
3209 binaryGroupItem.tooltip();
3210 ImGui::EndTooltip();
3216 CheckboxFlags(5, fmt::format(
"{}##GNSS2 {} {}", binaryGroupItem.name,
size_t(
id), b).c_str(),
3218 binaryGroupItem.flagsValue,
3220 binaryGroupItem.toggleFields);
3221 if (ImGui::IsItemHovered(ImGuiHoveredFlags_AllowWhenDisabled) && binaryGroupItem.tooltip !=
nullptr)
3223 ImGui::BeginTooltip();
3224 binaryGroupItem.tooltip();
3225 ImGui::EndTooltip();
3238 ImGui::Combo(fmt::format(
"Merge Binary outputs").c_str(), &binaryOutputRegisterMerge,
"None\0"
3279 NAV::gui::widgets::HelpMarker(
"VectorNav sensors have a buffer overflow if packages get too big (SatInfo/RawMeas selected and a lot of satellites). "
3280 "A workaround is, to split the data into different Binary Outputs. "
3281 "This option merges the outputs into a single observation.");
3290 ImGui::SetNextItemOpen(
true, ImGuiCond_FirstUseEver);
3291 if (ImGui::CollapsingHeader(fmt::format(
"IMU Subsystem##{}",
size_t(
id)).c_str()))
3293 if (ImGui::TreeNode(fmt::format(
"Reference Frame Rotation##{}",
size_t(
id)).c_str()))
3295 ImGui::TextUnformatted(
"Allows the measurements of the VN-310E to be rotated into a different reference frame.");
3297 gui::widgets::HelpMarker(
"This register contains a transformation matrix that allows for the transformation of measured acceleration, "
3298 "magnetic, and angular rates from the body frame of the VN-310E to any other arbitrary frame of reference. "
3299 "The use of this register allows for the sensor to be placed in any arbitrary orientation with respect to the "
3300 "user's desired body coordinate frame. This register can also be used to correct for any orientation errors due "
3301 "to mounting the VN-310E on the user's vehicle or platform.\n\n"
3302 "(X Y Z)_U = C * (X Y Z)_B\n\n"
3303 "The variables (X Y Z)_B are a measured parameter such as acceleration in the body reference frame with "
3304 "respect to the VectorNav. The variables (X Y Z)_U are a measured parameter such as acceleration in the user's "
3305 "frame of reference. The reference frame rotation register Thus needs to be loaded with the transformation "
3306 "matrix that will transform measurements from the body reference frame of the VectorNav to the desired user "
3307 "frame of reference.");
3311 gui::widgets::HelpMarker(
"The reference frame rotation is performed on all vector measurements prior to entering the INS "
3312 "filter. As such, changing this register while the attitude filter is running will lead to unexpected "
3313 "behavior in the INS output. To prevent this, the register is cached on startup and changes will "
3314 "not take effect during runtime. After setting the reference frame rotation register to its new value, "
3315 "send a write settings command and then reset the VN-310E. This will allow the INS filter to "
3316 "startup with the newly set reference frame rotation.",
3320 gui::widgets::HelpMarker(
"The matrix C in the Reference Frame Rotation Register must be an orthonormal, right-handed"
3321 " matrix. The sensor will output an error if the tolerance is not within 1e-5. The sensor will also"
3322 " report an error if any of the parameters are greater than 1 or less than -1.",
3325 ImGui::TextUnformatted(
"Rotation Angles [deg]");
3330 Eigen::Matrix3d dcm;
3334 auto b_Quat_p = Eigen::Quaterniond(dcm);
3337 std::array<float, 3> imuRot = {
static_cast<float>(eulerRot.x()),
static_cast<float>(eulerRot.y()),
static_cast<float>(eulerRot.z()) };
3338 if (ImGui::InputFloat3(fmt::format(
"##rotationAngles{}",
size_t(
id)).c_str(), imuRot.data()))
3341 imuRot.at(0) = std::max(imuRot.at(0), -179.9999F);
3342 imuRot.at(0) = std::min(imuRot.at(0), 180.0F);
3343 imuRot.at(1) = std::max(imuRot.at(1), -89.9999F);
3344 imuRot.at(1) = std::min(imuRot.at(1), 90.0F);
3345 imuRot.at(2) = std::max(imuRot.at(2), -179.9999F);
3346 imuRot.at(2) = std::min(imuRot.at(2), 180.0F);
3350 dcmf(1, 0), dcmf(1, 1), dcmf(1, 2),
3351 dcmf(2, 0), dcmf(2, 1), dcmf(2, 2));
3360 catch (
const std::exception& e)
3362 LOG_ERROR(
"{}: Could not configure the referenceFrameRotationMatrix: {}",
nameId(), e.what());
3373 ImGui::TextUnformatted(
"Rotation Matrix C");
3377 if (ImGui::InputFloat3(fmt::format(
"##referenceFrameRotationMatrix row 0 {}",
size_t(
id)).c_str(), row.data(),
"%.2f"))
3390 catch (
const std::exception& e)
3392 LOG_ERROR(
"{}: Could not configure the referenceFrameRotationMatrix: {}",
nameId(), e.what());
3402 if (ImGui::InputFloat3(fmt::format(
"##referenceFrameRotationMatrix row 1 {}",
size_t(
id)).c_str(), row.data(),
"%.2f"))
3415 catch (
const std::exception& e)
3417 LOG_ERROR(
"{}: Could not configure the referenceFrameRotationMatrix: {}",
nameId(), e.what());
3427 if (ImGui::InputFloat3(fmt::format(
"##referenceFrameRotationMatrix row 2 {}",
size_t(
id)).c_str(), row.data(),
"%.2f"))
3440 catch (
const std::exception& e)
3442 LOG_ERROR(
"{}: Could not configure the referenceFrameRotationMatrix: {}",
nameId(), e.what());
3456 if (ImGui::TreeNode(fmt::format(
"IMU Filtering Configuration##{}",
size_t(
id)).c_str()))
3458 ImGui::TextUnformatted(
"This register allows the user to configure the FIR filtering which is applied to the IMU measurements.\n"
3459 "The filter is a uniformly-weighted moving window (boxcar) filter, also known as a 'moving-average' filter.\n"
3460 "Its window size can be adjusted with respect to the internal IMU frequency (800 Hz).");
3462 if (ImGui::Checkbox(fmt::format(
"Couple the Imu-Filter's rate to the output rate##{}",
size_t(
id)).c_str(), &
_coupleImuRateOutput))
3469 "divisor, some samples are lost. This results in a low output rate that still contains "
3470 "noise due to high frequencies. Therefore, it is recommended to couple the ImuFilter's "
3471 "rate to the output rate.");
3476 ImGui::BeginDisabled();
3478 if (ImGui::InputInt(fmt::format(
"Mag Window Size##{}",
size_t(
id)).c_str(), &magWindowSize))
3480 if (magWindowSize < 0)
3484 else if (magWindowSize > std::numeric_limits<uint16_t>::max())
3486 magWindowSize = std::numeric_limits<uint16_t>::max();
3497 catch (
const std::exception& e)
3499 LOG_ERROR(
"{}: Could not configure the imuFilteringConfigurationRegister: {}",
nameId(), e.what());
3509 gui::widgets::HelpMarker(
"The WindowSize parameters for each sensor define the number of samples at the IMU rate (default 800Hz) "
3510 "which will be averaged for each output measurement.");
3513 if (ImGui::InputInt(fmt::format(
"Accel Window Size##{}",
size_t(
id)).c_str(), &accelWindowSize))
3515 if (accelWindowSize < 0)
3517 accelWindowSize = 0;
3519 else if (accelWindowSize > std::numeric_limits<uint16_t>::max())
3521 accelWindowSize = std::numeric_limits<uint16_t>::max();
3532 catch (
const std::exception& e)
3534 LOG_ERROR(
"{}: Could not configure the imuFilteringConfigurationRegister: {}",
nameId(), e.what());
3544 gui::widgets::HelpMarker(
"The WindowSize parameters for each sensor define the number of samples at the IMU rate (default 800Hz) "
3545 "which will be averaged for each output measurement.");
3548 if (ImGui::InputInt(fmt::format(
"Gyro Window Size##{}",
size_t(
id)).c_str(), &gyroWindowSize))
3550 if (gyroWindowSize < 0)
3554 else if (gyroWindowSize > std::numeric_limits<uint16_t>::max())
3556 gyroWindowSize = std::numeric_limits<uint16_t>::max();
3567 catch (
const std::exception& e)
3569 LOG_ERROR(
"{}: Could not configure the imuFilteringConfigurationRegister: {}",
nameId(), e.what());
3579 gui::widgets::HelpMarker(
"The WindowSize parameters for each sensor define the number of samples at the IMU rate (default 800Hz) "
3580 "which will be averaged for each output measurement.");
3583 if (ImGui::InputInt(fmt::format(
"Temp Window Size##{}",
size_t(
id)).c_str(), &tempWindowSize))
3585 if (tempWindowSize < 0)
3589 else if (tempWindowSize > std::numeric_limits<uint16_t>::max())
3591 tempWindowSize = std::numeric_limits<uint16_t>::max();
3602 catch (
const std::exception& e)
3604 LOG_ERROR(
"{}: Could not configure the imuFilteringConfigurationRegister: {}",
nameId(), e.what());
3614 gui::widgets::HelpMarker(
"The WindowSize parameters for each sensor define the number of samples at the IMU rate (default 800Hz) "
3615 "which will be averaged for each output measurement.");
3618 if (ImGui::InputInt(fmt::format(
"Pres Window Size##{}",
size_t(
id)).c_str(), &presWindowSize))
3620 if (presWindowSize < 0)
3624 else if (presWindowSize > std::numeric_limits<uint16_t>::max())
3626 presWindowSize = std::numeric_limits<uint16_t>::max();
3637 catch (
const std::exception& e)
3639 LOG_ERROR(
"{}: Could not configure the imuFilteringConfigurationRegister: {}",
nameId(), e.what());
3649 gui::widgets::HelpMarker(
"The WindowSize parameters for each sensor define the number of samples at the IMU rate (default 800Hz) "
3650 "which will be averaged for each output measurement.");
3653 ImGui::EndDisabled();
3656 static constexpr std::array<std::pair<vn::protocol::uart::FilterMode, const char*>, 4> imuFilteringConfigurationFilterModes = {
3657 { { vn::protocol::uart::FilterMode::FILTERMODE_NOFILTERING,
"No Filtering" },
3658 { vn::protocol::uart::FilterMode::FILTERMODE_ONLYRAW,
"Filtering performed only on raw uncompensated IMU measurements." },
3659 { vn::protocol::uart::FilterMode::FILTERMODE_ONLYCOMPENSATED,
"Filtering performed only on compensated IMU measurements." },
3660 { vn::protocol::uart::FilterMode::FILTERMODE_BOTH,
"Filtering performed on both uncompensated and compensated IMU measurements." } }
3664 for (
const auto& imuFilteringConfigurationFilterMode : imuFilteringConfigurationFilterModes)
3667 if (ImGui::Selectable(vn::protocol::uart::str(imuFilteringConfigurationFilterMode.first).c_str(), isSelected))
3678 catch (
const std::exception& e)
3680 LOG_ERROR(
"{}: Could not configure the imuFilteringConfigurationRegister: {}",
nameId(), e.what());
3689 if (ImGui::IsItemHovered())
3691 ImGui::BeginTooltip();
3692 ImGui::TextUnformatted(imuFilteringConfigurationFilterMode.second);
3693 ImGui::EndTooltip();
3698 ImGui::SetItemDefaultFocus();
3704 gui::widgets::HelpMarker(
"The FilterMode parameters for each sensor select which output quantities the filtering should be applied to. "
3705 "Filtering can be applied to either the uncompensated IMU measurements, compensated (HSI and biases "
3706 "compensated by onboard filters, if applicable), or both.");
3708 if (ImGui::BeginCombo(fmt::format(
"Accel Filter Mode##{}",
size_t(
id)).c_str(), vn::protocol::uart::str(
_imuFilteringConfigurationRegister.accelFilterMode).c_str()))
3710 for (
const auto& imuFilteringConfigurationFilterMode : imuFilteringConfigurationFilterModes)
3713 if (ImGui::Selectable(vn::protocol::uart::str(imuFilteringConfigurationFilterMode.first).c_str(), isSelected))
3724 catch (
const std::exception& e)
3726 LOG_ERROR(
"{}: Could not configure the imuFilteringConfigurationRegister: {}",
nameId(), e.what());
3735 if (ImGui::IsItemHovered())
3737 ImGui::BeginTooltip();
3738 ImGui::TextUnformatted(imuFilteringConfigurationFilterMode.second);
3739 ImGui::EndTooltip();
3744 ImGui::SetItemDefaultFocus();
3750 gui::widgets::HelpMarker(
"The FilterMode parameters for each sensor select which output quantities the filtering should be applied to. "
3751 "Filtering can be applied to either the uncompensated IMU measurements, compensated (HSI and biases "
3752 "compensated by onboard filters, if applicable), or both.");
3756 for (
const auto& imuFilteringConfigurationFilterMode : imuFilteringConfigurationFilterModes)
3759 if (ImGui::Selectable(vn::protocol::uart::str(imuFilteringConfigurationFilterMode.first).c_str(), isSelected))
3770 catch (
const std::exception& e)
3772 LOG_ERROR(
"{}: Could not configure the imuFilteringConfigurationRegister: {}",
nameId(), e.what());
3781 if (ImGui::IsItemHovered())
3783 ImGui::BeginTooltip();
3784 ImGui::TextUnformatted(imuFilteringConfigurationFilterMode.second);
3785 ImGui::EndTooltip();
3790 ImGui::SetItemDefaultFocus();
3796 gui::widgets::HelpMarker(
"The FilterMode parameters for each sensor select which output quantities the filtering should be applied to. "
3797 "Filtering can be applied to either the uncompensated IMU measurements, compensated (HSI and biases "
3798 "compensated by onboard filters, if applicable), or both.");
3802 for (
const auto& imuFilteringConfigurationFilterMode : imuFilteringConfigurationFilterModes)
3805 if (ImGui::Selectable(vn::protocol::uart::str(imuFilteringConfigurationFilterMode.first).c_str(), isSelected))
3816 catch (
const std::exception& e)
3818 LOG_ERROR(
"{}: Could not configure the imuFilteringConfigurationRegister: {}",
nameId(), e.what());
3827 if (ImGui::IsItemHovered())
3829 ImGui::BeginTooltip();
3830 ImGui::TextUnformatted(imuFilteringConfigurationFilterMode.second);
3831 ImGui::EndTooltip();
3836 ImGui::SetItemDefaultFocus();
3842 gui::widgets::HelpMarker(
"The FilterMode parameters for each sensor select which output quantities the filtering should be applied to. "
3843 "Filtering can be applied to either the uncompensated IMU measurements, compensated (HSI and biases "
3844 "compensated by onboard filters, if applicable), or both.");
3848 for (
const auto& imuFilteringConfigurationFilterMode : imuFilteringConfigurationFilterModes)
3851 if (ImGui::Selectable(vn::protocol::uart::str(imuFilteringConfigurationFilterMode.first).c_str(), isSelected))
3862 catch (
const std::exception& e)
3864 LOG_ERROR(
"{}: Could not configure the imuFilteringConfigurationRegister: {}",
nameId(), e.what());
3873 if (ImGui::IsItemHovered())
3875 ImGui::BeginTooltip();
3876 ImGui::TextUnformatted(imuFilteringConfigurationFilterMode.second);
3877 ImGui::EndTooltip();
3882 ImGui::SetItemDefaultFocus();
3888 gui::widgets::HelpMarker(
"The FilterMode parameters for each sensor select which output quantities the filtering should be applied to. "
3889 "Filtering can be applied to either the uncompensated IMU measurements, compensated (HSI and biases "
3890 "compensated by onboard filters, if applicable), or both.");
3895 if (ImGui::TreeNode(fmt::format(
"Delta Theta and Delta Velocity Configuration##{}",
size_t(
id)).c_str()))
3897 ImGui::TextUnformatted(
"The Delta Theta and Delta Velocity Configuration register allows configuration of the onboard coning and\n"
3898 "sculling used to generate integrated motion values from the angular rate and acceleration IMU quantities.\n"
3899 "The fully-coupled coning and sculling integrals are computed at the IMU sample rate (nominal 400 Hz).");
3901 static constexpr std::array<std::pair<vn::protocol::uart::IntegrationFrame, const char*>, 2> deltaThetaAndDeltaVelocityConfigurationIntegrationFrames = {
3902 { { vn::protocol::uart::IntegrationFrame::INTEGRATIONFRAME_BODY,
"Body frame" },
3903 { vn::protocol::uart::IntegrationFrame::INTEGRATIONFRAME_NED,
"NED frame" } }
3907 for (
const auto& deltaThetaAndDeltaVelocityConfigurationIntegrationFrame : deltaThetaAndDeltaVelocityConfigurationIntegrationFrames)
3910 if (ImGui::Selectable(vn::protocol::uart::str(deltaThetaAndDeltaVelocityConfigurationIntegrationFrame.first).c_str(), isSelected))
3921 catch (
const std::exception& e)
3923 LOG_ERROR(
"{}: Could not configure the deltaThetaAndDeltaVelocityConfigurationRegister: {}",
nameId(), e.what());
3932 if (ImGui::IsItemHovered())
3934 ImGui::BeginTooltip();
3935 ImGui::TextUnformatted(deltaThetaAndDeltaVelocityConfigurationIntegrationFrame.second);
3936 ImGui::EndTooltip();
3941 ImGui::SetItemDefaultFocus();
3947 gui::widgets::HelpMarker(
"The IntegrationFrame register setting selects the reference frame used for coning and sculling. Note that "
3948 "using any frame other than the body frame will rely on the onboard Kalman filter's attitude estimate. The "
3949 "factory default state is to integrate in the sensor body frame.");
3951 static constexpr std::array<std::pair<vn::protocol::uart::CompensationMode, const char*>, 2> deltaThetaAndDeltaVelocityConfigurationGyroCompensationModes = {
3952 { { vn::protocol::uart::CompensationMode::COMPENSATIONMODE_NONE,
"None" },
3953 { vn::protocol::uart::CompensationMode::COMPENSATIONMODE_BIAS,
"Bias" } }
3957 for (
const auto& deltaThetaAndDeltaVelocityConfigurationGyroCompensationMode : deltaThetaAndDeltaVelocityConfigurationGyroCompensationModes)
3960 if (ImGui::Selectable(vn::protocol::uart::str(deltaThetaAndDeltaVelocityConfigurationGyroCompensationMode.first).c_str(), isSelected))
3971 catch (
const std::exception& e)
3973 LOG_ERROR(
"{}: Could not configure the deltaThetaAndDeltaVelocityConfigurationRegister: {}",
nameId(), e.what());
3982 if (ImGui::IsItemHovered())
3984 ImGui::BeginTooltip();
3985 ImGui::TextUnformatted(deltaThetaAndDeltaVelocityConfigurationGyroCompensationMode.second);
3986 ImGui::EndTooltip();
3991 ImGui::SetItemDefaultFocus();
3997 gui::widgets::HelpMarker(
"The GyroCompensation register setting selects the compensation to be applied to the angular rate "
3998 "measurements before integration. If bias compensation is selected, the onboard Kalman filter’s real-time "
3999 "estimate of the gyro biases will be used to compensate the IMU measurements before integration. The "
4000 "factory default state is to integrate the uncompensated angular rates from the IMU.");
4002 static constexpr std::array<std::pair<vn::protocol::uart::AccCompensationMode, const char*>, 2> deltaThetaAndDeltaVelocityConfigurationAccelCompensationModes = {
4003 { { vn::protocol::uart::AccCompensationMode::ACCCOMPENSATIONMODE_NONE,
"None" },
4004 { vn::protocol::uart::AccCompensationMode::ACCCOMPENSATIONMODE_BIAS,
"Bias" } }
4008 for (
const auto& deltaThetaAndDeltaVelocityConfigurationAccelCompensationMode : deltaThetaAndDeltaVelocityConfigurationAccelCompensationModes)
4011 if (ImGui::Selectable(vn::protocol::uart::str(deltaThetaAndDeltaVelocityConfigurationAccelCompensationMode.first).c_str(), isSelected))
4022 catch (
const std::exception& e)
4024 LOG_ERROR(
"{}: Could not configure the deltaThetaAndDeltaVelocityConfigurationRegister: {}",
nameId(), e.what());
4033 if (ImGui::IsItemHovered())
4035 ImGui::BeginTooltip();
4036 ImGui::TextUnformatted(deltaThetaAndDeltaVelocityConfigurationAccelCompensationMode.second);
4037 ImGui::EndTooltip();
4042 ImGui::SetItemDefaultFocus();
4048 gui::widgets::HelpMarker(
"The AccelCompensation register setting selects the compensation to be applied to the acceleration "
4049 "measurements before integration. If bias compensation is selected, the onboard Kalman filter’s real-time "
4050 "estimate of the accel biases will be used to compensate the IMU measurements before integration. The "
4051 "factory default state is to integrate the uncompensated acceleration from the IMU.");
4063 ImGui::SetNextItemOpen(
true, ImGuiCond_FirstUseEver);
4064 if (ImGui::CollapsingHeader(fmt::format(
"GNSS Subsystem##{}",
size_t(
id)).c_str()))
4066 if (ImGui::TreeNode(fmt::format(
"GNSS Configuration##{}",
size_t(
id)).c_str()))
4068 static constexpr std::array<std::pair<vn::protocol::uart::GpsMode, const char*>, 3> gpsConfigurationModes = {
4069 { { vn::protocol::uart::GpsMode::GPSMODE_ONBOARDGPS,
"Use onboard GNSS" },
4070 { vn::protocol::uart::GpsMode::GPSMODE_EXTERNALGPS,
"Use external GNSS" },
4071 { vn::protocol::uart::GpsMode::GPSMODE_EXTERNALVN200GPS,
"Use external VectorNav sensor as the GNSS" } }
4073 if (ImGui::BeginCombo(fmt::format(
"Mode##{}",
size_t(
id)).c_str(), vn::protocol::uart::str(
_gpsConfigurationRegister.mode).c_str()))
4075 for (
const auto& gpsConfigurationMode : gpsConfigurationModes)
4078 if (ImGui::Selectable(vn::protocol::uart::str(gpsConfigurationMode.first).c_str(), isSelected))
4089 catch (
const std::exception& e)
4091 LOG_ERROR(
"{}: Could not configure the gpsConfigurationRegister: {}",
nameId(), e.what());
4100 if (ImGui::IsItemHovered())
4102 ImGui::BeginTooltip();
4103 ImGui::TextUnformatted(gpsConfigurationMode.second);
4104 ImGui::EndTooltip();
4109 ImGui::SetItemDefaultFocus();
4115 static constexpr std::array<std::pair<vn::protocol::uart::PpsSource, const char*>, 4> gpsConfigurationPpsSources = {
4116 { { vn::protocol::uart::PpsSource::PPSSOURCE_GPSPPSRISING,
"GNSS PPS signal is present on the GNSS_PPS pin (pin 24) and should trigger on a rising edge." },
4117 { vn::protocol::uart::PpsSource::PPSSOURCE_GPSPPSFALLING,
"GNSS PPS signal is present on the GNSS_PPS pin (pin 24) and should trigger on a falling edge" },
4118 { vn::protocol::uart::PpsSource::PPSSOURCE_SYNCINRISING,
"GNSS PPS signal is present on the SyncIn pin (pin 22) and should trigger on a rising edge" },
4119 { vn::protocol::uart::PpsSource::PPSSOURCE_SYNCINFALLING,
"GNSS PPS signal is present on the SyncIn pin (pin 22) and should trigger on a falling edge" } }
4121 if (ImGui::BeginCombo(fmt::format(
"PPS Source##{}",
size_t(
id)).c_str(), vn::protocol::uart::str(
_gpsConfigurationRegister.ppsSource).c_str()))
4123 for (
const auto& gpsConfigurationPpsSource : gpsConfigurationPpsSources)
4126 if (ImGui::Selectable(vn::protocol::uart::str(gpsConfigurationPpsSource.first).c_str(), isSelected))
4137 catch (
const std::exception& e)
4139 LOG_ERROR(
"{}: Could not configure the gpsConfigurationRegister: {}",
nameId(), e.what());
4148 if (ImGui::IsItemHovered())
4150 ImGui::BeginTooltip();
4151 ImGui::TextUnformatted(gpsConfigurationPpsSource.second);
4152 ImGui::EndTooltip();
4157 ImGui::SetItemDefaultFocus();
4163 static constexpr std::array<vn::protocol::uart::GpsRate, 1> gpsConfigurationRates = {
4165 vn::protocol::uart::GpsRate::GPSRATE_5HZ }
4167 if (ImGui::BeginCombo(fmt::format(
"Rate##{}",
size_t(
id)).c_str(), vn::protocol::uart::str(
_gpsConfigurationRegister.rate).c_str()))
4169 for (
const auto& gpsConfigurationRate : gpsConfigurationRates)
4172 if (ImGui::Selectable(vn::protocol::uart::str(gpsConfigurationRate).c_str(), isSelected))
4183 catch (
const std::exception& e)
4185 LOG_ERROR(
"{}: Could not configure the gpsConfigurationRegister: {}",
nameId(), e.what());
4197 ImGui::SetItemDefaultFocus();
4205 static constexpr std::array<std::pair<vn::protocol::uart::AntPower, const char*>, 3> gpsConfigurationAntPowers = {
4206 { { vn::protocol::uart::AntPower::ANTPOWER_OFFRESV,
"Disable antenna power supply." },
4207 { vn::protocol::uart::AntPower::ANTPOWER_INTERNAL,
"Use internal antenna power supply (3V, 50mA combined)." },
4208 { vn::protocol::uart::AntPower::ANTPOWER_EXTERNAL,
"Use external antenna power supply (VANT pin, up to 5V and 100mA combined)" } }
4210 if (ImGui::BeginCombo(fmt::format(
"Ant Power##{}",
size_t(
id)).c_str(), vn::protocol::uart::str(
_gpsConfigurationRegister.antPow).c_str()))
4212 for (
const auto& gpsConfigurationAntPower : gpsConfigurationAntPowers)
4215 if (ImGui::Selectable(vn::protocol::uart::str(gpsConfigurationAntPower.first).c_str(), isSelected))
4226 catch (
const std::exception& e)
4228 LOG_ERROR(
"{}: Could not configure the gpsConfigurationRegister: {}",
nameId(), e.what());
4237 if (ImGui::IsItemHovered())
4239 ImGui::BeginTooltip();
4240 ImGui::TextUnformatted(gpsConfigurationAntPower.second);
4241 ImGui::EndTooltip();
4246 ImGui::SetItemDefaultFocus();
4257 if (ImGui::TreeNode(fmt::format(
"GNSS Antenna A Offset##{}",
size_t(
id)).c_str()))
4259 ImGui::TextUnformatted(
"The position of the GNSS antenna A relative to the sensor in the vehicle coordinate frame\n"
4260 "also referred to as the GNSS antenna lever arm.");
4262 if (ImGui::InputFloat3(fmt::format(
"##gpsAntennaOffset {}",
size_t(
id)).c_str(),
_gpsAntennaOffset.c,
"%.6f"))
4272 catch (
const std::exception& e)
4274 LOG_ERROR(
"{}: Could not configure the gpsAntennaOffset: {}",
nameId(), e.what());
4287 if (ImGui::TreeNode(fmt::format(
"GNSS Compass Baseline##{}",
size_t(
id)).c_str()))
4289 ImGui::TextUnformatted(
"Configures the position offset and measurement uncertainty of the second GNSS\n"
4290 "antenna relative to the first GNSS antenna in the vehicle reference frame.");
4302 catch (
const std::exception& e)
4304 LOG_ERROR(
"{}: Could not configure the gpsCompassBaselineRegister: {}",
nameId(), e.what());
4315 "The accuracy of the estimated heading is dependent upon the accuracy of the measured baseline "
4316 "between the two GNSS antennas. The factory default baseline is {1.0m, 0.0m, 0.0m}. If any other "
4317 "baseline is used, it is extremely important that the user acurately measures this baseline to ensure "
4318 "accurate heading estimates.\n"
4319 "The heading accuracy is linearly proportional to the measurement accuracy of the position of "
4320 "GNSS antenna B with respect to GNSS antenna A, and inversely proportional to the baseline "
4322 "Heading Error [deg] ~= 0.57 * (Baseline Error [cm]) / (Baseline Length [m])\n\n"
4323 "On a 1 meter baseline, a 1 cm measurement error equates to heading error of 0.6 degrees.",
4326 if (ImGui::InputFloat3(fmt::format(
"Uncertainty [m]##{}",
size_t(
id)).c_str(),
_gpsCompassBaselineRegister.uncertainty.c,
"%.3f"))
4336 catch (
const std::exception& e)
4338 LOG_ERROR(
"{}: Could not configure the gpsCompassBaselineRegister: {}",
nameId(), e.what());
4349 "For the VN-310E to function properly it is very important that the user supplies a reasonable "
4350 "measurement uncertainty that is greater than the actual uncertainty in the baseline measurement. "
4351 "The VN-310E uses the uncertainty supplied by the user to validate measurements that it receives "
4352 "from the GNSS receivers. If the user inputs an uncertainty that is lower than the actual error in "
4353 "the baseline measurement between the two antennas, the VN-310E will no longer be able to derive "
4354 "heading estimates from the GNSS.\n\n"
4355 "It is recommended that you set the uncertainty equal to twice what you expect the worst case "
4356 "error to be in your baseline measurements. In many applications it is easier to measure more "
4357 "accurately in one direction than another. It is recommended that you set each of the X, Y, & Z "
4358 "uncertainties seperately to reflect this, as opposed to using a single large value.",
4370 ImGui::SetNextItemOpen(
true, ImGuiCond_FirstUseEver);
4371 if (ImGui::CollapsingHeader(fmt::format(
"Attitude Subsystem##{}",
size_t(
id)).c_str()))
4373 if (ImGui::TreeNode(fmt::format(
"VPE Basic Control##{}",
size_t(
id)).c_str()))
4375 ImGui::TextUnformatted(
"Provides control over various features relating to the onboard attitude filtering algorithm.");
4377 static constexpr std::array<vn::protocol::uart::VpeEnable, 2> vpeBasicControlEnables = {
4378 { vn::protocol::uart::VpeEnable::VPEENABLE_DISABLE,
4379 vn::protocol::uart::VpeEnable::VPEENABLE_ENABLE }
4381 if (ImGui::BeginCombo(fmt::format(
"Enable##{}",
size_t(
id)).c_str(), vn::protocol::uart::str(
_vpeBasicControlRegister.enable).c_str()))
4383 for (
const auto& vpeBasicControlEnable : vpeBasicControlEnables)
4386 if (ImGui::Selectable(vn::protocol::uart::str(vpeBasicControlEnable).c_str(), isSelected))
4397 catch (
const std::exception& e)
4399 LOG_ERROR(
"{}: Could not configure the vpeBasicControlRegister: {}",
nameId(), e.what());
4411 ImGui::SetItemDefaultFocus();
4417 static constexpr std::array<vn::protocol::uart::HeadingMode, 3> vpeBasicControlHeadingModes = {
4418 { vn::protocol::uart::HeadingMode::HEADINGMODE_ABSOLUTE,
4419 vn::protocol::uart::HeadingMode::HEADINGMODE_RELATIVE,
4420 vn::protocol::uart::HeadingMode::HEADINGMODE_INDOOR }
4422 if (ImGui::BeginCombo(fmt::format(
"Heading Mode##{}",
size_t(
id)).c_str(), vn::protocol::uart::str(
_vpeBasicControlRegister.headingMode).c_str()))
4424 for (
const auto& vpeBasicControlHeadingMode : vpeBasicControlHeadingModes)
4427 if (ImGui::Selectable(vn::protocol::uart::str(vpeBasicControlHeadingMode).c_str(), isSelected))
4438 catch (
const std::exception& e)
4440 LOG_ERROR(
"{}: Could not configure the vpeBasicControlRegister: {}",
nameId(), e.what());
4452 ImGui::SetItemDefaultFocus();
4458 static constexpr std::array<vn::protocol::uart::VpeMode, 2> vpeBasicControlModes = {
4459 { vn::protocol::uart::VpeMode::VPEMODE_OFF,
4460 vn::protocol::uart::VpeMode::VPEMODE_MODE1 }
4462 if (ImGui::BeginCombo(fmt::format(
"Filtering Mode##{}",
size_t(
id)).c_str(), vn::protocol::uart::str(
_vpeBasicControlRegister.filteringMode).c_str()))
4464 for (
const auto& vpeBasicControlMode : vpeBasicControlModes)
4467 if (ImGui::Selectable(vn::protocol::uart::str(vpeBasicControlMode).c_str(), isSelected))
4478 catch (
const std::exception& e)
4480 LOG_ERROR(
"{}: Could not configure the vpeBasicControlRegister: {}",
nameId(), e.what());
4492 ImGui::SetItemDefaultFocus();
4498 if (ImGui::BeginCombo(fmt::format(
"Tuning Mode##{}",
size_t(
id)).c_str(), vn::protocol::uart::str(
_vpeBasicControlRegister.tuningMode).c_str()))
4500 for (
const auto& vpeBasicControlMode : vpeBasicControlModes)
4503 if (ImGui::Selectable(vn::protocol::uart::str(vpeBasicControlMode).c_str(), isSelected))
4514 catch (
const std::exception& e)
4516 LOG_ERROR(
"{}: Could not configure the vpeBasicControlRegister: {}",
nameId(), e.what());
4528 ImGui::SetItemDefaultFocus();
4539 if (ImGui::TreeNode(fmt::format(
"VPE Magnetometer Basic Tuning##{}",
size_t(
id)).c_str()))
4541 ImGui::TextUnformatted(
"Provides basic control of the adaptive filtering and tuning for the magnetometer.");
4553 catch (
const std::exception& e)
4555 LOG_ERROR(
"{}: Could not configure the vpeMagnetometerBasicTuningRegister: {}",
nameId(), e.what());
4565 gui::widgets::HelpMarker(
"This sets the level of confidence placed in the magnetometer when no disturbances are present. "
4566 "A larger number provides better heading accuracy, but with more sensitivity to magnetic interference.");
4578 catch (
const std::exception& e)
4580 LOG_ERROR(
"{}: Could not configure the vpeMagnetometerBasicTuningRegister: {}",
nameId(), e.what());
4590 if (ImGui::DragFloat3(fmt::format(
"Adaptive Filtering Level##{}",
size_t(
id)).c_str(),
_vpeMagnetometerBasicTuningRegister.adaptiveFiltering.c, 0.1F, 0.0F, 10.0F,
"%.1f"))
4600 catch (
const std::exception& e)
4602 LOG_ERROR(
"{}: Could not configure the vpeMagnetometerBasicTuningRegister: {}",
nameId(), e.what());
4615 if (ImGui::TreeNode(fmt::format(
"VPE Accelerometer Basic Tuning##{}",
size_t(
id)).c_str()))
4617 ImGui::TextUnformatted(
"Provides basic control of the adaptive filtering and tuning for the accelerometer.");
4629 catch (
const std::exception& e)
4631 LOG_ERROR(
"{}: Could not configure the vpeAccelerometerBasicTuningRegister: {}",
nameId(), e.what());
4641 gui::widgets::HelpMarker(
"This sets the level of confidence placed in the accelerometer when no disturbances are present. "
4642 "A larger number provides better pitch/roll heading accuracy, but with more sensitivity to acceleration interference.");
4654 catch (
const std::exception& e)
4656 LOG_ERROR(
"{}: Could not configure the vpeAccelerometerBasicTuningRegister: {}",
nameId(), e.what());
4676 catch (
const std::exception& e)
4678 LOG_ERROR(
"{}: Could not configure the vpeAccelerometerBasicTuningRegister: {}",
nameId(), e.what());
4691 if (ImGui::TreeNode(fmt::format(
"VPE Gyro Basic Tuning##{}",
size_t(
id)).c_str()))
4693 ImGui::TextUnformatted(
"Provides basic control of the adaptive filtering and tuning for the gyroscope.");
4695 if (ImGui::DragFloat3(fmt::format(
"Base Tuning Level##{}",
size_t(
id)).c_str(),
_vpeGyroBasicTuningRegister.baseTuning.c, 0.1F, 0.0F, 10.0F,
"%.1f"))
4705 catch (
const std::exception& e)
4707 LOG_ERROR(
"{}: Could not configure the vpeGyroBasicTuningRegister: {}",
nameId(), e.what());
4719 if (ImGui::DragFloat3(fmt::format(
"Adaptive Tuning Level##{}",
size_t(
id)).c_str(),
_vpeGyroBasicTuningRegister.adaptiveTuning.c, 0.1F, 0.0F, 10.0F,
"%.1f"))
4729 catch (
const std::exception& e)
4731 LOG_ERROR(
"{}: Could not configure the vpeGyroBasicTuningRegister: {}",
nameId(), e.what());
4741 if (ImGui::DragFloat3(fmt::format(
"Variance - Angular Walk##{}",
size_t(
id)).c_str(),
_vpeGyroBasicTuningRegister.angularWalkVariance.c, 0.1F, 0.0F, 10.0F,
"%.1f"))
4751 catch (
const std::exception& e)
4753 LOG_ERROR(
"{}: Could not configure the vpeGyroBasicTuningRegister: {}",
nameId(), e.what());
4766 if (ImGui::TreeNode(fmt::format(
"Filter Startup Gyro Bias##{}",
size_t(
id)).c_str()))
4768 ImGui::TextUnformatted(
"The filter gyro bias estimate used at startup [rad/s].");
4770 if (ImGui::InputFloat3(fmt::format(
"## FilterStartupGyroBias {}",
size_t(
id)).c_str(),
_filterStartupGyroBias.c,
"%.1f"))
4780 catch (
const std::exception& e)
4782 LOG_ERROR(
"{}: Could not configure the filterStartupGyroBias: {}",
nameId(), e.what());
4803 ImGui::SetNextItemOpen(
true, ImGuiCond_FirstUseEver);
4804 if (ImGui::CollapsingHeader(fmt::format(
"INS Subsystem##{}",
size_t(
id)).c_str()))
4806 if (ImGui::TreeNode(fmt::format(
"INS Basic Configuration##{}",
size_t(
id)).c_str()))
4808 static constexpr std::array<std::pair<vn::protocol::uart::Scenario, const char*>, 3> insBasicConfigurationRegisterVn300Scenarios = {
4809 { { vn::protocol::uart::Scenario::SCENARIO_INSWITHPRESSURE,
"General purpose INS with barometric pressure sensor" },
4810 { vn::protocol::uart::Scenario::SCENARIO_INSWITHOUTPRESSURE,
"General purpose INS without barometric pressure sensor" },
4811 { vn::protocol::uart::Scenario::SCENARIO_GPSMOVINGBASELINEDYNAMIC,
"GNSS moving baseline for dynamic applications" } }
4815 for (
const auto& insBasicConfigurationRegisterVn300Scenario : insBasicConfigurationRegisterVn300Scenarios)
4818 if (ImGui::Selectable(vn::protocol::uart::str(insBasicConfigurationRegisterVn300Scenario.first).c_str(), isSelected))
4829 catch (
const std::exception& e)
4831 LOG_ERROR(
"{}: Could not configure the insBasicConfigurationRegisterVn300: {}",
nameId(), e.what());
4840 if (ImGui::IsItemHovered())
4842 ImGui::BeginTooltip();
4843 ImGui::TextUnformatted(insBasicConfigurationRegisterVn300Scenario.second);
4844 ImGui::EndTooltip();
4849 ImGui::SetItemDefaultFocus();
4865 catch (
const std::exception& e)
4867 LOG_ERROR(
"{}: Could not configure the insBasicConfigurationRegisterVn300: {}",
nameId(), e.what());
4878 "the ability to switch to using the magnetometer to "
4879 "stabilize heading during times when the device is "
4880 "stationary and the GNSS compass is not available. "
4881 "AHRS aiding also helps to eliminate large updates in "
4882 "the attitude solution during times when heading is "
4883 "weakly observable, such as at startup.");
4895 catch (
const std::exception& e)
4897 LOG_ERROR(
"{}: Could not configure the insBasicConfigurationRegisterVn300: {}",
nameId(), e.what());
4912 if (ImGui::TreeNode(fmt::format(
"Startup Filter Bias Estimate##{}",
size_t(
id)).c_str()))
4914 ImGui::TextUnformatted(
"Sets the initial estimate for the filter bias states");
4926 catch (
const std::exception& e)
4928 LOG_ERROR(
"{}: Could not configure the startupFilterBiasEstimateRegister: {}",
nameId(), e.what());
4948 catch (
const std::exception& e)
4950 LOG_ERROR(
"{}: Could not configure the startupFilterBiasEstimateRegister: {}",
nameId(), e.what());
4970 catch (
const std::exception& e)
4972 LOG_ERROR(
"{}: Could not configure the startupFilterBiasEstimateRegister: {}",
nameId(), e.what());
4991 ImGui::SetNextItemOpen(
true, ImGuiCond_FirstUseEver);
4992 if (ImGui::CollapsingHeader(fmt::format(
"Hard/Soft Iron Estimator Subsystem##{}",
size_t(
id)).c_str()))
4994 if (ImGui::TreeNode(fmt::format(
"Magnetometer Calibration Control##{}",
size_t(
id)).c_str()))
4996 ImGui::TextUnformatted(
"Controls the magnetometer real-time calibration algorithm.");
5000 gui::widgets::HelpMarker(
"On the PRODUCT the magnetometer is only used to provide a coarse heading estimate at startup "
5001 "and is completely tuned out of the INS filter during normal operation. A Hard/Soft Iron calibration "
5002 "may be performed to try and improve the startup magnetic heading, but is not required for nominal "
5007 static constexpr std::array<std::pair<vn::protocol::uart::HsiMode, const char*>, 3> magnetometerCalibrationControlHsiModes = {
5008 { { vn::protocol::uart::HsiMode::HSIMODE_OFF,
"Real-time hard/soft iron calibration algorithm is turned off" },
5009 { vn::protocol::uart::HsiMode::HSIMODE_RUN,
"Runs the real-time hard/soft iron calibration. The algorithm will continue using its existing solution.\n"
5010 "The algorithm can be started and stopped at any time by switching between the HSI_OFF and HSI_RUN state." },
5011 { vn::protocol::uart::HsiMode::HSIMODE_RESET,
"Resets the real-time hard/soft iron solution" } }
5015 for (
const auto& magnetometerCalibrationControlHsiMode : magnetometerCalibrationControlHsiModes)
5018 if (ImGui::Selectable(vn::protocol::uart::str(magnetometerCalibrationControlHsiMode.first).c_str(), isSelected))
5029 catch (
const std::exception& e)
5031 LOG_ERROR(
"{}: Could not configure the magnetometerCalibrationControlRegister: {}",
nameId(), e.what());
5040 if (ImGui::IsItemHovered())
5042 ImGui::BeginTooltip();
5043 ImGui::TextUnformatted(magnetometerCalibrationControlHsiMode.second);
5044 ImGui::EndTooltip();
5049 ImGui::SetItemDefaultFocus();
5055 gui::widgets::HelpMarker(
"Controls the mode of operation for the onboard real-time magnetometer hard/soft iron compensation algorithm.");
5057 static constexpr std::array<std::pair<vn::protocol::uart::HsiOutput, const char*>, 2> magnetometerCalibrationControlHsiOutputs = {
5058 { { vn::protocol::uart::HsiOutput::HSIOUTPUT_NOONBOARD,
"Onboard HSI is not applied to the magnetic measurements" },
5059 { vn::protocol::uart::HsiOutput::HSIOUTPUT_USEONBOARD,
"Onboard HSI is applied to the magnetic measurements" } }
5063 for (
const auto& [magnetometerCalibrationControlHsiOutputMode, magnetometerCalibrationControlHsiOutputDescription] : magnetometerCalibrationControlHsiOutputs)
5066 if (ImGui::Selectable(vn::protocol::uart::str(magnetometerCalibrationControlHsiOutputMode).c_str(), isSelected))
5077 catch (
const std::exception& e)
5079 LOG_ERROR(
"{}: Could not configure the magnetometerCalibrationControlRegister: {}",
nameId(), e.what());
5088 if (ImGui::IsItemHovered())
5090 ImGui::BeginTooltip();
5091 ImGui::TextUnformatted(magnetometerCalibrationControlHsiOutputDescription);
5092 ImGui::EndTooltip();
5097 ImGui::SetItemDefaultFocus();
5104 "outputs from the magnetometer sensor and also "
5105 "subsequently used in the attitude filter.");
5108 if (ImGui::SliderInt(fmt::format(
"Converge Rate##{}",
size_t(
id)).c_str(), &convergeRate, 0, 5))
5119 catch (
const std::exception& e)
5121 LOG_ERROR(
"{}: Could not configure the magnetometerCalibrationControlRegister: {}",
nameId(), e.what());
5132 "to converge onto a new solution. The slower the "
5133 "convergence the more accurate the estimate of the "
5134 "hard/soft iron solution. A quicker convergence will provide "
5135 "a less accurate estimate of the hard/soft iron parameters, "
5136 "but for applications where the hard/soft iron changes "
5137 "rapidly may provide a more accurate attitude estimate.\n\n"
5139 "1 = Solution converges slowly over approximately 60-90 seconds.\n"
5140 "5 = Solution converges rapidly over approximately 15-20 seconds.");
5150 ImGui::SetNextItemOpen(
true, ImGuiCond_FirstUseEver);
5151 if (ImGui::CollapsingHeader(fmt::format(
"World Magnetic & Gravity Module##{}",
size_t(
id)).c_str()))
5153 if (ImGui::TreeNode(fmt::format(
"Magnetic and Gravity Reference Vectors##{}",
size_t(
id)).c_str()))
5155 ImGui::TextUnformatted(
"Magnetic and gravity reference vectors");
5157 gui::widgets::HelpMarker(
"This register contains the reference vectors for the magnetic and gravitational fields as used by the "
5158 "onboard filter. The values map to either the user-set values or the results of calculations of the onboard "
5159 "reference models (see the Reference Vector Configuration Register in the IMU subsystem). When the "
5160 "reference values come from the onboard model(s), those values are read-only. When the reference models "
5161 "are disabled, the values reflect the user reference vectors and will be writable. For example, if the onboard "
5162 "World Magnetic Model is enabled and the onboard Gravitational Model is disabled, only the gravity "
5163 "reference values will be modified on a register write. Note that the user reference vectors will not be "
5164 "overwritten by the onboard models, but will retain their previous values for when the onboard models are "
5177 catch (
const std::exception& e)
5179 LOG_ERROR(
"{}: Could not configure the magneticAndGravityReferenceVectorsRegister: {}",
nameId(), e.what());
5199 catch (
const std::exception& e)
5201 LOG_ERROR(
"{}: Could not configure the magneticAndGravityReferenceVectorsRegister: {}",
nameId(), e.what());
5214 if (ImGui::TreeNode(fmt::format(
"Reference Vector Configuration##{}",
size_t(
id)).c_str()))
5216 ImGui::TextUnformatted(
"Control register for both the onboard world magnetic and gravity model corrections");
5218 gui::widgets::HelpMarker(
"This register allows configuration of the onboard spherical harmonic models used to calculate the local "
5219 "magnetic and gravitational reference values. Having accurate magnetic reference values improves the "
5220 "accuracy of heading when using the magnetometer and accounts for magnetic declination. Having accurate "
5221 "gravitational reference values improves accuracy by allowing the INS filter to more accurately estimate the "
5222 "accelerometer biases. The VectorNav currently includes the EGM96 gravitational model and the WMM2010 "
5223 "magnetic model. The models are upgradable to allow updating to future models when available.\n\n"
5224 "The magnetic and gravity models can be individually enabled or disabled using the UseMagModel and "
5225 "UseGravityModel parameters, respectively. When disabled, the corresponding values set by the user in the "
5226 "Reference Vector Register in the IMU subsystem will be used instead of values calculated by the onboard "
5228 "The VectorNav starts up with the user configured reference vector values. Shortly after startup (and if the "
5229 "models are enabled), the location and time set in this register will be used to update the reference vectors. "
5230 "When a 3D GNSS fix is available, the location and time reported by the GNSS will be used to update the model. "
5231 "If GNSS is lost, the reference vectors will hold their last valid values. The model values will be recalculated "
5232 "whenever the current position has changed by the RecaclThreshold or the date has changed by more than "
5233 "approximately 8 hours, whichever comes first.");
5245 catch (
const std::exception& e)
5247 LOG_ERROR(
"{}: Could not configure the referenceVectorConfigurationRegister: {}",
nameId(), e.what());
5267 catch (
const std::exception& e)
5269 LOG_ERROR(
"{}: Could not configure the referenceVectorConfigurationRegister: {}",
nameId(), e.what());
5280 if (ImGui::InputInt(fmt::format(
"Recalc Threshold [m]##{}",
size_t(
id)).c_str(), &recalcThreshold))
5291 catch (
const std::exception& e)
5293 LOG_ERROR(
"{}: Could not configure the referenceVectorConfigurationRegister: {}",
nameId(), e.what());
5303 gui::widgets::HelpMarker(
"Maximum distance traveled before magnetic and gravity models are recalculated for the new position.");
5315 catch (
const std::exception& e)
5317 LOG_ERROR(
"{}: Could not configure the referenceVectorConfigurationRegister: {}",
nameId(), e.what());
5327 gui::widgets::HelpMarker(
"The reference date expressed as a decimal year. Used for both the magnetic and gravity models.");
5339 catch (
const std::exception& e)
5341 LOG_ERROR(
"{}: Could not configure the referenceVectorConfigurationRegister: {}",
nameId(), e.what());
5363 catch (
const std::exception& e)
5365 LOG_ERROR(
"{}: Could not configure the referenceVectorConfigurationRegister: {}",
nameId(), e.what());
5387 catch (
const std::exception& e)
5389 LOG_ERROR(
"{}: Could not configure the referenceVectorConfigurationRegister: {}",
nameId(), e.what());
5411 ImGui::SetNextItemOpen(
true, ImGuiCond_FirstUseEver);
5412 if (ImGui::CollapsingHeader(fmt::format(
"Velocity Aiding##{}",
size_t(
id)).c_str()))
5414 if (ImGui::TreeNode(fmt::format(
"Velocity Compensation Control##{}",
size_t(
id)).c_str()))
5416 ImGui::TextUnformatted(
"Provides control over the velocity compensation feature for the attitude filter.");
5418 static constexpr std::array<vn::protocol::uart::VelocityCompensationMode, 2> velocityCompensationControlModes = {
5419 { vn::protocol::uart::VelocityCompensationMode::VELOCITYCOMPENSATIONMODE_DISABLED,
5420 vn::protocol::uart::VelocityCompensationMode::VELOCITYCOMPENSATIONMODE_BODYMEASUREMENT }
5424 for (
const auto& velocityCompensationControlMode : velocityCompensationControlModes)
5427 if (ImGui::Selectable(vn::protocol::uart::str(velocityCompensationControlMode).c_str(), isSelected))
5438 catch (
const std::exception& e)
5440 LOG_ERROR(
"{}: Could not configure the velocityCompensationControlRegister: {}",
nameId(), e.what());
5452 ImGui::SetItemDefaultFocus();
5470 catch (
const std::exception& e)
5472 LOG_ERROR(
"{}: Could not configure the velocityCompensationControlRegister: {}",
nameId(), e.what());
5494 catch (
const std::exception& e)
5496 LOG_ERROR(
"{}: Could not configure the velocityCompensationControlRegister: {}",
nameId(), e.what());
5534 for (
size_t b = 0; b < 3; b++)
5600 if (j.contains(
"UartSensor"))
5604 if (j.contains(
"sensorModel"))
5613 if (j.contains(
"asyncDataOutputType"))
5617 if (j.contains(
"asyncDataOutputFrequency"))
5623 if (j.contains(
"asciiOutputBufferSize"))
5628 if (j.contains(
"syncInPin"))
5636 if (j.contains(
"synchronizationControlRegister"))
5645 if (j.contains(
"communicationProtocolControlRegister"))
5649 if (j.contains(
"binaryOutputRegisterMerge"))
5666 for (
size_t b = 0; b < 3; b++)
5668 if (j.contains(fmt::format(
"binaryOutputRegister{}", b + 1)))
5672 if (j.contains(fmt::format(
"binaryOutputRegister{}-Frequency", b + 1)))
5674 std::string frequency;
5675 j.at(fmt::format(
"binaryOutputRegister{}-Frequency", b + 1)).get_to(frequency);
5691 if (j.contains(
"referenceFrameRotationMatrix"))
5695 if (j.contains(
"imuFilteringConfigurationRegister"))
5699 if (j.contains(
"deltaThetaAndDeltaVelocityConfigurationRegister"))
5703 if (j.contains(
"coupleImuRateOutput"))
5712 if (j.contains(
"gpsConfigurationRegister"))
5716 if (j.contains(
"gpsAntennaOffset"))
5720 if (j.contains(
"gpsCompassBaselineRegister"))
5729 if (j.contains(
"vpeBasicControlRegister"))
5733 if (j.contains(
"vpeMagnetometerBasicTuningRegister"))
5737 if (j.contains(
"vpeAccelerometerBasicTuningRegister"))
5741 if (j.contains(
"vpeGyroBasicTuningRegister"))
5745 if (j.contains(
"filterStartupGyroBias"))
5754 if (j.contains(
"insBasicConfigurationRegisterVn300"))
5758 if (j.contains(
"startupFilterBiasEstimateRegister"))
5767 if (j.contains(
"magnetometerCalibrationControlRegister"))
5776 if (j.contains(
"magneticAndGravityReferenceVectorsRegister"))
5780 if (j.contains(
"referenceVectorConfigurationRegister"))
5789 if (j.contains(
"velocityCompensationControlRegister"))
5822 ?
static_cast<Baudrate>(vn::sensors::VnSensor::supportedBaudrates()[vn::sensors::VnSensor::supportedBaudrates().size() - 1])
5829 size_t maxTries = std::filesystem::exists(
_sensorPort) ? 5 : 0;
5830 for (
size_t i = 0; i < maxTries; ++i)
5832 if (int32_t foundBaudrate = 0;
5833 vn::sensors::Searcher::search(
_sensorPort, &foundBaudrate))
5836 connectedBaudrate =
static_cast<Baudrate>(foundBaudrate);
5838 LOG_DEBUG(
"{}: Found VectorNav sensor on specified port '{}' with baudrate {} (it took {} attempts to connect)",
5851 for (
size_t i = 0; i < 5; ++i)
5858 if (std::vector<std::pair<std::string, uint32_t>> foundSensors = vn::sensors::Searcher::search();
5859 !foundSensors.empty())
5861 for (
const auto& [port, baudrate] : foundSensors)
5863 _vs.connect(port, baudrate);
5864 std::string modelNumber =
_vs.readModelNumber();
5867 LOG_DEBUG(
"{}: Found VectorNav sensor '{}' on port '{}' with baudrate {} ({} VN sensors connected in total)",
5868 nameId(), modelNumber, port, baudrate, foundSensors.size());
5872 if (modelNumber.find(searchString) != std::string::npos)
5875 connectedBaudrate =
static_cast<Baudrate>(baudrate);
5877 LOG_DEBUG(
"{}: Selected VectorNav sensor '{}' on port '{}' (it took {} attempts to connect)",
5878 nameId(), modelNumber, port, i + 1);
5886 LOG_ERROR(
"{}: Could not connect. Is the sensor connected and do you have read permissions?",
nameId());
5896 catch (
const std::exception& e)
5898 LOG_ERROR(
"{}: Failed to connect to sensor on port '{}' with baudrate {} with error: {}",
nameId(),
5905 if (!
_vs.verifySensorConnectivity())
5907 LOG_ERROR(
"{}: Connected to sensor on port '{}' with baudrate {} but sensor does not answer",
nameId(),
5912 catch (
const std::exception& e)
5914 LOG_ERROR(
"{}: Connected to sensor on port '{}' with baudrate {} but sensor threw an exception: {}",
nameId(),
5920 auto modelNumber =
_vs.readModelNumber();
5925 LOG_ERROR(
"{}: VN100/VN110 configured, but sensor identifies as {}",
nameId(), modelNumber);
5931 LOG_ERROR(
"{}: VN310 configured, but sensor identifies as {}",
nameId(), modelNumber);
5941 if (targetBaudrate != connectedBaudrate)
5943 auto suppBaud = vn::sensors::VnSensor::supportedBaudrates();
5944 if (std::ranges::find(suppBaud, targetBaudrate) != suppBaud.end())
5946 _vs.changeBaudRate(targetBaudrate);
5947 LOG_DEBUG(
"{}: Baudrate changed to {}",
nameId(),
static_cast<size_t>(targetBaudrate));
5951 LOG_ERROR(
"{}: Does not support baudrate {}",
nameId(),
static_cast<size_t>(targetBaudrate));
5955 if (
_vs.readSerialBaudRate() != targetBaudrate)
5957 LOG_ERROR(
"{}: Changing the baudrate from {} to {} was not successfull",
nameId(),
_vs.readSerialBaudRate(), targetBaudrate);
5963 if (
auto vnSynchronizationControlRegister =
_vs.readSynchronizationControl();
5972 LOG_ERROR(
"{}: Writing the synchronizationControlRegister was not successfull.\n"
5973 "Target: syncInMode = {}, syncInEdge = {}, syncInSkipFactor = {}, syncOutMode = {}, syncOutPolarity = {}, syncOutSkipFactor = {}, syncOutPulseWidth = {}\n"
5974 "Sensor: syncInMode = {}, syncInEdge = {}, syncInSkipFactor = {}, syncOutMode = {}, syncOutPolarity = {}, syncOutSkipFactor = {}, syncOutPulseWidth = {}",
5977 vnSynchronizationControlRegister.syncInMode, vnSynchronizationControlRegister.syncInEdge, vnSynchronizationControlRegister.syncInSkipFactor, vnSynchronizationControlRegister.syncOutMode, vnSynchronizationControlRegister.syncOutPolarity, vnSynchronizationControlRegister.syncOutSkipFactor, vnSynchronizationControlRegister.syncOutPulseWidth);
5983 if (
auto vnCommunicationProtocolControlRegister =
_vs.readCommunicationProtocolControl();
5992 LOG_ERROR(
"{}: Writing the communicationProtocolControlRegister was not successfull.\n"
5993 "Target: serialCount = {}, serialStatus = {}, spiCount = {}, spiStatus = {}, serialChecksum = {}, spiChecksum = {}, errorMode = {}\n"
5994 "Sensor: serialCount = {}, serialStatus = {}, spiCount = {}, spiStatus = {}, serialChecksum = {}, spiChecksum = {}, errorMode = {}",
5997 vnCommunicationProtocolControlRegister.serialCount, vnCommunicationProtocolControlRegister.serialStatus, vnCommunicationProtocolControlRegister.spiCount, vnCommunicationProtocolControlRegister.spiStatus, vnCommunicationProtocolControlRegister.serialChecksum, vnCommunicationProtocolControlRegister.spiChecksum, vnCommunicationProtocolControlRegister.errorMode);
6013 if (
auto vnReferenceFrameRotationMatrix =
_vs.readReferenceFrameRotation();
6016 LOG_ERROR(
"{}: Writing the referenceFrameRotationMatrix was not successfull.\n"
6017 "Target: DCM = {}\n"
6025 if (
auto vnImuFilteringConfigurationRegister =
_vs.readImuFilteringConfiguration();
6037 LOG_ERROR(
"{}: Writing the imuFilteringConfigurationRegister was not successfull.\n"
6038 "Target: magWindowSize = {}, accelWindowSize = {}, gyroWindowSize = {}, tempWindowSize = {}, presWindowSize = {}, magFilterMode = {}, accelFilterMode = {}, gyroFilterMode = {}, tempFilterMode = {}, presFilterMode = {}\n"
6039 "Sensor: magWindowSize = {}, accelWindowSize = {}, gyroWindowSize = {}, tempWindowSize = {}, presWindowSize = {}, magFilterMode = {}, accelFilterMode = {}, gyroFilterMode = {}, tempFilterMode = {}, presFilterMode = {}",
6041 _imuFilteringConfigurationRegister.magWindowSize,
_imuFilteringConfigurationRegister.accelWindowSize,
_imuFilteringConfigurationRegister.gyroWindowSize,
_imuFilteringConfigurationRegister.tempWindowSize,
_imuFilteringConfigurationRegister.presWindowSize,
_imuFilteringConfigurationRegister.magFilterMode,
_imuFilteringConfigurationRegister.accelFilterMode,
_imuFilteringConfigurationRegister.gyroFilterMode,
_imuFilteringConfigurationRegister.tempFilterMode,
_imuFilteringConfigurationRegister.presFilterMode,
6042 vnImuFilteringConfigurationRegister.magWindowSize, vnImuFilteringConfigurationRegister.accelWindowSize, vnImuFilteringConfigurationRegister.gyroWindowSize, vnImuFilteringConfigurationRegister.tempWindowSize, vnImuFilteringConfigurationRegister.presWindowSize, vnImuFilteringConfigurationRegister.magFilterMode, vnImuFilteringConfigurationRegister.accelFilterMode, vnImuFilteringConfigurationRegister.gyroFilterMode, vnImuFilteringConfigurationRegister.tempFilterMode, vnImuFilteringConfigurationRegister.presFilterMode);
6048 if (
auto vnDeltaThetaAndDeltaVelocityConfigurationRegister =
_vs.readDeltaThetaAndDeltaVelocityConfiguration();
6054 LOG_ERROR(
"{}: Writing the deltaThetaAndDeltaVelocityConfigurationRegister was not successfull.\n"
6055 "Target: integrationFrame = {}, gyroCompensation = {}, accelCompensation = {}, earthRateCorrection = {}\n"
6056 "Sensor: integrationFrame = {}, gyroCompensation = {}, accelCompensation = {}, earthRateCorrection = {}",
6059 vnDeltaThetaAndDeltaVelocityConfigurationRegister.integrationFrame, vnDeltaThetaAndDeltaVelocityConfigurationRegister.gyroCompensation, vnDeltaThetaAndDeltaVelocityConfigurationRegister.accelCompensation, vnDeltaThetaAndDeltaVelocityConfigurationRegister.earthRateCorrection);
6071 if (
auto vnGpsConfigurationRegister =
_vs.readGpsConfiguration();
6077 LOG_ERROR(
"{}: Writing the gpsConfigurationRegister was not successfull.\n"
6078 "Target: mode = {}, ppsSource = {}, rate = {}, antPow = {}\n"
6079 "Sensor: mode = {}, ppsSource = {}, rate = {}, antPow = {}",
6082 vnGpsConfigurationRegister.mode, vnGpsConfigurationRegister.ppsSource, vnGpsConfigurationRegister.rate, vnGpsConfigurationRegister.antPow);
6088 if (
auto vnGpsAntennaOffset =
_vs.readGpsAntennaOffset();
6091 LOG_ERROR(
"{}: Writing the gpsAntennaOffset was not successfull.\n"
6096 vnGpsAntennaOffset);
6102 if (
auto vnGpsCompassBaselineRegister =
_vs.readGpsCompassBaseline();
6106 LOG_ERROR(
"{}: Writing the gpsCompassBaselineRegister was not successfull.\n"
6107 "Target: position = {}, uncertainty = {}\n"
6108 "Sensor: position = {}, uncertainty = {}",
6111 vnGpsCompassBaselineRegister.position, vnGpsCompassBaselineRegister.uncertainty);
6131 if (
auto vnVpeBasicControlRegister =
_vs.readVpeBasicControl();
6137 LOG_ERROR(
"{}: Writing the vpeBasicControlRegister was not successfull.\n"
6138 "Target: enable = {}, headingMode = {}, filteringMode = {}, tuningMode = {}\n"
6139 "Sensor: enable = {}, headingMode = {}, filteringMode = {}, tuningMode = {}",
6142 vnVpeBasicControlRegister.enable, vnVpeBasicControlRegister.headingMode, vnVpeBasicControlRegister.filteringMode, vnVpeBasicControlRegister.tuningMode);
6150 if (
auto vnVpeMagnetometerBasicTuningRegister =
_vs.readVpeMagnetometerBasicTuning();
6155 LOG_ERROR(
"{}: Writing the vpeMagnetometerBasicTuningRegister was not successfull.\n"
6156 "Target: baseTuning = {}, adaptiveTuning = {}, adaptiveFiltering = {}\n"
6157 "Sensor: baseTuning = {}, adaptiveTuning = {}, adaptiveFiltering = {}",
6160 vnVpeMagnetometerBasicTuningRegister.baseTuning, vnVpeMagnetometerBasicTuningRegister.adaptiveTuning, vnVpeMagnetometerBasicTuningRegister.adaptiveFiltering);
6166 if (
auto vnVpeAccelerometerBasicTuningRegister =
_vs.readVpeAccelerometerBasicTuning();
6171 LOG_ERROR(
"{}: Writing the vpeAccelerometerBasicTuningRegister was not successfull.\n"
6172 "Target: baseTuning = {}, adaptiveTuning = {}, adaptiveFiltering = {}\n"
6173 "Sensor: baseTuning = {}, adaptiveTuning = {}, adaptiveFiltering = {}",
6176 vnVpeAccelerometerBasicTuningRegister.baseTuning, vnVpeAccelerometerBasicTuningRegister.adaptiveTuning, vnVpeAccelerometerBasicTuningRegister.adaptiveFiltering);
6182 if (
auto vnFilterStartupGyroBias =
_vs.readFilterStartupGyroBias();
6185 LOG_ERROR(
"{}: Writing the filterStartupGyroBias was not successfull.\n"
6190 vnFilterStartupGyroBias);
6196 if (
auto vnVpeGyroBasicTuningRegister =
_vs.readVpeGyroBasicTuning();
6201 LOG_ERROR(
"{}: Writing the vpeGyroBasicTuningRegister was not successfull.\n"
6202 "Target: angularWalkVariance = {}, baseTuning = {}, adaptiveTuning = {}\n"
6203 "Sensor: angularWalkVariance = {}, baseTuning = {}, adaptiveTuning = {}",
6206 vnVpeGyroBasicTuningRegister.angularWalkVariance, vnVpeGyroBasicTuningRegister.baseTuning, vnVpeGyroBasicTuningRegister.adaptiveTuning);
6219 if (
auto vnInsBasicConfigurationRegisterVn300 =
_vs.readInsBasicConfigurationVn300();
6224 LOG_ERROR(
"{}: Writing the insBasicConfigurationRegisterVn300 was not successfull.\n"
6225 "Target: scenario = {}, ahrsAiding = {}, estBaseline = {}\n"
6226 "Sensor: scenario = {}, ahrsAiding = {}, estBaseline = {}",
6229 vnInsBasicConfigurationRegisterVn300.scenario, vnInsBasicConfigurationRegisterVn300.ahrsAiding, vnInsBasicConfigurationRegisterVn300.estBaseline);
6235 if (
auto vnStartupFilterBiasEstimateRegister =
_vs.readStartupFilterBiasEstimate();
6240 LOG_ERROR(
"{}: Writing the startupFilterBiasEstimateRegister was not successfull.\n"
6241 "Target: gyroBias = {}, accelBias = {}, pressureBias = {}\n"
6242 "Sensor: gyroBias = {}, accelBias = {}, pressureBias = {}",
6245 vnStartupFilterBiasEstimateRegister.gyroBias, vnStartupFilterBiasEstimateRegister.accelBias, vnStartupFilterBiasEstimateRegister.pressureBias);
6256 if (
auto vnMagnetometerCalibrationControlRegister =
_vs.readMagnetometerCalibrationControl();
6261 LOG_ERROR(
"{}: Writing the magnetometerCalibrationControlRegister was not successfull.\n"
6262 "Target: hsiMode = {}, hsiOutput = {}, convergeRate = {}\n"
6263 "Sensor: hsiMode = {}, hsiOutput = {}, convergeRate = {}",
6266 vnMagnetometerCalibrationControlRegister.hsiMode, vnMagnetometerCalibrationControlRegister.hsiOutput, vnMagnetometerCalibrationControlRegister.convergeRate);
6276 if (
auto vnMagneticAndGravityReferenceVectorsRegister =
_vs.readMagneticAndGravityReferenceVectors();
6280 LOG_ERROR(
"{}: Writing the magneticAndGravityReferenceVectorsRegister was not successfull.\n"
6281 "Target: magRef = {}, accRef = {}\n"
6282 "Sensor: magRef = {}, accRef = {}",
6285 vnMagneticAndGravityReferenceVectorsRegister.magRef, vnMagneticAndGravityReferenceVectorsRegister.accRef);
6291 if (
auto vnReferenceVectorConfigurationRegister =
_vs.readReferenceVectorConfiguration();
6298 LOG_ERROR(
"{}: Writing the referenceVectorConfigurationRegister was not successfull.\n"
6299 "Target: useMagModel = {}, useGravityModel = {}, recalcThreshold = {}, year = {}, position = {}\n"
6300 "Sensor: useMagModel = {}, useGravityModel = {}, recalcThreshold = {}, year = {}, position = {}",
6303 vnReferenceVectorConfigurationRegister.useMagModel, vnReferenceVectorConfigurationRegister.useGravityModel, vnReferenceVectorConfigurationRegister.recalcThreshold, vnReferenceVectorConfigurationRegister.year, vnReferenceVectorConfigurationRegister.position);
6315 if (
auto vnVelocityCompensationControlRegister =
_vs.readVelocityCompensationControl();
6320 LOG_ERROR(
"{}: Writing the velocityCompensationControlRegister was not successfull.\n"
6321 "Target: mode = {}, velocityTuning = {}, rateTuning = {}\n"
6322 "Sensor: mode = {}, velocityTuning = {}, rateTuning = {}",
6325 vnVelocityCompensationControlRegister.mode, vnVelocityCompensationControlRegister.velocityTuning, vnVelocityCompensationControlRegister.rateTuning);
6338 if (
auto vnAsyncDataOutputType =
_vs.readAsyncDataOutputType();
6341 LOG_ERROR(
"{}: Writing the asyncDataOutputType was not successfull.\n"
6346 vnAsyncDataOutputType);
6354 if (
auto vnAsyncDataOutputFrequency =
_vs.readAsyncDataOutputType();
6357 LOG_ERROR(
"{}: Writing the asyncDataOutputFrequency was not successfull.\n"
6362 vnAsyncDataOutputFrequency);
6368 [[maybe_unused]]
size_t binaryOutputRegisterCounter = 1;
6402 binaryOutputRegisterCounter++;
6410 binaryOutputRegisterCounter++;
6418 catch (
const std::exception& e)
6420 LOG_ERROR(
"{}: Could not configure binary output register {}: {}",
nameId(), binaryOutputRegisterCounter, e.what());
6427 _vs.writeSettings();
6429 LOG_DEBUG(
"{}: Resetting device to apply permenent settings",
nameId());
6448 if (
_vs.isConnected())
6452 _vs.unregisterAsyncPacketReceivedHandler();
6454 catch (
const std::exception& e)
6456 LOG_WARN(
"{}: Could not unregisterAsyncPacketReceivedHandler ({})",
nameId(), e.what());
6461 vn::sensors::BinaryOutputRegister bor{
6462 vn::protocol::uart::AsyncMode::ASYNCMODE_NONE,
6464 vn::protocol::uart::CommonGroup::COMMONGROUP_NONE,
6465 vn::protocol::uart::TimeGroup::TIMEGROUP_NONE,
6466 vn::protocol::uart::ImuGroup::IMUGROUP_NONE,
6467 vn::protocol::uart::GpsGroup::GPSGROUP_NONE,
6468 vn::protocol::uart::AttitudeGroup::ATTITUDEGROUP_NONE,
6469 vn::protocol::uart::InsGroup::INSGROUP_NONE,
6470 vn::protocol::uart::GpsGroup::GPSGROUP_NONE
6473 _vs.writeBinaryOutput1(bor);
6474 _vs.writeBinaryOutput2(bor);
6475 _vs.writeBinaryOutput3(bor);
6476 _vs.writeAsyncDataOutputType(vn::protocol::uart::AsciiAsync::VNOFF);
6478 _vs.writeSettings();
6481 catch (
const std::exception& e)
6483 LOG_WARN(
"{}: Could not turn off sensor output ({})",
nameId(), e.what());
6491 catch (
const std::exception& e)
6497 catch (
const std::exception& e)
6499 LOG_WARN(
"{}: Unhandled exception while deinitializing sensor ({})",
nameId(), e.what());
6505 target->insTime = !target->insTime.empty() ? target->insTime : source->insTime;
6507 if (!target->timeOutputs && source->timeOutputs)
6509 target->timeOutputs = source->timeOutputs;
6511 else if (target->timeOutputs && source->timeOutputs)
6513 target->timeOutputs->timeStartup = target->timeOutputs->timeField & vn::protocol::uart::TimeGroup::TIMEGROUP_TIMESTARTUP ? target->timeOutputs->timeStartup : source->timeOutputs->timeStartup;
6514 target->timeOutputs->timeGps = target->timeOutputs->timeField & vn::protocol::uart::TimeGroup::TIMEGROUP_TIMEGPS ? target->timeOutputs->timeGps : source->timeOutputs->timeGps;
6515 target->timeOutputs->gpsTow = target->timeOutputs->timeField & vn::protocol::uart::TimeGroup::TIMEGROUP_GPSTOW ? target->timeOutputs->gpsTow : source->timeOutputs->gpsTow;
6516 target->timeOutputs->gpsWeek = target->timeOutputs->timeField & vn::protocol::uart::TimeGroup::TIMEGROUP_GPSWEEK ? target->timeOutputs->gpsWeek : source->timeOutputs->gpsWeek;
6517 target->timeOutputs->timeSyncIn = target->timeOutputs->timeField & vn::protocol::uart::TimeGroup::TIMEGROUP_TIMESYNCIN ? target->timeOutputs->timeSyncIn : source->timeOutputs->timeSyncIn;
6518 target->timeOutputs->timePPS = target->timeOutputs->timeField & vn::protocol::uart::TimeGroup::TIMEGROUP_TIMEGPSPPS ? target->timeOutputs->timePPS : source->timeOutputs->timePPS;
6520 target->timeOutputs->syncInCnt = target->timeOutputs->timeField & vn::protocol::uart::TimeGroup::TIMEGROUP_SYNCINCNT ? target->timeOutputs->syncInCnt : source->timeOutputs->syncInCnt;
6521 target->timeOutputs->syncOutCnt = target->timeOutputs->timeField & vn::protocol::uart::TimeGroup::TIMEGROUP_SYNCOUTCNT ? target->timeOutputs->syncOutCnt : source->timeOutputs->syncOutCnt;
6522 target->timeOutputs->timeStatus = target->timeOutputs->timeField & vn::protocol::uart::TimeGroup::TIMEGROUP_TIMESTATUS ? target->timeOutputs->timeStatus : source->timeOutputs->timeStatus;
6524 target->timeOutputs->timeField |= source->timeOutputs->timeField;
6527 if (!target->imuOutputs && source->imuOutputs)
6529 target->imuOutputs = source->imuOutputs;
6531 else if (target->imuOutputs && source->imuOutputs)
6533 target->imuOutputs->imuStatus = target->imuOutputs->imuField & vn::protocol::uart::ImuGroup::IMUGROUP_IMUSTATUS ? target->imuOutputs->imuStatus : source->imuOutputs->imuStatus;
6534 target->imuOutputs->uncompMag = target->imuOutputs->imuField & vn::protocol::uart::ImuGroup::IMUGROUP_UNCOMPMAG ? target->imuOutputs->uncompMag : source->imuOutputs->uncompMag;
6535 target->imuOutputs->uncompAccel = target->imuOutputs->imuField & vn::protocol::uart::ImuGroup::IMUGROUP_UNCOMPACCEL ? target->imuOutputs->uncompAccel : source->imuOutputs->uncompAccel;
6536 target->imuOutputs->uncompGyro = target->imuOutputs->imuField & vn::protocol::uart::ImuGroup::IMUGROUP_UNCOMPGYRO ? target->imuOutputs->uncompGyro : source->imuOutputs->uncompGyro;
6537 target->imuOutputs->temp = target->imuOutputs->imuField & vn::protocol::uart::ImuGroup::IMUGROUP_TEMP ? target->imuOutputs->temp : source->imuOutputs->temp;
6538 target->imuOutputs->pres = target->imuOutputs->imuField & vn::protocol::uart::ImuGroup::IMUGROUP_PRES ? target->imuOutputs->pres : source->imuOutputs->pres;
6539 target->imuOutputs->deltaTime = target->imuOutputs->imuField & vn::protocol::uart::ImuGroup::IMUGROUP_DELTATHETA ? target->imuOutputs->deltaTime : source->imuOutputs->deltaTime;
6540 target->imuOutputs->deltaTheta = target->imuOutputs->imuField & vn::protocol::uart::ImuGroup::IMUGROUP_DELTATHETA ? target->imuOutputs->deltaTheta : source->imuOutputs->deltaTheta;
6541 target->imuOutputs->deltaV = target->imuOutputs->imuField & vn::protocol::uart::ImuGroup::IMUGROUP_DELTAVEL ? target->imuOutputs->deltaV : source->imuOutputs->deltaV;
6542 target->imuOutputs->mag = target->imuOutputs->imuField & vn::protocol::uart::ImuGroup::IMUGROUP_MAG ? target->imuOutputs->mag : source->imuOutputs->mag;
6543 target->imuOutputs->accel = target->imuOutputs->imuField & vn::protocol::uart::ImuGroup::IMUGROUP_ACCEL ? target->imuOutputs->accel : source->imuOutputs->accel;
6544 target->imuOutputs->angularRate = target->imuOutputs->imuField & vn::protocol::uart::ImuGroup::IMUGROUP_ANGULARRATE ? target->imuOutputs->angularRate : source->imuOutputs->angularRate;
6546 target->imuOutputs->imuField |= source->imuOutputs->imuField;
6549 if (!target->gnss1Outputs && source->gnss1Outputs)
6551 target->gnss1Outputs = source->gnss1Outputs;
6553 else if (target->gnss1Outputs && source->gnss1Outputs)
6556 target->gnss1Outputs->tow = target->gnss1Outputs->gnssField & vn::protocol::uart::GpsGroup::GPSGROUP_TOW ? target->gnss1Outputs->tow : source->gnss1Outputs->tow;
6557 target->gnss1Outputs->week = target->gnss1Outputs->gnssField & vn::protocol::uart::GpsGroup::GPSGROUP_WEEK ? target->gnss1Outputs->week : source->gnss1Outputs->week;
6558 target->gnss1Outputs->numSats = target->gnss1Outputs->gnssField & vn::protocol::uart::GpsGroup::GPSGROUP_NUMSATS ? target->gnss1Outputs->numSats : source->gnss1Outputs->numSats;
6559 target->gnss1Outputs->fix = target->gnss1Outputs->gnssField & vn::protocol::uart::GpsGroup::GPSGROUP_FIX ? target->gnss1Outputs->fix : source->gnss1Outputs->fix;
6560 target->gnss1Outputs->posLla = target->gnss1Outputs->gnssField & vn::protocol::uart::GpsGroup::GPSGROUP_POSLLA ? target->gnss1Outputs->posLla : source->gnss1Outputs->posLla;
6561 target->gnss1Outputs->posEcef = target->gnss1Outputs->gnssField & vn::protocol::uart::GpsGroup::GPSGROUP_POSECEF ? target->gnss1Outputs->posEcef : source->gnss1Outputs->posEcef;
6562 target->gnss1Outputs->velNed = target->gnss1Outputs->gnssField & vn::protocol::uart::GpsGroup::GPSGROUP_VELNED ? target->gnss1Outputs->velNed : source->gnss1Outputs->velNed;
6563 target->gnss1Outputs->velEcef = target->gnss1Outputs->gnssField & vn::protocol::uart::GpsGroup::GPSGROUP_VELECEF ? target->gnss1Outputs->velEcef : source->gnss1Outputs->velEcef;
6564 target->gnss1Outputs->posU = target->gnss1Outputs->gnssField & vn::protocol::uart::GpsGroup::GPSGROUP_POSU ? target->gnss1Outputs->posU : source->gnss1Outputs->posU;
6565 target->gnss1Outputs->velU = target->gnss1Outputs->gnssField & vn::protocol::uart::GpsGroup::GPSGROUP_VELU ? target->gnss1Outputs->velU : source->gnss1Outputs->velU;
6566 target->gnss1Outputs->timeU = target->gnss1Outputs->gnssField & vn::protocol::uart::GpsGroup::GPSGROUP_TIMEU ? target->gnss1Outputs->timeU : source->gnss1Outputs->timeU;
6567 target->gnss1Outputs->timeInfo = target->gnss1Outputs->gnssField & vn::protocol::uart::GpsGroup::GPSGROUP_TIMEINFO ? target->gnss1Outputs->timeInfo : source->gnss1Outputs->timeInfo;
6568 target->gnss1Outputs->dop = target->gnss1Outputs->gnssField & vn::protocol::uart::GpsGroup::GPSGROUP_DOP ? target->gnss1Outputs->dop : source->gnss1Outputs->dop;
6569 target->gnss1Outputs->satInfo = target->gnss1Outputs->gnssField & vn::protocol::uart::GpsGroup::GPSGROUP_SATINFO ? target->gnss1Outputs->satInfo : source->gnss1Outputs->satInfo;
6570 target->gnss1Outputs->raw = target->gnss1Outputs->gnssField & vn::protocol::uart::GpsGroup::GPSGROUP_RAWMEAS ? target->gnss1Outputs->raw : source->gnss1Outputs->raw;
6572 target->gnss1Outputs->gnssField |= source->gnss1Outputs->gnssField;
6575 if (!target->attitudeOutputs && source->attitudeOutputs)
6577 target->attitudeOutputs = source->attitudeOutputs;
6579 else if (target->attitudeOutputs && source->attitudeOutputs)
6581 target->attitudeOutputs->vpeStatus = target->attitudeOutputs->attitudeField & vn::protocol::uart::AttitudeGroup::ATTITUDEGROUP_VPESTATUS ? target->attitudeOutputs->vpeStatus : source->attitudeOutputs->vpeStatus;
6582 target->attitudeOutputs->ypr = target->attitudeOutputs->attitudeField & vn::protocol::uart::AttitudeGroup::ATTITUDEGROUP_YAWPITCHROLL ? target->attitudeOutputs->ypr : source->attitudeOutputs->ypr;
6583 target->attitudeOutputs->qtn = target->attitudeOutputs->attitudeField & vn::protocol::uart::AttitudeGroup::ATTITUDEGROUP_QUATERNION ? target->attitudeOutputs->qtn : source->attitudeOutputs->qtn;
6584 target->attitudeOutputs->dcm = target->attitudeOutputs->attitudeField & vn::protocol::uart::AttitudeGroup::ATTITUDEGROUP_DCM ? target->attitudeOutputs->dcm : source->attitudeOutputs->dcm;
6585 target->attitudeOutputs->magNed = target->attitudeOutputs->attitudeField & vn::protocol::uart::AttitudeGroup::ATTITUDEGROUP_MAGNED ? target->attitudeOutputs->magNed : source->attitudeOutputs->magNed;
6586 target->attitudeOutputs->accelNed = target->attitudeOutputs->attitudeField & vn::protocol::uart::AttitudeGroup::ATTITUDEGROUP_ACCELNED ? target->attitudeOutputs->accelNed : source->attitudeOutputs->accelNed;
6587 target->attitudeOutputs->linearAccelBody = target->attitudeOutputs->attitudeField & vn::protocol::uart::AttitudeGroup::ATTITUDEGROUP_LINEARACCELBODY ? target->attitudeOutputs->linearAccelBody : source->attitudeOutputs->linearAccelBody;
6588 target->attitudeOutputs->linearAccelNed = target->attitudeOutputs->attitudeField & vn::protocol::uart::AttitudeGroup::ATTITUDEGROUP_LINEARACCELNED ? target->attitudeOutputs->linearAccelNed : source->attitudeOutputs->linearAccelNed;
6589 target->attitudeOutputs->yprU = target->attitudeOutputs->attitudeField & vn::protocol::uart::AttitudeGroup::ATTITUDEGROUP_YPRU ? target->attitudeOutputs->yprU : source->attitudeOutputs->yprU;
6591 target->attitudeOutputs->attitudeField |= source->attitudeOutputs->attitudeField;
6594 if (!target->insOutputs && source->insOutputs)
6596 target->insOutputs = source->insOutputs;
6598 else if (target->insOutputs && source->insOutputs)
6600 target->insOutputs->insStatus = target->insOutputs->insField & vn::protocol::uart::InsGroup::INSGROUP_INSSTATUS ? target->insOutputs->insStatus : source->insOutputs->insStatus;
6601 target->insOutputs->posLla = target->insOutputs->insField & vn::protocol::uart::InsGroup::INSGROUP_POSLLA ? target->insOutputs->posLla : source->insOutputs->posLla;
6602 target->insOutputs->posEcef = target->insOutputs->insField & vn::protocol::uart::InsGroup::INSGROUP_POSECEF ? target->insOutputs->posEcef : source->insOutputs->posEcef;
6603 target->insOutputs->velBody = target->insOutputs->insField & vn::protocol::uart::InsGroup::INSGROUP_VELBODY ? target->insOutputs->velBody : source->insOutputs->velBody;
6604 target->insOutputs->velNed = target->insOutputs->insField & vn::protocol::uart::InsGroup::INSGROUP_VELNED ? target->insOutputs->velNed : source->insOutputs->velNed;
6605 target->insOutputs->velEcef = target->insOutputs->insField & vn::protocol::uart::InsGroup::INSGROUP_VELECEF ? target->insOutputs->velEcef : source->insOutputs->velEcef;
6606 target->insOutputs->magEcef = target->insOutputs->insField & vn::protocol::uart::InsGroup::INSGROUP_MAGECEF ? target->insOutputs->magEcef : source->insOutputs->magEcef;
6607 target->insOutputs->accelEcef = target->insOutputs->insField & vn::protocol::uart::InsGroup::INSGROUP_ACCELECEF ? target->insOutputs->accelEcef : source->insOutputs->accelEcef;
6608 target->insOutputs->linearAccelEcef = target->insOutputs->insField & vn::protocol::uart::InsGroup::INSGROUP_LINEARACCELECEF ? target->insOutputs->linearAccelEcef : source->insOutputs->linearAccelEcef;
6609 target->insOutputs->posU = target->insOutputs->insField & vn::protocol::uart::InsGroup::INSGROUP_POSU ? target->insOutputs->posU : source->insOutputs->posU;
6610 target->insOutputs->velU = target->insOutputs->insField & vn::protocol::uart::InsGroup::INSGROUP_VELU ? target->insOutputs->velU : source->insOutputs->velU;
6612 target->insOutputs->insField |= source->insOutputs->insField;
6615 if (!target->gnss2Outputs && source->gnss2Outputs)
6617 target->gnss2Outputs = source->gnss2Outputs;
6619 else if (target->gnss2Outputs && source->gnss2Outputs)
6622 target->gnss2Outputs->tow = target->gnss2Outputs->gnssField & vn::protocol::uart::GpsGroup::GPSGROUP_TOW ? target->gnss2Outputs->tow : source->gnss2Outputs->tow;
6623 target->gnss2Outputs->week = target->gnss2Outputs->gnssField & vn::protocol::uart::GpsGroup::GPSGROUP_WEEK ? target->gnss2Outputs->week : source->gnss2Outputs->week;
6624 target->gnss2Outputs->numSats = target->gnss2Outputs->gnssField & vn::protocol::uart::GpsGroup::GPSGROUP_NUMSATS ? target->gnss2Outputs->numSats : source->gnss2Outputs->numSats;
6625 target->gnss2Outputs->fix = target->gnss2Outputs->gnssField & vn::protocol::uart::GpsGroup::GPSGROUP_FIX ? target->gnss2Outputs->fix : source->gnss2Outputs->fix;
6626 target->gnss2Outputs->posLla = target->gnss2Outputs->gnssField & vn::protocol::uart::GpsGroup::GPSGROUP_POSLLA ? target->gnss2Outputs->posLla : source->gnss2Outputs->posLla;
6627 target->gnss2Outputs->posEcef = target->gnss2Outputs->gnssField & vn::protocol::uart::GpsGroup::GPSGROUP_POSECEF ? target->gnss2Outputs->posEcef : source->gnss2Outputs->posEcef;
6628 target->gnss2Outputs->velNed = target->gnss2Outputs->gnssField & vn::protocol::uart::GpsGroup::GPSGROUP_VELNED ? target->gnss2Outputs->velNed : source->gnss2Outputs->velNed;
6629 target->gnss2Outputs->velEcef = target->gnss2Outputs->gnssField & vn::protocol::uart::GpsGroup::GPSGROUP_VELECEF ? target->gnss2Outputs->velEcef : source->gnss2Outputs->velEcef;
6630 target->gnss2Outputs->posU = target->gnss2Outputs->gnssField & vn::protocol::uart::GpsGroup::GPSGROUP_POSU ? target->gnss2Outputs->posU : source->gnss2Outputs->posU;
6631 target->gnss2Outputs->velU = target->gnss2Outputs->gnssField & vn::protocol::uart::GpsGroup::GPSGROUP_VELU ? target->gnss2Outputs->velU : source->gnss2Outputs->velU;
6632 target->gnss2Outputs->timeU = target->gnss2Outputs->gnssField & vn::protocol::uart::GpsGroup::GPSGROUP_TIMEU ? target->gnss2Outputs->timeU : source->gnss2Outputs->timeU;
6633 target->gnss2Outputs->timeInfo = target->gnss2Outputs->gnssField & vn::protocol::uart::GpsGroup::GPSGROUP_TIMEINFO ? target->gnss2Outputs->timeInfo : source->gnss2Outputs->timeInfo;
6634 target->gnss2Outputs->dop = target->gnss2Outputs->gnssField & vn::protocol::uart::GpsGroup::GPSGROUP_DOP ? target->gnss2Outputs->dop : source->gnss2Outputs->dop;
6635 target->gnss2Outputs->satInfo = target->gnss2Outputs->gnssField & vn::protocol::uart::GpsGroup::GPSGROUP_SATINFO ? target->gnss2Outputs->satInfo : source->gnss2Outputs->satInfo;
6636 target->gnss2Outputs->raw = target->gnss2Outputs->gnssField & vn::protocol::uart::GpsGroup::GPSGROUP_RAWMEAS ? target->gnss2Outputs->raw : source->gnss2Outputs->raw;
6638 target->gnss2Outputs->gnssField |= source->gnss2Outputs->gnssField;
6646 LOG_DATA(
"{}: Received message", vnSensor->nameId());
6648 if (p.getPacketLength() > 2500)
6650 LOG_ERROR(
"{} Packet size is {} bytes. VectorNav internal buffer overflows happen if the size is > 2550 bytes. "
6651 "You potentially already lost packages without noticing. "
6652 "Consider splitting the packet to different Binary outputs.",
6653 vnSensor->nameId(), p.getPacketLength());
6655 else if (p.getPacketLength() > 2200)
6657 LOG_WARN(
"{} Packet size is {} bytes. VectorNav internal buffer overflows happen if the size is > 2550 bytes. "
6658 "Consider splitting the packet to different Binary outputs.",
6659 vnSensor->nameId(), p.getPacketLength());
6662 if (p.type() == vn::protocol::uart::Packet::TYPE_BINARY)
6664 for (
size_t b = 0; b < 3; b++)
6667 if (p.isCompatible(vnSensor->_binaryOutputRegister.at(b).commonField,
6668 vnSensor->_binaryOutputRegister.at(b).timeField,
6669 vnSensor->_binaryOutputRegister.at(b).imuField,
6670 vnSensor->_binaryOutputRegister.at(b).gpsField,
6671 vnSensor->_binaryOutputRegister.at(b).attitudeField,
6672 vnSensor->_binaryOutputRegister.at(b).insField,
6673 vnSensor->_binaryOutputRegister.at(b).gps2Field))
6675 auto obs = std::make_shared<VectorNavBinaryOutput>(vnSensor->_imuPos);
6678 if (vnSensor->_binaryOutputRegister.at(b).timeField != vn::protocol::uart::TimeGroup::TIMEGROUP_NONE)
6680 if (!obs->timeOutputs)
6682 obs->timeOutputs = std::make_shared<NAV::vendor::vectornav::TimeOutputs>();
6683 obs->timeOutputs->timeField |= vnSensor->_binaryOutputRegister.at(b).timeField;
6686 if (vnSensor->_binaryOutputRegister.at(b).timeField & vn::protocol::uart::TimeGroup::TIMEGROUP_TIMESTARTUP)
6688 obs->timeOutputs->timeStartup = p.extractUint64();
6690 if (vnSensor->_binaryOutputRegister.at(b).timeField & vn::protocol::uart::TimeGroup::TIMEGROUP_TIMEGPS)
6692 obs->timeOutputs->timeGps = p.extractUint64();
6694 if (vnSensor->_binaryOutputRegister.at(b).timeField & vn::protocol::uart::TimeGroup::TIMEGROUP_GPSTOW)
6696 obs->timeOutputs->gpsTow = p.extractUint64();
6698 if (vnSensor->_binaryOutputRegister.at(b).timeField & vn::protocol::uart::TimeGroup::TIMEGROUP_GPSWEEK)
6700 obs->timeOutputs->gpsWeek = p.extractUint16();
6702 if (vnSensor->_binaryOutputRegister.at(b).timeField & vn::protocol::uart::TimeGroup::TIMEGROUP_TIMESYNCIN)
6704 obs->timeOutputs->timeSyncIn = p.extractUint64();
6706 if (vnSensor->_binaryOutputRegister.at(b).timeField & vn::protocol::uart::TimeGroup::TIMEGROUP_TIMEGPSPPS)
6708 obs->timeOutputs->timePPS = p.extractUint64();
6720 if (vnSensor->_binaryOutputRegister.at(b).timeField & vn::protocol::uart::TimeGroup::TIMEGROUP_SYNCINCNT)
6722 obs->timeOutputs->syncInCnt = p.extractUint32();
6724 if (vnSensor->_binaryOutputRegister.at(b).timeField & vn::protocol::uart::TimeGroup::TIMEGROUP_SYNCOUTCNT)
6726 obs->timeOutputs->syncOutCnt = p.extractUint32();
6728 if (vnSensor->_binaryOutputRegister.at(b).timeField & vn::protocol::uart::TimeGroup::TIMEGROUP_TIMESTATUS)
6730 obs->timeOutputs->timeStatus = p.extractUint8();
6734 if (vnSensor->_binaryOutputRegister.at(b).imuField != vn::protocol::uart::ImuGroup::IMUGROUP_NONE)
6736 if (!obs->imuOutputs)
6738 obs->imuOutputs = std::make_shared<NAV::vendor::vectornav::ImuOutputs>();
6739 obs->imuOutputs->imuField |= vnSensor->_binaryOutputRegister.at(b).imuField;
6742 if (vnSensor->_binaryOutputRegister.at(b).imuField & vn::protocol::uart::ImuGroup::IMUGROUP_IMUSTATUS)
6744 obs->imuOutputs->imuStatus = p.extractUint16();
6746 if (vnSensor->_binaryOutputRegister.at(b).imuField & vn::protocol::uart::ImuGroup::IMUGROUP_UNCOMPMAG)
6748 auto vec = p.extractVec3f();
6749 obs->imuOutputs->uncompMag = { vec.x, vec.y, vec.z };
6751 if (vnSensor->_binaryOutputRegister.at(b).imuField & vn::protocol::uart::ImuGroup::IMUGROUP_UNCOMPACCEL)
6753 auto vec = p.extractVec3f();
6754 obs->imuOutputs->uncompAccel = { vec.x, vec.y, vec.z };
6756 if (vnSensor->_binaryOutputRegister.at(b).imuField & vn::protocol::uart::ImuGroup::IMUGROUP_UNCOMPGYRO)
6758 auto vec = p.extractVec3f();
6759 obs->imuOutputs->uncompGyro = { vec.x, vec.y, vec.z };
6761 if (vnSensor->_binaryOutputRegister.at(b).imuField & vn::protocol::uart::ImuGroup::IMUGROUP_TEMP)
6763 obs->imuOutputs->temp = p.extractFloat();
6765 if (vnSensor->_binaryOutputRegister.at(b).imuField & vn::protocol::uart::ImuGroup::IMUGROUP_PRES)
6767 obs->imuOutputs->pres = p.extractFloat();
6769 if (vnSensor->_binaryOutputRegister.at(b).imuField & vn::protocol::uart::ImuGroup::IMUGROUP_DELTATHETA)
6771 obs->imuOutputs->deltaTime = p.extractFloat();
6772 auto vec = p.extractVec3f();
6773 obs->imuOutputs->deltaTheta = { vec.x, vec.y, vec.z };
6775 if (vnSensor->_binaryOutputRegister.at(b).imuField & vn::protocol::uart::ImuGroup::IMUGROUP_DELTAVEL)
6777 auto vec = p.extractVec3f();
6778 obs->imuOutputs->deltaV = { vec.x, vec.y, vec.z };
6780 if (vnSensor->_binaryOutputRegister.at(b).imuField & vn::protocol::uart::ImuGroup::IMUGROUP_MAG)
6782 auto vec = p.extractVec3f();
6783 obs->imuOutputs->mag = { vec.x, vec.y, vec.z };
6785 if (vnSensor->_binaryOutputRegister.at(b).imuField & vn::protocol::uart::ImuGroup::IMUGROUP_ACCEL)
6787 auto vec = p.extractVec3f();
6788 obs->imuOutputs->accel = { vec.x, vec.y, vec.z };
6790 if (vnSensor->_binaryOutputRegister.at(b).imuField & vn::protocol::uart::ImuGroup::IMUGROUP_ANGULARRATE)
6792 auto vec = p.extractVec3f();
6793 obs->imuOutputs->angularRate = { vec.x, vec.y, vec.z };
6797 if (vnSensor->_binaryOutputRegister.at(b).gpsField != vn::protocol::uart::GpsGroup::GPSGROUP_NONE)
6799 if (!obs->gnss1Outputs)
6801 obs->gnss1Outputs = std::make_shared<NAV::vendor::vectornav::GnssOutputs>();
6802 obs->gnss1Outputs->gnssField |= vnSensor->_binaryOutputRegister.at(b).gpsField;
6815 if (vnSensor->_binaryOutputRegister.at(b).gpsField & vn::protocol::uart::GpsGroup::GPSGROUP_TOW)
6817 obs->gnss1Outputs->tow = p.extractUint64();
6819 if (vnSensor->_binaryOutputRegister.at(b).gpsField & vn::protocol::uart::GpsGroup::GPSGROUP_WEEK)
6821 obs->gnss1Outputs->week = p.extractUint16();
6823 if (vnSensor->_binaryOutputRegister.at(b).gpsField & vn::protocol::uart::GpsGroup::GPSGROUP_NUMSATS)
6825 obs->gnss1Outputs->numSats = p.extractUint8();
6827 if (vnSensor->_binaryOutputRegister.at(b).gpsField & vn::protocol::uart::GpsGroup::GPSGROUP_FIX)
6829 obs->gnss1Outputs->fix = p.extractUint8();
6831 if (vnSensor->_binaryOutputRegister.at(b).gpsField & vn::protocol::uart::GpsGroup::GPSGROUP_POSLLA)
6833 auto vec = p.extractVec3d();
6834 obs->gnss1Outputs->posLla = { vec.x, vec.y, vec.z };
6836 if (vnSensor->_binaryOutputRegister.at(b).gpsField & vn::protocol::uart::GpsGroup::GPSGROUP_POSECEF)
6838 auto vec = p.extractVec3d();
6839 obs->gnss1Outputs->posEcef = { vec.x, vec.y, vec.z };
6841 if (vnSensor->_binaryOutputRegister.at(b).gpsField & vn::protocol::uart::GpsGroup::GPSGROUP_VELNED)
6843 auto vec = p.extractVec3f();
6844 obs->gnss1Outputs->velNed = { vec.x, vec.y, vec.z };
6846 if (vnSensor->_binaryOutputRegister.at(b).gpsField & vn::protocol::uart::GpsGroup::GPSGROUP_VELECEF)
6848 auto vec = p.extractVec3f();
6849 obs->gnss1Outputs->velEcef = { vec.x, vec.y, vec.z };
6851 if (vnSensor->_binaryOutputRegister.at(b).gpsField & vn::protocol::uart::GpsGroup::GPSGROUP_POSU)
6853 auto vec = p.extractVec3f();
6854 obs->gnss1Outputs->posU = { vec.x, vec.y, vec.z };
6856 if (vnSensor->_binaryOutputRegister.at(b).gpsField & vn::protocol::uart::GpsGroup::GPSGROUP_VELU)
6858 obs->gnss1Outputs->velU = p.extractFloat();
6860 if (vnSensor->_binaryOutputRegister.at(b).gpsField & vn::protocol::uart::GpsGroup::GPSGROUP_TIMEU)
6862 obs->gnss1Outputs->timeU = p.extractFloat();
6864 if (vnSensor->_binaryOutputRegister.at(b).gpsField & vn::protocol::uart::GpsGroup::GPSGROUP_TIMEINFO)
6866 obs->gnss1Outputs->timeInfo.status = p.extractUint8();
6867 obs->gnss1Outputs->timeInfo.leapSeconds = p.extractInt8();
6869 if (vnSensor->_binaryOutputRegister.at(b).gpsField & vn::protocol::uart::GpsGroup::GPSGROUP_DOP)
6871 obs->gnss1Outputs->dop.gDop = p.extractFloat();
6872 obs->gnss1Outputs->dop.pDop = p.extractFloat();
6873 obs->gnss1Outputs->dop.tDop = p.extractFloat();
6874 obs->gnss1Outputs->dop.vDop = p.extractFloat();
6875 obs->gnss1Outputs->dop.hDop = p.extractFloat();
6876 obs->gnss1Outputs->dop.nDop = p.extractFloat();
6877 obs->gnss1Outputs->dop.eDop = p.extractFloat();
6879 if (vnSensor->_binaryOutputRegister.at(b).gpsField & vn::protocol::uart::GpsGroup::GPSGROUP_SATINFO)
6881 obs->gnss1Outputs->satInfo.numSats = p.extractUint8();
6884 LOG_DATA(
"{}: SatInfo: numSats {}", vnSensor->nameId(), obs->gnss1Outputs->satInfo.numSats);
6885 for (
size_t i = 0; i < obs->gnss1Outputs->satInfo.numSats; i++)
6887 auto sys = p.extractInt8();
6888 auto svId = p.extractUint8();
6889 auto flags = p.extractUint8();
6890 auto cno = p.extractUint8();
6891 auto qi = p.extractUint8();
6892 auto el = p.extractInt8();
6893 auto az = p.extractInt16();
6894 obs->gnss1Outputs->satInfo.satellites.emplace_back(sys, svId, flags, cno, qi, el, az);
6895 LOG_DATA(
"{}: SatInfo: sys {}, svId {}, flags {}, cno {}, qi {}, el {}, az {}", vnSensor->nameId(),
6896 sys, svId, flags, cno, qi, el, az);
6899 if (vnSensor->_binaryOutputRegister.at(b).gpsField & vn::protocol::uart::GpsGroup::GPSGROUP_RAWMEAS)
6901 obs->gnss1Outputs->raw.tow = p.extractDouble();
6902 obs->gnss1Outputs->raw.week = p.extractUint16();
6903 obs->gnss1Outputs->raw.numSats = p.extractUint8();
6905 LOG_DATA(
"{}: RawMeas: tow {}, week {}, numSats {}", vnSensor->nameId(),
6906 obs->gnss1Outputs->raw.tow, obs->gnss1Outputs->raw.week, obs->gnss1Outputs->raw.numSats);
6908 for (
size_t i = 0; i < obs->gnss1Outputs->raw.numSats; i++)
6910 auto sys = p.extractUint8();
6911 auto svId = p.extractUint8();
6912 auto freq = p.extractUint8();
6913 auto chan = p.extractUint8();
6914 auto slot = p.extractInt8();
6915 auto cno = p.extractUint8();
6916 auto flags = p.extractUint16();
6917 auto pr = p.extractDouble();
6918 auto cp = p.extractDouble();
6919 auto dp = p.extractFloat();
6920 obs->gnss1Outputs->raw.satellites.emplace_back(sys, svId, freq, chan, slot, cno, flags, pr, cp, dp);
6921 LOG_DATA(
"{}: RawMeas: sys {}, svId {}, freq {}, chan {}, slot {}, cno {}, flags {}, pr {}, cp {}, dp {}",
6922 vnSensor->nameId(),
static_cast<int>(sys),
static_cast<int>(svId),
static_cast<int>(freq),
static_cast<int>(chan),
6923 static_cast<int>(slot),
static_cast<int>(cno),
static_cast<int>(flags), pr, cp, dp);
6928 if (vnSensor->_binaryOutputRegister.at(b).attitudeField != vn::protocol::uart::AttitudeGroup::ATTITUDEGROUP_NONE)
6930 if (!obs->attitudeOutputs)
6932 obs->attitudeOutputs = std::make_shared<NAV::vendor::vectornav::AttitudeOutputs>();
6933 obs->attitudeOutputs->attitudeField |= vnSensor->_binaryOutputRegister.at(b).attitudeField;
6936 if (vnSensor->_binaryOutputRegister.at(b).attitudeField & vn::protocol::uart::AttitudeGroup::ATTITUDEGROUP_VPESTATUS)
6938 obs->attitudeOutputs->vpeStatus = p.extractUint16();
6940 if (vnSensor->_binaryOutputRegister.at(b).attitudeField & vn::protocol::uart::AttitudeGroup::ATTITUDEGROUP_YAWPITCHROLL)
6942 auto vec = p.extractVec3f();
6943 obs->attitudeOutputs->ypr = { vec.x, vec.y, vec.z };
6945 if (vnSensor->_binaryOutputRegister.at(b).attitudeField & vn::protocol::uart::AttitudeGroup::ATTITUDEGROUP_QUATERNION)
6947 auto vec = p.extractVec4f();
6948 obs->attitudeOutputs->qtn = { vec.w, vec.x, vec.y, vec.z };
6950 if (vnSensor->_binaryOutputRegister.at(b).attitudeField & vn::protocol::uart::AttitudeGroup::ATTITUDEGROUP_DCM)
6952 auto col0 = p.extractVec3f();
6953 auto col1 = p.extractVec3f();
6954 auto col2 = p.extractVec3f();
6955 obs->attitudeOutputs->dcm << col0.x, col1.x, col2.x,
6956 col0.y, col1.y, col2.y,
6957 col0.z, col1.z, col2.z;
6959 if (vnSensor->_binaryOutputRegister.at(b).attitudeField & vn::protocol::uart::AttitudeGroup::ATTITUDEGROUP_MAGNED)
6961 auto vec = p.extractVec3f();
6962 obs->attitudeOutputs->magNed = { vec.x, vec.y, vec.z };
6964 if (vnSensor->_binaryOutputRegister.at(b).attitudeField & vn::protocol::uart::AttitudeGroup::ATTITUDEGROUP_ACCELNED)
6966 auto vec = p.extractVec3f();
6967 obs->attitudeOutputs->accelNed = { vec.x, vec.y, vec.z };
6969 if (vnSensor->_binaryOutputRegister.at(b).attitudeField & vn::protocol::uart::AttitudeGroup::ATTITUDEGROUP_LINEARACCELBODY)
6971 auto vec = p.extractVec3f();
6972 obs->attitudeOutputs->linearAccelBody = { vec.x, vec.y, vec.z };
6974 if (vnSensor->_binaryOutputRegister.at(b).attitudeField & vn::protocol::uart::AttitudeGroup::ATTITUDEGROUP_LINEARACCELNED)
6976 auto vec = p.extractVec3f();
6977 obs->attitudeOutputs->linearAccelNed = { vec.x, vec.y, vec.z };
6979 if (vnSensor->_binaryOutputRegister.at(b).attitudeField & vn::protocol::uart::AttitudeGroup::ATTITUDEGROUP_YPRU)
6981 auto vec = p.extractVec3f();
6982 obs->attitudeOutputs->yprU = { vec.x, vec.y, vec.z };
6986 if (vnSensor->_binaryOutputRegister.at(b).insField != vn::protocol::uart::InsGroup::INSGROUP_NONE)
6988 if (!obs->insOutputs)
6990 obs->insOutputs = std::make_shared<NAV::vendor::vectornav::InsOutputs>();
6991 obs->insOutputs->insField |= vnSensor->_binaryOutputRegister.at(b).insField;
6994 if (vnSensor->_binaryOutputRegister.at(b).insField & vn::protocol::uart::InsGroup::INSGROUP_INSSTATUS)
6996 obs->insOutputs->insStatus = p.extractUint16();
6998 if (vnSensor->_binaryOutputRegister.at(b).insField & vn::protocol::uart::InsGroup::INSGROUP_POSLLA)
7000 auto vec = p.extractVec3d();
7001 obs->insOutputs->posLla = { vec.x, vec.y, vec.z };
7003 if (vnSensor->_binaryOutputRegister.at(b).insField & vn::protocol::uart::InsGroup::INSGROUP_POSECEF)
7005 auto vec = p.extractVec3d();
7006 obs->insOutputs->posEcef = { vec.x, vec.y, vec.z };
7008 if (vnSensor->_binaryOutputRegister.at(b).insField & vn::protocol::uart::InsGroup::INSGROUP_VELBODY)
7010 auto vec = p.extractVec3f();
7011 obs->insOutputs->velBody = { vec.x, vec.y, vec.z };
7013 if (vnSensor->_binaryOutputRegister.at(b).insField & vn::protocol::uart::InsGroup::INSGROUP_VELNED)
7015 auto vec = p.extractVec3f();
7016 obs->insOutputs->velNed = { vec.x, vec.y, vec.z };
7018 if (vnSensor->_binaryOutputRegister.at(b).insField & vn::protocol::uart::InsGroup::INSGROUP_VELECEF)
7020 auto vec = p.extractVec3f();
7021 obs->insOutputs->velEcef = { vec.x, vec.y, vec.z };
7023 if (vnSensor->_binaryOutputRegister.at(b).insField & vn::protocol::uart::InsGroup::INSGROUP_MAGECEF)
7025 auto vec = p.extractVec3f();
7026 obs->insOutputs->magEcef = { vec.x, vec.y, vec.z };
7028 if (vnSensor->_binaryOutputRegister.at(b).insField & vn::protocol::uart::InsGroup::INSGROUP_ACCELECEF)
7030 auto vec = p.extractVec3f();
7031 obs->insOutputs->accelEcef = { vec.x, vec.y, vec.z };
7033 if (vnSensor->_binaryOutputRegister.at(b).insField & vn::protocol::uart::InsGroup::INSGROUP_LINEARACCELECEF)
7035 auto vec = p.extractVec3f();
7036 obs->insOutputs->linearAccelEcef = { vec.x, vec.y, vec.z };
7038 if (vnSensor->_binaryOutputRegister.at(b).insField & vn::protocol::uart::InsGroup::INSGROUP_POSU)
7040 obs->insOutputs->posU = p.extractFloat();
7042 if (vnSensor->_binaryOutputRegister.at(b).insField & vn::protocol::uart::InsGroup::INSGROUP_VELU)
7044 obs->insOutputs->velU = p.extractFloat();
7048 if (vnSensor->_binaryOutputRegister.at(b).gps2Field != vn::protocol::uart::GpsGroup::GPSGROUP_NONE)
7050 if (!obs->gnss2Outputs)
7052 obs->gnss2Outputs = std::make_shared<NAV::vendor::vectornav::GnssOutputs>();
7053 obs->gnss2Outputs->gnssField |= vnSensor->_binaryOutputRegister.at(b).gps2Field;
7066 if (vnSensor->_binaryOutputRegister.at(b).gps2Field & vn::protocol::uart::GpsGroup::GPSGROUP_TOW)
7068 obs->gnss2Outputs->tow = p.extractUint64();
7070 if (vnSensor->_binaryOutputRegister.at(b).gps2Field & vn::protocol::uart::GpsGroup::GPSGROUP_WEEK)
7072 obs->gnss2Outputs->week = p.extractUint16();
7074 if (vnSensor->_binaryOutputRegister.at(b).gps2Field & vn::protocol::uart::GpsGroup::GPSGROUP_NUMSATS)
7076 obs->gnss2Outputs->numSats = p.extractUint8();
7078 if (vnSensor->_binaryOutputRegister.at(b).gps2Field & vn::protocol::uart::GpsGroup::GPSGROUP_FIX)
7080 obs->gnss2Outputs->fix = p.extractUint8();
7082 if (vnSensor->_binaryOutputRegister.at(b).gps2Field & vn::protocol::uart::GpsGroup::GPSGROUP_POSLLA)
7084 auto vec = p.extractVec3d();
7085 obs->gnss2Outputs->posLla = { vec.x, vec.y, vec.z };
7087 if (vnSensor->_binaryOutputRegister.at(b).gps2Field & vn::protocol::uart::GpsGroup::GPSGROUP_POSECEF)
7089 auto vec = p.extractVec3d();
7090 obs->gnss2Outputs->posEcef = { vec.x, vec.y, vec.z };
7092 if (vnSensor->_binaryOutputRegister.at(b).gps2Field & vn::protocol::uart::GpsGroup::GPSGROUP_VELNED)
7094 auto vec = p.extractVec3f();
7095 obs->gnss2Outputs->velNed = { vec.x, vec.y, vec.z };
7097 if (vnSensor->_binaryOutputRegister.at(b).gps2Field & vn::protocol::uart::GpsGroup::GPSGROUP_VELECEF)
7099 auto vec = p.extractVec3f();
7100 obs->gnss2Outputs->velEcef = { vec.x, vec.y, vec.z };
7102 if (vnSensor->_binaryOutputRegister.at(b).gps2Field & vn::protocol::uart::GpsGroup::GPSGROUP_POSU)
7104 auto vec = p.extractVec3f();
7105 obs->gnss2Outputs->posU = { vec.x, vec.y, vec.z };
7107 if (vnSensor->_binaryOutputRegister.at(b).gps2Field & vn::protocol::uart::GpsGroup::GPSGROUP_VELU)
7109 obs->gnss2Outputs->velU = p.extractFloat();
7111 if (vnSensor->_binaryOutputRegister.at(b).gps2Field & vn::protocol::uart::GpsGroup::GPSGROUP_TIMEU)
7113 obs->gnss2Outputs->timeU = p.extractFloat();
7115 if (vnSensor->_binaryOutputRegister.at(b).gps2Field & vn::protocol::uart::GpsGroup::GPSGROUP_TIMEINFO)
7117 obs->gnss2Outputs->timeInfo.status = p.extractUint8();
7118 obs->gnss2Outputs->timeInfo.leapSeconds = p.extractInt8();
7120 if (vnSensor->_binaryOutputRegister.at(b).gps2Field & vn::protocol::uart::GpsGroup::GPSGROUP_DOP)
7122 obs->gnss2Outputs->dop.gDop = p.extractFloat();
7123 obs->gnss2Outputs->dop.pDop = p.extractFloat();
7124 obs->gnss2Outputs->dop.tDop = p.extractFloat();
7125 obs->gnss2Outputs->dop.vDop = p.extractFloat();
7126 obs->gnss2Outputs->dop.hDop = p.extractFloat();
7127 obs->gnss2Outputs->dop.nDop = p.extractFloat();
7128 obs->gnss2Outputs->dop.eDop = p.extractFloat();
7130 if (vnSensor->_binaryOutputRegister.at(b).gps2Field & vn::protocol::uart::GpsGroup::GPSGROUP_SATINFO)
7132 obs->gnss2Outputs->satInfo.numSats = p.extractUint8();
7134 for (
size_t i = 0; i < obs->gnss2Outputs->satInfo.numSats; i++)
7136 auto sys = p.extractInt8();
7137 auto svId = p.extractUint8();
7138 auto flags = p.extractUint8();
7139 auto cno = p.extractUint8();
7140 auto qi = p.extractUint8();
7141 auto el = p.extractInt8();
7142 auto az = p.extractInt16();
7143 obs->gnss2Outputs->satInfo.satellites.emplace_back(sys, svId, flags, cno, qi, el, az);
7146 if (vnSensor->_binaryOutputRegister.at(b).gps2Field & vn::protocol::uart::GpsGroup::GPSGROUP_RAWMEAS)
7148 obs->gnss2Outputs->raw.tow = p.extractDouble();
7149 obs->gnss2Outputs->raw.week = p.extractUint16();
7150 obs->gnss2Outputs->raw.numSats = p.extractUint8();
7152 for (
size_t i = 0; i < obs->gnss2Outputs->raw.numSats; i++)
7154 auto sys = p.extractUint8();
7155 auto svId = p.extractUint8();
7156 auto freq = p.extractUint8();
7157 auto chan = p.extractUint8();
7158 auto slot = p.extractInt8();
7159 auto cno = p.extractUint8();
7160 auto flags = p.extractUint16();
7161 auto pr = p.extractDouble();
7162 auto cp = p.extractDouble();
7163 auto dp = p.extractFloat();
7164 obs->gnss2Outputs->raw.satellites.emplace_back(sys, svId, freq, chan, slot, cno, flags, pr, cp, dp);
7169 if (p.getCurExtractLoc() != p.getPacketLength() - 2)
7171 LOG_DEBUG(
"{}: Only {} of {} bytes were extracted from the Binary Output {}", vnSensor->nameId(), p.getCurExtractLoc(), p.getPacketLength(), b + 1);
7175 auto updateSyncOut = [vnSensor, obs](
const InsTime& ppsTime) {
7176 if (vnSensor->_synchronizationControlRegister.syncOutMode == vn::protocol::uart::SYNCOUTMODE_GPSPPS
7177 && (obs->timeOutputs->timeField & vn::protocol::uart::TimeGroup::TIMEGROUP_SYNCOUTCNT))
7179 if (obs->timeOutputs->syncOutCnt > 0)
7181 if (vnSensor->_timeSyncOut.syncOutCnt == 0)
7183 LOG_INFO(
"{}: Found PPS time {} and is providing it to its connected nodes", vnSensor->nameId(), ppsTime.toYMDHMS(
GPST));
7185 if (vnSensor->_timeSyncOut.ppsTime != ppsTime || vnSensor->_timeSyncOut.syncOutCnt != obs->timeOutputs->syncOutCnt)
7187 LOG_DATA(
"{}: SyncOut time {}, pps {}, syncOutCnt {}",
7188 vnSensor->nameId(), obs->insTime.toYMDHMS(
GPST),
7189 ppsTime.toYMDHMS(
GPST), obs->timeOutputs->syncOutCnt);
7191 vnSensor->_timeSyncOut.ppsTime = ppsTime;
7192 vnSensor->_timeSyncOut.syncOutCnt = obs->timeOutputs->syncOutCnt;
7198 if (obs->timeOutputs && (obs->timeOutputs->timeField & vn::protocol::uart::TimeGroup::TIMEGROUP_TIMESTATUS))
7200 if (obs->timeOutputs->timeStatus.dateOk())
7202 if (obs->timeOutputs->timeStatus.timeOk()
7203 && (obs->timeOutputs->timeField & vn::protocol::uart::TimeGroup::TIMEGROUP_GPSTOW)
7204 && (obs->timeOutputs->timeField & vn::protocol::uart::TimeGroup::TIMEGROUP_GPSWEEK))
7207 updateSyncOut(
InsTime(0, obs->timeOutputs->gpsWeek, std::floor(obs->timeOutputs->gpsTow * 1e-9L)));
7209 else if (obs->timeOutputs->timeField & vn::protocol::uart::TimeGroup::TIMEGROUP_TIMEGPS)
7211 auto secondsSinceEpoche =
static_cast<long double>(obs->timeOutputs->timeGps) * 1e-9L;
7216 updateSyncOut(
InsTime(0, week, std::floor(tow)));
7221 if (obs->insTime.empty()
7222 && (obs->timeOutputs->timeField & vn::protocol::uart::TIMEGROUP_SYNCINCNT)
7223 && (obs->timeOutputs->timeField & vn::protocol::uart::TIMEGROUP_TIMESYNCIN)
7224 && vnSensor->_syncInPin && vnSensor->inputPins.front().isPinLinked())
7226 if (
auto timeSyncMaster = vnSensor->getInputValue<
TimeSync>(0);
7233 int64_t syncCntDiff = obs->timeOutputs->syncInCnt - timeSyncMaster->v->syncOutCnt - vnSensor->_syncCntOffset;
7235 if (std::abs(syncCntDiff) > 1)
7237 vnSensor->_syncCntOffset = obs->timeOutputs->syncInCnt - timeSyncMaster->v->syncOutCnt;
7238 syncCntDiff -= vnSensor->_syncCntOffset;
7239 LOG_DEBUG(
"{}: Counters did not start at the same time (_syncCntOffset = {})", vnSensor->nameId(), vnSensor->_syncCntOffset);
7241 vnSensor->_lastSyncOutCnt = timeSyncMaster->v->syncOutCnt;
7242 vnSensor->_lastSyncInCnt = obs->timeOutputs->syncInCnt;
7244 obs->insTime = timeSyncMaster->v->ppsTime + std::chrono::nanoseconds(obs->timeOutputs->timeSyncIn)
7245 + std::chrono::seconds(syncCntDiff);
7246 LOG_DATA(
"{}: SyncIn time {}, pps {}, syncOutCnt {}, syncInCnt {}, syncCntDiff {}",
7247 vnSensor->nameId(), obs->insTime.toYMDHMS(
GPST), timeSyncMaster->v->ppsTime.toYMDHMS(
GPST),
7248 timeSyncMaster->v->syncOutCnt, obs->timeOutputs->syncInCnt, syncCntDiff);
7256 if (obs->insTime.empty()
7257 && !vnSensor->_lastMessageTime.at(b).empty()
7258 && obs->timeOutputs->timeField & vn::protocol::uart::TimeGroup::TIMEGROUP_TIMESTARTUP)
7260 obs->insTime = vnSensor->_lastMessageTime.at(b) + std::chrono::nanoseconds(obs->timeOutputs->timeStartup - vnSensor->_lastMessageTimeSinceStartup.at(b));
7263 if (obs->insTime.empty()
7264 && !(obs->timeOutputs
7265 && (obs->timeOutputs->timeField & vn::protocol::uart::TimeGroup::TIMEGROUP_TIMESTATUS)
7266 && (obs->timeOutputs->timeField & vn::protocol::uart::TimeGroup::TIMEGROUP_GPSTOW)
7267 && (obs->timeOutputs->timeField & vn::protocol::uart::TimeGroup::TIMEGROUP_GPSWEEK)))
7269 if (
InsTime currentTime = util::time::GetCurrentInsTime();
7270 !currentTime.
empty())
7272 obs->insTime = currentTime;
7276 if (!obs->insTime.empty())
7278 if (!vnSensor->_lastMessageTime.at(b).empty())
7282 if (obs->insTime - vnSensor->_lastMessageTime.at(b) >= std::chrono::duration<double>(1.5 * (vnSensor->_binaryOutputRegister.at(b).rateDivisor /
IMU_DEFAULT_FREQUENCY)))
7284 LOG_WARN(
"{}: Potentially lost a message. dt = {:.4} s, expect {} s. (Previous message at [{}], current message [{}])", vnSensor->nameId(),
7285 static_cast<double>((obs->insTime - vnSensor->_lastMessageTime.at(b)).count()),
7287 vnSensor->_lastMessageTime.at(b), obs->insTime);
7290 vnSensor->_lastMessageTime.at(b) = obs->insTime;
7291 if (obs->timeOutputs->timeField & vn::protocol::uart::TimeGroup::TIMEGROUP_TIMESTARTUP)
7293 vnSensor->_lastMessageTimeSinceStartup.at(b) = obs->timeOutputs->timeStartup;
7301 if (vnSensor->_binaryOutputRegisterMergeObservation ==
nullptr)
7303 std::stringstream sstream;
7304 if (!obs->insTime.empty())
7306 sstream << obs->insTime;
7310 sstream << obs->timeOutputs->timeStartup;
7312 LOG_DATA(
"{}: {} - Storing message with time {}", vnSensor->nameId(), b, sstream.str());
7314 vnSensor->_binaryOutputRegisterMergeObservation = obs;
7315 vnSensor->_binaryOutputRegisterMergeIndex = b;
7319 auto allowedTimeDiff = std::chrono::microseconds(
static_cast<int>(0.5 * (vnSensor->_binaryOutputRegister.at(b).rateDivisor /
IMU_DEFAULT_FREQUENCY) * 1e6));
7320 if (vnSensor->_binaryOutputRegisterMergeIndex != b
7321 && ((!obs->insTime.empty() && !vnSensor->_binaryOutputRegisterMergeObservation->insTime.empty()
7322 && (obs->insTime - vnSensor->_binaryOutputRegisterMergeObservation->insTime < allowedTimeDiff))
7323 || (obs->timeOutputs !=
nullptr && vnSensor->_binaryOutputRegisterMergeObservation->timeOutputs !=
nullptr
7324 && obs->timeOutputs->timeField & vn::protocol::uart::TIMEGROUP_TIMESTARTUP
7325 && vnSensor->_binaryOutputRegisterMergeObservation->timeOutputs->timeField & vn::protocol::uart::TIMEGROUP_TIMESTARTUP
7326 && (std::chrono::nanoseconds(obs->timeOutputs->timeStartup - vnSensor->_binaryOutputRegisterMergeObservation->timeOutputs->timeStartup) < allowedTimeDiff))))
7330 vnSensor->_binaryOutputRegisterMergeObservation =
nullptr;
7332 std::stringstream sstream;
7333 if (!obs->insTime.empty())
7335 sstream << obs->insTime;
7339 sstream << obs->timeOutputs->timeStartup;
7341 LOG_DATA(
"{}: {} - Merged message with time {}", vnSensor->nameId(), b, sstream.str());
7343 vnSensor->invokeCallbacks(std::min(b, vnSensor->_binaryOutputRegisterMergeIndex) + 1, obs);
7347 [[maybe_unused]]
long double timeDiff = 0.0L;
7348 std::stringstream sstreamOld;
7349 std::stringstream sstreamNew;
7350 if (!obs->insTime.empty() && !vnSensor->_binaryOutputRegisterMergeObservation->insTime.empty())
7352 timeDiff = (obs->insTime - vnSensor->_binaryOutputRegisterMergeObservation->insTime).count();
7353 sstreamOld << vnSensor->_binaryOutputRegisterMergeObservation->insTime;
7354 sstreamNew << obs->insTime;
7358 sstreamOld << vnSensor->_binaryOutputRegisterMergeObservation->timeOutputs->timeStartup;
7359 sstreamNew << obs->timeOutputs->timeStartup;
7360 timeDiff =
static_cast<double>(obs->timeOutputs->timeStartup
7361 - vnSensor->_binaryOutputRegisterMergeObservation->timeOutputs->timeStartup)
7365 LOG_WARN(
"{}: Merging failed, because timestamps do not match. Potentially lost a message (diff {} sec, old ({}) {}, new ({}) {})",
7366 vnSensor->nameId(), timeDiff, vnSensor->_binaryOutputRegisterMergeIndex, sstreamOld.str(), b, sstreamNew.str());
7369 vnSensor->invokeCallbacks(vnSensor->_binaryOutputRegisterMergeIndex + 1, vnSensor->_binaryOutputRegisterMergeObservation);
7370 vnSensor->_binaryOutputRegisterMergeObservation = obs;
7371 vnSensor->_binaryOutputRegisterMergeIndex = b;
7377 if (!obs->insTime.empty())
7379 LOG_DATA(
"{}: {} - Normal message with time {}", vnSensor->nameId(), b, obs->insTime);
7382 vnSensor->invokeCallbacks(b + 1, obs);
7387 else if (p.type() == vn::protocol::uart::Packet::TYPE_ASCII)
7389 LOG_DATA(
"{} received an ASCII Async message: {}", vnSensor->nameId(), p.datastr());
7390 vnSensor->_asciiOutputBuffer.push_back(p.datastr());
7392 auto obs = std::make_shared<StringObs>(p.datastr());
7394 if (
InsTime currentTime = util::time::GetCurrentInsTime();
7395 !currentTime.
empty())
7397 obs->insTime = currentTime;
Transformation collection.
nlohmann::json json
json namespace
Text Help Marker (?) with Tooltip.
Utility class for logging to console and file.
#define LOG_DEBUG
Debug information. Should not be called on functions which receive observations (spamming)
#define LOG_DATA
All output which occurs repeatedly every time observations are received.
#define LOG_ERROR
Error occurred, which stops part of the program to work, but not everything.
#define LOG_WARN
Error occurred, but a fallback option exists and program continues to work normally.
#define LOG_INFO
Info to the user on the state of the program.
#define LOG_TRACE
Detailled info to trace the execution of the program. Should not be called on functions which receive...
Wrapper for String Messages.
Keeps track of the current real/simulation time.
Type Definitions for VectorNav messages.
Imu(const Imu &)=delete
Copy constructor.
The class is responsible for all time-related tasks.
constexpr bool empty() const
Checks if the Time object has a value.
void reset()
Resets the InsTime object.
bool isInitialized() const
Checks if the node is initialized.
bool doDeinitialize(bool wait=false)
Asks the node worker to deinitialize the node.
ImVec2 _guiConfigDefaultWindowSize
std::vector< OutputPin > outputPins
List of output pins.
std::vector< InputPin > inputPins
List of input pins.
std::string nameId() const
Node name and id.
std::string name
Name of the Node.
bool _onlyRealTime
Whether the node can run in post-processing or only real-time.
bool _hasConfig
Flag if the config window should be shown.
static std::string type()
Returns the type of the data class.
int _selectedBaudrate
Baudrate for the sensor.
Baudrate
Available Baudrates.
@ BAUDRATE_115200
Baudrate with 115200 symbols per second [Baud].
@ BAUDRATE_FASTEST
Fastest possible Baudrate will be automatically chosen.
void restore(const json &j)
Restores the node from a json object.
Baudrate sensorBaudrate() const
Returns the Baudrate for the element Selected by the GUI.
json save() const
Saves the node into a json object.
static std::string type()
Returns the type of the data class.
static constexpr size_t OUTPUT_PORT_INDEX_ASCII_OUTPUT
Flow (StringObs)
std::array< vn::sensors::BinaryOutputRegister, 3 > _binaryOutputRegister
Binary Output Register 1 - 3.
int64_t _lastSyncOutCnt
Last received syncOutCnt.
vn::sensors::MagnetometerCalibrationControlRegister _magnetometerCalibrationControlRegister
Magnetometer Calibration Control.
static std::string typeStatic()
String representation of the Class Type.
std::array< uint64_t, 3 > _lastMessageTimeSinceStartup
Stores the time of the last received message.
static std::string category()
String representation of the Class Category.
vn::sensors::VpeAccelerometerBasicTuningRegister _vpeAccelerometerBasicTuningRegister
VPE Accelerometer Basic Tuning.
json save() const override
Saves the node into a json object.
vn::sensors::MagneticAndGravityReferenceVectorsRegister _magneticAndGravityReferenceVectorsRegister
Magnetic and Gravity Reference Vectors.
static constexpr std::array _possibleAsyncDataOutputFrequency
Possible values for the Async Data Output Frequency Register.
int _asyncDataOutputFrequencySelected
Selected Frequency of the Async Ascii Output in the GUI.
std::array< InsTime, 3 > _lastMessageTime
Stores the time of the last received message.
static const std::array< BinaryGroupData, 10 > _binaryGroupTime
Binary group 1 contains a wide assortment of commonly used data required for most applications.
vn::math::vec3f _filterStartupGyroBias
Filter Startup Gyro Bias.
std::string type() const override
String representation of the Class Type.
static const std::array< BinaryGroupData, 11 > _binaryGroupIMU
Binary group 3 provides all outputs which are dependent upon the measurements collected from the onbo...
VectorNavModel _sensorModel
The sensor model which is selected in the GUI.
bool _coupleImuRateOutput
Couple the ImuFilter's rate (window size of moving-average filter) to the output rate (rateDivisor)
static void coupleImuFilterRates(NAV::VectorNavSensor *sensor, vn::sensors::BinaryOutputRegister &bor, uint32_t &binaryField)
Updates the ImuFilter's rate when pressing the checkbox button.
@ Output1_Output2
Merge Output 1 and 2.
@ Output2_Output3
Merge Output 2 and 3.
@ Output1_Output3
Merge Output 1 and 3.
vn::sensors::DeltaThetaAndDeltaVelocityConfigurationRegister _deltaThetaAndDeltaVelocityConfigurationRegister
Delta Theta and Delta Velocity Configuration.
std::shared_ptr< VectorNavBinaryOutput > _binaryOutputRegisterMergeObservation
First observation received, which should be merged together.
void guiConfig() override
ImGui config window which is shown on double click.
vn::sensors::VnSensor _vs
VnSensor Object.
std::string _connectedSensorPort
Connected sensor port.
~VectorNavSensor() override
Destructor.
ScrollingBuffer< std::string > _asciiOutputBuffer
Buffer to store Ascii Output Messages.
vn::sensors::VpeGyroBasicTuningRegister _vpeGyroBasicTuningRegister
VPE Gyro Basic Tuning.
std::array< size_t, 3 > _binaryOutputSelectedFrequency
Selected Frequency of the Binary Outputs in the GUI.
vn::math::mat3f _referenceFrameRotationMatrix
Reference Frame Rotation.
vn::protocol::uart::AsciiAsync _asyncDataOutputType
Async Data Output Type Register.
vn::sensors::ImuFilteringConfigurationRegister _imuFilteringConfigurationRegister
IMU Filtering Configuration.
vn::sensors::GpsCompassBaselineRegister _gpsCompassBaselineRegister
GNSS Compass Baseline.
vn::sensors::StartupFilterBiasEstimateRegister _startupFilterBiasEstimateRegister
Startup Filter Bias Estimate.
vn::sensors::GpsConfigurationRegister _gpsConfigurationRegister
GNSS Configuration.
struct NAV::VectorNavSensor::@061131263266062172247357061343017357216211246313 _gnssTimeCounter
Last received GNSS time.
VectorNavSensor()
Default constructor.
void restore(const json &j) override
Restores the node from a json object.
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...
@ VN310
VN-310/E (Tactical-Grade GNSS/INS with Integrated GNSS-Compass)
vn::sensors::VpeMagnetometerBasicTuningRegister _vpeMagnetometerBasicTuningRegister
VPE Magnetometer Basic Tuning.
bool initialize() override
Initialize the node.
int _asciiOutputBufferSize
Max size of the Ascii Output.
vn::math::vec3f _gpsAntennaOffset
GNSS Antenna A Offset.
static constexpr double IMU_DEFAULT_FREQUENCY
Internal Frequency of the Sensor.
int64_t _syncCntOffset
Offset between syncIn and syncOut.
vn::sensors::SynchronizationControlRegister _synchronizationControlRegister
Synchronization Control.
vn::sensors::VpeBasicControlRegister _vpeBasicControlRegister
VPE Basic Control.
void deinitialize() override
Deinitialize the node.
static void asciiOrBinaryAsyncMessageReceived(void *userData, vn::protocol::uart::Packet &p, size_t index)
Callback handler for notifications of new asynchronous data packets received.
vn::sensors::CommunicationProtocolControlRegister _communicationProtocolControlRegister
Communication Protocol Control.
TimeSync _timeSyncOut
Time synchronization for master sensors.
uint32_t _asyncDataOutputFrequency
Async Data Output Frequency Register.
BinaryRegisterMerge _binaryOutputRegisterMerge
Merge binary output registers together. This has to be done because VectorNav sensors have a buffer o...
vn::sensors::ReferenceVectorConfigurationRegister _referenceVectorConfigurationRegister
Reference Vector Configuration.
bool _syncInPin
Show the SyncIn Pin.
vn::sensors::InsBasicConfigurationRegisterVn300 _insBasicConfigurationRegisterVn300
INS Basic Configuration.
std::pair< std::vector< uint16_t >, std::vector< std::string > > _dividerFrequency
First: List of RateDividers, Second: List of Matching Frequencies.
int64_t _lastSyncInCnt
Last received syncInCnt.
bool resetNode() override
Resets the node. It is guaranteed that the node is initialized when this is called.
static const std::array< BinaryGroupData, 16 > _binaryGroupGNSS
Binary group 4 provides all outputs which are dependent upon the measurements collected from the prim...
vn::sensors::VelocityCompensationControlRegister _velocityCompensationControlRegister
Velocity Compensation Control.
static void mergeVectorNavBinaryObservations(const std::shared_ptr< VectorNavBinaryOutput > &target, const std::shared_ptr< VectorNavBinaryOutput > &source)
Merges the content of the two observations into one.
constexpr int32_t SECONDS_PER_DAY
Seconds / Day.
constexpr int32_t DAYS_PER_WEEK
Days / Week.
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.
bool DeleteOutputPin(OutputPin &pin)
Deletes the output pin. Invalidates the pin reference given.
bool DeleteInputPin(InputPin &pin)
Deletes the input pin. Invalidates the pin reference given.
InputPin * CreateInputPin(Node *node, const char *name, Pin::Type pinType, const std::vector< std::string > &dataIdentifier={}, InputPin::Callback callback=static_cast< InputPin::FlowFirableCallbackFunc >(nullptr), InputPin::FlowFirableCheckFunc firable=nullptr, int priority=0, int idx=-1)
Create an Input Pin object.
void ApplyChanges()
Signals that there have been changes to the flow.
Eigen::Quaternion< Scalar > b_Quat_p(Scalar mountingAngleX, Scalar mountingAngleY, Scalar mountingAngleZ)
Quaternion for rotations from platform to body frame.
Eigen::Vector3< typename Derived::Scalar > quat2eulerZYX(const Eigen::QuaternionBase< Derived > &q)
Converts the quaternion to Euler rotation angles with rotation sequence ZYX.
constexpr auto deg2rad(const T °)
Convert Degree to Radians.
constexpr auto rad2deg(const T &rad)
Convert Radians to Degree.
static void from_json(const json &j, vn::math::vec3f &vec)
static void to_json(json &j, const vn::math::vec3f &vec)
static void from_json(const json &j, SynchronizationControlRegister &synchronizationControlRegister)
static void to_json(json &j, const SynchronizationControlRegister &synchronizationControlRegister)
GPS week and time of week in GPS standard time [GPST].
Information needed to sync Master/Slave sensors.
InsTime ppsTime
Time of the last message with GNSS Time available (or empty otherwise)