mirror of https://github.com/ArduPilot/ardupilot
AP_GPS: fixed multiple GPS detection bug
This commit is contained in:
parent
fb4540a349
commit
4a6b46c661
|
@ -85,7 +85,7 @@ AP_GPS_Auto::_detect(void)
|
|||
detect_started_ms = hal.scheduler->millis();
|
||||
}
|
||||
|
||||
while (_port->available() > 0) {
|
||||
while (_port->available() > 0 && new_gps == NULL) {
|
||||
uint8_t data = _port->read();
|
||||
if (AP_GPS_UBLOX::_detect(data)) {
|
||||
hal.console->print_P(PSTR(" ublox "));
|
||||
|
|
Loading…
Reference in New Issue