AP_GPS: Add baudrate 230400 for GPS

Needed by bebop gps by default
This commit is contained in:
Julien BERAUD 2015-06-30 16:09:00 +02:00 committed by Andrew Tridgell
parent 282efe2d57
commit b32259307d
1 changed files with 1 additions and 1 deletions

View File

@ -125,7 +125,7 @@ void AP_GPS::init(DataFlash_Class *dataflash, const AP_SerialManager& serial_man
} }
// baudrates to try to detect GPSes with // 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 // initialisation blobs to send to the GPS to try to get it into the
// right mode // right mode