Skip to content

Commit

Permalink
AC_AttitudeControl_Heli: fix compile error
Browse files Browse the repository at this point in the history
  • Loading branch information
bnsgeyer authored Mar 13, 2024
1 parent 7a62717 commit b30e8a5
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 @@ -573,7 +573,7 @@ void AC_AttitudeControl_Heli::set_throttle_out(float throttle_in, bool apply_ang

// returns a throttle including compensation for roll/pitch angle
// throttle value should be 0 ~ 1
float AC_AttitudeControl_Multi::get_throttle_boosted(float throttle_in)
float AC_AttitudeControl_Heli::get_throttle_boosted(float throttle_in)
{
if (!_angle_boost_enabled) {
_angle_boost = 0;
Expand Down

0 comments on commit b30e8a5

Please sign in to comment.