mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-26 18:48:30 -04:00
AP_GPS: Adding 19200 as serial speed for GPS
APM supports baud speeds of 19200, but GPS baud rates don't support it. This commit adds it to follow APM supported baud rates.
This commit is contained in:
parent
6e643d64b7
commit
3dd4f30460
@ -155,7 +155,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[] = {4800U, 38400U, 115200U, 57600U, 9600U, 230400U};
|
||||
const uint32_t AP_GPS::_baudrates[] = {4800U, 19200U, 38400U, 115200U, 57600U, 9600U, 230400U};
|
||||
|
||||
// initialisation blobs to send to the GPS to try to get it into the
|
||||
// right mode
|
||||
|
Loading…
Reference in New Issue
Block a user