From 678b12af25e46f7ed9104018a9ca0f3d2c577579 Mon Sep 17 00:00:00 2001 From: "Andreas M. Antonopoulos" Date: Sun, 24 Jun 2012 17:01:25 -0700 Subject: [PATCH] AC2.6: Fix battery calculation and scaling bug for MAV1.0, now same as ArduPlane http://code.google.com/p/arducopter/issues/detail?id=430 --- ArduCopter/GCS_Mavlink.pde | 21 ++++++++++++++++++--- Tools/ArdupilotMegaPlanner/CurrentState.cs | 2 +- 2 files changed, 19 insertions(+), 4 deletions(-) diff --git a/ArduCopter/GCS_Mavlink.pde b/ArduCopter/GCS_Mavlink.pde index b5df926334..b759be8bb9 100644 --- a/ArduCopter/GCS_Mavlink.pde +++ b/ArduCopter/GCS_Mavlink.pde @@ -152,16 +152,31 @@ static NOINLINE void send_extended_status1(mavlink_channel_t chan, uint16_t pack // at the moment all sensors/controllers are assumed healthy control_sensors_health = control_sensors_present; - uint16_t battery_remaining = 1000.0 * (float)(g.pack_capacity - current_total1)/(float)g.pack_capacity; //Mavlink scaling 100% = 1000 + uint16_t battery_current = -1; + uint8_t battery_remaining = -1; + + if (current_total1 != 0 && g.pack_capacity != 0) { + battery_remaining = (100.0 * (g.pack_capacity - current_total1) / g.pack_capacity); + } + if (current_total1 != 0) { + battery_current = current_amps1 * 100; + } + + if (g.battery_monitoring == 3) { + /*setting a out-of-range value. + It informs to external devices that + it cannot be calculated properly just by voltage*/ + battery_remaining = 150; + } mavlink_msg_sys_status_send( chan, control_sensors_present, control_sensors_enabled, control_sensors_health, - 0, + 0, // CPU Load not supported in AC yet battery_voltage1 * 1000, // mV - 0, + battery_current, // in 10mA units battery_remaining, // in % 0, // comm drops %, 0, // comm drops in pkts, diff --git a/Tools/ArdupilotMegaPlanner/CurrentState.cs b/Tools/ArdupilotMegaPlanner/CurrentState.cs index 317d2a7fd9..b246d26199 100644 --- a/Tools/ArdupilotMegaPlanner/CurrentState.cs +++ b/Tools/ArdupilotMegaPlanner/CurrentState.cs @@ -156,7 +156,7 @@ namespace ArdupilotMega //battery public float battery_voltage { get { return _battery_voltage; } set { _battery_voltage = value / 1000; } } private float _battery_voltage; - public float battery_remaining { get { return _battery_remaining; } set { _battery_remaining = value / 1000; if (_battery_remaining < 0 || _battery_remaining > 1) _battery_remaining = 0; } } + public float battery_remaining { get { return _battery_remaining; } set { _battery_remaining = value / 100; if (_battery_remaining < 0 || _battery_remaining > 1) _battery_remaining = 0; } } private float _battery_remaining; // pressure