54 #include "../../definitions.h" 56 #define UBX_SYNC1 0xB5 57 #define UBX_SYNC2 0x62 60 #define UBX_CLASS_NAV 0x01 61 #define UBX_CLASS_INF 0x04 62 #define UBX_CLASS_ACK 0x05 63 #define UBX_CLASS_CFG 0x06 64 #define UBX_CLASS_MON 0x0A 65 #define UBX_CLASS_RTCM3 0xF5 68 #define UBX_ID_NAV_POSLLH 0x02 69 #define UBX_ID_NAV_DOP 0x04 70 #define UBX_ID_NAV_SOL 0x06 71 #define UBX_ID_NAV_PVT 0x07 72 #define UBX_ID_NAV_VELNED 0x12 73 #define UBX_ID_NAV_TIMEUTC 0x21 74 #define UBX_ID_NAV_SVINFO 0x30 75 #define UBX_ID_NAV_SAT 0x35 76 #define UBX_ID_NAV_SVIN 0x3B 77 #define UBX_ID_NAV_RELPOSNED 0x3C 78 #define UBX_ID_INF_DEBUG 0x04 79 #define UBX_ID_INF_ERROR 0x00 80 #define UBX_ID_INF_NOTICE 0x02 81 #define UBX_ID_INF_WARNING 0x01 82 #define UBX_ID_ACK_NAK 0x00 83 #define UBX_ID_ACK_ACK 0x01 84 #define UBX_ID_CFG_PRT 0x00 // deprecated in protocol version >= 27 -> use CFG_VALSET 85 #define UBX_ID_CFG_MSG 0x01 // deprecated in protocol version >= 27 -> use CFG_VALSET 86 #define UBX_ID_CFG_RATE 0x08 // deprecated in protocol version >= 27 -> use CFG_VALSET 87 #define UBX_ID_CFG_CFG 0x09 // deprecated in protocol version >= 27 -> use CFG_VALSET 88 #define UBX_ID_CFG_NAV5 0x24 // deprecated in protocol version >= 27 -> use CFG_VALSET 89 #define UBX_ID_CFG_RST 0x04 90 #define UBX_ID_CFG_SBAS 0x16 91 #define UBX_ID_CFG_TMODE3 0x71 // deprecated in protocol version >= 27 -> use CFG_VALSET 92 #define UBX_ID_CFG_VALSET 0x8A 93 #define UBX_ID_CFG_VALGET 0x8B 94 #define UBX_ID_CFG_VALDEL 0x8C 95 #define UBX_ID_MON_VER 0x04 96 #define UBX_ID_MON_HW 0x09 // deprecated in protocol version >= 27 -> use MON_RF 97 #define UBX_ID_MON_RF 0x38 102 #define UBX_ID_RTCM3_1005 0x05 103 #define UBX_ID_RTCM3_1074 0x4A 104 #define UBX_ID_RTCM3_1077 0x4D 105 #define UBX_ID_RTCM3_1084 0x54 106 #define UBX_ID_RTCM3_1087 0x57 107 #define UBX_ID_RTCM3_1094 0x5E 108 #define UBX_ID_RTCM3_1097 0x61 109 #define UBX_ID_RTCM3_1124 0x7C 110 #define UBX_ID_RTCM3_1127 0x7F 111 #define UBX_ID_RTCM3_1230 0xE6 112 #define UBX_ID_RTCM3_4072 0xFE 116 #define UBX_MSG_NAV_POSLLH ((UBX_CLASS_NAV) | UBX_ID_NAV_POSLLH << 8) 117 #define UBX_MSG_NAV_SOL ((UBX_CLASS_NAV) | UBX_ID_NAV_SOL << 8) 118 #define UBX_MSG_NAV_DOP ((UBX_CLASS_NAV) | UBX_ID_NAV_DOP << 8) 119 #define UBX_MSG_NAV_PVT ((UBX_CLASS_NAV) | UBX_ID_NAV_PVT << 8) 120 #define UBX_MSG_NAV_VELNED ((UBX_CLASS_NAV) | UBX_ID_NAV_VELNED << 8) 121 #define UBX_MSG_NAV_TIMEUTC ((UBX_CLASS_NAV) | UBX_ID_NAV_TIMEUTC << 8) 122 #define UBX_MSG_NAV_SVINFO ((UBX_CLASS_NAV) | UBX_ID_NAV_SVINFO << 8) 123 #define UBX_MSG_NAV_SAT ((UBX_CLASS_NAV) | UBX_ID_NAV_SAT << 8) 124 #define UBX_MSG_NAV_SVIN ((UBX_CLASS_NAV) | UBX_ID_NAV_SVIN << 8) 125 #define UBX_MSG_NAV_RELPOSNED ((UBX_CLASS_NAV) | UBX_ID_NAV_RELPOSNED << 8) 126 #define UBX_MSG_INF_DEBUG ((UBX_CLASS_INF) | UBX_ID_INF_DEBUG << 8) 127 #define UBX_MSG_INF_ERROR ((UBX_CLASS_INF) | UBX_ID_INF_ERROR << 8) 128 #define UBX_MSG_INF_NOTICE ((UBX_CLASS_INF) | UBX_ID_INF_NOTICE << 8) 129 #define UBX_MSG_INF_WARNING ((UBX_CLASS_INF) | UBX_ID_INF_WARNING << 8) 130 #define UBX_MSG_ACK_NAK ((UBX_CLASS_ACK) | UBX_ID_ACK_NAK << 8) 131 #define UBX_MSG_ACK_ACK ((UBX_CLASS_ACK) | UBX_ID_ACK_ACK << 8) 132 #define UBX_MSG_CFG_PRT ((UBX_CLASS_CFG) | UBX_ID_CFG_PRT << 8) 133 #define UBX_MSG_CFG_MSG ((UBX_CLASS_CFG) | UBX_ID_CFG_MSG << 8) 134 #define UBX_MSG_CFG_RATE ((UBX_CLASS_CFG) | UBX_ID_CFG_RATE << 8) 135 #define UBX_MSG_CFG_CFG ((UBX_CLASS_CFG) | UBX_ID_CFG_CFG << 8) 136 #define UBX_MSG_CFG_NAV5 ((UBX_CLASS_CFG) | UBX_ID_CFG_NAV5 << 8) 137 #define UBX_MSG_CFG_RST ((UBX_CLASS_CFG) | UBX_ID_CFG_RST << 8) 138 #define UBX_MSG_CFG_SBAS ((UBX_CLASS_CFG) | UBX_ID_CFG_SBAS << 8) 139 #define UBX_MSG_CFG_TMODE3 ((UBX_CLASS_CFG) | UBX_ID_CFG_TMODE3 << 8) 140 #define UBX_MSG_CFG_VALGET ((UBX_CLASS_CFG) | UBX_ID_CFG_VALGET << 8) 141 #define UBX_MSG_CFG_VALSET ((UBX_CLASS_CFG) | UBX_ID_CFG_VALSET << 8) 142 #define UBX_MSG_CFG_VALDEL ((UBX_CLASS_CFG) | UBX_ID_CFG_VALDEL << 8) 143 #define UBX_MSG_MON_HW ((UBX_CLASS_MON) | UBX_ID_MON_HW << 8) 144 #define UBX_MSG_MON_VER ((UBX_CLASS_MON) | UBX_ID_MON_VER << 8) 145 #define UBX_MSG_MON_RF ((UBX_CLASS_MON) | UBX_ID_MON_RF << 8) 146 #define UBX_MSG_RTCM3_1005 ((UBX_CLASS_RTCM3) | UBX_ID_RTCM3_1005 << 8) 147 #define UBX_MSG_RTCM3_1077 ((UBX_CLASS_RTCM3) | UBX_ID_RTCM3_1077 << 8) 148 #define UBX_MSG_RTCM3_1087 ((UBX_CLASS_RTCM3) | UBX_ID_RTCM3_1087 << 8) 149 #define UBX_MSG_RTCM3_1074 ((UBX_CLASS_RTCM3) | UBX_ID_RTCM3_1074 << 8) 150 #define UBX_MSG_RTCM3_1084 ((UBX_CLASS_RTCM3) | UBX_ID_RTCM3_1084 << 8) 151 #define UBX_MSG_RTCM3_1094 ((UBX_CLASS_RTCM3) | UBX_ID_RTCM3_1094 << 8) 152 #define UBX_MSG_RTCM3_1097 ((UBX_CLASS_RTCM3) | UBX_ID_RTCM3_1097 << 8) 153 #define UBX_MSG_RTCM3_1124 ((UBX_CLASS_RTCM3) | UBX_ID_RTCM3_1124 << 8) 154 #define UBX_MSG_RTCM3_1127 ((UBX_CLASS_RTCM3) | UBX_ID_RTCM3_1127 << 8) 155 #define UBX_MSG_RTCM3_1230 ((UBX_CLASS_RTCM3) | UBX_ID_RTCM3_1230 << 8) 156 #define UBX_MSG_RTCM3_4072 ((UBX_CLASS_RTCM3) | UBX_ID_RTCM3_4072 << 8) 160 #define UBX_RX_NAV_PVT_VALID_VALIDDATE 0x01 161 #define UBX_RX_NAV_PVT_VALID_VALIDTIME 0x02 162 #define UBX_RX_NAV_PVT_VALID_FULLYRESOLVED 0x04 165 #define UBX_RX_NAV_PVT_FLAGS_GNSSFIXOK 0x01 166 #define UBX_RX_NAV_PVT_FLAGS_DIFFSOLN 0x02 167 #define UBX_RX_NAV_PVT_FLAGS_PSMSTATE 0x1C 168 #define UBX_RX_NAV_PVT_FLAGS_HEADVEHVALID 0x20 169 #define UBX_RX_NAV_PVT_FLAGS_CARRSOLN 0xC0 173 #define UBX_RX_NAV_TIMEUTC_VALID_VALIDTOW 0x01 174 #define UBX_RX_NAV_TIMEUTC_VALID_VALIDKWN 0x02 175 #define UBX_RX_NAV_TIMEUTC_VALID_VALIDUTC 0x04 176 #define UBX_RX_NAV_TIMEUTC_VALID_UTCSTANDARD 0xF0 181 #define UBX_TX_CFG_PRT_PORTID 0x01 182 #define UBX_TX_CFG_PRT_PORTID_USB 0x03 183 #define UBX_TX_CFG_PRT_PORTID_SPI 0x04 184 #define UBX_TX_CFG_PRT_MODE 0x000008D0 185 #define UBX_TX_CFG_PRT_MODE_SPI 0x00000100 186 #define UBX_TX_CFG_PRT_BAUDRATE 38400 187 #define UBX_TX_CFG_PRT_INPROTOMASK_GPS ((1<<5) | 0x01) 188 #define UBX_TX_CFG_PRT_INPROTOMASK_RTCM (0x01) 189 #define UBX_TX_CFG_PRT_OUTPROTOMASK_GPS (0x01) 190 #define UBX_TX_CFG_PRT_OUTPROTOMASK_RTCM ((1<<5) | 0x01) 192 #define UBX_BAUDRATE_M8_AND_NEWER 115200 197 #define UBX_TX_CFG_RATE_MEASINTERVAL 200 198 #define UBX_TX_CFG_RATE_NAVRATE 1 199 #define UBX_TX_CFG_RATE_TIMEREF 0 204 #define UBX_TX_CFG_NAV5_MASK 0x0005 205 #define UBX_TX_CFG_NAV5_FIXMODE 2 209 #define UBX_TX_CFG_RST_BBR_MODE_HOT_START 0 210 #define UBX_TX_CFG_RST_BBR_MODE_WARM_START 1 211 #define UBX_TX_CFG_RST_BBR_MODE_COLD_START 0xFFFF 212 #define UBX_TX_CFG_RST_MODE_HARDWARE 0 213 #define UBX_TX_CFG_RST_MODE_SOFTWARE 1 216 #define UBX_CFG_KEY_CFG_UART1_BAUDRATE 0x40520001 217 #define UBX_CFG_KEY_CFG_UART1_STOPBITS 0x20520002 218 #define UBX_CFG_KEY_CFG_UART1_DATABITS 0x20520003 219 #define UBX_CFG_KEY_CFG_UART1_PARITY 0x20520004 220 #define UBX_CFG_KEY_CFG_UART1_ENABLED 0x20520005 221 #define UBX_CFG_KEY_CFG_UART1_REMAP 0x20520006 222 #define UBX_CFG_KEY_CFG_UART1INPROT_UBX 0x10730001 223 #define UBX_CFG_KEY_CFG_UART1INPROT_NMEA 0x10730002 224 #define UBX_CFG_KEY_CFG_UART1INPROT_RTCM3X 0x10730004 225 #define UBX_CFG_KEY_CFG_UART1OUTPROT_UBX 0x10740001 226 #define UBX_CFG_KEY_CFG_UART1OUTPROT_NMEA 0x10740002 227 #define UBX_CFG_KEY_CFG_UART1OUTPROT_RTCM3X 0x10740004 229 #define UBX_CFG_KEY_CFG_UART2_BAUDRATE 0x40530001 230 #define UBX_CFG_KEY_CFG_UART2_STOPBITS 0x20530002 231 #define UBX_CFG_KEY_CFG_UART2_DATABITS 0x20530003 232 #define UBX_CFG_KEY_CFG_UART2_PARITY 0x20530004 233 #define UBX_CFG_KEY_CFG_UART2_ENABLED 0x20530005 234 #define UBX_CFG_KEY_CFG_UART2_REMAP 0x20530006 235 #define UBX_CFG_KEY_CFG_UART2INPROT_UBX 0x10750001 236 #define UBX_CFG_KEY_CFG_UART2INPROT_NMEA 0x10750002 237 #define UBX_CFG_KEY_CFG_UART2INPROT_RTCM3X 0x10750004 238 #define UBX_CFG_KEY_CFG_UART2OUTPROT_UBX 0x10760001 239 #define UBX_CFG_KEY_CFG_UART2OUTPROT_NMEA 0x10760002 240 #define UBX_CFG_KEY_CFG_UART2OUTPROT_RTCM3X 0x10760004 242 #define UBX_CFG_KEY_CFG_USB_ENABLED 0x10650001 243 #define UBX_CFG_KEY_CFG_USBINPROT_UBX 0x10770001 244 #define UBX_CFG_KEY_CFG_USBINPROT_NMEA 0x10770002 245 #define UBX_CFG_KEY_CFG_USBINPROT_RTCM3X 0x10770004 246 #define UBX_CFG_KEY_CFG_USBOUTPROT_UBX 0x10780001 247 #define UBX_CFG_KEY_CFG_USBOUTPROT_NMEA 0x10780002 248 #define UBX_CFG_KEY_CFG_USBOUTPROT_RTCM3X 0x10780004 250 #define UBX_CFG_KEY_CFG_SPIINPROT_UBX 0x10790001 251 #define UBX_CFG_KEY_CFG_SPIINPROT_NMEA 0x10790002 252 #define UBX_CFG_KEY_CFG_SPIINPROT_RTCM3X 0x10790004 253 #define UBX_CFG_KEY_CFG_SPIOUTPROT_UBX 0x107a0001 254 #define UBX_CFG_KEY_CFG_SPIOUTPROT_NMEA 0x107a0002 255 #define UBX_CFG_KEY_CFG_SPIOUTPROT_RTCM3X 0x107a0004 257 #define UBX_CFG_KEY_NAVHPG_DGNSSMODE 0x20140011 259 #define UBX_CFG_KEY_NAVSPG_FIXMODE 0x20110011 260 #define UBX_CFG_KEY_NAVSPG_UTCSTANDARD 0x2011001c 261 #define UBX_CFG_KEY_NAVSPG_DYNMODEL 0x20110021 263 #define UBX_CFG_KEY_ODO_USE_ODO 0x10220001 264 #define UBX_CFG_KEY_ODO_USE_COG 0x10220002 265 #define UBX_CFG_KEY_ODO_OUTLPVEL 0x10220003 266 #define UBX_CFG_KEY_ODO_OUTLPCOG 0x10220004 268 #define UBX_CFG_KEY_RATE_MEAS 0x30210001 269 #define UBX_CFG_KEY_RATE_NAV 0x30210002 270 #define UBX_CFG_KEY_RATE_TIMEREF 0x20210003 272 #define UBX_CFG_KEY_TMODE_MODE 0x20030001 273 #define UBX_CFG_KEY_TMODE_POS_TYPE 0x20030002 274 #define UBX_CFG_KEY_TMODE_LAT 0x40030009 275 #define UBX_CFG_KEY_TMODE_LON 0x4003000a 276 #define UBX_CFG_KEY_TMODE_HEIGHT 0x4003000b 277 #define UBX_CFG_KEY_TMODE_LAT_HP 0x2003000c 278 #define UBX_CFG_KEY_TMODE_LON_HP 0x2003000d 279 #define UBX_CFG_KEY_TMODE_HEIGHT_HP 0x2003000e 280 #define UBX_CFG_KEY_TMODE_FIXED_POS_ACC 0x4003000f 281 #define UBX_CFG_KEY_TMODE_SVIN_MIN_DUR 0x40030010 282 #define UBX_CFG_KEY_TMODE_SVIN_ACC_LIMIT 0x40030011 284 #define UBX_CFG_KEY_MSGOUT_UBX_MON_RF_I2C 0x20910359 285 #define UBX_CFG_KEY_MSGOUT_UBX_NAV_SVIN_I2C 0x20910088 286 #define UBX_CFG_KEY_MSGOUT_UBX_NAV_SAT_I2C 0x20910015 287 #define UBX_CFG_KEY_MSGOUT_UBX_NAV_DOP_I2C 0x20910038 288 #define UBX_CFG_KEY_MSGOUT_UBX_NAV_PVT_I2C 0x20910006 289 #define UBX_CFG_KEY_MSGOUT_RTCM_3X_TYPE1005_I2C 0x209102bd 290 #define UBX_CFG_KEY_MSGOUT_RTCM_3X_TYPE1077_I2C 0x209102cc 291 #define UBX_CFG_KEY_MSGOUT_RTCM_3X_TYPE1087_I2C 0x209102d1 292 #define UBX_CFG_KEY_MSGOUT_RTCM_3X_TYPE1097_I2C 0x20910318 293 #define UBX_CFG_KEY_MSGOUT_RTCM_3X_TYPE1127_I2C 0x209102d6 294 #define UBX_CFG_KEY_MSGOUT_RTCM_3X_TYPE1230_I2C 0x20910303 296 #define UBX_CFG_KEY_SPI_ENABLED 0x10640006 297 #define UBX_CFG_KEY_SPI_MAXFF 0x20640001 304 #pragma pack(push, 1) 399 #define UBX_PAYLOAD_RX_NAV_PVT_SIZE_UBX7 (sizeof(ubx_payload_rx_nav_pvt_t) - 8) 400 #define UBX_PAYLOAD_RX_NAV_PVT_SIZE_UBX8 (sizeof(ubx_payload_rx_nav_pvt_t)) 472 uint8_t reserved3[2];
550 uint8_t reserved3[3];
558 uint8_t swVersion[30];
559 uint8_t hwVersion[10];
564 uint8_t extension[30];
621 #define UBX_CFG_LAYER_RAM (1 << 0) 622 #define UBX_CFG_LAYER_BBR (1 << 1) 623 #define UBX_CFG_LAYER_FLASH (1 << 2) 692 uint8_t reserved3[8];
767 uint8_t dynamic_model = 7);
771 int receive(
unsigned timeout)
override;
782 int restartSurveyIn();
787 int restartSurveyInPreV27();
792 int parseChar(
const uint8_t b);
797 int payloadRxInit(
void);
802 int payloadRxAdd(
const uint8_t b);
803 int payloadRxAddNavSvinfo(
const uint8_t b);
804 int payloadRxAddNavSat(
const uint8_t b);
805 int payloadRxAddMonVer(
const uint8_t b);
810 int payloadRxDone(
void);
815 void decodeInit(
void);
820 void addByteToChecksum(
const uint8_t);
826 bool sendMessage(
const uint16_t
msg,
const uint8_t *payload,
const uint16_t length);
833 bool configureMessageRate(
const uint16_t msg,
const uint8_t rate);
838 void calcChecksum(
const uint8_t *buffer,
const uint16_t length,
ubx_checksum_t *checksum);
843 int waitForAck(
const uint16_t msg,
const unsigned timeout,
const bool report);
850 inline bool configureMessageRateAndAck(uint16_t msg, uint8_t rate,
bool report_ack_error =
false);
856 int configureDevice();
861 int configureDevicePreV27();
877 bool cfgValset(uint32_t key_id, T value,
int &msg_size);
890 bool cfgValsetPort(uint32_t key_id, uint8_t value,
int &msg_size);
892 int activateRTCMOutput();
897 uint32_t fnv1_32_str(uint8_t *str, uint32_t hval);
910 uint64_t _last_timestamp_time{0};
911 bool _configured{
false};
913 bool _got_posllh{
false};
914 bool _got_velned{
false};
918 uint16_t _rx_payload_length{};
919 uint16_t _rx_payload_index{};
923 uint16_t _ack_waiting_msg{0};
925 uint32_t _ubx_version{0};
926 bool _use_nav_pvt{
false};
927 bool _proto_ver_27_or_higher{
false};
936 uint8_t _dyn_model{7};
uint16_t agcCnt
AGC Monitor (counts SIGI xor SIGLO, range 0 to 8191.
uint16_t tDOP
Time DOP [0.01].
uint32_t cAcc
Course / Heading accuracy estimate [1e-5 deg].
ubx_payload_tx_cfg_rst_t payload_tx_cfg_rst
uint8_t magI
Magnitude of I-part of complex signal (0=no signal, 255=max magnitude)
const Interface _interface
uint32_t sAcc
Speed accuracy estimate [cm/s].
ubx_payload_rx_nav_svinfo_part2_t payload_rx_nav_svinfo_part2
uint32_t hAcc
Horizontal accuracy estimate [mm].
uint8_t min
Minute of hour, range 0..59 (UTC)
ubx_payload_rx_mon_hw_ubx6_t payload_rx_mon_hw_ubx6
uint16_t pDOP
Position DOP [0.01].
uint16_t timeRef
Alignment to reference time: 0 = UTC time, 1 = GPS time.
uint32_t iTOW
GPS Time of Week [ms].
uint8_t dynModel
Dynamic Platform model: 0 Portable, 2 Stationary, 3 Pedestrian, 4 Automotive, 5 Sea, 6 Airborne <1g, 7 Airborne <2g, 8 Airborne <4g.
uint8_t numCh
Number of channels.
int32_t height
Height above ellipsoid [mm].
ubx_payload_rx_nav_posllh_t payload_rx_nav_posllh
uint8_t version
Message version, set to 0.
uint32_t hAcc
Horizontal accuracy estimate [mm].
uint16_t navRate
Navigation Rate, in number of measurement cycles.
uint32_t vAcc
Vertical accuracy estimate [mm].
int8_t ofsQ
Imbalance of Q-part of complex signal.
uint8_t gpsFix
GPSfix type: 0 = No fix, 1 = Dead Reckoning only, 2 = 2D fix, 3 = 3d-fix, 4 = GPS + dead reckoning...
uint8_t month
Month, range 1..12 (UTC)
ubx_payload_rx_mon_hw_ubx7_t payload_rx_mon_hw_ubx7
uint8_t valid
Validity Flags (see UBX_RX_NAV_TIMEUTC_VALID_...)
uint16_t year
Year, range 1999..2099 (UTC)
ubx_payload_rx_nav_timeutc_t payload_rx_nav_timeutc
ubx_payload_tx_cfg_msg_t payload_tx_cfg_msg
ubx_payload_tx_cfg_cfg_t payload_tx_cfg_cfg
uint32_t tAcc
Time accuracy estimate (UTC) [ns].
ubx_payload_rx_mon_rf_t payload_rx_mon_rf
uint32_t iTOW
GPS Time of Week [ms].
uint32_t iTOW
GPS Time of Week [ms].
uint32_t sAcc
Speed accuracy estimate [mm/s].
ubx_payload_rx_nav_sol_t payload_rx_nav_sol
int32_t velN
North velocity component [cm/s].
uint8_t gnssId
GNSS identifier.
uint8_t day
Day of month, range 1..31 (UTC)
ubx_payload_rx_nav_pvt_t payload_rx_nav_pvt
uint32_t loadMask
Load settings.
uint32_t iTOW
GPS Time of Week [ms].
ubx_payload_rx_mon_ver_part1_t payload_rx_mon_ver_part1
uint8_t antPower
Current power status of antenna.
uint32_t postStatus
POST status word.
int32_t lat
Latitude [1e-7 deg].
ubx_payload_rx_mon_ver_part2_t payload_rx_mon_ver_part2
void reset()
reset the parsing state
int8_t elev
Elevation [deg] range: +/-90.
int32_t lon
Longitude [1e-7 deg].
uint8_t sec
Seconds of minute, range 0..60 (UTC)
uint16_t eDOP
Easting DOP [0.01].
uint8_t numSvs
Number of Satellites.
ubx_payload_rx_nav_sat_part1_t payload_rx_nav_sat_part1
uint32_t reserved4
(ubx8+ only)
uint32_t iTOW
GPS Time of Week [ms].
ubx_payload_tx_cfg_tmode3_t payload_tx_cfg_tmode3
int32_t height
Height above ellipsoid [mm].
static enum ST24_DECODE_STATE _decode_state
uint8_t cnoThreshNumSVs
(ubx7+ only, else 0)
uint32_t tAcc
Time accuracy estimate (UTC) [ns].
static char msg[NUM_MSG][CONFIG_USART1_TXBUFSIZE]
uint32_t iTOW
GPS Time of Week [ms].
uint32_t speed
Speed (3-D) [cm/s].
uint32_t saveMask
Save settings.
int32_t gSpeed
Ground Speed (2-D) [mm/s].
uint8_t valid
Validity flags (see UBX_RX_NAV_PVT_VALID_...)
uint32_t clearMask
Clear settings.
int32_t nano
Fraction of second, range -1e9 .
uint8_t cno
Carrier to Noise Ratio (Signal Strength) [dbHz].
static unsigned char _buf[2048]
uint8_t antStatus
Status of the antenna superior state machine.
uint8_t min
Minute of hour, range 0..59 (UTC)
uint8_t cnoThresh
(ubx7+ only, else 0)
int16_t prRes
Pseudo range residual [0.1 m].
int32_t velD
NED down velocity [mm/s].
int32_t velE
NED east velocity [mm/s].
uint8_t fixMode
Position Fixing Mode: 1 2D only, 2 3D only, 3 Auto 2D/3D.
int(* GPSCallbackPtr)(GPSCallbackType type, void *data1, int data2, void *user)
Callback function for platform-specific stuff.
ubx_payload_rx_nav_dop_t payload_rx_nav_dop
ubx_payload_tx_cfg_valset_t payload_tx_cfg_valset
uint8_t utcStandard
(ubx8+ only, else 0)
uint8_t nBlocks
number of RF blocks included
uint16_t gDOP
Geometric DOP [0.01].
ubx_payload_rx_ack_ack_t payload_rx_ack_ack
uint8_t cfgData
configuration data (key and value pairs, max 64)
uint8_t sec
Seconds of minute, range 0..60 (UTC)
uint8_t magQ
Magnitude of Q-part of complex signal (0=no signal, 255=max magnitude)
int32_t velN
NED north velocity [mm/s].
uint32_t iTOW
GPS Time of Week [ms].
ubx_payload_tx_cfg_nav5_t payload_tx_cfg_nav5
int32_t fTOW
Fractional part of iTOW (range: +/-500000) [ns].
uint8_t svid
Satellite ID.
uint8_t blockId
RF block id.
uint16_t vDOP
Vertical DOP [0.01].
uint8_t svId
Satellite ID.
int8_t elev
Elevation [deg].
uint8_t chn
Channel number, 255 for SVs not assigned to a channel.
uint8_t day
Day of month, range 1..31 (UTC)
int32_t velD
Down velocity component [cm/s].
int32_t lon
Longitude [1e-7 deg].
uint16_t noisePerMS
Noise level as measured by the GPS core.
int32_t hMSL
Height above mean sea level [mm].
uint16_t hDOP
Horizontal DOP [0.01].
uint32_t vAcc
Vertical accuracy estimate [mm].
ubx_payload_tx_cfg_prt_t payload_tx_cfg_prt
ubx_payload_tx_cfg_rate_t payload_tx_cfg_rate
uint16_t measRate
Measurement Rate, GPS measurements are taken every measRate milliseconds.
uint8_t numSV
Number of SVs used in Nav Solution.
int16_t azim
Azimuth [deg].
int16_t azim
Azimuth [deg] range: 0-360.
uint16_t nDOP
Northing DOP [0.01].
GPS driver base class with Base Station Support.
ubx_payload_rx_nav_svinfo_part1_t payload_rx_nav_svinfo_part1
int32_t headVeh
(ubx8+ only) Heading of vehicle (2-D) [1e-5 deg]
ubx_payload_tx_cfg_sbas_t payload_tx_cfg_sbas
int32_t lat
Latitude [1e-7 deg].
uint8_t version
Message version (1)
uint8_t numSV
Number of SVs used in Nav Solution.
uint16_t staticHoldMaxDist
(ubx8+ only, else 0)
uint16_t pDOP
Position DOP [0.01].
uint8_t fixType
GNSSfix type: 0 = No fix, 1 = Dead Reckoning only, 2 = 2D fix, 3 = 3d-fix, 4 = GNSS + dead reckoning...
uint8_t month
Month, range 1..12 (UTC)
int32_t prRes
Pseudo range residual [cm].
int32_t nano
Fraction of second (UTC) [-1e9...1e9 ns].
uint32_t iTOW
GPS Time of Week [ms].
int8_t ofsI
Imbalance of I-part of complex signal.
uint8_t flags
Fix Status Flags (see UBX_RX_NAV_PVT_FLAGS_...)
int32_t headMot
Heading of motion (2-D) [1e-5 deg].
uint8_t hour
Hour of day, range 0..23 (UTC)
ubx_payload_rx_ack_nak_t payload_rx_ack_nak
uint8_t cno
Carrier to Noise Ratio (Signal Strength) [dbHz].
uint8_t hour
Hour of day, range 0..23 (UTC)
int32_t hMSL
Height above mean sea level [mm].
uint8_t layers
The layers where the configuration should be applied (.
uint8_t deviceMask
Storage devices to apply this top.
ubx_payload_rx_nav_sat_part2_t payload_rx_nav_sat_part2
int32_t velE
East velocity component [cm/s].
uint32_t gSpeed
Ground speed (2-D) [cm/s].
ubx_payload_rx_nav_velned_t payload_rx_nav_velned
uint32_t headAcc
Heading accuracy estimate (motion and vehicle) [1e-5 deg].
uint8_t flags
jammingState
uint8_t jamInd
CW jamming indicator, scaled (0=no CW jamming, 255=strong CW jamming)
ubx_payload_rx_nav_svin_t payload_rx_nav_svin
uint16_t pDOP
Position DOP [0.01].
int32_t heading
Heading of motion 2-D [1e-5 deg].