From 3cbc15bb5b1174045e6c3da8607b2619cbb8447e Mon Sep 17 00:00:00 2001 From: Leonard Hall Date: Thu, 21 Jan 2016 15:07:11 +0900 Subject: [PATCH] AP_MotorsMulticopter: add get_throttle_thrust_max accessor --- libraries/AP_Motors/AP_MotorsMulticopter.h | 3 +++ 1 file changed, 3 insertions(+) diff --git a/libraries/AP_Motors/AP_MotorsMulticopter.h b/libraries/AP_Motors/AP_MotorsMulticopter.h index 0eca58f59e..524b337e04 100644 --- a/libraries/AP_Motors/AP_MotorsMulticopter.h +++ b/libraries/AP_Motors/AP_MotorsMulticopter.h @@ -119,6 +119,9 @@ public: // get_throttle_limit - throttle limit ratio - for logging purposes only float get_throttle_limit() const { return _throttle_limit; } + // returns maximum thrust in the range 0 to 1 + float get_throttle_thrust_max() const { return _throttle_thrust_max; } + // return true if spool up is complete bool spool_up_complete() const { return _multicopter_flags.spool_mode == THROTTLE_UNLIMITED; }