mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 18:08:30 -04:00
AP_Motors: is_throttle_mix_min returns bol
This commit is contained in:
parent
cf45a1cf3a
commit
68b05a4ca2
@ -176,7 +176,7 @@ public:
|
||||
void set_throttle_mix_max() { _throttle_thr_mix_desired = AP_MOTORS_THR_MIX_MAX_DEFAULT; }
|
||||
|
||||
// get_throttle_thr_mix - get low throttle compensation value
|
||||
float is_throttle_mix_min() { return (_throttle_thr_mix < 1.25f*_thr_mix_min); }
|
||||
bool is_throttle_mix_min() { return (_throttle_thr_mix < 1.25f*_thr_mix_min); }
|
||||
|
||||
// get_lift_max - get maximum lift ratio
|
||||
float get_lift_max() { return _lift_max; }
|
||||
|
Loading…
Reference in New Issue
Block a user