Browse Source

AP_GPS: Raise target baud of u-blox devices

A knockon effect is that we need less config strings as raw logging
on u-blox will use the same baud rates
master
Michael du Breuil 9 years ago committed by Andrew Tridgell
parent
commit
3e3f539a6a
  1. 7
      libraries/AP_GPS/AP_GPS.cpp
  2. 3
      libraries/AP_GPS/AP_GPS_UBLOX.h

7
libraries/AP_GPS/AP_GPS.cpp

@ -161,7 +161,6 @@ const uint32_t AP_GPS::_baudrates[] = {4800U, 19200U, 38400U, 115200U, 57600U, 9
// initialisation blobs to send to the GPS to try to get it into the // initialisation blobs to send to the GPS to try to get it into the
// right mode // 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 MTK_SET_BINARY SIRF_SET_BINARY;
const char AP_GPS::_initialisation_raw_blob[] = UBLOX_SET_BINARY_RAW_BAUD MTK_SET_BINARY SIRF_SET_BINARY;
/* /*
send some more initialisation string bytes if there is room in the send some more initialisation string bytes if there is room in the
@ -268,11 +267,7 @@ AP_GPS::detect_instance(uint8_t instance)
_port[instance]->begin(baudrate); _port[instance]->begin(baudrate);
_port[instance]->set_flow_control(AP_HAL::UARTDriver::FLOW_CONTROL_DISABLE); _port[instance]->set_flow_control(AP_HAL::UARTDriver::FLOW_CONTROL_DISABLE);
dstate->last_baud_change_ms = now; dstate->last_baud_change_ms = now;
#if UBLOX_RXM_RAW_LOGGING
if(_raw_data != 0)
send_blob_start(instance, _initialisation_raw_blob, sizeof(_initialisation_raw_blob));
else
#endif
if(_auto_config == 1){ if(_auto_config == 1){
send_blob_start(instance, _initialisation_blob, sizeof(_initialisation_blob)); send_blob_start(instance, _initialisation_blob, sizeof(_initialisation_blob));
} }

3
libraries/AP_GPS/AP_GPS_UBLOX.h

@ -38,8 +38,7 @@
* modules are configured with all ubx binary messages off, which * modules are configured with all ubx binary messages off, which
* would mean we would never detect it. * 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,0003,0001,38400,0*26\r\n" #define UBLOX_SET_BINARY "\265\142\006\001\003\000\001\006\001\022\117$PUBX,41,1,0003,0001,115200,0*1E\r\n"
#define UBLOX_SET_BINARY_RAW_BAUD "\265\142\006\001\003\000\001\006\001\022\117$PUBX,41,1,0003,0001,115200,0*1E\r\n"
#define UBLOX_RXM_RAW_LOGGING 1 #define UBLOX_RXM_RAW_LOGGING 1
#define UBLOX_MAX_RXM_RAW_SATS 22 #define UBLOX_MAX_RXM_RAW_SATS 22

Loading…
Cancel
Save