mirror of https://github.com/ArduPilot/ardupilot
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:
parent
296e651b30
commit
a684bddbda
|
@ -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
|
||||
|
|
|
@ -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"),
|
||||
|
|
Loading…
Reference in New Issue