Some fixes for what looks like merge problems introduced by #9012.
[betaflight.git] / src / main / osd / osd.h
blob218b798bedcb76d2f475b3c8c004b1a00db78132
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"
25 #include "pg/pg.h"
27 #include "sensors/esc_sensor.h"
29 #define OSD_NUM_TIMER_TYPES 4
30 extern const char * const osdTimerSourceNames[OSD_NUM_TIMER_TYPES];
32 #define OSD_ELEMENT_BUFFER_LENGTH 32
34 #define OSD_PROFILE_NAME_LENGTH 16
36 #ifdef USE_OSD_PROFILES
37 #define OSD_PROFILE_COUNT 3
38 #else
39 #define OSD_PROFILE_COUNT 1
40 #endif
42 #define OSD_RCCHANNELS_COUNT 4
44 #define OSD_PROFILE_BITS_POS 11
45 #define OSD_PROFILE_MASK (((1 << OSD_PROFILE_COUNT) - 1) << OSD_PROFILE_BITS_POS)
46 #define OSD_POS_MAX 0x3FF
47 #define OSD_POSCFG_MAX (OSD_PROFILE_MASK | 0x3FF) // For CLI values
48 #define OSD_PROFILE_FLAG(x) (1 << ((x) - 1 + OSD_PROFILE_BITS_POS))
49 #define OSD_PROFILE_1_FLAG OSD_PROFILE_FLAG(1)
52 #ifdef USE_OSD_PROFILES
53 #define VISIBLE(x) osdElementVisible(x)
54 #define VISIBLE_IN_OSD_PROFILE(item, profile) ((item) & ((OSD_PROFILE_1_FLAG) << ((profile)-1)))
55 #else
56 #define VISIBLE(x) ((x) & OSD_PROFILE_MASK)
57 #define VISIBLE_IN_OSD_PROFILE(item, profile) VISIBLE(item)
58 #endif
61 // Character coordinate
62 #define OSD_POSITION_BITS 5 // 5 bits gives a range 0-31
63 #define OSD_POSITION_XY_MASK ((1 << OSD_POSITION_BITS) - 1)
64 #define OSD_POS(x,y) ((x & OSD_POSITION_XY_MASK) | ((y & OSD_POSITION_XY_MASK) << OSD_POSITION_BITS))
65 #define OSD_X(x) (x & OSD_POSITION_XY_MASK)
66 #define OSD_Y(x) ((x >> OSD_POSITION_BITS) & OSD_POSITION_XY_MASK)
68 // Timer configuration
69 // Stored as 15[alarm:8][precision:4][source:4]0
70 #define OSD_TIMER(src, prec, alarm) ((src & 0x0F) | ((prec & 0x0F) << 4) | ((alarm & 0xFF ) << 8))
71 #define OSD_TIMER_SRC(timer) (timer & 0x0F)
72 #define OSD_TIMER_PRECISION(timer) ((timer >> 4) & 0x0F)
73 #define OSD_TIMER_ALARM(timer) ((timer >> 8) & 0xFF)
75 // NB: to ensure backwards compatibility, new enum values must be appended at the end but before the OSD_XXXX_COUNT entry.
77 // *** IMPORTANT ***
78 // See the information at the top of osd/osd_elements.c for instructions
79 // on how to add OSD elements.
80 typedef enum {
81 OSD_RSSI_VALUE,
82 OSD_MAIN_BATT_VOLTAGE,
83 OSD_CROSSHAIRS,
84 OSD_ARTIFICIAL_HORIZON,
85 OSD_HORIZON_SIDEBARS,
86 OSD_ITEM_TIMER_1,
87 OSD_ITEM_TIMER_2,
88 OSD_FLYMODE,
89 OSD_CRAFT_NAME,
90 OSD_THROTTLE_POS,
91 OSD_VTX_CHANNEL,
92 OSD_CURRENT_DRAW,
93 OSD_MAH_DRAWN,
94 OSD_GPS_SPEED,
95 OSD_GPS_SATS,
96 OSD_ALTITUDE,
97 OSD_ROLL_PIDS,
98 OSD_PITCH_PIDS,
99 OSD_YAW_PIDS,
100 OSD_POWER,
101 OSD_PIDRATE_PROFILE,
102 OSD_WARNINGS,
103 OSD_AVG_CELL_VOLTAGE,
104 OSD_GPS_LON,
105 OSD_GPS_LAT,
106 OSD_DEBUG,
107 OSD_PITCH_ANGLE,
108 OSD_ROLL_ANGLE,
109 OSD_MAIN_BATT_USAGE,
110 OSD_DISARMED,
111 OSD_HOME_DIR,
112 OSD_HOME_DIST,
113 OSD_NUMERICAL_HEADING,
114 OSD_NUMERICAL_VARIO,
115 OSD_COMPASS_BAR,
116 OSD_ESC_TMP,
117 OSD_ESC_RPM,
118 OSD_REMAINING_TIME_ESTIMATE,
119 OSD_RTC_DATETIME,
120 OSD_ADJUSTMENT_RANGE,
121 OSD_CORE_TEMPERATURE,
122 OSD_ANTI_GRAVITY,
123 OSD_G_FORCE,
124 OSD_MOTOR_DIAG,
125 OSD_LOG_STATUS,
126 OSD_FLIP_ARROW,
127 OSD_LINK_QUALITY,
128 OSD_FLIGHT_DIST,
129 OSD_STICK_OVERLAY_LEFT,
130 OSD_STICK_OVERLAY_RIGHT,
131 OSD_DISPLAY_NAME,
132 OSD_ESC_RPM_FREQ,
133 OSD_RATE_PROFILE_NAME,
134 OSD_PID_PROFILE_NAME,
135 OSD_PROFILE_NAME,
136 OSD_RSSI_DBM_VALUE,
137 OSD_RC_CHANNELS,
138 OSD_ITEM_COUNT // MUST BE LAST
139 } osd_items_e;
141 // *** IMPORTANT ***
142 // DO NOT REORDER THE STATS ENUMERATION. The order here cooresponds to the enabled flag bit position
143 // storage and changing the order will corrupt user settings. Any new stats MUST be added to the end
144 // just before the OSD_STAT_COUNT entry. YOU MUST ALSO add the new stat to the
145 // osdStatsDisplayOrder array in osd.c.
147 // IF YOU WANT TO REORDER THE STATS DISPLAY, then adjust the ordering of the osdStatsDisplayOrder array
148 typedef enum {
149 OSD_STAT_RTC_DATE_TIME,
150 OSD_STAT_TIMER_1,
151 OSD_STAT_TIMER_2,
152 OSD_STAT_MAX_SPEED,
153 OSD_STAT_MAX_DISTANCE,
154 OSD_STAT_MIN_BATTERY,
155 OSD_STAT_END_BATTERY,
156 OSD_STAT_BATTERY,
157 OSD_STAT_MIN_RSSI,
158 OSD_STAT_MAX_CURRENT,
159 OSD_STAT_USED_MAH,
160 OSD_STAT_MAX_ALTITUDE,
161 OSD_STAT_BLACKBOX,
162 OSD_STAT_BLACKBOX_NUMBER,
163 OSD_STAT_MAX_G_FORCE,
164 OSD_STAT_MAX_ESC_TEMP,
165 OSD_STAT_MAX_ESC_RPM,
166 OSD_STAT_MIN_LINK_QUALITY,
167 OSD_STAT_FLIGHT_DISTANCE,
168 OSD_STAT_MAX_FFT,
169 OSD_STAT_TOTAL_FLIGHTS,
170 OSD_STAT_TOTAL_TIME,
171 OSD_STAT_TOTAL_DIST,
172 OSD_STAT_MIN_RSSI_DBM,
173 OSD_STAT_COUNT // MUST BE LAST
174 } osd_stats_e;
176 // Make sure the number of stats do not exceed the available 32bit storage
177 STATIC_ASSERT(OSD_STAT_COUNT <= 32, osdstats_overflow);
179 typedef enum {
180 OSD_UNIT_IMPERIAL,
181 OSD_UNIT_METRIC
182 } osd_unit_e;
184 typedef enum {
185 OSD_TIMER_1,
186 OSD_TIMER_2,
187 OSD_TIMER_COUNT
188 } osd_timer_e;
190 typedef enum {
191 OSD_TIMER_SRC_ON,
192 OSD_TIMER_SRC_TOTAL_ARMED,
193 OSD_TIMER_SRC_LAST_ARMED,
194 OSD_TIMER_SRC_ON_OR_ARMED,
195 OSD_TIMER_SRC_COUNT
196 } osd_timer_source_e;
198 typedef enum {
199 OSD_TIMER_PREC_SECOND,
200 OSD_TIMER_PREC_HUNDREDTHS,
201 OSD_TIMER_PREC_TENTHS,
202 OSD_TIMER_PREC_COUNT
203 } osd_timer_precision_e;
205 typedef enum {
206 OSD_WARNING_ARMING_DISABLE,
207 OSD_WARNING_BATTERY_NOT_FULL,
208 OSD_WARNING_BATTERY_WARNING,
209 OSD_WARNING_BATTERY_CRITICAL,
210 OSD_WARNING_VISUAL_BEEPER,
211 OSD_WARNING_CRASH_FLIP,
212 OSD_WARNING_ESC_FAIL,
213 OSD_WARNING_CORE_TEMPERATURE,
214 OSD_WARNING_RC_SMOOTHING,
215 OSD_WARNING_FAIL_SAFE,
216 OSD_WARNING_LAUNCH_CONTROL,
217 OSD_WARNING_GPS_RESCUE_UNAVAILABLE,
218 OSD_WARNING_GPS_RESCUE_DISABLED,
219 OSD_WARNING_RSSI,
220 OSD_WARNING_LINK_QUALITY,
221 OSD_WARNING_RSSI_DBM,
222 OSD_WARNING_COUNT // MUST BE LAST
223 } osdWarningsFlags_e;
225 typedef enum {
226 OSD_DISPLAYPORT_DEVICE_NONE = 0,
227 OSD_DISPLAYPORT_DEVICE_AUTO,
228 OSD_DISPLAYPORT_DEVICE_MAX7456,
229 OSD_DISPLAYPORT_DEVICE_MSP,
230 } osdDisplayPortDevice_e;
232 // Make sure the number of warnings do not exceed the available 32bit storage
233 STATIC_ASSERT(OSD_WARNING_COUNT <= 32, osdwarnings_overflow);
235 #define ESC_RPM_ALARM_OFF -1
236 #define ESC_TEMP_ALARM_OFF INT8_MIN
237 #define ESC_CURRENT_ALARM_OFF -1
239 #define OSD_GPS_RESCUE_DISABLED_WARNING_DURATION_US 3000000 // 3 seconds
241 extern const uint16_t osdTimerDefault[OSD_TIMER_COUNT];
242 extern const osd_stats_e osdStatsDisplayOrder[OSD_STAT_COUNT];
244 typedef struct osdConfig_s {
245 uint16_t item_pos[OSD_ITEM_COUNT];
247 // Alarms
248 uint16_t cap_alarm;
249 uint16_t alt_alarm;
250 uint8_t rssi_alarm;
252 osd_unit_e units;
254 uint16_t timers[OSD_TIMER_COUNT];
255 uint32_t enabledWarnings;
257 uint8_t ahMaxPitch;
258 uint8_t ahMaxRoll;
259 uint32_t enabled_stats;
260 int8_t esc_temp_alarm;
261 int16_t esc_rpm_alarm;
262 int16_t esc_current_alarm;
263 uint8_t core_temp_alarm;
264 uint8_t ahInvert; // invert the artificial horizon
265 uint8_t osdProfileIndex;
266 uint8_t overlay_radio_mode;
267 char profile[OSD_PROFILE_COUNT][OSD_PROFILE_NAME_LENGTH + 1];
268 uint16_t link_quality_alarm;
269 uint8_t rssi_dbm_alarm;
270 uint8_t gps_sats_show_hdop;
271 int8_t rcChannels[OSD_RCCHANNELS_COUNT]; // RC channel values to display, -1 if none
272 uint8_t displayPortDevice; // osdDisplayPortDevice_e
273 uint16_t distance_alarm;
274 } osdConfig_t;
276 PG_DECLARE(osdConfig_t, osdConfig);
278 typedef struct statistic_s {
279 timeUs_t armed_time;
280 int16_t max_speed;
281 int16_t min_voltage; // /100
282 uint16_t end_voltage;
283 int16_t max_current; // /10
284 uint8_t min_rssi;
285 int32_t max_altitude;
286 int16_t max_distance;
287 float max_g_force;
288 int16_t max_esc_temp;
289 int32_t max_esc_rpm;
290 uint16_t min_link_quality;
291 uint8_t min_rssi_dbm;
292 } statistic_t;
294 extern timeUs_t resumeRefreshAt;
295 extern timeUs_t osdFlyTime;
296 #if defined(USE_ACC)
297 extern float osdGForce;
298 #endif
299 #ifdef USE_ESC_SENSOR
300 extern escSensorData_t *osdEscDataCombined;
301 #endif
303 struct displayPort_s;
304 void osdInit(struct displayPort_s *osdDisplayPort);
305 bool osdInitialized(void);
306 void osdUpdate(timeUs_t currentTimeUs);
307 void osdStatSetState(uint8_t statIndex, bool enabled);
308 bool osdStatGetState(uint8_t statIndex);
309 void osdWarnSetState(uint8_t warningIndex, bool enabled);
310 bool osdWarnGetState(uint8_t warningIndex);
311 void osdSuppressStats(bool flag);
313 void osdAnalyzeActiveElements(void);
314 uint8_t getCurrentOsdProfileIndex(void);
315 void changeOsdProfileIndex(uint8_t profileIndex);
316 bool osdElementVisible(uint16_t value);
317 bool osdGetVisualBeeperState(void);
318 statistic_t *osdGetStats(void);
319 bool osdNeedsAccelerometer(void);