mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-24 00:33:56 -04:00
AP_MotorsMulticopter: update_battery_resistance captures resting voltage while disarmed
Previously it could also capture this when the input throttle was zero
This commit is contained in:
parent
bc42cb2a66
commit
290e657f61
@ -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;
|
||||
|
Loading…
Reference in New Issue
Block a user