Copter: PosHold: remove unnecessary loiter_nav->update

This commit is contained in:
Leonard Hall 2022-09-01 14:41:12 +09:30 committed by Randy Mackay
parent b580c873a8
commit 2165d19af1
1 changed files with 0 additions and 3 deletions

View File

@ -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;