From f4718cafad71f4b6e7f38489e46435dc9d2e3403 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Fri, 8 Jun 2012 16:40:30 +1000 Subject: [PATCH] GPS: re-open the serial port with a 256 byte serial receive buffer this ensures all GPS parsers have a 256 byte buffer available --- libraries/AP_GPS/AP_GPS_Auto.cpp | 3 ++- libraries/AP_GPS/AP_GPS_NMEA.cpp | 7 ------- 2 files changed, 2 insertions(+), 8 deletions(-) diff --git a/libraries/AP_GPS/AP_GPS_Auto.cpp b/libraries/AP_GPS/AP_GPS_Auto.cpp index c64d8fb464..724041e0e2 100644 --- a/libraries/AP_GPS/AP_GPS_Auto.cpp +++ b/libraries/AP_GPS/AP_GPS_Auto.cpp @@ -65,7 +65,8 @@ AP_GPS_Auto::read(void) // for (i = 0; i < (sizeof(baudrates) / sizeof(baudrates[0])); i++) { - _fs->begin(baudrates[i]); + // ensure the serial port has a large enough buffer for any protocol + _fs->begin(baudrates[i], 256, 16); if (NULL != (gps = _detect())) { // configure the detected GPS and give it a chance to listen to its device diff --git a/libraries/AP_GPS/AP_GPS_NMEA.cpp b/libraries/AP_GPS/AP_GPS_NMEA.cpp index 15bc788d5a..47d3969840 100644 --- a/libraries/AP_GPS/AP_GPS_NMEA.cpp +++ b/libraries/AP_GPS/AP_GPS_NMEA.cpp @@ -94,13 +94,6 @@ const char AP_GPS_NMEA::_gpvtg_string[] PROGMEM = "GPVTG"; AP_GPS_NMEA::AP_GPS_NMEA(Stream *s) : GPS(s) { - FastSerial *fs = (FastSerial *)_port; - - // Re-open the port with enough receive buffering for the messages we expect - // and very little tx buffering, since we don't care about sending. - // Leave the port speed alone as we don't actually know at what rate we're running... - // - fs->begin(0, 200, 16); } // Public Methods //////////////////////////////////////////////////////////////