Skip to content

Commit

Permalink
Copter: correct statements in poshold
Browse files Browse the repository at this point in the history
  • Loading branch information
bnsgeyer committed Dec 3, 2024
1 parent 13efb77 commit fb386e2
Showing 1 changed file with 1 addition and 2 deletions.
3 changes: 1 addition & 2 deletions ArduCopter/mode_poshold.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -118,10 +118,10 @@ void ModePosHold::run()
case AltHoldModeState::Landed_Ground_Idle:
attitude_control->reset_yaw_target_and_rate(false);
attitude_control->reset_rate_controller_I_terms_smoothly();
init_wind_comp_estimate();
pos_control->relax_z_controller(0.0f); // forces throttle output to decay to zero
loiter_nav->clear_pilot_desired_acceleration();
loiter_nav->init_target();
init_wind_comp_estimate();

// set poshold state to pilot override
roll_mode = RPMode::PILOT_OVERRIDE;
Expand All @@ -133,7 +133,6 @@ void ModePosHold::run()
attitude_control->reset_target_and_rate(false);
}
attitude_control->reset_rate_controller_I_terms_smoothly();
init_wind_comp_estimate();
pos_control->relax_z_controller(0.0f); // forces throttle output to decay to zero

// set poshold state to pilot override
Expand Down

0 comments on commit fb386e2

Please sign in to comment.