From 71d181810362fb57c82fa001a18f9c5c380dae89 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Sat, 4 Jun 2016 14:51:00 +0900 Subject: [PATCH] AP_MotorsMulticopter: minor comment update --- libraries/AP_Motors/AP_MotorsMulticopter.cpp | 1 + libraries/AP_Motors/AP_MotorsMulticopter.h | 2 +- 2 files changed, 2 insertions(+), 1 deletion(-) diff --git a/libraries/AP_Motors/AP_MotorsMulticopter.cpp b/libraries/AP_Motors/AP_MotorsMulticopter.cpp index 43fdbd0370..e084c62434 100644 --- a/libraries/AP_Motors/AP_MotorsMulticopter.cpp +++ b/libraries/AP_Motors/AP_MotorsMulticopter.cpp @@ -379,6 +379,7 @@ void AP_MotorsMulticopter::update_throttle_hover(float dt) } } +// run spool logic void AP_MotorsMulticopter::output_logic() { // force desired and current spool mode if disarmed or not interlocked diff --git a/libraries/AP_Motors/AP_MotorsMulticopter.h b/libraries/AP_Motors/AP_MotorsMulticopter.h index 064a28d2e8..15dd97811d 100644 --- a/libraries/AP_Motors/AP_MotorsMulticopter.h +++ b/libraries/AP_Motors/AP_MotorsMulticopter.h @@ -75,7 +75,7 @@ public: // get_batt_resistance - get battery resistance approximation - for logging purposes only float get_batt_resistance() const { return _batt_resistance; } - // get_throttle_limit - throttle limit ratio - for logging purposes only + // get throttle limit imposed by battery current limiting. This is a number from 0 ~ 1 where 0 means hover throttle, 1 means the hover throttle float get_throttle_limit() const { return _throttle_limit; } // returns maximum thrust in the range 0 to 1