From cb1b9b667437f1f00626c3df6d93633c845688c2 Mon Sep 17 00:00:00 2001 From: Michael du Breuil Date: Mon, 10 Jul 2017 13:34:16 -0700 Subject: [PATCH] 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 --- libraries/AP_GPS/AP_GPS_SBF.cpp | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/libraries/AP_GPS/AP_GPS_SBF.cpp b/libraries/AP_GPS/AP_GPS_SBF.cpp index 8c4ad5fc1b..07f41c159e 100644 --- a/libraries/AP_GPS/AP_GPS_SBF.cpp +++ b/libraries/AP_GPS/AP_GPS_SBF.cpp @@ -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; } }