AP_RCTelemetry: update to use capacity_remaining_pct() as a bool

This commit is contained in:
Willian Galvani 2020-07-30 12:14:52 -03:00 committed by Andrew Tridgell
parent 018ff3d11c
commit c08e04a16a
1 changed files with 4 additions and 1 deletions

View File

@ -756,7 +756,10 @@ void AP_CRSF_Telem::calc_battery()
used_mah = 0; 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; const int32_t capacity = used_mah;
_telem.bcast.battery.capacity[0] = (capacity & 0xFF0000) >> 16; _telem.bcast.battery.capacity[0] = (capacity & 0xFF0000) >> 16;