From 78858bbcddf36a572c3433a1cfec72066262ffe8 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Fri, 22 May 2020 12:13:08 +1000 Subject: [PATCH] AP_GPS: switch ublox over to 230400 baud this ensures we have sufficient bandwidth for raw data --- libraries/AP_GPS/AP_GPS.cpp | 6 +++--- libraries/AP_GPS/AP_GPS_UBLOX.h | 2 +- 2 files changed, 4 insertions(+), 4 deletions(-) diff --git a/libraries/AP_GPS/AP_GPS.cpp b/libraries/AP_GPS/AP_GPS.cpp index 7cbb394b95..1671ebe9ff 100644 --- a/libraries/AP_GPS/AP_GPS.cpp +++ b/libraries/AP_GPS/AP_GPS.cpp @@ -64,7 +64,7 @@ const uint32_t AP_GPS::_baudrates[] = {9600U, 115200U, 4800U, 19200U, 38400U, 57 // initialisation blobs to send to the GPS to try to get it into the // right mode -const char AP_GPS::_initialisation_blob[] = UBLOX_SET_BINARY MTK_SET_BINARY SIRF_SET_BINARY; +const char AP_GPS::_initialisation_blob[] = UBLOX_SET_BINARY_230400 MTK_SET_BINARY SIRF_SET_BINARY; AP_GPS *AP_GPS::_singleton; @@ -565,13 +565,13 @@ void AP_GPS::detect_instance(uint8_t instance) 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 115200 no matter what rate it is configured + the uBlox into 230400 no matter what rate it is configured for. */ if ((_type[instance] == GPS_TYPE_AUTO || _type[instance] == GPS_TYPE_UBLOX) && ((!_auto_config && _baudrates[dstate->current_baud] >= 38400) || - _baudrates[dstate->current_baud] == 115200) && + _baudrates[dstate->current_baud] == 230400) && AP_GPS_UBLOX::_detect(dstate->ublox_detect_state, data)) { new_gps = new AP_GPS_UBLOX(*this, state[instance], _port[instance], GPS_ROLE_NORMAL); } diff --git a/libraries/AP_GPS/AP_GPS_UBLOX.h b/libraries/AP_GPS/AP_GPS_UBLOX.h index 5c8c3f5e4f..0a67213824 100644 --- a/libraries/AP_GPS/AP_GPS_UBLOX.h +++ b/libraries/AP_GPS/AP_GPS_UBLOX.h @@ -37,7 +37,7 @@ * modules are configured with all ubx binary messages off, which * would mean we would never detect it. */ -#define UBLOX_SET_BINARY "\265\142\006\001\003\000\001\006\001\022\117$PUBX,41,1,0023,0001,115200,0*1C\r\n" +#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" // a varient with 230400 baudrate #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"