From 9f6027b332229c69d1bdf73af92ffb58180cc9ff Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Thu, 21 Feb 2019 12:43:55 +1100 Subject: [PATCH] Tracker: make set_home bool, do not save bad homes --- AntennaTracker/AntennaTracker.cpp | 4 +++- AntennaTracker/GCS_Mavlink.cpp | 5 ++++- AntennaTracker/Tracker.h | 4 ++-- AntennaTracker/sensors.cpp | 4 +++- AntennaTracker/system.cpp | 18 ++++++++++++------ 5 files changed, 24 insertions(+), 11 deletions(-) diff --git a/AntennaTracker/AntennaTracker.cpp b/AntennaTracker/AntennaTracker.cpp index eeb08d1249..15be5692a6 100644 --- a/AntennaTracker/AntennaTracker.cpp +++ b/AntennaTracker/AntennaTracker.cpp @@ -111,7 +111,9 @@ void Tracker::one_second_loop() // set home to current location Location temp_loc; if (ahrs.get_location(temp_loc)) { - set_home(temp_loc); + if (!set_home(temp_loc)){ + // fail silently + } } } diff --git a/AntennaTracker/GCS_Mavlink.cpp b/AntennaTracker/GCS_Mavlink.cpp index 943d966fbe..458d466145 100644 --- a/AntennaTracker/GCS_Mavlink.cpp +++ b/AntennaTracker/GCS_Mavlink.cpp @@ -470,7 +470,10 @@ void GCS_MAVLINK_Tracker::handleMessage(mavlink_message_t* msg) // check if this is the HOME wp if (packet.seq == 0) { - tracker.set_home(tell_command); // New home in EEPROM + if (!tracker.set_home(tell_command)) { + result = MAV_MISSION_ERROR; + goto mission_failed; + } send_text(MAV_SEVERITY_INFO,"New HOME received"); waypoint_receiving = false; } diff --git a/AntennaTracker/Tracker.h b/AntennaTracker/Tracker.h index 578d510fee..a8f3afd990 100644 --- a/AntennaTracker/Tracker.h +++ b/AntennaTracker/Tracker.h @@ -251,8 +251,8 @@ private: // system.cpp void init_tracker(); bool get_home_eeprom(struct Location &loc); - void set_home_eeprom(struct Location temp); - void set_home(struct Location temp); + bool set_home_eeprom(const Location &temp) WARN_IF_UNUSED; + bool set_home(const Location &temp) WARN_IF_UNUSED; void arm_servos(); void disarm_servos(); void prepare_servos(); diff --git a/AntennaTracker/sensors.cpp b/AntennaTracker/sensors.cpp index 6d5d51b8f2..a725bfe1b3 100644 --- a/AntennaTracker/sensors.cpp +++ b/AntennaTracker/sensors.cpp @@ -71,7 +71,9 @@ void Tracker::update_GPS(void) // Now have an initial GPS position // use it as the HOME position in future startups current_loc = gps.location(); - set_home(current_loc); + if (!set_home(current_loc)) { + // silently ignored + } if (g.compass_enabled) { // Set compass declination automatically diff --git a/AntennaTracker/system.cpp b/AntennaTracker/system.cpp index 251e3a32c2..ad2627b447 100644 --- a/AntennaTracker/system.cpp +++ b/AntennaTracker/system.cpp @@ -135,7 +135,7 @@ bool Tracker::get_home_eeprom(struct Location &loc) return true; } -void Tracker::set_home_eeprom(struct Location temp) +bool Tracker::set_home_eeprom(const Location &temp) { wp_storage.write_byte(0, 0); wp_storage.write_uint32(1, temp.alt); @@ -144,20 +144,26 @@ void Tracker::set_home_eeprom(struct Location temp) // Now have a home location in EEPROM g.command_total.set_and_save(1); // At most 1 entry for HOME + return true; } -void Tracker::set_home(struct Location temp) +bool Tracker::set_home(const Location &temp) { - set_home_eeprom(temp); - current_loc = temp; - // check EKF origin has been set Location ekf_origin; if (ahrs.get_origin(ekf_origin)) { if (!ahrs.set_home(temp)) { - // ignore error silently + return false; } } + + if (!set_home_eeprom(temp)) { + return false; + } + + current_loc = temp; + + return true; } void Tracker::arm_servos()