Increase priority of arming disabled OSD warnings and cycle through all
[betaflight.git] / src / main / io / osd.c
blob9ac454ad8d2b68f9681dd024a3801cc8780d9941
1 /*
2 * This file is part of Cleanflight and Betaflight.
4 * Cleanflight and Betaflight are free software. You can redistribute
5 * this software and/or modify this software under the terms of the
6 * GNU General Public License as published by the Free Software
7 * Foundation, either version 3 of the License, or (at your option)
8 * any later version.
10 * Cleanflight and Betaflight are distributed in the hope that they
11 * will be useful, but WITHOUT ANY WARRANTY; without even the implied
12 * warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
13 * See the GNU General Public License for more details.
15 * You should have received a copy of the GNU General Public License
16 * along with this software.
18 * If not, see <http://www.gnu.org/licenses/>.
22 Created by Marcin Baliniak
23 some functions based on MinimOSD
25 OSD-CMS separation by jflyper
28 #include <stdbool.h>
29 #include <stdint.h>
30 #include <stdlib.h>
31 #include <string.h>
32 #include <ctype.h>
33 #include <math.h>
35 #include "platform.h"
37 #ifdef USE_OSD
39 #include "blackbox/blackbox.h"
40 #include "blackbox/blackbox_io.h"
42 #include "build/build_config.h"
43 #include "build/debug.h"
44 #include "build/version.h"
46 #include "cms/cms.h"
47 #include "cms/cms_types.h"
49 #include "common/axis.h"
50 #include "common/maths.h"
51 #include "common/printf.h"
52 #include "common/typeconversion.h"
53 #include "common/utils.h"
55 #include "config/feature.h"
57 #include "drivers/display.h"
58 #include "drivers/flash.h"
59 #include "drivers/max7456_symbols.h"
60 #include "drivers/sdcard.h"
61 #include "drivers/time.h"
63 #include "fc/config.h"
64 #include "fc/core.h"
65 #include "fc/rc_adjustments.h"
66 #include "fc/rc_controls.h"
67 #include "fc/rc_modes.h"
68 #include "fc/rc.h"
69 #include "fc/runtime_config.h"
71 #include "flight/failsafe.h"
72 #include "flight/position.h"
73 #include "flight/imu.h"
74 #ifdef USE_ESC_SENSOR
75 #include "flight/mixer.h"
76 #endif
77 #include "flight/pid.h"
79 #include "io/asyncfatfs/asyncfatfs.h"
80 #include "io/beeper.h"
81 #include "io/flashfs.h"
82 #include "io/gps.h"
83 #include "io/osd.h"
84 #include "io/vtx_string.h"
85 #include "io/vtx.h"
87 #include "pg/pg.h"
88 #include "pg/pg_ids.h"
89 #include "pg/rx.h"
91 #include "rx/rx.h"
93 #include "sensors/acceleration.h"
94 #include "sensors/adcinternal.h"
95 #include "sensors/barometer.h"
96 #include "sensors/battery.h"
97 #include "sensors/esc_sensor.h"
98 #include "sensors/sensors.h"
100 #ifdef USE_HARDWARE_REVISION_DETECTION
101 #include "hardware_revision.h"
102 #endif
104 #define VIDEO_BUFFER_CHARS_PAL 480
105 #define FULL_CIRCLE 360
107 const char * const osdTimerSourceNames[] = {
108 "ON TIME ",
109 "TOTAL ARM",
110 "LAST ARM "
113 // Blink control
115 static bool blinkState = true;
116 static bool showVisualBeeper = false;
118 static uint32_t blinkBits[(OSD_ITEM_COUNT + 31)/32];
119 #define SET_BLINK(item) (blinkBits[(item) / 32] |= (1 << ((item) % 32)))
120 #define CLR_BLINK(item) (blinkBits[(item) / 32] &= ~(1 << ((item) % 32)))
121 #define IS_BLINK(item) (blinkBits[(item) / 32] & (1 << ((item) % 32)))
122 #define BLINK(item) (IS_BLINK(item) && blinkState)
124 // Things in both OSD and CMS
126 #define IS_HI(X) (rcData[X] > 1750)
127 #define IS_LO(X) (rcData[X] < 1250)
128 #define IS_MID(X) (rcData[X] > 1250 && rcData[X] < 1750)
130 static timeUs_t flyTime = 0;
131 static float osdGForce = 0;
133 typedef struct statistic_s {
134 timeUs_t armed_time;
135 int16_t max_speed;
136 int16_t min_voltage; // /10
137 int16_t max_current; // /10
138 int16_t min_rssi;
139 int32_t max_altitude;
140 int16_t max_distance;
141 float max_g_force;
142 } statistic_t;
144 static statistic_t stats;
146 timeUs_t resumeRefreshAt = 0;
147 #define REFRESH_1S 1000 * 1000
149 static uint8_t armState;
150 static bool lastArmState;
152 static displayPort_t *osdDisplayPort;
154 #ifdef USE_ESC_SENSOR
155 static escSensorData_t *escDataCombined;
156 #endif
158 #define AH_SYMBOL_COUNT 9
159 #define AH_SIDEBAR_WIDTH_POS 7
160 #define AH_SIDEBAR_HEIGHT_POS 3
162 static const char compassBar[] = {
163 SYM_HEADING_W,
164 SYM_HEADING_LINE, SYM_HEADING_DIVIDED_LINE, SYM_HEADING_LINE,
165 SYM_HEADING_N,
166 SYM_HEADING_LINE, SYM_HEADING_DIVIDED_LINE, SYM_HEADING_LINE,
167 SYM_HEADING_E,
168 SYM_HEADING_LINE, SYM_HEADING_DIVIDED_LINE, SYM_HEADING_LINE,
169 SYM_HEADING_S,
170 SYM_HEADING_LINE, SYM_HEADING_DIVIDED_LINE, SYM_HEADING_LINE,
171 SYM_HEADING_W,
172 SYM_HEADING_LINE, SYM_HEADING_DIVIDED_LINE, SYM_HEADING_LINE,
173 SYM_HEADING_N,
174 SYM_HEADING_LINE, SYM_HEADING_DIVIDED_LINE, SYM_HEADING_LINE
177 static const uint8_t osdElementDisplayOrder[] = {
178 OSD_MAIN_BATT_VOLTAGE,
179 OSD_RSSI_VALUE,
180 OSD_CROSSHAIRS,
181 OSD_HORIZON_SIDEBARS,
182 OSD_ITEM_TIMER_1,
183 OSD_ITEM_TIMER_2,
184 OSD_REMAINING_TIME_ESTIMATE,
185 OSD_FLYMODE,
186 OSD_THROTTLE_POS,
187 OSD_VTX_CHANNEL,
188 OSD_CURRENT_DRAW,
189 OSD_MAH_DRAWN,
190 OSD_CRAFT_NAME,
191 OSD_ALTITUDE,
192 OSD_ROLL_PIDS,
193 OSD_PITCH_PIDS,
194 OSD_YAW_PIDS,
195 OSD_POWER,
196 OSD_PIDRATE_PROFILE,
197 OSD_WARNINGS,
198 OSD_AVG_CELL_VOLTAGE,
199 OSD_DEBUG,
200 OSD_PITCH_ANGLE,
201 OSD_ROLL_ANGLE,
202 OSD_MAIN_BATT_USAGE,
203 OSD_DISARMED,
204 OSD_NUMERICAL_HEADING,
205 OSD_NUMERICAL_VARIO,
206 OSD_COMPASS_BAR,
207 OSD_ANTI_GRAVITY,
208 OSD_FLIP_ARROW,
209 #ifdef USE_RTC_TIME
210 OSD_RTC_DATETIME,
211 #endif
212 #ifdef USE_OSD_ADJUSTMENTS
213 OSD_ADJUSTMENT_RANGE,
214 #endif
215 #ifdef USE_ADC_INTERNAL
216 OSD_CORE_TEMPERATURE,
217 #endif
220 PG_REGISTER_WITH_RESET_FN(osdConfig_t, osdConfig, PG_OSD_CONFIG, 3);
223 * Gets the correct altitude symbol for the current unit system
225 static char osdGetMetersToSelectedUnitSymbol(void)
227 switch (osdConfig()->units) {
228 case OSD_UNIT_IMPERIAL:
229 return SYM_FT;
230 default:
231 return SYM_M;
236 * Gets average battery cell voltage in 0.01V units.
238 static int osdGetBatteryAverageCellVoltage(void)
240 return (getBatteryVoltage() * 10) / getBatteryCellCount();
243 static char osdGetBatterySymbol(int cellVoltage)
245 if (getBatteryState() == BATTERY_CRITICAL) {
246 return SYM_MAIN_BATT; // FIXME: currently the BAT- symbol, ideally replace with a battery with exclamation mark
247 } else {
248 // Calculate a symbol offset using cell voltage over full cell voltage range
249 const int symOffset = scaleRange(cellVoltage, batteryConfig()->vbatmincellvoltage * 10, batteryConfig()->vbatmaxcellvoltage * 10, 0, 7);
250 return SYM_BATT_EMPTY - constrain(symOffset, 0, 6);
255 * Converts altitude based on the current unit system.
256 * @param meters Value in meters to convert
258 static int32_t osdGetMetersToSelectedUnit(int32_t meters)
260 switch (osdConfig()->units) {
261 case OSD_UNIT_IMPERIAL:
262 return (meters * 328) / 100; // Convert to feet / 100
263 default:
264 return meters; // Already in metre / 100
268 #if defined(USE_ADC_INTERNAL) || defined(USE_ESC_SENSOR)
269 STATIC_UNIT_TESTED int osdConvertTemperatureToSelectedUnit(int tempInDeciDegrees)
271 switch (osdConfig()->units) {
272 case OSD_UNIT_IMPERIAL:
273 return ((tempInDeciDegrees * 9) / 5) + 320;
274 default:
275 return tempInDeciDegrees;
279 static char osdGetTemperatureSymbolForSelectedUnit(void)
281 switch (osdConfig()->units) {
282 case OSD_UNIT_IMPERIAL:
283 return 'F';
284 default:
285 return 'C';
288 #endif
290 static void osdFormatAltitudeString(char * buff, int32_t altitudeCm)
292 const int alt = osdGetMetersToSelectedUnit(altitudeCm) / 10;
294 tfp_sprintf(buff, "%5d %c", alt, osdGetMetersToSelectedUnitSymbol());
295 buff[5] = buff[4];
296 buff[4] = '.';
299 static void osdFormatPID(char * buff, const char * label, const pidf_t * pid)
301 tfp_sprintf(buff, "%s %3d %3d %3d", label, pid->P, pid->I, pid->D);
304 static uint8_t osdGetHeadingIntoDiscreteDirections(int heading, unsigned directions)
306 heading += FULL_CIRCLE; // Ensure positive value
308 // Split input heading 0..359 into sectors 0..(directions-1), but offset
309 // by half a sector so that sector 0 gets centered around heading 0.
310 // We multiply heading by directions to not loose precision in divisions
311 // In this way each segment will be a FULL_CIRCLE length
312 int direction = (heading * directions + FULL_CIRCLE / 2) / FULL_CIRCLE; // scale with rounding
313 direction %= directions; // normalize
315 return direction; // return segment number
318 static uint8_t osdGetDirectionSymbolFromHeading(int heading)
320 heading = osdGetHeadingIntoDiscreteDirections(heading, 16);
322 // Now heading has a heading with Up=0, Right=4, Down=8 and Left=12
323 // Our symbols are Down=0, Right=4, Up=8 and Left=12
324 // There're 16 arrow symbols. Transform it.
325 heading = 16 - heading;
326 heading = (heading + 8) % 16;
328 return SYM_ARROW_SOUTH + heading;
331 static char osdGetTimerSymbol(osd_timer_source_e src)
333 switch (src) {
334 case OSD_TIMER_SRC_ON:
335 return SYM_ON_M;
336 case OSD_TIMER_SRC_TOTAL_ARMED:
337 case OSD_TIMER_SRC_LAST_ARMED:
338 return SYM_FLY_M;
339 default:
340 return ' ';
344 static timeUs_t osdGetTimerValue(osd_timer_source_e src)
346 switch (src) {
347 case OSD_TIMER_SRC_ON:
348 return micros();
349 case OSD_TIMER_SRC_TOTAL_ARMED:
350 return flyTime;
351 case OSD_TIMER_SRC_LAST_ARMED:
352 return stats.armed_time;
353 default:
354 return 0;
358 STATIC_UNIT_TESTED void osdFormatTime(char * buff, osd_timer_precision_e precision, timeUs_t time)
360 int seconds = time / 1000000;
361 const int minutes = seconds / 60;
362 seconds = seconds % 60;
364 switch (precision) {
365 case OSD_TIMER_PREC_SECOND:
366 default:
367 tfp_sprintf(buff, "%02d:%02d", minutes, seconds);
368 break;
369 case OSD_TIMER_PREC_HUNDREDTHS:
371 const int hundredths = (time / 10000) % 100;
372 tfp_sprintf(buff, "%02d:%02d.%02d", minutes, seconds, hundredths);
373 break;
378 STATIC_UNIT_TESTED void osdFormatTimer(char *buff, bool showSymbol, bool usePrecision, int timerIndex)
380 const uint16_t timer = osdConfig()->timers[timerIndex];
381 const uint8_t src = OSD_TIMER_SRC(timer);
383 if (showSymbol) {
384 *(buff++) = osdGetTimerSymbol(src);
387 osdFormatTime(buff, (usePrecision ? OSD_TIMER_PRECISION(timer) : OSD_TIMER_PREC_SECOND), osdGetTimerValue(src));
390 #ifdef USE_GPS
391 static void osdFormatCoordinate(char *buff, char sym, int32_t val)
393 // latitude maximum integer width is 3 (-90).
394 // longitude maximum integer width is 4 (-180).
395 // We show 7 decimals, so we need to use 12 characters:
396 // eg: s-180.1234567z s=symbol, z=zero terminator, decimal separator between 0 and 1
398 static const int coordinateMaxLength = 13;//12 for the number (4 + dot + 7) + 1 for the symbol
400 buff[0] = sym;
401 const int32_t integerPart = val / GPS_DEGREES_DIVIDER;
402 const int32_t decimalPart = labs(val % GPS_DEGREES_DIVIDER);
403 const int written = tfp_sprintf(buff + 1, "%d.%07d", integerPart, decimalPart);
404 // pad with blanks to coordinateMaxLength
405 for (int pos = 1 + written; pos < coordinateMaxLength; ++pos) {
406 buff[pos] = SYM_BLANK;
408 buff[coordinateMaxLength] = '\0';
410 #endif // USE_GPS
412 #ifdef USE_RTC_TIME
413 static bool osdFormatRtcDateTime(char *buffer)
415 dateTime_t dateTime;
416 if (!rtcGetDateTime(&dateTime)) {
417 buffer[0] = '\0';
419 return false;
422 dateTimeFormatLocalShort(buffer, &dateTime);
424 return true;
426 #endif
428 static void osdFormatMessage(char *buff, size_t size, const char *message)
430 memset(buff, SYM_BLANK, size);
431 if (message) {
432 memcpy(buff, message, strlen(message));
434 // Ensure buff is zero terminated
435 buff[size - 1] = '\0';
438 void osdStatSetState(uint8_t statIndex, bool enabled)
440 if (enabled) {
441 osdConfigMutable()->enabled_stats |= (1 << statIndex);
442 } else {
443 osdConfigMutable()->enabled_stats &= ~(1 << statIndex);
447 bool osdStatGetState(uint8_t statIndex)
449 return osdConfig()->enabled_stats & (1 << statIndex);
452 void osdWarnSetState(uint8_t warningIndex, bool enabled)
454 if (enabled) {
455 osdConfigMutable()->enabledWarnings |= (1 << warningIndex);
456 } else {
457 osdConfigMutable()->enabledWarnings &= ~(1 << warningIndex);
461 bool osdWarnGetState(uint8_t warningIndex)
463 return osdConfig()->enabledWarnings & (1 << warningIndex);
466 static bool osdDrawSingleElement(uint8_t item)
468 if (!VISIBLE(osdConfig()->item_pos[item]) || BLINK(item)) {
469 return false;
472 uint8_t elemPosX = OSD_X(osdConfig()->item_pos[item]);
473 uint8_t elemPosY = OSD_Y(osdConfig()->item_pos[item]);
474 char buff[OSD_ELEMENT_BUFFER_LENGTH] = "";
476 switch (item) {
477 case OSD_FLIP_ARROW:
479 const int angleR = attitude.values.roll / 10;
480 const int angleP = attitude.values.pitch / 10; // still gotta update all angleR and angleP pointers.
481 if (IS_RC_MODE_ACTIVE(BOXFLIPOVERAFTERCRASH)) {
482 if (angleP > 0 && ((angleR > 175 && angleR < 180) || (angleR > -180 && angleR < -175))) {
483 buff[0] = SYM_ARROW_SOUTH;
484 } else if (angleP > 0 && angleR > 0 && angleR < 175) {
485 buff[0] = (SYM_ARROW_EAST + 2);
486 } else if (angleP > 0 && angleR < 0 && angleR > -175) {
487 buff[0] = (SYM_ARROW_WEST + 2);
488 } else if (angleP <= 0 && ((angleR > 175 && angleR < 180) || (angleR > -180 && angleR < -175))) {
489 buff[0] = SYM_ARROW_NORTH;
490 } else if (angleP <= 0 && angleR > 0 && angleR < 175) {
491 buff[0] = (SYM_ARROW_NORTH + 2);
492 } else if (angleP <= 0 && angleR < 0 && angleR > -175) {
493 buff[0] = (SYM_ARROW_SOUTH + 2);
495 } else {
496 buff[0] = ' ';
498 buff[1] = '\0';
499 break;
501 case OSD_RSSI_VALUE:
503 uint16_t osdRssi = getRssi() * 100 / 1024; // change range
504 if (osdRssi >= 100)
505 osdRssi = 99;
507 tfp_sprintf(buff, "%c%2d", SYM_RSSI, osdRssi);
508 break;
511 case OSD_MAIN_BATT_VOLTAGE:
512 buff[0] = osdGetBatterySymbol(osdGetBatteryAverageCellVoltage());
513 tfp_sprintf(buff + 1, "%2d.%1d%c", getBatteryVoltage() / 10, getBatteryVoltage() % 10, SYM_VOLT);
514 break;
516 case OSD_CURRENT_DRAW:
518 const int32_t amperage = getAmperage();
519 tfp_sprintf(buff, "%3d.%02d%c", abs(amperage) / 100, abs(amperage) % 100, SYM_AMP);
520 break;
523 case OSD_MAH_DRAWN:
524 tfp_sprintf(buff, "%4d%c", getMAhDrawn(), SYM_MAH);
525 break;
527 #ifdef USE_GPS
528 case OSD_GPS_SATS:
529 tfp_sprintf(buff, "%c%c%2d", SYM_SAT_L, SYM_SAT_R, gpsSol.numSat);
530 break;
532 case OSD_GPS_SPEED:
533 // FIXME ideally we want to use SYM_KMH symbol but it's not in the font any more, so we use K (M for MPH)
534 switch (osdConfig()->units) {
535 case OSD_UNIT_IMPERIAL:
536 tfp_sprintf(buff, "%3dM", CM_S_TO_MPH(gpsSol.groundSpeed));
537 break;
538 default:
539 tfp_sprintf(buff, "%3dK", CM_S_TO_KM_H(gpsSol.groundSpeed));
540 break;
542 break;
544 case OSD_GPS_LAT:
545 // The SYM_LAT symbol in the actual font contains only blank, so we use the SYM_ARROW_NORTH
546 osdFormatCoordinate(buff, SYM_ARROW_NORTH, gpsSol.llh.lat);
547 break;
549 case OSD_GPS_LON:
550 // The SYM_LON symbol in the actual font contains only blank, so we use the SYM_ARROW_EAST
551 osdFormatCoordinate(buff, SYM_ARROW_EAST, gpsSol.llh.lon);
552 break;
554 case OSD_HOME_DIR:
555 if (STATE(GPS_FIX) && STATE(GPS_FIX_HOME)) {
556 if (GPS_distanceToHome > 0) {
557 const int h = GPS_directionToHome - DECIDEGREES_TO_DEGREES(attitude.values.yaw);
558 buff[0] = osdGetDirectionSymbolFromHeading(h);
559 } else {
560 // We don't have a HOME symbol in the font, by now we use this
561 buff[0] = SYM_THR1;
564 } else {
565 // We use this symbol when we don't have a FIX
566 buff[0] = SYM_COLON;
569 buff[1] = 0;
571 break;
573 case OSD_HOME_DIST:
574 if (STATE(GPS_FIX) && STATE(GPS_FIX_HOME)) {
575 const int32_t distance = osdGetMetersToSelectedUnit(GPS_distanceToHome);
576 tfp_sprintf(buff, "%d%c", distance, osdGetMetersToSelectedUnitSymbol());
577 } else {
578 // We use this symbol when we don't have a FIX
579 buff[0] = SYM_COLON;
580 // overwrite any previous distance with blanks
581 memset(buff + 1, SYM_BLANK, 6);
582 buff[7] = '\0';
584 break;
586 #endif // GPS
588 case OSD_COMPASS_BAR:
589 memcpy(buff, compassBar + osdGetHeadingIntoDiscreteDirections(DECIDEGREES_TO_DEGREES(attitude.values.yaw), 16), 9);
590 buff[9] = 0;
591 break;
593 case OSD_ALTITUDE:
594 osdFormatAltitudeString(buff, getEstimatedAltitudeCm());
595 break;
597 case OSD_ITEM_TIMER_1:
598 case OSD_ITEM_TIMER_2:
599 osdFormatTimer(buff, true, true, item - OSD_ITEM_TIMER_1);
600 break;
602 case OSD_REMAINING_TIME_ESTIMATE:
604 const int mAhDrawn = getMAhDrawn();
605 const int remaining_time = (int)((osdConfig()->cap_alarm - mAhDrawn) * ((float)flyTime) / mAhDrawn);
607 if (mAhDrawn < 0.1 * osdConfig()->cap_alarm) {
608 tfp_sprintf(buff, "--:--");
609 } else if (mAhDrawn > osdConfig()->cap_alarm) {
610 tfp_sprintf(buff, "00:00");
611 } else {
612 osdFormatTime(buff, OSD_TIMER_PREC_SECOND, remaining_time);
614 break;
617 case OSD_FLYMODE:
619 // Note that flight mode display has precedence in what to display.
620 // 1. FS
621 // 2. GPS RESCUE
622 // 3. ANGLE, HORIZON, ACRO TRAINER
623 // 4. AIR
624 // 5. ACRO
626 if (FLIGHT_MODE(FAILSAFE_MODE)) {
627 strcpy(buff, "!FS!");
628 } else if (FLIGHT_MODE(GPS_RESCUE_MODE)) {
629 strcpy(buff, "RESC");
630 } else if (FLIGHT_MODE(ANGLE_MODE)) {
631 strcpy(buff, "STAB");
632 } else if (FLIGHT_MODE(HORIZON_MODE)) {
633 strcpy(buff, "HOR ");
634 } else if (IS_RC_MODE_ACTIVE(BOXACROTRAINER)) {
635 strcpy(buff, "ATRN");
636 } else if (isAirmodeActive()) {
637 strcpy(buff, "AIR ");
638 } else {
639 strcpy(buff, "ACRO");
642 break;
645 case OSD_ANTI_GRAVITY:
647 if (pidOsdAntiGravityActive()) {
648 strcpy(buff, "AG");
651 break;
654 case OSD_CRAFT_NAME:
655 // This does not strictly support iterative updating if the craft name changes at run time. But since the craft name is not supposed to be changing this should not matter, and blanking the entire length of the craft name string on update will make it impossible to configure elements to be displayed on the right hand side of the craft name.
656 //TODO: When iterative updating is implemented, change this so the craft name is only printed once whenever the OSD 'flight' screen is entered.
658 if (strlen(pilotConfig()->name) == 0) {
659 strcpy(buff, "CRAFT_NAME");
660 } else {
661 unsigned i;
662 for (i = 0; i < MAX_NAME_LENGTH; i++) {
663 if (pilotConfig()->name[i]) {
664 buff[i] = toupper((unsigned char)pilotConfig()->name[i]);
665 } else {
666 break;
669 buff[i] = '\0';
672 break;
674 case OSD_THROTTLE_POS:
675 buff[0] = SYM_THR;
676 buff[1] = SYM_THR1;
677 tfp_sprintf(buff + 2, "%3d", (constrain(rcData[THROTTLE], PWM_RANGE_MIN, PWM_RANGE_MAX) - PWM_RANGE_MIN) * 100 / (PWM_RANGE_MAX - PWM_RANGE_MIN));
678 break;
680 #if defined(USE_VTX_COMMON)
681 case OSD_VTX_CHANNEL:
683 const char vtxBandLetter = vtx58BandLetter[vtxSettingsConfig()->band];
684 const char *vtxChannelName = vtx58ChannelNames[vtxSettingsConfig()->channel];
685 uint8_t vtxPower = vtxSettingsConfig()->power;
686 const vtxDevice_t *vtxDevice = vtxCommonDevice();
687 if (vtxDevice && vtxSettingsConfig()->lowPowerDisarm) {
688 vtxCommonGetPowerIndex(vtxDevice, &vtxPower);
690 tfp_sprintf(buff, "%c:%s:%1d", vtxBandLetter, vtxChannelName, vtxPower);
691 break;
693 #endif
695 case OSD_CROSSHAIRS:
696 buff[0] = SYM_AH_CENTER_LINE;
697 buff[1] = SYM_AH_CENTER;
698 buff[2] = SYM_AH_CENTER_LINE_RIGHT;
699 buff[3] = 0;
700 break;
702 case OSD_ARTIFICIAL_HORIZON:
704 // Get pitch and roll limits in tenths of degrees
705 const int maxPitch = osdConfig()->ahMaxPitch * 10;
706 const int maxRoll = osdConfig()->ahMaxRoll * 10;
707 const int rollAngle = constrain(attitude.values.roll, -maxRoll, maxRoll);
708 int pitchAngle = constrain(attitude.values.pitch, -maxPitch, maxPitch);
709 // Convert pitchAngle to y compensation value
710 // (maxPitch / 25) divisor matches previous settings of fixed divisor of 8 and fixed max AHI pitch angle of 20.0 degrees
711 pitchAngle = ((pitchAngle * 25) / maxPitch) - 41; // 41 = 4 * AH_SYMBOL_COUNT + 5
713 for (int x = -4; x <= 4; x++) {
714 const int y = ((-rollAngle * x) / 64) - pitchAngle;
715 if (y >= 0 && y <= 81) {
716 displayWriteChar(osdDisplayPort, elemPosX + x, elemPosY + (y / AH_SYMBOL_COUNT), (SYM_AH_BAR9_0 + (y % AH_SYMBOL_COUNT)));
720 return true;
723 case OSD_HORIZON_SIDEBARS:
725 // Draw AH sides
726 const int8_t hudwidth = AH_SIDEBAR_WIDTH_POS;
727 const int8_t hudheight = AH_SIDEBAR_HEIGHT_POS;
728 for (int y = -hudheight; y <= hudheight; y++) {
729 displayWriteChar(osdDisplayPort, elemPosX - hudwidth, elemPosY + y, SYM_AH_DECORATION);
730 displayWriteChar(osdDisplayPort, elemPosX + hudwidth, elemPosY + y, SYM_AH_DECORATION);
733 // AH level indicators
734 displayWriteChar(osdDisplayPort, elemPosX - hudwidth + 1, elemPosY, SYM_AH_LEFT);
735 displayWriteChar(osdDisplayPort, elemPosX + hudwidth - 1, elemPosY, SYM_AH_RIGHT);
737 return true;
740 case OSD_G_FORCE:
741 tfp_sprintf(buff, "%01d.%01dG", (int)osdGForce, (int)(osdGForce * 10) % 10);
742 break;
744 case OSD_ROLL_PIDS:
745 osdFormatPID(buff, "ROL", &currentPidProfile->pid[PID_ROLL]);
746 break;
748 case OSD_PITCH_PIDS:
749 osdFormatPID(buff, "PIT", &currentPidProfile->pid[PID_PITCH]);
750 break;
752 case OSD_YAW_PIDS:
753 osdFormatPID(buff, "YAW", &currentPidProfile->pid[PID_YAW]);
754 break;
756 case OSD_POWER:
757 tfp_sprintf(buff, "%4dW", getAmperage() * getBatteryVoltage() / 1000);
758 break;
760 case OSD_PIDRATE_PROFILE:
761 tfp_sprintf(buff, "%d-%d", getCurrentPidProfileIndex() + 1, getCurrentControlRateProfileIndex() + 1);
762 break;
764 case OSD_WARNINGS:
767 #define OSD_WARNINGS_MAX_SIZE 11
768 #define OSD_FORMAT_MESSAGE_BUFFER_SIZE (OSD_WARNINGS_MAX_SIZE + 1)
770 STATIC_ASSERT(OSD_FORMAT_MESSAGE_BUFFER_SIZE <= sizeof(buff), osd_warnings_size_exceeds_buffer_size);
772 const batteryState_e batteryState = getBatteryState();
773 const timeUs_t currentTimeUs = micros();
775 static timeUs_t armingDisabledUpdateTimeUs;
776 static unsigned armingDisabledDisplayIndex;
778 // Cycle through the arming disabled reasons
779 if (osdWarnGetState(OSD_WARNING_ARMING_DISABLE)) {
780 if (IS_RC_MODE_ACTIVE(BOXARM) && isArmingDisabled()) {
781 const armingDisableFlags_e armSwitchOnlyFlag = 1 << (ARMING_DISABLE_FLAGS_COUNT - 1);
782 armingDisableFlags_e flags = getArmingDisableFlags();
784 // Remove the ARMSWITCH flag unless it's the only one
785 if ((flags & armSwitchOnlyFlag) && (flags != armSwitchOnlyFlag)) {
786 flags -= armSwitchOnlyFlag;
789 // Rotate to the next arming disabled reason after a 0.5 second time delay
790 // or if the current flag is no longer set
791 if ((currentTimeUs - armingDisabledUpdateTimeUs > 5e5) || !(flags & (1 << armingDisabledDisplayIndex))) {
792 if (armingDisabledUpdateTimeUs == 0) {
793 armingDisabledDisplayIndex = ARMING_DISABLE_FLAGS_COUNT - 1;
795 armingDisabledUpdateTimeUs = currentTimeUs;
797 do {
798 if (++armingDisabledDisplayIndex >= ARMING_DISABLE_FLAGS_COUNT) {
799 armingDisabledDisplayIndex = 0;
801 } while (!(flags & (1 << armingDisabledDisplayIndex)));
804 osdFormatMessage(buff, OSD_FORMAT_MESSAGE_BUFFER_SIZE, armingDisableFlagNames[armingDisabledDisplayIndex]);
805 break;
806 } else {
807 armingDisabledUpdateTimeUs = 0;
811 #ifdef USE_DSHOT
812 if (isTryingToArm() && !ARMING_FLAG(ARMED)) {
813 int armingDelayTime = (getLastDshotBeaconCommandTimeUs() + DSHOT_BEACON_GUARD_DELAY_US - currentTimeUs) / 1e5;
814 if (armingDelayTime < 0) {
815 armingDelayTime = 0;
817 if (armingDelayTime >= (DSHOT_BEACON_GUARD_DELAY_US / 1e5 - 5)) {
818 osdFormatMessage(buff, OSD_FORMAT_MESSAGE_BUFFER_SIZE, " BEACON ON"); // Display this message for the first 0.5 seconds
819 } else {
820 char armingDelayMessage[OSD_FORMAT_MESSAGE_BUFFER_SIZE];
821 tfp_sprintf(armingDelayMessage, "ARM IN %d.%d", armingDelayTime / 10, armingDelayTime % 10);
822 osdFormatMessage(buff, OSD_FORMAT_MESSAGE_BUFFER_SIZE, armingDelayMessage);
824 break;
826 #endif
827 if (osdWarnGetState(OSD_WARNING_FAIL_SAFE) && failsafeIsActive()) {
828 osdFormatMessage(buff, OSD_FORMAT_MESSAGE_BUFFER_SIZE, "FAIL SAFE");
829 break;
832 if (osdWarnGetState(OSD_WARNING_BATTERY_CRITICAL) && batteryState == BATTERY_CRITICAL) {
833 osdFormatMessage(buff, OSD_FORMAT_MESSAGE_BUFFER_SIZE, " LAND NOW");
834 break;
837 #ifdef USE_ADC_INTERNAL
838 uint8_t coreTemperature = getCoreTemperatureCelsius();
839 if (osdWarnGetState(OSD_WARNING_CORE_TEMPERATURE) && coreTemperature >= osdConfig()->core_temp_alarm) {
840 char coreTemperatureWarningMsg[OSD_FORMAT_MESSAGE_BUFFER_SIZE];
841 tfp_sprintf(coreTemperatureWarningMsg, "CORE: %3d%c", osdConvertTemperatureToSelectedUnit(getCoreTemperatureCelsius() * 10) / 10, osdGetTemperatureSymbolForSelectedUnit());
843 osdFormatMessage(buff, OSD_FORMAT_MESSAGE_BUFFER_SIZE, coreTemperatureWarningMsg);
845 break;
847 #endif
849 #ifdef USE_ESC_SENSOR
850 // Show warning if we lose motor output, the ESC is overheating or excessive current draw
851 if (featureIsEnabled(FEATURE_ESC_SENSOR) && osdWarnGetState(OSD_WARNING_ESC_FAIL)) {
852 char escWarningMsg[OSD_FORMAT_MESSAGE_BUFFER_SIZE];
853 unsigned pos = 0;
855 const char *title = "ESC";
857 // center justify message
858 while (pos < (OSD_WARNINGS_MAX_SIZE - (strlen(title) + getMotorCount())) / 2) {
859 escWarningMsg[pos++] = ' ';
862 strcpy(escWarningMsg + pos, title);
863 pos += strlen(title);
865 unsigned i = 0;
866 unsigned escWarningCount = 0;
867 while (i < getMotorCount() && pos < OSD_FORMAT_MESSAGE_BUFFER_SIZE - 1) {
868 escSensorData_t *escData = getEscSensorData(i);
869 const char motorNumber = '1' + i;
870 // if everything is OK just display motor number else R, T or C
871 char warnFlag = motorNumber;
872 if (ARMING_FLAG(ARMED) && osdConfig()->esc_rpm_alarm != ESC_RPM_ALARM_OFF && calcEscRpm(escData->rpm) <= osdConfig()->esc_rpm_alarm) {
873 warnFlag = 'R';
875 if (osdConfig()->esc_temp_alarm != ESC_TEMP_ALARM_OFF && escData->temperature >= osdConfig()->esc_temp_alarm) {
876 warnFlag = 'T';
878 if (ARMING_FLAG(ARMED) && osdConfig()->esc_current_alarm != ESC_CURRENT_ALARM_OFF && escData->current >= osdConfig()->esc_current_alarm) {
879 warnFlag = 'C';
882 escWarningMsg[pos++] = warnFlag;
884 if (warnFlag != motorNumber) {
885 escWarningCount++;
888 i++;
891 escWarningMsg[pos] = '\0';
893 if (escWarningCount > 0) {
894 osdFormatMessage(buff, OSD_FORMAT_MESSAGE_BUFFER_SIZE, escWarningMsg);
895 break;
898 #endif
900 // Warn when in flip over after crash mode
901 if (osdWarnGetState(OSD_WARNING_CRASH_FLIP) && isFlipOverAfterCrashMode()) {
902 osdFormatMessage(buff, OSD_FORMAT_MESSAGE_BUFFER_SIZE, "CRASH FLIP");
903 break;
906 if (osdWarnGetState(OSD_WARNING_BATTERY_WARNING) && batteryState == BATTERY_WARNING) {
907 osdFormatMessage(buff, OSD_FORMAT_MESSAGE_BUFFER_SIZE, "LOW BATTERY");
908 break;
911 #ifdef USE_RC_SMOOTHING_FILTER
912 // Show warning if rc smoothing hasn't initialized the filters
913 if (osdWarnGetState(OSD_WARNING_RC_SMOOTHING) && ARMING_FLAG(ARMED) && !rcSmoothingInitializationComplete()) {
914 osdFormatMessage(buff, OSD_FORMAT_MESSAGE_BUFFER_SIZE, "RCSMOOTHING");
915 break;
917 #endif
919 // Show warning if battery is not fresh
920 if (osdWarnGetState(OSD_WARNING_BATTERY_NOT_FULL) && !ARMING_FLAG(WAS_EVER_ARMED) && (getBatteryState() == BATTERY_OK)
921 && getBatteryAverageCellVoltage() < batteryConfig()->vbatfullcellvoltage) {
922 osdFormatMessage(buff, OSD_FORMAT_MESSAGE_BUFFER_SIZE, "BATT < FULL");
923 break;
926 // Visual beeper
927 if (osdWarnGetState(OSD_WARNING_VISUAL_BEEPER) && showVisualBeeper) {
928 osdFormatMessage(buff, OSD_FORMAT_MESSAGE_BUFFER_SIZE, " * * * *");
929 break;
932 osdFormatMessage(buff, OSD_FORMAT_MESSAGE_BUFFER_SIZE, NULL);
933 break;
936 case OSD_AVG_CELL_VOLTAGE:
938 const int cellV = osdGetBatteryAverageCellVoltage();
939 buff[0] = osdGetBatterySymbol(cellV);
940 tfp_sprintf(buff + 1, "%d.%02d%c", cellV / 100, cellV % 100, SYM_VOLT);
941 break;
944 case OSD_DEBUG:
945 tfp_sprintf(buff, "DBG %5d %5d %5d %5d", debug[0], debug[1], debug[2], debug[3]);
946 break;
948 case OSD_PITCH_ANGLE:
949 case OSD_ROLL_ANGLE:
951 const int angle = (item == OSD_PITCH_ANGLE) ? attitude.values.pitch : attitude.values.roll;
952 tfp_sprintf(buff, "%c%02d.%01d", angle < 0 ? '-' : ' ', abs(angle / 10), abs(angle % 10));
953 break;
956 case OSD_MAIN_BATT_USAGE:
958 // Set length of indicator bar
959 #define MAIN_BATT_USAGE_STEPS 11 // Use an odd number so the bar can be centered.
961 // Calculate constrained value
962 const float value = constrain(batteryConfig()->batteryCapacity - getMAhDrawn(), 0, batteryConfig()->batteryCapacity);
964 // Calculate mAh used progress
965 const uint8_t mAhUsedProgress = ceilf((value / (batteryConfig()->batteryCapacity / MAIN_BATT_USAGE_STEPS)));
967 // Create empty battery indicator bar
968 buff[0] = SYM_PB_START;
969 for (int i = 1; i <= MAIN_BATT_USAGE_STEPS; i++) {
970 buff[i] = i <= mAhUsedProgress ? SYM_PB_FULL : SYM_PB_EMPTY;
972 buff[MAIN_BATT_USAGE_STEPS + 1] = SYM_PB_CLOSE;
973 if (mAhUsedProgress > 0 && mAhUsedProgress < MAIN_BATT_USAGE_STEPS) {
974 buff[1 + mAhUsedProgress] = SYM_PB_END;
976 buff[MAIN_BATT_USAGE_STEPS+2] = '\0';
977 break;
980 case OSD_DISARMED:
981 if (!ARMING_FLAG(ARMED)) {
982 tfp_sprintf(buff, "DISARMED");
983 } else {
984 if (!lastArmState) { // previously disarmed - blank out the message one time
985 tfp_sprintf(buff, " ");
988 break;
990 case OSD_NUMERICAL_HEADING:
992 const int heading = DECIDEGREES_TO_DEGREES(attitude.values.yaw);
993 tfp_sprintf(buff, "%c%03d", osdGetDirectionSymbolFromHeading(heading), heading);
994 break;
996 #ifdef USE_VARIO
997 case OSD_NUMERICAL_VARIO:
999 const int verticalSpeed = osdGetMetersToSelectedUnit(getEstimatedVario());
1000 const char directionSymbol = verticalSpeed < 0 ? SYM_ARROW_SOUTH : SYM_ARROW_NORTH;
1001 tfp_sprintf(buff, "%c%01d.%01d", directionSymbol, abs(verticalSpeed / 100), abs((verticalSpeed % 100) / 10));
1002 break;
1004 #endif
1006 #ifdef USE_ESC_SENSOR
1007 case OSD_ESC_TMP:
1008 if (featureIsEnabled(FEATURE_ESC_SENSOR)) {
1009 tfp_sprintf(buff, "%3d%c", osdConvertTemperatureToSelectedUnit(escDataCombined->temperature * 10) / 10, osdGetTemperatureSymbolForSelectedUnit());
1011 break;
1013 case OSD_ESC_RPM:
1014 if (featureIsEnabled(FEATURE_ESC_SENSOR)) {
1015 tfp_sprintf(buff, "%5d", escDataCombined == NULL ? 0 : calcEscRpm(escDataCombined->rpm));
1017 break;
1018 #endif
1020 #ifdef USE_RTC_TIME
1021 case OSD_RTC_DATETIME:
1022 osdFormatRtcDateTime(&buff[0]);
1023 break;
1024 #endif
1026 #ifdef USE_OSD_ADJUSTMENTS
1027 case OSD_ADJUSTMENT_RANGE:
1028 if (getAdjustmentsRangeName()) {
1029 tfp_sprintf(buff, "%s: %3d", getAdjustmentsRangeName(), getAdjustmentsRangeValue());
1031 break;
1032 #endif
1034 #ifdef USE_ADC_INTERNAL
1035 case OSD_CORE_TEMPERATURE:
1036 tfp_sprintf(buff, "%3d%c", osdConvertTemperatureToSelectedUnit(getCoreTemperatureCelsius() * 10) / 10, osdGetTemperatureSymbolForSelectedUnit());
1037 break;
1038 #endif
1040 #ifdef USE_BLACKBOX
1041 case OSD_LOG_STATUS:
1042 if (!isBlackboxDeviceWorking()) {
1043 tfp_sprintf(buff, "L-");
1044 } else if (isBlackboxDeviceFull()) {
1045 tfp_sprintf(buff, "L>");
1046 } else {
1047 tfp_sprintf(buff, "L%d", blackboxGetLogNumber());
1049 break;
1050 #endif
1052 default:
1053 return false;
1056 displayWrite(osdDisplayPort, elemPosX, elemPosY, buff);
1058 return true;
1061 static void osdDrawElements(void)
1063 displayClearScreen(osdDisplayPort);
1065 // Hide OSD when OSDSW mode is active
1066 if (IS_RC_MODE_ACTIVE(BOXOSD)) {
1067 return;
1070 if (sensors(SENSOR_ACC)) {
1071 osdGForce = 0.0f;
1072 for (int axis = 0; axis < XYZ_AXIS_COUNT; axis++) {
1073 const float a = accAverage[axis];
1074 osdGForce += a * a;
1076 osdGForce = sqrtf(osdGForce) * acc.dev.acc_1G_rec;
1077 osdDrawSingleElement(OSD_ARTIFICIAL_HORIZON);
1078 osdDrawSingleElement(OSD_G_FORCE);
1082 for (unsigned i = 0; i < sizeof(osdElementDisplayOrder); i++) {
1083 osdDrawSingleElement(osdElementDisplayOrder[i]);
1086 #ifdef USE_GPS
1087 if (sensors(SENSOR_GPS)) {
1088 osdDrawSingleElement(OSD_GPS_SATS);
1089 osdDrawSingleElement(OSD_GPS_SPEED);
1090 osdDrawSingleElement(OSD_GPS_LAT);
1091 osdDrawSingleElement(OSD_GPS_LON);
1092 osdDrawSingleElement(OSD_HOME_DIST);
1093 osdDrawSingleElement(OSD_HOME_DIR);
1095 #endif // GPS
1097 #ifdef USE_ESC_SENSOR
1098 if (featureIsEnabled(FEATURE_ESC_SENSOR)) {
1099 osdDrawSingleElement(OSD_ESC_TMP);
1100 osdDrawSingleElement(OSD_ESC_RPM);
1102 #endif
1104 #ifdef USE_BLACKBOX
1105 if (IS_RC_MODE_ACTIVE(BOXBLACKBOX)) {
1106 osdDrawSingleElement(OSD_LOG_STATUS);
1108 #endif
1111 void pgResetFn_osdConfig(osdConfig_t *osdConfig)
1113 // Position elements near centre of screen and disabled by default
1114 for (int i = 0; i < OSD_ITEM_COUNT; i++) {
1115 osdConfig->item_pos[i] = OSD_POS(10, 7);
1118 // Always enable warnings elements by default
1119 osdConfig->item_pos[OSD_WARNINGS] = OSD_POS(9, 10) | VISIBLE_FLAG;
1121 // Default to old fixed positions for these elements
1122 osdConfig->item_pos[OSD_CROSSHAIRS] = OSD_POS(13, 6);
1123 osdConfig->item_pos[OSD_ARTIFICIAL_HORIZON] = OSD_POS(14, 2);
1124 osdConfig->item_pos[OSD_HORIZON_SIDEBARS] = OSD_POS(14, 6);
1126 // Enable the default stats
1127 osdConfig->enabled_stats = 0; // reset all to off and enable only a few initially
1128 osdStatSetState(OSD_STAT_MAX_SPEED, true);
1129 osdStatSetState(OSD_STAT_MIN_BATTERY, true);
1130 osdStatSetState(OSD_STAT_MIN_RSSI, true);
1131 osdStatSetState(OSD_STAT_MAX_CURRENT, true);
1132 osdStatSetState(OSD_STAT_USED_MAH, true);
1133 osdStatSetState(OSD_STAT_BLACKBOX, true);
1134 osdStatSetState(OSD_STAT_BLACKBOX_NUMBER, true);
1135 osdStatSetState(OSD_STAT_TIMER_2, true);
1137 osdConfig->units = OSD_UNIT_METRIC;
1139 // Enable all warnings by default
1140 for (int i=0; i < OSD_WARNING_COUNT; i++) {
1141 osdWarnSetState(i, true);
1144 osdConfig->timers[OSD_TIMER_1] = OSD_TIMER(OSD_TIMER_SRC_ON, OSD_TIMER_PREC_SECOND, 10);
1145 osdConfig->timers[OSD_TIMER_2] = OSD_TIMER(OSD_TIMER_SRC_TOTAL_ARMED, OSD_TIMER_PREC_SECOND, 10);
1147 osdConfig->rssi_alarm = 20;
1148 osdConfig->cap_alarm = 2200;
1149 osdConfig->alt_alarm = 100; // meters or feet depend on configuration
1150 osdConfig->esc_temp_alarm = ESC_TEMP_ALARM_OFF; // off by default
1151 osdConfig->esc_rpm_alarm = ESC_RPM_ALARM_OFF; // off by default
1152 osdConfig->esc_current_alarm = ESC_CURRENT_ALARM_OFF; // off by default
1153 osdConfig->core_temp_alarm = 70; // a temperature above 70C should produce a warning, lockups have been reported above 80C
1155 osdConfig->ahMaxPitch = 20; // 20 degrees
1156 osdConfig->ahMaxRoll = 40; // 40 degrees
1159 static void osdDrawLogo(int x, int y)
1161 // display logo and help
1162 int fontOffset = 160;
1163 for (int row = 0; row < 4; row++) {
1164 for (int column = 0; column < 24; column++) {
1165 if (fontOffset <= SYM_END_OF_FONT)
1166 displayWriteChar(osdDisplayPort, x + column, y + row, fontOffset++);
1171 void osdInit(displayPort_t *osdDisplayPortToUse)
1173 if (!osdDisplayPortToUse) {
1174 return;
1177 STATIC_ASSERT(OSD_POS_MAX == OSD_POS(31,31), OSD_POS_MAX_incorrect);
1179 osdDisplayPort = osdDisplayPortToUse;
1180 #ifdef USE_CMS
1181 cmsDisplayPortRegister(osdDisplayPort);
1182 #endif
1184 armState = ARMING_FLAG(ARMED);
1186 memset(blinkBits, 0, sizeof(blinkBits));
1188 displayClearScreen(osdDisplayPort);
1190 osdDrawLogo(3, 1);
1192 char string_buffer[30];
1193 tfp_sprintf(string_buffer, "V%s", FC_VERSION_STRING);
1194 displayWrite(osdDisplayPort, 20, 6, string_buffer);
1195 #ifdef USE_CMS
1196 displayWrite(osdDisplayPort, 7, 8, CMS_STARTUP_HELP_TEXT1);
1197 displayWrite(osdDisplayPort, 11, 9, CMS_STARTUP_HELP_TEXT2);
1198 displayWrite(osdDisplayPort, 11, 10, CMS_STARTUP_HELP_TEXT3);
1199 #endif
1201 #ifdef USE_RTC_TIME
1202 char dateTimeBuffer[FORMATTED_DATE_TIME_BUFSIZE];
1203 if (osdFormatRtcDateTime(&dateTimeBuffer[0])) {
1204 displayWrite(osdDisplayPort, 5, 12, dateTimeBuffer);
1206 #endif
1208 displayResync(osdDisplayPort);
1210 resumeRefreshAt = micros() + (4 * REFRESH_1S);
1213 bool osdInitialized(void)
1215 return osdDisplayPort;
1218 void osdUpdateAlarms(void)
1220 // This is overdone?
1222 int32_t alt = osdGetMetersToSelectedUnit(getEstimatedAltitudeCm()) / 100;
1224 if (getRssiPercent() < osdConfig()->rssi_alarm) {
1225 SET_BLINK(OSD_RSSI_VALUE);
1226 } else {
1227 CLR_BLINK(OSD_RSSI_VALUE);
1230 // Determine if the OSD_WARNINGS should blink
1231 if (getBatteryState() != BATTERY_OK
1232 && (osdWarnGetState(OSD_WARNING_BATTERY_CRITICAL) || osdWarnGetState(OSD_WARNING_BATTERY_WARNING))
1233 #ifdef USE_DSHOT
1234 && (!isTryingToArm())
1235 #endif
1237 SET_BLINK(OSD_WARNINGS);
1238 } else {
1239 CLR_BLINK(OSD_WARNINGS);
1242 if (getBatteryState() == BATTERY_OK) {
1243 CLR_BLINK(OSD_MAIN_BATT_VOLTAGE);
1244 CLR_BLINK(OSD_AVG_CELL_VOLTAGE);
1245 } else {
1246 SET_BLINK(OSD_MAIN_BATT_VOLTAGE);
1247 SET_BLINK(OSD_AVG_CELL_VOLTAGE);
1250 if (STATE(GPS_FIX) == 0) {
1251 SET_BLINK(OSD_GPS_SATS);
1252 } else {
1253 CLR_BLINK(OSD_GPS_SATS);
1256 for (int i = 0; i < OSD_TIMER_COUNT; i++) {
1257 const uint16_t timer = osdConfig()->timers[i];
1258 const timeUs_t time = osdGetTimerValue(OSD_TIMER_SRC(timer));
1259 const timeUs_t alarmTime = OSD_TIMER_ALARM(timer) * 60000000; // convert from minutes to us
1260 if (alarmTime != 0 && time >= alarmTime) {
1261 SET_BLINK(OSD_ITEM_TIMER_1 + i);
1262 } else {
1263 CLR_BLINK(OSD_ITEM_TIMER_1 + i);
1267 if (getMAhDrawn() >= osdConfig()->cap_alarm) {
1268 SET_BLINK(OSD_MAH_DRAWN);
1269 SET_BLINK(OSD_MAIN_BATT_USAGE);
1270 SET_BLINK(OSD_REMAINING_TIME_ESTIMATE);
1271 } else {
1272 CLR_BLINK(OSD_MAH_DRAWN);
1273 CLR_BLINK(OSD_MAIN_BATT_USAGE);
1274 CLR_BLINK(OSD_REMAINING_TIME_ESTIMATE);
1277 if (alt >= osdConfig()->alt_alarm) {
1278 SET_BLINK(OSD_ALTITUDE);
1279 } else {
1280 CLR_BLINK(OSD_ALTITUDE);
1283 #ifdef USE_ESC_SENSOR
1284 if (featureIsEnabled(FEATURE_ESC_SENSOR)) {
1285 // This works because the combined ESC data contains the maximum temperature seen amongst all ESCs
1286 if (osdConfig()->esc_temp_alarm != ESC_TEMP_ALARM_OFF && escDataCombined->temperature >= osdConfig()->esc_temp_alarm) {
1287 SET_BLINK(OSD_ESC_TMP);
1288 } else {
1289 CLR_BLINK(OSD_ESC_TMP);
1292 #endif
1295 void osdResetAlarms(void)
1297 CLR_BLINK(OSD_RSSI_VALUE);
1298 CLR_BLINK(OSD_MAIN_BATT_VOLTAGE);
1299 CLR_BLINK(OSD_WARNINGS);
1300 CLR_BLINK(OSD_GPS_SATS);
1301 CLR_BLINK(OSD_MAH_DRAWN);
1302 CLR_BLINK(OSD_ALTITUDE);
1303 CLR_BLINK(OSD_AVG_CELL_VOLTAGE);
1304 CLR_BLINK(OSD_MAIN_BATT_USAGE);
1305 CLR_BLINK(OSD_ITEM_TIMER_1);
1306 CLR_BLINK(OSD_ITEM_TIMER_2);
1307 CLR_BLINK(OSD_REMAINING_TIME_ESTIMATE);
1308 CLR_BLINK(OSD_ESC_TMP);
1311 static void osdResetStats(void)
1313 stats.max_current = 0;
1314 stats.max_speed = 0;
1315 stats.min_voltage = 500;
1316 stats.min_rssi = 99;
1317 stats.max_altitude = 0;
1318 stats.max_distance = 0;
1319 stats.armed_time = 0;
1320 stats.max_g_force = 0;
1323 static void osdUpdateStats(void)
1325 int16_t value = 0;
1326 #ifdef USE_GPS
1327 switch (osdConfig()->units) {
1328 case OSD_UNIT_IMPERIAL:
1329 value = CM_S_TO_MPH(gpsSol.groundSpeed);
1330 break;
1331 default:
1332 value = CM_S_TO_KM_H(gpsSol.groundSpeed);
1333 break;
1335 #endif
1336 if (stats.max_speed < value) {
1337 stats.max_speed = value;
1340 value = getBatteryVoltage();
1341 if (stats.min_voltage > value) {
1342 stats.min_voltage = value;
1345 value = getAmperage() / 100;
1346 if (stats.max_current < value) {
1347 stats.max_current = value;
1350 value = getRssiPercent();
1351 if (stats.min_rssi > value) {
1352 stats.min_rssi = value;
1355 int32_t altitudeCm = getEstimatedAltitudeCm();
1356 if (stats.max_altitude < altitudeCm) {
1357 stats.max_altitude = altitudeCm;
1360 if (stats.max_g_force < osdGForce) {
1361 stats.max_g_force = osdGForce;
1364 #ifdef USE_GPS
1365 if (STATE(GPS_FIX) && STATE(GPS_FIX_HOME)) {
1366 value = GPS_distanceToHome;
1368 if (stats.max_distance < GPS_distanceToHome) {
1369 stats.max_distance = GPS_distanceToHome;
1372 #endif
1375 #ifdef USE_BLACKBOX
1377 static void osdGetBlackboxStatusString(char * buff)
1379 bool storageDeviceIsWorking = isBlackboxDeviceWorking();
1380 uint32_t storageUsed = 0;
1381 uint32_t storageTotal = 0;
1383 switch (blackboxConfig()->device) {
1384 #ifdef USE_SDCARD
1385 case BLACKBOX_DEVICE_SDCARD:
1386 if (storageDeviceIsWorking) {
1387 storageTotal = sdcard_getMetadata()->numBlocks / 2000;
1388 storageUsed = storageTotal - (afatfs_getContiguousFreeSpace() / 1024000);
1390 break;
1391 #endif
1393 #ifdef USE_FLASHFS
1394 case BLACKBOX_DEVICE_FLASH:
1395 if (storageDeviceIsWorking) {
1396 const flashGeometry_t *geometry = flashfsGetGeometry();
1397 storageTotal = geometry->totalSize / 1024;
1398 storageUsed = flashfsGetOffset() / 1024;
1400 break;
1401 #endif
1403 default:
1404 break;
1407 if (storageDeviceIsWorking) {
1408 const uint16_t storageUsedPercent = (storageUsed * 100) / storageTotal;
1409 tfp_sprintf(buff, "%d%%", storageUsedPercent);
1410 } else {
1411 tfp_sprintf(buff, "FAULT");
1414 #endif
1416 static void osdDisplayStatisticLabel(uint8_t y, const char * text, const char * value)
1418 displayWrite(osdDisplayPort, 2, y, text);
1419 displayWrite(osdDisplayPort, 20, y, ":");
1420 displayWrite(osdDisplayPort, 22, y, value);
1424 * Test if there's some stat enabled
1426 static bool isSomeStatEnabled(void)
1428 return (osdConfig()->enabled_stats != 0);
1431 // *** IMPORTANT ***
1432 // The order of the OSD stats as displayed on-screen must match the osd_stats_e enumeration.
1433 // This is because the fields are presented in the configurator in the order of the enumeration
1434 // and we want the configuration order to match the on-screen display order. If you change the
1435 // display order you *must* update the osd_stats_e enumeration to match. Additionally the
1436 // changes to the stats display order *must* be implemented in the configurator otherwise the
1437 // stats selections will not be populated correctly and the settings will become corrupted.
1439 static void osdShowStats(uint16_t endBatteryVoltage)
1441 uint8_t top = 2;
1442 char buff[OSD_ELEMENT_BUFFER_LENGTH];
1444 displayClearScreen(osdDisplayPort);
1445 displayWrite(osdDisplayPort, 2, top++, " --- STATS ---");
1447 if (osdStatGetState(OSD_STAT_RTC_DATE_TIME)) {
1448 bool success = false;
1449 #ifdef USE_RTC_TIME
1450 success = osdFormatRtcDateTime(&buff[0]);
1451 #endif
1452 if (!success) {
1453 tfp_sprintf(buff, "NO RTC");
1456 displayWrite(osdDisplayPort, 2, top++, buff);
1459 if (osdStatGetState(OSD_STAT_TIMER_1)) {
1460 osdFormatTimer(buff, false, (OSD_TIMER_SRC(osdConfig()->timers[OSD_TIMER_1]) == OSD_TIMER_SRC_ON ? false : true), OSD_TIMER_1);
1461 osdDisplayStatisticLabel(top++, osdTimerSourceNames[OSD_TIMER_SRC(osdConfig()->timers[OSD_TIMER_1])], buff);
1464 if (osdStatGetState(OSD_STAT_TIMER_2)) {
1465 osdFormatTimer(buff, false, (OSD_TIMER_SRC(osdConfig()->timers[OSD_TIMER_2]) == OSD_TIMER_SRC_ON ? false : true), OSD_TIMER_2);
1466 osdDisplayStatisticLabel(top++, osdTimerSourceNames[OSD_TIMER_SRC(osdConfig()->timers[OSD_TIMER_2])], buff);
1469 if (osdStatGetState(OSD_STAT_MAX_SPEED) && STATE(GPS_FIX)) {
1470 itoa(stats.max_speed, buff, 10);
1471 osdDisplayStatisticLabel(top++, "MAX SPEED", buff);
1474 if (osdStatGetState(OSD_STAT_MAX_DISTANCE)) {
1475 tfp_sprintf(buff, "%d%c", osdGetMetersToSelectedUnit(stats.max_distance), osdGetMetersToSelectedUnitSymbol());
1476 osdDisplayStatisticLabel(top++, "MAX DISTANCE", buff);
1479 if (osdStatGetState(OSD_STAT_MIN_BATTERY)) {
1480 tfp_sprintf(buff, "%d.%1d%c", stats.min_voltage / 10, stats.min_voltage % 10, SYM_VOLT);
1481 osdDisplayStatisticLabel(top++, "MIN BATTERY", buff);
1484 if (osdStatGetState(OSD_STAT_END_BATTERY)) {
1485 tfp_sprintf(buff, "%d.%1d%c", endBatteryVoltage / 10, endBatteryVoltage % 10, SYM_VOLT);
1486 osdDisplayStatisticLabel(top++, "END BATTERY", buff);
1489 if (osdStatGetState(OSD_STAT_BATTERY)) {
1490 tfp_sprintf(buff, "%d.%1d%c", getBatteryVoltage() / 10, getBatteryVoltage() % 10, SYM_VOLT);
1491 osdDisplayStatisticLabel(top++, "BATTERY", buff);
1494 if (osdStatGetState(OSD_STAT_MIN_RSSI)) {
1495 itoa(stats.min_rssi, buff, 10);
1496 strcat(buff, "%");
1497 osdDisplayStatisticLabel(top++, "MIN RSSI", buff);
1500 if (batteryConfig()->currentMeterSource != CURRENT_METER_NONE) {
1501 if (osdStatGetState(OSD_STAT_MAX_CURRENT)) {
1502 itoa(stats.max_current, buff, 10);
1503 strcat(buff, "A");
1504 osdDisplayStatisticLabel(top++, "MAX CURRENT", buff);
1507 if (osdStatGetState(OSD_STAT_USED_MAH)) {
1508 tfp_sprintf(buff, "%d%c", getMAhDrawn(), SYM_MAH);
1509 osdDisplayStatisticLabel(top++, "USED MAH", buff);
1513 if (osdStatGetState(OSD_STAT_MAX_ALTITUDE)) {
1514 osdFormatAltitudeString(buff, stats.max_altitude);
1515 osdDisplayStatisticLabel(top++, "MAX ALTITUDE", buff);
1518 #ifdef USE_BLACKBOX
1519 if (osdStatGetState(OSD_STAT_BLACKBOX) && blackboxConfig()->device && blackboxConfig()->device != BLACKBOX_DEVICE_SERIAL) {
1520 osdGetBlackboxStatusString(buff);
1521 osdDisplayStatisticLabel(top++, "BLACKBOX", buff);
1524 if (osdStatGetState(OSD_STAT_BLACKBOX_NUMBER) && blackboxConfig()->device && blackboxConfig()->device != BLACKBOX_DEVICE_SERIAL) {
1525 itoa(blackboxGetLogNumber(), buff, 10);
1526 osdDisplayStatisticLabel(top++, "BB LOG NUM", buff);
1528 #endif
1530 if (osdStatGetState(OSD_STAT_MAX_G_FORCE)) {
1531 tfp_sprintf(buff, "%01d.%01dG", (int)stats.max_g_force, (int)(stats.max_g_force * 10) % 10);
1532 osdDisplayStatisticLabel(top++, "MAX G-FORCE", buff);
1537 static void osdShowArmed(void)
1539 displayClearScreen(osdDisplayPort);
1540 displayWrite(osdDisplayPort, 12, 7, "ARMED");
1543 STATIC_UNIT_TESTED void osdRefresh(timeUs_t currentTimeUs)
1545 static timeUs_t lastTimeUs = 0;
1546 static bool osdStatsEnabled = false;
1547 static bool osdStatsVisible = false;
1548 static timeUs_t osdStatsRefreshTimeUs;
1549 static uint16_t endBatteryVoltage;
1551 // detect arm/disarm
1552 if (armState != ARMING_FLAG(ARMED)) {
1553 if (ARMING_FLAG(ARMED)) {
1554 osdStatsEnabled = false;
1555 osdStatsVisible = false;
1556 osdResetStats();
1557 osdShowArmed();
1558 resumeRefreshAt = currentTimeUs + (REFRESH_1S / 2);
1559 } else if (isSomeStatEnabled()
1560 && (!(getArmingDisableFlags() & ARMING_DISABLED_RUNAWAY_TAKEOFF)
1561 || !VISIBLE(osdConfig()->item_pos[OSD_WARNINGS]))) { // suppress stats if runaway takeoff triggered disarm and WARNINGS element is visible
1562 osdStatsEnabled = true;
1563 resumeRefreshAt = currentTimeUs + (60 * REFRESH_1S);
1564 endBatteryVoltage = getBatteryVoltage();
1567 armState = ARMING_FLAG(ARMED);
1571 if (ARMING_FLAG(ARMED)) {
1572 osdUpdateStats();
1573 timeUs_t deltaT = currentTimeUs - lastTimeUs;
1574 flyTime += deltaT;
1575 stats.armed_time += deltaT;
1576 } else if (osdStatsEnabled) { // handle showing/hiding stats based on OSD disable switch position
1577 if (displayIsGrabbed(osdDisplayPort)) {
1578 osdStatsEnabled = false;
1579 resumeRefreshAt = 0;
1580 stats.armed_time = 0;
1581 } else {
1582 if (IS_RC_MODE_ACTIVE(BOXOSD) && osdStatsVisible) {
1583 osdStatsVisible = false;
1584 displayClearScreen(osdDisplayPort);
1585 } else if (!IS_RC_MODE_ACTIVE(BOXOSD)) {
1586 if (!osdStatsVisible) {
1587 osdStatsVisible = true;
1588 osdStatsRefreshTimeUs = 0;
1590 if (currentTimeUs >= osdStatsRefreshTimeUs) {
1591 osdStatsRefreshTimeUs = currentTimeUs + REFRESH_1S;
1592 osdShowStats(endBatteryVoltage);
1597 lastTimeUs = currentTimeUs;
1599 if (resumeRefreshAt) {
1600 if (cmp32(currentTimeUs, resumeRefreshAt) < 0) {
1601 // in timeout period, check sticks for activity to resume display.
1602 if (IS_HI(THROTTLE) || IS_HI(PITCH)) {
1603 resumeRefreshAt = currentTimeUs;
1605 displayHeartbeat(osdDisplayPort);
1606 return;
1607 } else {
1608 displayClearScreen(osdDisplayPort);
1609 resumeRefreshAt = 0;
1610 osdStatsEnabled = false;
1611 stats.armed_time = 0;
1615 blinkState = (currentTimeUs / 200000) % 2;
1617 #ifdef USE_ESC_SENSOR
1618 if (featureIsEnabled(FEATURE_ESC_SENSOR)) {
1619 escDataCombined = getEscSensorData(ESC_SENSOR_COMBINED);
1621 #endif
1623 #ifdef USE_CMS
1624 if (!displayIsGrabbed(osdDisplayPort)) {
1625 osdUpdateAlarms();
1626 osdDrawElements();
1627 displayHeartbeat(osdDisplayPort);
1628 #ifdef OSD_CALLS_CMS
1629 } else {
1630 cmsUpdate(currentTimeUs);
1631 #endif
1633 #endif
1634 lastArmState = ARMING_FLAG(ARMED);
1638 * Called periodically by the scheduler
1640 void osdUpdate(timeUs_t currentTimeUs)
1642 static uint32_t counter = 0;
1644 if (isBeeperOn()) {
1645 showVisualBeeper = true;
1648 #ifdef MAX7456_DMA_CHANNEL_TX
1649 // don't touch buffers if DMA transaction is in progress
1650 if (displayIsTransferInProgress(osdDisplayPort)) {
1651 return;
1653 #endif // MAX7456_DMA_CHANNEL_TX
1655 #ifdef USE_SLOW_MSP_DISPLAYPORT_RATE_WHEN_UNARMED
1656 static uint32_t idlecounter = 0;
1657 if (!ARMING_FLAG(ARMED)) {
1658 if (idlecounter++ % 4 != 0) {
1659 return;
1662 #endif
1664 // redraw values in buffer
1665 #ifdef USE_MAX7456
1666 #define DRAW_FREQ_DENOM 5
1667 #else
1668 #define DRAW_FREQ_DENOM 10 // MWOSD @ 115200 baud (
1669 #endif
1670 #define STATS_FREQ_DENOM 50
1672 if (counter % DRAW_FREQ_DENOM == 0) {
1673 osdRefresh(currentTimeUs);
1674 showVisualBeeper = false;
1675 } else {
1676 // rest of time redraw screen 10 chars per idle so it doesn't lock the main idle
1677 displayDrawScreen(osdDisplayPort);
1679 ++counter;
1681 #ifdef USE_CMS
1682 // do not allow ARM if we are in menu
1683 if (displayIsGrabbed(osdDisplayPort)) {
1684 setArmingDisabled(ARMING_DISABLED_OSD_MENU);
1685 } else {
1686 unsetArmingDisabled(ARMING_DISABLED_OSD_MENU);
1688 #endif
1691 #endif // USE_OSD