Skip to content
Snippets Groups Projects
Commit bfb2c1ee authored by Andrew Tridgell's avatar Andrew Tridgell
Browse files

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

the UBLOX needs more than 128 bytes for reliable parsing
parent ddebf7b4
No related branches found
No related tags found
No related merge requests found
...@@ -83,7 +83,9 @@ static void init_ardupilot() ...@@ -83,7 +83,9 @@ static void init_ardupilot()
// GPS serial port. // GPS serial port.
// //
#if GPS_PROTOCOL != GPS_PROTOCOL_IMU #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 #endif
Serial.printf_P(PSTR("\n\nInit " THISFIRMWARE Serial.printf_P(PSTR("\n\nInit " THISFIRMWARE
......
...@@ -86,7 +86,7 @@ static void init_ardupilot() ...@@ -86,7 +86,7 @@ static void init_ardupilot()
// GPS serial port. // GPS serial port.
// //
// standard gps running // standard gps running
Serial1.begin(38400, 128, 16); Serial1.begin(38400, 256, 16);
Serial.printf_P(PSTR("\n\nInit " THISFIRMWARE Serial.printf_P(PSTR("\n\nInit " THISFIRMWARE
"\n\nFree RAM: %u\n"), "\n\nFree RAM: %u\n"),
......
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment