| Line | Branch | Exec | Source |
|---|---|---|---|
| 1 | // This file is part of INSTINCT, the INS Toolkit for Integrated | ||
| 2 | // Navigation Concepts and Training by the Institute of Navigation of | ||
| 3 | // the University of Stuttgart, Germany. | ||
| 4 | // | ||
| 5 | // This Source Code Form is subject to the terms of the Mozilla Public | ||
| 6 | // License, v. 2.0. If a copy of the MPL was not distributed with this | ||
| 7 | // file, You can obtain one at https://mozilla.org/MPL/2.0/. | ||
| 8 | |||
| 9 | /// @file UbloxTypes.hpp | ||
| 10 | /// @brief Type Definitions for Ublox messages | ||
| 11 | /// @author T. Topp (topp@ins.uni-stuttgart.de) | ||
| 12 | /// @date 2020-05-19 | ||
| 13 | |||
| 14 | #pragma once | ||
| 15 | |||
| 16 | #include <string> | ||
| 17 | #include <array> | ||
| 18 | #include <optional> | ||
| 19 | #include <bitset> | ||
| 20 | #include <vector> | ||
| 21 | #include <cstdint> | ||
| 22 | #include <fmt/ostream.h> | ||
| 23 | |||
| 24 | #include "Navigation/GNSS/Core/SatelliteIdentifier.hpp" | ||
| 25 | |||
| 26 | namespace NAV::vendor::ublox | ||
| 27 | { | ||
| 28 | /// @brief Error detection modes available | ||
| 29 | enum ErrorDetectionMode : uint8_t | ||
| 30 | { | ||
| 31 | ERRORDETECTIONMODE_NONE, ///< No error detection is used | ||
| 32 | ERRORDETECTIONMODE_CHECKSUM, ///< 16-bit checksum is used | ||
| 33 | }; | ||
| 34 | |||
| 35 | /// @brief Enumeration of the available asynchronous ASCII talker IDs. | ||
| 36 | enum NmeaTalkerID : uint8_t | ||
| 37 | { | ||
| 38 | NMEA_TALKER_ID_OFF = 0, ///< Asynchronous output is turned off. | ||
| 39 | NMEA_TALKER_ID_GP = 1, ///< GPS, SBAS, QZSS | ||
| 40 | NMEA_TALKER_ID_GL = 2, ///< GLONASS | ||
| 41 | NMEA_TALKER_ID_GA = 3, ///< Galileo | ||
| 42 | NMEA_TALKER_ID_GB = 4, ///< BeiDou | ||
| 43 | NMEA_TALKER_ID_GN = 5 ///< Any combination of GNSS | ||
| 44 | }; | ||
| 45 | |||
| 46 | /// @brief NMEA Message Type. | ||
| 47 | enum NmeaMessageClass : uint8_t | ||
| 48 | { | ||
| 49 | NMEA_MSG_CLASS_STANDARD = 0xF0, ///< Standard Messages | ||
| 50 | NMEA_MSG_CLASS_PUBX = 0xF1 ///< PUBX Messages | ||
| 51 | }; | ||
| 52 | |||
| 53 | /// @brief NMEA Standard Messages. | ||
| 54 | /// Class ID = 0xF0 | ||
| 55 | enum NmeaStandardMessages : uint8_t | ||
| 56 | { | ||
| 57 | NMEA_STANDARD_MSG_DTM = 0x0A, ///< Datum Reference | ||
| 58 | NMEA_STANDARD_MSG_GBQ = 0x44, ///< Poll a standard message (if the current Talker ID is GB) | ||
| 59 | NMEA_STANDARD_MSG_GBS = 0x09, ///< GNSS Satellite Fault Detection | ||
| 60 | NMEA_STANDARD_MSG_GGA = 0x00, ///< Global positioning system fix data | ||
| 61 | NMEA_STANDARD_MSG_GLL = 0x01, ///< Latitude and longitude, with time of position fix and status | ||
| 62 | NMEA_STANDARD_MSG_GLQ = 0x43, ///< Poll a standard message (if the current Talker ID is GL) | ||
| 63 | NMEA_STANDARD_MSG_GNQ = 0x42, ///< Poll a standard message (if the current Talker ID is GN) | ||
| 64 | NMEA_STANDARD_MSG_GNS = 0x0D, ///< GNSS fix data | ||
| 65 | NMEA_STANDARD_MSG_GPQ = 0x40, ///< Poll a standard message (if the current Talker ID is GP) | ||
| 66 | NMEA_STANDARD_MSG_GRS = 0x06, ///< GNSS Range Residuals | ||
| 67 | NMEA_STANDARD_MSG_GSA = 0x02, ///< GNSS DOP and Active Satellites | ||
| 68 | NMEA_STANDARD_MSG_GST = 0x07, ///< GNSS Pseudo Range Error Statistics | ||
| 69 | NMEA_STANDARD_MSG_GSV = 0x03, ///< GNSS Satellites in View | ||
| 70 | NMEA_STANDARD_MSG_RMC = 0x04, ///< Recommended Minimum data | ||
| 71 | NMEA_STANDARD_MSG_TXT = 0x41, ///< Text Transmission | ||
| 72 | NMEA_STANDARD_MSG_VLW = 0x0F, ///< Dual ground/water distance | ||
| 73 | NMEA_STANDARD_MSG_VTG = 0x05, ///< Course over ground and Ground speed | ||
| 74 | NMEA_STANDARD_MSG_ZDA = 0x08 ///< Time and Date | ||
| 75 | }; | ||
| 76 | |||
| 77 | /// @brief NMEA PUBX Messages. | ||
| 78 | /// Class ID = 0xF1 | ||
| 79 | enum NmeaPubxMessages : uint8_t | ||
| 80 | { | ||
| 81 | NMEA_PUBX_MSG_CONFIG = 0x41, ///< Set Protocols and Baudrate | ||
| 82 | NMEA_PUBX_MSG_POSITION = 0x00, ///< Lat/Long Position Data | ||
| 83 | NMEA_PUBX_MSG_RATE = 0x40, ///< Set NMEA message output rate | ||
| 84 | NMEA_PUBX_MSG_SVSTATUS = 0x03, ///< Satellite Status | ||
| 85 | NMEA_PUBX_MSG_TIME = 0x04 ///< Time of Day and Clock Information | ||
| 86 | }; | ||
| 87 | |||
| 88 | /// @brief The available UBX Class IDs | ||
| 89 | enum UbxClass : uint8_t | ||
| 90 | { | ||
| 91 | UBX_CLASS_NONE = 0x00, ///< No Message Class specified | ||
| 92 | UBX_CLASS_NAV = 0x01, ///< Navigation Results Messages: Position, Speed, Time, Acceleration, Heading, DOP, SVs used | ||
| 93 | UBX_CLASS_RXM = 0x02, ///< Receiver Manager Messages: Satellite Status, RTC Status | ||
| 94 | UBX_CLASS_INF = 0x04, ///< Information Messages: Printf-Style Messages, with IDs such as Error, Warning, Notice | ||
| 95 | UBX_CLASS_ACK = 0x05, ///< Ack/Nak Messages: Acknowledge or Reject messages to UBX-CFG input messages | ||
| 96 | UBX_CLASS_CFG = 0x06, ///< Configuration Input Messages: Configure the receiver | ||
| 97 | UBX_CLASS_UPD = 0x09, ///< Firmware Update Messages: Memory/Flash erase/write, Reboot, Flash identification, etc. | ||
| 98 | UBX_CLASS_MON = 0x0A, ///< Monitoring Messages: Communication Status, CPU Load, Stack Usage, Task Status | ||
| 99 | UBX_CLASS_AID [[deprecated]] = 0x0B, ///< AssistNow Aiding Messages: Ephemeris, Almanac, other A-GPS data input | ||
| 100 | UBX_CLASS_TIM = 0x0D, ///< Timing Messages: Time Pulse Output, Time Mark Results | ||
| 101 | UBX_CLASS_ESF = 0x10, ///< External Sensor Fusion Messages: External Sensor Measurements and Status Information | ||
| 102 | UBX_CLASS_MGA = 0x13, ///< Multiple GNSS Assistance Messages: Assistance data for various GNSS | ||
| 103 | UBX_CLASS_LOG = 0x21, ///< Logging Messages: Log creation, deletion, info and retrieval | ||
| 104 | UBX_CLASS_SEC = 0x27, ///< Security Feature Messages | ||
| 105 | UBX_CLASS_HNR = 0x28 ///< High Rate Navigation Results Messages: High rate time, position, speed, heading | ||
| 106 | }; | ||
| 107 | |||
| 108 | /// @brief The available ACK Messages | ||
| 109 | enum UbxAckMessages : uint8_t | ||
| 110 | { | ||
| 111 | /// Message Acknowledged (Length = 2; Type = Output) | ||
| 112 | UBX_ACK_ACK = 0x01, | ||
| 113 | /// Message Not-Acknowledged (Length = 2; Type = Output) | ||
| 114 | UBX_ACK_NAK = 0x00 | ||
| 115 | }; | ||
| 116 | |||
| 117 | /// @brief Message Acknowledged | ||
| 118 | /// | ||
| 119 | /// Output upon processing of an input message. ACK Message is sent as soon as possible but at least within one second. | ||
| 120 | struct UbxAckAck | ||
| 121 | { | ||
| 122 | uint8_t clsID = 0; ///< Class ID of the Acknowledged Message | ||
| 123 | uint8_t msgID = 0; ///< Message ID of the Acknowledged Message | ||
| 124 | }; | ||
| 125 | |||
| 126 | /// @brief Message Not-Acknowledged | ||
| 127 | /// | ||
| 128 | /// Output upon processing of an input message. NAK Message is sent as soon as possible but at least within one second. | ||
| 129 | struct UbxAckNak | ||
| 130 | { | ||
| 131 | uint8_t clsID = 0; ///< Class ID of the Not-Acknowledged Message | ||
| 132 | uint8_t msgID = 0; ///< Message ID of the Not-Acknowledged Message | ||
| 133 | }; | ||
| 134 | |||
| 135 | /// @brief The available CFG Messages | ||
| 136 | enum UbxCfgMessages : uint8_t | ||
| 137 | { | ||
| 138 | /// Antenna Control Settings (Length = 4; Type = Get/Set) | ||
| 139 | UBX_CFG_ANT = 0x13, | ||
| 140 | /// Get/Set data batching configuration (Length = 8; Type = Get/Set) | ||
| 141 | UBX_CFG_BATCH = 0x93, | ||
| 142 | /// Clear, Save and Load configurations (Length = (12) or (13); Type = Command) | ||
| 143 | UBX_CFG_CFG = 0x09, | ||
| 144 | /// - Set User-defined Datum. (Length = 44; Type = Set) | ||
| 145 | /// - The currently defined Datum (Length = 52; Type = Get) | ||
| 146 | UBX_CFG_DAT = 0x06, | ||
| 147 | /// DGNSS configuration (Length = 4; Type = Get/Set) | ||
| 148 | UBX_CFG_DGNSS = 0x70, | ||
| 149 | /// Disciplined oscillator configuration (Length = 4 + 32*numOsc; Type = Get/Set) | ||
| 150 | UBX_CFG_DOSC = 0x61, | ||
| 151 | /// External synchronization source configuration (Length = 4 + 36*numSources; Type = Get/Set) | ||
| 152 | UBX_CFG_ESRC = 0x60, | ||
| 153 | /// Geofencing configuration (Length = 8 + 12*numFences; Type = Get/Set) | ||
| 154 | UBX_CFG_GEOFENCE = 0x69, | ||
| 155 | /// GNSS system configuration (Length = 4 + 8*numConfigBlocks; Type = Get/Set) | ||
| 156 | UBX_CFG_GNSS = 0x3E, | ||
| 157 | /// High Navigation Rate Settings (Length = 4; Type = Get/Set) | ||
| 158 | UBX_CFG_HNR = 0x5C, | ||
| 159 | /// - Poll configuration for one protocol (Length = 1; Type = Poll Request) | ||
| 160 | /// - Information message configuration (Length = 0 + 10*N; Type = Get/Set) | ||
| 161 | UBX_CFG_INF = 0x02, | ||
| 162 | /// Jamming/Interference Monitor configuration (Length = 8; Type = Get/Set) | ||
| 163 | UBX_CFG_ITFM = 0x39, | ||
| 164 | /// Data Logger Configuration (Length = 12; Type = Get/Set) | ||
| 165 | UBX_CFG_LOGFILTER = 0x47, | ||
| 166 | /// - Poll a message configuration (Length = 2; Type = Poll Request) | ||
| 167 | /// - Set Message Rate(s) (Length = 8; Type = Get/Set) | ||
| 168 | /// - Set Message Rate (Length = 3; Type = Get/Set) | ||
| 169 | UBX_CFG_MSG = 0x01, | ||
| 170 | /// Navigation Engine Settings (Length = 36; Type = Get/Set) | ||
| 171 | UBX_CFG_NAV5 = 0x24, | ||
| 172 | /// - Navigation Engine Expert Settings (Length = 40; Type = Get/Set) | ||
| 173 | /// - Navigation Engine Expert Settings (Length = 40; Type = Get/Set) | ||
| 174 | /// - Navigation Engine Expert Settings (Length = 44; Type = Get/Set) | ||
| 175 | UBX_CFG_NAVX5 = 0x23, | ||
| 176 | /// - NMEA protocol configuration (deprecated) (Length = 4; Type = Get/Set) | ||
| 177 | /// - NMEA protocol configuration V0 (deprecated) (Length = 12; Type = Get/Set) | ||
| 178 | /// - Extended NMEA protocol configuration V1 (Length = 20; Type = Get/Set) | ||
| 179 | UBX_CFG_NMEA = 0x17, | ||
| 180 | /// Odometer, Low-speed COG Engine Settings (Length = 20; Type = Get/Set) | ||
| 181 | UBX_CFG_ODO = 0x1E, | ||
| 182 | /// - Extended Power Management configuration (Length = 44; Type = Get/Set) | ||
| 183 | /// - Extended Power Management configuration (Length = 48; Type = Get/Set) | ||
| 184 | /// - Extended Power Management configuration (Length = 48; Type = Get/Set) | ||
| 185 | UBX_CFG_PM2 = 0x3B, | ||
| 186 | /// Power Mode Setup (Length = 8; Type = Get/Set) | ||
| 187 | UBX_CFG_PMS = 0x86, | ||
| 188 | /// - Polls the configuration for one I/O Port (Length = 1; Type = Poll Request) | ||
| 189 | /// - Port Configuration for UART (Length = 20; Type = Get/Set) | ||
| 190 | /// - Port Configuration for USB Port (Length = 20; Type = Get/Set) | ||
| 191 | /// - Port Configuration for SPI Port (Length = 20; Type = Get/Set) | ||
| 192 | /// - Port Configuration for DDC Port (Length = 20; Type = Get/Set) | ||
| 193 | UBX_CFG_PRT = 0x00, | ||
| 194 | /// Put receiver in a defined power state (Length = 8; Type = Set) | ||
| 195 | UBX_CFG_PWR = 0x57, | ||
| 196 | /// Navigation/Measurement Rate Settings (Length = 6; Type = Get/Set) | ||
| 197 | UBX_CFG_RATE = 0x08, | ||
| 198 | /// Contents of Remote Inventory (Length = 1 + 1*N; Type = Get/Set) | ||
| 199 | UBX_CFG_RINV = 0x34, | ||
| 200 | /// Reset Receiver / Clear Backup Data Structures (Length = 4; Type = Command) | ||
| 201 | UBX_CFG_RST = 0x04, | ||
| 202 | /// - RXM configuration (Length = 2; Type = Get/Set) | ||
| 203 | /// - RXM configuration (Length = 2; Type = Get/Set) | ||
| 204 | UBX_CFG_RXM = 0x11, | ||
| 205 | /// SBAS Configuration (Length = 8; Type = Get/Set) | ||
| 206 | UBX_CFG_SBAS = 0x16, | ||
| 207 | /// SLAS Configuration (Length = 4; Type = Get/Set) | ||
| 208 | UBX_CFG_SLAS = 0x8D, | ||
| 209 | /// Synchronization manager configuration (Length = 20; Type = Get/Set) | ||
| 210 | UBX_CFG_SMGR = 0x62, | ||
| 211 | /// Time Mode Settings 2 (Length = 28; Type = Get/Set) | ||
| 212 | UBX_CFG_TMODE2 = 0x3D, | ||
| 213 | /// Time Mode Settings 3 (Length = 40; Type = Get/Set) | ||
| 214 | UBX_CFG_TMODE3 = 0x71, | ||
| 215 | /// - Poll Time Pulse Parameters for Time Pulse 0 (Length = 0; Type = Poll Request) | ||
| 216 | /// - Poll Time Pulse Parameters (Length = 1; Type = Poll Request) | ||
| 217 | /// - Time Pulse Parameters (Length = 32; Type = Get/Set) | ||
| 218 | /// - Time Pulse Parameters (Length = 32; Type = Get/Se | ||
| 219 | UBX_CFG_TP5 = 0x31, | ||
| 220 | /// TX buffer time slots configuration (Length = 16; Type = Set) | ||
| 221 | UBX_CFG_TXSLOT = 0x53, | ||
| 222 | /// USB Configuration (Length = 108; Type = Get/Set) | ||
| 223 | UBX_CFG_USB = 0x1B, | ||
| 224 | }; | ||
| 225 | |||
| 226 | /// @brief The available ESF Messages | ||
| 227 | enum UbxEsfMessages : uint8_t | ||
| 228 | { | ||
| 229 | /// Vehicle dynamics information (Length = 36; Type = Periodic/Polled) | ||
| 230 | UBX_ESF_INS = 0x15, | ||
| 231 | /// External Sensor Fusion Measurements (Length = (8 + 4*numMeas) or (12 + 4*numMeas); Type = Input/Output) | ||
| 232 | UBX_ESF_MEAS = 0x02, | ||
| 233 | /// Raw sensor measurements (Length = 4 + 8*N; Type = Output) | ||
| 234 | UBX_ESF_RAW = 0x03, | ||
| 235 | /// External Sensor Fusion (ESF) status information (Length = 16 + 4*numSens; Type = Periodic/Polled) | ||
| 236 | UBX_ESF_STATUS = 0x10, | ||
| 237 | }; | ||
| 238 | |||
| 239 | /// @brief Vehicle dynamics information | ||
| 240 | /// | ||
| 241 | /// This message outputs information about the vehicle dynamics. | ||
| 242 | /// For ADR products (in protocol versions less than 19.2), the output dynamics | ||
| 243 | /// information (angular rates and accelerations) is expressed with respect to the | ||
| 244 | /// vehicle-frame. More information can be found in the ADR Navigation Output | ||
| 245 | /// section. | ||
| 246 | /// For ADR products, the output dynamics information (angular rates and | ||
| 247 | /// accelerations) is expressed with respect to the vehicle-frame. More information | ||
| 248 | /// can be found in the ADR Navigation Output section. | ||
| 249 | /// For UDR products, the output dynamics information (angular rates and | ||
| 250 | /// accelerations) are expressed with respect to the body-frame. More information | ||
| 251 | /// can be found in the UDR Navigation Output section. | ||
| 252 | struct UbxEsfIns | ||
| 253 | { | ||
| 254 | std::bitset<4UL * 8UL> bitfield0; ///< Bitfield (zAccelValid, yAccelValid, xAccelValid, zAngRateValid, yAngRateValid, xAngRateValid, version) | ||
| 255 | std::array<uint8_t, 4> reserved1{}; ///< Reserved | ||
| 256 | uint32_t iTOW = 0; ///< GPS time of week of the navigation epoch. See the description of iTOW for details. [ms] | ||
| 257 | int32_t xAngRate = 0; ///< Compensated x-axis angular rate. [deg/s * 1e-3] | ||
| 258 | int32_t yAngRate = 0; ///< Compensated y-axis angular rate. [deg/s * 1e-3] | ||
| 259 | int32_t zAngRate = 0; ///< Compensated z-axis angular rate. [deg/s * 1e-3] | ||
| 260 | int32_t xAccel = 0; ///< Compensated x-axis acceleration (gravity-free). [m/s^2 * 1e-2] | ||
| 261 | int32_t yAccel = 0; ///< Compensated y-axis acceleration (gravity-free). [m/s^2 * 1e-2] | ||
| 262 | int32_t zAccel = 0; ///< Compensated z-axis acceleration (gravity-free). [m/s^2 * 1e-2] | ||
| 263 | }; | ||
| 264 | |||
| 265 | /// @brief External Sensor Fusion Measurements | ||
| 266 | /// | ||
| 267 | /// Possible data types for the data field are described in the ESF Measurement Data section. | ||
| 268 | struct UbxEsfMeas | ||
| 269 | { | ||
| 270 | uint32_t timeTag = 0; ///< Time tag of measurement generated by external sensor | ||
| 271 | std::bitset<2UL * 8UL> flags; ///< Flags. Set all unused bits to zero (timeMarkSent, timeMarkEdge, calibTtagValid, numMeas) | ||
| 272 | uint16_t id = 0; ///< Identification number of data provider | ||
| 273 | std::vector<uint32_t> data; ///< data (see graphic below) | ||
| 274 | std::optional<std::vector<uint32_t>> calibTtag; ///< Receiver local time calibrated. This field must not be supplied when calibTtagValid is set to 0. [ms] | ||
| 275 | }; | ||
| 276 | |||
| 277 | /// @brief Raw sensor measurements | ||
| 278 | /// | ||
| 279 | /// The message contains measurements from the active inertial sensors | ||
| 280 | /// connected to the GNSS chip. Possible data types for the data field are | ||
| 281 | /// accelerometer, gyroscope and temperature readings as described in the ESF | ||
| 282 | /// Measurement Data section. | ||
| 283 | /// Note that the rate selected in UBX-CFG-MSG is not respected. If a positive rate is | ||
| 284 | /// selected then all raw measurements will be output. | ||
| 285 | /// See also Raw Sensor Measurement Data. | ||
| 286 | struct UbxEsfRaw | ||
| 287 | { | ||
| 288 | /// @brief Repeated data in this message | ||
| 289 | struct UbxEsfRawData | ||
| 290 | { | ||
| 291 | uint32_t data = 0; ///< data. Same as in UBX-ESF-MEAS (see graphic below) | ||
| 292 | uint32_t sTtag = 0; ///< sensor time tag | ||
| 293 | }; | ||
| 294 | |||
| 295 | std::array<uint8_t, 4> reserved1{}; ///< Reserved | ||
| 296 | std::vector<UbxEsfRawData> data; ///< Repeated block | ||
| 297 | }; | ||
| 298 | |||
| 299 | /// @brief External Sensor Fusion (ESF) status information | ||
| 300 | struct UbxEsfStatus | ||
| 301 | { | ||
| 302 | /// @brief Repeated data in this message | ||
| 303 | struct UbxEsfStatusSensor | ||
| 304 | { | ||
| 305 | std::bitset<1UL * 8UL> sensStatus1; ///< Sensor status, part 1 (seegraphic below) | ||
| 306 | std::bitset<1UL * 8UL> sensStatus2; ///< Sensor status, part 2 (seegraphic below) | ||
| 307 | uint8_t freq = 0; ///< Observation frequency [Hz] | ||
| 308 | std::bitset<1UL * 8UL> faults; ///< Sensor faults (see graphic below) | ||
| 309 | }; | ||
| 310 | |||
| 311 | uint32_t iTOW = 0; ///< GPS time of week of the navigation epoch. See the description of iTOW for details. [ms] | ||
| 312 | uint8_t version = 0; ///< Message version (2 for this version) | ||
| 313 | std::array<uint8_t, 7> reserved1{}; ///< Reserved | ||
| 314 | /// Fusion mode:0: Initialization mode: receiver is initializing some unknown values required for doing sensor fusion | ||
| 315 | /// 1: Fusion mode: GNSS and sensor data are used for navigation solution computation | ||
| 316 | /// 2: Suspended fusion mode: sensor fusion is temporarily disabled due to e.g. invalid sensor data or detected ferry | ||
| 317 | /// 3: Disabled fusion mode: sensor fusion is permanently disabled until receiver reset due e.g. to sensor error More details can be found in the Fusion Modes section. | ||
| 318 | uint8_t fusionMode = 0; | ||
| 319 | std::array<uint8_t, 2> reserved2{}; ///< Reserved | ||
| 320 | uint8_t numSens = 0; ///< Number of sensors | ||
| 321 | std::vector<UbxEsfStatusSensor> sensors; ///< Repeated block | ||
| 322 | }; | ||
| 323 | |||
| 324 | /// @brief The available HNR Messages | ||
| 325 | enum UbxHnrMessages : uint8_t | ||
| 326 | { | ||
| 327 | /// Vehicle dynamics information (Length = 36; Type = Periodic/Polled) | ||
| 328 | UBX_HNR_INS = 0x02, | ||
| 329 | /// High Rate Output of PVT Solution (Length = 72; Type = Periodic/Polled) | ||
| 330 | UBX_HNR_PVT = 0x00, | ||
| 331 | }; | ||
| 332 | |||
| 333 | /// @brief The available INF Messages | ||
| 334 | enum UbxInfMessages : uint8_t | ||
| 335 | { | ||
| 336 | /// ASCII output with debug contents (Length = 0 + 1*N; Type = Output) | ||
| 337 | UBX_INF_DEBUG = 0x04, | ||
| 338 | /// ASCII output with error contents (Length = 0 + 1*N; Type = Output) | ||
| 339 | UBX_INF_ERROR = 0x00, | ||
| 340 | /// ASCII output with informational contents (Length = 0 + 1*N; Type = Output) | ||
| 341 | UBX_INF_NOTICE = 0x02, | ||
| 342 | /// ASCII output with test contents (Length = 0 + 1*N; Type = Output) | ||
| 343 | UBX_INF_TEST = 0x03, | ||
| 344 | /// ASCII output with warning contents (Length = 0 + 1*N; Type = Output) | ||
| 345 | UBX_INF_WARNING = 0x01, | ||
| 346 | }; | ||
| 347 | |||
| 348 | /// @brief The available LOG Messages | ||
| 349 | enum UbxLogMessages : uint8_t | ||
| 350 | { | ||
| 351 | /// Batched data (Length = 100; Type = Polled) | ||
| 352 | UBX_LOG_BATCH = 0x11, | ||
| 353 | /// Create Log File (Length = 8; Type = Command) | ||
| 354 | UBX_LOG_CREATE = 0x07, | ||
| 355 | /// Erase Logged Data (Length = 0; Type = Command) | ||
| 356 | UBX_LOG_ERASE = 0x03, | ||
| 357 | /// - Find index of a log entry based on a given time (Length = 12; Type = Input) | ||
| 358 | /// - Response to FINDTIME request (Length = 8; Type = Output) | ||
| 359 | UBX_LOG_FINDTIME = 0x0E, | ||
| 360 | /// - Poll for log information (Length = 0; Type = Poll Request) | ||
| 361 | /// - Log information (Length = 48; Type = Output) | ||
| 362 | UBX_LOG_INFO = 0x08, | ||
| 363 | /// Request batch data (Length = 4; Type = Command) | ||
| 364 | UBX_LOG_RETRIEVEBATCH = 0x10, | ||
| 365 | /// Odometer log entry (Length = 32; Type = Output) | ||
| 366 | UBX_LOG_RETRIEVEPOSEXTRA = 0x0F, | ||
| 367 | /// Position fix log entry (Length = 40; Type = Output) | ||
| 368 | UBX_LOG_RETRIEVEPOS = 0x0B, | ||
| 369 | /// Byte string log entry (Length = 16 + 1*byteCount; Type = ) | ||
| 370 | UBX_LOG_RETRIEVESTRING = 0x0D, | ||
| 371 | /// Request log data (Length = 12; Type = Command) | ||
| 372 | UBX_LOG_RETRIEVE = 0x09, | ||
| 373 | /// Store arbitrary string in on-board flash (Length = 0 + 1*N; Type = Command) | ||
| 374 | UBX_LOG_STRING = 0x04, | ||
| 375 | }; | ||
| 376 | |||
| 377 | /// @brief The available MGA Messages | ||
| 378 | enum UbxMgaMessages : uint8_t | ||
| 379 | { | ||
| 380 | /// Multiple GNSS Acknowledge message (Length = 8; Type = Output) | ||
| 381 | UBX_MGA_ACK_DATA0 = 0x60, | ||
| 382 | /// Multiple GNSS AssistNow Offline Assistance (Length = 76; Type = Input) | ||
| 383 | UBX_MGA_ANO = 0x20, | ||
| 384 | /// BDS Ephemeris Assistance (Length = 88; Type = Input) | ||
| 385 | UBX_MGA_BDS_EPH = 0x03, | ||
| 386 | /// BDS Almanac Assistance (Length = 40; Type = Input) | ||
| 387 | UBX_MGA_BDS_ALM = 0x03, | ||
| 388 | /// BDS Health Assistance (Length = 68; Type = Input) | ||
| 389 | UBX_MGA_BDS_HEALTH = 0x03, | ||
| 390 | /// BDS UTC Assistance (Length = 20; Type = Input) | ||
| 391 | UBX_MGA_BDS_UTC = 0x03, | ||
| 392 | /// BDS Ionospheric Assistance (Length = 16; Type = Input) | ||
| 393 | UBX_MGA_BDS_IONO = 0x03, | ||
| 394 | /// - Poll the Navigation Database (Length = 0; Type = Poll Request) | ||
| 395 | /// - Navigation Database Dump Entry (Length = 12 + 1*N; Type = Input/Output) | ||
| 396 | UBX_MGA_DBD = 0x80, | ||
| 397 | /// Transfer MGA-ANO data block to flash (Length = 6 + 1*size; Type = Input) | ||
| 398 | UBX_MGA_FLASH_DATA = 0x21, | ||
| 399 | /// Finish flashing MGA-ANO data (Length = 2; Type = Input) | ||
| 400 | UBX_MGA_FLASH_STOP = 0x21, | ||
| 401 | /// Acknowledge last FLASH-DATA or -STOP (Length = 6; Type = Output) | ||
| 402 | UBX_MGA_FLASH_ACK = 0x21, | ||
| 403 | /// Galileo Ephemeris Assistance (Length = 76; Type = Input) | ||
| 404 | UBX_MGA_GAL_EPH = 0x02, | ||
| 405 | /// Galileo Almanac Assistance (Length = 32; Type = Input) | ||
| 406 | UBX_MGA_GAL_ALM = 0x02, | ||
| 407 | /// Galileo GPS time offset assistance (Length = 12; Type = Input) | ||
| 408 | UBX_MGA_GAL_TIMEOFFSET = 0x02, | ||
| 409 | /// Galileo UTC Assistance (Length = 20; Type = Input) | ||
| 410 | UBX_MGA_GAL_UTC = 0x02, | ||
| 411 | /// GLONASS Ephemeris Assistance (Length = 48; Type = Input) | ||
| 412 | UBX_MGA_GLO_EPH = 0x06, | ||
| 413 | /// GLONASS Almanac Assistance (Length = 36; Type = Input) | ||
| 414 | UBX_MGA_GLO_ALM = 0x06, | ||
| 415 | /// GLONASS Auxiliary Time Offset Assistance (Length = 20; Type = Input) | ||
| 416 | UBX_MGA_GLO_TIMEOFFSET = 0x06, | ||
| 417 | /// GPS Ephemeris Assistance (Length = 68; Type = Input) | ||
| 418 | UBX_MGA_GPS_EPH = 0x00, | ||
| 419 | /// GPS Almanac Assistance (Length = 36; Type = Input) | ||
| 420 | UBX_MGA_GPS_ALM = 0x00, | ||
| 421 | /// GPS Health Assistance (Length = 40; Type = Input) | ||
| 422 | UBX_MGA_GPS_HEALTH = 0x00, | ||
| 423 | /// GPS UTC Assistance (Length = 20; Type = Input) | ||
| 424 | UBX_MGA_GPS_UTC = 0x00, | ||
| 425 | /// GPS Ionosphere Assistance (Length = 16; Type = Input) | ||
| 426 | UBX_MGA_GPS_IONO = 0x00, | ||
| 427 | /// Initial Position Assistance (Length = 20; Type = Input) | ||
| 428 | UBX_MGA_INI_POS_XYZ = 0x40, | ||
| 429 | /// Initial Position Assistance (Length = 20; Type = Input) | ||
| 430 | UBX_MGA_INI_POS_LLH = 0x40, | ||
| 431 | /// Initial Time Assistance (Length = 24; Type = Input) | ||
| 432 | UBX_MGA_INI_TIME_UTC = 0x40, | ||
| 433 | /// Initial Time Assistance (Length = 24; Type = Input) | ||
| 434 | UBX_MGA_INI_TIME_GNSS = 0x40, | ||
| 435 | /// Initial Clock Drift Assistance (Length = 12; Type = Input) | ||
| 436 | UBX_MGA_INI_CLKD = 0x40, | ||
| 437 | /// Initial Frequency Assistance (Length = 12; Type = Input) | ||
| 438 | UBX_MGA_INI_FREQ = 0x40, | ||
| 439 | /// Earth Orientation Parameters Assistance (Length = 72; Type = Input) | ||
| 440 | UBX_MGA_INI_EOP = 0x40, | ||
| 441 | /// QZSS Ephemeris Assistance (Length = 68; Type = Input) | ||
| 442 | UBX_MGA_QZSS_EPH = 0x05, | ||
| 443 | /// QZSS Almanac Assistance (Length = 36; Type = Input) | ||
| 444 | UBX_MGA_QZSS_ALM = 0x05, | ||
| 445 | /// QZSS Health Assistance (Length = 12; Type = Input) | ||
| 446 | UBX_MGA_QZSS_HEALTH = 0x05, | ||
| 447 | }; | ||
| 448 | |||
| 449 | /// @brief The available MON Messages | ||
| 450 | enum UbxMonMessages : uint8_t | ||
| 451 | { | ||
| 452 | /// Data batching buffer status (Length = 12; Type = Polled) | ||
| 453 | UBX_MON_BATCH = 0x32, | ||
| 454 | /// Information message major GNSS selection (Length = 8; Type = Polled) | ||
| 455 | UBX_MON_GNSS = 0x28, | ||
| 456 | /// Extended Hardware Status (Length = 28; Type = Periodic/Polled) | ||
| 457 | UBX_MON_HW2 = 0x0B, | ||
| 458 | /// Hardware Status (Length = 60; Type = Periodic/Polled) | ||
| 459 | UBX_MON_HW = 0x09, | ||
| 460 | /// I/O Subsystem Status (Length = 0 + 20*N; Type = Periodic/Polled) | ||
| 461 | UBX_MON_IO = 0x02, | ||
| 462 | /// Message Parse and Process Status (Length = 120; Type = Periodic/Polled) | ||
| 463 | UBX_MON_MSGPP = 0x06, | ||
| 464 | /// - Poll Request for installed patches (Length = 0; Type = Poll Request) | ||
| 465 | /// - Output information about installed patches (Length = 4 + 16*nEntries; Type = Polled) | ||
| 466 | UBX_MON_PATCH = 0x27, | ||
| 467 | /// Receiver Buffer Status (Length = 24; Type = Periodic/Polled) | ||
| 468 | UBX_MON_RXBUFF = 0x07, | ||
| 469 | /// Receiver Status Information (Length = 1; Type = Output) | ||
| 470 | UBX_MON_RXR = 0x21, | ||
| 471 | /// Synchronization Manager Status (Length = 16; Type = Periodic/Polled) | ||
| 472 | UBX_MON_SMGR = 0x2E, | ||
| 473 | /// Transmitter Buffer Status (Length = 28; Type = Periodic/Polled) | ||
| 474 | UBX_MON_TXBUFF = 0x08, | ||
| 475 | /// - Poll Receiver/Software Version (Length = 0; Type = Poll Request) | ||
| 476 | /// - Receiver/Software Version (Length = 40 + 30*N; Type = Polled) | ||
| 477 | UBX_MON_VER = 0x04, | ||
| 478 | }; | ||
| 479 | |||
| 480 | /// @brief The available NAV Messages | ||
| 481 | enum UbxNavMessages : uint8_t | ||
| 482 | { | ||
| 483 | /// AssistNow Autonomous Status (Length = 16; Type = Periodic/Polled) | ||
| 484 | UBX_NAV_AOPSTATUS = 0x60, | ||
| 485 | /// Attitude Solution (Length = 32; Type = Periodic/Polled) | ||
| 486 | UBX_NAV_ATT = 0x05, | ||
| 487 | /// Clock Solution (Length = 20; Type = Periodic/Polled) | ||
| 488 | UBX_NAV_CLOCK = 0x22, | ||
| 489 | /// DGPS Data Used for NAV (Length = 16 + 12*numCh; Type = Periodic/Polled) | ||
| 490 | UBX_NAV_DGPS = 0x31, | ||
| 491 | /// Dilution of precision (Length = 18; Type = Periodic/Polled) | ||
| 492 | UBX_NAV_DOP = 0x04, | ||
| 493 | /// End Of Epoch (Length = 4; Type = Periodic) | ||
| 494 | UBX_NAV_EOE = 0x61, | ||
| 495 | /// Geofencing status (Length = 8 + 2*numFences; Type = Periodic/Polled) | ||
| 496 | UBX_NAV_GEOFENCE = 0x39, | ||
| 497 | /// High Precision Position Solution in ECEF (Length = 28; Type = Periodic/Polled) | ||
| 498 | UBX_NAV_HPPOSECEF = 0x13, | ||
| 499 | /// High Precision Geodetic Position Solution (Length = 36; Type = Periodic/Polled) | ||
| 500 | UBX_NAV_HPPOSLLH = 0x14, | ||
| 501 | /// Odometer Solution (Length = 20; Type = Periodic/Polled) | ||
| 502 | UBX_NAV_ODO = 0x09, | ||
| 503 | /// GNSS Orbit Database Info (Length = 8 + 6*numSv; Type = Periodic/Polled) | ||
| 504 | UBX_NAV_ORB = 0x34, | ||
| 505 | /// Position Solution in ECEF (Length = 20; Type = Periodic/Polled) | ||
| 506 | UBX_NAV_POSECEF = 0x01, | ||
| 507 | /// Geodetic Position Solution (Length = 28; Type = Periodic/Polled) | ||
| 508 | UBX_NAV_POSLLH = 0x02, | ||
| 509 | /// Navigation Position Velocity Time Solution (Length = 92; Type = Periodic/Polled) | ||
| 510 | UBX_NAV_PVT = 0x07, | ||
| 511 | /// Relative Positioning Information in NED frame (Length = 40; Type = Periodic/Polled) | ||
| 512 | UBX_NAV_RELPOSNED = 0x3C, | ||
| 513 | /// Reset odometer (Length = 0; Type = Command) | ||
| 514 | UBX_NAV_RESETODO = 0x10, | ||
| 515 | /// Satellite Information (Length = 8 + 12*numSvs; Type = Periodic/Polled) | ||
| 516 | UBX_NAV_SAT = 0x35, | ||
| 517 | /// SBAS Status Data (Length = 12 + 12*cnt; Type = Periodic/Polled) | ||
| 518 | UBX_NAV_SBAS = 0x32, | ||
| 519 | /// QZSS L1S SLAS Status Data (Length = 20 + 8*cnt; Type = Periodic/Polled) | ||
| 520 | UBX_NAV_SLAS = 0x42, | ||
| 521 | /// Navigation Solution Information (Length = 52; Type = Periodic/Polled) | ||
| 522 | UBX_NAV_SOL = 0x06, | ||
| 523 | /// Receiver Navigation Status (Length = 16; Type = Periodic/Polled) | ||
| 524 | UBX_NAV_STATUS = 0x03, | ||
| 525 | /// Space Vehicle Information (Length = 8 + 12*numCh; Type = Periodic/Polled) | ||
| 526 | UBX_NAV_SVINFO = 0x30, | ||
| 527 | /// Survey-in data (Length = 40; Type = Periodic/Polled) | ||
| 528 | UBX_NAV_SVIN = 0x3B, | ||
| 529 | /// BDS Time Solution (Length = 20; Type = Periodic/Polled) | ||
| 530 | UBX_NAV_TIMEBDS = 0x24, | ||
| 531 | /// Galileo Time Solution (Length = 20; Type = Periodic/Polled) | ||
| 532 | UBX_NAV_TIMEGAL = 0x25, | ||
| 533 | /// GLO Time Solution (Length = 20; Type = Periodic/Polled) | ||
| 534 | UBX_NAV_TIMEGLO = 0x23, | ||
| 535 | /// GPS Time Solution (Length = 16; Type = Periodic/Polled) | ||
| 536 | UBX_NAV_TIMEGPS = 0x20, | ||
| 537 | /// Leap second event information (Length = 24; Type = Periodic/Polled) | ||
| 538 | UBX_NAV_TIMELS = 0x26, | ||
| 539 | /// UTC Time Solution (Length = 20; Type = Periodic/Polled) | ||
| 540 | UBX_NAV_TIMEUTC = 0x21, | ||
| 541 | /// Velocity Solution in ECEF (Length = 20; Type = Periodic/Polled) | ||
| 542 | UBX_NAV_VELECEF = 0x11, | ||
| 543 | /// Velocity Solution in NED (Length = 36; Type = Periodic/Polled) | ||
| 544 | UBX_NAV_VELNED = 0x12, | ||
| 545 | }; | ||
| 546 | |||
| 547 | /// @brief Attitude Solution | ||
| 548 | /// | ||
| 549 | /// This message outputs the attitude solution as roll, pitch and heading angles. | ||
| 550 | /// More details about vehicle attitude can be found in the Vehicle Attitude Output | ||
| 551 | /// (ADR) section for ADR products. | ||
| 552 | /// More details about vehicle attitude can be found in the Vehicle Attitude Output | ||
| 553 | /// (UDR) section for UDR products. | ||
| 554 | struct UbxNavAtt | ||
| 555 | { | ||
| 556 | uint32_t iTOW = 0; ///< GPS time of week of the navigation epoch [ms]. See the description of iTOW for details. | ||
| 557 | uint8_t version = 0; ///< Message version (0 for this version) | ||
| 558 | std::array<uint8_t, 3> reserved1{}; ///< Reserved | ||
| 559 | int32_t roll = 0; ///< Vehicle roll [deg * 1e-5] | ||
| 560 | int32_t pitch = 0; ///< Vehicle pitch [deg * 1e-5] | ||
| 561 | int32_t heading = 0; ///< Vehicle heading [deg * 1e-5] | ||
| 562 | uint32_t accRoll = 0; ///< Vehicle roll accuracy [deg * 1e-5] (if null, roll angle is not available). | ||
| 563 | uint32_t accPitch = 0; ///< Vehicle pitch accuracy [deg * 1e-5] (if null, pitch angle is not available). | ||
| 564 | uint32_t accHeading = 0; ///< Vehicle heading accuracy [deg * 1e-5] (if null, heading angle is not available). | ||
| 565 | }; | ||
| 566 | |||
| 567 | /// @brief Position Solution in ECEF | ||
| 568 | /// | ||
| 569 | /// See important comments concerning validity of position given in section | ||
| 570 | /// Navigation Output Filters. | ||
| 571 | struct UbxNavPosecef | ||
| 572 | { | ||
| 573 | uint32_t iTOW = 0; ///< GPS time of week of the navigation epoch [ms]. See the description of iTOW for details. | ||
| 574 | int32_t ecefX = 0; ///< ECEF X coordinate [cm] | ||
| 575 | int32_t ecefY = 0; ///< ECEF Y coordinate [cm] | ||
| 576 | int32_t ecefZ = 0; ///< ECEF Z coordinate [cm] | ||
| 577 | uint32_t pAcc = 0; ///< Position Accuracy Estimate [cm] | ||
| 578 | }; | ||
| 579 | |||
| 580 | /// @brief Geodetic Position Solution | ||
| 581 | /// | ||
| 582 | /// See important comments concerning validity of position given in section | ||
| 583 | /// Navigation Output Filters. | ||
| 584 | /// This message outputs the Geodetic position in the currently selected ellipsoid. | ||
| 585 | /// The default is the WGS84 Ellipsoid, but can be changed with the message UBX-CFG-DAT. | ||
| 586 | struct UbxNavPosllh | ||
| 587 | { | ||
| 588 | uint32_t iTOW = 0; ///< GPS time of week of the navigation epoch [ms]. See the description of iTOW for details. | ||
| 589 | int32_t lon = 0; ///< Longitude [deg * 1e-7] | ||
| 590 | int32_t lat = 0; ///< Latitude [deg * 1e-7] | ||
| 591 | int32_t height = 0; ///< Height above ellipsoid [mm] | ||
| 592 | int32_t hMSL = 0; ///< Height above mean sea level [mm] | ||
| 593 | uint32_t hAcc = 0; ///< Horizontal accuracy estimate [mm] | ||
| 594 | uint32_t vAcc = 0; ///< Vertical accuracy estimate [mm] | ||
| 595 | }; | ||
| 596 | |||
| 597 | /// @brief Velocity Solution in NED | ||
| 598 | /// | ||
| 599 | /// See important comments concerning validity of position given in section Navigation Output Filters. | ||
| 600 | struct UbxNavVelned | ||
| 601 | { | ||
| 602 | uint32_t iTOW = 0; ///< GPS time of week of the navigation epoch [ms]. See the description of iTOW for details. | ||
| 603 | int32_t velN = 0; ///< North velocity component [cm/s] | ||
| 604 | int32_t velE = 0; ///< East velocity component [cm/s] | ||
| 605 | int32_t velD = 0; ///< Down velocity component [cm/s] | ||
| 606 | uint32_t speed = 0; ///< Speed (3-D) | ||
| 607 | uint32_t gSpeed = 0; ///< Ground speed (2-D) | ||
| 608 | int32_t heading = 0; ///< Heading of motion 2-D [deg * 1e-5] | ||
| 609 | uint32_t sAcc = 0; ///< Speed accuracy Estimation [cm/s] | ||
| 610 | uint32_t cAcc = 0; ///< Course / Heading accuracy estimation [deg * 1e-5] | ||
| 611 | }; | ||
| 612 | |||
| 613 | /// @brief The available RXM Messages | ||
| 614 | enum UbxRxmMessages : uint8_t | ||
| 615 | { | ||
| 616 | /// Indoor Messaging System Information (Length = 4 + 44*numTx; Type = Periodic/Polled) | ||
| 617 | UBX_RXM_IMES = 0x61, | ||
| 618 | /// - Satellite Measurements for RRLP (Length = 44 + 24*numSV; Type = Periodic/Polled) | ||
| 619 | UBX_RXM_MEASX = 0x14, | ||
| 620 | /// - Requests a Power Management task (Length = 8; Type = Command) | ||
| 621 | /// - Requests a Power Management task (Length = 16; Type = Command) | ||
| 622 | UBX_RXM_PMREQ = 0x41, | ||
| 623 | /// - Multi-GNSS Raw Measurement Data (Length = 16 + 32*numMeas; Type = Periodic/Polled) | ||
| 624 | /// - Multi-GNSS Raw Measurement Data (Length = 16 + 32*numMeas; Type = Periodic/Polled) | ||
| 625 | UBX_RXM_RAWX = 0x15, | ||
| 626 | /// - Galileo SAR Short-RLM report (Length = 16; Type = Output) | ||
| 627 | /// - Galileo SAR Long-RLM report (Length = 28; Type = Output) | ||
| 628 | UBX_RXM_RLM = 0x59, | ||
| 629 | /// RTCM input status (Length = 8; Type = Output) | ||
| 630 | UBX_RXM_RTCM = 0x32, | ||
| 631 | /// - Broadcast Navigation Data Subframe (Length = 8 + 4*numWords; Type = Output) | ||
| 632 | /// - Broadcast Navigation Data Subframe (Length = 8 + 4*numWords; Type = Output) | ||
| 633 | UBX_RXM_SFRBX = 0x13, | ||
| 634 | /// SV Status Info (Length = 8 + 6*numSV; Type = Periodic/Polled) | ||
| 635 | UBX_RXM_SVSI = 0x20, | ||
| 636 | }; | ||
| 637 | |||
| 638 | /// @brief Multi-GNSS Raw Measurement Data | ||
| 639 | /// | ||
| 640 | /// This message contains the information needed to be able to generate a RINEX 3 multi-GNSS observation file. | ||
| 641 | /// This message contains pseudorange, Doppler, carrier phase, phase lock and | ||
| 642 | /// signal quality information for GNSS satellites once signals have been | ||
| 643 | /// synchronized. This message supports all active GNSS. | ||
| 644 | struct UbxRxmRawx | ||
| 645 | { | ||
| 646 | /// @brief Repeated data in this message | ||
| 647 | struct UbxRxmRawxData | ||
| 648 | { | ||
| 649 | /// Pseudorange measurement [m]. | ||
| 650 | /// GLONASS inter frequency channel delays are compensated with an internal calibration table. | ||
| 651 | double prMes = 0.0; | ||
| 652 | /// Carrier phase measurement [cycles]. | ||
| 653 | /// The carrier phase initial ambiguity is initialized using an approximate | ||
| 654 | /// value to make the magnitude of the phase close to the pseudorange measurement. | ||
| 655 | /// Clock resets are applied to both phase and code measurements in accordance with the RINEX specification. | ||
| 656 | double cpMes = 0.0; | ||
| 657 | float doMes = 0.0F; ///< Doppler measurement (positive sign for approaching satellites) [Hz] | ||
| 658 | uint8_t gnssId = 0; ///< GNSS identifier (see Satellite Numbering for a list of identifiers) | ||
| 659 | uint8_t svId = 0; ///< Satellite identifier (see Satellite Numbering) | ||
| 660 | uint8_t sigId = 0; ///< New style signal identifier (see Signal Identifiers).(not supported in protocol versions less than 27) | ||
| 661 | uint8_t freqId = 0; ///< Only used for GLONASS: This is the frequency slot + 7 (range from 0 to 13) | ||
| 662 | uint16_t locktime = 0; ///< Carrier phase locktime counter [ms] (maximum 64500ms) | ||
| 663 | uint8_t cno = 0; ///< Carrier-to-noise density ratio (signal strength) [dB-Hz] | ||
| 664 | std::bitset<1UL * 8UL> prStdev; ///< Estimated pseudorange measurement standard deviation [m * 0.01*2^n] (see graphic below) | ||
| 665 | std::bitset<1UL * 8UL> cpStdev; ///< Estimated carrier phase measurement standard deviation [cycles * 0.004] (note a raw value of 0x0F indicates the value is invalid) (see graphic below) | ||
| 666 | std::bitset<1UL * 8UL> doStdev; ///< Estimated Doppler measurement standard deviation. [Hz * 0.002*2^n] (see graphic below) | ||
| 667 | std::bitset<1UL * 8UL> trkStat; ///< Tracking status bitfield (see graphic below) | ||
| 668 | uint8_t reserved2 = 0; ///< Reserved | ||
| 669 | |||
| 670 | /// @brief Pseudorange valid | ||
| 671 | 28669 | [[nodiscard]] bool prValid() const { return trkStat[0]; } | |
| 672 | |||
| 673 | /// @brief Carrier phase valid | ||
| 674 | 28669 | [[nodiscard]] bool cpValid() const { return trkStat[1]; } | |
| 675 | |||
| 676 | /// @brief Half cycle valid | ||
| 677 | 28590 | [[nodiscard]] bool halfCycValid() const { return trkStat[2]; } | |
| 678 | |||
| 679 | /// @brief Half cycle subtracted from phase | ||
| 680 | [[nodiscard]] bool subHalfSubtractedFromPhase() const { return trkStat[3]; } | ||
| 681 | }; | ||
| 682 | |||
| 683 | /// Measurement time of week in receiverblocal time approximately aligned to the GPS time system. | ||
| 684 | /// The receiver local time of week, week number and leap second information can be used to translate the | ||
| 685 | /// time to other time systems. More information about the difference in time systems can be found in RINEX 3 | ||
| 686 | /// documentation. For a receiver operating in GLONASS only mode, UTC time can be determined by subtracting the leapS field | ||
| 687 | /// from GPS time regardless of whether the GPS leap seconds are valid. [s] | ||
| 688 | double rcvTow = 0.0; | ||
| 689 | uint16_t week = 0; ///< GPS week number in receiver local time [weeks] | ||
| 690 | /// GPS leap seconds (GPS-UTC). This field represents the receiver's best knowledge of the leap seconds offset. | ||
| 691 | /// A flag is given in the recStat bitfield to indicate if the leap seconds are known. | ||
| 692 | int8_t leapS = 0; | ||
| 693 | uint8_t numMeas = 0; ///< Number of measurements to follow | ||
| 694 | std::bitset<1UL * 8UL> recStat; ///< Receiver tracking status bitfield (see graphic below) | ||
| 695 | uint8_t version = 0; ///< Message version (0x01 for this version). | ||
| 696 | std::array<uint8_t, 2> reserved1{}; ///< Reserved | ||
| 697 | std::vector<UbxRxmRawxData> data; ///< Repeated block | ||
| 698 | }; | ||
| 699 | |||
| 700 | /// @brief Broadcast Navigation Data Subframe | ||
| 701 | /// | ||
| 702 | /// This message reports a complete subframe of broadcast navigation data | ||
| 703 | /// decoded from a single signal. The number of data words reported in each | ||
| 704 | /// message depends on the nature of the signal. | ||
| 705 | /// See the section on Broadcast Navigation Data for further details. | ||
| 706 | struct UbxRxmSfrbx | ||
| 707 | { | ||
| 708 | uint8_t gnssId = 0; ///< GNSS identifier (see Satellite Numbering) | ||
| 709 | uint8_t svId = 0; ///< Satellite identifier (see Satellite Numbering) | ||
| 710 | uint8_t sigId = 0; ///< Signal identifier | ||
| 711 | uint8_t freqId = 0; ///< Only used for GLONASS: This is the frequency slot + 7 (range from 0 to 13) | ||
| 712 | uint8_t numWords = 0; ///< The number of data words contained in this message (0..16) | ||
| 713 | uint8_t chn = 0; ///< The tracking channel number the message was received on | ||
| 714 | uint8_t version = 0; ///< Message version (0x01 for this version) | ||
| 715 | uint8_t reserved0 = 0; ///< Reserved | ||
| 716 | std::vector<uint32_t> dwrd; ///< The data words | ||
| 717 | |||
| 718 | // TODO: Make this into functions | ||
| 719 | // uint8_t subFrameId = 0; ///< bit 20-22 of word 2/dwrd[1]. 3 bits subframe id (HOW = Handover Word) of GPS | ||
| 720 | // uint8_t wrdType = 0; ///< bit 3-8 of dwrd[0]. 6 bits word types of Galileo I/NAV | ||
| 721 | }; | ||
| 722 | |||
| 723 | /// @brief The available SEC Messages | ||
| 724 | enum UbxSecMessages : uint8_t | ||
| 725 | { | ||
| 726 | /// Unique Chip ID (Length = 9; Type = Output) | ||
| 727 | UBX_SEC_UNIQID = 0x03, | ||
| 728 | }; | ||
| 729 | |||
| 730 | /// @brief The available TIM Messages | ||
| 731 | enum UbxTimMessages : uint8_t | ||
| 732 | { | ||
| 733 | /// Oscillator frequency changed notification (Length = 32; Type = Periodic/Polled) | ||
| 734 | UBX_TIM_FCHG = 0x16, | ||
| 735 | /// Host oscillator control (Length = 8; Type = Input) | ||
| 736 | UBX_TIM_HOC = 0x17, | ||
| 737 | /// Source measurement (Length = 12 + 24*numMeas; Type = Input/Output) | ||
| 738 | UBX_TIM_SMEAS = 0x13, | ||
| 739 | /// Survey-in data (Length = 28; Type = Periodic/Polled) | ||
| 740 | UBX_TIM_SVIN = 0x04, | ||
| 741 | /// Time mark data (Length = 28; Type = Periodic/Polled) | ||
| 742 | UBX_TIM_TM2 = 0x03, | ||
| 743 | /// Time Pulse Time and Frequency Data (Length = 56; Type = Periodic) | ||
| 744 | UBX_TIM_TOS = 0x12, | ||
| 745 | /// Time Pulse Timedata (Length = 16; Type = Periodic/Polled) | ||
| 746 | UBX_TIM_TP = 0x01, | ||
| 747 | /// - Stop calibration (Length = 1; Type = Command) | ||
| 748 | /// - VCO calibration extended command (Length = 12; Type = Command) | ||
| 749 | /// - Results of the calibration (Length = 12; Type = Periodic/Polled) | ||
| 750 | UBX_TIM_VCOCAL = 0x15, | ||
| 751 | /// Sourced Time Verification (Length = 20; Type = Periodic/Polled) | ||
| 752 | UBX_TIM_VRFY = 0x06, | ||
| 753 | }; | ||
| 754 | |||
| 755 | /// @brief The available UPD Messages | ||
| 756 | enum UbxUpdMessages : uint8_t | ||
| 757 | { | ||
| 758 | /// - Poll Backup File Restore Status (Length = 0; Type = Poll Request) | ||
| 759 | /// - Create Backup File in Flash (Length = 4; Type = Command) | ||
| 760 | /// - Clear Backup in Flash (Length = 4; Type = command) | ||
| 761 | /// - Backup File Creation Acknowledge (Length = 8; Type = Output) | ||
| 762 | /// - System Restored from Backup (Length = 8; Type = Output) | ||
| 763 | UBX_UPD_SOS = 0x14, | ||
| 764 | }; | ||
| 765 | |||
| 766 | /// @brief Get the UBX Msg Class From String object | ||
| 767 | /// | ||
| 768 | /// @param[in] className String of the UBX Class | ||
| 769 | /// @return The UBX class | ||
| 770 | [[nodiscard]] UbxClass getMsgClassFromString(const std::string& className); | ||
| 771 | |||
| 772 | /// @brief Get the UBX Msg Id From String object | ||
| 773 | /// @param[in] msgClass The Ubx Msg Class to search in | ||
| 774 | /// @param[in] idName String of the Msg Id | ||
| 775 | /// @return The Msg Id integer | ||
| 776 | [[nodiscard]] uint8_t getMsgIdFromString(UbxClass msgClass, const std::string& idName); | ||
| 777 | |||
| 778 | /// @brief Get the UBX Msg Id From String objects | ||
| 779 | /// @param[in] className String of the UBX class | ||
| 780 | /// @param[in] idName String of the Msg Id | ||
| 781 | /// @return The Msg Id integer | ||
| 782 | [[nodiscard]] uint8_t getMsgIdFromString(const std::string& className, const std::string& idName); | ||
| 783 | |||
| 784 | /// @brief Get the a string from a UBX Msg Class | ||
| 785 | /// @param[in] msgClass The Ubx Msg Class | ||
| 786 | /// @return The Msg Class string | ||
| 787 | [[nodiscard]] std::string getStringFromMsgClass(UbxClass msgClass); | ||
| 788 | |||
| 789 | /// @brief Get the a string from a UBX Msg Id | ||
| 790 | /// @param[in] msgClass The Ubx Msg Class to search in | ||
| 791 | /// @param[in] msgId Msg Id | ||
| 792 | /// @return The Msg Id string | ||
| 793 | [[nodiscard]] std::string getStringFromMsgId(UbxClass msgClass, uint8_t msgId); | ||
| 794 | |||
| 795 | /// @brief Get the GNSS Satellite System from gnssId | ||
| 796 | /// @param gnssId Ublox gnssId | ||
| 797 | [[nodiscard]] SatelliteSystem getSatSys(uint8_t gnssId); | ||
| 798 | |||
| 799 | /// @brief Get the GNSS code from gnssId and sigId | ||
| 800 | /// @param gnssId Ublox gnssId | ||
| 801 | /// @param sigId Ublox sigId | ||
| 802 | /// @return The Code object | ||
| 803 | [[nodiscard]] Code getCode(uint8_t gnssId, uint8_t sigId); | ||
| 804 | |||
| 805 | } // namespace NAV::vendor::ublox | ||
| 806 | |||
| 807 | /// @brief Stream insertion operator overload | ||
| 808 | /// @param[in, out] os Output stream object to stream the time into | ||
| 809 | /// @param[in] obj Object to print | ||
| 810 | /// @return Returns the output stream object in order to chain stream insertions | ||
| 811 | std::ostream& operator<<(std::ostream& os, const NAV::vendor::ublox::UbxClass& obj); | ||
| 812 | |||
| 813 | #ifndef DOXYGEN_IGNORE | ||
| 814 | |||
| 815 | template<> | ||
| 816 | struct fmt::formatter<NAV::vendor::ublox::ErrorDetectionMode> : ostream_formatter | ||
| 817 | {}; | ||
| 818 | template<> | ||
| 819 | struct fmt::formatter<NAV::vendor::ublox::NmeaTalkerID> : ostream_formatter | ||
| 820 | {}; | ||
| 821 | template<> | ||
| 822 | struct fmt::formatter<NAV::vendor::ublox::NmeaMessageClass> : ostream_formatter | ||
| 823 | {}; | ||
| 824 | template<> | ||
| 825 | struct fmt::formatter<NAV::vendor::ublox::NmeaStandardMessages> : ostream_formatter | ||
| 826 | {}; | ||
| 827 | template<> | ||
| 828 | struct fmt::formatter<NAV::vendor::ublox::NmeaPubxMessages> : ostream_formatter | ||
| 829 | {}; | ||
| 830 | |||
| 831 | /// @brief Formatter for UbxClass | ||
| 832 | template<> | ||
| 833 | struct fmt::formatter<NAV::vendor::ublox::UbxClass> : fmt::formatter<std::string> | ||
| 834 | { | ||
| 835 | /// @brief Defines how to format SatelliteSystem structs | ||
| 836 | /// @param[in] ubxClass Struct to format | ||
| 837 | /// @param[in, out] ctx Format context | ||
| 838 | /// @return Output iterator | ||
| 839 | template<typename FormatContext> | ||
| 840 | ✗ | auto format(const NAV::vendor::ublox::UbxClass& ubxClass, FormatContext& ctx) const | |
| 841 | { | ||
| 842 | ✗ | return fmt::formatter<std::string>::format(NAV::vendor::ublox::getStringFromMsgClass(ubxClass), ctx); | |
| 843 | } | ||
| 844 | }; | ||
| 845 | |||
| 846 | template<> | ||
| 847 | struct fmt::formatter<NAV::vendor::ublox::UbxAckMessages> : ostream_formatter | ||
| 848 | {}; | ||
| 849 | template<> | ||
| 850 | struct fmt::formatter<NAV::vendor::ublox::UbxCfgMessages> : ostream_formatter | ||
| 851 | {}; | ||
| 852 | template<> | ||
| 853 | struct fmt::formatter<NAV::vendor::ublox::UbxEsfMessages> : ostream_formatter | ||
| 854 | {}; | ||
| 855 | template<> | ||
| 856 | struct fmt::formatter<NAV::vendor::ublox::UbxHnrMessages> : ostream_formatter | ||
| 857 | {}; | ||
| 858 | template<> | ||
| 859 | struct fmt::formatter<NAV::vendor::ublox::UbxInfMessages> : ostream_formatter | ||
| 860 | {}; | ||
| 861 | template<> | ||
| 862 | struct fmt::formatter<NAV::vendor::ublox::UbxLogMessages> : ostream_formatter | ||
| 863 | {}; | ||
| 864 | template<> | ||
| 865 | struct fmt::formatter<NAV::vendor::ublox::UbxMgaMessages> : ostream_formatter | ||
| 866 | {}; | ||
| 867 | template<> | ||
| 868 | struct fmt::formatter<NAV::vendor::ublox::UbxMonMessages> : ostream_formatter | ||
| 869 | {}; | ||
| 870 | template<> | ||
| 871 | struct fmt::formatter<NAV::vendor::ublox::UbxNavMessages> : ostream_formatter | ||
| 872 | {}; | ||
| 873 | template<> | ||
| 874 | struct fmt::formatter<NAV::vendor::ublox::UbxRxmMessages> : ostream_formatter | ||
| 875 | {}; | ||
| 876 | template<> | ||
| 877 | struct fmt::formatter<NAV::vendor::ublox::UbxSecMessages> : ostream_formatter | ||
| 878 | {}; | ||
| 879 | template<> | ||
| 880 | struct fmt::formatter<NAV::vendor::ublox::UbxTimMessages> : ostream_formatter | ||
| 881 | {}; | ||
| 882 | template<> | ||
| 883 | struct fmt::formatter<NAV::vendor::ublox::UbxUpdMessages> : ostream_formatter | ||
| 884 | {}; | ||
| 885 | |||
| 886 | #endif | ||
| 887 |