From bfb2c1ee872ede859a749f6555b33dbf54a49311 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Fri, 8 Jun 2012 16:39:48 +1000 Subject: [PATCH] GPS: open the GPS serial port with a 256 byte buffer the UBLOX needs more than 128 bytes for reliable parsing --- ArduCopter/system.pde | 4 +++- ArduPlane/system.pde | 2 +- 2 files changed, 4 insertions(+), 2 deletions(-) diff --git a/ArduCopter/system.pde b/ArduCopter/system.pde index f68eb6872b..14dad5a4c0 100644 --- a/ArduCopter/system.pde +++ b/ArduCopter/system.pde @@ -83,7 +83,9 @@ static void init_ardupilot() // GPS serial port. // #if GPS_PROTOCOL != GPS_PROTOCOL_IMU - Serial1.begin(38400, 128, 16); + // standard gps running. Note that we need a 256 byte buffer for some + // GPS types (eg. UBLOX) + Serial1.begin(38400, 256, 16); #endif Serial.printf_P(PSTR("\n\nInit " THISFIRMWARE diff --git a/ArduPlane/system.pde b/ArduPlane/system.pde index 3a856b827c..ea6d30b5ad 100644 --- a/ArduPlane/system.pde +++ b/ArduPlane/system.pde @@ -86,7 +86,7 @@ static void init_ardupilot() // GPS serial port. // // standard gps running - Serial1.begin(38400, 128, 16); + Serial1.begin(38400, 256, 16); Serial.printf_P(PSTR("\n\nInit " THISFIRMWARE "\n\nFree RAM: %u\n"),