mirror of https://github.com/ArduPilot/ardupilot
Rover: raise GPS serial buffer size
This commit is contained in:
parent
c15d784976
commit
cfeecdae46
|
@ -110,7 +110,7 @@ static void init_ardupilot()
|
|||
// on the message set configured.
|
||||
//
|
||||
// standard gps running
|
||||
hal.uartB->begin(115200, 128, 16);
|
||||
hal.uartB->begin(115200, 256, 16);
|
||||
|
||||
cliSerial->printf_P(PSTR("\n\nInit " THISFIRMWARE
|
||||
"\n\nFree RAM: %u\n"),
|
||||
|
|
Loading…
Reference in New Issue