From 38581669ec773905b58388d20348cd9ca591129a Mon Sep 17 00:00:00 2001 From: Ferrin Benjamin Katz Date: Thu, 13 Oct 2016 16:58:51 -0700 Subject: [PATCH] Plane: slow down home update Moved the code theat updates the home position while the aircraft is unarmed from 10hz loop to one second loop and ensured that is does not update more then once every 5 seconds. Closes issue 4311. --- ArduPlane/ArduPlane.cpp | 19 ++++++++++++------- ArduPlane/Plane.h | 3 +++ 2 files changed, 15 insertions(+), 7 deletions(-) diff --git a/ArduPlane/ArduPlane.cpp b/ArduPlane/ArduPlane.cpp index 271e912058..39e6547ad8 100644 --- a/ArduPlane/ArduPlane.cpp +++ b/ArduPlane/ArduPlane.cpp @@ -337,6 +337,18 @@ void Plane::one_second_loop() #endif ins.set_raw_logging(should_log(MASK_LOG_IMU_RAW)); + + // update home position if soft armed and gps position has + // changed. Update every 5s at most + if (!hal.util->get_soft_armed() && + gps.last_message_time_ms() - last_home_update_ms > 5000 && + gps.status() >= AP_GPS::GPS_OK_FIX_3D) { + last_home_update_ms = gps.last_message_time_ms(); + update_home(); + + // reset the landing altitude correction + auto_state.land_alt_offset = 0; + } } void Plane::log_perf_info() @@ -481,13 +493,6 @@ void Plane::update_GPS_10Hz(void) } #endif - if (!hal.util->get_soft_armed()) { - update_home(); - - // reset the landing altitude correction - auto_state.land_alt_offset = 0; - } - // update wind estimate ahrs.estimate_wind(); } else if (gps.status() < AP_GPS::GPS_OK_FIX_3D && ground_start_count != 0) { diff --git a/ArduPlane/Plane.h b/ArduPlane/Plane.h index 88a226ca04..b5ea118e04 100644 --- a/ArduPlane/Plane.h +++ b/ArduPlane/Plane.h @@ -778,6 +778,9 @@ private: uint32_t last_trim_check; uint32_t last_trim_save; } auto_trim; + + // last time home was updated while disarmed + uint32_t last_home_update_ms; // Camera/Antenna mount tracking and stabilisation stuff #if MOUNT == ENABLED