1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-17 05:15:25 +03:00

Tidy of OSD code

This commit is contained in:
Martin Budden 2017-11-22 07:18:24 +00:00
parent 3d965ba64f
commit b49f20fd8d
2 changed files with 104 additions and 108 deletions

View file

@ -42,7 +42,6 @@
#include "cms/cms.h" #include "cms/cms.h"
#include "cms/cms_types.h" #include "cms/cms_types.h"
#include "cms/cms_menu_osd.h"
#include "common/maths.h" #include "common/maths.h"
#include "common/printf.h" #include "common/printf.h"
@ -62,27 +61,26 @@
#include "io/flashfs.h" #include "io/flashfs.h"
#include "io/gps.h" #include "io/gps.h"
#include "io/osd.h" #include "io/osd.h"
#include "io/vtx_rtc6705.h"
#include "io/vtx_control.h" #include "io/vtx_control.h"
#include "io/vtx_rtc6705.h"
#include "io/vtx_string.h" #include "io/vtx_string.h"
#include "io/vtx.h" #include "io/vtx.h"
#include "fc/config.h" #include "fc/config.h"
#include "fc/rc_adjustments.h"
#include "fc/rc_controls.h" #include "fc/rc_controls.h"
#include "fc/runtime_config.h" #include "fc/runtime_config.h"
#include "fc/rc_adjustments.h"
#include "flight/altitude.h" #include "flight/altitude.h"
#include "flight/navigation.h"
#include "flight/pid.h"
#include "flight/imu.h" #include "flight/imu.h"
#include "flight/pid.h"
#include "rx/rx.h" #include "rx/rx.h"
#include "sensors/barometer.h" #include "sensors/barometer.h"
#include "sensors/battery.h" #include "sensors/battery.h"
#include "sensors/sensors.h"
#include "sensors/esc_sensor.h" #include "sensors/esc_sensor.h"
#include "sensors/sensors.h"
#ifdef USE_HARDWARE_REVISION_DETECTION #ifdef USE_HARDWARE_REVISION_DETECTION
#include "hardware_revision.h" #include "hardware_revision.h"
@ -118,26 +116,29 @@ static timeUs_t flyTime = 0;
static uint8_t statRssi; static uint8_t statRssi;
typedef struct statistic_s { typedef struct statistic_s {
timeUs_t armed_time;
int16_t max_speed; int16_t max_speed;
int16_t min_voltage; // /10 int16_t min_voltage; // /10
int16_t max_current; // /10 int16_t max_current; // /10
int16_t min_rssi; int16_t min_rssi;
int16_t max_altitude; int16_t max_altitude;
int16_t max_distance; int16_t max_distance;
timeUs_t armed_time;
} statistic_t; } statistic_t;
static statistic_t stats; static statistic_t stats;
uint32_t resumeRefreshAt = 0; timeUs_t resumeRefreshAt = 0;
#define REFRESH_1S 1000 * 1000 #define REFRESH_1S 1000 * 1000
static uint8_t armState; static uint8_t armState;
static displayPort_t *osdDisplayPort; static displayPort_t *osdDisplayPort;
#define AH_SYMBOL_COUNT 9 #ifdef USE_ESC_SENSOR
static escSensorData_t *escData;
#endif
#define AH_SYMBOL_COUNT 9
#define AH_SIDEBAR_WIDTH_POS 7 #define AH_SIDEBAR_WIDTH_POS 7
#define AH_SIDEBAR_HEIGHT_POS 3 #define AH_SIDEBAR_HEIGHT_POS 3
@ -156,11 +157,7 @@ static const char compassBar[] = {
SYM_HEADING_LINE, SYM_HEADING_DIVIDED_LINE, SYM_HEADING_LINE SYM_HEADING_LINE, SYM_HEADING_DIVIDED_LINE, SYM_HEADING_LINE
}; };
PG_REGISTER_WITH_RESET_FN(osdConfig_t, osdConfig, PG_OSD_CONFIG, 1); PG_REGISTER_WITH_RESET_FN(osdConfig_t, osdConfig, PG_OSD_CONFIG, 2);
#ifdef USE_ESC_SENSOR
static escSensorData_t *escData;
#endif
/** /**
* Gets the correct altitude symbol for the current unit system * Gets the correct altitude symbol for the current unit system
@ -188,8 +185,8 @@ static char osdGetBatterySymbol(int cellVoltage)
if (getBatteryState() == BATTERY_CRITICAL) { if (getBatteryState() == BATTERY_CRITICAL) {
return SYM_MAIN_BATT; // FIXME: currently the BAT- symbol, ideally replace with a battery with exclamation mark return SYM_MAIN_BATT; // FIXME: currently the BAT- symbol, ideally replace with a battery with exclamation mark
} else { } else {
/* Calculate a symbol offset using cell voltage over full cell voltage range */ // Calculate a symbol offset using cell voltage over full cell voltage range
int symOffset = scaleRange(cellVoltage, batteryConfig()->vbatmincellvoltage * 10, batteryConfig()->vbatmaxcellvoltage * 10, 0, 7); const int symOffset = scaleRange(cellVoltage, batteryConfig()->vbatmincellvoltage * 10, batteryConfig()->vbatmaxcellvoltage * 10, 0, 7);
return SYM_BATT_EMPTY - constrain(symOffset, 0, 6); return SYM_BATT_EMPTY - constrain(symOffset, 0, 6);
} }
} }
@ -310,7 +307,7 @@ STATIC_UNIT_TESTED void osdFormatTimer(char *buff, bool showSymbol, int timerInd
} }
#ifdef USE_RTC_TIME #ifdef USE_RTC_TIME
bool printRtcDateTime(char *buffer) static bool printRtcDateTime(char *buffer)
{ {
dateTime_t dateTime; dateTime_t dateTime;
if (!rtcGetDateTime(&dateTime)) { if (!rtcGetDateTime(&dateTime)) {
@ -395,17 +392,6 @@ static void osdDrawSingleElement(uint8_t item)
break; break;
} }
case OSD_HOME_DIST:
if (STATE(GPS_FIX) && STATE(GPS_FIX_HOME)) {
int32_t distance = osdGetMetersToSelectedUnit(GPS_distanceToHome);
tfp_sprintf(buff, "%d%c", distance, osdGetMetersToSelectedUnitSymbol());
} else {
// We use this symbol when we don't have a FIX
buff[0] = SYM_COLON;
buff[1] = 0;
}
break;
case OSD_HOME_DIR: case OSD_HOME_DIR:
if (STATE(GPS_FIX) && STATE(GPS_FIX_HOME)) { if (STATE(GPS_FIX) && STATE(GPS_FIX_HOME)) {
if (GPS_distanceToHome > 0) { if (GPS_distanceToHome > 0) {
@ -425,6 +411,17 @@ static void osdDrawSingleElement(uint8_t item)
break; break;
case OSD_HOME_DIST:
if (STATE(GPS_FIX) && STATE(GPS_FIX_HOME)) {
int32_t distance = osdGetMetersToSelectedUnit(GPS_distanceToHome);
tfp_sprintf(buff, "%d%c", distance, osdGetMetersToSelectedUnitSymbol());
} else {
// We use this symbol when we don't have a FIX
buff[0] = SYM_COLON;
buff[1] = 0;
}
break;
#endif // GPS #endif // GPS
case OSD_COMPASS_BAR: case OSD_COMPASS_BAR:
@ -471,30 +468,33 @@ static void osdDrawSingleElement(uint8_t item)
{ {
char *p = "ACRO"; char *p = "ACRO";
if (isAirmodeActive()) if (isAirmodeActive()) {
p = "AIR"; p = "AIR";
}
if (FLIGHT_MODE(FAILSAFE_MODE)) if (FLIGHT_MODE(FAILSAFE_MODE)) {
p = "!FS!"; p = "!FS!";
else if (FLIGHT_MODE(ANGLE_MODE)) } else if (FLIGHT_MODE(ANGLE_MODE)) {
p = "STAB"; p = "STAB";
else if (FLIGHT_MODE(HORIZON_MODE)) } else if (FLIGHT_MODE(HORIZON_MODE)) {
p = "HOR"; p = "HOR";
}
displayWrite(osdDisplayPort, elemPosX, elemPosY, p); displayWrite(osdDisplayPort, elemPosX, elemPosY, p);
return; return;
} }
case OSD_CRAFT_NAME: case OSD_CRAFT_NAME:
if (strlen(pilotConfig()->name) == 0) if (strlen(pilotConfig()->name) == 0) {
strcpy(buff, "CRAFT_NAME"); strcpy(buff, "CRAFT_NAME");
else { } else {
for (unsigned int i = 0; i < MAX_NAME_LENGTH; i++) { for (unsigned int i = 0; i < MAX_NAME_LENGTH; i++) {
buff[i] = toupper((unsigned char)pilotConfig()->name[i]); buff[i] = toupper((unsigned char)pilotConfig()->name[i]);
if (pilotConfig()->name[i] == 0) if (pilotConfig()->name[i] == 0) {
break; break;
} }
} }
}
break; break;
case OSD_THROTTLE_POS: case OSD_THROTTLE_POS:
@ -586,41 +586,28 @@ static void osdDrawSingleElement(uint8_t item)
} }
case OSD_ROLL_PIDS: case OSD_ROLL_PIDS:
{ osdFormatPID(buff, "ROL", &currentPidProfile->pid[PID_ROLL]);
const pidProfile_t *pidProfile = currentPidProfile;
osdFormatPID(buff, "ROL", &pidProfile->pid[PID_ROLL]);
break; break;
}
case OSD_PITCH_PIDS: case OSD_PITCH_PIDS:
{ osdFormatPID(buff, "PIT", &currentPidProfile->pid[PID_PITCH]);
const pidProfile_t *pidProfile = currentPidProfile;
osdFormatPID(buff, "PIT", &pidProfile->pid[PID_PITCH]);
break; break;
}
case OSD_YAW_PIDS: case OSD_YAW_PIDS:
{ osdFormatPID(buff, "YAW", &currentPidProfile->pid[PID_YAW]);
const pidProfile_t *pidProfile = currentPidProfile;
osdFormatPID(buff, "YAW", &pidProfile->pid[PID_YAW]);
break; break;
}
case OSD_POWER: case OSD_POWER:
tfp_sprintf(buff, "%4dW", getAmperage() * getBatteryVoltage() / 1000); tfp_sprintf(buff, "%4dW", getAmperage() * getBatteryVoltage() / 1000);
break; break;
case OSD_PIDRATE_PROFILE: case OSD_PIDRATE_PROFILE:
{ tfp_sprintf(buff, "%d-%d", getCurrentPidProfileIndex() + 1, getCurrentControlRateProfileIndex() + 1);
const uint8_t pidProfileIndex = getCurrentPidProfileIndex();
const uint8_t rateProfileIndex = getCurrentControlRateProfileIndex();
tfp_sprintf(buff, "%d-%d", pidProfileIndex + 1, rateProfileIndex + 1);
break; break;
}
case OSD_WARNINGS: case OSD_WARNINGS:
{ {
uint16_t enabledWarnings = osdConfig()->enabledWarnings; const uint16_t enabledWarnings = osdConfig()->enabledWarnings;
const batteryState_e batteryState = getBatteryState(); const batteryState_e batteryState = getBatteryState();
@ -629,7 +616,7 @@ static void osdDrawSingleElement(uint8_t item)
break; break;
} }
/* Warn when in flip over after crash mode */ // Warn when in flip over after crash mode
if ((enabledWarnings & OSD_WARNING_CRASH_FLIP) if ((enabledWarnings & OSD_WARNING_CRASH_FLIP)
&& (isModeActivationConditionPresent(BOXFLIPOVERAFTERCRASH)) && (isModeActivationConditionPresent(BOXFLIPOVERAFTERCRASH))
&& IS_RC_MODE_ACTIVE(BOXFLIPOVERAFTERCRASH)) { && IS_RC_MODE_ACTIVE(BOXFLIPOVERAFTERCRASH)) {
@ -637,7 +624,7 @@ static void osdDrawSingleElement(uint8_t item)
break; break;
} }
/* Show most severe reason for arming being disabled */ // Show most severe reason for arming being disabled
if (enabledWarnings & OSD_WARNING_ARMING_DISABLE && IS_RC_MODE_ACTIVE(BOXARM) && isArmingDisabled()) { if (enabledWarnings & OSD_WARNING_ARMING_DISABLE && IS_RC_MODE_ACTIVE(BOXARM) && isArmingDisabled()) {
const armingDisableFlags_e flags = getArmingDisableFlags(); const armingDisableFlags_e flags = getArmingDisableFlags();
for (int i = 0; i < NUM_ARMING_DISABLE_FLAGS; i++) { for (int i = 0; i < NUM_ARMING_DISABLE_FLAGS; i++) {
@ -654,14 +641,14 @@ static void osdDrawSingleElement(uint8_t item)
break; break;
} }
/* Show warning if battery is not fresh */ // Show warning if battery is not fresh
if (enabledWarnings & OSD_WARNING_BATTERY_NOT_FULL && !ARMING_FLAG(WAS_EVER_ARMED) && (getBatteryState() == BATTERY_OK) if (enabledWarnings & OSD_WARNING_BATTERY_NOT_FULL && !ARMING_FLAG(WAS_EVER_ARMED) && (getBatteryState() == BATTERY_OK)
&& getBatteryAverageCellVoltage() < batteryConfig()->vbatfullcellvoltage) { && getBatteryAverageCellVoltage() < batteryConfig()->vbatfullcellvoltage) {
tfp_sprintf(buff, "BATT NOT FULL"); tfp_sprintf(buff, "BATT NOT FULL");
break; break;
} }
/* Visual beeper */ // Visual beeper
if (enabledWarnings & OSD_WARNING_VISUAL_BEEPER && showVisualBeeper) { if (enabledWarnings & OSD_WARNING_VISUAL_BEEPER && showVisualBeeper) {
tfp_sprintf(buff, " * * * *"); tfp_sprintf(buff, " * * * *");
break; break;
@ -696,19 +683,20 @@ static void osdDrawSingleElement(uint8_t item)
#define MAIN_BATT_USAGE_STEPS 11 // Use an odd number so the bar can be centralised. #define MAIN_BATT_USAGE_STEPS 11 // Use an odd number so the bar can be centralised.
//Calculate constrained value //Calculate constrained value
float value = constrain(batteryConfig()->batteryCapacity - getMAhDrawn(), 0, batteryConfig()->batteryCapacity); const float value = constrain(batteryConfig()->batteryCapacity - getMAhDrawn(), 0, batteryConfig()->batteryCapacity);
//Calculate mAh used progress //Calculate mAh used progress
uint8_t mAhUsedProgress = ceil((value / (batteryConfig()->batteryCapacity / MAIN_BATT_USAGE_STEPS))); const uint8_t mAhUsedProgress = ceil((value / (batteryConfig()->batteryCapacity / MAIN_BATT_USAGE_STEPS)));
//Create empty battery indicator bar //Create empty battery indicator bar
buff[0] = SYM_PB_START; buff[0] = SYM_PB_START;
for (uint8_t i = 1; i <= MAIN_BATT_USAGE_STEPS; i++) { for (uint8_t i = 1; i <= MAIN_BATT_USAGE_STEPS; i++) {
if (i <= mAhUsedProgress) if (i <= mAhUsedProgress) {
buff[i] = SYM_PB_FULL; buff[i] = SYM_PB_FULL;
else } else {
buff[i] = SYM_PB_EMPTY; buff[i] = SYM_PB_EMPTY;
} }
}
buff[MAIN_BATT_USAGE_STEPS+1] = SYM_PB_CLOSE; buff[MAIN_BATT_USAGE_STEPS+1] = SYM_PB_CLOSE;
if (mAhUsedProgress > 0 && mAhUsedProgress < MAIN_BATT_USAGE_STEPS) { if (mAhUsedProgress > 0 && mAhUsedProgress < MAIN_BATT_USAGE_STEPS) {
@ -775,9 +763,10 @@ static void osdDrawElements(void)
{ {
displayClearScreen(osdDisplayPort); displayClearScreen(osdDisplayPort);
/* Hide OSD when OSDSW mode is active */ // Hide OSD when OSDSW mode is active
if (IS_RC_MODE_ACTIVE(BOXOSD)) if (IS_RC_MODE_ACTIVE(BOXOSD)) {
return; return;
}
if (sensors(SENSOR_ACC)) { if (sensors(SENSOR_ACC)) {
osdDrawSingleElement(OSD_ARTIFICIAL_HORIZON); osdDrawSingleElement(OSD_ARTIFICIAL_HORIZON);
@ -841,12 +830,12 @@ static void osdDrawElements(void)
void pgResetFn_osdConfig(osdConfig_t *osdConfig) void pgResetFn_osdConfig(osdConfig_t *osdConfig)
{ {
/* Position elements near centre of screen and disabled by default */ // Position elements near centre of screen and disabled by default
for (int i = 0; i < OSD_ITEM_COUNT; i++) { for (int i = 0; i < OSD_ITEM_COUNT; i++) {
osdConfig->item_pos[i] = OSD_POS(10, 7); osdConfig->item_pos[i] = OSD_POS(10, 7);
} }
/* Always enable warnings elements by default */ // Always enable warnings elements by default
osdConfig->item_pos[OSD_WARNINGS] = OSD_POS(9, 10) | VISIBLE_FLAG; osdConfig->item_pos[OSD_WARNINGS] = OSD_POS(9, 10) | VISIBLE_FLAG;
osdConfig->enabled_stats[OSD_STAT_MAX_SPEED] = true; osdConfig->enabled_stats[OSD_STAT_MAX_SPEED] = true;
@ -865,7 +854,7 @@ void pgResetFn_osdConfig(osdConfig_t *osdConfig)
osdConfig->units = OSD_UNIT_METRIC; osdConfig->units = OSD_UNIT_METRIC;
/* Enable all warnings by default */ // Enable all warnings by default
osdConfig->enabledWarnings = UINT16_MAX; osdConfig->enabledWarnings = UINT16_MAX;
osdConfig->timers[OSD_TIMER_1] = OSD_TIMER(OSD_TIMER_SRC_ON, OSD_TIMER_PREC_SECOND, 10); osdConfig->timers[OSD_TIMER_1] = OSD_TIMER(OSD_TIMER_SRC_ON, OSD_TIMER_PREC_SECOND, 10);
@ -893,8 +882,9 @@ static void osdDrawLogo(int x, int y)
void osdInit(displayPort_t *osdDisplayPortToUse) void osdInit(displayPort_t *osdDisplayPortToUse)
{ {
if (!osdDisplayPortToUse) if (!osdDisplayPortToUse) {
return; return;
}
BUILD_BUG_ON(OSD_POS_MAX != OSD_POS(31,31)); BUILD_BUG_ON(OSD_POS_MAX != OSD_POS(31,31));
@ -927,7 +917,7 @@ void osdInit(displayPort_t *osdDisplayPortToUse)
} }
#endif #endif
displayResync(osdDisplayPort); displayResync(osdDisplayPort);
resumeRefreshAt = micros() + (4 * REFRESH_1S); resumeRefreshAt = micros() + (4 * REFRESH_1S);
} }
@ -938,10 +928,11 @@ void osdUpdateAlarms(void)
int32_t alt = osdGetMetersToSelectedUnit(getEstimatedAltitude()) / 100; int32_t alt = osdGetMetersToSelectedUnit(getEstimatedAltitude()) / 100;
if (statRssi < osdConfig()->rssi_alarm) if (statRssi < osdConfig()->rssi_alarm) {
SET_BLINK(OSD_RSSI_VALUE); SET_BLINK(OSD_RSSI_VALUE);
else } else {
CLR_BLINK(OSD_RSSI_VALUE); CLR_BLINK(OSD_RSSI_VALUE);
}
if (getBatteryState() == BATTERY_OK) { if (getBatteryState() == BATTERY_OK) {
CLR_BLINK(OSD_WARNINGS); CLR_BLINK(OSD_WARNINGS);
@ -953,20 +944,22 @@ void osdUpdateAlarms(void)
SET_BLINK(OSD_AVG_CELL_VOLTAGE); SET_BLINK(OSD_AVG_CELL_VOLTAGE);
} }
if (STATE(GPS_FIX) == 0) if (STATE(GPS_FIX) == 0) {
SET_BLINK(OSD_GPS_SATS); SET_BLINK(OSD_GPS_SATS);
else } else {
CLR_BLINK(OSD_GPS_SATS); CLR_BLINK(OSD_GPS_SATS);
}
for (int i = 0; i < OSD_TIMER_COUNT; i++) { for (int i = 0; i < OSD_TIMER_COUNT; i++) {
const uint16_t timer = osdConfig()->timers[i]; const uint16_t timer = osdConfig()->timers[i];
const timeUs_t time = osdGetTimerValue(OSD_TIMER_SRC(timer)); const timeUs_t time = osdGetTimerValue(OSD_TIMER_SRC(timer));
const timeUs_t alarmTime = OSD_TIMER_ALARM(timer) * 60000000; // convert from minutes to us const timeUs_t alarmTime = OSD_TIMER_ALARM(timer) * 60000000; // convert from minutes to us
if (alarmTime != 0 && time >= alarmTime) if (alarmTime != 0 && time >= alarmTime) {
SET_BLINK(OSD_ITEM_TIMER_1 + i); SET_BLINK(OSD_ITEM_TIMER_1 + i);
else } else {
CLR_BLINK(OSD_ITEM_TIMER_1 + i); CLR_BLINK(OSD_ITEM_TIMER_1 + i);
} }
}
if (getMAhDrawn() >= osdConfig()->cap_alarm) { if (getMAhDrawn() >= osdConfig()->cap_alarm) {
SET_BLINK(OSD_MAH_DRAWN); SET_BLINK(OSD_MAH_DRAWN);
@ -978,10 +971,11 @@ void osdUpdateAlarms(void)
CLR_BLINK(OSD_REMAINING_TIME_ESTIMATE); CLR_BLINK(OSD_REMAINING_TIME_ESTIMATE);
} }
if (alt >= osdConfig()->alt_alarm) if (alt >= osdConfig()->alt_alarm) {
SET_BLINK(OSD_ALTITUDE); SET_BLINK(OSD_ALTITUDE);
else } else {
CLR_BLINK(OSD_ALTITUDE); CLR_BLINK(OSD_ALTITUDE);
}
} }
void osdResetAlarms(void) void osdResetAlarms(void)
@ -1017,21 +1011,26 @@ static void osdUpdateStats(void)
#ifdef USE_GPS #ifdef USE_GPS
value = CM_S_TO_KM_H(gpsSol.groundSpeed); value = CM_S_TO_KM_H(gpsSol.groundSpeed);
#endif #endif
if (stats.max_speed < value) if (stats.max_speed < value) {
stats.max_speed = value; stats.max_speed = value;
}
if (stats.min_voltage > getBatteryVoltage()) if (stats.min_voltage > getBatteryVoltage()) {
stats.min_voltage = getBatteryVoltage(); stats.min_voltage = getBatteryVoltage();
}
value = getAmperage() / 100; value = getAmperage() / 100;
if (stats.max_current < value) if (stats.max_current < value) {
stats.max_current = value; stats.max_current = value;
}
if (stats.min_rssi > statRssi) if (stats.min_rssi > statRssi) {
stats.min_rssi = statRssi; stats.min_rssi = statRssi;
}
if (stats.max_altitude < getEstimatedAltitude()) if (stats.max_altitude < getEstimatedAltitude()) {
stats.max_altitude = getEstimatedAltitude(); stats.max_altitude = getEstimatedAltitude();
}
#ifdef USE_GPS #ifdef USE_GPS
if (STATE(GPS_FIX) && STATE(GPS_FIX_HOME) && (stats.max_distance < GPS_distanceToHome)) { if (STATE(GPS_FIX) && STATE(GPS_FIX_HOME) && (stats.max_distance < GPS_distanceToHome)) {
@ -1092,7 +1091,8 @@ static void osdDisplayStatisticLabel(uint8_t y, const char * text, const char *
/* /*
* Test if there's some stat enabled * Test if there's some stat enabled
*/ */
static bool isSomeStatEnabled(void) { static bool isSomeStatEnabled(void)
{
for (int i = 0; i < OSD_STAT_COUNT; i++) { for (int i = 0; i < OSD_STAT_COUNT; i++) {
if (osdConfig()->enabled_stats[i]) { if (osdConfig()->enabled_stats[i]) {
return true; return true;
@ -1187,7 +1187,7 @@ static void osdShowStats(void)
} }
#endif #endif
/* Reset time since last armed here to ensure this timer is at zero when back at "main" OSD screen */ // Reset time since last armed here to ensure this timer is at zero when back at "main" OSD screen
stats.armed_time = 0; stats.armed_time = 0;
} }

View file

@ -17,7 +17,6 @@
#pragma once #pragma once
#ifdef USE_OSD
#include "common/time.h" #include "common/time.h"
#include "config/parameter_group.h" #include "config/parameter_group.h"
@ -141,7 +140,6 @@ typedef enum {
typedef struct osdConfig_s { typedef struct osdConfig_s {
uint16_t item_pos[OSD_ITEM_COUNT]; uint16_t item_pos[OSD_ITEM_COUNT];
bool enabled_stats[OSD_STAT_COUNT];
// Alarms // Alarms
uint16_t cap_alarm; uint16_t cap_alarm;
@ -155,16 +153,14 @@ typedef struct osdConfig_s {
uint8_t ahMaxPitch; uint8_t ahMaxPitch;
uint8_t ahMaxRoll; uint8_t ahMaxRoll;
bool enabled_stats[OSD_STAT_COUNT];
} osdConfig_t; } osdConfig_t;
extern uint32_t resumeRefreshAt; extern timeUs_t resumeRefreshAt;
PG_DECLARE(osdConfig_t, osdConfig); PG_DECLARE(osdConfig_t, osdConfig);
struct displayPort_s; struct displayPort_s;
void osdInit(struct displayPort_s *osdDisplayPort); void osdInit(struct displayPort_s *osdDisplayPort);
void osdResetConfig(osdConfig_t *osdProfile);
void osdResetAlarms(void); void osdResetAlarms(void);
void osdUpdate(timeUs_t currentTimeUs); void osdUpdate(timeUs_t currentTimeUs);
#endif