From c08e04a16aa2aff54f6a3e7a3348e51b3fadab76 Mon Sep 17 00:00:00 2001 From: Willian Galvani Date: Thu, 30 Jul 2020 12:14:52 -0300 Subject: [PATCH] AP_RCTelemetry: update to use capacity_remaining_pct() as a bool --- libraries/AP_RCTelemetry/AP_CRSF_Telem.cpp | 5 ++++- 1 file changed, 4 insertions(+), 1 deletion(-) diff --git a/libraries/AP_RCTelemetry/AP_CRSF_Telem.cpp b/libraries/AP_RCTelemetry/AP_CRSF_Telem.cpp index 7a9990d2a0..164aaf07b7 100644 --- a/libraries/AP_RCTelemetry/AP_CRSF_Telem.cpp +++ b/libraries/AP_RCTelemetry/AP_CRSF_Telem.cpp @@ -756,7 +756,10 @@ void AP_CRSF_Telem::calc_battery() used_mah = 0; } - _telem.bcast.battery.remaining = _battery.capacity_remaining_pct(0); + uint8_t percentage = 0; + IGNORE_RETURN(_battery.capacity_remaining_pct(percentage, 0)); + + _telem.bcast.battery.remaining = percentage; const int32_t capacity = used_mah; _telem.bcast.battery.capacity[0] = (capacity & 0xFF0000) >> 16;