diff --git a/libraries/AP_GPS/AP_GPS.cpp b/libraries/AP_GPS/AP_GPS.cpp index 886333859c..1f3f2f3115 100644 --- a/libraries/AP_GPS/AP_GPS.cpp +++ b/libraries/AP_GPS/AP_GPS.cpp @@ -753,13 +753,6 @@ AP_GPS_Backend *AP_GPS::_detect_instance(uint8_t instance) while (bytecount-- > 0) { uint8_t data = _port[instance]->read(); - /* - 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. - */ #if AP_GPS_UBLOX_ENABLED if ((_type[instance] == GPS_TYPE_AUTO || diff --git a/libraries/AP_GPS/AP_GPS_UBLOX.h b/libraries/AP_GPS/AP_GPS_UBLOX.h index b0f75435ec..872ec83243 100644 --- a/libraries/AP_GPS/AP_GPS_UBLOX.h +++ b/libraries/AP_GPS/AP_GPS_UBLOX.h @@ -38,6 +38,12 @@ * 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. + + * 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. */ #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"