mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 07:44:03 -04:00
AP_OSD: update to use capacity_remaining_pct() as a bool
This commit is contained in:
parent
20779ba47c
commit
d422314020
@ -1225,16 +1225,22 @@ void AP_OSD_Screen::draw_altitude(uint8_t x, uint8_t y)
|
||||
void AP_OSD_Screen::draw_bat_volt(uint8_t x, uint8_t y)
|
||||
{
|
||||
AP_BattMonitor &battery = AP::battery();
|
||||
uint8_t pct = battery.capacity_remaining_pct();
|
||||
uint8_t p = (100 - pct) / 16.6;
|
||||
float v = battery.voltage();
|
||||
uint8_t pct;
|
||||
if (!battery.capacity_remaining_pct(pct)) {
|
||||
// Do not show battery percentage
|
||||
backend->write(x,y, v < osd->warn_batvolt, "%2.1f%c", (double)v, SYM_VOLT);
|
||||
return;
|
||||
}
|
||||
uint8_t p = (100 - pct) / 16.6;
|
||||
backend->write(x,y, v < osd->warn_batvolt, "%c%2.1f%c", SYM_BATT_FULL + p, (double)v, SYM_VOLT);
|
||||
}
|
||||
|
||||
void AP_OSD_Screen::draw_avgcellvolt(uint8_t x, uint8_t y)
|
||||
{
|
||||
AP_BattMonitor &battery = AP::battery();
|
||||
uint8_t pct = battery.capacity_remaining_pct();
|
||||
uint8_t pct = 0;
|
||||
IGNORE_RETURN(battery.capacity_remaining_pct(pct));
|
||||
uint8_t p = (100 - pct) / 16.6;
|
||||
float v = battery.voltage();
|
||||
// calculate cell count - WARNING this can be inaccurate if the LIPO/LIION battery is far from fully charged when attached and is used in this panel
|
||||
@ -1253,7 +1259,8 @@ void AP_OSD_Screen::draw_avgcellvolt(uint8_t x, uint8_t y)
|
||||
void AP_OSD_Screen::draw_restvolt(uint8_t x, uint8_t y)
|
||||
{
|
||||
AP_BattMonitor &battery = AP::battery();
|
||||
uint8_t pct = battery.capacity_remaining_pct();
|
||||
uint8_t pct = 0;
|
||||
IGNORE_RETURN(battery.capacity_remaining_pct(pct));
|
||||
uint8_t p = (100 - pct) / 16.6;
|
||||
float v = battery.voltage_resting_estimate();
|
||||
backend->write(x,y, v < osd->warn_restvolt, "%c%2.1f%c", SYM_BATT_FULL + p, (double)v, SYM_VOLT);
|
||||
@ -1849,9 +1856,14 @@ void AP_OSD_Screen::draw_atemp(uint8_t x, uint8_t y)
|
||||
void AP_OSD_Screen::draw_bat2_vlt(uint8_t x, uint8_t y)
|
||||
{
|
||||
AP_BattMonitor &battery = AP::battery();
|
||||
uint8_t pct2 = battery.capacity_remaining_pct(1);
|
||||
uint8_t p2 = (100 - pct2) / 16.6;
|
||||
uint8_t pct2 = 0;
|
||||
float v2 = battery.voltage(1);
|
||||
if (!battery.capacity_remaining_pct(pct2, 1)) {
|
||||
// Do not show battery percentage
|
||||
backend->write(x,y, v2 < osd->warn_bat2volt, "%2.1f%c", (double)v2, SYM_VOLT);
|
||||
return;
|
||||
}
|
||||
uint8_t p2 = (100 - pct2) / 16.6;
|
||||
backend->write(x,y, v2 < osd->warn_bat2volt, "%c%2.1f%c", SYM_BATT_FULL + p2, (double)v2, SYM_VOLT);
|
||||
}
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user