Browse Source

AP_MotorsMulticopter: update_battery_resistance captures resting voltage while disarmed

Previously it could also capture this when the input throttle was zero
master
Leonard Hall 9 years ago committed by Randy Mackay
parent
commit
290e657f61
  1. 4
      libraries/AP_Motors/AP_MotorsMulticopter.cpp

4
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 // update_battery_resistance - calculate battery resistance when throttle is above hover_out
void AP_MotorsMulticopter::update_battery_resistance() void AP_MotorsMulticopter::update_battery_resistance()
{ {
// if motors are stopped, reset resting voltage and current // if disarmed reset resting voltage and current
if (get_throttle() <= 0.0f || !_flags.armed) { if (!_flags.armed) {
_batt_voltage_resting = _batt_voltage; _batt_voltage_resting = _batt_voltage;
_batt_current_resting = _batt_current; _batt_current_resting = _batt_current;
_batt_timer = 0; _batt_timer = 0;

Loading…
Cancel
Save