From bc42cb2a661c46a5f2ddf9bd0c23b03d75d9a689 Mon Sep 17 00:00:00 2001 From: Leonard Hall Date: Mon, 25 Jan 2016 12:15:02 +0900 Subject: [PATCH] AP_MotorsMulticopter: update_battery_resistance uses get_throttle accessor --- libraries/AP_Motors/AP_MotorsMulticopter.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/libraries/AP_Motors/AP_MotorsMulticopter.cpp b/libraries/AP_Motors/AP_MotorsMulticopter.cpp index 88eb0fa656..943a21672a 100644 --- a/libraries/AP_Motors/AP_MotorsMulticopter.cpp +++ b/libraries/AP_Motors/AP_MotorsMulticopter.cpp @@ -234,14 +234,14 @@ void AP_MotorsMulticopter::update_lift_max_from_batt_voltage() void AP_MotorsMulticopter::update_battery_resistance() { // if motors are stopped, reset resting voltage and current - if (_throttle_control_input <= 0 || !_flags.armed) { + if (get_throttle() <= 0.0f || !_flags.armed) { _batt_voltage_resting = _batt_voltage; _batt_current_resting = _batt_current; _batt_timer = 0; } else { // update battery resistance when throttle is over hover throttle if ((_batt_timer < 400) && ((_batt_current_resting*2.0f) < _batt_current)) { - if (_throttle_control_input >= _hover_out) { + if (get_throttle() >= _hover_out) { // filter reaches 90% in 1/4 the test time _batt_resistance += 0.05f*(( (_batt_voltage_resting-_batt_voltage)/(_batt_current-_batt_current_resting) ) - _batt_resistance); _batt_timer += 1;