Browse Source

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
master
Michael du Breuil 8 years ago committed by Randy Mackay
parent
commit
cb1b9b6674
  1. 3
      libraries/AP_GPS/AP_GPS_SBF.cpp

3
libraries/AP_GPS/AP_GPS_SBF.cpp

@ -65,7 +65,8 @@ AP_GPS_SBF::read(void) @@ -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;
}
}

Loading…
Cancel
Save