From a658c4f6236e4aec7ca2c565e0a7ac633f39871e Mon Sep 17 00:00:00 2001 From: Hwurzburg Date: Wed, 19 May 2021 07:22:59 -0500 Subject: [PATCH] Copter: correct ACRO_RP_EXPO constraint range --- ArduCopter/mode_acro.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ArduCopter/mode_acro.cpp b/ArduCopter/mode_acro.cpp index 32f23bd910..0f0e61aa6d 100644 --- a/ArduCopter/mode_acro.cpp +++ b/ArduCopter/mode_acro.cpp @@ -111,7 +111,7 @@ void ModeAcro::get_pilot_desired_angle_rates(int16_t roll_in, int16_t pitch_in, } // range check expo - g.acro_rp_expo = constrain_float(g.acro_rp_expo, 0.0f, 1.0f); + g.acro_rp_expo = constrain_float(g.acro_rp_expo, -0.5f, 1.0f); // calculate roll, pitch rate requests if (is_zero(g.acro_rp_expo)) {