From 3dd4f3046014d4dcbaa12421a755ea628a8e9d15 Mon Sep 17 00:00:00 2001 From: Lee Hicks Date: Mon, 8 Aug 2016 14:22:44 -0500 Subject: [PATCH] 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. --- libraries/AP_GPS/AP_GPS.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_GPS/AP_GPS.cpp b/libraries/AP_GPS/AP_GPS.cpp index 0689a14b5d..e603419f4b 100644 --- a/libraries/AP_GPS/AP_GPS.cpp +++ b/libraries/AP_GPS/AP_GPS.cpp @@ -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