From 51e8d8a29424c8ff83e29678964313975082cd4b Mon Sep 17 00:00:00 2001 From: Lee Hicks Date: Mon, 8 Aug 2016 14:23:17 -0500 Subject: [PATCH] AP_GPS: Don't send config blob to GPS unless AUTO_CONFIG=1 All GPS types will recieve startup up blob config. For some recievers this will cause them to hang. This commit only allows sending of blobs if AUTO_CONFIG=1. Fixes #2622 --- libraries/AP_GPS/AP_GPS.cpp | 12 +++++++++--- 1 file changed, 9 insertions(+), 3 deletions(-) diff --git a/libraries/AP_GPS/AP_GPS.cpp b/libraries/AP_GPS/AP_GPS.cpp index c2f65de400..eed614e0d9 100644 --- a/libraries/AP_GPS/AP_GPS.cpp +++ b/libraries/AP_GPS/AP_GPS.cpp @@ -267,10 +267,14 @@ AP_GPS::detect_instance(uint8_t instance) send_blob_start(instance, _initialisation_raw_blob, sizeof(_initialisation_raw_blob)); else #endif - send_blob_start(instance, _initialisation_blob, sizeof(_initialisation_blob)); + if(_auto_config == 1){ + send_blob_start(instance, _initialisation_blob, sizeof(_initialisation_blob)); + } } - send_blob_update(instance); + if(_auto_config == 1){ + send_blob_update(instance); + } while (initblob_state[instance].remaining == 0 && _port[instance]->available() > 0 && new_gps == NULL) { @@ -386,7 +390,9 @@ AP_GPS::update_instance(uint8_t instance) return; } - send_blob_update(instance); + if(_auto_config == 1){ + send_blob_update(instance); + } // we have an active driver for this instance bool result = drivers[instance]->read();