AP_Motors: fix heli yaw behavior in autorotation

This commit is contained in:
Ferruccio Vicari 2024-04-17 15:57:49 +00:00 committed by Bill Geyer
parent 0bdf073f38
commit 1c104557b7
1 changed files with 1 additions and 1 deletions

View File

@ -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[];