mirror of https://github.com/ArduPilot/ardupilot
AP_Motors: fix heli yaw behavior in autorotation
This commit is contained in:
parent
0bdf073f38
commit
1c104557b7
|
@ -129,7 +129,7 @@ public:
|
||||||
uint32_t get_output_mask() const;
|
uint32_t get_output_mask() const;
|
||||||
|
|
||||||
// rotor_speed_above_critical - return true if rotor speed is above that critical for flight
|
// 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
|
// var_info for holding Parameter information
|
||||||
static const struct AP_Param::GroupInfo var_info[];
|
static const struct AP_Param::GroupInfo var_info[];
|
||||||
|
|
Loading…
Reference in New Issue