PX4 Firmware
PX4 Autopilot Software http://px4.io
ubx.h File Reference

U-Blox protocol definition. More...

#include "gps_helper.h"
#include "base_station.h"
#include "../../definitions.h"
Include dependency graph for ubx.h:
This graph shows which files directly or indirectly include this file:

Go to the source code of this file.

Classes

struct  ubx_header_t
 
struct  ubx_checksum_t
 
struct  ubx_payload_rx_nav_posllh_t
 
struct  ubx_payload_rx_nav_dop_t
 
struct  ubx_payload_rx_nav_sol_t
 
struct  ubx_payload_rx_nav_pvt_t
 
struct  ubx_payload_rx_nav_timeutc_t
 
struct  ubx_payload_rx_nav_svinfo_part1_t
 
struct  ubx_payload_rx_nav_svinfo_part2_t
 
struct  ubx_payload_rx_nav_sat_part1_t
 
struct  ubx_payload_rx_nav_sat_part2_t
 
struct  ubx_payload_rx_nav_svin_t
 
struct  ubx_payload_rx_nav_velned_t
 
struct  ubx_payload_rx_mon_hw_ubx6_t
 
struct  ubx_payload_rx_mon_hw_ubx7_t
 
struct  ubx_payload_rx_mon_rf_t
 
struct  ubx_payload_rx_mon_rf_t::ubx_payload_rx_mon_rf_block_t
 
struct  ubx_payload_rx_mon_ver_part1_t
 
struct  ubx_payload_rx_mon_ver_part2_t
 
union  ubx_payload_rx_ack_ack_t
 
union  ubx_payload_rx_ack_nak_t
 
struct  ubx_payload_tx_cfg_prt_t
 
struct  ubx_payload_tx_cfg_rate_t
 
struct  ubx_payload_tx_cfg_cfg_t
 
struct  ubx_payload_tx_cfg_valset_t
 
struct  ubx_payload_tx_cfg_nav5_t
 
struct  ubx_payload_tx_cfg_rst_t
 
struct  ubx_payload_tx_cfg_sbas_t
 
struct  ubx_payload_tx_cfg_msg_t
 
struct  ubx_payload_tx_cfg_tmode3_t
 
union  ubx_buf_t
 
class  GPSDriverUBX
 

Macros

#define UBX_SYNC1   0xB5
 
#define UBX_SYNC2   0x62
 
#define UBX_CLASS_NAV   0x01
 
#define UBX_CLASS_INF   0x04
 
#define UBX_CLASS_ACK   0x05
 
#define UBX_CLASS_CFG   0x06
 
#define UBX_CLASS_MON   0x0A
 
#define UBX_CLASS_RTCM3   0xF5
 
#define UBX_ID_NAV_POSLLH   0x02
 
#define UBX_ID_NAV_DOP   0x04
 
#define UBX_ID_NAV_SOL   0x06
 
#define UBX_ID_NAV_PVT   0x07
 
#define UBX_ID_NAV_VELNED   0x12
 
#define UBX_ID_NAV_TIMEUTC   0x21
 
#define UBX_ID_NAV_SVINFO   0x30
 
#define UBX_ID_NAV_SAT   0x35
 
#define UBX_ID_NAV_SVIN   0x3B
 
#define UBX_ID_NAV_RELPOSNED   0x3C
 
#define UBX_ID_INF_DEBUG   0x04
 
#define UBX_ID_INF_ERROR   0x00
 
#define UBX_ID_INF_NOTICE   0x02
 
#define UBX_ID_INF_WARNING   0x01
 
#define UBX_ID_ACK_NAK   0x00
 
#define UBX_ID_ACK_ACK   0x01
 
#define UBX_ID_CFG_PRT   0x00
 
#define UBX_ID_CFG_MSG   0x01
 
#define UBX_ID_CFG_RATE   0x08
 
#define UBX_ID_CFG_CFG   0x09
 
#define UBX_ID_CFG_NAV5   0x24
 
#define UBX_ID_CFG_RST   0x04
 
#define UBX_ID_CFG_SBAS   0x16
 
#define UBX_ID_CFG_TMODE3   0x71
 
#define UBX_ID_CFG_VALSET   0x8A
 
#define UBX_ID_CFG_VALGET   0x8B
 
#define UBX_ID_CFG_VALDEL   0x8C
 
#define UBX_ID_MON_VER   0x04
 
#define UBX_ID_MON_HW   0x09
 
#define UBX_ID_MON_RF   0x38
 
#define UBX_ID_RTCM3_1005   0x05
 Stationary RTK reference station ARP. More...
 
#define UBX_ID_RTCM3_1074   0x4A
 GPS MSM4. More...
 
#define UBX_ID_RTCM3_1077   0x4D
 GPS MSM7. More...
 
#define UBX_ID_RTCM3_1084   0x54
 GLONASS MSM4. More...
 
#define UBX_ID_RTCM3_1087   0x57
 GLONASS MSM7. More...
 
#define UBX_ID_RTCM3_1094   0x5E
 Galileo MSM4. More...
 
#define UBX_ID_RTCM3_1097   0x61
 Galileo MSM7. More...
 
#define UBX_ID_RTCM3_1124   0x7C
 BeiDou MSM4. More...
 
#define UBX_ID_RTCM3_1127   0x7F
 BeiDou MSM7. More...
 
#define UBX_ID_RTCM3_1230   0xE6
 GLONASS code-phase biases. More...
 
#define UBX_ID_RTCM3_4072   0xFE
 Reference station PVT (u-blox proprietary RTCM Message) - Used for moving baseline. More...
 
#define UBX_MSG_NAV_POSLLH   ((UBX_CLASS_NAV) | UBX_ID_NAV_POSLLH << 8)
 
#define UBX_MSG_NAV_SOL   ((UBX_CLASS_NAV) | UBX_ID_NAV_SOL << 8)
 
#define UBX_MSG_NAV_DOP   ((UBX_CLASS_NAV) | UBX_ID_NAV_DOP << 8)
 
#define UBX_MSG_NAV_PVT   ((UBX_CLASS_NAV) | UBX_ID_NAV_PVT << 8)
 
#define UBX_MSG_NAV_VELNED   ((UBX_CLASS_NAV) | UBX_ID_NAV_VELNED << 8)
 
#define UBX_MSG_NAV_TIMEUTC   ((UBX_CLASS_NAV) | UBX_ID_NAV_TIMEUTC << 8)
 
#define UBX_MSG_NAV_SVINFO   ((UBX_CLASS_NAV) | UBX_ID_NAV_SVINFO << 8)
 
#define UBX_MSG_NAV_SAT   ((UBX_CLASS_NAV) | UBX_ID_NAV_SAT << 8)
 
#define UBX_MSG_NAV_SVIN   ((UBX_CLASS_NAV) | UBX_ID_NAV_SVIN << 8)
 
#define UBX_MSG_NAV_RELPOSNED   ((UBX_CLASS_NAV) | UBX_ID_NAV_RELPOSNED << 8)
 
#define UBX_MSG_INF_DEBUG   ((UBX_CLASS_INF) | UBX_ID_INF_DEBUG << 8)
 
#define UBX_MSG_INF_ERROR   ((UBX_CLASS_INF) | UBX_ID_INF_ERROR << 8)
 
#define UBX_MSG_INF_NOTICE   ((UBX_CLASS_INF) | UBX_ID_INF_NOTICE << 8)
 
#define UBX_MSG_INF_WARNING   ((UBX_CLASS_INF) | UBX_ID_INF_WARNING << 8)
 
#define UBX_MSG_ACK_NAK   ((UBX_CLASS_ACK) | UBX_ID_ACK_NAK << 8)
 
#define UBX_MSG_ACK_ACK   ((UBX_CLASS_ACK) | UBX_ID_ACK_ACK << 8)
 
#define UBX_MSG_CFG_PRT   ((UBX_CLASS_CFG) | UBX_ID_CFG_PRT << 8)
 
#define UBX_MSG_CFG_MSG   ((UBX_CLASS_CFG) | UBX_ID_CFG_MSG << 8)
 
#define UBX_MSG_CFG_RATE   ((UBX_CLASS_CFG) | UBX_ID_CFG_RATE << 8)
 
#define UBX_MSG_CFG_CFG   ((UBX_CLASS_CFG) | UBX_ID_CFG_CFG << 8)
 
#define UBX_MSG_CFG_NAV5   ((UBX_CLASS_CFG) | UBX_ID_CFG_NAV5 << 8)
 
#define UBX_MSG_CFG_RST   ((UBX_CLASS_CFG) | UBX_ID_CFG_RST << 8)
 
#define UBX_MSG_CFG_SBAS   ((UBX_CLASS_CFG) | UBX_ID_CFG_SBAS << 8)
 
#define UBX_MSG_CFG_TMODE3   ((UBX_CLASS_CFG) | UBX_ID_CFG_TMODE3 << 8)
 
#define UBX_MSG_CFG_VALGET   ((UBX_CLASS_CFG) | UBX_ID_CFG_VALGET << 8)
 
#define UBX_MSG_CFG_VALSET   ((UBX_CLASS_CFG) | UBX_ID_CFG_VALSET << 8)
 
#define UBX_MSG_CFG_VALDEL   ((UBX_CLASS_CFG) | UBX_ID_CFG_VALDEL << 8)
 
#define UBX_MSG_MON_HW   ((UBX_CLASS_MON) | UBX_ID_MON_HW << 8)
 
#define UBX_MSG_MON_VER   ((UBX_CLASS_MON) | UBX_ID_MON_VER << 8)
 
#define UBX_MSG_MON_RF   ((UBX_CLASS_MON) | UBX_ID_MON_RF << 8)
 
#define UBX_MSG_RTCM3_1005   ((UBX_CLASS_RTCM3) | UBX_ID_RTCM3_1005 << 8)
 
#define UBX_MSG_RTCM3_1077   ((UBX_CLASS_RTCM3) | UBX_ID_RTCM3_1077 << 8)
 
#define UBX_MSG_RTCM3_1087   ((UBX_CLASS_RTCM3) | UBX_ID_RTCM3_1087 << 8)
 
#define UBX_MSG_RTCM3_1074   ((UBX_CLASS_RTCM3) | UBX_ID_RTCM3_1074 << 8)
 
#define UBX_MSG_RTCM3_1084   ((UBX_CLASS_RTCM3) | UBX_ID_RTCM3_1084 << 8)
 
#define UBX_MSG_RTCM3_1094   ((UBX_CLASS_RTCM3) | UBX_ID_RTCM3_1094 << 8)
 
#define UBX_MSG_RTCM3_1097   ((UBX_CLASS_RTCM3) | UBX_ID_RTCM3_1097 << 8)
 
#define UBX_MSG_RTCM3_1124   ((UBX_CLASS_RTCM3) | UBX_ID_RTCM3_1124 << 8)
 
#define UBX_MSG_RTCM3_1127   ((UBX_CLASS_RTCM3) | UBX_ID_RTCM3_1127 << 8)
 
#define UBX_MSG_RTCM3_1230   ((UBX_CLASS_RTCM3) | UBX_ID_RTCM3_1230 << 8)
 
#define UBX_MSG_RTCM3_4072   ((UBX_CLASS_RTCM3) | UBX_ID_RTCM3_4072 << 8)
 
#define UBX_RX_NAV_PVT_VALID_VALIDDATE   0x01
 validDate (Valid UTC Date) More...
 
#define UBX_RX_NAV_PVT_VALID_VALIDTIME   0x02
 validTime (Valid UTC Time) More...
 
#define UBX_RX_NAV_PVT_VALID_FULLYRESOLVED   0x04
 fullyResolved (1 = UTC Time of Day has been fully resolved (no seconds uncertainty)) More...
 
#define UBX_RX_NAV_PVT_FLAGS_GNSSFIXOK   0x01
 gnssFixOK (A valid fix (i.e within DOP & accuracy masks)) More...
 
#define UBX_RX_NAV_PVT_FLAGS_DIFFSOLN   0x02
 diffSoln (1 if differential corrections were applied) More...
 
#define UBX_RX_NAV_PVT_FLAGS_PSMSTATE   0x1C
 psmState (Power Save Mode state (see Power Management)) More...
 
#define UBX_RX_NAV_PVT_FLAGS_HEADVEHVALID   0x20
 headVehValid (Heading of vehicle is valid) More...
 
#define UBX_RX_NAV_PVT_FLAGS_CARRSOLN   0xC0
 Carrier phase range solution (RTK mode) More...
 
#define UBX_RX_NAV_TIMEUTC_VALID_VALIDTOW   0x01
 validTOW (1 = Valid Time of Week) More...
 
#define UBX_RX_NAV_TIMEUTC_VALID_VALIDKWN   0x02
 validWKN (1 = Valid Week Number) More...
 
#define UBX_RX_NAV_TIMEUTC_VALID_VALIDUTC   0x04
 validUTC (1 = Valid UTC Time) More...
 
#define UBX_RX_NAV_TIMEUTC_VALID_UTCSTANDARD   0xF0
 utcStandard (0..15 = UTC standard identifier) More...
 
#define UBX_TX_CFG_PRT_PORTID   0x01
 UART1. More...
 
#define UBX_TX_CFG_PRT_PORTID_USB   0x03
 USB. More...
 
#define UBX_TX_CFG_PRT_PORTID_SPI   0x04
 SPI. More...
 
#define UBX_TX_CFG_PRT_MODE   0x000008D0
 0b0000100011010000: 8N1 More...
 
#define UBX_TX_CFG_PRT_MODE_SPI   0x00000100
 
#define UBX_TX_CFG_PRT_BAUDRATE   38400
 choose 38400 as GPS baudrate (pre M8* boards only) More...
 
#define UBX_TX_CFG_PRT_INPROTOMASK_GPS   ((1<<5) | 0x01)
 RTCM3 in and UBX in. More...
 
#define UBX_TX_CFG_PRT_INPROTOMASK_RTCM   (0x01)
 UBX in. More...
 
#define UBX_TX_CFG_PRT_OUTPROTOMASK_GPS   (0x01)
 UBX out. More...
 
#define UBX_TX_CFG_PRT_OUTPROTOMASK_RTCM   ((1<<5) | 0x01)
 RTCM3 out and UBX out. More...
 
#define UBX_BAUDRATE_M8_AND_NEWER   115200
 baudrate for M8+ boards More...
 
#define UBX_TX_CFG_RATE_MEASINTERVAL   200
 200ms for 5Hz (F9* boards use 10Hz) More...
 
#define UBX_TX_CFG_RATE_NAVRATE   1
 cannot be changed More...
 
#define UBX_TX_CFG_RATE_TIMEREF   0
 0: UTC, 1: GPS time More...
 
#define UBX_TX_CFG_NAV5_MASK   0x0005
 Only update dynamic model and fix mode. More...
 
#define UBX_TX_CFG_NAV5_FIXMODE   2
 1 2D only, 2 3D only, 3 Auto 2D/3D More...
 
#define UBX_TX_CFG_RST_BBR_MODE_HOT_START   0
 
#define UBX_TX_CFG_RST_BBR_MODE_WARM_START   1
 
#define UBX_TX_CFG_RST_BBR_MODE_COLD_START   0xFFFF
 
#define UBX_TX_CFG_RST_MODE_HARDWARE   0
 
#define UBX_TX_CFG_RST_MODE_SOFTWARE   1
 
#define UBX_CFG_KEY_CFG_UART1_BAUDRATE   0x40520001
 
#define UBX_CFG_KEY_CFG_UART1_STOPBITS   0x20520002
 
#define UBX_CFG_KEY_CFG_UART1_DATABITS   0x20520003
 
#define UBX_CFG_KEY_CFG_UART1_PARITY   0x20520004
 
#define UBX_CFG_KEY_CFG_UART1_ENABLED   0x20520005
 
#define UBX_CFG_KEY_CFG_UART1_REMAP   0x20520006
 
#define UBX_CFG_KEY_CFG_UART1INPROT_UBX   0x10730001
 
#define UBX_CFG_KEY_CFG_UART1INPROT_NMEA   0x10730002
 
#define UBX_CFG_KEY_CFG_UART1INPROT_RTCM3X   0x10730004
 
#define UBX_CFG_KEY_CFG_UART1OUTPROT_UBX   0x10740001
 
#define UBX_CFG_KEY_CFG_UART1OUTPROT_NMEA   0x10740002
 
#define UBX_CFG_KEY_CFG_UART1OUTPROT_RTCM3X   0x10740004
 
#define UBX_CFG_KEY_CFG_UART2_BAUDRATE   0x40530001
 
#define UBX_CFG_KEY_CFG_UART2_STOPBITS   0x20530002
 
#define UBX_CFG_KEY_CFG_UART2_DATABITS   0x20530003
 
#define UBX_CFG_KEY_CFG_UART2_PARITY   0x20530004
 
#define UBX_CFG_KEY_CFG_UART2_ENABLED   0x20530005
 
#define UBX_CFG_KEY_CFG_UART2_REMAP   0x20530006
 
#define UBX_CFG_KEY_CFG_UART2INPROT_UBX   0x10750001
 
#define UBX_CFG_KEY_CFG_UART2INPROT_NMEA   0x10750002
 
#define UBX_CFG_KEY_CFG_UART2INPROT_RTCM3X   0x10750004
 
#define UBX_CFG_KEY_CFG_UART2OUTPROT_UBX   0x10760001
 
#define UBX_CFG_KEY_CFG_UART2OUTPROT_NMEA   0x10760002
 
#define UBX_CFG_KEY_CFG_UART2OUTPROT_RTCM3X   0x10760004
 
#define UBX_CFG_KEY_CFG_USB_ENABLED   0x10650001
 
#define UBX_CFG_KEY_CFG_USBINPROT_UBX   0x10770001
 
#define UBX_CFG_KEY_CFG_USBINPROT_NMEA   0x10770002
 
#define UBX_CFG_KEY_CFG_USBINPROT_RTCM3X   0x10770004
 
#define UBX_CFG_KEY_CFG_USBOUTPROT_UBX   0x10780001
 
#define UBX_CFG_KEY_CFG_USBOUTPROT_NMEA   0x10780002
 
#define UBX_CFG_KEY_CFG_USBOUTPROT_RTCM3X   0x10780004
 
#define UBX_CFG_KEY_CFG_SPIINPROT_UBX   0x10790001
 
#define UBX_CFG_KEY_CFG_SPIINPROT_NMEA   0x10790002
 
#define UBX_CFG_KEY_CFG_SPIINPROT_RTCM3X   0x10790004
 
#define UBX_CFG_KEY_CFG_SPIOUTPROT_UBX   0x107a0001
 
#define UBX_CFG_KEY_CFG_SPIOUTPROT_NMEA   0x107a0002
 
#define UBX_CFG_KEY_CFG_SPIOUTPROT_RTCM3X   0x107a0004
 
#define UBX_CFG_KEY_NAVHPG_DGNSSMODE   0x20140011
 
#define UBX_CFG_KEY_NAVSPG_FIXMODE   0x20110011
 
#define UBX_CFG_KEY_NAVSPG_UTCSTANDARD   0x2011001c
 
#define UBX_CFG_KEY_NAVSPG_DYNMODEL   0x20110021
 
#define UBX_CFG_KEY_ODO_USE_ODO   0x10220001
 
#define UBX_CFG_KEY_ODO_USE_COG   0x10220002
 
#define UBX_CFG_KEY_ODO_OUTLPVEL   0x10220003
 
#define UBX_CFG_KEY_ODO_OUTLPCOG   0x10220004
 
#define UBX_CFG_KEY_RATE_MEAS   0x30210001
 
#define UBX_CFG_KEY_RATE_NAV   0x30210002
 
#define UBX_CFG_KEY_RATE_TIMEREF   0x20210003
 
#define UBX_CFG_KEY_TMODE_MODE   0x20030001
 
#define UBX_CFG_KEY_TMODE_POS_TYPE   0x20030002
 
#define UBX_CFG_KEY_TMODE_LAT   0x40030009
 
#define UBX_CFG_KEY_TMODE_LON   0x4003000a
 
#define UBX_CFG_KEY_TMODE_HEIGHT   0x4003000b
 
#define UBX_CFG_KEY_TMODE_LAT_HP   0x2003000c
 
#define UBX_CFG_KEY_TMODE_LON_HP   0x2003000d
 
#define UBX_CFG_KEY_TMODE_HEIGHT_HP   0x2003000e
 
#define UBX_CFG_KEY_TMODE_FIXED_POS_ACC   0x4003000f
 
#define UBX_CFG_KEY_TMODE_SVIN_MIN_DUR   0x40030010
 
#define UBX_CFG_KEY_TMODE_SVIN_ACC_LIMIT   0x40030011
 
#define UBX_CFG_KEY_MSGOUT_UBX_MON_RF_I2C   0x20910359
 
#define UBX_CFG_KEY_MSGOUT_UBX_NAV_SVIN_I2C   0x20910088
 
#define UBX_CFG_KEY_MSGOUT_UBX_NAV_SAT_I2C   0x20910015
 
#define UBX_CFG_KEY_MSGOUT_UBX_NAV_DOP_I2C   0x20910038
 
#define UBX_CFG_KEY_MSGOUT_UBX_NAV_PVT_I2C   0x20910006
 
#define UBX_CFG_KEY_MSGOUT_RTCM_3X_TYPE1005_I2C   0x209102bd
 
#define UBX_CFG_KEY_MSGOUT_RTCM_3X_TYPE1077_I2C   0x209102cc
 
#define UBX_CFG_KEY_MSGOUT_RTCM_3X_TYPE1087_I2C   0x209102d1
 
#define UBX_CFG_KEY_MSGOUT_RTCM_3X_TYPE1097_I2C   0x20910318
 
#define UBX_CFG_KEY_MSGOUT_RTCM_3X_TYPE1127_I2C   0x209102d6
 
#define UBX_CFG_KEY_MSGOUT_RTCM_3X_TYPE1230_I2C   0x20910303
 
#define UBX_CFG_KEY_SPI_ENABLED   0x10640006
 
#define UBX_CFG_KEY_SPI_MAXFF   0x20640001
 
#define UBX_PAYLOAD_RX_NAV_PVT_SIZE_UBX7   (sizeof(ubx_payload_rx_nav_pvt_t) - 8)
 
#define UBX_PAYLOAD_RX_NAV_PVT_SIZE_UBX8   (sizeof(ubx_payload_rx_nav_pvt_t))
 
#define UBX_CFG_LAYER_RAM   (1 << 0)
 
#define UBX_CFG_LAYER_BBR   (1 << 1)
 
#define UBX_CFG_LAYER_FLASH   (1 << 2)
 

Enumerations

enum  ubx_decode_state_t {
  UBX_DECODE_SYNC1 = 0, UBX_DECODE_SYNC2, UBX_DECODE_CLASS, UBX_DECODE_ID,
  UBX_DECODE_LENGTH1, UBX_DECODE_LENGTH2, UBX_DECODE_PAYLOAD, UBX_DECODE_CHKSUM1,
  UBX_DECODE_CHKSUM2, UBX_DECODE_RTCM3
}
 
enum  ubx_rxmsg_state_t { UBX_RXMSG_IGNORE = 0, UBX_RXMSG_HANDLE, UBX_RXMSG_DISABLE, UBX_RXMSG_ERROR_LENGTH }
 
enum  ubx_ack_state_t { UBX_ACK_IDLE = 0, UBX_ACK_WAITING, UBX_ACK_GOT_ACK, UBX_ACK_GOT_NAK }
 

Detailed Description

U-Blox protocol definition.

Following u-blox 6/7/8 Receiver Description including Prototol Specification.

Author
Thomas Gubler thoma.nosp@m.sgub.nosp@m.ler@s.nosp@m.tude.nosp@m.nt.et.nosp@m.hz.c.nosp@m.h
Julian Oes julia.nosp@m.n@oe.nosp@m.s.ch
Anton Babushkin anton.nosp@m..bab.nosp@m.ushki.nosp@m.n@me.nosp@m..com
Beat Küng beat-.nosp@m.kuen.nosp@m.g@gmx.nosp@m..net
Hannes Delago (rework, add ubx7+ compatibility)

Definition in file ubx.h.

Macro Definition Documentation

◆ UBX_BAUDRATE_M8_AND_NEWER

#define UBX_BAUDRATE_M8_AND_NEWER   115200

baudrate for M8+ boards

Definition at line 192 of file ubx.h.

Referenced by GPSDriverUBX::configure().

◆ UBX_CFG_KEY_CFG_SPIINPROT_NMEA

#define UBX_CFG_KEY_CFG_SPIINPROT_NMEA   0x10790002

Definition at line 251 of file ubx.h.

Referenced by GPSDriverUBX::configure().

◆ UBX_CFG_KEY_CFG_SPIINPROT_RTCM3X

#define UBX_CFG_KEY_CFG_SPIINPROT_RTCM3X   0x10790004

Definition at line 252 of file ubx.h.

Referenced by GPSDriverUBX::configure().

◆ UBX_CFG_KEY_CFG_SPIINPROT_UBX

#define UBX_CFG_KEY_CFG_SPIINPROT_UBX   0x10790001

Definition at line 250 of file ubx.h.

Referenced by GPSDriverUBX::configure().

◆ UBX_CFG_KEY_CFG_SPIOUTPROT_NMEA

#define UBX_CFG_KEY_CFG_SPIOUTPROT_NMEA   0x107a0002

Definition at line 254 of file ubx.h.

Referenced by GPSDriverUBX::configure().

◆ UBX_CFG_KEY_CFG_SPIOUTPROT_RTCM3X

#define UBX_CFG_KEY_CFG_SPIOUTPROT_RTCM3X   0x107a0004

Definition at line 255 of file ubx.h.

Referenced by GPSDriverUBX::configure().

◆ UBX_CFG_KEY_CFG_SPIOUTPROT_UBX

#define UBX_CFG_KEY_CFG_SPIOUTPROT_UBX   0x107a0001

Definition at line 253 of file ubx.h.

Referenced by GPSDriverUBX::configure().

◆ UBX_CFG_KEY_CFG_UART1_BAUDRATE

#define UBX_CFG_KEY_CFG_UART1_BAUDRATE   0x40520001

Definition at line 216 of file ubx.h.

Referenced by GPSDriverUBX::configure().

◆ UBX_CFG_KEY_CFG_UART1_DATABITS

#define UBX_CFG_KEY_CFG_UART1_DATABITS   0x20520003

Definition at line 218 of file ubx.h.

Referenced by GPSDriverUBX::configure().

◆ UBX_CFG_KEY_CFG_UART1_ENABLED

#define UBX_CFG_KEY_CFG_UART1_ENABLED   0x20520005

Definition at line 220 of file ubx.h.

◆ UBX_CFG_KEY_CFG_UART1_PARITY

#define UBX_CFG_KEY_CFG_UART1_PARITY   0x20520004

Definition at line 219 of file ubx.h.

Referenced by GPSDriverUBX::configure().

◆ UBX_CFG_KEY_CFG_UART1_REMAP

#define UBX_CFG_KEY_CFG_UART1_REMAP   0x20520006

Definition at line 221 of file ubx.h.

◆ UBX_CFG_KEY_CFG_UART1_STOPBITS

#define UBX_CFG_KEY_CFG_UART1_STOPBITS   0x20520002

Definition at line 217 of file ubx.h.

Referenced by GPSDriverUBX::configure().

◆ UBX_CFG_KEY_CFG_UART1INPROT_NMEA

#define UBX_CFG_KEY_CFG_UART1INPROT_NMEA   0x10730002

Definition at line 223 of file ubx.h.

Referenced by GPSDriverUBX::configure().

◆ UBX_CFG_KEY_CFG_UART1INPROT_RTCM3X

#define UBX_CFG_KEY_CFG_UART1INPROT_RTCM3X   0x10730004

Definition at line 224 of file ubx.h.

Referenced by GPSDriverUBX::configure().

◆ UBX_CFG_KEY_CFG_UART1INPROT_UBX

#define UBX_CFG_KEY_CFG_UART1INPROT_UBX   0x10730001

Definition at line 222 of file ubx.h.

Referenced by GPSDriverUBX::configure().

◆ UBX_CFG_KEY_CFG_UART1OUTPROT_NMEA

#define UBX_CFG_KEY_CFG_UART1OUTPROT_NMEA   0x10740002

Definition at line 226 of file ubx.h.

Referenced by GPSDriverUBX::configure().

◆ UBX_CFG_KEY_CFG_UART1OUTPROT_RTCM3X

#define UBX_CFG_KEY_CFG_UART1OUTPROT_RTCM3X   0x10740004

Definition at line 227 of file ubx.h.

Referenced by GPSDriverUBX::configure().

◆ UBX_CFG_KEY_CFG_UART1OUTPROT_UBX

#define UBX_CFG_KEY_CFG_UART1OUTPROT_UBX   0x10740001

Definition at line 225 of file ubx.h.

Referenced by GPSDriverUBX::configure().

◆ UBX_CFG_KEY_CFG_UART2_BAUDRATE

#define UBX_CFG_KEY_CFG_UART2_BAUDRATE   0x40530001

Definition at line 229 of file ubx.h.

◆ UBX_CFG_KEY_CFG_UART2_DATABITS

#define UBX_CFG_KEY_CFG_UART2_DATABITS   0x20530003

Definition at line 231 of file ubx.h.

◆ UBX_CFG_KEY_CFG_UART2_ENABLED

#define UBX_CFG_KEY_CFG_UART2_ENABLED   0x20530005

Definition at line 233 of file ubx.h.

◆ UBX_CFG_KEY_CFG_UART2_PARITY

#define UBX_CFG_KEY_CFG_UART2_PARITY   0x20530004

Definition at line 232 of file ubx.h.

◆ UBX_CFG_KEY_CFG_UART2_REMAP

#define UBX_CFG_KEY_CFG_UART2_REMAP   0x20530006

Definition at line 234 of file ubx.h.

◆ UBX_CFG_KEY_CFG_UART2_STOPBITS

#define UBX_CFG_KEY_CFG_UART2_STOPBITS   0x20530002

Definition at line 230 of file ubx.h.

◆ UBX_CFG_KEY_CFG_UART2INPROT_NMEA

#define UBX_CFG_KEY_CFG_UART2INPROT_NMEA   0x10750002

Definition at line 236 of file ubx.h.

◆ UBX_CFG_KEY_CFG_UART2INPROT_RTCM3X

#define UBX_CFG_KEY_CFG_UART2INPROT_RTCM3X   0x10750004

Definition at line 237 of file ubx.h.

◆ UBX_CFG_KEY_CFG_UART2INPROT_UBX

#define UBX_CFG_KEY_CFG_UART2INPROT_UBX   0x10750001

Definition at line 235 of file ubx.h.

◆ UBX_CFG_KEY_CFG_UART2OUTPROT_NMEA

#define UBX_CFG_KEY_CFG_UART2OUTPROT_NMEA   0x10760002

Definition at line 239 of file ubx.h.

◆ UBX_CFG_KEY_CFG_UART2OUTPROT_RTCM3X

#define UBX_CFG_KEY_CFG_UART2OUTPROT_RTCM3X   0x10760004

Definition at line 240 of file ubx.h.

◆ UBX_CFG_KEY_CFG_UART2OUTPROT_UBX

#define UBX_CFG_KEY_CFG_UART2OUTPROT_UBX   0x10760001

Definition at line 238 of file ubx.h.

◆ UBX_CFG_KEY_CFG_USB_ENABLED

#define UBX_CFG_KEY_CFG_USB_ENABLED   0x10650001

Definition at line 242 of file ubx.h.

◆ UBX_CFG_KEY_CFG_USBINPROT_NMEA

#define UBX_CFG_KEY_CFG_USBINPROT_NMEA   0x10770002

Definition at line 244 of file ubx.h.

Referenced by GPSDriverUBX::configure().

◆ UBX_CFG_KEY_CFG_USBINPROT_RTCM3X

#define UBX_CFG_KEY_CFG_USBINPROT_RTCM3X   0x10770004

Definition at line 245 of file ubx.h.

Referenced by GPSDriverUBX::configure().

◆ UBX_CFG_KEY_CFG_USBINPROT_UBX

#define UBX_CFG_KEY_CFG_USBINPROT_UBX   0x10770001

Definition at line 243 of file ubx.h.

Referenced by GPSDriverUBX::configure().

◆ UBX_CFG_KEY_CFG_USBOUTPROT_NMEA

#define UBX_CFG_KEY_CFG_USBOUTPROT_NMEA   0x10780002

Definition at line 247 of file ubx.h.

Referenced by GPSDriverUBX::configure().

◆ UBX_CFG_KEY_CFG_USBOUTPROT_RTCM3X

#define UBX_CFG_KEY_CFG_USBOUTPROT_RTCM3X   0x10780004

Definition at line 248 of file ubx.h.

Referenced by GPSDriverUBX::configure().

◆ UBX_CFG_KEY_CFG_USBOUTPROT_UBX

#define UBX_CFG_KEY_CFG_USBOUTPROT_UBX   0x10780001

Definition at line 246 of file ubx.h.

Referenced by GPSDriverUBX::configure().

◆ UBX_CFG_KEY_MSGOUT_RTCM_3X_TYPE1005_I2C

#define UBX_CFG_KEY_MSGOUT_RTCM_3X_TYPE1005_I2C   0x209102bd

Definition at line 289 of file ubx.h.

Referenced by GPSDriverUBX::activateRTCMOutput(), and GPSDriverUBX::restartSurveyIn().

◆ UBX_CFG_KEY_MSGOUT_RTCM_3X_TYPE1077_I2C

#define UBX_CFG_KEY_MSGOUT_RTCM_3X_TYPE1077_I2C   0x209102cc

Definition at line 290 of file ubx.h.

Referenced by GPSDriverUBX::activateRTCMOutput(), and GPSDriverUBX::restartSurveyIn().

◆ UBX_CFG_KEY_MSGOUT_RTCM_3X_TYPE1087_I2C

#define UBX_CFG_KEY_MSGOUT_RTCM_3X_TYPE1087_I2C   0x209102d1

Definition at line 291 of file ubx.h.

Referenced by GPSDriverUBX::activateRTCMOutput(), and GPSDriverUBX::restartSurveyIn().

◆ UBX_CFG_KEY_MSGOUT_RTCM_3X_TYPE1097_I2C

#define UBX_CFG_KEY_MSGOUT_RTCM_3X_TYPE1097_I2C   0x20910318

Definition at line 292 of file ubx.h.

Referenced by GPSDriverUBX::activateRTCMOutput(), and GPSDriverUBX::restartSurveyIn().

◆ UBX_CFG_KEY_MSGOUT_RTCM_3X_TYPE1127_I2C

#define UBX_CFG_KEY_MSGOUT_RTCM_3X_TYPE1127_I2C   0x209102d6

Definition at line 293 of file ubx.h.

Referenced by GPSDriverUBX::activateRTCMOutput(), and GPSDriverUBX::restartSurveyIn().

◆ UBX_CFG_KEY_MSGOUT_RTCM_3X_TYPE1230_I2C

#define UBX_CFG_KEY_MSGOUT_RTCM_3X_TYPE1230_I2C   0x20910303

Definition at line 294 of file ubx.h.

Referenced by GPSDriverUBX::activateRTCMOutput(), and GPSDriverUBX::restartSurveyIn().

◆ UBX_CFG_KEY_MSGOUT_UBX_MON_RF_I2C

#define UBX_CFG_KEY_MSGOUT_UBX_MON_RF_I2C   0x20910359

Definition at line 284 of file ubx.h.

Referenced by GPSDriverUBX::configureDevice().

◆ UBX_CFG_KEY_MSGOUT_UBX_NAV_DOP_I2C

#define UBX_CFG_KEY_MSGOUT_UBX_NAV_DOP_I2C   0x20910038

Definition at line 287 of file ubx.h.

Referenced by GPSDriverUBX::configureDevice().

◆ UBX_CFG_KEY_MSGOUT_UBX_NAV_PVT_I2C

#define UBX_CFG_KEY_MSGOUT_UBX_NAV_PVT_I2C   0x20910006

Definition at line 288 of file ubx.h.

Referenced by GPSDriverUBX::configureDevice().

◆ UBX_CFG_KEY_MSGOUT_UBX_NAV_SAT_I2C

#define UBX_CFG_KEY_MSGOUT_UBX_NAV_SAT_I2C   0x20910015

Definition at line 286 of file ubx.h.

Referenced by GPSDriverUBX::configureDevice().

◆ UBX_CFG_KEY_MSGOUT_UBX_NAV_SVIN_I2C

#define UBX_CFG_KEY_MSGOUT_UBX_NAV_SVIN_I2C   0x20910088

Definition at line 285 of file ubx.h.

Referenced by GPSDriverUBX::activateRTCMOutput(), and GPSDriverUBX::restartSurveyIn().

◆ UBX_CFG_KEY_NAVHPG_DGNSSMODE

#define UBX_CFG_KEY_NAVHPG_DGNSSMODE   0x20140011

Definition at line 257 of file ubx.h.

Referenced by GPSDriverUBX::configureDevice().

◆ UBX_CFG_KEY_NAVSPG_DYNMODEL

#define UBX_CFG_KEY_NAVSPG_DYNMODEL   0x20110021

Definition at line 261 of file ubx.h.

Referenced by GPSDriverUBX::configureDevice().

◆ UBX_CFG_KEY_NAVSPG_FIXMODE

#define UBX_CFG_KEY_NAVSPG_FIXMODE   0x20110011

Definition at line 259 of file ubx.h.

Referenced by GPSDriverUBX::configureDevice().

◆ UBX_CFG_KEY_NAVSPG_UTCSTANDARD

#define UBX_CFG_KEY_NAVSPG_UTCSTANDARD   0x2011001c

Definition at line 260 of file ubx.h.

Referenced by GPSDriverUBX::configureDevice().

◆ UBX_CFG_KEY_ODO_OUTLPCOG

#define UBX_CFG_KEY_ODO_OUTLPCOG   0x10220004

Definition at line 266 of file ubx.h.

Referenced by GPSDriverUBX::configureDevice().

◆ UBX_CFG_KEY_ODO_OUTLPVEL

#define UBX_CFG_KEY_ODO_OUTLPVEL   0x10220003

Definition at line 265 of file ubx.h.

Referenced by GPSDriverUBX::configureDevice().

◆ UBX_CFG_KEY_ODO_USE_COG

#define UBX_CFG_KEY_ODO_USE_COG   0x10220002

Definition at line 264 of file ubx.h.

Referenced by GPSDriverUBX::configureDevice().

◆ UBX_CFG_KEY_ODO_USE_ODO

#define UBX_CFG_KEY_ODO_USE_ODO   0x10220001

Definition at line 263 of file ubx.h.

Referenced by GPSDriverUBX::configureDevice().

◆ UBX_CFG_KEY_RATE_MEAS

#define UBX_CFG_KEY_RATE_MEAS   0x30210001

Definition at line 268 of file ubx.h.

Referenced by GPSDriverUBX::activateRTCMOutput(), and GPSDriverUBX::configureDevice().

◆ UBX_CFG_KEY_RATE_NAV

#define UBX_CFG_KEY_RATE_NAV   0x30210002

Definition at line 269 of file ubx.h.

Referenced by GPSDriverUBX::configureDevice().

◆ UBX_CFG_KEY_RATE_TIMEREF

#define UBX_CFG_KEY_RATE_TIMEREF   0x20210003

Definition at line 270 of file ubx.h.

Referenced by GPSDriverUBX::configureDevice().

◆ UBX_CFG_KEY_SPI_ENABLED

#define UBX_CFG_KEY_SPI_ENABLED   0x10640006

Definition at line 296 of file ubx.h.

Referenced by GPSDriverUBX::configure().

◆ UBX_CFG_KEY_SPI_MAXFF

#define UBX_CFG_KEY_SPI_MAXFF   0x20640001

Definition at line 297 of file ubx.h.

Referenced by GPSDriverUBX::configure().

◆ UBX_CFG_KEY_TMODE_FIXED_POS_ACC

#define UBX_CFG_KEY_TMODE_FIXED_POS_ACC   0x4003000f

Definition at line 280 of file ubx.h.

Referenced by GPSDriverUBX::restartSurveyIn().

◆ UBX_CFG_KEY_TMODE_HEIGHT

#define UBX_CFG_KEY_TMODE_HEIGHT   0x4003000b

Definition at line 276 of file ubx.h.

Referenced by GPSDriverUBX::restartSurveyIn().

◆ UBX_CFG_KEY_TMODE_HEIGHT_HP

#define UBX_CFG_KEY_TMODE_HEIGHT_HP   0x2003000e

Definition at line 279 of file ubx.h.

Referenced by GPSDriverUBX::restartSurveyIn().

◆ UBX_CFG_KEY_TMODE_LAT

#define UBX_CFG_KEY_TMODE_LAT   0x40030009

Definition at line 274 of file ubx.h.

Referenced by GPSDriverUBX::restartSurveyIn().

◆ UBX_CFG_KEY_TMODE_LAT_HP

#define UBX_CFG_KEY_TMODE_LAT_HP   0x2003000c

Definition at line 277 of file ubx.h.

Referenced by GPSDriverUBX::restartSurveyIn().

◆ UBX_CFG_KEY_TMODE_LON

#define UBX_CFG_KEY_TMODE_LON   0x4003000a

Definition at line 275 of file ubx.h.

Referenced by GPSDriverUBX::restartSurveyIn().

◆ UBX_CFG_KEY_TMODE_LON_HP

#define UBX_CFG_KEY_TMODE_LON_HP   0x2003000d

Definition at line 278 of file ubx.h.

Referenced by GPSDriverUBX::restartSurveyIn().

◆ UBX_CFG_KEY_TMODE_MODE

#define UBX_CFG_KEY_TMODE_MODE   0x20030001

Definition at line 272 of file ubx.h.

Referenced by GPSDriverUBX::restartSurveyIn().

◆ UBX_CFG_KEY_TMODE_POS_TYPE

#define UBX_CFG_KEY_TMODE_POS_TYPE   0x20030002

Definition at line 273 of file ubx.h.

Referenced by GPSDriverUBX::restartSurveyIn().

◆ UBX_CFG_KEY_TMODE_SVIN_ACC_LIMIT

#define UBX_CFG_KEY_TMODE_SVIN_ACC_LIMIT   0x40030011

Definition at line 282 of file ubx.h.

Referenced by GPSDriverUBX::restartSurveyIn().

◆ UBX_CFG_KEY_TMODE_SVIN_MIN_DUR

#define UBX_CFG_KEY_TMODE_SVIN_MIN_DUR   0x40030010

Definition at line 281 of file ubx.h.

Referenced by GPSDriverUBX::restartSurveyIn().

◆ UBX_CFG_LAYER_BBR

#define UBX_CFG_LAYER_BBR   (1 << 1)

Definition at line 622 of file ubx.h.

◆ UBX_CFG_LAYER_FLASH

#define UBX_CFG_LAYER_FLASH   (1 << 2)

Definition at line 623 of file ubx.h.

◆ UBX_CFG_LAYER_RAM

#define UBX_CFG_LAYER_RAM   (1 << 0)

Definition at line 621 of file ubx.h.

Referenced by GPSDriverUBX::initCfgValset().

◆ UBX_CLASS_ACK

#define UBX_CLASS_ACK   0x05

Definition at line 62 of file ubx.h.

◆ UBX_CLASS_CFG

#define UBX_CLASS_CFG   0x06

Definition at line 63 of file ubx.h.

◆ UBX_CLASS_INF

#define UBX_CLASS_INF   0x04

Definition at line 61 of file ubx.h.

◆ UBX_CLASS_MON

#define UBX_CLASS_MON   0x0A

Definition at line 64 of file ubx.h.

◆ UBX_CLASS_NAV

#define UBX_CLASS_NAV   0x01

Definition at line 60 of file ubx.h.

◆ UBX_CLASS_RTCM3

#define UBX_CLASS_RTCM3   0xF5

Definition at line 65 of file ubx.h.

◆ UBX_ID_ACK_ACK

#define UBX_ID_ACK_ACK   0x01

Definition at line 83 of file ubx.h.

◆ UBX_ID_ACK_NAK

#define UBX_ID_ACK_NAK   0x00

Definition at line 82 of file ubx.h.

◆ UBX_ID_CFG_CFG

#define UBX_ID_CFG_CFG   0x09

Definition at line 87 of file ubx.h.

◆ UBX_ID_CFG_MSG

#define UBX_ID_CFG_MSG   0x01

Definition at line 85 of file ubx.h.

◆ UBX_ID_CFG_NAV5

#define UBX_ID_CFG_NAV5   0x24

Definition at line 88 of file ubx.h.

◆ UBX_ID_CFG_PRT

#define UBX_ID_CFG_PRT   0x00

Definition at line 84 of file ubx.h.

◆ UBX_ID_CFG_RATE

#define UBX_ID_CFG_RATE   0x08

Definition at line 86 of file ubx.h.

◆ UBX_ID_CFG_RST

#define UBX_ID_CFG_RST   0x04

Definition at line 89 of file ubx.h.

◆ UBX_ID_CFG_SBAS

#define UBX_ID_CFG_SBAS   0x16

Definition at line 90 of file ubx.h.

◆ UBX_ID_CFG_TMODE3

#define UBX_ID_CFG_TMODE3   0x71

Definition at line 91 of file ubx.h.

◆ UBX_ID_CFG_VALDEL

#define UBX_ID_CFG_VALDEL   0x8C

Definition at line 94 of file ubx.h.

◆ UBX_ID_CFG_VALGET

#define UBX_ID_CFG_VALGET   0x8B

Definition at line 93 of file ubx.h.

◆ UBX_ID_CFG_VALSET

#define UBX_ID_CFG_VALSET   0x8A

Definition at line 92 of file ubx.h.

◆ UBX_ID_INF_DEBUG

#define UBX_ID_INF_DEBUG   0x04

Definition at line 78 of file ubx.h.

◆ UBX_ID_INF_ERROR

#define UBX_ID_INF_ERROR   0x00

Definition at line 79 of file ubx.h.

◆ UBX_ID_INF_NOTICE

#define UBX_ID_INF_NOTICE   0x02

Definition at line 80 of file ubx.h.

◆ UBX_ID_INF_WARNING

#define UBX_ID_INF_WARNING   0x01

Definition at line 81 of file ubx.h.

◆ UBX_ID_MON_HW

#define UBX_ID_MON_HW   0x09

Definition at line 96 of file ubx.h.

◆ UBX_ID_MON_RF

#define UBX_ID_MON_RF   0x38

Definition at line 97 of file ubx.h.

◆ UBX_ID_MON_VER

#define UBX_ID_MON_VER   0x04

Definition at line 95 of file ubx.h.

◆ UBX_ID_NAV_DOP

#define UBX_ID_NAV_DOP   0x04

Definition at line 69 of file ubx.h.

◆ UBX_ID_NAV_POSLLH

#define UBX_ID_NAV_POSLLH   0x02

Definition at line 68 of file ubx.h.

◆ UBX_ID_NAV_PVT

#define UBX_ID_NAV_PVT   0x07

Definition at line 71 of file ubx.h.

◆ UBX_ID_NAV_RELPOSNED

#define UBX_ID_NAV_RELPOSNED   0x3C

Definition at line 77 of file ubx.h.

◆ UBX_ID_NAV_SAT

#define UBX_ID_NAV_SAT   0x35

Definition at line 75 of file ubx.h.

◆ UBX_ID_NAV_SOL

#define UBX_ID_NAV_SOL   0x06

Definition at line 70 of file ubx.h.

◆ UBX_ID_NAV_SVIN

#define UBX_ID_NAV_SVIN   0x3B

Definition at line 76 of file ubx.h.

◆ UBX_ID_NAV_SVINFO

#define UBX_ID_NAV_SVINFO   0x30

Definition at line 74 of file ubx.h.

◆ UBX_ID_NAV_TIMEUTC

#define UBX_ID_NAV_TIMEUTC   0x21

Definition at line 73 of file ubx.h.

◆ UBX_ID_NAV_VELNED

#define UBX_ID_NAV_VELNED   0x12

Definition at line 72 of file ubx.h.

◆ UBX_ID_RTCM3_1005

#define UBX_ID_RTCM3_1005   0x05

Stationary RTK reference station ARP.

Definition at line 102 of file ubx.h.

◆ UBX_ID_RTCM3_1074

#define UBX_ID_RTCM3_1074   0x4A

GPS MSM4.

Definition at line 103 of file ubx.h.

◆ UBX_ID_RTCM3_1077

#define UBX_ID_RTCM3_1077   0x4D

GPS MSM7.

Definition at line 104 of file ubx.h.

◆ UBX_ID_RTCM3_1084

#define UBX_ID_RTCM3_1084   0x54

GLONASS MSM4.

Definition at line 105 of file ubx.h.

◆ UBX_ID_RTCM3_1087

#define UBX_ID_RTCM3_1087   0x57

GLONASS MSM7.

Definition at line 106 of file ubx.h.

◆ UBX_ID_RTCM3_1094

#define UBX_ID_RTCM3_1094   0x5E

Galileo MSM4.

Definition at line 107 of file ubx.h.

◆ UBX_ID_RTCM3_1097

#define UBX_ID_RTCM3_1097   0x61

Galileo MSM7.

Definition at line 108 of file ubx.h.

◆ UBX_ID_RTCM3_1124

#define UBX_ID_RTCM3_1124   0x7C

BeiDou MSM4.

Definition at line 109 of file ubx.h.

◆ UBX_ID_RTCM3_1127

#define UBX_ID_RTCM3_1127   0x7F

BeiDou MSM7.

Definition at line 110 of file ubx.h.

◆ UBX_ID_RTCM3_1230

#define UBX_ID_RTCM3_1230   0xE6

GLONASS code-phase biases.

Definition at line 111 of file ubx.h.

◆ UBX_ID_RTCM3_4072

#define UBX_ID_RTCM3_4072   0xFE

Reference station PVT (u-blox proprietary RTCM Message) - Used for moving baseline.

Definition at line 112 of file ubx.h.

◆ UBX_MSG_ACK_ACK

#define UBX_MSG_ACK_ACK   ((UBX_CLASS_ACK) | UBX_ID_ACK_ACK << 8)

Definition at line 131 of file ubx.h.

Referenced by GPSDriverUBX::payloadRxDone(), and GPSDriverUBX::payloadRxInit().

◆ UBX_MSG_ACK_NAK

#define UBX_MSG_ACK_NAK   ((UBX_CLASS_ACK) | UBX_ID_ACK_NAK << 8)

Definition at line 130 of file ubx.h.

Referenced by GPSDriverUBX::payloadRxDone(), and GPSDriverUBX::payloadRxInit().

◆ UBX_MSG_CFG_CFG

#define UBX_MSG_CFG_CFG   ((UBX_CLASS_CFG) | UBX_ID_CFG_CFG << 8)

Definition at line 135 of file ubx.h.

◆ UBX_MSG_CFG_MSG

◆ UBX_MSG_CFG_NAV5

#define UBX_MSG_CFG_NAV5   ((UBX_CLASS_CFG) | UBX_ID_CFG_NAV5 << 8)

Definition at line 136 of file ubx.h.

Referenced by GPSDriverUBX::configureDevicePreV27().

◆ UBX_MSG_CFG_PRT

#define UBX_MSG_CFG_PRT   ((UBX_CLASS_CFG) | UBX_ID_CFG_PRT << 8)

Definition at line 132 of file ubx.h.

Referenced by GPSDriverUBX::configure().

◆ UBX_MSG_CFG_RATE

#define UBX_MSG_CFG_RATE   ((UBX_CLASS_CFG) | UBX_ID_CFG_RATE << 8)

Definition at line 134 of file ubx.h.

Referenced by GPSDriverUBX::activateRTCMOutput(), and GPSDriverUBX::configureDevicePreV27().

◆ UBX_MSG_CFG_RST

#define UBX_MSG_CFG_RST   ((UBX_CLASS_CFG) | UBX_ID_CFG_RST << 8)

Definition at line 137 of file ubx.h.

Referenced by GPSDriverUBX::reset().

◆ UBX_MSG_CFG_SBAS

#define UBX_MSG_CFG_SBAS   ((UBX_CLASS_CFG) | UBX_ID_CFG_SBAS << 8)

Definition at line 138 of file ubx.h.

◆ UBX_MSG_CFG_TMODE3

#define UBX_MSG_CFG_TMODE3   ((UBX_CLASS_CFG) | UBX_ID_CFG_TMODE3 << 8)

Definition at line 139 of file ubx.h.

Referenced by GPSDriverUBX::restartSurveyInPreV27().

◆ UBX_MSG_CFG_VALDEL

#define UBX_MSG_CFG_VALDEL   ((UBX_CLASS_CFG) | UBX_ID_CFG_VALDEL << 8)

Definition at line 142 of file ubx.h.

◆ UBX_MSG_CFG_VALGET

#define UBX_MSG_CFG_VALGET   ((UBX_CLASS_CFG) | UBX_ID_CFG_VALGET << 8)

Definition at line 140 of file ubx.h.

◆ UBX_MSG_CFG_VALSET

◆ UBX_MSG_INF_DEBUG

#define UBX_MSG_INF_DEBUG   ((UBX_CLASS_INF) | UBX_ID_INF_DEBUG << 8)

Definition at line 126 of file ubx.h.

Referenced by GPSDriverUBX::payloadRxDone(), and GPSDriverUBX::payloadRxInit().

◆ UBX_MSG_INF_ERROR

#define UBX_MSG_INF_ERROR   ((UBX_CLASS_INF) | UBX_ID_INF_ERROR << 8)

Definition at line 127 of file ubx.h.

Referenced by GPSDriverUBX::payloadRxDone(), and GPSDriverUBX::payloadRxInit().

◆ UBX_MSG_INF_NOTICE

#define UBX_MSG_INF_NOTICE   ((UBX_CLASS_INF) | UBX_ID_INF_NOTICE << 8)

Definition at line 128 of file ubx.h.

Referenced by GPSDriverUBX::payloadRxDone(), and GPSDriverUBX::payloadRxInit().

◆ UBX_MSG_INF_WARNING

#define UBX_MSG_INF_WARNING   ((UBX_CLASS_INF) | UBX_ID_INF_WARNING << 8)

Definition at line 129 of file ubx.h.

Referenced by GPSDriverUBX::payloadRxDone(), and GPSDriverUBX::payloadRxInit().

◆ UBX_MSG_MON_HW

#define UBX_MSG_MON_HW   ((UBX_CLASS_MON) | UBX_ID_MON_HW << 8)

◆ UBX_MSG_MON_RF

#define UBX_MSG_MON_RF   ((UBX_CLASS_MON) | UBX_ID_MON_RF << 8)

Definition at line 145 of file ubx.h.

Referenced by GPSDriverUBX::payloadRxDone(), and GPSDriverUBX::payloadRxInit().

◆ UBX_MSG_MON_VER

#define UBX_MSG_MON_VER   ((UBX_CLASS_MON) | UBX_ID_MON_VER << 8)

◆ UBX_MSG_NAV_DOP

#define UBX_MSG_NAV_DOP   ((UBX_CLASS_NAV) | UBX_ID_NAV_DOP << 8)

◆ UBX_MSG_NAV_POSLLH

#define UBX_MSG_NAV_POSLLH   ((UBX_CLASS_NAV) | UBX_ID_NAV_POSLLH << 8)

◆ UBX_MSG_NAV_PVT

#define UBX_MSG_NAV_PVT   ((UBX_CLASS_NAV) | UBX_ID_NAV_PVT << 8)

◆ UBX_MSG_NAV_RELPOSNED

#define UBX_MSG_NAV_RELPOSNED   ((UBX_CLASS_NAV) | UBX_ID_NAV_RELPOSNED << 8)

Definition at line 125 of file ubx.h.

◆ UBX_MSG_NAV_SAT

#define UBX_MSG_NAV_SAT   ((UBX_CLASS_NAV) | UBX_ID_NAV_SAT << 8)

◆ UBX_MSG_NAV_SOL

#define UBX_MSG_NAV_SOL   ((UBX_CLASS_NAV) | UBX_ID_NAV_SOL << 8)

◆ UBX_MSG_NAV_SVIN

◆ UBX_MSG_NAV_SVINFO

◆ UBX_MSG_NAV_TIMEUTC

#define UBX_MSG_NAV_TIMEUTC   ((UBX_CLASS_NAV) | UBX_ID_NAV_TIMEUTC << 8)

◆ UBX_MSG_NAV_VELNED

#define UBX_MSG_NAV_VELNED   ((UBX_CLASS_NAV) | UBX_ID_NAV_VELNED << 8)

◆ UBX_MSG_RTCM3_1005

#define UBX_MSG_RTCM3_1005   ((UBX_CLASS_RTCM3) | UBX_ID_RTCM3_1005 << 8)

Definition at line 146 of file ubx.h.

Referenced by GPSDriverUBX::activateRTCMOutput(), and GPSDriverUBX::restartSurveyInPreV27().

◆ UBX_MSG_RTCM3_1074

#define UBX_MSG_RTCM3_1074   ((UBX_CLASS_RTCM3) | UBX_ID_RTCM3_1074 << 8)

Definition at line 149 of file ubx.h.

◆ UBX_MSG_RTCM3_1077

#define UBX_MSG_RTCM3_1077   ((UBX_CLASS_RTCM3) | UBX_ID_RTCM3_1077 << 8)

Definition at line 147 of file ubx.h.

Referenced by GPSDriverUBX::activateRTCMOutput(), and GPSDriverUBX::restartSurveyInPreV27().

◆ UBX_MSG_RTCM3_1084

#define UBX_MSG_RTCM3_1084   ((UBX_CLASS_RTCM3) | UBX_ID_RTCM3_1084 << 8)

Definition at line 150 of file ubx.h.

◆ UBX_MSG_RTCM3_1087

#define UBX_MSG_RTCM3_1087   ((UBX_CLASS_RTCM3) | UBX_ID_RTCM3_1087 << 8)

Definition at line 148 of file ubx.h.

Referenced by GPSDriverUBX::activateRTCMOutput(), and GPSDriverUBX::restartSurveyInPreV27().

◆ UBX_MSG_RTCM3_1094

#define UBX_MSG_RTCM3_1094   ((UBX_CLASS_RTCM3) | UBX_ID_RTCM3_1094 << 8)

Definition at line 151 of file ubx.h.

◆ UBX_MSG_RTCM3_1097

#define UBX_MSG_RTCM3_1097   ((UBX_CLASS_RTCM3) | UBX_ID_RTCM3_1097 << 8)

Definition at line 152 of file ubx.h.

Referenced by GPSDriverUBX::activateRTCMOutput(), and GPSDriverUBX::restartSurveyInPreV27().

◆ UBX_MSG_RTCM3_1124

#define UBX_MSG_RTCM3_1124   ((UBX_CLASS_RTCM3) | UBX_ID_RTCM3_1124 << 8)

Definition at line 153 of file ubx.h.

◆ UBX_MSG_RTCM3_1127

#define UBX_MSG_RTCM3_1127   ((UBX_CLASS_RTCM3) | UBX_ID_RTCM3_1127 << 8)

Definition at line 154 of file ubx.h.

Referenced by GPSDriverUBX::activateRTCMOutput(), and GPSDriverUBX::restartSurveyInPreV27().

◆ UBX_MSG_RTCM3_1230

#define UBX_MSG_RTCM3_1230   ((UBX_CLASS_RTCM3) | UBX_ID_RTCM3_1230 << 8)

Definition at line 155 of file ubx.h.

Referenced by GPSDriverUBX::activateRTCMOutput(), and GPSDriverUBX::restartSurveyInPreV27().

◆ UBX_MSG_RTCM3_4072

#define UBX_MSG_RTCM3_4072   ((UBX_CLASS_RTCM3) | UBX_ID_RTCM3_4072 << 8)

Definition at line 156 of file ubx.h.

◆ UBX_PAYLOAD_RX_NAV_PVT_SIZE_UBX7

#define UBX_PAYLOAD_RX_NAV_PVT_SIZE_UBX7   (sizeof(ubx_payload_rx_nav_pvt_t) - 8)

Definition at line 399 of file ubx.h.

Referenced by GPSDriverUBX::payloadRxInit().

◆ UBX_PAYLOAD_RX_NAV_PVT_SIZE_UBX8

#define UBX_PAYLOAD_RX_NAV_PVT_SIZE_UBX8   (sizeof(ubx_payload_rx_nav_pvt_t))

Definition at line 400 of file ubx.h.

Referenced by GPSDriverUBX::payloadRxInit().

◆ UBX_RX_NAV_PVT_FLAGS_CARRSOLN

#define UBX_RX_NAV_PVT_FLAGS_CARRSOLN   0xC0

Carrier phase range solution (RTK mode)

Definition at line 169 of file ubx.h.

◆ UBX_RX_NAV_PVT_FLAGS_DIFFSOLN

#define UBX_RX_NAV_PVT_FLAGS_DIFFSOLN   0x02

diffSoln (1 if differential corrections were applied)

Definition at line 166 of file ubx.h.

Referenced by GPSDriverUBX::payloadRxDone().

◆ UBX_RX_NAV_PVT_FLAGS_GNSSFIXOK

#define UBX_RX_NAV_PVT_FLAGS_GNSSFIXOK   0x01

gnssFixOK (A valid fix (i.e within DOP & accuracy masks))

Definition at line 165 of file ubx.h.

Referenced by GPSDriverUBX::payloadRxDone().

◆ UBX_RX_NAV_PVT_FLAGS_HEADVEHVALID

#define UBX_RX_NAV_PVT_FLAGS_HEADVEHVALID   0x20

headVehValid (Heading of vehicle is valid)

Definition at line 168 of file ubx.h.

◆ UBX_RX_NAV_PVT_FLAGS_PSMSTATE

#define UBX_RX_NAV_PVT_FLAGS_PSMSTATE   0x1C

psmState (Power Save Mode state (see Power Management))

Definition at line 167 of file ubx.h.

◆ UBX_RX_NAV_PVT_VALID_FULLYRESOLVED

#define UBX_RX_NAV_PVT_VALID_FULLYRESOLVED   0x04

fullyResolved (1 = UTC Time of Day has been fully resolved (no seconds uncertainty))

Definition at line 162 of file ubx.h.

Referenced by GPSDriverUBX::payloadRxDone().

◆ UBX_RX_NAV_PVT_VALID_VALIDDATE

#define UBX_RX_NAV_PVT_VALID_VALIDDATE   0x01

validDate (Valid UTC Date)

Definition at line 160 of file ubx.h.

Referenced by GPSDriverUBX::payloadRxDone().

◆ UBX_RX_NAV_PVT_VALID_VALIDTIME

#define UBX_RX_NAV_PVT_VALID_VALIDTIME   0x02

validTime (Valid UTC Time)

Definition at line 161 of file ubx.h.

Referenced by GPSDriverUBX::payloadRxDone().

◆ UBX_RX_NAV_TIMEUTC_VALID_UTCSTANDARD

#define UBX_RX_NAV_TIMEUTC_VALID_UTCSTANDARD   0xF0

utcStandard (0..15 = UTC standard identifier)

Definition at line 176 of file ubx.h.

◆ UBX_RX_NAV_TIMEUTC_VALID_VALIDKWN

#define UBX_RX_NAV_TIMEUTC_VALID_VALIDKWN   0x02

validWKN (1 = Valid Week Number)

Definition at line 174 of file ubx.h.

◆ UBX_RX_NAV_TIMEUTC_VALID_VALIDTOW

#define UBX_RX_NAV_TIMEUTC_VALID_VALIDTOW   0x01

validTOW (1 = Valid Time of Week)

Definition at line 173 of file ubx.h.

◆ UBX_RX_NAV_TIMEUTC_VALID_VALIDUTC

#define UBX_RX_NAV_TIMEUTC_VALID_VALIDUTC   0x04

validUTC (1 = Valid UTC Time)

Definition at line 175 of file ubx.h.

Referenced by GPSDriverUBX::payloadRxDone().

◆ UBX_SYNC1

#define UBX_SYNC1   0xB5

Definition at line 56 of file ubx.h.

Referenced by GPSDriverUBX::parseChar(), and GPSDriverUBX::sendMessage().

◆ UBX_SYNC2

#define UBX_SYNC2   0x62

Definition at line 57 of file ubx.h.

Referenced by GPSDriverUBX::parseChar(), and GPSDriverUBX::sendMessage().

◆ UBX_TX_CFG_NAV5_FIXMODE

#define UBX_TX_CFG_NAV5_FIXMODE   2

1 2D only, 2 3D only, 3 Auto 2D/3D

Definition at line 205 of file ubx.h.

Referenced by GPSDriverUBX::configureDevicePreV27().

◆ UBX_TX_CFG_NAV5_MASK

#define UBX_TX_CFG_NAV5_MASK   0x0005

Only update dynamic model and fix mode.

Definition at line 204 of file ubx.h.

Referenced by GPSDriverUBX::configureDevicePreV27().

◆ UBX_TX_CFG_PRT_BAUDRATE

#define UBX_TX_CFG_PRT_BAUDRATE   38400

choose 38400 as GPS baudrate (pre M8* boards only)

Definition at line 186 of file ubx.h.

Referenced by GPSDriverUBX::configure().

◆ UBX_TX_CFG_PRT_INPROTOMASK_GPS

#define UBX_TX_CFG_PRT_INPROTOMASK_GPS   ((1<<5) | 0x01)

RTCM3 in and UBX in.

Definition at line 187 of file ubx.h.

Referenced by GPSDriverUBX::configure().

◆ UBX_TX_CFG_PRT_INPROTOMASK_RTCM

#define UBX_TX_CFG_PRT_INPROTOMASK_RTCM   (0x01)

UBX in.

Definition at line 188 of file ubx.h.

Referenced by GPSDriverUBX::configure().

◆ UBX_TX_CFG_PRT_MODE

#define UBX_TX_CFG_PRT_MODE   0x000008D0

0b0000100011010000: 8N1

Definition at line 184 of file ubx.h.

Referenced by GPSDriverUBX::configure().

◆ UBX_TX_CFG_PRT_MODE_SPI

#define UBX_TX_CFG_PRT_MODE_SPI   0x00000100

Definition at line 185 of file ubx.h.

Referenced by GPSDriverUBX::configure().

◆ UBX_TX_CFG_PRT_OUTPROTOMASK_GPS

#define UBX_TX_CFG_PRT_OUTPROTOMASK_GPS   (0x01)

UBX out.

Definition at line 189 of file ubx.h.

Referenced by GPSDriverUBX::configure().

◆ UBX_TX_CFG_PRT_OUTPROTOMASK_RTCM

#define UBX_TX_CFG_PRT_OUTPROTOMASK_RTCM   ((1<<5) | 0x01)

RTCM3 out and UBX out.

Definition at line 190 of file ubx.h.

Referenced by GPSDriverUBX::configure().

◆ UBX_TX_CFG_PRT_PORTID

#define UBX_TX_CFG_PRT_PORTID   0x01

UART1.

Definition at line 181 of file ubx.h.

Referenced by GPSDriverUBX::configure().

◆ UBX_TX_CFG_PRT_PORTID_SPI

#define UBX_TX_CFG_PRT_PORTID_SPI   0x04

SPI.

Definition at line 183 of file ubx.h.

Referenced by GPSDriverUBX::configure().

◆ UBX_TX_CFG_PRT_PORTID_USB

#define UBX_TX_CFG_PRT_PORTID_USB   0x03

USB.

Definition at line 182 of file ubx.h.

Referenced by GPSDriverUBX::configure().

◆ UBX_TX_CFG_RATE_MEASINTERVAL

#define UBX_TX_CFG_RATE_MEASINTERVAL   200

200ms for 5Hz (F9* boards use 10Hz)

Definition at line 197 of file ubx.h.

Referenced by GPSDriverUBX::configureDevicePreV27().

◆ UBX_TX_CFG_RATE_NAVRATE

#define UBX_TX_CFG_RATE_NAVRATE   1

cannot be changed

Definition at line 198 of file ubx.h.

Referenced by GPSDriverUBX::activateRTCMOutput(), and GPSDriverUBX::configureDevicePreV27().

◆ UBX_TX_CFG_RATE_TIMEREF

#define UBX_TX_CFG_RATE_TIMEREF   0

0: UTC, 1: GPS time

Definition at line 199 of file ubx.h.

Referenced by GPSDriverUBX::activateRTCMOutput(), and GPSDriverUBX::configureDevicePreV27().

◆ UBX_TX_CFG_RST_BBR_MODE_COLD_START

#define UBX_TX_CFG_RST_BBR_MODE_COLD_START   0xFFFF

Definition at line 211 of file ubx.h.

Referenced by GPSDriverUBX::reset().

◆ UBX_TX_CFG_RST_BBR_MODE_HOT_START

#define UBX_TX_CFG_RST_BBR_MODE_HOT_START   0

Definition at line 209 of file ubx.h.

Referenced by GPSDriverUBX::reset().

◆ UBX_TX_CFG_RST_BBR_MODE_WARM_START

#define UBX_TX_CFG_RST_BBR_MODE_WARM_START   1

Definition at line 210 of file ubx.h.

Referenced by GPSDriverUBX::reset().

◆ UBX_TX_CFG_RST_MODE_HARDWARE

#define UBX_TX_CFG_RST_MODE_HARDWARE   0

Definition at line 212 of file ubx.h.

◆ UBX_TX_CFG_RST_MODE_SOFTWARE

#define UBX_TX_CFG_RST_MODE_SOFTWARE   1

Definition at line 213 of file ubx.h.

Referenced by GPSDriverUBX::reset().

Enumeration Type Documentation

◆ ubx_ack_state_t

Enumerator
UBX_ACK_IDLE 
UBX_ACK_WAITING 
UBX_ACK_GOT_ACK 
UBX_ACK_GOT_NAK 

Definition at line 753 of file ubx.h.

◆ ubx_decode_state_t

Enumerator
UBX_DECODE_SYNC1 
UBX_DECODE_SYNC2 
UBX_DECODE_CLASS 
UBX_DECODE_ID 
UBX_DECODE_LENGTH1 
UBX_DECODE_LENGTH2 
UBX_DECODE_PAYLOAD 
UBX_DECODE_CHKSUM1 
UBX_DECODE_CHKSUM2 
UBX_DECODE_RTCM3 

Definition at line 730 of file ubx.h.

◆ ubx_rxmsg_state_t

Enumerator
UBX_RXMSG_IGNORE 
UBX_RXMSG_HANDLE 
UBX_RXMSG_DISABLE 
UBX_RXMSG_ERROR_LENGTH 

Definition at line 745 of file ubx.h.