1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-16 21:05:35 +03:00

Prepare OSD for iterative updating

This commit is contained in:
Martin Budden 2018-01-08 17:12:58 +00:00
parent ec4ad45528
commit e6f5926131
4 changed files with 145 additions and 125 deletions

View file

@ -29,6 +29,8 @@
// Satellite Graphics // Satellite Graphics
#define SYM_SAT_L 0x1E #define SYM_SAT_L 0x1E
#define SYM_SAT_R 0x1F #define SYM_SAT_R 0x1F
#define SYM_HDP_L 0xBD
#define SYM_HDP_R 0xBE
//#define SYM_SAT 0x0F // Not used //#define SYM_SAT 0x0F // Not used
// Degrees Icon for HEADING/DIRECTION HOME // Degrees Icon for HEADING/DIRECTION HOME
@ -104,6 +106,7 @@
#define SYM_GMISSION1 0xB6 #define SYM_GMISSION1 0xB6
#define SYM_GLAND 0xB7 #define SYM_GLAND 0xB7
#define SYM_GLAND1 0xB8 #define SYM_GLAND1 0xB8
#define SYM_HOME_DIST 0xA0
// Gimbal active Mode // Gimbal active Mode
#define SYM_GIMBAL 0x16 #define SYM_GIMBAL 0x16
@ -202,6 +205,7 @@
#define SYM_FLY_M 0x9C #define SYM_FLY_M 0x9C
#define SYM_ON_H 0x70 #define SYM_ON_H 0x70
#define SYM_FLY_H 0x71 #define SYM_FLY_H 0x71
#define SYM_CLOCK 0xBC
// Throttle Position (%) // Throttle Position (%)
#define SYM_THR 0x04 #define SYM_THR 0x04
@ -215,6 +219,8 @@
//Misc //Misc
#define SYM_COLON 0x2D #define SYM_COLON 0x2D
#define SYM_ZERO_HALF_TRAILING_DOT 0xC0
#define SYM_ZERO_HALF_LEADING_DOT 0xD0
//sport //sport
#define SYM_MIN 0xB3 #define SYM_MIN 0xB3

View file

@ -56,16 +56,6 @@
#include "drivers/sdcard.h" #include "drivers/sdcard.h"
#include "drivers/time.h" #include "drivers/time.h"
#include "io/asyncfatfs/asyncfatfs.h"
#include "io/beeper.h"
#include "io/flashfs.h"
#include "io/gps.h"
#include "io/osd.h"
#include "io/vtx_control.h"
#include "io/vtx_rtc6705.h"
#include "io/vtx_string.h"
#include "io/vtx.h"
#include "fc/config.h" #include "fc/config.h"
#include "fc/rc_adjustments.h" #include "fc/rc_adjustments.h"
#include "fc/rc_controls.h" #include "fc/rc_controls.h"
@ -75,6 +65,14 @@
#include "flight/imu.h" #include "flight/imu.h"
#include "flight/pid.h" #include "flight/pid.h"
#include "io/asyncfatfs/asyncfatfs.h"
#include "io/beeper.h"
#include "io/flashfs.h"
#include "io/gps.h"
#include "io/osd.h"
#include "io/vtx_string.h"
#include "io/vtx.h"
#include "pg/pg.h" #include "pg/pg.h"
#include "pg/pg_ids.h" #include "pg/pg_ids.h"
@ -309,8 +307,36 @@ STATIC_UNIT_TESTED void osdFormatTimer(char *buff, bool showSymbol, int timerInd
osdFormatTime(buff, OSD_TIMER_PRECISION(timer), osdGetTimerValue(src)); osdFormatTime(buff, OSD_TIMER_PRECISION(timer), osdGetTimerValue(src));
} }
#ifdef USE_GPS
static void osdFormatCoordinate(char *buff, char sym, int32_t val)
{
// latitude maximum integer width is 3 (-90).
// longitude maximum integer width is 4 (-180).
// We show 7 decimals, so we need to use 11 characters because
// we are embedding the decimal separator between two digits
// eg: s-1801234567z s=symbol, z=zero terminator, decimal separator embedded between 0 and 1
static const int decimalPlaces = 7;
static const int coordinateMaxLength = 11;//5 + decimalPlaces; // 4 for the integer part of the number + 1 for the symbol
buff[0] = sym;
const int32_t integerPart = val / GPS_DEGREES_DIVIDER;
const int32_t decimalPart = labs(val % GPS_DEGREES_DIVIDER);
const int written = tfp_sprintf(buff + 1, "%d", integerPart);
tfp_sprintf(buff + 1 + written, "%07d", decimalPart);
// embed the decimal separator
buff[1+written-1] += SYM_ZERO_HALF_TRAILING_DOT - '0';
buff[1+written] += SYM_ZERO_HALF_LEADING_DOT - '0';
// pad with blanks to coordinateMaxLength
for (int pos = 1 + decimalPlaces + written; pos < coordinateMaxLength; ++pos) {
buff[pos] = SYM_BLANK;
}
buff[coordinateMaxLength] = '\0';
}
#endif // USE_GPS
#ifdef USE_RTC_TIME #ifdef USE_RTC_TIME
static bool printRtcDateTime(char *buffer) static bool osdFormatRtcDateTime(char *buffer)
{ {
dateTime_t dateTime; dateTime_t dateTime;
if (!rtcGetDateTime(&dateTime)) { if (!rtcGetDateTime(&dateTime)) {
@ -325,10 +351,20 @@ static bool printRtcDateTime(char *buffer)
} }
#endif #endif
static void osdDrawSingleElement(uint8_t item) static void osdFormatMessage(char *buff, size_t size, const char *message)
{
memset(buff, SYM_BLANK, size);
if (message) {
memcpy(buff, message, strlen(message));
}
// Ensure buff is zero terminated
buff[size - 1] = '\0';
}
static bool osdDrawSingleElement(uint8_t item)
{ {
if (!VISIBLE(osdConfig()->item_pos[item]) || BLINK(item)) { if (!VISIBLE(osdConfig()->item_pos[item]) || BLINK(item)) {
return; return false;
} }
uint8_t elemPosX = OSD_X(osdConfig()->item_pos[item]); uint8_t elemPosX = OSD_X(osdConfig()->item_pos[item]);
@ -343,13 +379,13 @@ static void osdDrawSingleElement(uint8_t item)
if (osdRssi >= 100) if (osdRssi >= 100)
osdRssi = 99; osdRssi = 99;
tfp_sprintf(buff, "%c%d", SYM_RSSI, osdRssi); tfp_sprintf(buff, "%c%2d", SYM_RSSI, osdRssi);
break; break;
} }
case OSD_MAIN_BATT_VOLTAGE: case OSD_MAIN_BATT_VOLTAGE:
buff[0] = osdGetBatterySymbol(osdGetBatteryAverageCellVoltage()); buff[0] = osdGetBatterySymbol(osdGetBatteryAverageCellVoltage());
tfp_sprintf(buff + 1, "%d.%1d%c", getBatteryVoltage() / 10, getBatteryVoltage() % 10, SYM_VOLT); tfp_sprintf(buff + 1, "%2d.%1d%c", getBatteryVoltage() / 10, getBatteryVoltage() % 10, SYM_VOLT);
break; break;
case OSD_CURRENT_DRAW: case OSD_CURRENT_DRAW:
@ -365,7 +401,7 @@ static void osdDrawSingleElement(uint8_t item)
#ifdef USE_GPS #ifdef USE_GPS
case OSD_GPS_SATS: case OSD_GPS_SATS:
tfp_sprintf(buff, "%c%c%d", SYM_SAT_L, SYM_SAT_R, gpsSol.numSat); tfp_sprintf(buff, "%c%c%2d", SYM_SAT_L, SYM_SAT_R, gpsSol.numSat);
break; break;
case OSD_GPS_SPEED: case OSD_GPS_SPEED:
@ -374,26 +410,12 @@ static void osdDrawSingleElement(uint8_t item)
break; break;
case OSD_GPS_LAT: case OSD_GPS_LAT:
osdFormatCoordinate(buff, SYM_LAT, gpsSol.llh.lat);
break;
case OSD_GPS_LON: case OSD_GPS_LON:
{ osdFormatCoordinate(buff, SYM_LON, gpsSol.llh.lon);
int32_t val; break;
if (item == OSD_GPS_LAT) {
buff[0] = SYM_ARROW_EAST;
val = gpsSol.llh.lat;
} else {
buff[0] = SYM_ARROW_SOUTH;
val = gpsSol.llh.lon;
}
char wholeDegreeString[5];
tfp_sprintf(wholeDegreeString, "%d", val / GPS_DEGREES_DIVIDER);
char wholeUnshifted[12];
tfp_sprintf(wholeUnshifted, "%d", val);
tfp_sprintf(buff + 1, "%s.%s", wholeDegreeString, wholeUnshifted + strlen(wholeDegreeString));
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)) {
@ -416,46 +438,37 @@ static void osdDrawSingleElement(uint8_t item)
case OSD_HOME_DIST: case OSD_HOME_DIST:
if (STATE(GPS_FIX) && STATE(GPS_FIX_HOME)) { if (STATE(GPS_FIX) && STATE(GPS_FIX_HOME)) {
int32_t distance = osdGetMetersToSelectedUnit(GPS_distanceToHome); const int32_t distance = osdGetMetersToSelectedUnit(GPS_distanceToHome);
tfp_sprintf(buff, "%d%c", distance, osdGetMetersToSelectedUnitSymbol()); tfp_sprintf(buff, "%d%c", distance, osdGetMetersToSelectedUnitSymbol());
} else { } else {
// We use this symbol when we don't have a FIX // We use this symbol when we don't have a FIX
buff[0] = SYM_COLON; buff[0] = SYM_COLON;
buff[1] = 0; // overwrite any previous distance with blanks
memset(buff + 1, SYM_BLANK, 6);
buff[7] = '\0';
} }
break; break;
#endif // GPS #endif // GPS
case OSD_COMPASS_BAR: case OSD_COMPASS_BAR:
{ memcpy(buff, compassBar + osdGetHeadingIntoDiscreteDirections(DECIDEGREES_TO_DEGREES(attitude.values.yaw), 16), 9);
int16_t h = DECIDEGREES_TO_DEGREES(attitude.values.yaw); buff[9] = 0;
break;
h = osdGetHeadingIntoDiscreteDirections(h, 16);
memcpy(buff, compassBar + h, 9);
buff[9]=0;
break;
}
case OSD_ALTITUDE: case OSD_ALTITUDE:
{ osdFormatAltitudeString(buff, getEstimatedAltitude(), true);
osdFormatAltitudeString(buff, getEstimatedAltitude(), true); break;
break;
}
case OSD_ITEM_TIMER_1: case OSD_ITEM_TIMER_1:
case OSD_ITEM_TIMER_2: case OSD_ITEM_TIMER_2:
{ osdFormatTimer(buff, true, item - OSD_ITEM_TIMER_1);
const int timer = item - OSD_ITEM_TIMER_1; break;
osdFormatTimer(buff, true, timer);
break;
}
case OSD_REMAINING_TIME_ESTIMATE: case OSD_REMAINING_TIME_ESTIMATE:
{ {
const int mAhDrawn = getMAhDrawn(); const int mAhDrawn = getMAhDrawn();
int remaining_time = (int)((osdConfig()->cap_alarm - mAhDrawn) * ((float)flyTime) / mAhDrawn); const int remaining_time = (int)((osdConfig()->cap_alarm - mAhDrawn) * ((float)flyTime) / mAhDrawn);
if (mAhDrawn < 0.1 * osdConfig()->cap_alarm) { if (mAhDrawn < 0.1 * osdConfig()->cap_alarm) {
tfp_sprintf(buff, "--:--"); tfp_sprintf(buff, "--:--");
@ -472,7 +485,7 @@ 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)) {
@ -480,11 +493,11 @@ static void osdDrawSingleElement(uint8_t item)
} 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 true;
} }
case OSD_CRAFT_NAME: case OSD_CRAFT_NAME:
@ -494,16 +507,17 @@ static void osdDrawSingleElement(uint8_t item)
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; buff[i] = SYM_BLANK;
} }
} }
buff[MAX_NAME_LENGTH] = '\0';
} }
break; break;
case OSD_THROTTLE_POS: case OSD_THROTTLE_POS:
buff[0] = SYM_THR; buff[0] = SYM_THR;
buff[1] = SYM_THR1; buff[1] = SYM_THR1;
tfp_sprintf(buff + 2, "%d", (constrain(rcData[THROTTLE], PWM_RANGE_MIN, PWM_RANGE_MAX) - PWM_RANGE_MIN) * 100 / (PWM_RANGE_MAX - PWM_RANGE_MIN)); tfp_sprintf(buff + 2, "%3d", (constrain(rcData[THROTTLE], PWM_RANGE_MIN, PWM_RANGE_MAX) - PWM_RANGE_MIN) * 100 / (PWM_RANGE_MAX - PWM_RANGE_MIN));
break; break;
#if defined(USE_VTX_COMMON) #if defined(USE_VTX_COMMON)
@ -515,7 +529,7 @@ static void osdDrawSingleElement(uint8_t item)
if (vtxSettingsConfig()->lowPowerDisarm) { if (vtxSettingsConfig()->lowPowerDisarm) {
vtxCommonGetPowerIndex(&vtxPower); vtxCommonGetPowerIndex(&vtxPower);
} }
tfp_sprintf(buff, "%c:%s:%d", vtxBandLetter, vtxChannelName, vtxPower); tfp_sprintf(buff, "%c:%s:%2d", vtxBandLetter, vtxChannelName, vtxPower);
break; break;
} }
#endif #endif
@ -536,18 +550,15 @@ static void osdDrawSingleElement(uint8_t item)
{ {
elemPosX = 14; elemPosX = 14;
elemPosY = 6 - 4; // Top center of the AH area elemPosY = 6 - 4; // Top center of the AH area
// Get pitch and roll limits in tenths of degrees
const int maxPitch = osdConfig()->ahMaxPitch * 10;
const int maxRoll = osdConfig()->ahMaxRoll * 10;
const int rollAngle = constrain(attitude.values.roll, -maxRoll, maxRoll);
int pitchAngle = constrain(attitude.values.pitch, -maxPitch, maxPitch);
if (displayScreenSize(osdDisplayPort) == VIDEO_BUFFER_CHARS_PAL) { if (displayScreenSize(osdDisplayPort) == VIDEO_BUFFER_CHARS_PAL) {
++elemPosY; ++elemPosY;
} }
// Get pitch and roll limits in tenths of degrees
const int maxPitch = osdConfig()->ahMaxPitch * 10;
const int maxRoll = osdConfig()->ahMaxRoll * 10;
const int rollAngle = constrain(attitude.values.roll, -maxRoll, maxRoll);
int pitchAngle = constrain(attitude.values.pitch, -maxPitch, maxPitch);
// Convert pitchAngle to y compensation value // Convert pitchAngle to y compensation value
// (maxPitch / 25) divisor matches previous settings of fixed divisor of 8 and fixed max AHI pitch angle of 20.0 degrees // (maxPitch / 25) divisor matches previous settings of fixed divisor of 8 and fixed max AHI pitch angle of 20.0 degrees
pitchAngle = ((pitchAngle * 25) / maxPitch) - 41; // 41 = 4 * AH_SYMBOL_COUNT + 5 pitchAngle = ((pitchAngle * 25) / maxPitch) - 41; // 41 = 4 * AH_SYMBOL_COUNT + 5
@ -561,14 +572,13 @@ static void osdDrawSingleElement(uint8_t item)
osdDrawSingleElement(OSD_HORIZON_SIDEBARS); osdDrawSingleElement(OSD_HORIZON_SIDEBARS);
return; return true;
} }
case OSD_HORIZON_SIDEBARS: case OSD_HORIZON_SIDEBARS:
{ {
elemPosX = 14; elemPosX = 14;
elemPosY = 6; elemPosY = 6;
if (displayScreenSize(osdDisplayPort) == VIDEO_BUFFER_CHARS_PAL) { if (displayScreenSize(osdDisplayPort) == VIDEO_BUFFER_CHARS_PAL) {
++elemPosY; ++elemPosY;
} }
@ -585,7 +595,7 @@ static void osdDrawSingleElement(uint8_t item)
displayWriteChar(osdDisplayPort, elemPosX - hudwidth + 1, elemPosY, SYM_AH_LEFT); displayWriteChar(osdDisplayPort, elemPosX - hudwidth + 1, elemPosY, SYM_AH_LEFT);
displayWriteChar(osdDisplayPort, elemPosX + hudwidth - 1, elemPosY, SYM_AH_RIGHT); displayWriteChar(osdDisplayPort, elemPosX + hudwidth - 1, elemPosY, SYM_AH_RIGHT);
return; return true;
} }
case OSD_ROLL_PIDS: case OSD_ROLL_PIDS:
@ -615,7 +625,7 @@ static void osdDrawSingleElement(uint8_t item)
const batteryState_e batteryState = getBatteryState(); const batteryState_e batteryState = getBatteryState();
if (enabledWarnings & OSD_WARNING_BATTERY_CRITICAL && batteryState == BATTERY_CRITICAL) { if (enabledWarnings & OSD_WARNING_BATTERY_CRITICAL && batteryState == BATTERY_CRITICAL) {
tfp_sprintf(buff, " LAND NOW"); osdFormatMessage(buff, sizeof(buff), " LAND NOW");
break; break;
} }
@ -623,7 +633,7 @@ static void osdDrawSingleElement(uint8_t item)
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)) {
tfp_sprintf(buff, "CRASH FLIP"); osdFormatMessage(buff, sizeof(buff), "CRASH FLIP");
break; break;
} }
@ -632,7 +642,7 @@ static void osdDrawSingleElement(uint8_t item)
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++) {
if (flags & (1 << i)) { if (flags & (1 << i)) {
tfp_sprintf(buff, "%s", armingDisableFlagNames[i]); osdFormatMessage(buff, sizeof(buff), armingDisableFlagNames[i]);
break; break;
} }
} }
@ -640,24 +650,24 @@ static void osdDrawSingleElement(uint8_t item)
} }
if (enabledWarnings & OSD_WARNING_BATTERY_WARNING && batteryState == BATTERY_WARNING) { if (enabledWarnings & OSD_WARNING_BATTERY_WARNING && batteryState == BATTERY_WARNING) {
tfp_sprintf(buff, "LOW BATTERY"); osdFormatMessage(buff, sizeof(buff), "LOW BATTERY");
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"); osdFormatMessage(buff, sizeof(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, " * * * *"); osdFormatMessage(buff, sizeof(buff), " * * * *");
break; break;
} }
return; return true;
} }
case OSD_AVG_CELL_VOLTAGE: case OSD_AVG_CELL_VOLTAGE:
@ -682,42 +692,35 @@ static void osdDrawSingleElement(uint8_t item)
case OSD_MAIN_BATT_USAGE: case OSD_MAIN_BATT_USAGE:
{ {
//Set length of indicator bar // Set length of indicator bar
#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 centered.
//Calculate constrained value // Calculate constrained value
const 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
const 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 (int i = 1; i <= MAIN_BATT_USAGE_STEPS; i++) {
if (i <= mAhUsedProgress) { buff[i] = i <= mAhUsedProgress ? SYM_PB_FULL : SYM_PB_EMPTY;
buff[i] = SYM_PB_FULL;
} else {
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) {
buff[1+mAhUsedProgress] = SYM_PB_END; buff[1 + mAhUsedProgress] = SYM_PB_END;
} }
buff[MAIN_BATT_USAGE_STEPS+2] = '\0';
buff[MAIN_BATT_USAGE_STEPS+2] = 0;
break; break;
} }
case OSD_DISARMED: case OSD_DISARMED:
if (!ARMING_FLAG(ARMED)) { if (!ARMING_FLAG(ARMED)) {
tfp_sprintf(buff, "DISARMED"); tfp_sprintf(buff, "DISARMED");
break;
} else { } else {
return; tfp_sprintf(buff, " ");
} }
break;
case OSD_NUMERICAL_HEADING: case OSD_NUMERICAL_HEADING:
{ {
@ -733,19 +736,20 @@ static void osdDrawSingleElement(uint8_t item)
tfp_sprintf(buff, "%c%01d.%01d", directionSymbol, abs(verticalSpeed / 100), abs((verticalSpeed % 100) / 10)); tfp_sprintf(buff, "%c%01d.%01d", directionSymbol, abs(verticalSpeed / 100), abs((verticalSpeed % 100) / 10));
break; break;
} }
#ifdef USE_ESC_SENSOR #ifdef USE_ESC_SENSOR
case OSD_ESC_TMP: case OSD_ESC_TMP:
tfp_sprintf(buff, "%d%c", escData == NULL ? 0 : escData->temperature, SYM_TEMP_C); tfp_sprintf(buff, "%3d%c", escData == NULL ? 0 : escData->temperature, SYM_TEMP_C);
break; break;
case OSD_ESC_RPM: case OSD_ESC_RPM:
tfp_sprintf(buff, "%d", escData == NULL ? 0 : escData->rpm); tfp_sprintf(buff, "%5d", escData == NULL ? 0 : escData->rpm);
break; break;
#endif #endif
#ifdef USE_RTC_TIME #ifdef USE_RTC_TIME
case OSD_RTC_DATETIME: case OSD_RTC_DATETIME:
printRtcDateTime(&buff[0]); osdFormatRtcDateTime(&buff[0]);
break; break;
#endif #endif
@ -755,11 +759,13 @@ static void osdDrawSingleElement(uint8_t item)
break; break;
#endif #endif
default: default:
return; return false;
} }
displayWrite(osdDisplayPort, elemPosX + elemOffsetX, elemPosY, buff); displayWrite(osdDisplayPort, elemPosX + elemOffsetX, elemPosY, buff);
return true;
} }
static void osdDrawElements(void) static void osdDrawElements(void)
@ -915,7 +921,7 @@ void osdInit(displayPort_t *osdDisplayPortToUse)
#ifdef USE_RTC_TIME #ifdef USE_RTC_TIME
char dateTimeBuffer[FORMATTED_DATE_TIME_BUFSIZE]; char dateTimeBuffer[FORMATTED_DATE_TIME_BUFSIZE];
if (printRtcDateTime(&dateTimeBuffer[0])) { if (osdFormatRtcDateTime(&dateTimeBuffer[0])) {
displayWrite(osdDisplayPort, 5, 12, dateTimeBuffer); displayWrite(osdDisplayPort, 5, 12, dateTimeBuffer);
} }
#endif #endif
@ -1011,6 +1017,7 @@ static void osdResetStats(void)
static void osdUpdateStats(void) static void osdUpdateStats(void)
{ {
int16_t value = 0; int16_t value = 0;
#ifdef USE_GPS #ifdef USE_GPS
value = CM_S_TO_KM_H(gpsSol.groundSpeed); value = CM_S_TO_KM_H(gpsSol.groundSpeed);
#endif #endif
@ -1027,6 +1034,7 @@ static void osdUpdateStats(void)
stats.max_current = value; stats.max_current = value;
} }
statRssi = scaleRange(getRssi(), 0, 1024, 0, 100);
if (stats.min_rssi > statRssi) { if (stats.min_rssi > statRssi) {
stats.min_rssi = statRssi; stats.min_rssi = statRssi;
} }
@ -1097,10 +1105,10 @@ static void osdDisplayStatisticLabel(uint8_t y, const char * text, const char *
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;
}
} }
}
return false; return false;
} }
@ -1115,7 +1123,7 @@ static void osdShowStats(void)
if (osdConfig()->enabled_stats[OSD_STAT_RTC_DATE_TIME]) { if (osdConfig()->enabled_stats[OSD_STAT_RTC_DATE_TIME]) {
bool success = false; bool success = false;
#ifdef USE_RTC_TIME #ifdef USE_RTC_TIME
success = printRtcDateTime(&buff[0]); success = osdFormatRtcDateTime(&buff[0]);
#endif #endif
if (!success) { if (!success) {
tfp_sprintf(buff, "NO RTC"); tfp_sprintf(buff, "NO RTC");
@ -1218,8 +1226,6 @@ STATIC_UNIT_TESTED void osdRefresh(timeUs_t currentTimeUs)
armState = ARMING_FLAG(ARMED); armState = ARMING_FLAG(ARMED);
} }
statRssi = scaleRange(getRssi(), 0, 1024, 0, 100);
osdUpdateStats(); osdUpdateStats();
if (ARMING_FLAG(ARMED)) { if (ARMING_FLAG(ARMED)) {
@ -1283,13 +1289,6 @@ void osdUpdate(timeUs_t currentTimeUs)
} }
#endif // MAX7456_DMA_CHANNEL_TX #endif // MAX7456_DMA_CHANNEL_TX
// redraw values in buffer
#ifdef USE_MAX7456
#define DRAW_FREQ_DENOM 5
#else
#define DRAW_FREQ_DENOM 10 // MWOSD @ 115200 baud (
#endif
#ifdef USE_SLOW_MSP_DISPLAYPORT_RATE_WHEN_UNARMED #ifdef USE_SLOW_MSP_DISPLAYPORT_RATE_WHEN_UNARMED
static uint32_t idlecounter = 0; static uint32_t idlecounter = 0;
if (!ARMING_FLAG(ARMED)) { if (!ARMING_FLAG(ARMED)) {
@ -1299,13 +1298,22 @@ void osdUpdate(timeUs_t currentTimeUs)
} }
#endif #endif
if (counter++ % DRAW_FREQ_DENOM == 0) { // redraw values in buffer
osdRefresh(currentTimeUs); #ifdef USE_MAX7456
#define DRAW_FREQ_DENOM 5
#else
#define DRAW_FREQ_DENOM 10 // MWOSD @ 115200 baud (
#endif
#define STATS_FREQ_DENOM 50
if (counter % DRAW_FREQ_DENOM == 0) {
osdRefresh(currentTimeUs);
showVisualBeeper = false; showVisualBeeper = false;
} else { // rest of time redraw screen 10 chars per idle so it doesn't lock the main idle } else {
// rest of time redraw screen 10 chars per idle so it doesn't lock the main idle
displayDrawScreen(osdDisplayPort); displayDrawScreen(osdDisplayPort);
} }
++counter;
#ifdef USE_CMS #ifdef USE_CMS
// do not allow ARM if we are in menu // do not allow ARM if we are in menu
@ -1317,4 +1325,4 @@ void osdUpdate(timeUs_t currentTimeUs)
#endif #endif
} }
#endif // OSD #endif // USE_OSD

View file

@ -139,10 +139,10 @@ void doTestArm(bool testEmpty = true)
*/ */
bool isSomeStatEnabled(void) { bool isSomeStatEnabled(void) {
for (int i = 0; i < OSD_STAT_COUNT; i++) { for (int i = 0; i < OSD_STAT_COUNT; i++) {
if (osdConfigMutable()->enabled_stats[i]) { if (osdConfigMutable()->enabled_stats[i]) {
return true; return true;
}
} }
}
return false; return false;
} }
@ -544,7 +544,7 @@ TEST(OsdTest, TestElementRssi)
osdRefresh(simulationTime); osdRefresh(simulationTime);
// then // then
displayPortTestBufferSubstring(8, 1, "%c0", SYM_RSSI); displayPortTestBufferSubstring(8, 1, "%c 0", SYM_RSSI);
// when // when
rssi = 512; rssi = 512;

View file

@ -143,6 +143,12 @@ void displayPortTestBufferIsEmpty()
{ {
for (size_t i = 0; i < UNITTEST_DISPLAYPORT_BUFFER_LEN; i++) { for (size_t i = 0; i < UNITTEST_DISPLAYPORT_BUFFER_LEN; i++) {
EXPECT_EQ(' ', testDisplayPortBuffer[i]); EXPECT_EQ(' ', testDisplayPortBuffer[i]);
if (testDisplayPortBuffer[i] != ' ') {
testDisplayPortBuffer[UNITTEST_DISPLAYPORT_BUFFER_LEN - 1] = '\0';
printf("FIRST ERROR AT:%d\r\n", (int)i);
printf("DISPLAY:%s\r\n", testDisplayPortBuffer);
break;
}
} }
} }