2013-08-29 02:34:34 -03:00
|
|
|
/*
|
|
|
|
This program is free software: you can redistribute it and/or modify
|
|
|
|
it under the terms of the GNU General Public License as published by
|
|
|
|
the Free Software Foundation, either version 3 of the License, or
|
|
|
|
(at your option) any later version.
|
|
|
|
|
|
|
|
This program is distributed in the hope that it will be useful,
|
|
|
|
but WITHOUT ANY WARRANTY; without even the implied warranty of
|
|
|
|
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
|
|
|
GNU General Public License for more details.
|
|
|
|
|
|
|
|
You should have received a copy of the GNU General Public License
|
|
|
|
along with this program. If not, see <http://www.gnu.org/licenses/>.
|
|
|
|
*/
|
|
|
|
|
2010-09-06 19:31:18 -03:00
|
|
|
//
|
|
|
|
// u-blox UBX GPS driver for ArduPilot and ArduPilotMega.
|
|
|
|
// Code by Michael Smith, Jordi Munoz and Jose Julio, DIYDrones.com
|
|
|
|
//
|
2013-03-25 04:24:14 -03:00
|
|
|
// UBlox Lea6H protocol: http://www.u-blox.com/images/downloads/Product_Docs/u-blox6_ReceiverDescriptionProtocolSpec_%28GPS.G6-SW-10018%29.pdf
|
2016-02-17 21:25:23 -04:00
|
|
|
#pragma once
|
2010-09-06 17:16:50 -03:00
|
|
|
|
2022-07-13 05:53:16 -03:00
|
|
|
#include "AP_GPS.h"
|
|
|
|
#include "GPS_Backend.h"
|
2022-04-09 21:07:37 -03:00
|
|
|
|
|
|
|
#if AP_GPS_UBLOX_ENABLED
|
|
|
|
|
2022-07-13 05:53:16 -03:00
|
|
|
#include <AP_HAL/AP_HAL.h>
|
2010-09-06 17:16:50 -03:00
|
|
|
|
2012-06-15 02:53:14 -03:00
|
|
|
/*
|
2013-03-17 03:52:29 -03:00
|
|
|
* try to put a UBlox into binary mode. This is in two parts.
|
|
|
|
*
|
|
|
|
* First we send a ubx binary message that enables the NAV_SOL message
|
|
|
|
* at rate 1. Then we send a NMEA message to set the baud rate to our
|
|
|
|
* desired rate. The reason for doing the NMEA message second is if we
|
|
|
|
* send it first the second message will be ignored for a baud rate
|
|
|
|
* change.
|
|
|
|
* The reason we need the NAV_SOL rate message at all is some uBlox
|
|
|
|
* modules are configured with all ubx binary messages off, which
|
|
|
|
* would mean we would never detect it.
|
2022-07-21 20:54:14 -03:00
|
|
|
|
|
|
|
* running a uBlox at less than 38400 will lead to packet
|
|
|
|
* corruption, as we can't receive the packets in the 200ms
|
|
|
|
* window for 5Hz fixes. The NMEA startup message should force
|
|
|
|
* the uBlox into 230400 no matter what rate it is configured
|
|
|
|
* for.
|
2012-06-15 02:53:14 -03:00
|
|
|
*/
|
2020-05-21 23:13:08 -03:00
|
|
|
#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"
|
2015-05-04 20:52:28 -03:00
|
|
|
|
2020-12-23 22:02:11 -04:00
|
|
|
// a variant with 230400 baudrate
|
2019-11-16 00:26:28 -04:00
|
|
|
#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"
|
|
|
|
|
2020-12-23 22:02:11 -04:00
|
|
|
// a variant with 460800 baudrate
|
2019-11-16 00:26:28 -04:00
|
|
|
#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"
|
|
|
|
|
2015-05-04 20:52:28 -03:00
|
|
|
#define UBLOX_RXM_RAW_LOGGING 1
|
2015-06-29 19:04:35 -03:00
|
|
|
#define UBLOX_MAX_RXM_RAW_SATS 22
|
|
|
|
#define UBLOX_MAX_RXM_RAWX_SATS 32
|
2015-07-29 19:39:11 -03:00
|
|
|
#define UBLOX_GNSS_SETTINGS 1
|
2022-03-06 20:24:31 -04:00
|
|
|
#ifndef UBLOX_TIM_TM2_LOGGING
|
|
|
|
#define UBLOX_TIM_TM2_LOGGING (BOARD_FLASH_SIZE>1024)
|
|
|
|
#endif
|
2010-10-17 03:06:04 -03:00
|
|
|
|
2015-07-14 18:12:47 -03:00
|
|
|
#define UBLOX_MAX_GNSS_CONFIG_BLOCKS 7
|
|
|
|
|
2019-03-30 01:21:11 -03:00
|
|
|
#define UBX_TIMEGPS_VALID_WEEK_MASK 0x2
|
|
|
|
|
2016-02-02 03:58:33 -04:00
|
|
|
#define UBLOX_MAX_PORTS 6
|
|
|
|
|
|
|
|
#define RATE_POSLLH 1
|
|
|
|
#define RATE_STATUS 1
|
|
|
|
#define RATE_SOL 1
|
2019-03-30 01:21:11 -03:00
|
|
|
#define RATE_TIMEGPS 5
|
2016-07-30 20:38:43 -03:00
|
|
|
#define RATE_PVT 1
|
2016-02-02 03:58:33 -04:00
|
|
|
#define RATE_VELNED 1
|
|
|
|
#define RATE_DOP 1
|
|
|
|
#define RATE_HW 5
|
|
|
|
#define RATE_HW2 5
|
2022-03-06 20:24:31 -04:00
|
|
|
#define RATE_TIM_TM2 1
|
2016-02-02 03:58:33 -04:00
|
|
|
|
|
|
|
#define CONFIG_RATE_NAV (1<<0)
|
|
|
|
#define CONFIG_RATE_POSLLH (1<<1)
|
|
|
|
#define CONFIG_RATE_STATUS (1<<2)
|
|
|
|
#define CONFIG_RATE_SOL (1<<3)
|
|
|
|
#define CONFIG_RATE_VELNED (1<<4)
|
|
|
|
#define CONFIG_RATE_DOP (1<<5)
|
|
|
|
#define CONFIG_RATE_MON_HW (1<<6)
|
|
|
|
#define CONFIG_RATE_MON_HW2 (1<<7)
|
|
|
|
#define CONFIG_RATE_RAW (1<<8)
|
|
|
|
#define CONFIG_VERSION (1<<9)
|
|
|
|
#define CONFIG_NAV_SETTINGS (1<<10)
|
|
|
|
#define CONFIG_GNSS (1<<11)
|
|
|
|
#define CONFIG_SBAS (1<<12)
|
2016-07-30 20:38:43 -03:00
|
|
|
#define CONFIG_RATE_PVT (1<<13)
|
2018-06-22 02:25:27 -03:00
|
|
|
#define CONFIG_TP5 (1<<14)
|
2019-03-30 01:21:11 -03:00
|
|
|
#define CONFIG_RATE_TIMEGPS (1<<15)
|
2019-11-05 23:43:41 -04:00
|
|
|
#define CONFIG_TMODE_MODE (1<<16)
|
2019-11-16 00:26:28 -04:00
|
|
|
#define CONFIG_RTK_MOVBASE (1<<17)
|
2022-03-06 20:24:31 -04:00
|
|
|
#define CONFIG_TIM_TM2 (1<<18)
|
2022-11-20 23:33:46 -04:00
|
|
|
#define CONFIG_M10 (1<<19)
|
|
|
|
#define CONFIG_LAST (1<<20) // this must always be the last bit
|
2016-02-02 03:58:33 -04:00
|
|
|
|
2017-02-15 19:20:21 -04:00
|
|
|
#define CONFIG_REQUIRED_INITIAL (CONFIG_RATE_NAV | CONFIG_RATE_POSLLH | CONFIG_RATE_STATUS | CONFIG_RATE_VELNED)
|
|
|
|
|
2016-02-02 03:58:33 -04:00
|
|
|
#define CONFIG_ALL (CONFIG_RATE_NAV | CONFIG_RATE_POSLLH | CONFIG_RATE_STATUS | CONFIG_RATE_SOL | CONFIG_RATE_VELNED \
|
|
|
|
| CONFIG_RATE_DOP | CONFIG_RATE_MON_HW | CONFIG_RATE_MON_HW2 | CONFIG_RATE_RAW | CONFIG_VERSION \
|
2019-11-12 07:03:37 -04:00
|
|
|
| CONFIG_NAV_SETTINGS | CONFIG_GNSS | CONFIG_SBAS)
|
2016-02-02 03:58:33 -04:00
|
|
|
|
2015-10-28 21:32:57 -03:00
|
|
|
//Configuration Sub-Sections
|
|
|
|
#define SAVE_CFG_IO (1<<0)
|
|
|
|
#define SAVE_CFG_MSG (1<<1)
|
|
|
|
#define SAVE_CFG_INF (1<<2)
|
|
|
|
#define SAVE_CFG_NAV (1<<3)
|
|
|
|
#define SAVE_CFG_RXM (1<<4)
|
|
|
|
#define SAVE_CFG_RINV (1<<9)
|
|
|
|
#define SAVE_CFG_ANT (1<<10)
|
|
|
|
#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)
|
|
|
|
|
2019-11-16 00:26:28 -04:00
|
|
|
class RTCM3_Parser;
|
|
|
|
|
2014-03-28 16:52:27 -03:00
|
|
|
class AP_GPS_UBLOX : public AP_GPS_Backend
|
2010-09-06 17:16:50 -03:00
|
|
|
{
|
2010-09-06 19:31:18 -03:00
|
|
|
public:
|
2019-11-16 00:26:28 -04:00
|
|
|
AP_GPS_UBLOX(AP_GPS &_gps, AP_GPS::GPS_State &_state, AP_HAL::UARTDriver *_port, AP_GPS::GPS_Role role);
|
|
|
|
~AP_GPS_UBLOX() override;
|
2013-02-19 20:32:15 -04:00
|
|
|
|
2010-09-06 17:16:50 -03:00
|
|
|
// Methods
|
2018-11-07 06:58:08 -04:00
|
|
|
bool read() override;
|
2012-06-15 02:53:14 -03:00
|
|
|
|
2018-11-07 06:58:08 -04:00
|
|
|
AP_GPS::GPS_Status highest_supported_status(void) override { return AP_GPS::GPS_OK_FIX_3D_RTK_FIXED; }
|
2015-07-14 04:07:29 -03:00
|
|
|
|
2014-03-28 16:52:27 -03:00
|
|
|
static bool _detect(struct UBLOX_detect_state &state, uint8_t data);
|
2012-09-20 03:48:22 -03:00
|
|
|
|
2021-02-23 16:18:17 -04:00
|
|
|
bool is_configured(void) const override {
|
2017-03-06 19:14:26 -04:00
|
|
|
#if CONFIG_HAL_BOARD != HAL_BOARD_SITL
|
2016-02-02 03:58:33 -04:00
|
|
|
if (!gps._auto_config) {
|
|
|
|
return true;
|
|
|
|
} else {
|
|
|
|
return !_unconfigured_messages;
|
|
|
|
}
|
2017-03-06 19:14:26 -04:00
|
|
|
#else
|
|
|
|
return true;
|
|
|
|
#endif // CONFIG_HAL_BOARD != HAL_BOARD_SITL
|
2016-02-02 03:58:33 -04:00
|
|
|
}
|
|
|
|
|
2023-02-17 18:17:43 -04:00
|
|
|
bool get_error_codes(uint32_t &error_codes) const override {
|
|
|
|
error_codes = _unconfigured_messages;
|
|
|
|
return true;
|
|
|
|
};
|
|
|
|
|
2016-04-13 11:27:19 -03:00
|
|
|
void broadcast_configuration_failure_reason(void) const override;
|
2019-01-18 00:23:42 -04:00
|
|
|
void Write_AP_Logger_Log_Startup_messages() const override;
|
2016-12-18 19:31:28 -04:00
|
|
|
|
2017-05-24 14:42:03 -03:00
|
|
|
// get the velocity lag, returns true if the driver is confident in the returned value
|
|
|
|
bool get_lag(float &lag_sec) const override;
|
2016-12-18 19:31:28 -04:00
|
|
|
|
2016-08-01 08:58:23 -03:00
|
|
|
const char *name() const override { return "u-blox"; }
|
|
|
|
|
2019-11-16 00:26:28 -04:00
|
|
|
// support for retrieving RTCMv3 data from a moving baseline base
|
|
|
|
bool get_RTCMV3(const uint8_t *&bytes, uint16_t &len) override;
|
|
|
|
void clear_RTCMV3(void) override;
|
2019-12-17 21:50:20 -04:00
|
|
|
|
|
|
|
// ublox specific healthy checks
|
|
|
|
bool is_healthy(void) const override;
|
2019-11-16 00:26:28 -04:00
|
|
|
|
2010-09-06 19:31:18 -03:00
|
|
|
private:
|
2011-10-28 15:52:50 -03:00
|
|
|
// u-blox UBX protocol essentials
|
2013-05-09 07:04:36 -03:00
|
|
|
struct PACKED ubx_header {
|
2012-08-17 03:19:44 -03:00
|
|
|
uint8_t preamble1;
|
|
|
|
uint8_t preamble2;
|
|
|
|
uint8_t msg_class;
|
|
|
|
uint8_t msg_id;
|
|
|
|
uint16_t length;
|
|
|
|
};
|
2015-07-29 19:39:11 -03:00
|
|
|
#if UBLOX_GNSS_SETTINGS
|
2015-07-14 18:12:47 -03:00
|
|
|
struct PACKED ubx_cfg_gnss {
|
|
|
|
uint8_t msgVer;
|
|
|
|
uint8_t numTrkChHw;
|
|
|
|
uint8_t numTrkChUse;
|
|
|
|
uint8_t numConfigBlocks;
|
2015-07-20 00:13:50 -03:00
|
|
|
PACKED struct configBlock {
|
2015-07-14 18:12:47 -03:00
|
|
|
uint8_t gnssId;
|
|
|
|
uint8_t resTrkCh;
|
|
|
|
uint8_t maxTrkCh;
|
|
|
|
uint8_t reserved1;
|
|
|
|
uint32_t flags;
|
|
|
|
} configBlock[UBLOX_MAX_GNSS_CONFIG_BLOCKS];
|
|
|
|
};
|
2015-07-29 19:39:11 -03:00
|
|
|
#endif
|
2013-05-09 07:04:36 -03:00
|
|
|
struct PACKED ubx_cfg_nav_rate {
|
2012-08-17 03:19:44 -03:00
|
|
|
uint16_t measure_rate_ms;
|
|
|
|
uint16_t nav_rate;
|
|
|
|
uint16_t timeref;
|
|
|
|
};
|
2016-02-02 03:58:33 -04:00
|
|
|
struct PACKED ubx_cfg_msg {
|
|
|
|
uint8_t msg_class;
|
|
|
|
uint8_t msg_id;
|
|
|
|
};
|
2013-05-09 07:04:36 -03:00
|
|
|
struct PACKED ubx_cfg_msg_rate {
|
2012-08-17 03:19:44 -03:00
|
|
|
uint8_t msg_class;
|
|
|
|
uint8_t msg_id;
|
|
|
|
uint8_t rate;
|
|
|
|
};
|
2016-02-02 03:58:33 -04:00
|
|
|
struct PACKED ubx_cfg_msg_rate_6 {
|
|
|
|
uint8_t msg_class;
|
|
|
|
uint8_t msg_id;
|
|
|
|
uint8_t rates[6];
|
|
|
|
};
|
2013-05-09 07:04:36 -03:00
|
|
|
struct PACKED ubx_cfg_nav_settings {
|
2012-08-17 03:19:44 -03:00
|
|
|
uint16_t mask;
|
|
|
|
uint8_t dynModel;
|
|
|
|
uint8_t fixMode;
|
|
|
|
int32_t fixedAlt;
|
|
|
|
uint32_t fixedAltVar;
|
|
|
|
int8_t minElev;
|
|
|
|
uint8_t drLimit;
|
|
|
|
uint16_t pDop;
|
|
|
|
uint16_t tDop;
|
|
|
|
uint16_t pAcc;
|
|
|
|
uint16_t tAcc;
|
|
|
|
uint8_t staticHoldThresh;
|
|
|
|
uint8_t res1;
|
|
|
|
uint32_t res2;
|
|
|
|
uint32_t res3;
|
|
|
|
uint32_t res4;
|
|
|
|
};
|
2018-06-22 02:25:27 -03:00
|
|
|
struct PACKED ubx_cfg_tp5 {
|
|
|
|
uint8_t tpIdx;
|
|
|
|
uint8_t version;
|
|
|
|
uint8_t reserved1[2];
|
|
|
|
int16_t antCableDelay;
|
|
|
|
int16_t rfGroupDelay;
|
|
|
|
uint32_t freqPeriod;
|
|
|
|
uint32_t freqPeriodLock;
|
|
|
|
uint32_t pulseLenRatio;
|
|
|
|
uint32_t pulseLenRatioLock;
|
|
|
|
int32_t userConfigDelay;
|
|
|
|
uint32_t flags;
|
|
|
|
};
|
2016-02-02 03:58:33 -04:00
|
|
|
struct PACKED ubx_cfg_prt {
|
|
|
|
uint8_t portID;
|
|
|
|
};
|
2014-09-04 01:27:05 -03:00
|
|
|
struct PACKED ubx_cfg_sbas {
|
|
|
|
uint8_t mode;
|
|
|
|
uint8_t usage;
|
|
|
|
uint8_t maxSBAS;
|
|
|
|
uint8_t scanmode2;
|
|
|
|
uint32_t scanmode1;
|
|
|
|
};
|
2019-11-05 23:43:41 -04:00
|
|
|
// F9 config keys
|
|
|
|
enum class ConfigKey : uint32_t {
|
|
|
|
TMODE_MODE = 0x20030001,
|
2019-11-16 00:26:28 -04:00
|
|
|
CFG_RATE_MEAS = 0x30210001,
|
|
|
|
|
|
|
|
CFG_UART1_BAUDRATE = 0x40520001,
|
|
|
|
CFG_UART1_ENABLED = 0x10520005,
|
|
|
|
CFG_UART1INPROT_UBX = 0x10730001,
|
|
|
|
CFG_UART1INPROT_NMEA = 0x10730002,
|
|
|
|
CFG_UART1INPROT_RTCM3X = 0x10730004,
|
|
|
|
CFG_UART1OUTPROT_UBX = 0x10740001,
|
|
|
|
CFG_UART1OUTPROT_NMEA = 0x10740002,
|
|
|
|
CFG_UART1OUTPROT_RTCM3X = 0x10740004,
|
|
|
|
|
|
|
|
CFG_UART2_BAUDRATE = 0x40530001,
|
|
|
|
CFG_UART2_ENABLED = 0x10530005,
|
|
|
|
CFG_UART2INPROT_UBX = 0x10750001,
|
|
|
|
CFG_UART2INPROT_NMEA = 0x10750002,
|
|
|
|
CFG_UART2INPROT_RTCM3X = 0x10750004,
|
|
|
|
CFG_UART2OUTPROT_UBX = 0x10760001,
|
|
|
|
CFG_UART2OUTPROT_NMEA = 0x10760002,
|
|
|
|
CFG_UART2OUTPROT_RTCM3X = 0x10760004,
|
|
|
|
|
|
|
|
MSGOUT_RTCM_3X_TYPE4072_0_UART1 = 0x209102ff,
|
|
|
|
MSGOUT_RTCM_3X_TYPE4072_1_UART1 = 0x20910382,
|
|
|
|
MSGOUT_RTCM_3X_TYPE1077_UART1 = 0x209102cd,
|
|
|
|
MSGOUT_RTCM_3X_TYPE1087_UART1 = 0x209102d2,
|
|
|
|
MSGOUT_RTCM_3X_TYPE1097_UART1 = 0x20910319,
|
|
|
|
MSGOUT_RTCM_3X_TYPE1127_UART1 = 0x209102d7,
|
|
|
|
MSGOUT_RTCM_3X_TYPE1230_UART1 = 0x20910304,
|
|
|
|
MSGOUT_UBX_NAV_RELPOSNED_UART1 = 0x2091008e,
|
|
|
|
|
|
|
|
MSGOUT_RTCM_3X_TYPE4072_0_UART2 = 0x20910300,
|
|
|
|
MSGOUT_RTCM_3X_TYPE4072_1_UART2 = 0x20910383,
|
|
|
|
MSGOUT_RTCM_3X_TYPE1077_UART2 = 0x209102ce,
|
|
|
|
MSGOUT_RTCM_3X_TYPE1087_UART2 = 0x209102d3,
|
|
|
|
MSGOUT_RTCM_3X_TYPE1097_UART2 = 0x2091031a,
|
|
|
|
MSGOUT_RTCM_3X_TYPE1127_UART2 = 0x209102d8,
|
|
|
|
MSGOUT_RTCM_3X_TYPE1230_UART2 = 0x20910305,
|
|
|
|
MSGOUT_UBX_NAV_RELPOSNED_UART2 = 0x2091008f,
|
2022-11-20 23:33:46 -04:00
|
|
|
|
|
|
|
// enable specific signals and constellations
|
|
|
|
CFG_SIGNAL_GPS_ENA = 0x1031001f,
|
|
|
|
CFG_SIGNAL_GPS_L1CA_ENA = 0x10310001,
|
|
|
|
CFG_SIGNAL_GPS_L2C_ENA = 0x10310003,
|
|
|
|
CFG_SIGNAL_GPS_L5_ENA = 0x10310004,
|
|
|
|
CFG_SIGNAL_SBAS_ENA = 0x10310020,
|
|
|
|
CFG_SIGNAL_SBAS_L1CA_ENA = 0x10310005,
|
|
|
|
CFG_SIGNAL_GAL_ENA = 0x10310021,
|
|
|
|
CFG_SIGNAL_GAL_E1_ENA = 0x10310007,
|
|
|
|
CFG_SIGNAL_GAL_E5A_ENA = 0x10310009,
|
|
|
|
CFG_SIGNAL_GAL_E5B_ENA = 0x1031000a,
|
|
|
|
CFG_SIGNAL_BDS_ENA = 0x10310022,
|
|
|
|
CFG_SIGNAL_BDS_B1_ENA = 0x1031000d,
|
|
|
|
CFG_SIGNAL_BDS_B1C_ENA = 0x1031000f,
|
|
|
|
CFG_SIGNAL_BDS_B2_ENA = 0x1031000e,
|
|
|
|
CFG_SIGNAL_BDS_B2A_ENA = 0x10310028,
|
|
|
|
CFG_SIGNAL_QZSS_ENA = 0x10310024,
|
|
|
|
CFG_SIGNAL_QZSS_L1CA_ENA = 0x10310012,
|
|
|
|
CFG_SIGNAL_QZSS_L1S_ENA = 0x10310014,
|
|
|
|
CFG_SIGNAL_QZSS_L2C_ENA = 0x10310015,
|
|
|
|
CFG_SIGNAL_QZSS_L5_ENA = 0x10310017,
|
|
|
|
CFG_SIGNAL_GLO_ENA = 0x10310025,
|
|
|
|
CFG_SIGNAL_GLO_L1_ENA = 0x10310018,
|
|
|
|
CFG_SIGNAL_GLO_L2_ENA = 0x1031001a,
|
|
|
|
CFG_SIGNAL_NAVIC_ENA = 0x10310026,
|
|
|
|
CFG_SIGNAL_NAVIC_L5_ENA = 0x1031001d,
|
|
|
|
|
|
|
|
// other keys
|
|
|
|
CFG_NAVSPG_DYNMODEL = 0x20110021,
|
|
|
|
|
|
|
|
};
|
|
|
|
|
|
|
|
// layers for VALSET
|
|
|
|
#define UBX_VALSET_LAYER_RAM 0x1U
|
|
|
|
#define UBX_VALSET_LAYER_BBR 0x2U
|
|
|
|
#define UBX_VALSET_LAYER_FLASH 0x4U
|
|
|
|
#define UBX_VALSET_LAYER_ALL 0x7U
|
|
|
|
|
2019-11-05 23:43:41 -04:00
|
|
|
struct PACKED ubx_cfg_valset {
|
|
|
|
uint8_t version;
|
|
|
|
uint8_t layers;
|
|
|
|
uint8_t transaction;
|
|
|
|
uint8_t reserved[1];
|
|
|
|
uint32_t key;
|
|
|
|
};
|
|
|
|
struct PACKED ubx_cfg_valget {
|
|
|
|
uint8_t version;
|
|
|
|
uint8_t layers;
|
|
|
|
uint8_t reserved[2];
|
|
|
|
// variable length data, check buffer length
|
|
|
|
};
|
2013-05-09 07:04:36 -03:00
|
|
|
struct PACKED ubx_nav_posllh {
|
2018-05-15 22:16:01 -03:00
|
|
|
uint32_t itow; // GPS msToW
|
2012-08-17 03:19:44 -03:00
|
|
|
int32_t longitude;
|
|
|
|
int32_t latitude;
|
|
|
|
int32_t altitude_ellipsoid;
|
|
|
|
int32_t altitude_msl;
|
|
|
|
uint32_t horizontal_accuracy;
|
|
|
|
uint32_t vertical_accuracy;
|
2011-10-28 15:52:50 -03:00
|
|
|
};
|
2013-05-09 07:04:36 -03:00
|
|
|
struct PACKED ubx_nav_status {
|
2018-05-15 22:16:01 -03:00
|
|
|
uint32_t itow; // GPS msToW
|
2012-08-17 03:19:44 -03:00
|
|
|
uint8_t fix_type;
|
|
|
|
uint8_t fix_status;
|
|
|
|
uint8_t differential_status;
|
|
|
|
uint8_t res;
|
|
|
|
uint32_t time_to_first_fix;
|
|
|
|
uint32_t uptime; // milliseconds
|
2011-10-28 15:52:50 -03:00
|
|
|
};
|
2015-07-14 02:09:43 -03:00
|
|
|
struct PACKED ubx_nav_dop {
|
2018-05-15 22:16:01 -03:00
|
|
|
uint32_t itow; // GPS msToW
|
2015-07-14 02:09:43 -03:00
|
|
|
uint16_t gDOP;
|
|
|
|
uint16_t pDOP;
|
|
|
|
uint16_t tDOP;
|
|
|
|
uint16_t vDOP;
|
|
|
|
uint16_t hDOP;
|
|
|
|
uint16_t nDOP;
|
|
|
|
uint16_t eDOP;
|
|
|
|
};
|
2013-05-09 07:04:36 -03:00
|
|
|
struct PACKED ubx_nav_solution {
|
2018-05-15 22:16:01 -03:00
|
|
|
uint32_t itow;
|
2012-08-17 03:19:44 -03:00
|
|
|
int32_t time_nsec;
|
2013-12-11 02:21:02 -04:00
|
|
|
uint16_t week;
|
2012-08-17 03:19:44 -03:00
|
|
|
uint8_t fix_type;
|
|
|
|
uint8_t fix_status;
|
|
|
|
int32_t ecef_x;
|
|
|
|
int32_t ecef_y;
|
|
|
|
int32_t ecef_z;
|
|
|
|
uint32_t position_accuracy_3d;
|
|
|
|
int32_t ecef_x_velocity;
|
|
|
|
int32_t ecef_y_velocity;
|
|
|
|
int32_t ecef_z_velocity;
|
|
|
|
uint32_t speed_accuracy;
|
|
|
|
uint16_t position_DOP;
|
|
|
|
uint8_t res;
|
|
|
|
uint8_t satellites;
|
|
|
|
uint32_t res2;
|
2011-10-28 15:52:50 -03:00
|
|
|
};
|
2016-07-30 20:38:43 -03:00
|
|
|
struct PACKED ubx_nav_pvt {
|
|
|
|
uint32_t itow;
|
|
|
|
uint16_t year;
|
|
|
|
uint8_t month, day, hour, min, sec;
|
|
|
|
uint8_t valid;
|
|
|
|
uint32_t t_acc;
|
|
|
|
int32_t nano;
|
|
|
|
uint8_t fix_type;
|
|
|
|
uint8_t flags;
|
|
|
|
uint8_t flags2;
|
|
|
|
uint8_t num_sv;
|
|
|
|
int32_t lon, lat;
|
2022-06-14 17:50:54 -03:00
|
|
|
int32_t h_ellipsoid, h_msl;
|
2016-07-30 20:38:43 -03:00
|
|
|
uint32_t h_acc, v_acc;
|
|
|
|
int32_t velN, velE, velD, gspeed;
|
|
|
|
int32_t head_mot;
|
|
|
|
uint32_t s_acc;
|
|
|
|
uint32_t head_acc;
|
|
|
|
uint16_t p_dop;
|
2020-09-25 07:49:30 -03:00
|
|
|
uint8_t flags3;
|
|
|
|
uint8_t reserved1[5];
|
|
|
|
int32_t headVeh;
|
|
|
|
int16_t magDec;
|
|
|
|
uint16_t magAcc;
|
2016-07-30 20:38:43 -03:00
|
|
|
};
|
2019-09-03 16:32:09 -03:00
|
|
|
struct PACKED ubx_nav_relposned {
|
|
|
|
uint8_t version;
|
|
|
|
uint8_t reserved1;
|
|
|
|
uint16_t refStationId;
|
|
|
|
uint32_t iTOW;
|
|
|
|
int32_t relPosN;
|
|
|
|
int32_t relPosE;
|
|
|
|
int32_t relPosD;
|
|
|
|
int32_t relPosLength;
|
|
|
|
int32_t relPosHeading;
|
|
|
|
uint8_t reserved2[4];
|
|
|
|
int8_t relPosHPN;
|
|
|
|
int8_t relPosHPE;
|
|
|
|
int8_t relPosHPD;
|
|
|
|
int8_t relPosHPLength;
|
|
|
|
uint32_t accN;
|
|
|
|
uint32_t accE;
|
|
|
|
uint32_t accD;
|
|
|
|
uint32_t accLength;
|
|
|
|
uint32_t accHeading;
|
|
|
|
uint8_t reserved3[4];
|
|
|
|
uint32_t flags;
|
|
|
|
};
|
|
|
|
|
2013-05-09 07:04:36 -03:00
|
|
|
struct PACKED ubx_nav_velned {
|
2018-05-15 22:16:01 -03:00
|
|
|
uint32_t itow; // GPS msToW
|
2012-08-17 03:19:44 -03:00
|
|
|
int32_t ned_north;
|
|
|
|
int32_t ned_east;
|
|
|
|
int32_t ned_down;
|
|
|
|
uint32_t speed_3d;
|
|
|
|
uint32_t speed_2d;
|
|
|
|
int32_t heading_2d;
|
|
|
|
uint32_t speed_accuracy;
|
|
|
|
uint32_t heading_accuracy;
|
2011-10-28 15:52:50 -03:00
|
|
|
};
|
2015-07-29 19:39:11 -03:00
|
|
|
|
2019-03-30 01:21:11 -03:00
|
|
|
struct PACKED ubx_nav_timegps {
|
|
|
|
uint32_t itow;
|
|
|
|
int32_t ftow;
|
|
|
|
uint16_t week;
|
|
|
|
int8_t leapS;
|
|
|
|
uint8_t valid; // leapsvalid | weekvalid | tow valid;
|
|
|
|
uint32_t tAcc;
|
|
|
|
};
|
|
|
|
|
2014-04-02 20:55:05 -03:00
|
|
|
// Lea6 uses a 60 byte message
|
|
|
|
struct PACKED ubx_mon_hw_60 {
|
|
|
|
uint32_t pinSel;
|
|
|
|
uint32_t pinBank;
|
|
|
|
uint32_t pinDir;
|
|
|
|
uint32_t pinVal;
|
|
|
|
uint16_t noisePerMS;
|
|
|
|
uint16_t agcCnt;
|
|
|
|
uint8_t aStatus;
|
|
|
|
uint8_t aPower;
|
|
|
|
uint8_t flags;
|
|
|
|
uint8_t reserved1;
|
|
|
|
uint32_t usedMask;
|
|
|
|
uint8_t VP[17];
|
|
|
|
uint8_t jamInd;
|
|
|
|
uint16_t reserved3;
|
|
|
|
uint32_t pinIrq;
|
|
|
|
uint32_t pullH;
|
|
|
|
uint32_t pullL;
|
|
|
|
};
|
|
|
|
// Neo7 uses a 68 byte message
|
|
|
|
struct PACKED ubx_mon_hw_68 {
|
2014-03-23 22:02:37 -03:00
|
|
|
uint32_t pinSel;
|
|
|
|
uint32_t pinBank;
|
|
|
|
uint32_t pinDir;
|
|
|
|
uint32_t pinVal;
|
|
|
|
uint16_t noisePerMS;
|
|
|
|
uint16_t agcCnt;
|
|
|
|
uint8_t aStatus;
|
|
|
|
uint8_t aPower;
|
|
|
|
uint8_t flags;
|
|
|
|
uint8_t reserved1;
|
|
|
|
uint32_t usedMask;
|
|
|
|
uint8_t VP[25];
|
|
|
|
uint8_t jamInd;
|
|
|
|
uint16_t reserved3;
|
|
|
|
uint32_t pinIrq;
|
|
|
|
uint32_t pullH;
|
|
|
|
uint32_t pullL;
|
|
|
|
};
|
|
|
|
struct PACKED ubx_mon_hw2 {
|
|
|
|
int8_t ofsI;
|
|
|
|
uint8_t magI;
|
|
|
|
int8_t ofsQ;
|
|
|
|
uint8_t magQ;
|
|
|
|
uint8_t cfgSource;
|
|
|
|
uint8_t reserved0[3];
|
|
|
|
uint32_t lowLevCfg;
|
|
|
|
uint32_t reserved1[2];
|
|
|
|
uint32_t postStatus;
|
|
|
|
uint32_t reserved2;
|
|
|
|
};
|
2016-02-02 03:58:33 -04:00
|
|
|
struct PACKED ubx_mon_ver {
|
|
|
|
char swVersion[30];
|
|
|
|
char hwVersion[10];
|
|
|
|
char extension; // extensions are not enabled
|
|
|
|
};
|
2015-04-01 08:49:34 -03:00
|
|
|
struct PACKED ubx_nav_svinfo_header {
|
|
|
|
uint32_t itow;
|
|
|
|
uint8_t numCh;
|
|
|
|
uint8_t globalFlags;
|
|
|
|
uint16_t reserved;
|
|
|
|
};
|
2015-05-04 20:52:28 -03:00
|
|
|
#if UBLOX_RXM_RAW_LOGGING
|
2015-05-04 05:18:34 -03:00
|
|
|
struct PACKED ubx_rxm_raw {
|
|
|
|
int32_t iTOW;
|
|
|
|
int16_t week;
|
|
|
|
uint8_t numSV;
|
|
|
|
uint8_t reserved1;
|
|
|
|
struct ubx_rxm_raw_sv {
|
|
|
|
double cpMes;
|
|
|
|
double prMes;
|
|
|
|
float doMes;
|
|
|
|
uint8_t sv;
|
|
|
|
int8_t mesQI;
|
|
|
|
int8_t cno;
|
|
|
|
uint8_t lli;
|
|
|
|
} svinfo[UBLOX_MAX_RXM_RAW_SATS];
|
|
|
|
};
|
2015-06-29 19:04:35 -03:00
|
|
|
struct PACKED ubx_rxm_rawx {
|
|
|
|
double rcvTow;
|
|
|
|
uint16_t week;
|
|
|
|
int8_t leapS;
|
|
|
|
uint8_t numMeas;
|
|
|
|
uint8_t recStat;
|
|
|
|
uint8_t reserved1[3];
|
2015-07-20 00:13:50 -03:00
|
|
|
PACKED struct ubx_rxm_rawx_sv {
|
2015-06-29 19:04:35 -03:00
|
|
|
double prMes;
|
|
|
|
double cpMes;
|
|
|
|
float doMes;
|
|
|
|
uint8_t gnssId;
|
|
|
|
uint8_t svId;
|
2015-07-20 00:13:50 -03:00
|
|
|
uint8_t reserved2;
|
2015-06-29 19:04:35 -03:00
|
|
|
uint8_t freqId;
|
|
|
|
uint16_t locktime;
|
|
|
|
uint8_t cno;
|
|
|
|
uint8_t prStdev;
|
|
|
|
uint8_t cpStdev;
|
|
|
|
uint8_t doStdev;
|
|
|
|
uint8_t trkStat;
|
2015-07-20 00:13:50 -03:00
|
|
|
uint8_t reserved3;
|
2015-06-29 19:04:35 -03:00
|
|
|
} svinfo[UBLOX_MAX_RXM_RAWX_SATS];
|
|
|
|
};
|
2015-05-04 20:52:28 -03:00
|
|
|
#endif
|
2015-10-28 21:32:57 -03:00
|
|
|
|
|
|
|
struct PACKED ubx_ack_ack {
|
|
|
|
uint8_t clsID;
|
|
|
|
uint8_t msgID;
|
|
|
|
};
|
|
|
|
|
|
|
|
|
|
|
|
struct PACKED ubx_cfg_cfg {
|
|
|
|
uint32_t clearMask;
|
|
|
|
uint32_t saveMask;
|
|
|
|
uint32_t loadMask;
|
|
|
|
};
|
|
|
|
|
2022-03-06 20:24:31 -04:00
|
|
|
struct PACKED ubx_tim_tm2 {
|
|
|
|
uint8_t ch;
|
|
|
|
uint8_t flags;
|
|
|
|
uint16_t count;
|
|
|
|
uint16_t wnR;
|
|
|
|
uint16_t wnF;
|
|
|
|
uint32_t towMsR;
|
|
|
|
uint32_t towSubMsR;
|
|
|
|
uint32_t towMsF;
|
|
|
|
uint32_t towSubMsF;
|
|
|
|
uint32_t accEst;
|
|
|
|
};
|
|
|
|
|
2013-01-05 01:32:42 -04:00
|
|
|
// Receive buffer
|
2013-05-09 07:04:36 -03:00
|
|
|
union PACKED {
|
2016-06-06 10:49:46 -03:00
|
|
|
DEFINE_BYTE_ARRAY_METHODS
|
2013-01-05 01:32:42 -04:00
|
|
|
ubx_nav_posllh posllh;
|
|
|
|
ubx_nav_status status;
|
2015-07-14 02:09:43 -03:00
|
|
|
ubx_nav_dop dop;
|
2013-01-05 01:32:42 -04:00
|
|
|
ubx_nav_solution solution;
|
2016-07-30 20:38:43 -03:00
|
|
|
ubx_nav_pvt pvt;
|
2019-03-30 01:21:11 -03:00
|
|
|
ubx_nav_timegps timegps;
|
2013-01-05 01:32:42 -04:00
|
|
|
ubx_nav_velned velned;
|
2016-02-02 03:58:33 -04:00
|
|
|
ubx_cfg_msg_rate msg_rate;
|
|
|
|
ubx_cfg_msg_rate_6 msg_rate_6;
|
2013-01-05 01:32:42 -04:00
|
|
|
ubx_cfg_nav_settings nav_settings;
|
2016-02-02 03:58:33 -04:00
|
|
|
ubx_cfg_nav_rate nav_rate;
|
|
|
|
ubx_cfg_prt prt;
|
2014-04-02 20:55:05 -03:00
|
|
|
ubx_mon_hw_60 mon_hw_60;
|
|
|
|
ubx_mon_hw_68 mon_hw_68;
|
2014-03-23 22:02:37 -03:00
|
|
|
ubx_mon_hw2 mon_hw2;
|
2016-02-02 03:58:33 -04:00
|
|
|
ubx_mon_ver mon_ver;
|
2018-06-22 02:25:27 -03:00
|
|
|
ubx_cfg_tp5 nav_tp5;
|
2015-07-29 19:39:11 -03:00
|
|
|
#if UBLOX_GNSS_SETTINGS
|
2015-07-14 18:12:47 -03:00
|
|
|
ubx_cfg_gnss gnss;
|
2015-07-29 19:39:11 -03:00
|
|
|
#endif
|
2015-07-29 21:21:42 -03:00
|
|
|
ubx_cfg_sbas sbas;
|
2019-11-05 23:43:41 -04:00
|
|
|
ubx_cfg_valget valget;
|
2015-04-01 08:49:34 -03:00
|
|
|
ubx_nav_svinfo_header svinfo_header;
|
2019-09-03 16:32:09 -03:00
|
|
|
ubx_nav_relposned relposned;
|
2015-05-04 20:52:28 -03:00
|
|
|
#if UBLOX_RXM_RAW_LOGGING
|
2015-05-04 05:18:34 -03:00
|
|
|
ubx_rxm_raw rxm_raw;
|
2015-06-29 19:04:35 -03:00
|
|
|
ubx_rxm_rawx rxm_rawx;
|
2015-05-04 20:52:28 -03:00
|
|
|
#endif
|
2015-10-28 21:32:57 -03:00
|
|
|
ubx_ack_ack ack;
|
2022-03-06 20:24:31 -04:00
|
|
|
ubx_tim_tm2 tim_tm2;
|
2013-01-05 01:32:42 -04:00
|
|
|
} _buffer;
|
2013-01-04 04:39:15 -04:00
|
|
|
|
2019-09-03 16:32:09 -03:00
|
|
|
enum class RELPOSNED {
|
|
|
|
gnssFixOK = 1U << 0,
|
|
|
|
diffSoln = 1U << 1,
|
|
|
|
relPosValid = 1U << 2,
|
2019-10-07 03:00:11 -03:00
|
|
|
carrSolnFloat = 1U << 3,
|
2019-11-16 00:26:28 -04:00
|
|
|
|
2019-10-07 03:00:11 -03:00
|
|
|
carrSolnFixed = 1U << 4,
|
2019-09-03 16:32:09 -03:00
|
|
|
isMoving = 1U << 5,
|
|
|
|
refPosMiss = 1U << 6,
|
|
|
|
refObsMiss = 1U << 7,
|
2019-11-16 00:26:28 -04:00
|
|
|
|
2019-09-03 16:32:09 -03:00
|
|
|
relPosHeadingValid = 1U << 8,
|
|
|
|
relPosNormalized = 1U << 9
|
|
|
|
};
|
|
|
|
|
2011-10-28 15:52:50 -03:00
|
|
|
enum ubs_protocol_bytes {
|
|
|
|
PREAMBLE1 = 0xb5,
|
|
|
|
PREAMBLE2 = 0x62,
|
2012-06-10 03:34:13 -03:00
|
|
|
CLASS_NAV = 0x01,
|
|
|
|
CLASS_ACK = 0x05,
|
|
|
|
CLASS_CFG = 0x06,
|
2014-03-23 22:02:37 -03:00
|
|
|
CLASS_MON = 0x0A,
|
2015-05-04 05:18:34 -03:00
|
|
|
CLASS_RXM = 0x02,
|
2022-03-06 20:24:31 -04:00
|
|
|
CLASS_TIM = 0x0d,
|
2012-08-17 03:19:44 -03:00
|
|
|
MSG_ACK_NACK = 0x00,
|
|
|
|
MSG_ACK_ACK = 0x01,
|
2011-10-28 15:52:50 -03:00
|
|
|
MSG_POSLLH = 0x2,
|
|
|
|
MSG_STATUS = 0x3,
|
2015-07-14 02:09:43 -03:00
|
|
|
MSG_DOP = 0x4,
|
2011-10-28 15:52:50 -03:00
|
|
|
MSG_SOL = 0x6,
|
2016-07-30 20:38:43 -03:00
|
|
|
MSG_PVT = 0x7,
|
2019-03-30 01:21:11 -03:00
|
|
|
MSG_TIMEGPS = 0x20,
|
2019-09-03 16:32:09 -03:00
|
|
|
MSG_RELPOSNED = 0x3c,
|
2012-06-10 03:34:13 -03:00
|
|
|
MSG_VELNED = 0x12,
|
2015-10-28 21:32:57 -03:00
|
|
|
MSG_CFG_CFG = 0x09,
|
2012-06-10 03:34:13 -03:00
|
|
|
MSG_CFG_RATE = 0x08,
|
2016-02-02 03:58:33 -04:00
|
|
|
MSG_CFG_MSG = 0x01,
|
2014-03-23 22:02:37 -03:00
|
|
|
MSG_CFG_NAV_SETTINGS = 0x24,
|
2016-02-02 03:58:33 -04:00
|
|
|
MSG_CFG_PRT = 0x00,
|
2014-09-04 01:27:05 -03:00
|
|
|
MSG_CFG_SBAS = 0x16,
|
2015-07-14 18:12:47 -03:00
|
|
|
MSG_CFG_GNSS = 0x3E,
|
2018-06-22 02:25:27 -03:00
|
|
|
MSG_CFG_TP5 = 0x31,
|
2019-11-05 23:43:41 -04:00
|
|
|
MSG_CFG_VALSET = 0x8A,
|
|
|
|
MSG_CFG_VALGET = 0x8B,
|
2014-03-23 22:02:37 -03:00
|
|
|
MSG_MON_HW = 0x09,
|
2015-04-01 08:49:34 -03:00
|
|
|
MSG_MON_HW2 = 0x0B,
|
2016-02-02 03:58:33 -04:00
|
|
|
MSG_MON_VER = 0x04,
|
2015-05-04 05:18:34 -03:00
|
|
|
MSG_NAV_SVINFO = 0x30,
|
2015-06-29 19:04:35 -03:00
|
|
|
MSG_RXM_RAW = 0x10,
|
2022-03-06 20:24:31 -04:00
|
|
|
MSG_RXM_RAWX = 0x15,
|
|
|
|
MSG_TIM_TM2 = 0x03
|
2011-10-28 15:52:50 -03:00
|
|
|
};
|
2015-07-14 18:12:47 -03:00
|
|
|
enum ubx_gnss_identifier {
|
|
|
|
GNSS_GPS = 0x00,
|
|
|
|
GNSS_SBAS = 0x01,
|
|
|
|
GNSS_GALILEO = 0x02,
|
|
|
|
GNSS_BEIDOU = 0x03,
|
|
|
|
GNSS_IMES = 0x04,
|
|
|
|
GNSS_QZSS = 0x05,
|
|
|
|
GNSS_GLONASS = 0x06
|
|
|
|
};
|
2011-10-28 15:52:50 -03:00
|
|
|
enum ubs_nav_fix_type {
|
|
|
|
FIX_NONE = 0,
|
|
|
|
FIX_DEAD_RECKONING = 1,
|
|
|
|
FIX_2D = 2,
|
|
|
|
FIX_3D = 3,
|
|
|
|
FIX_GPS_DEAD_RECKONING = 4,
|
|
|
|
FIX_TIME = 5
|
|
|
|
};
|
|
|
|
enum ubx_nav_status_bits {
|
2015-06-18 11:53:28 -03:00
|
|
|
NAV_STATUS_FIX_VALID = 1,
|
|
|
|
NAV_STATUS_DGPS_USED = 2
|
2011-10-28 15:52:50 -03:00
|
|
|
};
|
2015-04-01 08:49:34 -03:00
|
|
|
enum ubx_hardware_version {
|
|
|
|
ANTARIS = 0,
|
|
|
|
UBLOX_5,
|
|
|
|
UBLOX_6,
|
|
|
|
UBLOX_7,
|
2017-05-24 14:42:03 -03:00
|
|
|
UBLOX_M8,
|
2020-10-05 01:23:24 -03:00
|
|
|
UBLOX_F9 = 0x80, // comes from MON_VER hwVersion/swVersion strings
|
|
|
|
UBLOX_M9 = 0x81, // comes from MON_VER hwVersion/swVersion strings
|
2022-11-20 23:33:46 -04:00
|
|
|
UBLOX_M10 = 0x82,
|
2017-05-24 14:42:03 -03:00
|
|
|
UBLOX_UNKNOWN_HARDWARE_GENERATION = 0xff // not in the ublox spec used for
|
|
|
|
// flagging state in the driver
|
2015-04-01 08:49:34 -03:00
|
|
|
};
|
2010-09-06 19:31:18 -03:00
|
|
|
|
2016-02-02 03:58:33 -04:00
|
|
|
enum config_step {
|
2017-01-12 02:19:35 -04:00
|
|
|
STEP_PVT = 0,
|
2017-02-15 19:20:21 -04:00
|
|
|
STEP_NAV_RATE, // poll NAV rate
|
2016-07-30 20:38:43 -03:00
|
|
|
STEP_SOL,
|
2017-01-12 02:19:35 -04:00
|
|
|
STEP_PORT,
|
|
|
|
STEP_STATUS,
|
2017-02-15 19:20:21 -04:00
|
|
|
STEP_POSLLH,
|
2017-01-12 02:19:35 -04:00
|
|
|
STEP_VELNED,
|
2019-03-30 01:21:11 -03:00
|
|
|
STEP_TIMEGPS,
|
2016-07-30 20:38:43 -03:00
|
|
|
STEP_POLL_SVINFO, // poll svinfo
|
|
|
|
STEP_POLL_SBAS, // poll SBAS
|
|
|
|
STEP_POLL_NAV, // poll NAV settings
|
|
|
|
STEP_POLL_GNSS, // poll GNSS
|
2018-06-22 02:25:27 -03:00
|
|
|
STEP_POLL_TP5, // poll TP5
|
2019-11-05 23:43:41 -04:00
|
|
|
STEP_TMODE, // set TMODE-MODE
|
2016-02-02 03:58:33 -04:00
|
|
|
STEP_DOP,
|
|
|
|
STEP_MON_HW,
|
|
|
|
STEP_MON_HW2,
|
|
|
|
STEP_RAW,
|
|
|
|
STEP_RAWX,
|
|
|
|
STEP_VERSION,
|
2019-12-22 18:33:59 -04:00
|
|
|
STEP_RTK_MOVBASE, // setup moving baseline
|
2022-03-06 20:24:31 -04:00
|
|
|
STEP_TIM_TM2,
|
2022-11-20 23:33:46 -04:00
|
|
|
STEP_M10,
|
2016-02-02 03:58:33 -04:00
|
|
|
STEP_LAST
|
|
|
|
};
|
|
|
|
|
2011-10-28 15:52:50 -03:00
|
|
|
// Packet checksum accumulators
|
2012-08-17 03:19:44 -03:00
|
|
|
uint8_t _ck_a;
|
|
|
|
uint8_t _ck_b;
|
2010-09-06 19:31:18 -03:00
|
|
|
|
2011-10-28 15:52:50 -03:00
|
|
|
// State machine state
|
2012-08-17 03:19:44 -03:00
|
|
|
uint8_t _step;
|
|
|
|
uint8_t _msg_id;
|
|
|
|
uint16_t _payload_length;
|
|
|
|
uint16_t _payload_counter;
|
2010-09-06 19:31:18 -03:00
|
|
|
|
2012-08-17 03:19:44 -03:00
|
|
|
uint8_t _class;
|
2015-10-28 21:32:57 -03:00
|
|
|
bool _cfg_saved;
|
2012-06-10 03:34:13 -03:00
|
|
|
|
2014-04-14 19:23:12 -03:00
|
|
|
uint32_t _last_vel_time;
|
|
|
|
uint32_t _last_pos_time;
|
2015-11-04 17:14:27 -04:00
|
|
|
uint32_t _last_cfg_sent_time;
|
2015-11-09 17:31:15 -04:00
|
|
|
uint8_t _num_cfg_save_tries;
|
2016-02-02 03:58:33 -04:00
|
|
|
uint32_t _last_config_time;
|
|
|
|
uint16_t _delay_time;
|
|
|
|
uint8_t _next_message;
|
|
|
|
uint8_t _ublox_port;
|
|
|
|
bool _have_version;
|
2016-08-02 02:48:16 -03:00
|
|
|
struct ubx_mon_ver _version;
|
2016-02-02 03:58:33 -04:00
|
|
|
uint32_t _unconfigured_messages;
|
|
|
|
uint8_t _hardware_generation;
|
2020-04-02 21:51:22 -03:00
|
|
|
uint32_t _last_pvt_itow;
|
|
|
|
uint32_t _last_relposned_itow;
|
|
|
|
uint32_t _last_relposned_ms;
|
2016-02-02 03:58:33 -04:00
|
|
|
|
2019-11-16 00:26:28 -04:00
|
|
|
// the role set from GPS_TYPE
|
|
|
|
AP_GPS::GPS_Role role;
|
2014-04-14 19:23:12 -03:00
|
|
|
|
2012-08-17 03:19:44 -03:00
|
|
|
// do we have new position information?
|
2014-03-23 22:02:37 -03:00
|
|
|
bool _new_position:1;
|
2012-08-17 03:19:44 -03:00
|
|
|
// do we have new speed information?
|
2014-03-23 22:02:37 -03:00
|
|
|
bool _new_speed:1;
|
|
|
|
|
2012-08-17 03:19:44 -03:00
|
|
|
uint8_t _disable_counter;
|
2012-06-10 03:34:13 -03:00
|
|
|
|
2011-10-28 15:52:50 -03:00
|
|
|
// Buffer parse & GPS state update
|
2012-08-17 03:19:44 -03:00
|
|
|
bool _parse_gps();
|
2012-06-04 01:47:58 -03:00
|
|
|
|
2012-08-17 03:19:44 -03:00
|
|
|
// used to update fix between status and position packets
|
2014-03-28 16:52:27 -03:00
|
|
|
AP_GPS::GPS_Status next_fix;
|
2012-06-10 03:34:13 -03:00
|
|
|
|
2016-02-12 16:32:08 -04:00
|
|
|
bool _cfg_needs_save;
|
|
|
|
|
2015-11-16 02:08:52 -04:00
|
|
|
bool noReceivedHdop;
|
2016-07-30 20:38:43 -03:00
|
|
|
|
|
|
|
bool havePvtMsg;
|
2015-08-07 07:20:55 -03:00
|
|
|
|
2016-02-02 03:58:33 -04:00
|
|
|
bool _configure_message_rate(uint8_t msg_class, uint8_t msg_id, uint8_t rate);
|
2022-11-20 23:33:46 -04:00
|
|
|
bool _configure_valset(ConfigKey key, const void *value, uint8_t layers=UBX_VALSET_LAYER_ALL);
|
2019-11-05 23:43:41 -04:00
|
|
|
bool _configure_valget(ConfigKey key);
|
2016-02-02 03:58:33 -04:00
|
|
|
void _configure_rate(void);
|
2014-09-04 01:27:05 -03:00
|
|
|
void _configure_sbas(bool enable);
|
2015-05-04 05:18:34 -03:00
|
|
|
void _update_checksum(uint8_t *data, uint16_t len, uint8_t &ck_a, uint8_t &ck_b);
|
2022-01-09 18:38:04 -04:00
|
|
|
bool _send_message(uint8_t msg_class, uint8_t msg_id, const void *msg, uint16_t size);
|
2016-02-02 03:58:33 -04:00
|
|
|
void send_next_rate_update(void);
|
|
|
|
bool _request_message_rate(uint8_t msg_class, uint8_t msg_id);
|
|
|
|
void _request_next_config(void);
|
|
|
|
void _request_port(void);
|
2015-04-01 08:49:34 -03:00
|
|
|
void _request_version(void);
|
2015-10-28 21:32:57 -03:00
|
|
|
void _save_cfg(void);
|
2016-02-02 03:58:33 -04:00
|
|
|
void _verify_rate(uint8_t msg_class, uint8_t msg_id, uint8_t rate);
|
2018-05-15 22:16:01 -03:00
|
|
|
void _check_new_itow(uint32_t itow);
|
2012-06-10 03:34:13 -03:00
|
|
|
|
2014-03-23 22:02:37 -03:00
|
|
|
void unexpected_message(void);
|
|
|
|
void log_mon_hw(void);
|
|
|
|
void log_mon_hw2(void);
|
2022-03-06 20:24:31 -04:00
|
|
|
void log_tim_tm2(void);
|
2015-05-04 05:18:34 -03:00
|
|
|
void log_rxm_raw(const struct ubx_rxm_raw &raw);
|
2015-06-29 19:04:35 -03:00
|
|
|
void log_rxm_rawx(const struct ubx_rxm_rawx &raw);
|
2015-07-21 16:06:05 -03:00
|
|
|
|
2020-09-29 16:47:37 -03:00
|
|
|
#if GPS_MOVING_BASELINE
|
2020-04-03 00:54:15 -03:00
|
|
|
// see if we should use uart2 for moving baseline config
|
|
|
|
bool mb_use_uart2(void) const {
|
2022-06-14 17:43:04 -03:00
|
|
|
return option_set(AP_GPS::DriverOptions::UBX_MBUseUart2)?true:false;
|
2020-04-03 00:54:15 -03:00
|
|
|
}
|
2020-04-03 03:52:42 -03:00
|
|
|
#endif
|
2019-11-16 00:26:28 -04:00
|
|
|
|
|
|
|
// structure for list of config key/value pairs for
|
|
|
|
// specific configurations
|
|
|
|
struct PACKED config_list {
|
|
|
|
ConfigKey key;
|
|
|
|
// support up to 4 byte values, assumes little-endian
|
|
|
|
uint32_t value;
|
|
|
|
};
|
|
|
|
|
|
|
|
// return size of a config key payload
|
|
|
|
uint8_t config_key_size(ConfigKey key) const;
|
|
|
|
|
|
|
|
// configure a set of config key/value pairs. The unconfig_bit corresponds to
|
|
|
|
// a bit in _unconfigured_messages
|
2022-11-20 23:33:46 -04:00
|
|
|
bool _configure_config_set(const config_list *list, uint8_t count, uint32_t unconfig_bit, uint8_t layers=UBX_VALSET_LAYER_ALL);
|
2019-11-16 00:26:28 -04:00
|
|
|
|
|
|
|
// find index in active_config list
|
|
|
|
int8_t find_active_config_index(ConfigKey key) const;
|
|
|
|
|
2019-12-17 21:50:20 -04:00
|
|
|
// return true if GPS is capable of F9 config
|
|
|
|
bool supports_F9_config(void) const;
|
|
|
|
|
2022-01-18 07:37:15 -04:00
|
|
|
uint8_t _pps_freq = 1;
|
2022-01-16 08:15:59 -04:00
|
|
|
#ifdef HAL_GPIO_PPS
|
|
|
|
void pps_interrupt(uint8_t pin, bool high, uint32_t timestamp_us);
|
2022-01-18 07:37:15 -04:00
|
|
|
void set_pps_desired_freq(uint8_t freq) override;
|
2022-01-16 08:15:59 -04:00
|
|
|
#endif
|
|
|
|
|
2022-11-20 23:33:46 -04:00
|
|
|
// status of active configuration for a role
|
|
|
|
struct {
|
|
|
|
const config_list *list;
|
|
|
|
uint8_t count;
|
|
|
|
uint32_t done_mask;
|
|
|
|
uint32_t unconfig_bit;
|
|
|
|
uint8_t layers;
|
|
|
|
} active_config;
|
|
|
|
|
2020-09-29 16:47:37 -03:00
|
|
|
#if GPS_MOVING_BASELINE
|
2019-11-16 00:26:28 -04:00
|
|
|
// config for moving baseline base
|
2020-04-03 00:54:15 -03:00
|
|
|
static const config_list config_MB_Base_uart1[];
|
|
|
|
static const config_list config_MB_Base_uart2[];
|
2019-11-16 00:26:28 -04:00
|
|
|
|
|
|
|
// config for moving baseline rover
|
2020-04-03 00:54:15 -03:00
|
|
|
static const config_list config_MB_Rover_uart1[];
|
|
|
|
static const config_list config_MB_Rover_uart2[];
|
|
|
|
|
2019-11-16 00:26:28 -04:00
|
|
|
// RTCM3 parser for when in moving baseline base mode
|
|
|
|
RTCM3_Parser *rtcm3_parser;
|
2020-09-29 16:47:37 -03:00
|
|
|
#endif // GPS_MOVING_BASELINE
|
2022-11-20 23:33:46 -04:00
|
|
|
|
|
|
|
static const config_list config_M10[];
|
2010-09-06 17:16:50 -03:00
|
|
|
};
|
2022-04-09 21:07:37 -03:00
|
|
|
|
|
|
|
#endif
|