mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
AP_GPS: stop reading arbitrary amounts of data in GPS init
We don't like doing this in other places as the vehicle can go out to lunch for arbitrary periods of time
This commit is contained in:
parent
b88f414320
commit
00329ae443
@ -744,7 +744,14 @@ AP_GPS_Backend *AP_GPS::_detect_instance(uint8_t instance)
|
||||
send_blob_update(instance);
|
||||
}
|
||||
|
||||
while (initblob_state[instance].remaining == 0 && _port[instance]->available() > 0) {
|
||||
if (initblob_state[instance].remaining != 0) {
|
||||
// don't run detection engines if we haven't sent out the initblobs
|
||||
return nullptr;
|
||||
}
|
||||
|
||||
uint16_t bytecount = MIN(8192U, _port[instance]->available());
|
||||
|
||||
while (bytecount-- > 0) {
|
||||
uint8_t data = _port[instance]->read();
|
||||
/*
|
||||
running a uBlox at less than 38400 will lead to packet
|
||||
|
Loading…
Reference in New Issue
Block a user