From 348001e786babb08be6f2686377706e45600273e Mon Sep 17 00:00:00 2001 From: Jonathan Challinger Date: Tue, 28 Apr 2015 11:56:10 -0700 Subject: [PATCH] AP_Motors: add get_throttle_warn function --- libraries/AP_Motors/AP_Motors_Class.h | 3 +++ 1 file changed, 3 insertions(+) diff --git a/libraries/AP_Motors/AP_Motors_Class.h b/libraries/AP_Motors/AP_Motors_Class.h index a68058cb74..89e3dbdef5 100644 --- a/libraries/AP_Motors/AP_Motors_Class.h +++ b/libraries/AP_Motors/AP_Motors_Class.h @@ -179,6 +179,9 @@ public: // get_throttle_limit - throttle limit ratio float get_throttle_limit() { return _throttle_limit; } + // returns warning throttle + float get_throttle_warn() { return rel_pwm_to_thr_range(_spin_when_armed); } + // 1 if motor is enabled, 0 otherwise bool motor_enabled[AP_MOTORS_MAX_NUM_MOTORS];