GPS: open the GPS serial port with a 256 byte buffer

the UBLOX needs more than 128 bytes for reliable parsing
This commit is contained in:
Andrew Tridgell 2012-06-08 16:39:48 +10:00
parent 296e651b30
commit a684bddbda
2 changed files with 4 additions and 2 deletions

View File

@ -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

View File

@ -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"),