AP_OSD:Add avg resting cell and refactor

Co-authored-by: MichelleRos
This commit is contained in:
Henry Wurzburg 2023-02-06 07:22:48 -06:00 committed by Andrew Tridgell
parent 9b60072a04
commit 4d79c6b9d6
3 changed files with 88 additions and 40 deletions

View File

@ -207,6 +207,13 @@ const AP_Param::GroupInfo AP_OSD::var_info[] = {
// @User: Standard
AP_GROUPINFO("_W_RESTVOLT", 26, AP_OSD, warn_restvolt, 10.0f),
// @Param: _W_ACRVOLT
// @DisplayName: Avg Cell Resting Volt warn level
// @Description: Set level at which ACRVOLT item will flash
// @Range: 0 100
// @User: Standard
AP_GROUPINFO("_W_ACRVOLT", 31, AP_OSD, warn_avgcellrestvolt, 3.6f),
#endif //osd enabled
#if OSD_PARAM_ENABLED
// @Group: 5_

View File

@ -169,12 +169,20 @@ private:
//typical fpv camera has 80deg vertical field of view, 16 row of chars
static constexpr float ah_pitch_rad_to_char = 16.0f/(DEG_TO_RAD * 80);
enum class VoltageType {
VOLTAGE,
RESTING_VOLTAGE,
AVG_CELL,
RESTING_CELL,
};
AP_OSD_Setting altitude{true, 23, 8};
AP_OSD_Setting bat_volt{true, 24, 1};
AP_OSD_Setting rssi{true, 1, 1};
AP_OSD_Setting link_quality{false,1,1};
AP_OSD_Setting restvolt{false, 24, 2};
AP_OSD_Setting avgcellvolt{false, 24, 3};
AP_OSD_Setting avgcellrestvolt{false, 24, 4};
AP_OSD_Setting current{true, 25, 2};
AP_OSD_Setting batused{true, 23, 3};
AP_OSD_Setting sats{true, 1, 3};
@ -243,8 +251,10 @@ private:
#endif
void draw_altitude(uint8_t x, uint8_t y);
void draw_bat_volt(uint8_t instance,VoltageType type,uint8_t x, uint8_t y);
void draw_bat_volt(uint8_t x, uint8_t y);
void draw_avgcellvolt(uint8_t x, uint8_t y);
void draw_avgcellrestvolt(uint8_t x, uint8_t y);
void draw_restvolt(uint8_t x, uint8_t y);
void draw_rssi(uint8_t x, uint8_t y);
void draw_link_quality(uint8_t x, uint8_t y);
@ -524,6 +534,7 @@ public:
AP_Float max_battery_voltage;
AP_Int8 cell_count;
AP_Float warn_restvolt;
AP_Float warn_avgcellrestvolt;
AP_Float warn_batvolt;
AP_Float warn_bat2volt;
AP_Int8 msgtime_s;

View File

@ -1001,6 +1001,22 @@ const AP_Param::GroupInfo AP_OSD_Screen::var_info[] = {
// @Range: 0 15
AP_SUBGROUPINFO(rngf, "RNGF", 60, AP_OSD_Screen, AP_OSD_Setting),
// @Param: ACRVOLT_EN
// @DisplayName: ACRVOLT_EN
// @Description: Displays resting voltage for the average cell. WARNING: this can be inaccurate if the cell count is not detected or set properly. If the the battery is far from fully charged the detected cell count might not be accurate if auto cell count detection is used (OSD_CELL_COUNT=0).
// @Values: 0:Disabled,1:Enabled
// @Param: ACRVOLT_X
// @DisplayName: ACRVOLT_X
// @Description: Horizontal position on screen
// @Range: 0 29
// @Param: ACRVOLT_Y
// @DisplayName: ACRVOLT_Y
// @Description: Vertical position on screen
// @Range: 0 15
AP_SUBGROUPINFO(avgcellrestvolt, "ACRVOLT", 61, AP_OSD_Screen, AP_OSD_Setting),
AP_GROUPEND
};
@ -1285,52 +1301,74 @@ void AP_OSD_Screen::draw_altitude(uint8_t x, uint8_t y)
backend->write(x, y, false, "%4d%c", (int)u_scale(ALTITUDE, alt), u_icon(ALTITUDE));
}
void AP_OSD_Screen::draw_bat_volt(uint8_t x, uint8_t y)
void AP_OSD_Screen::draw_bat_volt(uint8_t instance, VoltageType type, uint8_t x, uint8_t y)
{
AP_BattMonitor &battery = AP::battery();
float v = battery.voltage();
float v = battery.voltage(instance);
float blinkvolt = osd->warn_batvolt;
uint8_t pct;
if (!battery.capacity_remaining_pct(pct)) {
bool show_remaining_pct = battery.capacity_remaining_pct(pct);
uint8_t p = (100 - pct) / 16.6;
switch (type) {
case VoltageType::VOLTAGE: {
break;
}
case VoltageType::RESTING_VOLTAGE: {
v = battery.voltage_resting_estimate(instance);
blinkvolt = osd->warn_restvolt;
break;
}
case VoltageType::RESTING_CELL: {
blinkvolt = osd->warn_avgcellrestvolt;
v = battery.voltage_resting_estimate(instance);
FALLTHROUGH;
}
case VoltageType::AVG_CELL: {
if (type == VoltageType::AVG_CELL) { //for fallthrough of RESTING_CELL
blinkvolt = osd->warn_avgcellvolt;
}
// 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
osd->max_battery_voltage.set(MAX(osd->max_battery_voltage,v));
if (osd->cell_count > 0) {
v = v / osd->cell_count;
} else if (osd->cell_count < 0) { // user must decide on autodetect cell count or manually entered to display this panel since default is -1
backend->write(x,y, false, "%c---%c", SYMBOL(SYM_BATT_FULL) + p, SYMBOL(SYM_VOLT));
return;
} else { // use autodetected cell count
v = v / (uint8_t)(osd->max_battery_voltage * 0.2381 + 1);
}
break;
}
}
if (!show_remaining_pct) {
// Do not show battery percentage
backend->write(x,y, v < osd->warn_batvolt, "%2.1f%c", (double)v, SYMBOL(SYM_VOLT));
backend->write(x,y, v < blinkvolt, "%2.1f%c", (double)v, SYMBOL(SYM_VOLT));
return;
}
uint8_t p = (100 - pct) / 16.6;
backend->write(x,y, v < osd->warn_batvolt, "%c%2.1f%c", SYMBOL(SYM_BATT_FULL) + p, (double)v, SYMBOL(SYM_VOLT));
backend->write(x,y, v < blinkvolt, "%c%2.1f%c", SYMBOL(SYM_BATT_FULL) + p, (double)v, SYMBOL(SYM_VOLT));
}
void AP_OSD_Screen::draw_bat_volt(uint8_t x, uint8_t y)
{
draw_bat_volt(0,VoltageType::VOLTAGE,x,y);
}
void AP_OSD_Screen::draw_avgcellvolt(uint8_t x, uint8_t y)
{
AP_BattMonitor &battery = AP::battery();
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
osd->max_battery_voltage.set(MAX(osd->max_battery_voltage,v));
if (osd->cell_count > 0) {
v = v / osd->cell_count;
backend->write(x,y, v < osd->warn_avgcellvolt, "%c%1.2f%c", SYMBOL(SYM_BATT_FULL) + p, v, SYMBOL(SYM_VOLT));
} else if (osd->cell_count < 0) { // user must decide on autodetect cell count or manually entered to display this panel since default is -1
backend->write(x,y, false, "%c---%c", SYMBOL(SYM_BATT_FULL) + p, SYMBOL(SYM_VOLT));
} else { // use autodetected cell count
v = v / (uint8_t)(osd->max_battery_voltage * 0.2381 + 1);
backend->write(x,y, v < osd->warn_avgcellvolt, "%c%1.2f%c", SYMBOL(SYM_BATT_FULL) + p, v, SYMBOL(SYM_VOLT));
}
draw_bat_volt(0,VoltageType::AVG_CELL,x,y);
}
void AP_OSD_Screen::draw_avgcellrestvolt(uint8_t x, uint8_t y)
{
draw_bat_volt(0,VoltageType::RESTING_CELL,x, y);
}
void AP_OSD_Screen::draw_restvolt(uint8_t x, uint8_t y)
{
AP_BattMonitor &battery = AP::battery();
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", SYMBOL(SYM_BATT_FULL) + p, (double)v, SYMBOL(SYM_VOLT));
draw_bat_volt(0,VoltageType::RESTING_VOLTAGE,x,y);
}
void AP_OSD_Screen::draw_rssi(uint8_t x, uint8_t y)
{
AP_RSSI *ap_rssi = AP_RSSI::get_singleton();
@ -2007,16 +2045,7 @@ 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 = 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, SYMBOL(SYM_VOLT));
return;
}
uint8_t p2 = (100 - pct2) / 16.6;
backend->write(x,y, v2 < osd->warn_bat2volt, "%c%2.1f%c", SYMBOL(SYM_BATT_FULL) + p2, (double)v2, SYMBOL(SYM_VOLT));
draw_bat_volt(1,VoltageType::VOLTAGE,x,y);
}
void AP_OSD_Screen::draw_bat2used(uint8_t x, uint8_t y)
@ -2204,6 +2233,7 @@ void AP_OSD_Screen::draw(void)
DRAW_SETTING(bat_volt);
DRAW_SETTING(bat2_vlt);
DRAW_SETTING(avgcellvolt);
DRAW_SETTING(avgcellrestvolt);
DRAW_SETTING(restvolt);
DRAW_SETTING(rssi);
DRAW_SETTING(link_quality);