From 68b05a4ca27a86cc94026500995fbbd9d53c7585 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Fri, 8 May 2015 10:26:47 +0900 Subject: [PATCH] AP_Motors: is_throttle_mix_min returns bol --- libraries/AP_Motors/AP_Motors_Class.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_Motors/AP_Motors_Class.h b/libraries/AP_Motors/AP_Motors_Class.h index d599e9e54b..33b19dce4b 100644 --- a/libraries/AP_Motors/AP_Motors_Class.h +++ b/libraries/AP_Motors/AP_Motors_Class.h @@ -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; }