Skip to content

Commit

Permalink
AC_AttitudeControl: only allow angle boost when not autorotating
Browse files Browse the repository at this point in the history
  • Loading branch information
bnsgeyer committed Mar 22, 2024
1 parent 2c9b01f commit 9cc494b
Showing 1 changed file with 1 addition and 1 deletion.
2 changes: 1 addition & 1 deletion libraries/AC_AttitudeControl/AC_AttitudeControl_Heli.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -540,7 +540,7 @@ void AC_AttitudeControl_Heli::set_throttle_out(float throttle_in, bool apply_ang
update_althold_lean_angle_max(throttle_in);

_motors.set_throttle_filter_cutoff(filter_cutoff);
if (apply_angle_boost) {
if (apply_angle_boost && !((AP_MotorsHeli&)_motors).get_in_autorotation()) {
// Apply angle boost
throttle_in = get_throttle_boosted(throttle_in);
} else {
Expand Down

0 comments on commit 9cc494b

Please sign in to comment.