From 1e0ae4b998bb3889b3938aba9a24f0fd53b452d4 Mon Sep 17 00:00:00 2001 From: Josh Henderson Date: Thu, 23 Sep 2021 01:21:46 -0400 Subject: [PATCH] GCS_MAVLINK: Common capacity_remaining_pct checks healthy status and has_current --- libraries/GCS_MAVLink/GCS_Common.cpp | 6 ++---- 1 file changed, 2 insertions(+), 4 deletions(-) diff --git a/libraries/GCS_MAVLink/GCS_Common.cpp b/libraries/GCS_MAVLink/GCS_Common.cpp index 90f1bbabda..f487317c3b 100644 --- a/libraries/GCS_MAVLink/GCS_Common.cpp +++ b/libraries/GCS_MAVLink/GCS_Common.cpp @@ -4684,10 +4684,9 @@ void GCS_MAVLINK::send_sys_status() const AP_BattMonitor &battery = AP::battery(); float battery_current; - int8_t battery_remaining = -1; + const int8_t battery_remaining = battery_remaining_pct(AP_BATT_PRIMARY_INSTANCE); if (battery.healthy() && battery.current_amps(battery_current)) { - battery_remaining = battery_remaining_pct(AP_BATT_PRIMARY_INSTANCE); battery_current = constrain_float(battery_current * 100,-INT16_MAX,INT16_MAX); } else { battery_current = -1; @@ -5780,10 +5779,9 @@ void GCS_MAVLINK::send_high_latency2() const const AP_BattMonitor &battery = AP::battery(); float battery_current = -1; - int8_t battery_remaining = -1; + const int8_t battery_remaining = battery_remaining_pct(AP_BATT_PRIMARY_INSTANCE); if (battery.healthy() && battery.current_amps(battery_current)) { - battery_remaining = battery_remaining_pct(AP_BATT_PRIMARY_INSTANCE); battery_current = constrain_float(battery_current * 100,-INT16_MAX,INT16_MAX); }