From 7ad45468e3ed4f4cdb8bed4724ba1a0efd42c62f Mon Sep 17 00:00:00 2001 From: Bill Geyer Date: Mon, 1 Apr 2024 20:02:31 -0400 Subject: [PATCH] AC_AttitudeControl_Heli: fix bug --- libraries/AC_AttitudeControl/AC_AttitudeControl_Heli.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AC_AttitudeControl/AC_AttitudeControl_Heli.cpp b/libraries/AC_AttitudeControl/AC_AttitudeControl_Heli.cpp index 945a1bc52e77e5..907e9b11be27c8 100644 --- a/libraries/AC_AttitudeControl/AC_AttitudeControl_Heli.cpp +++ b/libraries/AC_AttitudeControl/AC_AttitudeControl_Heli.cpp @@ -567,7 +567,7 @@ float AC_AttitudeControl_Heli::get_throttle_boosted(float throttle_in) float boost_factor = 1.0f / constrain_float(cos_tilt_target, 0.1f, 1.0f); // angle boost and inverted factor applied about the zero thrust collective - const float coll_mid = (AP_MotorsHeli&)_motors).get_coll_mid(); + const float coll_mid = ((AP_MotorsHeli&)_motors).get_coll_mid(); float throttle_out = ((throttle_in - coll_mid) * inverted_factor * boost_factor) + coll_mid; _angle_boost = constrain_float(throttle_out - throttle_in, -1.0f, 1.0f); return throttle_out;