From ebf5f98dbd90d16d5c48b4501ecc06800f30fbfd Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Mon, 26 Jan 2015 22:21:08 +0900 Subject: [PATCH] GPS: detect_instance does not set uart rx, tx size --- 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 933d4326ed..10033f7513 100644 --- a/libraries/AP_GPS/AP_GPS.cpp +++ b/libraries/AP_GPS/AP_GPS.cpp @@ -186,7 +186,7 @@ AP_GPS::detect_instance(uint8_t instance) dstate->last_baud = 0; } uint32_t baudrate = pgm_read_dword(&_baudrates[dstate->last_baud]); - _port[instance]->begin(baudrate, 256, 16); + _port[instance]->begin(baudrate); dstate->last_baud_change_ms = now; send_blob_start(instance, _initialisation_blob, sizeof(_initialisation_blob)); }