From 1c104557b7cd13f01b76919894df5b3ce75e90f4 Mon Sep 17 00:00:00 2001 From: Ferruccio Vicari Date: Wed, 17 Apr 2024 15:57:49 +0000 Subject: [PATCH] AP_Motors: fix heli yaw behavior in autorotation --- libraries/AP_Motors/AP_MotorsHeli_RSC.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_Motors/AP_MotorsHeli_RSC.h b/libraries/AP_Motors/AP_MotorsHeli_RSC.h index 276728ca4d..03b3500c9b 100644 --- a/libraries/AP_Motors/AP_MotorsHeli_RSC.h +++ b/libraries/AP_Motors/AP_MotorsHeli_RSC.h @@ -129,7 +129,7 @@ public: uint32_t get_output_mask() const; // rotor_speed_above_critical - return true if rotor speed is above that critical for flight - bool rotor_speed_above_critical(void) const { return get_rotor_speed() > get_critical_speed(); } + bool rotor_speed_above_critical(void) const { return get_rotor_speed() >= get_critical_speed(); } // var_info for holding Parameter information static const struct AP_Param::GroupInfo var_info[];