diff --git a/libraries/AC_AttitudeControl/AC_PosControl.cpp b/libraries/AC_AttitudeControl/AC_PosControl.cpp index c1a7aa3e02..b5649d4471 100644 --- a/libraries/AC_AttitudeControl/AC_PosControl.cpp +++ b/libraries/AC_AttitudeControl/AC_PosControl.cpp @@ -548,6 +548,7 @@ void AC_PosControl::update_xy_controller(bool use_desired_velocity) uint32_t now = hal.scheduler->millis(); if ((now - _last_update_xy_ms) >= POSCONTROL_ACTIVE_TIMEOUT_MS) { init_xy_controller(); + now = _last_update_xy_ms; } // check if xy leash needs to be recalculated