diff --git a/ArduPlane/ArduPlane.cpp b/ArduPlane/ArduPlane.cpp index a7d8113ec5..b837d2e209 100644 --- a/ArduPlane/ArduPlane.cpp +++ b/ArduPlane/ArduPlane.cpp @@ -349,9 +349,9 @@ void Plane::one_second_loop() } #endif - // update home position if soft armed and gps position has + // update home position if armed and gps position has // changed. Update every 5s at most - if (!hal.util->get_soft_armed() && + if (!arming.is_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();