From 2165d19af1ddabef9381a6e7c1a00b4c58073ef2 Mon Sep 17 00:00:00 2001 From: Leonard Hall Date: Thu, 1 Sep 2022 14:41:12 +0930 Subject: [PATCH] Copter: PosHold: remove unnecessary loiter_nav->update --- ArduCopter/mode_poshold.cpp | 3 --- 1 file changed, 3 deletions(-) diff --git a/ArduCopter/mode_poshold.cpp b/ArduCopter/mode_poshold.cpp index 484dbf2f39..9ad5133836 100644 --- a/ArduCopter/mode_poshold.cpp +++ b/ArduCopter/mode_poshold.cpp @@ -106,7 +106,6 @@ void ModePosHold::run() pos_control->relax_z_controller(0.0f); // forces throttle output to decay to zero loiter_nav->clear_pilot_desired_acceleration(); loiter_nav->init_target(); - loiter_nav->update(false); // set poshold state to pilot override roll_mode = RPMode::PILOT_OVERRIDE; @@ -131,7 +130,6 @@ void ModePosHold::run() // init and update loiter although pilot is controlling lean angles loiter_nav->clear_pilot_desired_acceleration(); loiter_nav->init_target(); - loiter_nav->update(false); // set poshold state to pilot override roll_mode = RPMode::PILOT_OVERRIDE; @@ -141,7 +139,6 @@ void ModePosHold::run() case AltHold_Landed_Ground_Idle: loiter_nav->clear_pilot_desired_acceleration(); loiter_nav->init_target(); - loiter_nav->update(false); attitude_control->reset_yaw_target_and_rate(); init_wind_comp_estimate(); FALLTHROUGH;