From 900feadb8ec279d5bb8ae37cf7fefea1506e5b54 Mon Sep 17 00:00:00 2001 From: Tom Pittenger Date: Fri, 6 Dec 2024 13:22:30 -0800 Subject: [PATCH] GCS_Common: fix send_sys_status() which was killing current value if ANY battery was unhealthy --- libraries/GCS_MAVLink/GCS_Common.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/libraries/GCS_MAVLink/GCS_Common.cpp b/libraries/GCS_MAVLink/GCS_Common.cpp index e670339e7b..89b3006893 100644 --- a/libraries/GCS_MAVLink/GCS_Common.cpp +++ b/libraries/GCS_MAVLink/GCS_Common.cpp @@ -5766,7 +5766,7 @@ void GCS_MAVLINK::send_sys_status() float battery_current; const int8_t battery_remaining = battery_remaining_pct(AP_BATT_PRIMARY_INSTANCE); - if (battery.healthy() && battery.current_amps(battery_current)) { + if (battery.healthy(AP_BATT_PRIMARY_INSTANCE) && battery.current_amps(battery_current, AP_BATT_PRIMARY_INSTANCE)) { battery_current = constrain_float(battery_current * 100,-INT16_MAX,INT16_MAX); } else { battery_current = -1; @@ -5795,7 +5795,7 @@ void GCS_MAVLINK::send_sys_status() 0, #endif #if AP_BATTERY_ENABLED - battery.gcs_voltage() * 1000, // mV + battery.gcs_voltage(AP_BATT_PRIMARY_INSTANCE) * 1000, // mV battery_current, // in 10mA units battery_remaining, // in % #else