AntennaTracker: don't use EEPROM home if a startup home is set in parameters

This commit is contained in:
Andrew Tridgell 2014-04-09 14:30:27 +10:00
parent db7c3a9c52
commit b45819dd97
1 changed files with 3 additions and 1 deletions

View File

@ -83,7 +83,9 @@ static void init_tracker()
current_loc.lng = g.start_longitude * 1.0e7f;
// see if EEPROM has a default location as well
get_home_eeprom(current_loc);
if (current_loc.lat == 0 && current_loc.lng == 0) {
get_home_eeprom(current_loc);
}
gcs_send_text_P(SEVERITY_LOW,PSTR("\nReady to track."));
hal.scheduler->delay(1000); // Why????