AP_GPS: Fix SBF race condition on start

Unsure what the underlying problem is, but the length of the first string in
the initilisation_blob increasing resulted in a race condition, waiting
longer before retrying the message resolves it, but we still need to identify
the underlying problem. This patch just results in the GPS working with current
configurations. Tested against AsteRx-M firmware 3.6.3
This commit is contained in:
Michael du Breuil 2017-07-10 13:34:16 -07:00 committed by Randy Mackay
parent 20889ff8a9
commit cb1b9b6674
1 changed files with 2 additions and 1 deletions

View File

@ -65,7 +65,8 @@ AP_GPS_SBF::read(void)
if (now > _init_blob_time) {
port->write((const uint8_t*)init_str, strlen(init_str));
_init_blob_time = now + 1000;
// if this is too low a race condition on start occurs and the GPS isn't detected
_init_blob_time = now + 2000;
}
}