Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Path: blob/master/libraries/AP_GPS/AP_GPS_UBLOX.h
Views: 1798
/*1This program is free software: you can redistribute it and/or modify2it under the terms of the GNU General Public License as published by3the Free Software Foundation, either version 3 of the License, or4(at your option) any later version.56This program is distributed in the hope that it will be useful,7but WITHOUT ANY WARRANTY; without even the implied warranty of8MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the9GNU General Public License for more details.1011You should have received a copy of the GNU General Public License12along with this program. If not, see <http://www.gnu.org/licenses/>.13*/1415//16// u-blox UBX GPS driver for ArduPilot and ArduPilotMega.17// Code by Michael Smith, Jordi Munoz and Jose Julio, DIYDrones.com18//19// UBlox Lea6H protocol: http://www.u-blox.com/images/downloads/Product_Docs/u-blox6_ReceiverDescriptionProtocolSpec_%28GPS.G6-SW-10018%29.pdf20#pragma once2122#include "AP_GPS_config.h"2324#if AP_GPS_UBLOX_ENABLED2526#include "AP_GPS.h"27#include "GPS_Backend.h"2829#include <AP_HAL/AP_HAL.h>3031/*32* try to put a UBlox into binary mode. This is in two parts.33*34* First we send a ubx binary message that enables the NAV_SOL message35* at rate 1. Then we send a NMEA message to set the baud rate to our36* desired rate. The reason for doing the NMEA message second is if we37* send it first the second message will be ignored for a baud rate38* change.39* The reason we need the NAV_SOL rate message at all is some uBlox40* modules are configured with all ubx binary messages off, which41* would mean we would never detect it.4243* running a uBlox at less than 38400 will lead to packet44* corruption, as we can't receive the packets in the 200ms45* window for 5Hz fixes. The NMEA startup message should force46* the uBlox into 230400 no matter what rate it is configured47* for.48*/49#define UBLOX_SET_BINARY_115200 "\265\142\006\001\003\000\001\006\001\022\117$PUBX,41,1,0023,0001,115200,0*1C\r\n"5051// a variant with 230400 baudrate52#define UBLOX_SET_BINARY_230400 "\265\142\006\001\003\000\001\006\001\022\117$PUBX,41,1,0023,0001,230400,0*1E\r\n"5354// a variant with 460800 baudrate55#define UBLOX_SET_BINARY_460800 "\265\142\006\001\003\000\001\006\001\022\117$PUBX,41,1,0023,0001,460800,0*11\r\n"5657#define UBLOX_RXM_RAW_LOGGING 158#define UBLOX_MAX_RXM_RAW_SATS 2259#define UBLOX_MAX_RXM_RAWX_SATS 3260#define UBLOX_MAX_EXTENSIONS 861#define UBLOX_GNSS_SETTINGS 162#ifndef UBLOX_TIM_TM2_LOGGING63#define UBLOX_TIM_TM2_LOGGING (BOARD_FLASH_SIZE>1024)64#endif6566#define UBLOX_MAX_GNSS_CONFIG_BLOCKS 76768#define UBX_TIMEGPS_VALID_WEEK_MASK 0x26970#define UBLOX_MAX_PORTS 671#define UBLOX_MODULE_LEN 97273#define RATE_POSLLH 174#define RATE_STATUS 175#define RATE_SOL 176#define RATE_TIMEGPS 577#define RATE_PVT 178#define RATE_VELNED 179#define RATE_DOP 180#define RATE_HW 581#define RATE_HW2 582#define RATE_TIM_TM2 18384#define CONFIG_RATE_NAV (1<<0)85#define CONFIG_RATE_POSLLH (1<<1)86#define CONFIG_RATE_STATUS (1<<2)87#define CONFIG_RATE_SOL (1<<3)88#define CONFIG_RATE_VELNED (1<<4)89#define CONFIG_RATE_DOP (1<<5)90#define CONFIG_RATE_MON_HW (1<<6)91#define CONFIG_RATE_MON_HW2 (1<<7)92#define CONFIG_RATE_RAW (1<<8)93#define CONFIG_VERSION (1<<9)94#define CONFIG_NAV_SETTINGS (1<<10)95#define CONFIG_GNSS (1<<11)96#define CONFIG_SBAS (1<<12)97#define CONFIG_RATE_PVT (1<<13)98#define CONFIG_TP5 (1<<14)99#define CONFIG_RATE_TIMEGPS (1<<15)100#define CONFIG_TMODE_MODE (1<<16)101#define CONFIG_RTK_MOVBASE (1<<17)102#define CONFIG_TIM_TM2 (1<<18)103#define CONFIG_F9 (1<<19)104#define CONFIG_M10 (1<<20)105#define CONFIG_L5 (1<<21)106#define CONFIG_LAST (1<<22) // this must always be the last bit107108#define CONFIG_REQUIRED_INITIAL (CONFIG_RATE_NAV | CONFIG_RATE_POSLLH | CONFIG_RATE_STATUS | CONFIG_RATE_VELNED)109110#define CONFIG_ALL (CONFIG_RATE_NAV | CONFIG_RATE_POSLLH | CONFIG_RATE_STATUS | CONFIG_RATE_SOL | CONFIG_RATE_VELNED \111| CONFIG_RATE_DOP | CONFIG_RATE_MON_HW | CONFIG_RATE_MON_HW2 | CONFIG_RATE_RAW | CONFIG_VERSION \112| CONFIG_NAV_SETTINGS | CONFIG_GNSS | CONFIG_SBAS)113114//Configuration Sub-Sections115#define SAVE_CFG_IO (1<<0)116#define SAVE_CFG_MSG (1<<1)117#define SAVE_CFG_INF (1<<2)118#define SAVE_CFG_NAV (1<<3)119#define SAVE_CFG_RXM (1<<4)120#define SAVE_CFG_RINV (1<<9)121#define SAVE_CFG_ANT (1<<10)122#define SAVE_CFG_ALL (SAVE_CFG_IO|SAVE_CFG_MSG|SAVE_CFG_INF|SAVE_CFG_NAV|SAVE_CFG_RXM|SAVE_CFG_RINV|SAVE_CFG_ANT)123124class RTCM3_Parser;125126class AP_GPS_UBLOX : public AP_GPS_Backend127{128public:129AP_GPS_UBLOX(AP_GPS &_gps, AP_GPS::Params &_params, AP_GPS::GPS_State &_state, AP_HAL::UARTDriver *_port, AP_GPS::GPS_Role role);130~AP_GPS_UBLOX() override;131132// Methods133bool read() override;134135AP_GPS::GPS_Status highest_supported_status(void) override { return AP_GPS::GPS_OK_FIX_3D_RTK_FIXED; }136137static bool _detect(struct UBLOX_detect_state &state, uint8_t data);138139bool is_configured(void) const override {140#if CONFIG_HAL_BOARD != HAL_BOARD_SITL141if (!gps._auto_config) {142return true;143} else {144return !_unconfigured_messages;145}146#else147return true;148#endif // CONFIG_HAL_BOARD != HAL_BOARD_SITL149}150151bool get_error_codes(uint32_t &error_codes) const override {152error_codes = _unconfigured_messages;153return true;154};155156void broadcast_configuration_failure_reason(void) const override;157#if HAL_LOGGING_ENABLED158void Write_AP_Logger_Log_Startup_messages() const override;159#endif160161// get the velocity lag, returns true if the driver is confident in the returned value162bool get_lag(float &lag_sec) const override;163164const char *name() const override { return "u-blox"; }165166// support for retrieving RTCMv3 data from a moving baseline base167bool get_RTCMV3(const uint8_t *&bytes, uint16_t &len) override;168void clear_RTCMV3(void) override;169170// ublox specific healthy checks171bool is_healthy(void) const override;172173private:174// u-blox UBX protocol essentials175struct PACKED ubx_header {176uint8_t preamble1;177uint8_t preamble2;178uint8_t msg_class;179uint8_t msg_id;180uint16_t length;181};182#if UBLOX_GNSS_SETTINGS183struct PACKED ubx_cfg_gnss {184uint8_t msgVer;185uint8_t numTrkChHw;186uint8_t numTrkChUse;187uint8_t numConfigBlocks;188PACKED struct configBlock {189uint8_t gnssId;190uint8_t resTrkCh;191uint8_t maxTrkCh;192uint8_t reserved1;193uint32_t flags;194} configBlock[UBLOX_MAX_GNSS_CONFIG_BLOCKS];195};196#endif197struct PACKED ubx_cfg_nav_rate {198uint16_t measure_rate_ms;199uint16_t nav_rate;200uint16_t timeref;201};202struct PACKED ubx_cfg_msg {203uint8_t msg_class;204uint8_t msg_id;205};206struct PACKED ubx_cfg_msg_rate {207uint8_t msg_class;208uint8_t msg_id;209uint8_t rate;210};211struct PACKED ubx_cfg_msg_rate_6 {212uint8_t msg_class;213uint8_t msg_id;214uint8_t rates[6];215};216struct PACKED ubx_cfg_nav_settings {217uint16_t mask;218uint8_t dynModel;219uint8_t fixMode;220int32_t fixedAlt;221uint32_t fixedAltVar;222int8_t minElev;223uint8_t drLimit;224uint16_t pDop;225uint16_t tDop;226uint16_t pAcc;227uint16_t tAcc;228uint8_t staticHoldThresh;229uint8_t res1;230uint32_t res2;231uint32_t res3;232uint32_t res4;233};234struct PACKED ubx_cfg_tp5 {235uint8_t tpIdx;236uint8_t version;237uint8_t reserved1[2];238int16_t antCableDelay;239int16_t rfGroupDelay;240uint32_t freqPeriod;241uint32_t freqPeriodLock;242uint32_t pulseLenRatio;243uint32_t pulseLenRatioLock;244int32_t userConfigDelay;245uint32_t flags;246};247struct PACKED ubx_cfg_prt {248uint8_t portID;249};250struct PACKED ubx_cfg_sbas {251uint8_t mode;252uint8_t usage;253uint8_t maxSBAS;254uint8_t scanmode2;255uint32_t scanmode1;256};257// F9 config keys258enum class ConfigKey : uint32_t {259TMODE_MODE = 0x20030001,260CFG_RATE_MEAS = 0x30210001,261262CFG_UART1_BAUDRATE = 0x40520001,263CFG_UART1_ENABLED = 0x10520005,264CFG_UART1INPROT_UBX = 0x10730001,265CFG_UART1INPROT_NMEA = 0x10730002,266CFG_UART1INPROT_RTCM3X = 0x10730004,267CFG_UART1OUTPROT_UBX = 0x10740001,268CFG_UART1OUTPROT_NMEA = 0x10740002,269CFG_UART1OUTPROT_RTCM3X = 0x10740004,270271CFG_UART2_BAUDRATE = 0x40530001,272CFG_UART2_ENABLED = 0x10530005,273CFG_UART2INPROT_UBX = 0x10750001,274CFG_UART2INPROT_NMEA = 0x10750002,275CFG_UART2INPROT_RTCM3X = 0x10750004,276CFG_UART2OUTPROT_UBX = 0x10760001,277CFG_UART2OUTPROT_NMEA = 0x10760002,278CFG_UART2OUTPROT_RTCM3X = 0x10760004,279280MSGOUT_RTCM_3X_TYPE4072_0_UART1 = 0x209102ff,281MSGOUT_RTCM_3X_TYPE4072_1_UART1 = 0x20910382,282MSGOUT_RTCM_3X_TYPE1077_UART1 = 0x209102cd,283MSGOUT_RTCM_3X_TYPE1087_UART1 = 0x209102d2,284MSGOUT_RTCM_3X_TYPE1097_UART1 = 0x20910319,285MSGOUT_RTCM_3X_TYPE1127_UART1 = 0x209102d7,286MSGOUT_RTCM_3X_TYPE1230_UART1 = 0x20910304,287MSGOUT_UBX_NAV_RELPOSNED_UART1 = 0x2091008e,288289MSGOUT_RTCM_3X_TYPE4072_0_UART2 = 0x20910300,290MSGOUT_RTCM_3X_TYPE4072_1_UART2 = 0x20910383,291MSGOUT_RTCM_3X_TYPE1077_UART2 = 0x209102ce,292MSGOUT_RTCM_3X_TYPE1087_UART2 = 0x209102d3,293MSGOUT_RTCM_3X_TYPE1097_UART2 = 0x2091031a,294MSGOUT_RTCM_3X_TYPE1127_UART2 = 0x209102d8,295MSGOUT_RTCM_3X_TYPE1230_UART2 = 0x20910305,296MSGOUT_UBX_NAV_RELPOSNED_UART2 = 0x2091008f,297298// enable specific signals and constellations299CFG_SIGNAL_GPS_ENA = 0x1031001f,300CFG_SIGNAL_GPS_L1CA_ENA = 0x10310001,301CFG_SIGNAL_GPS_L2C_ENA = 0x10310003,302CFG_SIGNAL_GPS_L5_ENA = 0x10310004,303CFG_SIGNAL_SBAS_ENA = 0x10310020,304CFG_SIGNAL_SBAS_L1CA_ENA = 0x10310005,305CFG_SIGNAL_GAL_ENA = 0x10310021,306CFG_SIGNAL_GAL_E1_ENA = 0x10310007,307CFG_SIGNAL_GAL_E5A_ENA = 0x10310009,308CFG_SIGNAL_GAL_E5B_ENA = 0x1031000a,309CFG_SIGNAL_BDS_ENA = 0x10310022,310CFG_SIGNAL_BDS_B1_ENA = 0x1031000d,311CFG_SIGNAL_BDS_B1C_ENA = 0x1031000f,312CFG_SIGNAL_BDS_B2_ENA = 0x1031000e,313CFG_SIGNAL_BDS_B2A_ENA = 0x10310028,314CFG_SIGNAL_QZSS_ENA = 0x10310024,315CFG_SIGNAL_QZSS_L1CA_ENA = 0x10310012,316CFG_SIGNAL_QZSS_L1S_ENA = 0x10310014,317CFG_SIGNAL_QZSS_L2C_ENA = 0x10310015,318CFG_SIGNAL_QZSS_L5_ENA = 0x10310017,319CFG_SIGNAL_GLO_ENA = 0x10310025,320CFG_SIGNAL_GLO_L1_ENA = 0x10310018,321CFG_SIGNAL_GLO_L2_ENA = 0x1031001a,322CFG_SIGNAL_NAVIC_ENA = 0x10310026,323CFG_SIGNAL_NAVIC_L5_ENA = 0x1031001d,324325CFG_SIGNAL_L5_HEALTH_OVRD = 0x10320001,326327// other keys328CFG_NAVSPG_DYNMODEL = 0x20110021,329330};331332// layers for VALSET333#define UBX_VALSET_LAYER_RAM 0x1U334#define UBX_VALSET_LAYER_BBR 0x2U335#define UBX_VALSET_LAYER_FLASH 0x4U336#define UBX_VALSET_LAYER_ALL 0x7U337338struct PACKED ubx_cfg_valset {339uint8_t version;340uint8_t layers;341uint8_t transaction;342uint8_t reserved[1];343uint32_t key;344};345struct PACKED ubx_cfg_valget {346uint8_t version;347uint8_t layers;348uint8_t reserved[2];349// variable length data, check buffer length350};351struct PACKED ubx_nav_posllh {352uint32_t itow; // GPS msToW353int32_t longitude;354int32_t latitude;355int32_t altitude_ellipsoid;356int32_t altitude_msl;357uint32_t horizontal_accuracy;358uint32_t vertical_accuracy;359};360struct PACKED ubx_nav_status {361uint32_t itow; // GPS msToW362uint8_t fix_type;363uint8_t fix_status;364uint8_t differential_status;365uint8_t res;366uint32_t time_to_first_fix;367uint32_t uptime; // milliseconds368};369struct PACKED ubx_nav_dop {370uint32_t itow; // GPS msToW371uint16_t gDOP;372uint16_t pDOP;373uint16_t tDOP;374uint16_t vDOP;375uint16_t hDOP;376uint16_t nDOP;377uint16_t eDOP;378};379struct PACKED ubx_nav_solution {380uint32_t itow;381int32_t time_nsec;382uint16_t week;383uint8_t fix_type;384uint8_t fix_status;385int32_t ecef_x;386int32_t ecef_y;387int32_t ecef_z;388uint32_t position_accuracy_3d;389int32_t ecef_x_velocity;390int32_t ecef_y_velocity;391int32_t ecef_z_velocity;392uint32_t speed_accuracy;393uint16_t position_DOP;394uint8_t res;395uint8_t satellites;396uint32_t res2;397};398struct PACKED ubx_nav_pvt {399uint32_t itow;400uint16_t year;401uint8_t month, day, hour, min, sec;402uint8_t valid;403uint32_t t_acc;404int32_t nano;405uint8_t fix_type;406uint8_t flags;407uint8_t flags2;408uint8_t num_sv;409int32_t lon, lat;410int32_t h_ellipsoid, h_msl;411uint32_t h_acc, v_acc;412int32_t velN, velE, velD, gspeed;413int32_t head_mot;414uint32_t s_acc;415uint32_t head_acc;416uint16_t p_dop;417uint8_t flags3;418uint8_t reserved1[5];419int32_t headVeh;420int16_t magDec;421uint16_t magAcc;422};423struct PACKED ubx_nav_relposned {424uint8_t version;425uint8_t reserved1;426uint16_t refStationId;427uint32_t iTOW;428int32_t relPosN;429int32_t relPosE;430int32_t relPosD;431int32_t relPosLength;432int32_t relPosHeading;433uint8_t reserved2[4];434int8_t relPosHPN;435int8_t relPosHPE;436int8_t relPosHPD;437int8_t relPosHPLength;438uint32_t accN;439uint32_t accE;440uint32_t accD;441uint32_t accLength;442uint32_t accHeading;443uint8_t reserved3[4];444uint32_t flags;445};446447struct PACKED ubx_nav_velned {448uint32_t itow; // GPS msToW449int32_t ned_north;450int32_t ned_east;451int32_t ned_down;452uint32_t speed_3d;453uint32_t speed_2d;454int32_t heading_2d;455uint32_t speed_accuracy;456uint32_t heading_accuracy;457};458459struct PACKED ubx_nav_timegps {460uint32_t itow;461int32_t ftow;462uint16_t week;463int8_t leapS;464uint8_t valid; // leapsvalid | weekvalid | tow valid;465uint32_t tAcc;466};467468// Lea6 uses a 60 byte message469struct PACKED ubx_mon_hw_60 {470uint32_t pinSel;471uint32_t pinBank;472uint32_t pinDir;473uint32_t pinVal;474uint16_t noisePerMS;475uint16_t agcCnt;476uint8_t aStatus;477uint8_t aPower;478uint8_t flags;479uint8_t reserved1;480uint32_t usedMask;481uint8_t VP[17];482uint8_t jamInd;483uint16_t reserved3;484uint32_t pinIrq;485uint32_t pullH;486uint32_t pullL;487};488// Neo7 uses a 68 byte message489struct PACKED ubx_mon_hw_68 {490uint32_t pinSel;491uint32_t pinBank;492uint32_t pinDir;493uint32_t pinVal;494uint16_t noisePerMS;495uint16_t agcCnt;496uint8_t aStatus;497uint8_t aPower;498uint8_t flags;499uint8_t reserved1;500uint32_t usedMask;501uint8_t VP[25];502uint8_t jamInd;503uint16_t reserved3;504uint32_t pinIrq;505uint32_t pullH;506uint32_t pullL;507};508struct PACKED ubx_mon_hw2 {509int8_t ofsI;510uint8_t magI;511int8_t ofsQ;512uint8_t magQ;513uint8_t cfgSource;514uint8_t reserved0[3];515uint32_t lowLevCfg;516uint32_t reserved1[2];517uint32_t postStatus;518uint32_t reserved2;519};520struct PACKED ubx_mon_ver {521char swVersion[30];522char hwVersion[10];523char extension[30*UBLOX_MAX_EXTENSIONS]; // extensions are not enabled524};525struct PACKED ubx_nav_svinfo_header {526uint32_t itow;527uint8_t numCh;528uint8_t globalFlags;529uint16_t reserved;530};531#if UBLOX_RXM_RAW_LOGGING532struct PACKED ubx_rxm_raw {533int32_t iTOW;534int16_t week;535uint8_t numSV;536uint8_t reserved1;537struct ubx_rxm_raw_sv {538double cpMes;539double prMes;540float doMes;541uint8_t sv;542int8_t mesQI;543int8_t cno;544uint8_t lli;545} svinfo[UBLOX_MAX_RXM_RAW_SATS];546};547struct PACKED ubx_rxm_rawx {548double rcvTow;549uint16_t week;550int8_t leapS;551uint8_t numMeas;552uint8_t recStat;553uint8_t reserved1[3];554PACKED struct ubx_rxm_rawx_sv {555double prMes;556double cpMes;557float doMes;558uint8_t gnssId;559uint8_t svId;560uint8_t reserved2;561uint8_t freqId;562uint16_t locktime;563uint8_t cno;564uint8_t prStdev;565uint8_t cpStdev;566uint8_t doStdev;567uint8_t trkStat;568uint8_t reserved3;569} svinfo[UBLOX_MAX_RXM_RAWX_SATS];570};571#endif572573struct PACKED ubx_ack_ack {574uint8_t clsID;575uint8_t msgID;576};577struct PACKED ubx_ack_nack {578uint8_t clsID;579uint8_t msgID;580};581582583struct PACKED ubx_cfg_cfg {584uint32_t clearMask;585uint32_t saveMask;586uint32_t loadMask;587};588589struct PACKED ubx_tim_tm2 {590uint8_t ch;591uint8_t flags;592uint16_t count;593uint16_t wnR;594uint16_t wnF;595uint32_t towMsR;596uint32_t towSubMsR;597uint32_t towMsF;598uint32_t towSubMsF;599uint32_t accEst;600};601602// Receive buffer603union PACKED {604DEFINE_BYTE_ARRAY_METHODS605ubx_nav_posllh posllh;606ubx_nav_status status;607ubx_nav_dop dop;608ubx_nav_solution solution;609ubx_nav_pvt pvt;610ubx_nav_timegps timegps;611ubx_nav_velned velned;612ubx_cfg_msg_rate msg_rate;613ubx_cfg_msg_rate_6 msg_rate_6;614ubx_cfg_nav_settings nav_settings;615ubx_cfg_nav_rate nav_rate;616ubx_cfg_prt prt;617ubx_mon_hw_60 mon_hw_60;618ubx_mon_hw_68 mon_hw_68;619ubx_mon_hw2 mon_hw2;620ubx_mon_ver mon_ver;621ubx_cfg_tp5 nav_tp5;622#if UBLOX_GNSS_SETTINGS623ubx_cfg_gnss gnss;624#endif625ubx_cfg_sbas sbas;626ubx_cfg_valget valget;627ubx_nav_svinfo_header svinfo_header;628ubx_nav_relposned relposned;629#if UBLOX_RXM_RAW_LOGGING630ubx_rxm_raw rxm_raw;631ubx_rxm_rawx rxm_rawx;632#endif633ubx_ack_ack ack;634ubx_ack_nack nack;635ubx_tim_tm2 tim_tm2;636} _buffer;637638enum class RELPOSNED {639gnssFixOK = 1U << 0,640diffSoln = 1U << 1,641relPosValid = 1U << 2,642carrSolnFloat = 1U << 3,643644carrSolnFixed = 1U << 4,645isMoving = 1U << 5,646refPosMiss = 1U << 6,647refObsMiss = 1U << 7,648649relPosHeadingValid = 1U << 8,650relPosNormalized = 1U << 9651};652653enum ubs_protocol_bytes {654PREAMBLE1 = 0xb5,655PREAMBLE2 = 0x62,656CLASS_NAV = 0x01,657CLASS_ACK = 0x05,658CLASS_CFG = 0x06,659CLASS_MON = 0x0A,660CLASS_RXM = 0x02,661CLASS_TIM = 0x0d,662MSG_ACK_NACK = 0x00,663MSG_ACK_ACK = 0x01,664MSG_POSLLH = 0x2,665MSG_STATUS = 0x3,666MSG_DOP = 0x4,667MSG_SOL = 0x6,668MSG_PVT = 0x7,669MSG_TIMEGPS = 0x20,670MSG_RELPOSNED = 0x3c,671MSG_VELNED = 0x12,672MSG_CFG_CFG = 0x09,673MSG_CFG_RATE = 0x08,674MSG_CFG_MSG = 0x01,675MSG_CFG_NAV_SETTINGS = 0x24,676MSG_CFG_PRT = 0x00,677MSG_CFG_SBAS = 0x16,678MSG_CFG_GNSS = 0x3E,679MSG_CFG_TP5 = 0x31,680MSG_CFG_VALSET = 0x8A,681MSG_CFG_VALGET = 0x8B,682MSG_MON_HW = 0x09,683MSG_MON_HW2 = 0x0B,684MSG_MON_VER = 0x04,685MSG_NAV_SVINFO = 0x30,686MSG_RXM_RAW = 0x10,687MSG_RXM_RAWX = 0x15,688MSG_TIM_TM2 = 0x03689};690enum ubx_gnss_identifier {691GNSS_GPS = 0x00,692GNSS_SBAS = 0x01,693GNSS_GALILEO = 0x02,694GNSS_BEIDOU = 0x03,695GNSS_IMES = 0x04,696GNSS_QZSS = 0x05,697GNSS_GLONASS = 0x06698};699enum ubs_nav_fix_type {700FIX_NONE = 0,701FIX_DEAD_RECKONING = 1,702FIX_2D = 2,703FIX_3D = 3,704FIX_GPS_DEAD_RECKONING = 4,705FIX_TIME = 5706};707enum ubx_nav_status_bits {708NAV_STATUS_FIX_VALID = 1,709NAV_STATUS_DGPS_USED = 2710};711enum ubx_hardware_version {712ANTARIS = 0,713UBLOX_5,714UBLOX_6,715UBLOX_7,716UBLOX_M8,717UBLOX_F9 = 0x80, // comes from MON_VER hwVersion/swVersion strings718UBLOX_M9 = 0x81, // comes from MON_VER hwVersion/swVersion strings719UBLOX_M10 = 0x82,720UBLOX_UNKNOWN_HARDWARE_GENERATION = 0xff // not in the ublox spec used for721// flagging state in the driver722};723724enum ubx_hardware_variant {725UBLOX_F9_ZED, // comes from MON_VER extension strings726UBLOX_F9_NEO, // comes from MON_VER extension strings727UBLOX_UNKNOWN_HARDWARE_VARIANT = 0xff728};729730enum config_step {731STEP_PVT = 0,732STEP_NAV_RATE, // poll NAV rate733STEP_SOL,734STEP_PORT,735STEP_STATUS,736STEP_POSLLH,737STEP_VELNED,738STEP_TIMEGPS,739STEP_POLL_SVINFO, // poll svinfo740STEP_POLL_SBAS, // poll SBAS741STEP_POLL_NAV, // poll NAV settings742STEP_POLL_GNSS, // poll GNSS743STEP_POLL_TP5, // poll TP5744STEP_TMODE, // set TMODE-MODE745STEP_DOP,746STEP_MON_HW,747STEP_MON_HW2,748STEP_RAW,749STEP_RAWX,750STEP_VERSION,751STEP_RTK_MOVBASE, // setup moving baseline752STEP_TIM_TM2,753STEP_F9,754STEP_F9_VALIDATE,755STEP_M10,756STEP_L5,757STEP_LAST758};759760// Packet checksum accumulators761uint8_t _ck_a;762uint8_t _ck_b;763764// State machine state765uint8_t _step;766uint8_t _msg_id;767uint16_t _payload_length;768uint16_t _payload_counter;769770uint8_t _class;771bool _cfg_saved;772773uint32_t _last_vel_time;774uint32_t _last_pos_time;775uint32_t _last_cfg_sent_time;776uint8_t _num_cfg_save_tries;777uint32_t _last_config_time;778uint32_t _f9_config_time;779uint16_t _delay_time;780uint8_t _next_message { STEP_PVT };781uint8_t _ublox_port { 255 };782bool _have_version;783struct ubx_mon_ver _version;784char _module[UBLOX_MODULE_LEN];785uint32_t _unconfigured_messages {CONFIG_ALL};786uint8_t _hardware_generation { UBLOX_UNKNOWN_HARDWARE_GENERATION };787uint8_t _hardware_variant;788uint32_t _last_pvt_itow;789uint32_t _last_relposned_itow;790uint32_t _last_relposned_ms;791792// the role set from GPS_TYPE793AP_GPS::GPS_Role role;794795// do we have new position information?796bool _new_position:1;797// do we have new speed information?798bool _new_speed:1;799800uint8_t _disable_counter;801802// Buffer parse & GPS state update803bool _parse_gps();804805// used to update fix between status and position packets806AP_GPS::GPS_Status next_fix { AP_GPS::NO_FIX };807808bool _cfg_needs_save;809810bool noReceivedHdop { true };811812bool havePvtMsg;813814// structure for list of config key/value pairs for815// specific configurations816struct PACKED config_list {817ConfigKey key;818// support up to 4 byte values, assumes little-endian819uint32_t value;820};821822bool _configure_message_rate(uint8_t msg_class, uint8_t msg_id, uint8_t rate);823bool _configure_valset(ConfigKey key, const void *value, uint8_t layers=UBX_VALSET_LAYER_ALL);824bool _configure_list_valset(const config_list *list, uint8_t count, uint8_t layers=UBX_VALSET_LAYER_ALL);825bool _configure_valget(ConfigKey key);826void _configure_rate(void);827void _configure_sbas(bool enable);828void _update_checksum(uint8_t *data, uint16_t len, uint8_t &ck_a, uint8_t &ck_b);829bool _send_message(uint8_t msg_class, uint8_t msg_id, const void *msg, uint16_t size);830void send_next_rate_update(void);831bool _request_message_rate(uint8_t msg_class, uint8_t msg_id);832void _request_next_config(void);833void _request_port(void);834void _request_version(void);835void _save_cfg(void);836void _verify_rate(uint8_t msg_class, uint8_t msg_id, uint8_t rate);837void _check_new_itow(uint32_t itow);838839void unexpected_message(void);840void log_mon_hw(void);841void log_mon_hw2(void);842void log_tim_tm2(void);843void log_rxm_raw(const struct ubx_rxm_raw &raw);844void log_rxm_rawx(const struct ubx_rxm_rawx &raw);845846#if GPS_MOVING_BASELINE847// see if we should use uart2 for moving baseline config848bool mb_use_uart2(void) const {849return option_set(AP_GPS::DriverOptions::UBX_MBUseUart2)?true:false;850}851#endif852853// return size of a config key payload854uint8_t config_key_size(ConfigKey key) const;855856// configure a set of config key/value pairs. The unconfig_bit corresponds to857// a bit in _unconfigured_messages858bool _configure_config_set(const config_list *list, uint8_t count, uint32_t unconfig_bit, uint8_t layers=UBX_VALSET_LAYER_ALL);859860// find index in active_config list861int8_t find_active_config_index(ConfigKey key) const;862863// return true if GPS is capable of F9 config864bool supports_F9_config(void) const;865866// is the config key a GNSS key867bool is_gnss_key(ConfigKey key) const;868869// populate config_GNSS for F9P870uint8_t populate_F9_gnss(void);871uint8_t last_configured_gnss;872873uint8_t _pps_freq = 1;874#ifdef HAL_GPIO_PPS875void pps_interrupt(uint8_t pin, bool high, uint32_t timestamp_us);876void set_pps_desired_freq(uint8_t freq) override;877#endif878879// status of active configuration for a role880struct {881const config_list *list;882uint8_t count;883uint32_t done_mask;884uint32_t unconfig_bit;885uint8_t layers;886int8_t fetch_index;887int8_t set_index;888} active_config;889890#if GPS_MOVING_BASELINE891// config for moving baseline base892static const config_list config_MB_Base_uart1[];893static const config_list config_MB_Base_uart2[];894895// config for moving baseline rover896static const config_list config_MB_Rover_uart1[];897static const config_list config_MB_Rover_uart2[];898899// RTCM3 parser for when in moving baseline base mode900RTCM3_Parser *rtcm3_parser;901#endif // GPS_MOVING_BASELINE902903bool supports_l5;904static const config_list config_M10[];905static const config_list config_L5_ovrd_ena[];906static const config_list config_L5_ovrd_dis[];907// scratch space for GNSS config908config_list* config_GNSS;909};910911#endif912913914