From ed20c4cbc82e152c1068b6adf14502e3e3ac9ecc Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sun, 14 Jul 2013 21:59:15 +1000 Subject: [PATCH] Plane: fixed initial reporting of battery remaining we were not showing battery remaining 100% until we used some battery --- ArduPlane/ArduPlane.pde | 2 ++ ArduPlane/GCS_Mavlink.pde | 8 ++++---- ArduPlane/sensors.pde | 13 ++++++------- 3 files changed, 12 insertions(+), 11 deletions(-) diff --git a/ArduPlane/ArduPlane.pde b/ArduPlane/ArduPlane.pde index c3a47763e9..e808f51bb3 100644 --- a/ArduPlane/ArduPlane.pde +++ b/ArduPlane/ArduPlane.pde @@ -447,6 +447,8 @@ static struct { float current_total_mah; // true when a low battery event has happened bool low_batttery; + // time when current was last read + uint32_t last_time_ms; } battery; //////////////////////////////////////////////////////////////////////////////// diff --git a/ArduPlane/GCS_Mavlink.pde b/ArduPlane/GCS_Mavlink.pde index 02d25683ae..131a2d3f45 100644 --- a/ArduPlane/GCS_Mavlink.pde +++ b/ArduPlane/GCS_Mavlink.pde @@ -216,10 +216,10 @@ static NOINLINE void send_extended_status1(mavlink_channel_t chan, uint16_t pack uint16_t battery_current = -1; uint8_t battery_remaining = -1; - if (battery.current_total_mah != 0 && g.pack_capacity != 0) { - battery_remaining = (100.0 * (g.pack_capacity - battery.current_total_mah) / g.pack_capacity); - } - if (battery.current_total_mah != 0) { + if (battery.last_time_ms != 0) { + if (g.pack_capacity != 0) { + battery_remaining = (100.0 * (g.pack_capacity - battery.current_total_mah) / g.pack_capacity); + } battery_current = battery.current_amps * 100; } diff --git a/ArduPlane/sensors.pde b/ArduPlane/sensors.pde index eb9a112c05..ddac273e83 100644 --- a/ArduPlane/sensors.pde +++ b/ArduPlane/sensors.pde @@ -52,17 +52,16 @@ static void read_battery(void) } if (g.battery_monitoring == 4) { - static uint32_t last_time_ms; uint32_t tnow = hal.scheduler->millis(); - float dt = tnow - last_time_ms; - if (last_time_ms != 0 && dt < 2000) { - // this copes with changing the pin at runtime - batt_curr_pin->set_pin(g.battery_curr_pin); - battery.current_amps = CURRENT_AMPS(batt_curr_pin); + float dt = tnow - battery.last_time_ms; + // this copes with changing the pin at runtime + batt_curr_pin->set_pin(g.battery_curr_pin); + battery.current_amps = CURRENT_AMPS(batt_curr_pin); + if (battery.last_time_ms != 0 && dt < 2000) { // .0002778 is 1/3600 (conversion to hours) battery.current_total_mah += battery.current_amps * dt * 0.0002778f; } - last_time_ms = tnow; + battery.last_time_ms = tnow; } if (battery.voltage != 0 &&