From 290e657f619cc29796cf1f9770cc544e1616fb60 Mon Sep 17 00:00:00 2001 From: Leonard Hall Date: Fri, 22 Jan 2016 10:26:21 +0900 Subject: [PATCH] AP_MotorsMulticopter: update_battery_resistance captures resting voltage while disarmed Previously it could also capture this when the input throttle was zero --- 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 943a21672a..4571faed6e 100644 --- a/libraries/AP_Motors/AP_MotorsMulticopter.cpp +++ b/libraries/AP_Motors/AP_MotorsMulticopter.cpp @@ -233,8 +233,8 @@ void AP_MotorsMulticopter::update_lift_max_from_batt_voltage() // update_battery_resistance - calculate battery resistance when throttle is above hover_out void AP_MotorsMulticopter::update_battery_resistance() { - // if motors are stopped, reset resting voltage and current - if (get_throttle() <= 0.0f || !_flags.armed) { + // if disarmed reset resting voltage and current + if (!_flags.armed) { _batt_voltage_resting = _batt_voltage; _batt_current_resting = _batt_current; _batt_timer = 0;