Browse Source

AP_GPS: SBF respect GPS_AUTO_CONFIG

mission-4.1.18
Michael du Breuil 7 years ago committed by Francisco Ferreira
parent
commit
20988b9f05
  1. 3
      libraries/AP_GPS/AP_GPS_SBF.cpp

3
libraries/AP_GPS/AP_GPS_SBF.cpp

@ -55,7 +55,8 @@ AP_GPS_SBF::read(void)
{ {
uint32_t now = AP_HAL::millis(); uint32_t now = AP_HAL::millis();
if (_init_blob_index < (sizeof(_initialisation_blob) / sizeof(_initialisation_blob[0]))) { if (gps._auto_config != AP_GPS::GPS_AUTO_CONFIG_DISABLE &&
_init_blob_index < (sizeof(_initialisation_blob) / sizeof(_initialisation_blob[0]))) {
const char *init_str = _initialisation_blob[_init_blob_index]; const char *init_str = _initialisation_blob[_init_blob_index];
if (validcommand) { if (validcommand) {
_init_blob_index++; _init_blob_index++;

Loading…
Cancel
Save