48 return "VectorNavBinaryConverter";
94 if (
auto* connectedPin = link.getConnectedPin())
96 outputPins.front().recreateLink(*connectedPin);
104 if (ImGui::Checkbox(fmt::format(
"Use compensated data##{}",
size_t(
id)).c_str(), &
_useCompensatedData))
113 ImGui::Combo(fmt::format(
"Data Source##{}",
size_t(
id)).c_str(), &posVelSource,
"Best\0INS\0GNSS 1\0GNSS 2\0\0"))
119 if (ImGui::Checkbox(fmt::format(
"Force static##{}",
size_t(
id)).c_str(), &
_forceStatic))
145 if (j.contains(
"outputType"))
178 if (j.contains(
"posVelSource"))
182 if (j.contains(
"forceStatic"))
186 if (j.contains(
"useCompensatedData"))
203 auto vnObs = std::static_pointer_cast<const VectorNavBinaryOutput>(queue.
extract_front());
205 std::shared_ptr<const NodeData> convertedData =
nullptr;
236 auto imuObs = std::make_shared<ImuObsWDelta>(vnObs->imuPos);
238 if (vnObs->gnss1Outputs || vnObs->gnss2Outputs)
240 if (!vnObs->timeOutputs
241 || !(vnObs->timeOutputs->timeField & vn::protocol::uart::TimeGroup::TIMEGROUP_TIMESTATUS)
242 || !vnObs->timeOutputs->timeStatus.dateOk()
243 || !vnObs->timeOutputs->timeStatus.timeOk()
244 || !(vnObs->timeOutputs->timeField & vn::protocol::uart::TimeGroup::TIMEGROUP_GPSTOW)
245 || !(vnObs->timeOutputs->timeField & vn::protocol::uart::TimeGroup::TIMEGROUP_GPSWEEK))
249 imuObs->insTime =
InsTime(
InsTime_GPSweekTow(0,
static_cast<int32_t
>(vnObs->timeOutputs->gpsWeek),
static_cast<double>(vnObs->timeOutputs->gpsTow) * 1e-9L));
256 imuObs->insTime = vnObs->insTime;
259 bool accelFound =
false;
260 bool gyroFound =
false;
261 bool dThetaFound =
false;
262 bool dVelFound =
false;
263 if (vnObs->imuOutputs)
267 if (vnObs->imuOutputs->imuField & vn::protocol::uart::ImuGroup::IMUGROUP_UNCOMPMAG)
269 imuObs->p_magneticField = vnObs->imuOutputs->uncompMag.cast<
double>();
271 if (vnObs->imuOutputs->imuField & vn::protocol::uart::ImuGroup::IMUGROUP_UNCOMPACCEL)
273 imuObs->p_acceleration = vnObs->imuOutputs->uncompAccel.cast<
double>();
276 if (vnObs->imuOutputs->imuField & vn::protocol::uart::ImuGroup::IMUGROUP_UNCOMPGYRO)
278 imuObs->p_angularRate = vnObs->imuOutputs->uncompGyro.cast<
double>();
284 if (vnObs->imuOutputs->imuField & vn::protocol::uart::ImuGroup::IMUGROUP_MAG)
286 imuObs->p_magneticField = vnObs->imuOutputs->mag.cast<
double>();
288 if (vnObs->imuOutputs->imuField & vn::protocol::uart::ImuGroup::IMUGROUP_ACCEL)
290 imuObs->p_acceleration = vnObs->imuOutputs->accel.cast<
double>();
293 if (vnObs->imuOutputs->imuField & vn::protocol::uart::ImuGroup::IMUGROUP_ANGULARRATE)
295 imuObs->p_angularRate = vnObs->imuOutputs->angularRate.cast<
double>();
299 if (vnObs->imuOutputs->imuField & vn::protocol::uart::ImuGroup::IMUGROUP_TEMP)
301 imuObs->temperature = vnObs->imuOutputs->temp;
303 if (vnObs->imuOutputs->imuField & vn::protocol::uart::ImuGroup::IMUGROUP_DELTATHETA)
305 imuObs->dtime = vnObs->imuOutputs->deltaTime;
306 imuObs->dtheta =
deg2rad(vnObs->imuOutputs->deltaTheta.cast<
double>());
309 if (vnObs->imuOutputs->imuField & vn::protocol::uart::ImuGroup::IMUGROUP_DELTAVEL)
311 imuObs->dvel = vnObs->imuOutputs->deltaV.cast<
double>();
316 if (accelFound && gyroFound && dThetaFound && dVelFound)
321 LOG_ERROR(
"{}: Conversion failed. Need {} acceleration and gyroscope measurements and deltaTheta and deltaVel in the input data.",
328 auto imuObs = std::make_shared<ImuObs>(vnObs->imuPos);
330 if (vnObs->gnss1Outputs || vnObs->gnss2Outputs)
332 if (!vnObs->timeOutputs
333 || !(vnObs->timeOutputs->timeField & vn::protocol::uart::TimeGroup::TIMEGROUP_TIMESTATUS)
334 || !vnObs->timeOutputs->timeStatus.dateOk()
335 || !vnObs->timeOutputs->timeStatus.timeOk()
336 || !(vnObs->timeOutputs->timeField & vn::protocol::uart::TimeGroup::TIMEGROUP_GPSTOW)
337 || !(vnObs->timeOutputs->timeField & vn::protocol::uart::TimeGroup::TIMEGROUP_GPSWEEK))
341 imuObs->insTime =
InsTime(
InsTime_GPSweekTow(0,
static_cast<int32_t
>(vnObs->timeOutputs->gpsWeek),
static_cast<double>(vnObs->timeOutputs->gpsTow) * 1e-9L));
348 imuObs->insTime = vnObs->insTime;
351 bool accelFound =
false;
352 bool gyroFound =
false;
353 if (vnObs->imuOutputs)
357 if (vnObs->imuOutputs->imuField & vn::protocol::uart::ImuGroup::IMUGROUP_UNCOMPMAG)
359 imuObs->p_magneticField = vnObs->imuOutputs->uncompMag.cast<
double>();
361 if (vnObs->imuOutputs->imuField & vn::protocol::uart::ImuGroup::IMUGROUP_UNCOMPACCEL)
363 imuObs->p_acceleration = vnObs->imuOutputs->uncompAccel.cast<
double>();
366 if (vnObs->imuOutputs->imuField & vn::protocol::uart::ImuGroup::IMUGROUP_UNCOMPGYRO)
368 imuObs->p_angularRate = vnObs->imuOutputs->uncompGyro.cast<
double>();
374 if (vnObs->imuOutputs->imuField & vn::protocol::uart::ImuGroup::IMUGROUP_MAG)
376 imuObs->p_magneticField = vnObs->imuOutputs->mag.cast<
double>();
378 if (vnObs->imuOutputs->imuField & vn::protocol::uart::ImuGroup::IMUGROUP_ACCEL)
380 imuObs->p_acceleration = vnObs->imuOutputs->accel.cast<
double>();
383 if (vnObs->imuOutputs->imuField & vn::protocol::uart::ImuGroup::IMUGROUP_ANGULARRATE)
385 imuObs->p_angularRate = vnObs->imuOutputs->angularRate.cast<
double>();
389 if (vnObs->imuOutputs->imuField & vn::protocol::uart::ImuGroup::IMUGROUP_TEMP)
391 imuObs->temperature = vnObs->imuOutputs->temp;
395 if (accelFound && gyroFound)
400 LOG_ERROR(
"{}: Conversion failed. Need {} acceleration and gyroscope measurements in the input data.",
nameId(),
_useCompensatedData ?
"compensated" :
"uncompensated");
406 auto baroPressObs = std::make_shared<BaroPressObs>();
408 if (vnObs->gnss1Outputs || vnObs->gnss2Outputs)
410 if (!vnObs->timeOutputs
411 || !(vnObs->timeOutputs->timeField & vn::protocol::uart::TimeGroup::TIMEGROUP_TIMESTATUS)
412 || !vnObs->timeOutputs->timeStatus.dateOk()
413 || !vnObs->timeOutputs->timeStatus.timeOk()
414 || !(vnObs->timeOutputs->timeField & vn::protocol::uart::TimeGroup::TIMEGROUP_GPSTOW)
415 || !(vnObs->timeOutputs->timeField & vn::protocol::uart::TimeGroup::TIMEGROUP_GPSWEEK))
419 baroPressObs->insTime =
InsTime(
InsTime_GPSweekTow(0,
static_cast<int32_t
>(vnObs->timeOutputs->gpsWeek),
static_cast<double>(vnObs->timeOutputs->gpsTow) * 1e-9L));
426 baroPressObs->insTime = vnObs->insTime;
429 bool baroFound =
false;
430 if (vnObs->imuOutputs)
432 if (vnObs->imuOutputs->imuField & vn::protocol::uart::ImuGroup::IMUGROUP_PRES)
449 LOG_ERROR(
"{}: Conversion failed. No barometer pressure data found in the input data.",
nameId());
455 std::optional<Eigen::Quaterniond> n_Quat_b;
456 std::optional<Eigen::Vector3d> e_position;
457 std::optional<Eigen::Vector3d> lla_position;
458 std::optional<Eigen::Vector3d> n_velocity;
460 if (vnObs->attitudeOutputs)
462 if (vnObs->attitudeOutputs->attitudeField & vn::protocol::uart::AttitudeGroup::ATTITUDEGROUP_QUATERNION)
464 n_Quat_b = vnObs->attitudeOutputs->qtn.cast<
double>();
466 else if (vnObs->attitudeOutputs->attitudeField & vn::protocol::uart::AttitudeGroup::ATTITUDEGROUP_YAWPITCHROLL)
468 Eigen::Vector3d ypr =
deg2rad(vnObs->attitudeOutputs->ypr.cast<
double>());
471 else if (vnObs->attitudeOutputs->attitudeField & vn::protocol::uart::AttitudeGroup::ATTITUDEGROUP_DCM)
473 n_Quat_b = vnObs->attitudeOutputs->dcm.cast<
double>();
477 auto posVelAttObs = std::make_shared<PosVelAtt>();
484 if (!vnObs->timeOutputs
485 || !(vnObs->timeOutputs->timeField & vn::protocol::uart::TimeGroup::TIMEGROUP_TIMESTATUS)
486 || !vnObs->timeOutputs->timeStatus.dateOk()
487 || !vnObs->timeOutputs->timeStatus.timeOk()
488 || !(vnObs->timeOutputs->timeField & vn::protocol::uart::TimeGroup::TIMEGROUP_GPSTOW)
489 || !(vnObs->timeOutputs->timeField & vn::protocol::uart::TimeGroup::TIMEGROUP_GPSWEEK))
494 posVelAttObs->insTime =
InsTime(
InsTime_GPSweekTow(0,
static_cast<int32_t
>(vnObs->timeOutputs->gpsWeek),
static_cast<double>(vnObs->timeOutputs->gpsTow) * 1e-9L));
496 if (vnObs->insOutputs->insField & vn::protocol::uart::InsGroup::INSGROUP_POSLLA)
498 lla_position = {
deg2rad(vnObs->insOutputs->posLla(0)),
499 deg2rad(vnObs->insOutputs->posLla(1)),
500 vnObs->insOutputs->posLla(2) };
502 if (vnObs->insOutputs->insField & vn::protocol::uart::InsGroup::INSGROUP_POSECEF)
504 e_position = vnObs->insOutputs->posEcef;
507 if (vnObs->insOutputs->insField & vn::protocol::uart::InsGroup::INSGROUP_VELNED)
509 n_velocity = vnObs->insOutputs->velNed.cast<
double>();
511 else if ((vnObs->insOutputs->insField & vn::protocol::uart::InsGroup::INSGROUP_VELECEF)
512 && (e_position.has_value() || lla_position.has_value()))
514 Eigen::Vector3d lla = lla_position.has_value() ? lla_position.value() :
trafo::ecef2lla_WGS84(e_position.value());
515 n_velocity =
trafo::n_Quat_e(lla(0), lla(1)) * vnObs->insOutputs->velEcef.cast<
double>();
517 else if ((vnObs->insOutputs->insField & vn::protocol::uart::InsGroup::INSGROUP_VELBODY)
518 && n_Quat_b.has_value())
520 n_velocity = n_Quat_b.value() * vnObs->insOutputs->velBody.cast<
double>();
525 && vnObs->gnss1Outputs && vnObs->gnss1Outputs->fix >= 2)
527 if (!vnObs->gnss1Outputs
528 || !vnObs->gnss1Outputs->timeInfo.status.timeOk()
529 || !vnObs->gnss1Outputs->timeInfo.status.dateOk())
534 posVelAttObs->insTime =
InsTime(
InsTime_GPSweekTow(0,
static_cast<int32_t
>(vnObs->gnss1Outputs->week),
static_cast<double>(vnObs->gnss1Outputs->tow) * 1e-9L));
536 if (!e_position.has_value() && !lla_position.has_value())
538 if (vnObs->gnss1Outputs->gnssField & vn::protocol::uart::GpsGroup::GPSGROUP_POSLLA)
540 lla_position = {
deg2rad(vnObs->gnss1Outputs->posLla(0)),
541 deg2rad(vnObs->gnss1Outputs->posLla(1)),
542 vnObs->gnss1Outputs->posLla(2) };
544 if (vnObs->gnss1Outputs->gnssField & vn::protocol::uart::GpsGroup::GPSGROUP_POSECEF)
546 e_position = vnObs->gnss1Outputs->posEcef;
550 if (!n_velocity.has_value())
552 if (vnObs->gnss1Outputs->gnssField & vn::protocol::uart::GpsGroup::GPSGROUP_VELNED)
554 n_velocity = vnObs->gnss1Outputs->velNed.cast<
double>();
556 else if ((vnObs->gnss1Outputs->gnssField & vn::protocol::uart::GpsGroup::GPSGROUP_VELECEF)
557 && (e_position.has_value() || lla_position.has_value()))
559 Eigen::Vector3d lla = lla_position.has_value() ? lla_position.value() :
trafo::ecef2lla_WGS84(e_position.value());
560 n_velocity =
trafo::n_Quat_e(lla(0), lla(1)) * vnObs->gnss1Outputs->velEcef.cast<
double>();
565 && vnObs->gnss2Outputs && vnObs->gnss2Outputs->fix >= 2)
567 if (!vnObs->gnss2Outputs
568 || !vnObs->gnss2Outputs->timeInfo.status.timeOk()
569 || !vnObs->gnss2Outputs->timeInfo.status.dateOk())
574 posVelAttObs->insTime =
InsTime(
InsTime_GPSweekTow(0,
static_cast<int32_t
>(vnObs->gnss2Outputs->week),
static_cast<double>(vnObs->gnss2Outputs->tow) * 1e-9L));
576 if (!e_position.has_value() && !lla_position.has_value())
578 if (vnObs->gnss2Outputs->gnssField & vn::protocol::uart::GpsGroup::GPSGROUP_POSLLA)
580 lla_position = {
deg2rad(vnObs->gnss2Outputs->posLla(0)),
581 deg2rad(vnObs->gnss2Outputs->posLla(1)),
582 vnObs->gnss2Outputs->posLla(2) };
584 if (vnObs->gnss2Outputs->gnssField & vn::protocol::uart::GpsGroup::GPSGROUP_POSECEF)
586 e_position = vnObs->gnss2Outputs->posEcef;
590 if (!n_velocity.has_value())
592 if (vnObs->gnss2Outputs->gnssField & vn::protocol::uart::GpsGroup::GPSGROUP_VELNED)
594 n_velocity = vnObs->gnss2Outputs->velNed.cast<
double>();
596 else if ((vnObs->gnss2Outputs->gnssField & vn::protocol::uart::GpsGroup::GPSGROUP_VELECEF)
597 && (e_position.has_value() || lla_position.has_value()))
599 Eigen::Vector3d lla = lla_position.has_value() ? lla_position.value() :
trafo::ecef2lla_WGS84(e_position.value());
600 n_velocity =
trafo::n_Quat_e(lla(0), lla(1)) * vnObs->gnss2Outputs->velEcef.cast<
double>();
605 if ((e_position.has_value() || lla_position.has_value()) && n_velocity.has_value())
607 if (e_position.has_value())
609 posVelAttObs->setPosition_e(e_position.value());
613 posVelAttObs->setPosition_lla(lla_position.value());
615 posVelAttObs->setVelocity_n(n_velocity.value());
617 if (!n_Quat_b.has_value())
619 LOG_DEBUG(
"{}: Conversion succeeded but has no attitude info.",
nameId());
623 posVelAttObs->setAttitude_n_Quat_b(n_Quat_b.value());
634 posVelAttObs->setVelocity_n(Eigen::Vector3d::Zero());
641 LOG_ERROR(
"{}: Conversion failed. No position or velocity data found in the input data.",
nameId());
647 auto gnssObs = std::make_shared<GnssObs>();
649 if (!vnObs->gnss1Outputs
650 || !vnObs->gnss1Outputs->timeInfo.status.timeOk()
651 || !vnObs->gnss1Outputs->timeInfo.status.dateOk())
656 gnssObs->insTime =
InsTime(
InsTime_GPSweekTow(0,
static_cast<int32_t
>(vnObs->gnss1Outputs->raw.week), vnObs->gnss1Outputs->raw.tow));
658 if (vnObs->gnss1Outputs)
660 if (vnObs->gnss1Outputs->gnssField & vn::protocol::uart::GpsGroup::GPSGROUP_RAWMEAS)
662 for (
const auto& satRaw : vnObs->gnss1Outputs->raw.satellites)
664 bool skipMeasurement =
false;
681 LOG_TRACE(
"VectorNav SatRawElement satellite system '{}' is not supported yet. Skipping measurement.", satRaw.sys);
682 skipMeasurement =
true;
691 LOG_TRACE(
"VectorNav SatRawElement satellite system '{}' is not supported yet. Skipping measurement.", satRaw.sys);
692 skipMeasurement =
true;
735 LOG_TRACE(
"VectorNav SatRawElement satellite system '{}' frequency '{}' channel '{}' is not supported yet. Skipping measurement.", satRaw.sys, satRaw.freq, satRaw.chan);
736 skipMeasurement =
true;
775 LOG_TRACE(
"VectorNav SatRawElement satellite system '{}' frequency '{}' channel '{}' is not supported yet. Skipping measurement.", satRaw.sys, satRaw.freq, satRaw.chan);
776 skipMeasurement =
true;
794 LOG_TRACE(
"VectorNav SatRawElement satellite system '{}' frequency '{}' channel '{}' is not supported yet. Skipping measurement.", satRaw.sys, satRaw.freq, satRaw.chan);
795 skipMeasurement =
true;
800 LOG_TRACE(
"VectorNav SatRawElement satellite system '{}' frequency '{}' is not supported yet. Skipping measurement.", satRaw.sys, satRaw.freq);
801 skipMeasurement =
true;
816 LOG_TRACE(
"VectorNav SatRawElement satellite system '{}' frequency '{}' channel '{}' is not supported yet. Skipping measurement.", satRaw.sys, satRaw.freq, satRaw.chan);
817 skipMeasurement =
true;
835 LOG_TRACE(
"VectorNav SatRawElement satellite system '{}' frequency '{}' channel '{}' is not supported yet. Skipping measurement.", satRaw.sys, satRaw.freq, satRaw.chan);
836 skipMeasurement =
true;
841 LOG_TRACE(
"VectorNav SatRawElement satellite system '{}' frequency '{}' is not supported yet. Skipping measurement.", satRaw.sys, satRaw.freq);
842 skipMeasurement =
true;
869 LOG_TRACE(
"VectorNav SatRawElement satellite system '{}' frequency '{}' channel '{}' is not supported yet. Skipping measurement.", satRaw.sys, satRaw.freq, satRaw.chan);
870 skipMeasurement =
true;
888 LOG_TRACE(
"VectorNav SatRawElement satellite system '{}' frequency '{}' channel '{}' is not supported yet. Skipping measurement.", satRaw.sys, satRaw.freq, satRaw.chan);
889 skipMeasurement =
true;
907 LOG_TRACE(
"VectorNav SatRawElement satellite system '{}' frequency '{}' channel '{}' is not supported yet. Skipping measurement.", satRaw.sys, satRaw.freq, satRaw.chan);
908 skipMeasurement =
true;
926 LOG_TRACE(
"VectorNav SatRawElement satellite system '{}' frequency '{}' channel '{}' is not supported yet. Skipping measurement.", satRaw.sys, satRaw.freq, satRaw.chan);
927 skipMeasurement =
true;
945 LOG_TRACE(
"VectorNav SatRawElement satellite system '{}' frequency '{}' channel '{}' is not supported yet. Skipping measurement.", satRaw.sys, satRaw.freq, satRaw.chan);
946 skipMeasurement =
true;
951 LOG_TRACE(
"VectorNav SatRawElement satellite system '{}' frequency '{}' is not supported yet. Skipping measurement.", satRaw.sys, satRaw.freq);
952 skipMeasurement =
true;
973 LOG_TRACE(
"VectorNav SatRawElement satellite system '{}' frequency '{}' channel '{}' is not supported yet. Skipping measurement.", satRaw.sys, satRaw.freq, satRaw.chan);
974 skipMeasurement =
true;
995 LOG_TRACE(
"VectorNav SatRawElement satellite system '{}' frequency '{}' channel '{}' is not supported yet. Skipping measurement.", satRaw.sys, satRaw.freq, satRaw.chan);
996 skipMeasurement =
true;
1002 switch (satRaw.chan)
1014 LOG_TRACE(
"VectorNav SatRawElement satellite system '{}' frequency '{}' channel '{}' is not supported yet. Skipping measurement.", satRaw.sys, satRaw.freq, satRaw.chan);
1015 skipMeasurement =
true;
1020 LOG_TRACE(
"VectorNav SatRawElement satellite system '{}' frequency '{}' is not supported yet. Skipping measurement.", satRaw.sys, satRaw.freq);
1021 skipMeasurement =
true;
1026 switch (satRaw.freq)
1030 switch (satRaw.chan)
1045 LOG_TRACE(
"VectorNav SatRawElement satellite system '{}' frequency '{}' channel '{}' is not supported yet. Skipping measurement.", satRaw.sys, satRaw.freq, satRaw.chan);
1046 skipMeasurement =
true;
1052 switch (satRaw.chan)
1064 LOG_TRACE(
"VectorNav SatRawElement satellite system '{}' frequency '{}' channel '{}' is not supported yet. Skipping measurement.", satRaw.sys, satRaw.freq, satRaw.chan);
1065 skipMeasurement =
true;
1071 switch (satRaw.chan)
1083 LOG_TRACE(
"VectorNav SatRawElement satellite system '{}' frequency '{}' channel '{}' is not supported yet. Skipping measurement.", satRaw.sys, satRaw.freq, satRaw.chan);
1084 skipMeasurement =
true;
1090 switch (satRaw.chan)
1102 LOG_TRACE(
"VectorNav SatRawElement satellite system '{}' frequency '{}' channel '{}' is not supported yet. Skipping measurement.", satRaw.sys, satRaw.freq, satRaw.chan);
1103 skipMeasurement =
true;
1108 LOG_TRACE(
"VectorNav SatRawElement satellite system '{}' frequency '{}' is not supported yet. Skipping measurement.", satRaw.sys, satRaw.freq);
1109 skipMeasurement =
true;
1114 switch (satRaw.freq)
1118 switch (satRaw.chan)
1127 LOG_TRACE(
"VectorNav SatRawElement satellite system '{}' frequency '{}' channel '{}' is not supported yet. Skipping measurement.", satRaw.sys, satRaw.freq, satRaw.chan);
1128 skipMeasurement =
true;
1134 switch (satRaw.chan)
1143 LOG_TRACE(
"VectorNav SatRawElement satellite system '{}' frequency '{}' channel '{}' is not supported yet. Skipping measurement.", satRaw.sys, satRaw.freq, satRaw.chan);
1144 skipMeasurement =
true;
1149 LOG_TRACE(
"VectorNav SatRawElement satellite system '{}' frequency '{}' is not supported yet. Skipping measurement.", satRaw.sys, satRaw.freq);
1150 skipMeasurement =
true;
1156 skipMeasurement =
true;
1160 if (skipMeasurement)
1165 (*gnssObs)(
SatSigId(code, satRaw.svId)).pseudorange = { .value = satRaw.pr };
1166 (*gnssObs)(
SatSigId(code, satRaw.svId)).carrierPhase = { .value = satRaw.cp };
1167 (*gnssObs)(
SatSigId(code, satRaw.svId)).doppler = satRaw.dp;
1168 (*gnssObs)(
SatSigId(code, satRaw.svId)).CN0 = satRaw.cno;
1186 return "ImuObsWDelta";
1188 return "BaroPressObs";
Barometric Pressure Storage Class.
Transformation collection.
Combo representing an enumeration.
nlohmann::json json
json namespace
The class is responsible for all time-related tasks.
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_ERROR
Error occurred, which stops part of the program to work, but not everything.
#define LOG_TRACE
Detailled info to trace the execution of the program. Should not be called on functions which receive...
constexpr double SCALE_FACTOR_KILO2HECTOPASCAL
Scale factor to kPa to hPa.
Converts VectorNavBinaryOutput.
static std::string type()
Returns the type of the data class.
Enumerate for GNSS Codes.
@ G2P
GPS L2 - P-code (unencrypted)
@ B7I
BeiDou B2b (BDS-2) - B2I(OS)
@ J2L
QZSS L2 - L2C-code (long)
@ G1L
GPS L1 - L1C-P (pilot)
@ G2D
GPS L2 - Semi-codeless P(Y) tracking (L1 C/A + (P2-P1))
@ J6L
QZSS L6 - L6P LEX signal (long)
@ G1Y
GPS L1 - Y-code (with decryption)
@ G1X
GPS L1 - L1C-(D+P) (combined)
@ G2X
GPS L2 - L2C(M+L) (combined)
@ J6X
QZSS L6 - L6(D+P) LEX signal (combined)
@ E6X
GAL E6 - Combined (B+C)
@ J1L
QZSS L1 - L1C (pilot)
@ J1S
QZSS L1 - L1C (data)
@ J1X
QZSS L1 - L1C (combined)
@ E8X
GAL E5(a+b) - AltBOC (combined)
@ G2Y
GPS L2 - Y-code (with decryption)
@ E1Z
GAL E1 - PRS + OS (data + pilot)
@ G1P
GPS L1 - P-code (unencrypted)
@ J2X
QZSS L2 - L2C-code (combined)
@ G1W
GPS L1 - Semicodeless P(Y) tracking (Z-tracking)
@ G2L
GPS L2 - L2C(L) (long)
@ E8I
GAL E5(a+b) - AltBOC (data)
@ G2W
GPS L2 - Semicodeless P(Y) tracking (Z-tracking)
@ E1A
GAL E1 - PRS signal.
@ E8Q
GAL E5(a+b) - AltBOC (pilot)
@ J6S
QZSS L6 - L6D LEX signal (short)
@ B6X
BeiDou B3 - B3I, B3Q, combined.
@ B7X
BeiDou B2b (BDS-2) - B2I(OS), B2Q, combined.
@ E1X
GAL E1 - OS(B+C) (combined)
@ B2I
BeiDou B1-2 - B1I(OS)
@ B7Q
BeiDou B2b (BDS-2) - B2Q.
@ G1S
GPS L1 - L1C-D (data)
@ B2X
BeiDou B1-2 - B1I(OS), B1Q, combined.
@ G2S
GPS L2 - L2C(M) (medium)
@ J2S
QZSS L2 - L2C-code (medium)
Frequency definition for different satellite systems.
static std::string type()
Returns the type of the data class.
static std::string type()
Returns the type of the data class.
static std::string type()
Returns the type of the data class.
The class is responsible for all time-related tasks.
ImVec2 _guiConfigDefaultWindowSize
std::vector< OutputPin > outputPins
List of output pins.
Node(std::string name)
Constructor.
std::string nameId() const
Node name and id.
std::string name
Name of the Node.
void invokeCallbacks(size_t portIndex, const std::shared_ptr< const NodeData > &data)
Calls all registered callbacks on the specified output port.
bool _hasConfig
Flag if the config window should be shown.
static std::string type()
Returns the type of the data class.
auto extract_front()
Returns a copy of the first element in the container and removes it from the container.
VectorNavBinaryConverter()
Default constructor.
static std::shared_ptr< const GnssObs > convert2GnssObs(const std::shared_ptr< const VectorNavBinaryOutput > &vnObs)
Converts the VectorNavBinaryOutput to a GnssObs observation.
std::shared_ptr< const ImuObs > convert2ImuObs(const std::shared_ptr< const VectorNavBinaryOutput > &vnObs) const
Converts the VectorNavBinaryOutput to a ImuObs observation.
OutputType _outputType
The selected output type in the GUI.
std::shared_ptr< const PosVelAtt > convert2PosVelAtt(const std::shared_ptr< const VectorNavBinaryOutput > &vnObs)
Converts the VectorNavBinaryOutput to a PosVelAtt observation.
OutputType
Enum specifying the type of the output message.
@ ImuObsWDelta
Extract ImuObsWDelta data.
@ GnssObs
Extract GnssObs data.
@ COUNT
Number of items in the enum.
@ PosVelAtt
Extract PosVelAtt data.
@ BaroPressObs
Extract BaroPressObs data.
@ ImuObs
Extract ImuObs data.
void receiveObs(InputPin::NodeDataQueue &queue, size_t pinIdx)
Converts the VectorNavBinaryOutput observation to the selected message type.
static constexpr size_t OUTPUT_PORT_INDEX_CONVERTED
Flow.
static std::string category()
String representation of the Class Category.
std::shared_ptr< const PosVelAtt > _posVelAtt__init
Position, Velocity and Attitude at initialization (needed for static data)
void restore(const json &j) override
Restores the node from a json object.
static std::string typeStatic()
String representation of the Class Type.
std::shared_ptr< const ImuObsWDelta > convert2ImuObsWDelta(const std::shared_ptr< const VectorNavBinaryOutput > &vnObs) const
Converts the VectorNavBinaryOutput to a ImuObsWDelta observation.
json save() const override
Saves the node into a json object.
std::shared_ptr< const BaroPressObs > convert2BaroPressObs(const std::shared_ptr< const VectorNavBinaryOutput > &vnObs) const
Converts the VectorNavBinaryOutput to a BaroPressObs observation.
~VectorNavBinaryConverter() override
Destructor.
PosVelSource _posVelSource
The selected PosVel source in the GUI.
std::string type() const override
String representation of the Class Type.
bool _forceStatic
GUI option. If checked forces position to a static value and velocity to 0.
bool _useCompensatedData
Whether to extract the compensated data or the uncompensated.
bool initialize() override
Initialize the node.
void guiConfig() override
ImGui config window which is shown on double click.
@ PosVelSource_Best
INS > GNSS1 > GNSS2.
@ PosVelSource_Gnss2
Take only GNSS2 values into account.
@ PosVelSource_Gnss1
Take only GNSS1 values into account.
@ PosVelSource_Ins
Take only INS values into account.
static std::string type()
Returns the type of the data class.
@ Aligning
INS Filter is dynamically aligning.
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.
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::Vector3< typename Derived::Scalar > ecef2lla_WGS84(const Eigen::MatrixBase< Derived > &e_position)
Converts Earth-centered-Earth-fixed coordinates into latitude, longitude and altitude using WGS84.
Eigen::Quaternion< Scalar > n_Quat_e(const Scalar &latitude, const Scalar &longitude)
Quaternion for rotations from Earth-fixed to navigation frame.
Eigen::Quaternion< Scalar > n_Quat_b(Scalar roll, Scalar pitch, Scalar yaw)
Quaternion for rotations from body to navigation frame.
@ E07
Galileo E5b (1207.14 MHz).
@ J01
QZSS L1 (1575.42 MHz).
@ S01
SBAS L1 (1575.42 MHz).
@ E06
Galileo E6 (1278.75 MHz).
@ R02
GLONASS, "G2" (1246 MHz).
@ B08
Beidou B2 (B2a + B2b) (1191.795MHz).
@ E01
Galileo, "E1" (1575.42 MHz).
@ B06
Beidou B3 (1268.52 MHz).
@ E05
Galileo E5a (1176.45 MHz).
@ S05
SBAS L5 (1176.45 MHz).
@ G02
GPS L2 (1227.6 MHz).
@ R01
GLONASS, "G1" (1602 MHZ).
@ G01
GPS L1 (1575.42 MHz).
@ B01
Beidou B1 (1575.42 MHz).
@ J05
QZSS L5 (1176.45 MHz).
@ J02
QZSS L2 (1227.6 MHz).
@ E08
Galileo E5 (E5a + E5b) (1191.795MHz).
@ J06
QZSS L6 / LEX (1278.75 MHz).
@ G05
GPS L5 (1176.45 MHz).
const char * to_string(gui::widgets::PositionWithFrame::ReferenceFrame refFrame)
Converts the enum to a string.
constexpr auto deg2rad(const T °)
Convert Degree to Radians.
SatelliteSystem_
Satellite System enumeration.
@ GPS
Global Positioning System.
@ QZSS
Quasi-Zenith Satellite System.
@ GLO
Globalnaja nawigazionnaja sputnikowaja sistema (GLONASS)
@ SBAS
Satellite Based Augmentation System.
@ SatSys_None
No Satellite system.
@ IRNSS
Indian Regional Navigation Satellite System.
GPS week and time of week in GPS standard time [GPST].
Identifies a satellite signal (satellite frequency and number)
@ E6
E6(GAL), LEX(QZSS), B3(BDS)
@ L5
L5(GPS,QZSS,SBAS), E5a(GAL)
@ L2
L2(GPS,QZSS), G2(GLO)
@ L1
L1(GPS,QZSS,SBAS), G1(GLO), E2-L1-E1(GAL), B1(BDS)
@ Q_Chan
Q chan (GPS,GAL,QZSS,BDS)
@ SemiCodeless
semi-codeless (GPS)
@ I_Chan
I chan (GPS,GAL,QZSS,BDS)
@ L_Chan
L chan (L2CGPS, L2CQZSS), P chan (GPS,QZSS)
@ BC_Chan
B+C chan (GAL), I+Q chan (GPS,GAL,QZSS,BDS), M+L chan (GPS,QZSS), D+P chan (GPS,QZSS)
@ CA_Code
C/A-code (GPS,GLO,SBAS,QZSS), C chan (GAL)
@ M_Chan
M chan (L2CGPS, L2CQZSS), D chan (GPS,QZSS)
@ Z_Tracking
based on Z-tracking (GPS)