mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-05 15:33:57 -04:00
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
This commit is contained in:
parent
7c3b8dceb9
commit
51e8d8a294
@ -267,10 +267,14 @@ AP_GPS::detect_instance(uint8_t instance)
|
|||||||
send_blob_start(instance, _initialisation_raw_blob, sizeof(_initialisation_raw_blob));
|
send_blob_start(instance, _initialisation_raw_blob, sizeof(_initialisation_raw_blob));
|
||||||
else
|
else
|
||||||
#endif
|
#endif
|
||||||
|
if(_auto_config == 1){
|
||||||
send_blob_start(instance, _initialisation_blob, sizeof(_initialisation_blob));
|
send_blob_start(instance, _initialisation_blob, sizeof(_initialisation_blob));
|
||||||
}
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
if(_auto_config == 1){
|
||||||
send_blob_update(instance);
|
send_blob_update(instance);
|
||||||
|
}
|
||||||
|
|
||||||
while (initblob_state[instance].remaining == 0 && _port[instance]->available() > 0
|
while (initblob_state[instance].remaining == 0 && _port[instance]->available() > 0
|
||||||
&& new_gps == NULL) {
|
&& new_gps == NULL) {
|
||||||
@ -386,7 +390,9 @@ AP_GPS::update_instance(uint8_t instance)
|
|||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
if(_auto_config == 1){
|
||||||
send_blob_update(instance);
|
send_blob_update(instance);
|
||||||
|
}
|
||||||
|
|
||||||
// we have an active driver for this instance
|
// we have an active driver for this instance
|
||||||
bool result = drivers[instance]->read();
|
bool result = drivers[instance]->read();
|
||||||
|
Loading…
Reference in New Issue
Block a user