mirror of https://github.com/ArduPilot/ardupilot
GPS: re-open the serial port with a 256 byte serial receive buffer
this ensures all GPS parsers have a 256 byte buffer available
This commit is contained in:
parent
bfb2c1ee87
commit
f4718cafad
|
@ -65,7 +65,8 @@ AP_GPS_Auto::read(void)
|
||||||
//
|
//
|
||||||
for (i = 0; i < (sizeof(baudrates) / sizeof(baudrates[0])); i++) {
|
for (i = 0; i < (sizeof(baudrates) / sizeof(baudrates[0])); i++) {
|
||||||
|
|
||||||
_fs->begin(baudrates[i]);
|
// ensure the serial port has a large enough buffer for any protocol
|
||||||
|
_fs->begin(baudrates[i], 256, 16);
|
||||||
if (NULL != (gps = _detect())) {
|
if (NULL != (gps = _detect())) {
|
||||||
|
|
||||||
// configure the detected GPS and give it a chance to listen to its device
|
// configure the detected GPS and give it a chance to listen to its device
|
||||||
|
|
|
@ -94,13 +94,6 @@ const char AP_GPS_NMEA::_gpvtg_string[] PROGMEM = "GPVTG";
|
||||||
AP_GPS_NMEA::AP_GPS_NMEA(Stream *s) :
|
AP_GPS_NMEA::AP_GPS_NMEA(Stream *s) :
|
||||||
GPS(s)
|
GPS(s)
|
||||||
{
|
{
|
||||||
FastSerial *fs = (FastSerial *)_port;
|
|
||||||
|
|
||||||
// Re-open the port with enough receive buffering for the messages we expect
|
|
||||||
// and very little tx buffering, since we don't care about sending.
|
|
||||||
// Leave the port speed alone as we don't actually know at what rate we're running...
|
|
||||||
//
|
|
||||||
fs->begin(0, 200, 16);
|
|
||||||
}
|
}
|
||||||
|
|
||||||
// Public Methods //////////////////////////////////////////////////////////////
|
// Public Methods //////////////////////////////////////////////////////////////
|
||||||
|
|
Loading…
Reference in New Issue