mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
AP_Notify: update to use capacity_remaining_pct() as a bool
This commit is contained in:
parent
207723319b
commit
b9452c83be
@ -526,8 +526,12 @@ void Display::update_battery(uint8_t r)
|
||||
{
|
||||
char msg [DISPLAY_MESSAGE_SIZE];
|
||||
AP_BattMonitor &battery = AP::battery();
|
||||
uint8_t pct = battery.capacity_remaining_pct();
|
||||
uint8_t pct;
|
||||
if (battery.capacity_remaining_pct(pct)) {
|
||||
snprintf(msg, DISPLAY_MESSAGE_SIZE, "BAT:%4.2fV %2d%% ", (double)battery.voltage(), pct) ;
|
||||
} else {
|
||||
snprintf(msg, DISPLAY_MESSAGE_SIZE, "BAT:%4.2fV --%% ", (double)battery.voltage()) ;
|
||||
}
|
||||
draw_text(COLUMN(0), ROW(r), msg);
|
||||
}
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user