Bump workflow action (#13355)
[betaflight.git] / src / main / osd / osd.h
blobded88fb7d4fbda2823200bf0d767151a22154a07
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/>.
21 #pragma once
23 #include "common/time.h"
24 #include "common/unit.h"
26 #include "drivers/display.h"
28 #include "pg/pg.h"
30 #include "sensors/esc_sensor.h"
32 #define OSD_NUM_TIMER_TYPES 4
33 extern const char * const osdTimerSourceNames[OSD_NUM_TIMER_TYPES];
35 #define OSD_ELEMENT_BUFFER_LENGTH 32
37 #define OSD_PROFILE_NAME_LENGTH 16
39 #ifdef USE_OSD_PROFILES
40 #define OSD_PROFILE_COUNT 3
41 #else
42 #define OSD_PROFILE_COUNT 1
43 #endif
45 #define OSD_RCCHANNELS_COUNT 4
47 #define OSD_CAMERA_FRAME_MIN_WIDTH 2
48 #define OSD_CAMERA_FRAME_MAX_WIDTH 30 // Characters per row supportes by MAX7456
49 #define OSD_CAMERA_FRAME_MIN_HEIGHT 2
50 #define OSD_CAMERA_FRAME_MAX_HEIGHT 16 // Rows supported by MAX7456 (PAL)
52 #define OSD_FRAMERATE_MIN_HZ 1
53 #define OSD_FRAMERATE_MAX_HZ 60
54 #define OSD_FRAMERATE_DEFAULT_HZ 12
56 #define OSD_PROFILE_BITS_POS 11
57 #define OSD_PROFILE_MASK (((1 << OSD_PROFILE_COUNT) - 1) << OSD_PROFILE_BITS_POS)
58 #define OSD_POS_MAX 0x7FF
59 #define OSD_POSCFG_MAX UINT16_MAX // element positions now use all 16 bits
60 #define OSD_PROFILE_FLAG(x) (1 << ((x) - 1 + OSD_PROFILE_BITS_POS))
61 #define OSD_PROFILE_1_FLAG OSD_PROFILE_FLAG(1)
64 #ifdef USE_OSD_PROFILES
65 #define VISIBLE(x) osdElementVisible(x)
66 #define VISIBLE_IN_OSD_PROFILE(item, profile) ((item) & ((OSD_PROFILE_1_FLAG) << ((profile)-1)))
67 #else
68 #define VISIBLE(x) ((x) & OSD_PROFILE_MASK)
69 #define VISIBLE_IN_OSD_PROFILE(item, profile) VISIBLE(item)
70 #endif
73 // Character coordinate
74 #define OSD_POSITION_BITS 5 // 5 bits gives a range 0-31
75 #define OSD_POSITION_BIT_XHD 10 // extra bit used to extend X range in a backward compatible manner for HD displays
76 #define OSD_POSITION_XHD_MASK (1 << OSD_POSITION_BIT_XHD)
77 #define OSD_POSITION_XY_MASK ((1 << OSD_POSITION_BITS) - 1)
78 #define OSD_TYPE_MASK 0xC000 // bits 14-15
79 #define OSD_POS(x,y) ((x & OSD_POSITION_XY_MASK) | ((x << (OSD_POSITION_BIT_XHD - OSD_POSITION_BITS)) & OSD_POSITION_XHD_MASK) | \
80 ((y & OSD_POSITION_XY_MASK) << OSD_POSITION_BITS))
81 #define OSD_X(x) ((x & OSD_POSITION_XY_MASK) | ((x & OSD_POSITION_XHD_MASK) >> (OSD_POSITION_BIT_XHD - OSD_POSITION_BITS)))
82 #define OSD_Y(x) ((x >> OSD_POSITION_BITS) & OSD_POSITION_XY_MASK)
83 #define OSD_TYPE(x) ((x & OSD_TYPE_MASK) >> 14)
85 #define OSD_SD_COLS VIDEO_COLUMNS_SD
86 #define OSD_SD_ROWS VIDEO_LINES_PAL
88 // Default HD OSD canvas size to be applied unless the goggles announce otherwise
89 #define OSD_HD_COLS 53
90 #define OSD_HD_ROWS 20
92 // Timer configuration
93 // Stored as 15[alarm:8][precision:4][source:4]0
94 #define OSD_TIMER(src, prec, alarm) ((src & 0x0F) | ((prec & 0x0F) << 4) | ((alarm & 0xFF ) << 8))
95 #define OSD_TIMER_SRC(timer) (timer & 0x0F)
96 #define OSD_TIMER_PRECISION(timer) ((timer >> 4) & 0x0F)
97 #define OSD_TIMER_ALARM(timer) ((timer >> 8) & 0xFF)
99 #ifdef USE_MAX7456
100 #define OSD_DRAW_FREQ_DENOM 5
101 #else
102 // MWOSD @ 115200 baud
103 #define OSD_DRAW_FREQ_DENOM 10
104 #endif
106 // NB: to ensure backwards compatibility, new enum values must be appended at the end but before the OSD_XXXX_COUNT entry.
108 // *** IMPORTANT ***
109 // See the information at the top of osd/osd_elements.c for instructions
110 // on how to add OSD elements.
111 typedef enum {
112 OSD_RSSI_VALUE,
113 OSD_MAIN_BATT_VOLTAGE,
114 OSD_CROSSHAIRS,
115 OSD_ARTIFICIAL_HORIZON,
116 OSD_HORIZON_SIDEBARS,
117 OSD_ITEM_TIMER_1,
118 OSD_ITEM_TIMER_2,
119 OSD_FLYMODE,
120 OSD_CRAFT_NAME,
121 OSD_THROTTLE_POS,
122 OSD_VTX_CHANNEL,
123 OSD_CURRENT_DRAW,
124 OSD_MAH_DRAWN,
125 OSD_GPS_SPEED,
126 OSD_GPS_SATS,
127 OSD_ALTITUDE,
128 OSD_ROLL_PIDS,
129 OSD_PITCH_PIDS,
130 OSD_YAW_PIDS,
131 OSD_POWER,
132 OSD_PIDRATE_PROFILE,
133 OSD_WARNINGS,
134 OSD_AVG_CELL_VOLTAGE,
135 OSD_GPS_LON,
136 OSD_GPS_LAT,
137 OSD_DEBUG,
138 OSD_PITCH_ANGLE,
139 OSD_ROLL_ANGLE,
140 OSD_MAIN_BATT_USAGE,
141 OSD_DISARMED,
142 OSD_HOME_DIR,
143 OSD_HOME_DIST,
144 OSD_NUMERICAL_HEADING,
145 OSD_NUMERICAL_VARIO,
146 OSD_COMPASS_BAR,
147 OSD_ESC_TMP,
148 OSD_ESC_RPM,
149 OSD_REMAINING_TIME_ESTIMATE,
150 OSD_RTC_DATETIME,
151 OSD_ADJUSTMENT_RANGE,
152 OSD_CORE_TEMPERATURE,
153 OSD_ANTI_GRAVITY,
154 OSD_G_FORCE,
155 OSD_MOTOR_DIAG,
156 OSD_LOG_STATUS,
157 OSD_FLIP_ARROW,
158 OSD_LINK_QUALITY,
159 OSD_FLIGHT_DIST,
160 OSD_STICK_OVERLAY_LEFT,
161 OSD_STICK_OVERLAY_RIGHT,
162 OSD_PILOT_NAME,
163 OSD_ESC_RPM_FREQ,
164 OSD_RATE_PROFILE_NAME,
165 OSD_PID_PROFILE_NAME,
166 OSD_PROFILE_NAME,
167 OSD_RSSI_DBM_VALUE,
168 OSD_RC_CHANNELS,
169 OSD_CAMERA_FRAME,
170 OSD_EFFICIENCY,
171 OSD_TOTAL_FLIGHTS,
172 OSD_UP_DOWN_REFERENCE,
173 OSD_TX_UPLINK_POWER,
174 OSD_WATT_HOURS_DRAWN,
175 OSD_AUX_VALUE,
176 OSD_READY_MODE,
177 OSD_RSNR_VALUE,
178 OSD_SYS_GOGGLE_VOLTAGE,
179 OSD_SYS_VTX_VOLTAGE,
180 OSD_SYS_BITRATE,
181 OSD_SYS_DELAY,
182 OSD_SYS_DISTANCE,
183 OSD_SYS_LQ,
184 OSD_SYS_GOGGLE_DVR,
185 OSD_SYS_VTX_DVR,
186 OSD_SYS_WARNINGS,
187 OSD_SYS_VTX_TEMP,
188 OSD_SYS_FAN_SPEED,
189 OSD_GPS_LAP_TIME_CURRENT,
190 OSD_GPS_LAP_TIME_PREVIOUS,
191 OSD_GPS_LAP_TIME_BEST3,
192 OSD_ITEM_COUNT // MUST BE LAST
193 } osd_items_e;
195 // *** IMPORTANT ***
196 // Whenever new elements are added to 'osd_items_e', make sure to increment
197 // the parameter group version for 'osdConfig' in 'osd.c'
199 // *** IMPORTANT ***
200 // DO NOT REORDER THE STATS ENUMERATION. The order here cooresponds to the enabled flag bit position
201 // storage and changing the order will corrupt user settings. Any new stats MUST be added to the end
202 // just before the OSD_STAT_COUNT entry. YOU MUST ALSO add the new stat to the
203 // osdStatsDisplayOrder array in osd.c.
205 // IF YOU WANT TO REORDER THE STATS DISPLAY, then adjust the ordering of the osdStatsDisplayOrder array
206 typedef enum {
207 OSD_STAT_RTC_DATE_TIME,
208 OSD_STAT_TIMER_1,
209 OSD_STAT_TIMER_2,
210 OSD_STAT_MAX_SPEED,
211 OSD_STAT_MAX_DISTANCE,
212 OSD_STAT_MIN_BATTERY,
213 OSD_STAT_END_BATTERY,
214 OSD_STAT_BATTERY,
215 OSD_STAT_MIN_RSSI,
216 OSD_STAT_MAX_CURRENT,
217 OSD_STAT_USED_MAH,
218 OSD_STAT_MAX_ALTITUDE,
219 OSD_STAT_BLACKBOX,
220 OSD_STAT_BLACKBOX_NUMBER,
221 OSD_STAT_MAX_G_FORCE,
222 OSD_STAT_MAX_ESC_TEMP,
223 OSD_STAT_MAX_ESC_RPM,
224 OSD_STAT_MIN_LINK_QUALITY,
225 OSD_STAT_FLIGHT_DISTANCE,
226 OSD_STAT_MAX_FFT,
227 OSD_STAT_TOTAL_FLIGHTS,
228 OSD_STAT_TOTAL_TIME,
229 OSD_STAT_TOTAL_DIST,
230 OSD_STAT_MIN_RSSI_DBM,
231 OSD_STAT_WATT_HOURS_DRAWN,
232 OSD_STAT_MIN_RSNR,
233 OSD_STAT_BEST_3_CONSEC_LAPS,
234 OSD_STAT_BEST_LAP,
235 OSD_STAT_FULL_THROTTLE_TIME,
236 OSD_STAT_FULL_THROTTLE_COUNTER,
237 OSD_STAT_AVG_THROTTLE,
238 OSD_STAT_COUNT // MUST BE LAST
239 } osd_stats_e;
241 // Make sure the number of stats do not exceed the available 32bit storage
242 STATIC_ASSERT(OSD_STAT_COUNT <= 32, osdstats_overflow);
244 typedef enum {
245 OSD_TIMER_1,
246 OSD_TIMER_2,
247 OSD_TIMER_COUNT
248 } osd_timer_e;
250 typedef enum {
251 OSD_TIMER_SRC_ON,
252 OSD_TIMER_SRC_TOTAL_ARMED,
253 OSD_TIMER_SRC_LAST_ARMED,
254 OSD_TIMER_SRC_ON_OR_ARMED,
255 OSD_TIMER_SRC_COUNT
256 } osd_timer_source_e;
258 typedef enum {
259 OSD_TIMER_PREC_SECOND,
260 OSD_TIMER_PREC_HUNDREDTHS,
261 OSD_TIMER_PREC_TENTHS,
262 OSD_TIMER_PREC_COUNT
263 } osd_timer_precision_e;
265 typedef enum {
266 OSD_WARNING_ARMING_DISABLE,
267 OSD_WARNING_BATTERY_NOT_FULL,
268 OSD_WARNING_BATTERY_WARNING,
269 OSD_WARNING_BATTERY_CRITICAL,
270 OSD_WARNING_VISUAL_BEEPER,
271 OSD_WARNING_CRASH_FLIP,
272 OSD_WARNING_ESC_FAIL,
273 OSD_WARNING_CORE_TEMPERATURE,
274 OSD_WARNING_RC_SMOOTHING,
275 OSD_WARNING_FAIL_SAFE,
276 OSD_WARNING_LAUNCH_CONTROL,
277 OSD_WARNING_GPS_RESCUE_UNAVAILABLE,
278 OSD_WARNING_GPS_RESCUE_DISABLED,
279 OSD_WARNING_RSSI,
280 OSD_WARNING_LINK_QUALITY,
281 OSD_WARNING_RSSI_DBM,
282 OSD_WARNING_OVER_CAP,
283 OSD_WARNING_RSNR,
284 OSD_WARNING_LOAD,
285 OSD_WARNING_COUNT // MUST BE LAST
286 } osdWarningsFlags_e;
288 typedef enum {
289 OSD_DISPLAYPORT_DEVICE_NONE = 0,
290 OSD_DISPLAYPORT_DEVICE_AUTO,
291 OSD_DISPLAYPORT_DEVICE_MAX7456,
292 OSD_DISPLAYPORT_DEVICE_MSP,
293 OSD_DISPLAYPORT_DEVICE_FRSKYOSD,
294 } osdDisplayPortDevice_e;
296 // Make sure the number of warnings do not exceed the available 32bit storage
297 STATIC_ASSERT(OSD_WARNING_COUNT <= 32, osdwarnings_overflow);
299 #define ESC_RPM_ALARM_OFF -1
300 #define ESC_TEMP_ALARM_OFF 0
301 #define ESC_CURRENT_ALARM_OFF -1
303 #define OSD_GPS_RESCUE_DISABLED_WARNING_DURATION_US 3000000 // 3 seconds
305 extern const uint16_t osdTimerDefault[OSD_TIMER_COUNT];
306 extern const osd_stats_e osdStatsDisplayOrder[OSD_STAT_COUNT];
308 typedef struct osdConfig_s {
309 // Alarms
310 uint16_t cap_alarm;
311 uint16_t alt_alarm;
312 uint8_t rssi_alarm;
314 uint8_t units;
316 uint16_t timers[OSD_TIMER_COUNT];
317 uint32_t enabledWarnings;
319 uint8_t ahMaxPitch;
320 uint8_t ahMaxRoll;
321 uint32_t enabled_stats;
322 uint8_t esc_temp_alarm;
323 int16_t esc_rpm_alarm;
324 int16_t esc_current_alarm;
325 uint8_t core_temp_alarm;
326 uint8_t ahInvert; // invert the artificial horizon
327 uint8_t osdProfileIndex;
328 uint8_t overlay_radio_mode;
329 char profile[OSD_PROFILE_COUNT][OSD_PROFILE_NAME_LENGTH + 1];
330 uint16_t link_quality_alarm;
331 int16_t rssi_dbm_alarm;
332 int16_t rsnr_alarm;
333 uint8_t gps_sats_show_hdop;
334 int8_t rcChannels[OSD_RCCHANNELS_COUNT]; // RC channel values to display, -1 if none
335 uint8_t displayPortDevice; // osdDisplayPortDevice_e
336 uint16_t distance_alarm;
337 uint8_t logo_on_arming; // show the logo on arming
338 uint8_t logo_on_arming_duration; // display duration in 0.1s units
339 uint8_t camera_frame_width; // The width of the box for the camera frame element
340 uint8_t camera_frame_height; // The height of the box for the camera frame element
341 uint16_t framerate_hz;
342 uint8_t cms_background_type; // For supporting devices, determines whether the CMS background is transparent or opaque
343 uint8_t stat_show_cell_value;
344 #ifdef USE_CRAFTNAME_MSGS
345 uint8_t osd_craftname_msgs; // Insert LQ/RSSI-dBm and warnings into CraftName
346 #endif //USE_CRAFTNAME_MSGS
347 uint8_t aux_channel;
348 uint16_t aux_scale;
349 uint8_t aux_symbol;
350 uint8_t canvas_cols; // Canvas dimensions for HD display
351 uint8_t canvas_rows;
352 #ifdef USE_OSD_QUICK_MENU
353 uint8_t osd_use_quick_menu; // use QUICK menu YES/NO
354 #endif // USE_OSD_QUICK_MENU
355 #ifdef USE_SPEC_PREARM_SCREEN
356 uint8_t osd_show_spec_prearm;
357 #endif // USE_SPEC_PREARM_SCREEN
358 } osdConfig_t;
360 PG_DECLARE(osdConfig_t, osdConfig);
362 typedef struct osdElementConfig_s {
363 uint16_t item_pos[OSD_ITEM_COUNT];
364 } osdElementConfig_t;
366 PG_DECLARE(osdElementConfig_t, osdElementConfig);
368 typedef struct statistic_s {
369 timeUs_t armed_time;
370 int16_t max_speed;
371 int16_t min_voltage; // /100
372 uint16_t end_voltage;
373 int16_t max_current; // /10
374 uint8_t min_rssi;
375 int32_t max_altitude;
376 int16_t max_distance;
377 float max_g_force;
378 int16_t max_esc_temp_ix;
379 int16_t max_esc_temp;
380 int32_t max_esc_rpm;
381 uint16_t min_link_quality;
382 int16_t min_rssi_dbm;
383 int16_t min_rsnr;
384 } statistic_t;
386 extern timeUs_t resumeRefreshAt;
387 extern timeUs_t osdFlyTime;
388 #if defined(USE_ACC)
389 extern float osdGForce;
390 #endif
391 #ifdef USE_ESC_SENSOR
392 extern escSensorData_t *osdEscDataCombined;
393 #endif
394 extern uint16_t osdAuxValue;
396 void osdInit(displayPort_t *osdDisplayPort, osdDisplayPortDevice_e displayPortDevice);
397 bool osdUpdateCheck(timeUs_t currentTimeUs, timeDelta_t currentDeltaTimeUs);
398 void osdUpdate(timeUs_t currentTimeUs);
400 void osdStatSetState(uint8_t statIndex, bool enabled);
401 bool osdStatGetState(uint8_t statIndex);
402 void osdSuppressStats(bool flag);
403 void osdAnalyzeActiveElements(void);
404 void changeOsdProfileIndex(uint8_t profileIndex);
405 uint8_t getCurrentOsdProfileIndex(void);
406 displayPort_t *osdGetDisplayPort(osdDisplayPortDevice_e *displayPortDevice);
408 void osdWarnSetState(uint8_t warningIndex, bool enabled);
409 bool osdWarnGetState(uint8_t warningIndex);
410 bool osdElementVisible(uint16_t value);
411 bool osdGetVisualBeeperState(void);
412 void osdSetVisualBeeperState(bool state);
413 statistic_t *osdGetStats(void);
414 bool osdNeedsAccelerometer(void);
415 int osdPrintFloat(char *buffer, char leadingSymbol, float value, char *formatString, unsigned decimalPlaces, bool round, char trailingSymbol);