diff --git a/ArduPlane/quadplane.cpp b/ArduPlane/quadplane.cpp index c1f027661fc55..272499d5b451d 100644 --- a/ArduPlane/quadplane.cpp +++ b/ArduPlane/quadplane.cpp @@ -987,11 +987,9 @@ void QuadPlane::relax_attitude_control() */ void QuadPlane::check_attitude_relax(void) { - uint32_t now = AP_HAL::millis(); - if (now - last_att_control_ms > 100) { + if (AP_HAL::millis() - last_att_control_ms > 100) { relax_attitude_control(); } - last_att_control_ms = now; } /* @@ -1943,8 +1941,10 @@ void QuadPlane::update_throttle_hover() */ void QuadPlane::motors_output(bool run_rate_controller) { + const uint32_t now = AP_HAL::millis(); if (run_rate_controller) { attitude_control->rate_controller_run(); + last_att_control_ms = now; } /* Delay for ARMING_DELAY_MS after arming before allowing props to spin: @@ -1992,7 +1992,7 @@ void QuadPlane::motors_output(bool run_rate_controller) // remember when motors were last active for throttle suppression if (motors->get_throttle() > 0.01f || tilt.motors_active) { - last_motors_active_ms = AP_HAL::millis(); + last_motors_active_ms = now; } }