New SPI API supporting DMA
[betaflight.git] / src / main / osd / osd.h
blobd6c1b2c944d46f6b1921d1352fc8272dc191a2d2
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_TASK_FREQUENCY_MIN 30
53 #define OSD_TASK_FREQUENCY_MAX 300
54 #define OSD_TASK_FREQUENCY_DEFAULT 60
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 0x3FF
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_XY_MASK ((1 << OSD_POSITION_BITS) - 1)
76 #define OSD_TYPE_MASK 0xC000 // bits 14-15
77 #define OSD_POS(x,y) ((x & OSD_POSITION_XY_MASK) | ((y & OSD_POSITION_XY_MASK) << OSD_POSITION_BITS))
78 #define OSD_X(x) (x & OSD_POSITION_XY_MASK)
79 #define OSD_Y(x) ((x >> OSD_POSITION_BITS) & OSD_POSITION_XY_MASK)
80 #define OSD_TYPE(x) ((x & OSD_TYPE_MASK) >> 14)
82 // Timer configuration
83 // Stored as 15[alarm:8][precision:4][source:4]0
84 #define OSD_TIMER(src, prec, alarm) ((src & 0x0F) | ((prec & 0x0F) << 4) | ((alarm & 0xFF ) << 8))
85 #define OSD_TIMER_SRC(timer) (timer & 0x0F)
86 #define OSD_TIMER_PRECISION(timer) ((timer >> 4) & 0x0F)
87 #define OSD_TIMER_ALARM(timer) ((timer >> 8) & 0xFF)
89 #ifdef USE_MAX7456
90 #define OSD_DRAW_FREQ_DENOM 5
91 #else
92 // MWOSD @ 115200 baud
93 #define OSD_DRAW_FREQ_DENOM 10
94 #endif
96 // NB: to ensure backwards compatibility, new enum values must be appended at the end but before the OSD_XXXX_COUNT entry.
98 // *** IMPORTANT ***
99 // See the information at the top of osd/osd_elements.c for instructions
100 // on how to add OSD elements.
101 typedef enum {
102 OSD_RSSI_VALUE,
103 OSD_MAIN_BATT_VOLTAGE,
104 OSD_CROSSHAIRS,
105 OSD_ARTIFICIAL_HORIZON,
106 OSD_HORIZON_SIDEBARS,
107 OSD_ITEM_TIMER_1,
108 OSD_ITEM_TIMER_2,
109 OSD_FLYMODE,
110 OSD_CRAFT_NAME,
111 OSD_THROTTLE_POS,
112 OSD_VTX_CHANNEL,
113 OSD_CURRENT_DRAW,
114 OSD_MAH_DRAWN,
115 OSD_GPS_SPEED,
116 OSD_GPS_SATS,
117 OSD_ALTITUDE,
118 OSD_ROLL_PIDS,
119 OSD_PITCH_PIDS,
120 OSD_YAW_PIDS,
121 OSD_POWER,
122 OSD_PIDRATE_PROFILE,
123 OSD_WARNINGS,
124 OSD_AVG_CELL_VOLTAGE,
125 OSD_GPS_LON,
126 OSD_GPS_LAT,
127 OSD_DEBUG,
128 OSD_PITCH_ANGLE,
129 OSD_ROLL_ANGLE,
130 OSD_MAIN_BATT_USAGE,
131 OSD_DISARMED,
132 OSD_HOME_DIR,
133 OSD_HOME_DIST,
134 OSD_NUMERICAL_HEADING,
135 OSD_NUMERICAL_VARIO,
136 OSD_COMPASS_BAR,
137 OSD_ESC_TMP,
138 OSD_ESC_RPM,
139 OSD_REMAINING_TIME_ESTIMATE,
140 OSD_RTC_DATETIME,
141 OSD_ADJUSTMENT_RANGE,
142 OSD_CORE_TEMPERATURE,
143 OSD_ANTI_GRAVITY,
144 OSD_G_FORCE,
145 OSD_MOTOR_DIAG,
146 OSD_LOG_STATUS,
147 OSD_FLIP_ARROW,
148 OSD_LINK_QUALITY,
149 OSD_FLIGHT_DIST,
150 OSD_STICK_OVERLAY_LEFT,
151 OSD_STICK_OVERLAY_RIGHT,
152 OSD_DISPLAY_NAME,
153 OSD_ESC_RPM_FREQ,
154 OSD_RATE_PROFILE_NAME,
155 OSD_PID_PROFILE_NAME,
156 OSD_PROFILE_NAME,
157 OSD_RSSI_DBM_VALUE,
158 OSD_RC_CHANNELS,
159 OSD_CAMERA_FRAME,
160 OSD_EFFICIENCY,
161 OSD_TOTAL_FLIGHTS,
162 OSD_UP_DOWN_REFERENCE,
163 OSD_TX_UPLINK_POWER,
164 OSD_ITEM_COUNT // MUST BE LAST
165 } osd_items_e;
167 // *** IMPORTANT ***
168 // Whenever new elements are added to 'osd_items_e', make sure to increment
169 // the parameter group version for 'osdConfig' in 'osd.c'
171 // *** IMPORTANT ***
172 // DO NOT REORDER THE STATS ENUMERATION. The order here cooresponds to the enabled flag bit position
173 // storage and changing the order will corrupt user settings. Any new stats MUST be added to the end
174 // just before the OSD_STAT_COUNT entry. YOU MUST ALSO add the new stat to the
175 // osdStatsDisplayOrder array in osd.c.
177 // IF YOU WANT TO REORDER THE STATS DISPLAY, then adjust the ordering of the osdStatsDisplayOrder array
178 typedef enum {
179 OSD_STAT_RTC_DATE_TIME,
180 OSD_STAT_TIMER_1,
181 OSD_STAT_TIMER_2,
182 OSD_STAT_MAX_SPEED,
183 OSD_STAT_MAX_DISTANCE,
184 OSD_STAT_MIN_BATTERY,
185 OSD_STAT_END_BATTERY,
186 OSD_STAT_BATTERY,
187 OSD_STAT_MIN_RSSI,
188 OSD_STAT_MAX_CURRENT,
189 OSD_STAT_USED_MAH,
190 OSD_STAT_MAX_ALTITUDE,
191 OSD_STAT_BLACKBOX,
192 OSD_STAT_BLACKBOX_NUMBER,
193 OSD_STAT_MAX_G_FORCE,
194 OSD_STAT_MAX_ESC_TEMP,
195 OSD_STAT_MAX_ESC_RPM,
196 OSD_STAT_MIN_LINK_QUALITY,
197 OSD_STAT_FLIGHT_DISTANCE,
198 OSD_STAT_MAX_FFT,
199 OSD_STAT_TOTAL_FLIGHTS,
200 OSD_STAT_TOTAL_TIME,
201 OSD_STAT_TOTAL_DIST,
202 OSD_STAT_MIN_RSSI_DBM,
203 OSD_STAT_COUNT // MUST BE LAST
204 } osd_stats_e;
206 // Make sure the number of stats do not exceed the available 32bit storage
207 STATIC_ASSERT(OSD_STAT_COUNT <= 32, osdstats_overflow);
209 typedef enum {
210 OSD_TIMER_1,
211 OSD_TIMER_2,
212 OSD_TIMER_COUNT
213 } osd_timer_e;
215 typedef enum {
216 OSD_TIMER_SRC_ON,
217 OSD_TIMER_SRC_TOTAL_ARMED,
218 OSD_TIMER_SRC_LAST_ARMED,
219 OSD_TIMER_SRC_ON_OR_ARMED,
220 OSD_TIMER_SRC_COUNT
221 } osd_timer_source_e;
223 typedef enum {
224 OSD_TIMER_PREC_SECOND,
225 OSD_TIMER_PREC_HUNDREDTHS,
226 OSD_TIMER_PREC_TENTHS,
227 OSD_TIMER_PREC_COUNT
228 } osd_timer_precision_e;
230 typedef enum {
231 OSD_WARNING_ARMING_DISABLE,
232 OSD_WARNING_BATTERY_NOT_FULL,
233 OSD_WARNING_BATTERY_WARNING,
234 OSD_WARNING_BATTERY_CRITICAL,
235 OSD_WARNING_VISUAL_BEEPER,
236 OSD_WARNING_CRASH_FLIP,
237 OSD_WARNING_ESC_FAIL,
238 OSD_WARNING_CORE_TEMPERATURE,
239 OSD_WARNING_RC_SMOOTHING,
240 OSD_WARNING_FAIL_SAFE,
241 OSD_WARNING_LAUNCH_CONTROL,
242 OSD_WARNING_GPS_RESCUE_UNAVAILABLE,
243 OSD_WARNING_GPS_RESCUE_DISABLED,
244 OSD_WARNING_RSSI,
245 OSD_WARNING_LINK_QUALITY,
246 OSD_WARNING_RSSI_DBM,
247 OSD_WARNING_OVER_CAP,
248 OSD_WARNING_COUNT // MUST BE LAST
249 } osdWarningsFlags_e;
251 typedef enum {
252 OSD_DISPLAYPORT_DEVICE_NONE = 0,
253 OSD_DISPLAYPORT_DEVICE_AUTO,
254 OSD_DISPLAYPORT_DEVICE_MAX7456,
255 OSD_DISPLAYPORT_DEVICE_MSP,
256 OSD_DISPLAYPORT_DEVICE_FRSKYOSD,
257 } osdDisplayPortDevice_e;
259 // Make sure the number of warnings do not exceed the available 32bit storage
260 STATIC_ASSERT(OSD_WARNING_COUNT <= 32, osdwarnings_overflow);
262 #define ESC_RPM_ALARM_OFF -1
263 #define ESC_TEMP_ALARM_OFF INT8_MIN
264 #define ESC_CURRENT_ALARM_OFF -1
266 #define OSD_GPS_RESCUE_DISABLED_WARNING_DURATION_US 3000000 // 3 seconds
268 extern const uint16_t osdTimerDefault[OSD_TIMER_COUNT];
269 extern const osd_stats_e osdStatsDisplayOrder[OSD_STAT_COUNT];
271 typedef struct osdConfig_s {
272 // Alarms
273 uint16_t cap_alarm;
274 uint16_t alt_alarm;
275 uint8_t rssi_alarm;
277 uint8_t units;
279 uint16_t timers[OSD_TIMER_COUNT];
280 uint32_t enabledWarnings;
282 uint8_t ahMaxPitch;
283 uint8_t ahMaxRoll;
284 uint32_t enabled_stats;
285 int8_t esc_temp_alarm;
286 int16_t esc_rpm_alarm;
287 int16_t esc_current_alarm;
288 uint8_t core_temp_alarm;
289 uint8_t ahInvert; // invert the artificial horizon
290 uint8_t osdProfileIndex;
291 uint8_t overlay_radio_mode;
292 char profile[OSD_PROFILE_COUNT][OSD_PROFILE_NAME_LENGTH + 1];
293 uint16_t link_quality_alarm;
294 int16_t rssi_dbm_alarm;
295 uint8_t gps_sats_show_hdop;
296 int8_t rcChannels[OSD_RCCHANNELS_COUNT]; // RC channel values to display, -1 if none
297 uint8_t displayPortDevice; // osdDisplayPortDevice_e
298 uint16_t distance_alarm;
299 uint8_t logo_on_arming; // show the logo on arming
300 uint8_t logo_on_arming_duration; // display duration in 0.1s units
301 uint8_t camera_frame_width; // The width of the box for the camera frame element
302 uint8_t camera_frame_height; // The height of the box for the camera frame element
303 uint16_t task_frequency;
304 uint8_t cms_background_type; // For supporting devices, determines whether the CMS background is transparent or opaque
305 uint8_t stat_show_cell_value;
306 } osdConfig_t;
308 PG_DECLARE(osdConfig_t, osdConfig);
310 typedef struct osdElementConfig_s {
311 uint16_t item_pos[OSD_ITEM_COUNT];
312 } osdElementConfig_t;
314 PG_DECLARE(osdElementConfig_t, osdElementConfig);
316 typedef struct statistic_s {
317 timeUs_t armed_time;
318 int16_t max_speed;
319 int16_t min_voltage; // /100
320 uint16_t end_voltage;
321 int16_t max_current; // /10
322 uint8_t min_rssi;
323 int32_t max_altitude;
324 int16_t max_distance;
325 float max_g_force;
326 int16_t max_esc_temp;
327 int32_t max_esc_rpm;
328 uint16_t min_link_quality;
329 int16_t min_rssi_dbm;
330 } statistic_t;
332 extern timeUs_t resumeRefreshAt;
333 extern timeUs_t osdFlyTime;
334 #if defined(USE_ACC)
335 extern float osdGForce;
336 #endif
337 #ifdef USE_ESC_SENSOR
338 extern escSensorData_t *osdEscDataCombined;
339 #endif
341 void osdInit(displayPort_t *osdDisplayPort, osdDisplayPortDevice_e displayPortDevice);
342 void osdUpdate(timeUs_t currentTimeUs);
344 void osdStatSetState(uint8_t statIndex, bool enabled);
345 bool osdStatGetState(uint8_t statIndex);
346 void osdSuppressStats(bool flag);
347 void osdAnalyzeActiveElements(void);
348 void changeOsdProfileIndex(uint8_t profileIndex);
349 uint8_t getCurrentOsdProfileIndex(void);
350 displayPort_t *osdGetDisplayPort(osdDisplayPortDevice_e *displayPortDevice);
352 void osdWarnSetState(uint8_t warningIndex, bool enabled);
353 bool osdWarnGetState(uint8_t warningIndex);
354 bool osdElementVisible(uint16_t value);
355 bool osdGetVisualBeeperState(void);
356 statistic_t *osdGetStats(void);
357 bool osdNeedsAccelerometer(void);
358 int osdPrintFloat(char *buffer, char leadingSymbol, float value, char *formatString, unsigned decimalPlaces, bool round, char trailingSymbol);