22#include <fmt/ostream.h>
296 std::vector<UbxEsfRawData>
data;
697 std::vector<UbxRxmRawxData>
data;
782[[nodiscard]] uint8_t
getMsgIdFromString(
const std::string& className,
const std::string& idName);
803[[nodiscard]]
Code getCode(uint8_t gnssId, uint8_t sigId);
813#ifndef DOXYGEN_IGNORE
819struct fmt::formatter<
NAV::vendor::ublox::NmeaTalkerID> : ostream_formatter
822struct fmt::formatter<
NAV::vendor::ublox::NmeaMessageClass> : ostream_formatter
825struct fmt::formatter<
NAV::vendor::ublox::NmeaStandardMessages> : ostream_formatter
828struct fmt::formatter<
NAV::vendor::ublox::NmeaPubxMessages> : ostream_formatter
833struct fmt::formatter<
NAV::vendor::ublox::UbxClass> : fmt::formatter<std::string>
839 template<
typename FormatContext>
847struct fmt::formatter<
NAV::vendor::ublox::UbxAckMessages> : ostream_formatter
850struct fmt::formatter<
NAV::vendor::ublox::UbxCfgMessages> : ostream_formatter
853struct fmt::formatter<
NAV::vendor::ublox::UbxEsfMessages> : ostream_formatter
856struct fmt::formatter<
NAV::vendor::ublox::UbxHnrMessages> : ostream_formatter
859struct fmt::formatter<
NAV::vendor::ublox::UbxInfMessages> : ostream_formatter
862struct fmt::formatter<
NAV::vendor::ublox::UbxLogMessages> : ostream_formatter
865struct fmt::formatter<
NAV::vendor::ublox::UbxMgaMessages> : ostream_formatter
868struct fmt::formatter<
NAV::vendor::ublox::UbxMonMessages> : ostream_formatter
871struct fmt::formatter<
NAV::vendor::ublox::UbxNavMessages> : ostream_formatter
874struct fmt::formatter<
NAV::vendor::ublox::UbxRxmMessages> : ostream_formatter
877struct fmt::formatter<
NAV::vendor::ublox::UbxSecMessages> : ostream_formatter
880struct fmt::formatter<
NAV::vendor::ublox::UbxTimMessages> : ostream_formatter
883struct fmt::formatter<
NAV::vendor::ublox::UbxUpdMessages> : ostream_formatter
Structs identifying a unique satellite.
std::ostream & operator<<(std::ostream &os, const NAV::vendor::ublox::UbxClass &obj)
Stream insertion operator overload.
Enumerate for GNSS Codes.
NmeaMessageClass
NMEA Message Type.
@ NMEA_MSG_CLASS_PUBX
PUBX Messages.
@ NMEA_MSG_CLASS_STANDARD
Standard Messages.
UbxMgaMessages
The available MGA Messages.
@ UBX_MGA_FLASH_STOP
Finish flashing MGA-ANO data (Length = 2; Type = Input)
@ UBX_MGA_INI_TIME_GNSS
Initial Time Assistance (Length = 24; Type = Input)
@ UBX_MGA_GPS_ALM
GPS Almanac Assistance (Length = 36; Type = Input)
@ UBX_MGA_GAL_EPH
Galileo Ephemeris Assistance (Length = 76; Type = Input)
@ UBX_MGA_QZSS_HEALTH
QZSS Health Assistance (Length = 12; Type = Input)
@ UBX_MGA_QZSS_EPH
QZSS Ephemeris Assistance (Length = 68; Type = Input)
@ UBX_MGA_INI_CLKD
Initial Clock Drift Assistance (Length = 12; Type = Input)
@ UBX_MGA_ACK_DATA0
Multiple GNSS Acknowledge message (Length = 8; Type = Output)
@ UBX_MGA_INI_POS_LLH
Initial Position Assistance (Length = 20; Type = Input)
@ UBX_MGA_BDS_ALM
BDS Almanac Assistance (Length = 40; Type = Input)
@ UBX_MGA_GPS_UTC
GPS UTC Assistance (Length = 20; Type = Input)
@ UBX_MGA_GLO_EPH
GLONASS Ephemeris Assistance (Length = 48; Type = Input)
@ UBX_MGA_ANO
Multiple GNSS AssistNow Offline Assistance (Length = 76; Type = Input)
@ UBX_MGA_BDS_EPH
BDS Ephemeris Assistance (Length = 88; Type = Input)
@ UBX_MGA_GLO_ALM
GLONASS Almanac Assistance (Length = 36; Type = Input)
@ UBX_MGA_INI_FREQ
Initial Frequency Assistance (Length = 12; Type = Input)
@ UBX_MGA_INI_TIME_UTC
Initial Time Assistance (Length = 24; Type = Input)
@ UBX_MGA_GPS_HEALTH
GPS Health Assistance (Length = 40; Type = Input)
@ UBX_MGA_INI_EOP
Earth Orientation Parameters Assistance (Length = 72; Type = Input)
@ UBX_MGA_FLASH_ACK
Acknowledge last FLASH-DATA or -STOP (Length = 6; Type = Output)
@ UBX_MGA_FLASH_DATA
Transfer MGA-ANO data block to flash (Length = 6 + 1*size; Type = Input)
@ UBX_MGA_BDS_IONO
BDS Ionospheric Assistance (Length = 16; Type = Input)
@ UBX_MGA_BDS_UTC
BDS UTC Assistance (Length = 20; Type = Input)
@ UBX_MGA_GPS_IONO
GPS Ionosphere Assistance (Length = 16; Type = Input)
@ UBX_MGA_INI_POS_XYZ
Initial Position Assistance (Length = 20; Type = Input)
@ UBX_MGA_GAL_ALM
Galileo Almanac Assistance (Length = 32; Type = Input)
@ UBX_MGA_GAL_UTC
Galileo UTC Assistance (Length = 20; Type = Input)
@ UBX_MGA_GAL_TIMEOFFSET
Galileo GPS time offset assistance (Length = 12; Type = Input)
@ UBX_MGA_QZSS_ALM
QZSS Almanac Assistance (Length = 36; Type = Input)
@ UBX_MGA_BDS_HEALTH
BDS Health Assistance (Length = 68; Type = Input)
@ UBX_MGA_GPS_EPH
GPS Ephemeris Assistance (Length = 68; Type = Input)
@ UBX_MGA_GLO_TIMEOFFSET
GLONASS Auxiliary Time Offset Assistance (Length = 20; Type = Input)
UbxUpdMessages
The available UPD Messages.
UbxTimMessages
The available TIM Messages.
@ UBX_TIM_TP
Time Pulse Timedata (Length = 16; Type = Periodic/Polled)
@ UBX_TIM_VRFY
Sourced Time Verification (Length = 20; Type = Periodic/Polled)
@ UBX_TIM_SVIN
Survey-in data (Length = 28; Type = Periodic/Polled)
@ UBX_TIM_TM2
Time mark data (Length = 28; Type = Periodic/Polled)
@ UBX_TIM_FCHG
Oscillator frequency changed notification (Length = 32; Type = Periodic/Polled)
@ UBX_TIM_TOS
Time Pulse Time and Frequency Data (Length = 56; Type = Periodic)
@ UBX_TIM_HOC
Host oscillator control (Length = 8; Type = Input)
@ UBX_TIM_SMEAS
Source measurement (Length = 12 + 24*numMeas; Type = Input/Output)
std::string getStringFromMsgId(UbxClass msgClass, uint8_t msgId)
Get the a string from a UBX Msg Id.
UbxCfgMessages
The available CFG Messages.
@ UBX_CFG_TMODE3
Time Mode Settings 3 (Length = 40; Type = Get/Set)
@ UBX_CFG_RATE
Navigation/Measurement Rate Settings (Length = 6; Type = Get/Set)
@ UBX_CFG_CFG
Clear, Save and Load configurations (Length = (12) or (13); Type = Command)
@ UBX_CFG_DGNSS
DGNSS configuration (Length = 4; Type = Get/Set)
@ UBX_CFG_GEOFENCE
Geofencing configuration (Length = 8 + 12*numFences; Type = Get/Set)
@ UBX_CFG_TMODE2
Time Mode Settings 2 (Length = 28; Type = Get/Set)
@ UBX_CFG_ANT
Antenna Control Settings (Length = 4; Type = Get/Set)
@ UBX_CFG_ODO
Odometer, Low-speed COG Engine Settings (Length = 20; Type = Get/Set)
@ UBX_CFG_ITFM
Jamming/Interference Monitor configuration (Length = 8; Type = Get/Set)
@ UBX_CFG_SLAS
SLAS Configuration (Length = 4; Type = Get/Set)
@ UBX_CFG_ESRC
External synchronization source configuration (Length = 4 + 36*numSources; Type = Get/Set)
@ UBX_CFG_GNSS
GNSS system configuration (Length = 4 + 8*numConfigBlocks; Type = Get/Set)
@ UBX_CFG_LOGFILTER
Data Logger Configuration (Length = 12; Type = Get/Set)
@ UBX_CFG_PWR
Put receiver in a defined power state (Length = 8; Type = Set)
@ UBX_CFG_BATCH
Get/Set data batching configuration (Length = 8; Type = Get/Set)
@ UBX_CFG_RINV
Contents of Remote Inventory (Length = 1 + 1*N; Type = Get/Set)
@ UBX_CFG_DOSC
Disciplined oscillator configuration (Length = 4 + 32*numOsc; Type = Get/Set)
@ UBX_CFG_SBAS
SBAS Configuration (Length = 8; Type = Get/Set)
@ UBX_CFG_HNR
High Navigation Rate Settings (Length = 4; Type = Get/Set)
@ UBX_CFG_RST
Reset Receiver / Clear Backup Data Structures (Length = 4; Type = Command)
@ UBX_CFG_PMS
Power Mode Setup (Length = 8; Type = Get/Set)
@ UBX_CFG_USB
USB Configuration (Length = 108; Type = Get/Set)
@ UBX_CFG_NAV5
Navigation Engine Settings (Length = 36; Type = Get/Set)
@ UBX_CFG_TXSLOT
TX buffer time slots configuration (Length = 16; Type = Set)
@ UBX_CFG_SMGR
Synchronization manager configuration (Length = 20; Type = Get/Set)
Code getCode(uint8_t gnssId, uint8_t sigId)
Get the GNSS code from gnssId and sigId.
UbxAckMessages
The available ACK Messages.
@ UBX_ACK_ACK
Message Acknowledged (Length = 2; Type = Output)
@ UBX_ACK_NAK
Message Not-Acknowledged (Length = 2; Type = Output)
ErrorDetectionMode
Error detection modes available.
@ ERRORDETECTIONMODE_NONE
No error detection is used.
@ ERRORDETECTIONMODE_CHECKSUM
16-bit checksum is used
UbxLogMessages
The available LOG Messages.
@ UBX_LOG_RETRIEVEPOS
Position fix log entry (Length = 40; Type = Output)
@ UBX_LOG_ERASE
Erase Logged Data (Length = 0; Type = Command)
@ UBX_LOG_BATCH
Batched data (Length = 100; Type = Polled)
@ UBX_LOG_RETRIEVE
Request log data (Length = 12; Type = Command)
@ UBX_LOG_RETRIEVESTRING
Byte string log entry (Length = 16 + 1*byteCount; Type = )
@ UBX_LOG_RETRIEVEPOSEXTRA
Odometer log entry (Length = 32; Type = Output)
@ UBX_LOG_STRING
Store arbitrary string in on-board flash (Length = 0 + 1*N; Type = Command)
@ UBX_LOG_RETRIEVEBATCH
Request batch data (Length = 4; Type = Command)
@ UBX_LOG_CREATE
Create Log File (Length = 8; Type = Command)
UbxInfMessages
The available INF Messages.
@ UBX_INF_ERROR
ASCII output with error contents (Length = 0 + 1*N; Type = Output)
@ UBX_INF_TEST
ASCII output with test contents (Length = 0 + 1*N; Type = Output)
@ UBX_INF_NOTICE
ASCII output with informational contents (Length = 0 + 1*N; Type = Output)
@ UBX_INF_DEBUG
ASCII output with debug contents (Length = 0 + 1*N; Type = Output)
@ UBX_INF_WARNING
ASCII output with warning contents (Length = 0 + 1*N; Type = Output)
UbxClass getMsgClassFromString(const std::string &className)
Get the UBX Msg Class From String object.
SatelliteSystem getSatSys(uint8_t gnssId)
Get the GNSS Satellite System from gnssId.
uint8_t getMsgIdFromString(UbxClass msgClass, const std::string &idName)
Get the UBX Msg Id From String object.
UbxEsfMessages
The available ESF Messages.
@ UBX_ESF_INS
Vehicle dynamics information (Length = 36; Type = Periodic/Polled)
@ UBX_ESF_RAW
Raw sensor measurements (Length = 4 + 8*N; Type = Output)
@ UBX_ESF_STATUS
External Sensor Fusion (ESF) status information (Length = 16 + 4*numSens; Type = Periodic/Polled)
@ UBX_ESF_MEAS
External Sensor Fusion Measurements (Length = (8 + 4*numMeas) or (12 + 4*numMeas); Type = Input/Outpu...
UbxClass
The available UBX Class IDs.
@ UBX_CLASS_NAV
Navigation Results Messages: Position, Speed, Time, Acceleration, Heading, DOP, SVs used.
@ UBX_CLASS_TIM
Timing Messages: Time Pulse Output, Time Mark Results.
@ UBX_CLASS_AID
AssistNow Aiding Messages: Ephemeris, Almanac, other A-GPS data input.
@ UBX_CLASS_NONE
No Message Class specified.
@ UBX_CLASS_INF
Information Messages: Printf-Style Messages, with IDs such as Error, Warning, Notice.
@ UBX_CLASS_HNR
High Rate Navigation Results Messages: High rate time, position, speed, heading.
@ UBX_CLASS_SEC
Security Feature Messages.
@ UBX_CLASS_MON
Monitoring Messages: Communication Status, CPU Load, Stack Usage, Task Status.
@ UBX_CLASS_MGA
Multiple GNSS Assistance Messages: Assistance data for various GNSS.
@ UBX_CLASS_RXM
Receiver Manager Messages: Satellite Status, RTC Status.
@ UBX_CLASS_ESF
External Sensor Fusion Messages: External Sensor Measurements and Status Information.
@ UBX_CLASS_LOG
Logging Messages: Log creation, deletion, info and retrieval.
@ UBX_CLASS_UPD
Firmware Update Messages: Memory/Flash erase/write, Reboot, Flash identification, etc.
@ UBX_CLASS_CFG
Configuration Input Messages: Configure the receiver.
@ UBX_CLASS_ACK
Ack/Nak Messages: Acknowledge or Reject messages to UBX-CFG input messages.
UbxRxmMessages
The available RXM Messages.
@ UBX_RXM_IMES
Indoor Messaging System Information (Length = 4 + 44*numTx; Type = Periodic/Polled)
@ UBX_RXM_SVSI
SV Status Info (Length = 8 + 6*numSV; Type = Periodic/Polled)
@ UBX_RXM_RTCM
RTCM input status (Length = 8; Type = Output)
std::string getStringFromMsgClass(UbxClass msgClass)
Get the a string from a UBX Msg Class.
NmeaStandardMessages
NMEA Standard Messages. Class ID = 0xF0.
@ NMEA_STANDARD_MSG_GPQ
Poll a standard message (if the current Talker ID is GP)
@ NMEA_STANDARD_MSG_GBS
GNSS Satellite Fault Detection.
@ NMEA_STANDARD_MSG_GLL
Latitude and longitude, with time of position fix and status.
@ NMEA_STANDARD_MSG_GBQ
Poll a standard message (if the current Talker ID is GB)
@ NMEA_STANDARD_MSG_DTM
Datum Reference.
@ NMEA_STANDARD_MSG_GGA
Global positioning system fix data.
@ NMEA_STANDARD_MSG_VLW
Dual ground/water distance.
@ NMEA_STANDARD_MSG_GST
GNSS Pseudo Range Error Statistics.
@ NMEA_STANDARD_MSG_GSA
GNSS DOP and Active Satellites.
@ NMEA_STANDARD_MSG_TXT
Text Transmission.
@ NMEA_STANDARD_MSG_GRS
GNSS Range Residuals.
@ NMEA_STANDARD_MSG_GNS
GNSS fix data.
@ NMEA_STANDARD_MSG_ZDA
Time and Date.
@ NMEA_STANDARD_MSG_VTG
Course over ground and Ground speed.
@ NMEA_STANDARD_MSG_GSV
GNSS Satellites in View.
@ NMEA_STANDARD_MSG_GNQ
Poll a standard message (if the current Talker ID is GN)
@ NMEA_STANDARD_MSG_GLQ
Poll a standard message (if the current Talker ID is GL)
@ NMEA_STANDARD_MSG_RMC
Recommended Minimum data.
UbxHnrMessages
The available HNR Messages.
@ UBX_HNR_INS
Vehicle dynamics information (Length = 36; Type = Periodic/Polled)
@ UBX_HNR_PVT
High Rate Output of PVT Solution (Length = 72; Type = Periodic/Polled)
NmeaPubxMessages
NMEA PUBX Messages. Class ID = 0xF1.
@ NMEA_PUBX_MSG_TIME
Time of Day and Clock Information.
@ NMEA_PUBX_MSG_RATE
Set NMEA message output rate.
@ NMEA_PUBX_MSG_POSITION
Lat/Long Position Data.
@ NMEA_PUBX_MSG_SVSTATUS
Satellite Status.
@ NMEA_PUBX_MSG_CONFIG
Set Protocols and Baudrate.
UbxSecMessages
The available SEC Messages.
@ UBX_SEC_UNIQID
Unique Chip ID (Length = 9; Type = Output)
UbxNavMessages
The available NAV Messages.
@ UBX_NAV_VELNED
Velocity Solution in NED (Length = 36; Type = Periodic/Polled)
@ UBX_NAV_ATT
Attitude Solution (Length = 32; Type = Periodic/Polled)
@ UBX_NAV_RESETODO
Reset odometer (Length = 0; Type = Command)
@ UBX_NAV_SAT
Satellite Information (Length = 8 + 12*numSvs; Type = Periodic/Polled)
@ UBX_NAV_TIMEGLO
GLO Time Solution (Length = 20; Type = Periodic/Polled)
@ UBX_NAV_DOP
Dilution of precision (Length = 18; Type = Periodic/Polled)
@ UBX_NAV_POSECEF
Position Solution in ECEF (Length = 20; Type = Periodic/Polled)
@ UBX_NAV_TIMEUTC
UTC Time Solution (Length = 20; Type = Periodic/Polled)
@ UBX_NAV_GEOFENCE
Geofencing status (Length = 8 + 2*numFences; Type = Periodic/Polled)
@ UBX_NAV_AOPSTATUS
AssistNow Autonomous Status (Length = 16; Type = Periodic/Polled)
@ UBX_NAV_PVT
Navigation Position Velocity Time Solution (Length = 92; Type = Periodic/Polled)
@ UBX_NAV_ODO
Odometer Solution (Length = 20; Type = Periodic/Polled)
@ UBX_NAV_EOE
End Of Epoch (Length = 4; Type = Periodic)
@ UBX_NAV_HPPOSLLH
High Precision Geodetic Position Solution (Length = 36; Type = Periodic/Polled)
@ UBX_NAV_DGPS
DGPS Data Used for NAV (Length = 16 + 12*numCh; Type = Periodic/Polled)
@ UBX_NAV_CLOCK
Clock Solution (Length = 20; Type = Periodic/Polled)
@ UBX_NAV_RELPOSNED
Relative Positioning Information in NED frame (Length = 40; Type = Periodic/Polled)
@ UBX_NAV_SVIN
Survey-in data (Length = 40; Type = Periodic/Polled)
@ UBX_NAV_SBAS
SBAS Status Data (Length = 12 + 12*cnt; Type = Periodic/Polled)
@ UBX_NAV_VELECEF
Velocity Solution in ECEF (Length = 20; Type = Periodic/Polled)
@ UBX_NAV_TIMEGPS
GPS Time Solution (Length = 16; Type = Periodic/Polled)
@ UBX_NAV_TIMELS
Leap second event information (Length = 24; Type = Periodic/Polled)
@ UBX_NAV_TIMEGAL
Galileo Time Solution (Length = 20; Type = Periodic/Polled)
@ UBX_NAV_SVINFO
Space Vehicle Information (Length = 8 + 12*numCh; Type = Periodic/Polled)
@ UBX_NAV_SOL
Navigation Solution Information (Length = 52; Type = Periodic/Polled)
@ UBX_NAV_SLAS
QZSS L1S SLAS Status Data (Length = 20 + 8*cnt; Type = Periodic/Polled)
@ UBX_NAV_HPPOSECEF
High Precision Position Solution in ECEF (Length = 28; Type = Periodic/Polled)
@ UBX_NAV_ORB
GNSS Orbit Database Info (Length = 8 + 6*numSv; Type = Periodic/Polled)
@ UBX_NAV_POSLLH
Geodetic Position Solution (Length = 28; Type = Periodic/Polled)
@ UBX_NAV_TIMEBDS
BDS Time Solution (Length = 20; Type = Periodic/Polled)
@ UBX_NAV_STATUS
Receiver Navigation Status (Length = 16; Type = Periodic/Polled)
UbxMonMessages
The available MON Messages.
@ UBX_MON_TXBUFF
Transmitter Buffer Status (Length = 28; Type = Periodic/Polled)
@ UBX_MON_GNSS
Information message major GNSS selection (Length = 8; Type = Polled)
@ UBX_MON_RXBUFF
Receiver Buffer Status (Length = 24; Type = Periodic/Polled)
@ UBX_MON_HW2
Extended Hardware Status (Length = 28; Type = Periodic/Polled)
@ UBX_MON_RXR
Receiver Status Information (Length = 1; Type = Output)
@ UBX_MON_HW
Hardware Status (Length = 60; Type = Periodic/Polled)
@ UBX_MON_MSGPP
Message Parse and Process Status (Length = 120; Type = Periodic/Polled)
@ UBX_MON_IO
I/O Subsystem Status (Length = 0 + 20*N; Type = Periodic/Polled)
@ UBX_MON_SMGR
Synchronization Manager Status (Length = 16; Type = Periodic/Polled)
@ UBX_MON_BATCH
Data batching buffer status (Length = 12; Type = Polled)
NmeaTalkerID
Enumeration of the available asynchronous ASCII talker IDs.
@ NMEA_TALKER_ID_OFF
Asynchronous output is turned off.
@ NMEA_TALKER_ID_GL
GLONASS.
@ NMEA_TALKER_ID_GA
Galileo.
@ NMEA_TALKER_ID_GN
Any combination of GNSS.
@ NMEA_TALKER_ID_GB
BeiDou.
@ NMEA_TALKER_ID_GP
GPS, SBAS, QZSS.
uint8_t msgID
Message ID of the Acknowledged Message.
uint8_t clsID
Class ID of the Acknowledged Message.
Message Not-Acknowledged.
uint8_t clsID
Class ID of the Not-Acknowledged Message.
uint8_t msgID
Message ID of the Not-Acknowledged Message.
Vehicle dynamics information.
int32_t xAngRate
Compensated x-axis angular rate. [deg/s * 1e-3].
int32_t zAccel
Compensated z-axis acceleration (gravity-free). [m/s^2 * 1e-2].
int32_t zAngRate
Compensated z-axis angular rate. [deg/s * 1e-3].
std::bitset< 4UL *8UL > bitfield0
Bitfield (zAccelValid, yAccelValid, xAccelValid, zAngRateValid, yAngRateValid, xAngRateValid,...
int32_t xAccel
Compensated x-axis acceleration (gravity-free). [m/s^2 * 1e-2].
std::array< uint8_t, 4 > reserved1
Reserved.
uint32_t iTOW
GPS time of week of the navigation epoch. See the description of iTOW for details....
int32_t yAngRate
Compensated y-axis angular rate. [deg/s * 1e-3].
int32_t yAccel
Compensated y-axis acceleration (gravity-free). [m/s^2 * 1e-2].
External Sensor Fusion Measurements.
std::optional< std::vector< uint32_t > > calibTtag
Receiver local time calibrated. This field must not be supplied when calibTtagValid is set to 0....
std::bitset< 2UL *8UL > flags
Flags. Set all unused bits to zero (timeMarkSent, timeMarkEdge, calibTtagValid, numMeas)
std::vector< uint32_t > data
data (see graphic below)
uint32_t timeTag
Time tag of measurement generated by external sensor.
Repeated data in this message.
uint32_t sTtag
sensor time tag
uint32_t data
data. Same as in UBX-ESF-MEAS (see graphic below)
std::array< uint8_t, 4 > reserved1
Reserved.
std::vector< UbxEsfRawData > data
Repeated block.
Repeated data in this message.
std::bitset< 1UL *8UL > faults
Sensor faults (see graphic below)
std::bitset< 1UL *8UL > sensStatus2
Sensor status, part 2 (seegraphic below)
uint8_t freq
Observation frequency [Hz].
std::bitset< 1UL *8UL > sensStatus1
Sensor status, part 1 (seegraphic below)
External Sensor Fusion (ESF) status information.
std::array< uint8_t, 7 > reserved1
std::array< uint8_t, 2 > reserved2
Reserved.
std::vector< UbxEsfStatusSensor > sensors
Repeated block.
uint32_t iTOW
GPS time of week of the navigation epoch. See the description of iTOW for details....
uint8_t version
Message version (2 for this version)
uint8_t numSens
Number of sensors.
uint32_t accHeading
Vehicle heading accuracy [deg * 1e-5] (if null, heading angle is not available).
int32_t roll
Vehicle roll [deg * 1e-5].
uint32_t accRoll
Vehicle roll accuracy [deg * 1e-5] (if null, roll angle is not available).
uint32_t iTOW
GPS time of week of the navigation epoch [ms]. See the description of iTOW for details.
int32_t pitch
Vehicle pitch [deg * 1e-5].
uint32_t accPitch
Vehicle pitch accuracy [deg * 1e-5] (if null, pitch angle is not available).
std::array< uint8_t, 3 > reserved1
Reserved.
uint8_t version
Message version (0 for this version)
int32_t heading
Vehicle heading [deg * 1e-5].
Position Solution in ECEF.
int32_t ecefY
ECEF Y coordinate [cm].
uint32_t iTOW
GPS time of week of the navigation epoch [ms]. See the description of iTOW for details.
uint32_t pAcc
Position Accuracy Estimate [cm].
int32_t ecefX
ECEF X coordinate [cm].
int32_t ecefZ
ECEF Z coordinate [cm].
Geodetic Position Solution.
uint32_t iTOW
GPS time of week of the navigation epoch [ms]. See the description of iTOW for details.
int32_t hMSL
Height above mean sea level [mm].
int32_t lat
Latitude [deg * 1e-7].
uint32_t hAcc
Horizontal accuracy estimate [mm].
int32_t lon
Longitude [deg * 1e-7].
int32_t height
Height above ellipsoid [mm].
uint32_t vAcc
Vertical accuracy estimate [mm].
Velocity Solution in NED.
uint32_t sAcc
Speed accuracy Estimation [cm/s].
int32_t velD
Down velocity component [cm/s].
uint32_t speed
Speed (3-D)
uint32_t cAcc
Course / Heading accuracy estimation [deg * 1e-5].
int32_t heading
Heading of motion 2-D [deg * 1e-5].
uint32_t gSpeed
Ground speed (2-D)
int32_t velN
North velocity component [cm/s].
int32_t velE
East velocity component [cm/s].
uint32_t iTOW
GPS time of week of the navigation epoch [ms]. See the description of iTOW for details.
Repeated data in this message.
bool prValid() const
Pseudorange valid.
uint16_t locktime
Carrier phase locktime counter [ms] (maximum 64500ms)
uint8_t cno
Carrier-to-noise density ratio (signal strength) [dB-Hz].
std::bitset< 1UL *8UL > doStdev
Estimated Doppler measurement standard deviation. [Hz * 0.002*2^n] (see graphic below)
float doMes
Doppler measurement (positive sign for approaching satellites) [Hz].
std::bitset< 1UL *8UL > cpStdev
Estimated carrier phase measurement standard deviation [cycles * 0.004] (note a raw value of 0x0F ind...
std::bitset< 1UL *8UL > trkStat
Tracking status bitfield (see graphic below)
uint8_t reserved2
Reserved.
bool cpValid() const
Carrier phase valid.
uint8_t gnssId
GNSS identifier (see Satellite Numbering for a list of identifiers)
bool halfCycValid() const
Half cycle valid.
uint8_t svId
Satellite identifier (see Satellite Numbering)
uint8_t sigId
New style signal identifier (see Signal Identifiers).(not supported in protocol versions less than 27...
bool subHalfSubtractedFromPhase() const
Half cycle subtracted from phase.
std::bitset< 1UL *8UL > prStdev
Estimated pseudorange measurement standard deviation [m * 0.01*2^n] (see graphic below)
uint8_t freqId
Only used for GLONASS: This is the frequency slot + 7 (range from 0 to 13)
Multi-GNSS Raw Measurement Data.
uint8_t version
Message version (0x01 for this version).
uint8_t numMeas
Number of measurements to follow.
std::vector< UbxRxmRawxData > data
Repeated block.
std::bitset< 1UL *8UL > recStat
Receiver tracking status bitfield (see graphic below)
std::array< uint8_t, 2 > reserved1
Reserved.
Broadcast Navigation Data Subframe.
uint8_t svId
Satellite identifier (see Satellite Numbering)
std::vector< uint32_t > dwrd
The data words.
uint8_t version
Message version (0x01 for this version)
uint8_t freqId
Only used for GLONASS: This is the frequency slot + 7 (range from 0 to 13)
uint8_t numWords
The number of data words contained in this message (0..16)
uint8_t sigId
Signal identifier.
uint8_t gnssId
GNSS identifier (see Satellite Numbering)
uint8_t reserved0
Reserved.
uint8_t chn
The tracking channel number the message was received on.