Browse Source

AP_GPS: Add baudrate 230400 for GPS

Needed by bebop gps by default
mission-4.1.18
Julien BERAUD 10 years ago committed by Andrew Tridgell
parent
commit
b32259307d
  1. 2
      libraries/AP_GPS/AP_GPS.cpp

2
libraries/AP_GPS/AP_GPS.cpp

@ -125,7 +125,7 @@ void AP_GPS::init(DataFlash_Class *dataflash, const AP_SerialManager& serial_man @@ -125,7 +125,7 @@ void AP_GPS::init(DataFlash_Class *dataflash, const AP_SerialManager& serial_man
}
// baudrates to try to detect GPSes with
const uint32_t AP_GPS::_baudrates[] PROGMEM = {4800U, 38400U, 115200U, 57600U, 9600U};
const uint32_t AP_GPS::_baudrates[] PROGMEM = {4800U, 38400U, 115200U, 57600U, 9600U, 230400U};
// initialisation blobs to send to the GPS to try to get it into the
// right mode

Loading…
Cancel
Save