SITL: Added comment to clarify IMU acceleration value
[ardupilot.git] / libraries / AP_OSD / AP_OSD_Screen.cpp
blob947203c3ab81260821018b397644a865ac26bbf5
1 /*
2 * This file is free software: you can redistribute it and/or modify it
3 * under the terms of the GNU General Public License as published by the
4 * Free Software Foundation, either version 3 of the License, or
5 * (at your option) any later version.
7 * This file is distributed in the hope that it will be useful, but
8 * WITHOUT ANY WARRANTY; without even the implied warranty of
9 * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
10 * See the GNU General Public License for more details.
12 * You should have received a copy of the GNU General Public License along
13 * with this program. If not, see <http://www.gnu.org/licenses/>.
15 * AP_OSD partially based on betaflight and inav osd.c implemention.
16 * clarity.mcm font is taken from inav configurator.
17 * Many thanks to their authors.
20 parameter settings for one screen
22 #include "AP_OSD_config.h"
24 #if OSD_ENABLED
26 #include "AP_OSD.h"
27 #include "AP_OSD_Backend.h"
29 #include <AP_HAL/AP_HAL.h>
30 #include <AP_HAL/Util.h>
31 #include <AP_AHRS/AP_AHRS.h>
32 #include <AP_Math/AP_Math.h>
33 #include <AP_RSSI/AP_RSSI.h>
34 #include <AP_Notify/AP_Notify.h>
35 #include <AP_Stats/AP_Stats.h>
36 #include <AP_Common/Location.h>
37 #include <AP_BattMonitor/AP_BattMonitor.h>
38 #include <AP_GPS/AP_GPS.h>
39 #include <AP_RTC/AP_RTC.h>
40 #include <AP_MSP/msp.h>
41 #include <AP_OLC/AP_OLC.h>
42 #include <AP_VideoTX/AP_VideoTX.h>
43 #include <AP_Terrain/AP_Terrain.h>
44 #include <AP_RangeFinder/AP_RangeFinder.h>
45 #include <AP_Vehicle/AP_Vehicle.h>
46 #include <AP_RPM/AP_RPM.h>
47 #include <AP_MSP/AP_MSP.h>
48 #if APM_BUILD_TYPE(APM_BUILD_Rover)
49 #include <AP_WindVane/AP_WindVane.h>
50 #endif
51 #include <AP_Filesystem/AP_Filesystem.h>
53 #include <ctype.h>
54 #include <GCS_MAVLink/GCS.h>
55 #include <AC_Fence/AC_Fence.h>
57 #if AP_OSD_EXTENDED_LNK_STATS
58 // We need to this file to access the CRSF telemetry objects which contains the link stats data
59 #include <AP_RCProtocol/AP_RCProtocol_CRSF.h>
60 #endif
62 const AP_Param::GroupInfo AP_OSD_Screen::var_info[] = {
64 // @Param: ENABLE
65 // @DisplayName: Enable screen
66 // @Description: Enable this screen
67 // @Values: 0:Disabled,1:Enabled
68 // @User: Standard
69 AP_GROUPINFO_FLAGS("ENABLE", 1, AP_OSD_Screen, enabled, 0, AP_PARAM_FLAG_ENABLE),
71 // @Param: CHAN_MIN
72 // @DisplayName: Transmitter switch screen minimum pwm
73 // @Description: This sets the PWM lower limit for this screen
74 // @Range: 900 2100
75 // @User: Standard
76 AP_GROUPINFO("CHAN_MIN", 2, AP_OSD_Screen, channel_min, 900),
78 // @Param: CHAN_MAX
79 // @DisplayName: Transmitter switch screen maximum pwm
80 // @Description: This sets the PWM upper limit for this screen
81 // @Range: 900 2100
82 // @User: Standard
83 AP_GROUPINFO("CHAN_MAX", 3, AP_OSD_Screen, channel_max, 2100),
85 // @Param: ALTITUDE_EN
86 // @DisplayName: ALTITUDE_EN
87 // @Description: Enables display of altitude AGL
88 // @Values: 0:Disabled,1:Enabled
90 // @Param: ALTITUDE_X
91 // @DisplayName: ALTITUDE_X
92 // @Description: Horizontal position on screen
93 // @Range: 0 59
95 // @Param: ALTITUDE_Y
96 // @DisplayName: ALTITUDE_Y
97 // @Description: Vertical position on screen
98 // @Range: 0 21
99 AP_SUBGROUPINFO(altitude, "ALTITUDE", 4, AP_OSD_Screen, AP_OSD_Setting),
101 // @Param: BAT_VOLT_EN
102 // @DisplayName: BATVOLT_EN
103 // @Description: Displays main battery voltage
104 // @Values: 0:Disabled,1:Enabled
106 // @Param: BAT_VOLT_X
107 // @DisplayName: BATVOLT_X
108 // @Description: Horizontal position on screen
109 // @Range: 0 59
111 // @Param: BAT_VOLT_Y
112 // @DisplayName: BATVOLT_Y
113 // @Description: Vertical position on screen
114 // @Range: 0 21
115 AP_SUBGROUPINFO(bat_volt, "BAT_VOLT", 5, AP_OSD_Screen, AP_OSD_Setting),
117 // @Param: RSSI_EN
118 // @DisplayName: RSSI_EN
119 // @Description: Displays RC signal strength
120 // @Values: 0:Disabled,1:Enabled
122 // @Param: RSSI_X
123 // @DisplayName: RSSI_X
124 // @Description: Horizontal position on screen
125 // @Range: 0 59
127 // @Param: RSSI_Y
128 // @DisplayName: RSSI_Y
129 // @Description: Vertical position on screen
130 // @Range: 0 21
131 AP_SUBGROUPINFO(rssi, "RSSI", 6, AP_OSD_Screen, AP_OSD_Setting),
133 // @Param: CURRENT_EN
134 // @DisplayName: CURRENT_EN
135 // @Description: Displays main battery current
136 // @Values: 0:Disabled,1:Enabled
138 // @Param: CURRENT_X
139 // @DisplayName: CURRENT_X
140 // @Description: Horizontal position on screen
141 // @Range: 0 59
143 // @Param: CURRENT_Y
144 // @DisplayName: CURRENT_Y
145 // @Description: Vertical position on screen
146 // @Range: 0 21
147 AP_SUBGROUPINFO(current, "CURRENT", 7, AP_OSD_Screen, AP_OSD_Setting),
149 // @Param: BATUSED_EN
150 // @DisplayName: BATUSED_EN
151 // @Description: Displays primary battery mAh consumed
152 // @Values: 0:Disabled,1:Enabled
154 // @Param: BATUSED_X
155 // @DisplayName: BATUSED_X
156 // @Description: Horizontal position on screen
157 // @Range: 0 59
159 // @Param: BATUSED_Y
160 // @DisplayName: BATUSED_Y
161 // @Description: Vertical position on screen
162 // @Range: 0 21
163 AP_SUBGROUPINFO(batused, "BATUSED", 8, AP_OSD_Screen, AP_OSD_Setting),
165 // @Param: SATS_EN
166 // @DisplayName: SATS_EN
167 // @Description: Displays number of acquired satellites
168 // @Values: 0:Disabled,1:Enabled
170 // @Param: SATS_X
171 // @DisplayName: SATS_X
172 // @Description: Horizontal position on screen
173 // @Range: 0 59
175 // @Param: SATS_Y
176 // @DisplayName: SATS_Y
177 // @Description: Vertical position on screen
178 // @Range: 0 21
179 AP_SUBGROUPINFO(sats, "SATS", 9, AP_OSD_Screen, AP_OSD_Setting),
181 // @Param: FLTMODE_EN
182 // @DisplayName: FLTMODE_EN
183 // @Description: Displays flight mode
184 // @Values: 0:Disabled,1:Enabled
186 // @Param: FLTMODE_X
187 // @DisplayName: FLTMODE_X
188 // @Description: Horizontal position on screen
189 // @Range: 0 59
191 // @Param: FLTMODE_Y
192 // @DisplayName: FLTMODE_Y
193 // @Description: Vertical position on screen
194 // @Range: 0 21
195 AP_SUBGROUPINFO(fltmode, "FLTMODE", 10, AP_OSD_Screen, AP_OSD_Setting),
197 // @Param: MESSAGE_EN
198 // @DisplayName: MESSAGE_EN
199 // @Description: Displays Mavlink messages
200 // @Values: 0:Disabled,1:Enabled
202 // @Param: MESSAGE_X
203 // @DisplayName: MESSAGE_X
204 // @Description: Horizontal position on screen
205 // @Range: 0 59
207 // @Param: MESSAGE_Y
208 // @DisplayName: MESSAGE_Y
209 // @Description: Vertical position on screen
210 // @Range: 0 21
211 AP_SUBGROUPINFO(message, "MESSAGE", 11, AP_OSD_Screen, AP_OSD_Setting),
213 // @Param: GSPEED_EN
214 // @DisplayName: GSPEED_EN
215 // @Description: Displays GPS ground speed
216 // @Values: 0:Disabled,1:Enabled
218 // @Param: GSPEED_X
219 // @DisplayName: GSPEED_X
220 // @Description: Horizontal position on screen
221 // @Range: 0 59
223 // @Param: GSPEED_Y
224 // @DisplayName: GSPEED_Y
225 // @Description: Vertical position on screen
226 // @Range: 0 21
227 AP_SUBGROUPINFO(gspeed, "GSPEED", 12, AP_OSD_Screen, AP_OSD_Setting),
229 // @Param: HORIZON_EN
230 // @DisplayName: HORIZON_EN
231 // @Description: Displays artificial horizon
232 // @Values: 0:Disabled,1:Enabled
234 // @Param: HORIZON_X
235 // @DisplayName: HORIZON_X
236 // @Description: Horizontal position on screen
237 // @Range: 0 59
239 // @Param: HORIZON_Y
240 // @DisplayName: HORIZON_Y
241 // @Description: Vertical position on screen
242 // @Range: 0 21
243 AP_SUBGROUPINFO(horizon, "HORIZON", 13, AP_OSD_Screen, AP_OSD_Setting),
245 // @Param: HOME_EN
246 // @DisplayName: HOME_EN
247 // @Description: Displays distance and relative direction to HOME
248 // @Values: 0:Disabled,1:Enabled
250 // @Param: HOME_X
251 // @DisplayName: HOME_X
252 // @Description: Horizontal position on screen
253 // @Range: 0 59
255 // @Param: HOME_Y
256 // @DisplayName: HOME_Y
257 // @Description: Vertical position on screen
258 // @Range: 0 21
259 AP_SUBGROUPINFO(home, "HOME", 14, AP_OSD_Screen, AP_OSD_Setting),
261 // @Param: HEADING_EN
262 // @DisplayName: HEADING_EN
263 // @Description: Displays heading
264 // @Values: 0:Disabled,1:Enabled
266 // @Param: HEADING_X
267 // @DisplayName: HEADING_X
268 // @Description: Horizontal position on screen
269 // @Range: 0 59
271 // @Param: HEADING_Y
272 // @DisplayName: HEADING_Y
273 // @Description: Vertical position on screen
274 // @Range: 0 21
275 AP_SUBGROUPINFO(heading, "HEADING", 15, AP_OSD_Screen, AP_OSD_Setting),
277 // @Param: THROTTLE_EN
278 // @DisplayName: THROTTLE_EN
279 // @Description: Displays actual throttle percentage being sent to motor(s)
280 // @Values: 0:Disabled,1:Enabled
282 // @Param: THROTTLE_X
283 // @DisplayName: THROTTLE_X
284 // @Description: Horizontal position on screen
285 // @Range: 0 59
287 // @Param: THROTTLE_Y
288 // @DisplayName: THROTTLE_Y
289 // @Description: Vertical position on screen
290 // @Range: 0 21
291 AP_SUBGROUPINFO(throttle, "THROTTLE", 16, AP_OSD_Screen, AP_OSD_Setting),
293 // @Param: COMPASS_EN
294 // @DisplayName: COMPASS_EN
295 // @Description: Enables display of compass rose
296 // @Values: 0:Disabled,1:Enabled
298 // @Param: COMPASS_X
299 // @DisplayName: COMPASS_X
300 // @Description: Horizontal position on screen
301 // @Range: 0 59
303 // @Param: COMPASS_Y
304 // @DisplayName: COMPASS_Y
305 // @Description: Vertical position on screen
306 // @Range: 0 21
307 AP_SUBGROUPINFO(compass, "COMPASS", 17, AP_OSD_Screen, AP_OSD_Setting),
309 // @Param: WIND_EN
310 // @DisplayName: WIND_EN
311 // @Description: Displays wind speed and relative direction, on Rover this is the apparent wind speed and direction from the windvane, if fitted
312 // @Values: 0:Disabled,1:Enabled
314 // @Param: WIND_X
315 // @DisplayName: WIND_X
316 // @Description: Horizontal position on screen
317 // @Range: 0 59
319 // @Param: WIND_Y
320 // @DisplayName: WIND_Y
321 // @Description: Vertical position on screen
322 // @Range: 0 21
323 AP_SUBGROUPINFO(wind, "WIND", 18, AP_OSD_Screen, AP_OSD_Setting),
326 // @Param: ASPEED_EN
327 // @DisplayName: ASPEED_EN
328 // @Description: Displays airspeed value being used by TECS (fused value)
329 // @Values: 0:Disabled,1:Enabled
331 // @Param: ASPEED_X
332 // @DisplayName: ASPEED_X
333 // @Description: Horizontal position on screen
334 // @Range: 0 59
336 // @Param: ASPEED_Y
337 // @DisplayName: ASPEED_Y
338 // @Description: Vertical position on screen
339 // @Range: 0 21
340 AP_SUBGROUPINFO(aspeed, "ASPEED", 19, AP_OSD_Screen, AP_OSD_Setting),
342 // @Param: VSPEED_EN
343 // @DisplayName: VSPEED_EN
344 // @Description: Displays climb rate
345 // @Values: 0:Disabled,1:Enabled
347 // @Param: VSPEED_X
348 // @DisplayName: VSPEED_X
349 // @Description: Horizontal position on screen
350 // @Range: 0 59
352 // @Param: VSPEED_Y
353 // @DisplayName: VSPEED_Y
354 // @Description: Vertical position on screen
355 // @Range: 0 21
356 AP_SUBGROUPINFO(vspeed, "VSPEED", 20, AP_OSD_Screen, AP_OSD_Setting),
358 #if HAL_WITH_ESC_TELEM
359 // @Param: ESCTEMP_EN
360 // @DisplayName: ESCTEMP_EN
361 // @Description: Displays highest temp of all active ESCs, or of a specific ECS if OSDx_ESC_IDX is set
362 // @Values: 0:Disabled,1:Enabled
364 // @Param: ESCTEMP_X
365 // @DisplayName: ESCTEMP_X
366 // @Description: Horizontal position on screen
367 // @Range: 0 59
369 // @Param: ESCTEMP_Y
370 // @DisplayName: ESCTEMP_Y
371 // @Description: Vertical position on screen
372 // @Range: 0 21
373 AP_SUBGROUPINFO(esc_temp, "ESCTEMP", 21, AP_OSD_Screen, AP_OSD_Setting),
375 // @Param: ESCRPM_EN
376 // @DisplayName: ESCRPM_EN
377 // @Description: Displays highest rpm of all active ESCs, or of a specific ESC if OSDx_ESC_IDX is set
378 // @Values: 0:Disabled,1:Enabled
380 // @Param: ESCRPM_X
381 // @DisplayName: ESCRPM_X
382 // @Description: Horizontal position on screen
383 // @Range: 0 59
385 // @Param: ESCRPM_Y
386 // @DisplayName: ESCRPM_Y
387 // @Description: Vertical position on screen
388 // @Range: 0 21
389 AP_SUBGROUPINFO(esc_rpm, "ESCRPM", 22, AP_OSD_Screen, AP_OSD_Setting),
391 // @Param: ESCAMPS_EN
392 // @DisplayName: ESCAMPS_EN
393 // @Description: Displays the current of the ESC with the highest rpm of all active ESCs, or of a specific ESC if OSDx_ESC_IDX is set
394 // @Values: 0:Disabled,1:Enabled
396 // @Param: ESCAMPS_X
397 // @DisplayName: ESCAMPS_X
398 // @Description: Horizontal position on screen
399 // @Range: 0 59
401 // @Param: ESCAMPS_Y
402 // @DisplayName: ESCAMPS_Y
403 // @Description: Vertical position on screen
404 // @Range: 0 21
405 AP_SUBGROUPINFO(esc_amps, "ESCAMPS", 23, AP_OSD_Screen, AP_OSD_Setting),
406 #endif
407 // @Param: GPSLAT_EN
408 // @DisplayName: GPSLAT_EN
409 // @Description: Displays GPS latitude
410 // @Values: 0:Disabled,1:Enabled
412 // @Param: GPSLAT_X
413 // @DisplayName: GPSLAT_X
414 // @Description: Horizontal position on screen
415 // @Range: 0 59
417 // @Param: GPSLAT_Y
418 // @DisplayName: GPSLAT_Y
419 // @Description: Vertical position on screen
420 // @Range: 0 21
421 AP_SUBGROUPINFO(gps_latitude, "GPSLAT", 24, AP_OSD_Screen, AP_OSD_Setting),
423 // @Param: GPSLONG_EN
424 // @DisplayName: GPSLONG_EN
425 // @Description: Displays GPS longitude
426 // @Values: 0:Disabled,1:Enabled
428 // @Param: GPSLONG_X
429 // @DisplayName: GPSLONG_X
430 // @Description: Horizontal position on screen
431 // @Range: 0 59
433 // @Param: GPSLONG_Y
434 // @DisplayName: GPSLONG_Y
435 // @Description: Vertical position on screen
436 // @Range: 0 21
437 AP_SUBGROUPINFO(gps_longitude, "GPSLONG", 25, AP_OSD_Screen, AP_OSD_Setting),
439 // @Param: ROLL_EN
440 // @DisplayName: ROLL_EN
441 // @Description: Displays degrees of roll from level
442 // @Values: 0:Disabled,1:Enabled
444 // @Param: ROLL_X
445 // @DisplayName: ROLL_X
446 // @Description: Horizontal position on screen
447 // @Range: 0 59
449 // @Param: ROLL_Y
450 // @DisplayName: ROLL_Y
451 // @Description: Vertical position on screen
452 // @Range: 0 21
453 AP_SUBGROUPINFO(roll_angle, "ROLL", 26, AP_OSD_Screen, AP_OSD_Setting),
455 // @Param: PITCH_EN
456 // @DisplayName: PITCH_EN
457 // @Description: Displays degrees of pitch from level
458 // @Values: 0:Disabled,1:Enabled
460 // @Param: PITCH_X
461 // @DisplayName: PITCH_X
462 // @Description: Horizontal position on screen
463 // @Range: 0 59
465 // @Param: PITCH_Y
466 // @DisplayName: PITCH_Y
467 // @Description: Vertical position on screen
468 // @Range: 0 21
469 AP_SUBGROUPINFO(pitch_angle, "PITCH", 27, AP_OSD_Screen, AP_OSD_Setting),
471 // @Param: TEMP_EN
472 // @DisplayName: TEMP_EN
473 // @Description: Displays temperature reported by primary barometer
474 // @Values: 0:Disabled,1:Enabled
476 // @Param: TEMP_X
477 // @DisplayName: TEMP_X
478 // @Description: Horizontal position on screen
479 // @Range: 0 59
481 // @Param: TEMP_Y
482 // @DisplayName: TEMP_Y
483 // @Description: Vertical position on screen
484 // @Range: 0 21
485 AP_SUBGROUPINFO(temp, "TEMP", 28, AP_OSD_Screen, AP_OSD_Setting),
487 // @Param: HDOP_EN
488 // @DisplayName: HDOP_EN
489 // @Description: Displays Horizontal Dilution Of Position
490 // @Values: 0:Disabled,1:Enabled
492 // @Param: HDOP_X
493 // @DisplayName: HDOP_X
494 // @Description: Horizontal position on screen
495 // @Range: 0 59
497 // @Param: HDOP_Y
498 // @DisplayName: HDOP_Y
499 // @Description: Vertical position on screen
500 // @Range: 0 21
501 AP_SUBGROUPINFO(hdop, "HDOP", 29, AP_OSD_Screen, AP_OSD_Setting),
503 // @Param: WAYPOINT_EN
504 // @DisplayName: WAYPOINT_EN
505 // @Description: Displays bearing and distance to next waypoint
506 // @Values: 0:Disabled,1:Enabled
508 // @Param: WAYPOINT_X
509 // @DisplayName: WAYPOINT_X
510 // @Description: Horizontal position on screen
511 // @Range: 0 59
513 // @Param: WAYPOINT_Y
514 // @DisplayName: WAYPOINT_Y
515 // @Description: Vertical position on screen
516 // @Range: 0 21
517 AP_SUBGROUPINFO(waypoint, "WAYPOINT", 30, AP_OSD_Screen, AP_OSD_Setting),
519 // @Param: XTRACK_EN
520 // @DisplayName: XTRACK_EN
521 // @Description: Displays crosstrack error
522 // @Values: 0:Disabled,1:Enabled
524 // @Param: XTRACK_X
525 // @DisplayName: XTRACK_X
526 // @Description: Horizontal position on screen
527 // @Range: 0 59
529 // @Param: XTRACK_Y
530 // @DisplayName: XTRACK_Y
531 // @Description: Vertical position on screen
532 // @Range: 0 21
533 AP_SUBGROUPINFO(xtrack_error, "XTRACK", 31, AP_OSD_Screen, AP_OSD_Setting),
535 // @Param: DIST_EN
536 // @DisplayName: DIST_EN
537 // @Description: Displays total distance flown
538 // @Values: 0:Disabled,1:Enabled
540 // @Param: DIST_X
541 // @DisplayName: DIST_X
542 // @Description: Horizontal position on screen
543 // @Range: 0 59
545 // @Param: DIST_Y
546 // @DisplayName: DIST_Y
547 // @Description: Vertical position on screen
548 // @Range: 0 21
549 AP_SUBGROUPINFO(dist, "DIST", 32, AP_OSD_Screen, AP_OSD_Setting),
551 // @Param: STATS_EN
552 // @DisplayName: STATS_EN
553 // @Description: Displays flight stats
554 // @Values: 0:Disabled,1:Enabled
556 // @Param: STATS_X
557 // @DisplayName: STATS_X
558 // @Description: Horizontal position on screen
559 // @Range: 0 59
561 // @Param: STATS_Y
562 // @DisplayName: STATS_Y
563 // @Description: Vertical position on screen
564 // @Range: 0 21
565 AP_SUBGROUPINFO(stat, "STATS", 33, AP_OSD_Screen, AP_OSD_Setting),
567 // @Param: FLTIME_EN
568 // @DisplayName: FLTIME_EN
569 // @Description: Displays total flight time
570 // @Values: 0:Disabled,1:Enabled
572 // @Param: FLTIME_X
573 // @DisplayName: FLTIME_X
574 // @Description: Horizontal position on screen
575 // @Range: 0 59
577 // @Param: FLTIME_Y
578 // @DisplayName: FLTIME_Y
579 // @Description: Vertical position on screen
580 // @Range: 0 21
581 AP_SUBGROUPINFO(flightime, "FLTIME", 34, AP_OSD_Screen, AP_OSD_Setting),
583 // @Param: CLIMBEFF_EN
584 // @DisplayName: CLIMBEFF_EN
585 // @Description: Displays climb efficiency (climb rate/current)
586 // @Values: 0:Disabled,1:Enabled
588 // @Param: CLIMBEFF_X
589 // @DisplayName: CLIMBEFF_X
590 // @Description: Horizontal position on screen
591 // @Range: 0 59
593 // @Param: CLIMBEFF_Y
594 // @DisplayName: CLIMBEFF_Y
595 // @Description: Vertical position on screen
596 // @Range: 0 21
597 AP_SUBGROUPINFO(climbeff, "CLIMBEFF", 35, AP_OSD_Screen, AP_OSD_Setting),
599 // @Param: EFF_EN
600 // @DisplayName: EFF_EN
601 // @Description: Displays flight efficiency (mAh/km or /mi)
602 // @Values: 0:Disabled,1:Enabled
604 // @Param: EFF_X
605 // @DisplayName: EFF_X
606 // @Description: Horizontal position on screen
607 // @Range: 0 59
609 // @Param: EFF_Y
610 // @DisplayName: EFF_Y
611 // @Description: Vertical position on screen
612 // @Range: 0 21
613 AP_SUBGROUPINFO(eff, "EFF", 36, AP_OSD_Screen, AP_OSD_Setting),
615 #if BARO_MAX_INSTANCES > 1
616 // @Param: BTEMP_EN
617 // @DisplayName: BTEMP_EN
618 // @Description: Displays temperature reported by secondary barometer
619 // @Values: 0:Disabled,1:Enabled
621 // @Param: BTEMP_X
622 // @DisplayName: BTEMP_X
623 // @Description: Horizontal position on screen
624 // @Range: 0 59
626 // @Param: BTEMP_Y
627 // @DisplayName: BTEMP_Y
628 // @Description: Vertical position on screen
629 // @Range: 0 21
630 AP_SUBGROUPINFO(btemp, "BTEMP", 37, AP_OSD_Screen, AP_OSD_Setting),
631 #endif
633 // @Param: ATEMP_EN
634 // @DisplayName: ATEMP_EN
635 // @Description: Displays temperature reported by primary airspeed sensor
636 // @Values: 0:Disabled,1:Enabled
638 // @Param: ATEMP_X
639 // @DisplayName: ATEMP_X
640 // @Description: Horizontal position on screen
641 // @Range: 0 59
643 // @Param: ATEMP_Y
644 // @DisplayName: ATEMP_Y
645 // @Description: Vertical position on screen
646 // @Range: 0 21
647 AP_SUBGROUPINFO(atemp, "ATEMP", 38, AP_OSD_Screen, AP_OSD_Setting),
649 // @Param: BAT2_VLT_EN
650 // @DisplayName: BAT2VLT_EN
651 // @Description: Displays battery2 voltage
652 // @Values: 0:Disabled,1:Enabled
654 // @Param: BAT2_VLT_X
655 // @DisplayName: BAT2VLT_X
656 // @Description: Horizontal position on screen
657 // @Range: 0 59
659 // @Param: BAT2_VLT_Y
660 // @DisplayName: BAT2VLT_Y
661 // @Description: Vertical position on screen
662 // @Range: 0 21
663 AP_SUBGROUPINFO(bat2_vlt, "BAT2_VLT", 39, AP_OSD_Screen, AP_OSD_Setting),
665 // @Param: BAT2USED_EN
666 // @DisplayName: BAT2USED_EN
667 // @Description: Displays secondary battery mAh consumed
668 // @Values: 0:Disabled,1:Enabled
670 // @Param: BAT2USED_X
671 // @DisplayName: BAT2USED_X
672 // @Description: Horizontal position on screen
673 // @Range: 0 59
675 // @Param: BAT2USED_Y
676 // @DisplayName: BAT2USED_Y
677 // @Description: Vertical position on screen
678 // @Range: 0 21
679 AP_SUBGROUPINFO(bat2used, "BAT2USED", 40, AP_OSD_Screen, AP_OSD_Setting),
682 // @Param: ASPD2_EN
683 // @DisplayName: ASPD2_EN
684 // @Description: Displays airspeed reported directly from secondary airspeed sensor
685 // @Values: 0:Disabled,1:Enabled
687 // @Param: ASPD2_X
688 // @DisplayName: ASPD2_X
689 // @Description: Horizontal position on screen
690 // @Range: 0 59
692 // @Param: ASPD2_Y
693 // @DisplayName: ASPD2_Y
694 // @Description: Vertical position on screen
695 // @Range: 0 21
696 AP_SUBGROUPINFO(aspd2, "ASPD2", 41, AP_OSD_Screen, AP_OSD_Setting),
698 // @Param: ASPD1_EN
699 // @DisplayName: ASPD1_EN
700 // @Description: Displays airspeed reported directly from primary airspeed sensor
701 // @Values: 0:Disabled,1:Enabled
703 // @Param: ASPD1_X
704 // @DisplayName: ASPD1_X
705 // @Description: Horizontal position on screen
706 // @Range: 0 59
708 // @Param: ASPD1_Y
709 // @DisplayName: ASPD1_Y
710 // @Description: Vertical position on screen
711 // @Range: 0 21
712 AP_SUBGROUPINFO(aspd1, "ASPD1", 42, AP_OSD_Screen, AP_OSD_Setting),
714 // @Param: CLK_EN
715 // @DisplayName: CLK_EN
716 // @Description: Displays a clock panel based on AP_RTC local time
717 // @Values: 0:Disabled,1:Enabled
719 // @Param: CLK_X
720 // @DisplayName: CLK_X
721 // @Description: Horizontal position on screen
722 // @Range: 0 59
724 // @Param: CLK_Y
725 // @DisplayName: CLK_Y
726 // @Description: Vertical position on screen
727 // @Range: 0 21
728 AP_SUBGROUPINFO(clk, "CLK", 43, AP_OSD_Screen, AP_OSD_Setting),
730 #if HAL_OSD_SIDEBAR_ENABLE || HAL_MSP_ENABLED
731 // @Param: SIDEBARS_EN
732 // @DisplayName: SIDEBARS_EN
733 // @Description: Displays artificial horizon side bars
734 // @Values: 0:Disabled,1:Enabled
736 // @Param: SIDEBARS_X
737 // @DisplayName: SIDEBARS_X
738 // @Description: Horizontal position on screen
739 // @Range: 0 59
741 // @Param: SIDEBARS_Y
742 // @DisplayName: SIDEBARS_Y
743 // @Description: Vertical position on screen
744 // @Range: 0 21
745 AP_SUBGROUPINFO(sidebars, "SIDEBARS", 44, AP_OSD_Screen, AP_OSD_Setting),
746 #endif
748 #if HAL_MSP_ENABLED
749 // @Param: CRSSHAIR_EN
750 // @DisplayName: CRSSHAIR_EN
751 // @Description: Displays artificial horizon crosshair (MSP OSD only)
752 // @Values: 0:Disabled,1:Enabled
754 // @Param: CRSSHAIR_X
755 // @DisplayName: CRSSHAIR_X
756 // @Description: Horizontal position on screen (MSP OSD only)
757 // @Range: 0 59
759 // @Param: CRSSHAIR_Y
760 // @DisplayName: CRSSHAIR_Y
761 // @Description: Vertical position on screen (MSP OSD only)
762 // @Range: 0 21
763 AP_SUBGROUPINFO(crosshair, "CRSSHAIR", 45, AP_OSD_Screen, AP_OSD_Setting),
765 // @Param: HOMEDIST_EN
766 // @DisplayName: HOMEDIST_EN
767 // @Description: Displays distance from HOME (MSP OSD only)
768 // @Values: 0:Disabled,1:Enabled
770 // @Param: HOMEDIST_X
771 // @DisplayName: HOMEDIST_X
772 // @Description: Horizontal position on screen (MSP OSD only)
773 // @Range: 0 59
775 // @Param: HOMEDIST_Y
776 // @DisplayName: HOMEDIST_Y
777 // @Description: Vertical position on screen (MSP OSD only)
778 // @Range: 0 21
779 AP_SUBGROUPINFO(home_dist, "HOMEDIST", 46, AP_OSD_Screen, AP_OSD_Setting),
781 // @Param: HOMEDIR_EN
782 // @DisplayName: HOMEDIR_EN
783 // @Description: Displays relative direction to HOME (MSP OSD only)
784 // @Values: 0:Disabled,1:Enabled
786 // @Param: HOMEDIR_X
787 // @DisplayName: HOMEDIR_X
788 // @Description: Horizontal position on screen
789 // @Range: 0 59
791 // @Param: HOMEDIR_Y
792 // @DisplayName: HOMEDIR_Y
793 // @Description: Vertical position on screen
794 // @Range: 0 21
795 AP_SUBGROUPINFO(home_dir, "HOMEDIR", 47, AP_OSD_Screen, AP_OSD_Setting),
797 // @Param: POWER_EN
798 // @DisplayName: POWER_EN
799 // @Description: Displays power (MSP OSD only)
800 // @Values: 0:Disabled,1:Enabled
802 // @Param: POWER_X
803 // @DisplayName: POWER_X
804 // @Description: Horizontal position on screen
805 // @Range: 0 59
807 // @Param: POWER_Y
808 // @DisplayName: POWER_Y
809 // @Description: Vertical position on screen
810 // @Range: 0 21
811 AP_SUBGROUPINFO(power, "POWER", 48, AP_OSD_Screen, AP_OSD_Setting),
813 // @Param: CELLVOLT_EN
814 // @DisplayName: CELL_VOLT_EN
815 // @Description: Displays average cell voltage (MSP OSD only)
816 // @Values: 0:Disabled,1:Enabled
818 // @Param: CELLVOLT_X
819 // @DisplayName: CELL_VOLT_X
820 // @Description: Horizontal position on screen
821 // @Range: 0 59
823 // @Param: CELLVOLT_Y
824 // @DisplayName: CELL_VOLT_Y
825 // @Description: Vertical position on screen
826 // @Range: 0 21
827 AP_SUBGROUPINFO(cell_volt, "CELLVOLT", 49, AP_OSD_Screen, AP_OSD_Setting),
829 // @Param: BATTBAR_EN
830 // @DisplayName: BATT_BAR_EN
831 // @Description: Displays battery usage bar (MSP OSD only)
832 // @Values: 0:Disabled,1:Enabled
834 // @Param: BATTBAR_X
835 // @DisplayName: BATT_BAR_X
836 // @Description: Horizontal position on screen
837 // @Range: 0 59
839 // @Param: BATTBAR_Y
840 // @DisplayName: BATT_BAR_Y
841 // @Description: Vertical position on screen
842 // @Range: 0 21
843 AP_SUBGROUPINFO(batt_bar, "BATTBAR", 50, AP_OSD_Screen, AP_OSD_Setting),
845 // @Param: ARMING_EN
846 // @DisplayName: ARMING_EN
847 // @Description: Displays arming status (MSP OSD only)
848 // @Values: 0:Disabled,1:Enabled
850 // @Param: ARMING_X
851 // @DisplayName: ARMING_X
852 // @Description: Horizontal position on screen
853 // @Range: 0 59
855 // @Param: ARMING_Y
856 // @DisplayName: ARMING_Y
857 // @Description: Vertical position on screen
858 // @Range: 0 21
859 AP_SUBGROUPINFO(arming, "ARMING", 51, AP_OSD_Screen, AP_OSD_Setting),
860 #endif //HAL_MSP_ENABLED
862 #if HAL_PLUSCODE_ENABLE
863 // @Param: PLUSCODE_EN
864 // @DisplayName: PLUSCODE_EN
865 // @Description: Displays pluscode (OLC) element
866 // @Values: 0:Disabled,1:Enabled
868 // @Param: PLUSCODE_X
869 // @DisplayName: PLUSCODE_X
870 // @Description: Horizontal position on screen
871 // @Range: 0 59
873 // @Param: PLUSCODE_Y
874 // @DisplayName: PLUSCODE_Y
875 // @Description: Vertical position on screen
876 // @Range: 0 21
877 AP_SUBGROUPINFO(pluscode, "PLUSCODE", 52, AP_OSD_Screen, AP_OSD_Setting),
878 #endif
880 #if AP_OSD_CALLSIGN_FROM_SD_ENABLED
881 // @Param: CALLSIGN_EN
882 // @DisplayName: CALLSIGN_EN
883 // @Description: Displays callsign from callsign.txt on microSD card
884 // @Values: 0:Disabled,1:Enabled
886 // @Param: CALLSIGN_X
887 // @DisplayName: CALLSIGN_X
888 // @Description: Horizontal position on screen
889 // @Range: 0 59
891 // @Param: CALLSIGN_Y
892 // @DisplayName: CALLSIGN_Y
893 // @Description: Vertical position on screen
894 // @Range: 0 21
895 AP_SUBGROUPINFO(callsign, "CALLSIGN", 53, AP_OSD_Screen, AP_OSD_Setting),
896 #endif
898 // @Param: CURRENT2_EN
899 // @DisplayName: CURRENT2_EN
900 // @Description: Displays 2nd battery current
901 // @Values: 0:Disabled,1:Enabled
903 // @Param: CURRENT2_X
904 // @DisplayName: CURRENT2_X
905 // @Description: Horizontal position on screen
906 // @Range: 0 59
908 // @Param: CURRENT2_Y
909 // @DisplayName: CURRENT2_Y
910 // @Description: Vertical position on screen
911 // @Range: 0 21
912 AP_SUBGROUPINFO(current2, "CURRENT2", 54, AP_OSD_Screen, AP_OSD_Setting),
914 #if AP_VIDEOTX_ENABLED
915 // @Param: VTX_PWR_EN
916 // @DisplayName: VTX_PWR_EN
917 // @Description: Displays VTX Power
918 // @Values: 0:Disabled,1:Enabled
920 // @Param: VTX_PWR_X
921 // @DisplayName: VTX_PWR_X
922 // @Description: Horizontal position on screen
923 // @Range: 0 59
925 // @Param: VTX_PWR_Y
926 // @DisplayName: VTX_PWR_Y
927 // @Description: Vertical position on screen
928 // @Range: 0 21
929 AP_SUBGROUPINFO(vtx_power, "VTX_PWR", 55, AP_OSD_Screen, AP_OSD_Setting),
930 #endif // AP_VIDEOTX_ENABLED
932 #if AP_TERRAIN_AVAILABLE
933 // @Param: TER_HGT_EN
934 // @DisplayName: TER_HGT_EN
935 // @Description: Displays Height above terrain
936 // @Values: 0:Disabled,1:Enabled
938 // @Param: TER_HGT_X
939 // @DisplayName: TER_HGT_X
940 // @Description: Horizontal position on screen
941 // @Range: 0 59
943 // @Param: TER_HGT_Y
944 // @DisplayName: TER_HGT_Y
945 // @Description: Vertical position on screen
946 // @Range: 0 21
947 AP_SUBGROUPINFO(hgt_abvterr, "TER_HGT", 56, AP_OSD_Screen, AP_OSD_Setting),
948 #endif
950 // @Param: AVGCELLV_EN
951 // @DisplayName: AVGCELLV_EN
952 // @Description: Displays average cell voltage. WARNING: this can be inaccurate if the cell count is not detected or set properly. If the the battery is far from fully charged the detected cell count might not be accurate if auto cell count detection is used (OSD_CELL_COUNT=0).
953 // @Values: 0:Disabled,1:Enabled
955 // @Param: AVGCELLV_X
956 // @DisplayName: AVGCELLV_X
957 // @Description: Horizontal position on screen
958 // @Range: 0 59
960 // @Param: AVGCELLV_Y
961 // @DisplayName: AVGCELLV_Y
962 // @Description: Vertical position on screen
963 // @Range: 0 21
964 AP_SUBGROUPINFO(avgcellvolt, "AVGCELLV", 57, AP_OSD_Screen, AP_OSD_Setting),
966 // @Param: RESTVOLT_EN
967 // @DisplayName: RESTVOLT_EN
968 // @Description: Displays main battery resting voltage
969 // @Values: 0:Disabled,1:Enabled
971 // @Param: RESTVOLT_X
972 // @DisplayName: RESTVOLT_X
973 // @Description: Horizontal position on screen
974 // @Range: 0 59
976 // @Param: RESTVOLT_Y
977 // @DisplayName: RESTVOLT_Y
978 // @Description: Vertical position on screen
979 // @Range: 0 21
980 AP_SUBGROUPINFO(restvolt, "RESTVOLT", 58, AP_OSD_Screen, AP_OSD_Setting),
982 // @Param: FENCE_EN
983 // @DisplayName: FENCE_EN
984 // @Description: Displays indication of fence enable and breach
985 // @Values: 0:Disabled,1:Enabled
987 // @Param: FENCE_X
988 // @DisplayName: FENCE_X
989 // @Description: Horizontal position on screen
990 // @Range: 0 59
992 // @Param: FENCE_Y
993 // @DisplayName: FENCE_Y
994 // @Description: Vertical position on screen
995 // @Range: 0 21
996 AP_SUBGROUPINFO(fence, "FENCE", 59, AP_OSD_Screen, AP_OSD_Setting),
998 // @Param: RNGF_EN
999 // @DisplayName: RNGF_EN
1000 // @Description: Displays a rangefinder's distance in cm
1001 // @Values: 0:Disabled,1:Enabled
1003 // @Param: RNGF_X
1004 // @DisplayName: RNGF_X
1005 // @Description: Horizontal position on screen
1006 // @Range: 0 59
1008 // @Param: RNGF_Y
1009 // @DisplayName: RNGF_Y
1010 // @Description: Vertical position on screen
1011 // @Range: 0 21
1012 AP_SUBGROUPINFO(rngf, "RNGF", 60, AP_OSD_Screen, AP_OSD_Setting),
1014 // @Param: ACRVOLT_EN
1015 // @DisplayName: ACRVOLT_EN
1016 // @Description: Displays resting voltage for the average cell. WARNING: this can be inaccurate if the cell count is not detected or set properly. If the the battery is far from fully charged the detected cell count might not be accurate if auto cell count detection is used (OSD_CELL_COUNT=0).
1017 // @Values: 0:Disabled,1:Enabled
1019 // @Param: ACRVOLT_X
1020 // @DisplayName: ACRVOLT_X
1021 // @Description: Horizontal position on screen
1022 // @Range: 0 59
1024 // @Param: ACRVOLT_Y
1025 // @DisplayName: ACRVOLT_Y
1026 // @Description: Vertical position on screen
1027 // @Range: 0 21
1028 AP_SUBGROUPINFO(avgcellrestvolt, "ACRVOLT", 61, AP_OSD_Screen, AP_OSD_Setting),
1030 #if AP_RPM_ENABLED
1031 // @Param: RPM_EN
1032 // @DisplayName: RPM_EN
1033 // @Description: Displays main rotor revs/min
1034 // @Values: 0:Disabled,1:Enabled
1036 // @Param: RPM_X
1037 // @DisplayName: RPM_X
1038 // @Description: Horizontal position on screen
1039 // @Range: 0 29
1041 // @Param: RPM_Y
1042 // @DisplayName: RPM_Y
1043 // @Description: Vertical position on screen
1044 // @Range: 0 15
1045 AP_SUBGROUPINFO(rrpm, "RPM", 62, AP_OSD_Screen, AP_OSD_Setting),
1046 #endif
1048 AP_GROUPEND
1051 const AP_Param::GroupInfo AP_OSD_Screen::var_info2[] = {
1052 // duplicate of OSDn_ENABLE to ensure params are hidden when not enabled
1053 AP_GROUPINFO_FLAGS("ENABLE", 2, AP_OSD_Screen, enabled, 0, AP_PARAM_FLAG_ENABLE | AP_PARAM_FLAG_HIDDEN),
1055 // @Param: LINK_Q_EN
1056 // @DisplayName: LINK_Q_EN
1057 // @Description: Displays Receiver link quality
1058 // @Values: 0:Disabled,1:Enabled
1060 // @Param: LINK_Q_X
1061 // @DisplayName: LINK_Q_X
1062 // @Description: Horizontal position on screen
1063 // @Range: 0 59
1065 // @Param: LINK_Q_Y
1066 // @DisplayName: LINK_Q_Y
1067 // @Description: Vertical position on screen
1068 // @Range: 0 21
1069 AP_SUBGROUPINFO(link_quality, "LINK_Q", 1, AP_OSD_Screen, AP_OSD_Setting),
1071 #if HAL_WITH_MSP_DISPLAYPORT
1072 // @Param: TXT_RES
1073 // @DisplayName: Sets the overlay text resolution (MSP DisplayPort only)
1074 // @Description: Sets the overlay text resolution for this screen to either SD 30x16 or HD 50x18/60x22 (MSP DisplayPort only)
1075 // @Values: 0:30x16,1:50x18,2:60x22
1076 // @User: Standard
1077 AP_GROUPINFO("TXT_RES", 3, AP_OSD_Screen, txt_resolution, 0),
1079 // @Param: FONT
1080 // @DisplayName: Sets the font index for this screen (MSP DisplayPort only)
1081 // @Description: Sets the font index for this screen (MSP DisplayPort only)
1082 // @Range: 0 21
1083 // @User: Standard
1084 AP_GROUPINFO("FONT", 4, AP_OSD_Screen, font_index, 0),
1085 #endif
1087 #if AP_OSD_EXTENDED_LNK_STATS
1088 // @Param: RC_PWR_EN
1089 // @DisplayName: RC_PWR_EN
1090 // @Description: Displays the RC link transmit (TX) power in mW or W, depending on level
1091 // @Values: 0:Disabled,1:Enabled
1093 // @Param: RC_PWR_X
1094 // @DisplayName: RC_PWR_X
1095 // @Description: Horizontal position on screen
1096 // @Range: 0 59
1098 // @Param: RC_PWR_Y
1099 // @DisplayName: RC_PWR_Y
1100 // @Description: Vertical position on screen
1101 // @Range: 0 21
1102 AP_SUBGROUPINFO(rc_tx_power, "RC_PWR", 5, AP_OSD_Screen, AP_OSD_Setting),
1104 // @Param: RSSIDBM_EN
1105 // @DisplayName: RSSIDBM_EN
1106 // @Description: Displays RC link signal strength in dBm
1107 // @Values: 0:Disabled,1:Enabled
1109 // @Param: RSSIDBM_X
1110 // @DisplayName: RSSIDBM_X
1111 // @Description: Horizontal position on screen
1112 // @Range: 0 59
1114 // @Param: RSSIDBM_Y
1115 // @DisplayName: RSSIDBM_Y
1116 // @Description: Vertical position on screen
1117 // @Range: 0 21
1118 AP_SUBGROUPINFO(rc_rssi_dbm, "RSSIDBM", 6, AP_OSD_Screen, AP_OSD_Setting),
1120 // @Param: RC_SNR_EN
1121 // @DisplayName: RC_SNR_EN
1122 // @Description: Displays RC link signal to noise ratio in dB
1123 // @Values: 0:Disabled,1:Enabled
1125 // @Param: RC_SNR_X
1126 // @DisplayName: RC_SNR_X
1127 // @Description: Horizontal position on screen
1128 // @Range: 0 59
1130 // @Param: RC_SNR_Y
1131 // @DisplayName: RC_SNR_Y
1132 // @Description: Vertical position on screen
1133 // @Range: 0 21
1134 AP_SUBGROUPINFO(rc_snr, "RC_SNR", 7, AP_OSD_Screen, AP_OSD_Setting),
1136 // @Param: RC_ANT_EN
1137 // @DisplayName: RC_ANT_EN
1138 // @Description: Displays the current RC link active antenna
1139 // @Values: 0:Disabled,1:Enabled
1141 // @Param: RC_ANT_X
1142 // @DisplayName: RC_ANT_X
1143 // @Description: Horizontal position on screen
1144 // @Range: 0 59
1146 // @Param: RC_ANT_Y
1147 // @DisplayName: RC_ANT_Y
1148 // @Description: Vertical position on screen
1149 // @Range: 0 21
1150 AP_SUBGROUPINFO(rc_active_antenna, "RC_ANT", 8, AP_OSD_Screen, AP_OSD_Setting),
1152 // @Param: RC_LQ_EN
1153 // @DisplayName: RC_LQ_EN
1154 // @Description: Displays the RC link quality (uplink, 0 to 100%) and also RF mode if bit 7 of OSD_OPTIONS is set
1155 // @Values: 0:Disabled,1:Enabled
1157 // @Param: RC_LQ_X
1158 // @DisplayName: RC_LQ_X
1159 // @Description: Horizontal position on screen
1160 // @Range: 0 59
1162 // @Param: RC_LQ_Y
1163 // @DisplayName: RC_LQ_Y
1164 // @Description: Vertical position on screen
1165 // @Range: 0 21
1166 AP_SUBGROUPINFO(rc_lq, "RC_LQ", 9, AP_OSD_Screen, AP_OSD_Setting),
1167 #endif
1169 #if HAL_WITH_ESC_TELEM
1170 // @Param: ESC_IDX
1171 // @DisplayName: ESC_IDX
1172 // @Description: Index of the ESC to use for displaying ESC information. 0 means use the ESC with the highest value.
1173 // @Range: 0 32
1174 AP_GROUPINFO("ESC_IDX", 10, AP_OSD_Screen, esc_index, 0),
1175 #endif
1177 AP_GROUPEND
1181 uint8_t AP_OSD_AbstractScreen::symbols_lookup_table[AP_OSD_NUM_SYMBOLS];
1183 // Symbol indexes to acces _symbols[index][set]
1184 #define SYM_M 0
1185 #define SYM_KM 1
1186 #define SYM_FT 2
1187 #define SYM_MI 3
1188 #define SYM_ALT_M 4
1189 #define SYM_ALT_FT 5
1190 #define SYM_BATT_FULL 6
1191 #define SYM_RSSI 7
1193 #define SYM_VOLT 8
1194 #define SYM_AMP 9
1195 #define SYM_MAH 10
1196 #define SYM_MS 11
1197 #define SYM_FS 12
1198 #define SYM_KMH 13
1199 #define SYM_MPH 14
1200 #define SYM_DEGR 15
1201 #define SYM_PCNT 16
1202 #define SYM_RPM 17
1203 #define SYM_ASPD 18
1204 #define SYM_GSPD 19
1205 #define SYM_WSPD 20
1206 #define SYM_VSPD 21
1207 #define SYM_WPNO 22
1208 #define SYM_WPDIR 23
1209 #define SYM_WPDST 24
1210 #define SYM_FTMIN 25
1211 #define SYM_FTSEC 26
1213 #define SYM_SAT_L 27
1214 #define SYM_SAT_R 28
1215 #define SYM_HDOP_L 29
1216 #define SYM_HDOP_R 30
1218 #define SYM_HOME 31
1219 #define SYM_WIND 32
1221 #define SYM_ARROW_START 33
1222 #define SYM_ARROW_COUNT 34
1223 #define SYM_AH_H_START 35
1224 #define SYM_AH_H_COUNT 36
1226 #define SYM_AH_V_START 37
1227 #define SYM_AH_V_COUNT 38
1229 #define SYM_AH_CENTER_LINE_LEFT 39
1230 #define SYM_AH_CENTER_LINE_RIGHT 40
1231 #define SYM_AH_CENTER 41
1233 #define SYM_HEADING_N 42
1234 #define SYM_HEADING_S 43
1235 #define SYM_HEADING_E 44
1236 #define SYM_HEADING_W 45
1237 #define SYM_HEADING_DIVIDED_LINE 46
1238 #define SYM_HEADING_LINE 47
1240 #define SYM_UP_UP 48
1241 #define SYM_UP 49
1242 #define SYM_DOWN 50
1243 #define SYM_DOWN_DOWN 51
1245 #define SYM_DEGREES_C 52
1246 #define SYM_DEGREES_F 53
1247 #define SYM_GPS_LAT 54
1248 #define SYM_GPS_LONG 55
1249 #define SYM_ARMED 56
1250 #define SYM_DISARMED 57
1251 #define SYM_ROLL0 58
1252 #define SYM_ROLLR 59
1253 #define SYM_ROLLL 60
1254 #define SYM_PTCH0 61
1255 #define SYM_PTCHUP 62
1256 #define SYM_PTCHDWN 63
1257 #define SYM_XERR 64
1258 #define SYM_KN 65
1259 #define SYM_NM 66
1260 #define SYM_DIST 67
1261 #define SYM_FLY 68
1262 #define SYM_EFF 69
1263 #define SYM_AH 70
1264 #define SYM_MW 71
1265 #define SYM_CLK 72
1266 #define SYM_KILO 73
1267 #define SYM_TERALT 74
1268 #define SYM_FENCE_ENABLED 75
1269 #define SYM_FENCE_DISABLED 76
1270 #define SYM_RNGFD 77
1271 #define SYM_LQ 78
1273 #define SYM_SIDEBAR_R_ARROW 79
1274 #define SYM_SIDEBAR_L_ARROW 80
1275 #define SYM_SIDEBAR_A 81
1276 #define SYM_SIDEBAR_B 82
1277 #define SYM_SIDEBAR_C 83
1278 #define SYM_SIDEBAR_D 84
1279 #define SYM_SIDEBAR_E 85
1280 #define SYM_SIDEBAR_F 86
1281 #define SYM_SIDEBAR_G 87
1282 #define SYM_SIDEBAR_H 88
1283 #define SYM_SIDEBAR_I 89
1284 #define SYM_SIDEBAR_J 90
1286 #define SYM_WATT 91
1287 #define SYM_WH 92
1288 #define SYM_DB 93
1289 #define SYM_DBM 94
1290 #define SYM_SNR 95
1291 #define SYM_ANT 96
1292 #define SYM_ARROW_RIGHT 97
1293 #define SYM_ARROW_LEFT 98
1295 #define SYM_G 99
1296 #define SYM_BATT_UNKNOWN 100
1297 #define SYM_ROLL 101
1298 #define SYM_PITCH 102
1299 #define SYM_DPS 103
1300 #define SYM_HEADING 104
1301 #define SYM_RADIUS 105
1302 #define SYM_FLAP 106
1304 #define SYMBOL(n) AP_OSD_AbstractScreen::symbols_lookup_table[n]
1306 // constructor
1307 AP_OSD_Screen::AP_OSD_Screen()
1309 AP_Param::setup_object_defaults(this, var_info);
1310 AP_Param::setup_object_defaults(this, var_info2);
1313 void AP_OSD_AbstractScreen::set_backend(AP_OSD_Backend *_backend)
1315 backend = _backend;
1316 osd = _backend->get_osd();
1319 bool AP_OSD_AbstractScreen::check_option(uint32_t option)
1321 return osd?(osd->options & option) != 0 : false;
1325 get the right units icon given a unit
1327 char AP_OSD_AbstractScreen::u_icon(enum unit_type unit)
1329 static const uint8_t icons_metric[UNIT_TYPE_LAST] {
1330 SYM_ALT_M, //ALTITUDE
1331 SYM_KMH, //SPEED
1332 SYM_MS, //VSPEED
1333 SYM_M, //DISTANCE
1334 SYM_KM, //DISTANCE_LONG
1335 SYM_DEGREES_C //TEMPERATURE
1337 static const uint8_t icons_imperial[UNIT_TYPE_LAST] {
1338 SYM_ALT_FT, //ALTITUDE
1339 SYM_MPH, //SPEED
1340 SYM_FS, //VSPEED
1341 SYM_FT, //DISTANCE
1342 SYM_MI, //DISTANCE_LONG
1343 SYM_DEGREES_F //TEMPERATURE
1345 static const uint8_t icons_SI[UNIT_TYPE_LAST] {
1346 SYM_ALT_M, //ALTITUDE
1347 SYM_MS, //SPEED
1348 SYM_MS, //VSPEED
1349 SYM_M, //DISTANCE
1350 SYM_KM, //DISTANCE_LONG
1351 SYM_DEGREES_C //TEMPERATURE
1353 static const uint8_t icons_aviation[UNIT_TYPE_LAST] {
1354 SYM_ALT_FT, //ALTITUDE Ft
1355 SYM_KN, //SPEED Knots
1356 SYM_FTMIN, //VSPEED
1357 SYM_FT, //DISTANCE
1358 SYM_NM, //DISTANCE_LONG Nm
1359 SYM_DEGREES_C //TEMPERATURE
1361 static const uint8_t* icons[AP_OSD::UNITS_LAST] = {
1362 icons_metric,
1363 icons_imperial,
1364 icons_SI,
1365 icons_aviation,
1367 return (char)SYMBOL(icons[constrain_int16(osd->units, 0, AP_OSD::UNITS_LAST-1)][unit]);
1371 scale a value for the user selected units
1373 float AP_OSD_AbstractScreen::u_scale(enum unit_type unit, float value)
1375 static const float scale_metric[UNIT_TYPE_LAST] = {
1376 1.0, //ALTITUDE m
1377 3.6, //SPEED km/hr
1378 1.0, //VSPEED m/s
1379 1.0, //DISTANCE m
1380 1.0/1000, //DISTANCE_LONG km
1381 1.0, //TEMPERATURE C
1383 static const float scale_imperial[UNIT_TYPE_LAST] = {
1384 3.28084, //ALTITUDE ft
1385 2.23694, //SPEED mph
1386 3.28084, //VSPEED ft/s
1387 3.28084, //DISTANCE ft
1388 1.0/1609.34, //DISTANCE_LONG miles
1389 1.8, //TEMPERATURE F
1391 static const float offset_imperial[UNIT_TYPE_LAST] = {
1392 0.0, //ALTITUDE
1393 0.0, //SPEED
1394 0.0, //VSPEED
1395 0.0, //DISTANCE
1396 0.0, //DISTANCE_LONG
1397 32.0, //TEMPERATURE F
1399 static const float scale_SI[UNIT_TYPE_LAST] = {
1400 1.0, //ALTITUDE m
1401 1.0, //SPEED m/s
1402 1.0, //VSPEED m/s
1403 1.0, //DISTANCE m
1404 1.0/1000, //DISTANCE_LONG km
1405 1.0, //TEMPERATURE C
1407 static const float scale_aviation[UNIT_TYPE_LAST] = {
1408 3.28084, //ALTITUDE Ft
1409 1.94384, //SPEED Knots
1410 196.85, //VSPEED ft/min
1411 3.28084, //DISTANCE ft
1412 0.000539957, //DISTANCE_LONG Nm
1413 1.0, //TEMPERATURE C
1415 static const float *scale[AP_OSD::UNITS_LAST] = {
1416 scale_metric,
1417 scale_imperial,
1418 scale_SI,
1419 scale_aviation
1421 static const float *offsets[AP_OSD::UNITS_LAST] = {
1422 nullptr,
1423 offset_imperial,
1424 nullptr,
1425 nullptr
1427 uint8_t units = constrain_int16(osd->units, 0, AP_OSD::UNITS_LAST-1);
1428 return value * scale[units][unit] + (offsets[units]?offsets[units][unit]:0);
1431 char AP_OSD_Screen::get_arrow_font_index(int32_t angle_cd)
1433 uint32_t interval = 36000 / SYMBOL(SYM_ARROW_COUNT);
1434 angle_cd = wrap_360_cd(angle_cd);
1435 // if using BF font table must translate arrows
1436 if (check_option(AP_OSD::OPTION_BF_ARROWS)) {
1437 angle_cd = angle_cd > 18000? 54000 - angle_cd : 18000- angle_cd;
1439 return SYMBOL(SYM_ARROW_START) + ((angle_cd + interval / 2) / interval) % SYMBOL(SYM_ARROW_COUNT);
1442 void AP_OSD_Screen::draw_altitude(uint8_t x, uint8_t y)
1444 float alt;
1445 AP_AHRS &ahrs = AP::ahrs();
1446 WITH_SEMAPHORE(ahrs.get_semaphore());
1447 ahrs.get_relative_position_D_home(alt);
1448 alt = -alt;
1449 backend->write(x, y, false, "%4d%c", (int)u_scale(ALTITUDE, alt), u_icon(ALTITUDE));
1452 #if AP_BATTERY_ENABLED
1453 void AP_OSD_Screen::draw_bat_volt(uint8_t instance, VoltageType type, uint8_t x, uint8_t y)
1455 AP_BattMonitor &battery = AP::battery();
1456 float v = battery.voltage(instance);
1457 float blinkvolt = osd->warn_batvolt;
1458 uint8_t pct;
1459 bool show_remaining_pct = battery.capacity_remaining_pct(pct);
1460 uint8_t p = (100 - pct) / 16.6;
1461 switch (type) {
1462 case VoltageType::VOLTAGE: {
1463 break;
1465 case VoltageType::RESTING_VOLTAGE: {
1466 v = battery.voltage_resting_estimate(instance);
1467 blinkvolt = osd->warn_restvolt;
1468 break;
1470 case VoltageType::RESTING_CELL: {
1471 blinkvolt = osd->warn_avgcellrestvolt;
1472 v = battery.voltage_resting_estimate(instance);
1473 FALLTHROUGH;
1475 case VoltageType::AVG_CELL: {
1476 if (type == VoltageType::AVG_CELL) { //for fallthrough of RESTING_CELL
1477 blinkvolt = osd->warn_avgcellvolt;
1479 // calculate cell count - WARNING this can be inaccurate if the LIPO/LIION battery is far from
1480 // fully charged when attached and is used in this panel
1481 osd->max_battery_voltage.set(MAX(osd->max_battery_voltage,v));
1482 if (osd->cell_count > 0) {
1483 v = v / osd->cell_count;
1484 } else if (osd->cell_count < 0) { // user must decide on autodetect cell count or manually entered to display this panel since default is -1
1485 backend->write(x,y, false, "%c---%c", SYMBOL(SYM_BATT_FULL) + p, SYMBOL(SYM_VOLT));
1486 return;
1487 } else { // use autodetected cell count
1488 v = v / (uint8_t)(osd->max_battery_voltage * 0.2381 + 1);
1490 break;
1493 if (!show_remaining_pct) {
1494 // Do not show battery percentage
1495 if (type == VoltageType::RESTING_CELL || type == VoltageType::AVG_CELL) {
1496 backend->write(x,y, v < blinkvolt, "%1.2f%c", (double)v, SYMBOL(SYM_VOLT));
1497 } else {
1498 backend->write(x,y, v < blinkvolt, "%2.1f%c", (double)v, SYMBOL(SYM_VOLT));
1500 return;
1502 if (type == VoltageType::RESTING_CELL || type == VoltageType::AVG_CELL) {
1503 backend->write(x,y, v < blinkvolt, "%c%1.2f%c", SYMBOL(SYM_BATT_FULL) + p, (double)v, SYMBOL(SYM_VOLT));
1504 } else {
1505 backend->write(x,y, v < blinkvolt, "%c%2.1f%c", SYMBOL(SYM_BATT_FULL) + p, (double)v, SYMBOL(SYM_VOLT));
1509 void AP_OSD_Screen::draw_bat_volt(uint8_t x, uint8_t y)
1511 draw_bat_volt(0,VoltageType::VOLTAGE,x,y);
1514 void AP_OSD_Screen::draw_avgcellvolt(uint8_t x, uint8_t y)
1516 draw_bat_volt(0,VoltageType::AVG_CELL,x,y);
1519 void AP_OSD_Screen::draw_avgcellrestvolt(uint8_t x, uint8_t y)
1521 draw_bat_volt(0,VoltageType::RESTING_CELL,x, y);
1524 void AP_OSD_Screen::draw_restvolt(uint8_t x, uint8_t y)
1526 draw_bat_volt(0,VoltageType::RESTING_VOLTAGE,x,y);
1528 #endif // AP_BATTERY_ENABLED
1530 #if AP_RSSI_ENABLED
1531 void AP_OSD_Screen::draw_rssi(uint8_t x, uint8_t y)
1533 AP_RSSI *ap_rssi = AP_RSSI::get_singleton();
1534 if (ap_rssi) {
1535 const uint8_t rssiv = ap_rssi->read_receiver_rssi() * 100;
1536 backend->write(x, y, rssiv < osd->warn_rssi, "%c%2d", SYMBOL(SYM_RSSI), rssiv);
1540 void AP_OSD_Screen::draw_link_quality(uint8_t x, uint8_t y)
1542 AP_RSSI *ap_rssi = AP_RSSI::get_singleton();
1543 if (ap_rssi) {
1544 const int16_t lqv = ap_rssi->read_receiver_link_quality();
1545 if (lqv < 0){
1546 backend->write(x, y, false, "%c--", SYMBOL(SYM_LQ));
1547 } else {
1548 backend->write(x, y, false, "%c%2d", SYMBOL(SYM_LQ), lqv);
1552 #endif // AP_RSSI_ENABLED
1554 #if AP_BATTERY_ENABLED
1555 void AP_OSD_Screen::draw_current(uint8_t instance, uint8_t x, uint8_t y)
1557 float amps;
1558 if (!AP::battery().current_amps(amps, instance)) {
1559 osd->_stats.avg_current_a = 0;
1561 //filter current and display with autoranging for low values
1562 osd->_stats.avg_current_a= osd->_stats.avg_current_a + (amps - osd->_stats.avg_current_a) * 0.33;
1563 if (osd->_stats.avg_current_a < 10.0) {
1564 backend->write(x, y, false, "%2.2f%c", osd->_stats.avg_current_a, SYMBOL(SYM_AMP));
1566 else {
1567 backend->write(x, y, false, "%2.1f%c", osd->_stats.avg_current_a, SYMBOL(SYM_AMP));
1571 void AP_OSD_Screen::draw_current(uint8_t x, uint8_t y)
1573 draw_current(0, x, y);
1575 #endif
1577 void AP_OSD_Screen::draw_fltmode(uint8_t x, uint8_t y)
1579 AP_Notify * notify = AP_Notify::get_singleton();
1580 char arm;
1581 if (AP_Notify::flags.armed) {
1582 arm = SYMBOL(SYM_ARMED);
1583 } else {
1584 arm = SYMBOL(SYM_DISARMED);
1586 if (notify) {
1587 backend->write(x, y, false, "%s%c", notify->get_flight_mode_str(), arm);
1591 void AP_OSD_Screen::draw_sats(uint8_t x, uint8_t y)
1593 AP_GPS & gps = AP::gps();
1594 uint8_t nsat = gps.num_sats();
1595 bool flash = (nsat < osd->warn_nsat) || (gps.status() < AP_GPS::GPS_OK_FIX_3D);
1596 backend->write(x, y, flash, "%c%c%2u", SYMBOL(SYM_SAT_L), SYMBOL(SYM_SAT_R), nsat);
1599 #if AP_BATTERY_ENABLED
1600 void AP_OSD_Screen::draw_batused(uint8_t instance, uint8_t x, uint8_t y)
1602 float mah;
1603 if (!AP::battery().consumed_mah(mah, instance)) {
1604 mah = 0;
1606 if (mah <= 9999) {
1607 backend->write(x,y, false, "%4d%c", (int)mah, SYMBOL(SYM_MAH));
1608 } else {
1609 const float ah = mah * 1e-3f;
1610 backend->write(x,y, false, "%2.2f%c", (double)ah, SYMBOL(SYM_AH));
1614 void AP_OSD_Screen::draw_batused(uint8_t x, uint8_t y)
1616 draw_batused(0, x, y);
1618 #endif
1620 //Autoscroll message is the same as in minimosd-extra.
1621 //Thanks to night-ghost for the approach.
1622 void AP_OSD_Screen::draw_message(uint8_t x, uint8_t y)
1624 AP_Notify * notify = AP_Notify::get_singleton();
1625 if (notify) {
1626 int32_t visible_time = AP_HAL::millis() - notify->get_text_updated_millis();
1627 if (visible_time < osd->msgtime_s *1000) {
1628 char buffer[NOTIFY_TEXT_BUFFER_SIZE];
1629 strncpy(buffer, notify->get_text(), sizeof(buffer));
1630 int16_t len = strnlen(buffer, sizeof(buffer));
1632 for (int16_t i=0; i<len; i++) {
1633 //converted to uppercase,
1634 //because we do not have small letter chars inside used font
1635 buffer[i] = toupper(buffer[i]);
1636 //normalize whitespace
1637 if (isspace(buffer[i])) {
1638 buffer[i] = ' ';
1642 int16_t start_position = 0;
1643 //scroll if required
1644 //scroll pattern: wait, scroll to the left, wait, scroll to the right
1645 if (len > message_visible_width) {
1646 int16_t chars_to_scroll = len - message_visible_width;
1647 int16_t total_cycles = 2*message_scroll_delay + 2*chars_to_scroll;
1648 int16_t current_cycle = (visible_time / message_scroll_time_ms) % total_cycles;
1650 //calculate scroll start_position
1651 if (current_cycle < total_cycles/2) {
1652 //move to the left
1653 start_position = current_cycle - message_scroll_delay;
1654 } else {
1655 //move to the right
1656 start_position = total_cycles - current_cycle;
1658 start_position = constrain_int16(start_position, 0, chars_to_scroll);
1659 int16_t end_position = start_position + message_visible_width;
1661 //ensure array boundaries
1662 start_position = MIN(start_position, int(sizeof(buffer)-1));
1663 end_position = MIN(end_position, int(sizeof(buffer)-1));
1665 //trim invisible part
1666 buffer[end_position] = 0;
1669 backend->write(x, y, buffer + start_position);
1674 // draw a arrow at the given angle, and print the given magnitude
1675 void AP_OSD_Screen::draw_speed(uint8_t x, uint8_t y, float angle_rad, float magnitude)
1677 int32_t angle_cd = angle_rad * DEGX100;
1678 char arrow = get_arrow_font_index(angle_cd);
1679 if (u_scale(SPEED, magnitude) < 9.95) {
1680 backend->write(x, y, false, "%c %1.1f%c", arrow, u_scale(SPEED, magnitude), u_icon(SPEED));
1681 } else {
1682 backend->write(x, y, false, "%c%3d%c", arrow, (int)roundf(u_scale(SPEED, magnitude)), u_icon(SPEED));
1686 void AP_OSD_Screen::draw_gspeed(uint8_t x, uint8_t y)
1688 AP_AHRS &ahrs = AP::ahrs();
1689 WITH_SEMAPHORE(ahrs.get_semaphore());
1690 Vector2f v = ahrs.groundspeed_vector();
1691 backend->write(x, y, false, "%c", SYMBOL(SYM_GSPD));
1692 float angle = 0;
1693 const float length = v.length();
1694 if (length > 1.0f) {
1695 angle = atan2f(v.y, v.x) - ahrs.get_yaw();
1697 draw_speed(x + 1, y, angle, length);
1700 //Thanks to betaflight/inav for simple and clean artificial horizon visual design
1701 void AP_OSD_Screen::draw_horizon(uint8_t x, uint8_t y)
1703 AP_AHRS &ahrs = AP::ahrs();
1704 WITH_SEMAPHORE(ahrs.get_semaphore());
1705 float roll;
1706 float pitch;
1707 bool inverted = false;
1708 AP::vehicle()->get_osd_roll_pitch_rad(roll,pitch);
1709 pitch *= -1;
1710 // Are we inverted? then flash horizon line
1711 if (abs(roll) >= radians(90)) {
1712 inverted = true;
1714 // Aviation style AH instead of Betaflight FPV style
1715 if (inverted && check_option(AP_OSD::OPTION_AVIATION_AH)) {
1716 pitch = -pitch;
1718 //inverted roll AH (Russian HUD emulation)
1719 if (check_option(AP_OSD::OPTION_INVERTED_AH_ROLL)) {
1720 roll = -roll;
1723 pitch = constrain_float(pitch, -ah_max_pitch, ah_max_pitch);
1724 float ky = sinf(roll);
1725 float kx = cosf(roll);
1727 float ratio = backend->get_aspect_ratio_correction();
1729 if (fabsf(ky) < fabsf(kx)) {
1730 for (int dx = -4; dx <= 4; dx++) {
1731 float fy = (ratio * dx) * (ky/kx) + pitch * ah_pitch_rad_to_char + 0.5f;
1732 int dy = floorf(fy);
1733 char c = (fy - dy) * SYMBOL(SYM_AH_H_COUNT);
1734 //chars in font in reversed order
1735 c = SYMBOL(SYM_AH_H_START) + ((SYMBOL(SYM_AH_H_COUNT) - 1) - c);
1736 if (dy >= -4 && dy <= 4) {
1737 backend->write(x + dx, y - dy, inverted, "%c", c);
1740 } else {
1741 for (int dy=-4; dy<=4; dy++) {
1742 float fx = ((dy / ratio) - pitch * ah_pitch_rad_to_char) * (kx/ky) + 0.5f;
1743 int dx = floorf(fx);
1744 char c = (fx - dx) * SYMBOL(SYM_AH_V_COUNT);
1745 c = SYMBOL(SYM_AH_V_START) + c;
1746 if (dx >= -4 && dx <=4) {
1747 backend->write(x + dx, y - dy, inverted, "%c", c);
1752 if (!check_option(AP_OSD::OPTION_DISABLE_CROSSHAIR)) {
1753 backend->write(x-1,y, false, "%c%c%c", SYMBOL(SYM_AH_CENTER_LINE_LEFT), SYMBOL(SYM_AH_CENTER), SYMBOL(SYM_AH_CENTER_LINE_RIGHT));
1758 void AP_OSD_Screen::draw_distance(uint8_t x, uint8_t y, float distance)
1760 char unit_icon = u_icon(DISTANCE);
1761 float distance_scaled = u_scale(DISTANCE, distance);
1762 const char *fmt = "%4.0f%c";
1763 if (distance_scaled > 9999.0f || (osd->units == AP_OSD::UNITS_IMPERIAL && distance_scaled > 5280.0f && (osd->options & AP_OSD::OPTION_IMPERIAL_MILES))) {
1764 distance_scaled = u_scale(DISTANCE_LONG, distance);
1765 unit_icon= u_icon(DISTANCE_LONG);
1766 //try to pack as many useful info as possible
1767 if (distance_scaled<9.0f) {
1768 fmt = "%1.3f%c";
1769 } else if (distance_scaled < 99.0f) {
1770 fmt = "%2.2f%c";
1771 } else if (distance_scaled < 999.0f) {
1772 fmt = "%3.1f%c";
1773 } else {
1774 fmt = "%4.0f%c";
1776 } else if (distance_scaled < 10.0f) {
1777 fmt = "% 3.1f%c";
1779 backend->write(x, y, false, fmt, (double)distance_scaled, unit_icon);
1782 void AP_OSD_Screen::draw_home(uint8_t x, uint8_t y)
1784 AP_AHRS &ahrs = AP::ahrs();
1785 WITH_SEMAPHORE(ahrs.get_semaphore());
1786 Location loc;
1787 if (ahrs.get_location(loc) && ahrs.home_is_set()) {
1788 const Location &home_loc = ahrs.get_home();
1789 float distance = home_loc.get_distance(loc);
1790 int32_t angle_cd = loc.get_bearing_to(home_loc) - ahrs.yaw_sensor;
1791 if (distance < 2.0f) {
1792 //avoid fast rotating arrow at small distances
1793 angle_cd = 0;
1795 char arrow = get_arrow_font_index(angle_cd);
1796 backend->write(x, y, false, "%c%c", SYMBOL(SYM_HOME), arrow);
1797 draw_distance(x+2, y, distance);
1798 } else {
1799 backend->write(x, y, true, "%c", SYMBOL(SYM_HOME));
1803 void AP_OSD_Screen::draw_heading(uint8_t x, uint8_t y)
1805 AP_AHRS &ahrs = AP::ahrs();
1806 uint16_t yaw = ahrs.yaw_sensor / 100;
1807 backend->write(x, y, false, "%3d%c", yaw, SYMBOL(SYM_DEGR));
1810 #if AP_RPM_ENABLED
1811 void AP_OSD_Screen::draw_rrpm(uint8_t x, uint8_t y)
1813 float _rrpm;
1814 const AP_RPM *rpm = AP_RPM::get_singleton();
1815 if (rpm != nullptr) {
1816 if (!rpm->get_rpm(0, _rrpm)) {
1817 // No valid RPM data
1818 _rrpm = -1;
1820 } else {
1821 // No RPM because pointer is null
1822 _rrpm = -1;
1824 int r_rpm = static_cast<int>(_rrpm);
1825 backend->write(x, y, false, "%4d%c", (int)r_rpm, SYMBOL(SYM_RPM));
1827 #endif
1829 void AP_OSD_Screen::draw_throttle(uint8_t x, uint8_t y)
1831 backend->write(x, y, false, "%3d%c", gcs().get_hud_throttle(), SYMBOL(SYM_PCNT));
1834 #if HAL_OSD_SIDEBAR_ENABLE
1836 void AP_OSD_Screen::draw_sidebars(uint8_t x, uint8_t y)
1838 const int8_t total_sectors = 18;
1839 static const uint8_t sidebar_sectors[total_sectors] = {
1840 SYM_SIDEBAR_A,
1841 SYM_SIDEBAR_B,
1842 SYM_SIDEBAR_C,
1843 SYM_SIDEBAR_D,
1844 SYM_SIDEBAR_E,
1845 SYM_SIDEBAR_F,
1846 SYM_SIDEBAR_G,
1847 SYM_SIDEBAR_E,
1848 SYM_SIDEBAR_F,
1849 SYM_SIDEBAR_G,
1850 SYM_SIDEBAR_E,
1851 SYM_SIDEBAR_F,
1852 SYM_SIDEBAR_G,
1853 SYM_SIDEBAR_E,
1854 SYM_SIDEBAR_F,
1855 SYM_SIDEBAR_H,
1856 SYM_SIDEBAR_I,
1857 SYM_SIDEBAR_J,
1860 // Get altitude and airspeed, scaled to appropriate units
1861 float aspd = 0.0f;
1862 float alt = 0.0f;
1863 AP_AHRS &ahrs = AP::ahrs();
1864 WITH_SEMAPHORE(ahrs.get_semaphore());
1865 bool have_speed_estimate = ahrs.airspeed_estimate(aspd);
1866 if (!have_speed_estimate) { aspd = 0.0f; }
1867 ahrs.get_relative_position_D_home(alt);
1868 float scaled_aspd = u_scale(SPEED, aspd);
1869 float scaled_alt = u_scale(ALTITUDE, -alt);
1870 static const int aspd_interval = 10; //units between large tick marks
1871 int alt_interval = (osd->units == AP_OSD::UNITS_AVIATION || osd->units == AP_OSD::UNITS_IMPERIAL) ? 20 : 10;
1873 // Height values taking into account configurable vertical extension
1874 const int bar_total_height = 7 + (osd->sidebar_v_ext * 2);
1875 const int bar_middle = bar_total_height / 2; // Integer division
1877 // render airspeed ladder
1878 int aspd_symbol_index = fmodf(scaled_aspd, aspd_interval) / aspd_interval * total_sectors;
1879 for (int i = 0; i < bar_total_height; i++){
1880 if (i == bar_middle) {
1881 // the middle section of the ladder with the currrent airspeed
1882 backend->write(x, y+i, false, "%3d%c%c", (int) scaled_aspd, u_icon(SPEED), SYMBOL(SYM_SIDEBAR_R_ARROW));
1883 } else {
1884 backend->write(x+4, y+i, false, "%c", SYMBOL(sidebar_sectors[aspd_symbol_index]));
1886 aspd_symbol_index = (aspd_symbol_index + 12) % 18;
1889 // render the altitude ladder
1890 // similar formula to above, but accounts for negative altitudes
1891 int alt_symbol_index = fmodf(fmodf(scaled_alt, alt_interval) + alt_interval, alt_interval) / alt_interval * total_sectors;
1892 for (int i = 0; i < bar_total_height; i++){
1893 if (i == bar_middle) {
1894 // the middle section of the ladder with the currrent altitude
1895 backend->write(x + 16 + osd->sidebar_h_offset, y+i, false, "%c%d%c", SYMBOL(SYM_SIDEBAR_L_ARROW), (int) scaled_alt, u_icon(ALTITUDE));
1896 } else {
1897 backend->write(x + 16 + osd->sidebar_h_offset, y+i, false, "%c", SYMBOL(sidebar_sectors[alt_symbol_index]));
1899 alt_symbol_index = (alt_symbol_index + 12) % 18;
1903 #endif // HAL_OSD_SIDEBAR_ENABLE
1905 //Thanks to betaflight/inav for simple and clean compass visual design
1906 void AP_OSD_Screen::draw_compass(uint8_t x, uint8_t y)
1908 const int8_t total_sectors = 16;
1909 static const uint8_t compass_circle[total_sectors] = {
1910 SYM_HEADING_N,
1911 SYM_HEADING_LINE,
1912 SYM_HEADING_DIVIDED_LINE,
1913 SYM_HEADING_LINE,
1914 SYM_HEADING_E,
1915 SYM_HEADING_LINE,
1916 SYM_HEADING_DIVIDED_LINE,
1917 SYM_HEADING_LINE,
1918 SYM_HEADING_S,
1919 SYM_HEADING_LINE,
1920 SYM_HEADING_DIVIDED_LINE,
1921 SYM_HEADING_LINE,
1922 SYM_HEADING_W,
1923 SYM_HEADING_LINE,
1924 SYM_HEADING_DIVIDED_LINE,
1925 SYM_HEADING_LINE,
1927 AP_AHRS &ahrs = AP::ahrs();
1928 int32_t yaw = ahrs.yaw_sensor;
1929 int32_t interval = 36000 / total_sectors;
1930 int8_t center_sector = ((yaw + interval / 2) / interval) % total_sectors;
1931 for (int8_t i = -4; i <= 4; i++) {
1932 int8_t sector = center_sector + i;
1933 sector = (sector + total_sectors) % total_sectors;
1934 backend->write(x + i, y, false, "%c", SYMBOL(compass_circle[sector]));
1938 void AP_OSD_Screen::draw_wind(uint8_t x, uint8_t y)
1940 #if !APM_BUILD_TYPE(APM_BUILD_Rover)
1941 AP_AHRS &ahrs = AP::ahrs();
1942 WITH_SEMAPHORE(ahrs.get_semaphore());
1943 Vector3f v = ahrs.wind_estimate();
1944 float angle = 0;
1945 const float length = v.length();
1946 if (length > 1.0f) {
1947 if (check_option(AP_OSD::OPTION_INVERTED_WIND)) {
1948 angle = M_PI;
1950 angle = angle + atan2f(v.y, v.x) - ahrs.get_yaw();
1952 draw_speed(x + 1, y, angle, length);
1954 #else
1955 const AP_WindVane* windvane = AP_WindVane::get_singleton();
1956 if (windvane != nullptr) {
1957 draw_speed(x + 1, y, windvane->get_apparent_wind_direction_rad() + M_PI, windvane->get_apparent_wind_speed());
1959 #endif
1961 backend->write(x, y, false, "%c", SYMBOL(SYM_WSPD));
1964 void AP_OSD_Screen::draw_aspeed(uint8_t x, uint8_t y)
1966 float aspd = 0.0f;
1967 AP_AHRS &ahrs = AP::ahrs();
1968 WITH_SEMAPHORE(ahrs.get_semaphore());
1969 bool have_estimate = ahrs.airspeed_estimate(aspd);
1970 if (have_estimate) {
1971 backend->write(x, y, false, "%c%4d%c", SYMBOL(SYM_ASPD), (int)u_scale(SPEED, aspd), u_icon(SPEED));
1972 } else {
1973 backend->write(x, y, false, "%c ---%c", SYMBOL(SYM_ASPD), u_icon(SPEED));
1977 void AP_OSD_Screen::draw_vspeed(uint8_t x, uint8_t y)
1979 Vector3f v;
1980 float vspd;
1981 float vs_scaled;
1982 AP_AHRS &ahrs = AP::ahrs();
1983 WITH_SEMAPHORE(ahrs.get_semaphore());
1984 if (ahrs.get_velocity_NED(v)) {
1985 vspd = -v.z;
1986 } else {
1987 auto &baro = AP::baro();
1988 WITH_SEMAPHORE(baro.get_semaphore());
1989 vspd = baro.get_climb_rate();
1991 char sym;
1992 if (vspd > 3.0f) {
1993 sym = SYMBOL(SYM_UP_UP);
1994 } else if (vspd >=0.0f) {
1995 sym = SYMBOL(SYM_UP);
1996 } else if (vspd >= -3.0f) {
1997 sym = SYMBOL(SYM_DOWN);
1998 } else {
1999 sym = SYMBOL(SYM_DOWN_DOWN);
2001 vs_scaled = u_scale(VSPEED, fabsf(vspd));
2002 if ((osd->units != AP_OSD::UNITS_AVIATION) && (vs_scaled < 9.95f)) {
2003 backend->write(x, y, false, "%c%.1f%c", sym, (float)vs_scaled, u_icon(VSPEED));
2004 } else {
2005 const char *fmt = osd->units == AP_OSD::UNITS_AVIATION ? "%c%4d%c" : "%c%2d%c";
2006 backend->write(x, y, false, fmt, sym, (int)roundf(vs_scaled), u_icon(VSPEED));
2010 #if HAL_WITH_ESC_TELEM
2011 void AP_OSD_Screen::draw_esc_temp(uint8_t x, uint8_t y)
2013 int16_t etemp;
2015 if (esc_index > 0) {
2016 if (!AP::esc_telem().get_temperature(esc_index-1, etemp)) {
2017 return;
2020 else if (!AP::esc_telem().get_highest_temperature(etemp)) {
2021 return;
2024 backend->write(x, y, false, "%3d%c", (int)u_scale(TEMPERATURE, etemp / 100), u_icon(TEMPERATURE));
2027 void AP_OSD_Screen::draw_esc_rpm(uint8_t x, uint8_t y)
2029 float rpm;
2030 uint8_t esc = AP::esc_telem().get_max_rpm_esc();
2031 if (esc_index > 0) {
2032 if (!AP::esc_telem().get_rpm(esc_index-1, rpm)) {
2033 return;
2035 } else if (!AP::esc_telem().get_rpm(esc, rpm)) {
2036 return;
2038 float krpm = rpm * 0.001f;
2039 const char *format = krpm < 9.995 ? "%.2f%c%c" : (krpm < 99.95 ? "%.1f%c%c" : "%.0f%c%c");
2040 backend->write(x, y, false, format, krpm, SYMBOL(SYM_KILO), SYMBOL(SYM_RPM));
2043 void AP_OSD_Screen::draw_esc_amps(uint8_t x, uint8_t y)
2045 float amps;
2046 uint8_t esc = AP::esc_telem().get_max_rpm_esc();
2047 if (esc_index > 0) {
2048 if (!AP::esc_telem().get_current(esc_index-1, amps)) {
2049 return;
2051 } else if (!AP::esc_telem().get_current(esc, amps)) {
2052 return;
2054 backend->write(x, y, false, "%4.1f%c", amps, SYMBOL(SYM_AMP));
2056 #endif
2058 #if AP_OSD_EXTENDED_LNK_STATS
2059 bool AP_OSD_Screen::is_btfl_fonts()
2061 const AP_MSP *p_msp = AP::msp();
2062 return (p_msp != nullptr && p_msp->is_option_enabled(AP_MSP::Option::DISPLAYPORT_BTFL_SYMBOLS));
2065 void AP_OSD_Screen::draw_rc_tx_power(uint8_t x, uint8_t y)
2067 const int16_t tx_power = AP::crsf()->get_link_status().tx_power;
2068 bool btfl = is_btfl_fonts();
2069 if (tx_power > 0) {
2070 if (tx_power < 1000) {
2071 if (btfl) {
2072 backend->write(x, y, false, "%3d%cW", tx_power, SYMBOL(SYM_ALT_M)); // SYM_ALT_M (0x0C) is the BTFL character for a small "m"
2073 } else {
2074 backend->write(x, y, false, "%3d%c", tx_power, SYMBOL(SYM_MW));
2076 } else {
2077 const float value_w = float(tx_power) * 0.001f;
2078 if (btfl) {
2079 backend->write(x, y, false, "%.2fW", value_w);
2080 } else {
2081 backend->write(x, y, false, "%.2f%c", value_w, SYMBOL(SYM_WATT));
2084 } else {
2085 if (btfl) {
2086 backend->write(x, y, false, "---%cW", SYMBOL(SYM_ALT_M));
2087 } else {
2088 backend->write(x, y, false, "---%c", SYMBOL(SYM_MW));
2093 void AP_OSD_Screen::draw_rc_rssi_dbm(uint8_t x, uint8_t y)
2095 const int8_t rssidbm = AP::crsf()->get_link_status().rssi_dbm;
2096 const bool blink = -rssidbm < osd->warn_rssi;
2097 bool btfl = is_btfl_fonts();
2099 backend->write(x, y, blink, "%c", SYMBOL(SYM_RSSI));
2100 uint8_t new_x = x + 1;
2101 if (rssidbm >= 0) {
2102 if (btfl) {
2103 backend->write(new_x, y, blink, "%4dDBM", -rssidbm);
2104 } else {
2105 backend->write(new_x, y, blink, "%4d%c", -rssidbm, SYMBOL(SYM_DBM));
2107 } else {
2108 if (btfl){
2109 backend->write(new_x, y, blink, "----DBM");
2110 } else {
2111 backend->write(new_x, y, blink, "----%c", SYMBOL(SYM_DBM));
2116 void AP_OSD_Screen::draw_rc_snr(uint8_t x, uint8_t y)
2118 const int8_t snr = AP::crsf()->get_link_status().snr;
2119 const bool blink = snr < osd->warn_snr;
2120 bool btfl = is_btfl_fonts();
2121 if (snr == INT8_MIN) {
2122 if (btfl) {
2123 backend->write(x, y, blink, "SNR---DB");
2124 } else {
2125 backend->write(x, y, blink, "%c---%c", SYMBOL(SYM_SNR), SYMBOL(SYM_DB));
2127 } else {
2128 if (btfl) {
2129 backend->write(x, y, blink, "SNR%3dDB", snr);
2130 } else {
2131 backend->write(x, y, blink, "%c%3d%c", SYMBOL(SYM_SNR), snr, SYMBOL(SYM_DB));
2136 void AP_OSD_Screen::draw_rc_active_antenna(uint8_t x, uint8_t y)
2138 const int8_t active_antenna = AP::crsf()->get_link_status().active_antenna;
2139 bool btfl = is_btfl_fonts();
2140 if (active_antenna < 0) {
2141 if (btfl) {
2142 backend->write(x, y, false, "ANT-");
2143 } else {
2144 backend->write(x, y, false, "%c-", SYMBOL(SYM_ANT));
2146 } else {
2147 if (btfl) {
2148 backend->write(x, y, false, "ANT%d", active_antenna + 1);
2149 } else {
2150 backend->write(x, y, false, "%c%d", SYMBOL(SYM_ANT), active_antenna + 1);
2155 void AP_OSD_Screen::draw_rc_lq(uint8_t x, uint8_t y)
2157 const int16_t lqv = AP::crsf()->get_link_status().link_quality;
2158 const bool blink = lqv < osd->warn_lq;
2159 bool btfl = is_btfl_fonts();
2160 bool prefix_rf = check_option(AP_OSD::OPTION_RF_MODE_ALONG_WITH_LQ);
2161 const int16_t rf_mode = AP::crsf()->get_link_status().rf_mode;
2162 if (lqv < 0) {
2163 if (btfl) {
2164 if (prefix_rf) {
2165 backend->write(x, y, blink, "LQ--:--");
2166 } else {
2167 backend->write(x, y, blink, "LQ--");
2169 } else {
2170 if (prefix_rf) {
2171 backend->write(x, y, blink, "%c--:--", SYMBOL(SYM_LQ));
2172 } else {
2173 backend->write(x, y, blink, "%c--", SYMBOL(SYM_LQ));
2176 } else {
2177 if (btfl) {
2178 if (prefix_rf) {
2179 backend->write(x, y, blink, "LQ%2d:%2d", rf_mode, lqv);
2180 } else {
2181 backend->write(x, y, blink, "LQ%2d", lqv);
2183 } else {
2184 if(prefix_rf) {
2185 backend->write(x, y, blink, "%c%2d:%2d", SYMBOL(SYM_LQ), rf_mode, lqv);
2186 } else {
2187 backend->write(x, y, blink, "%c%2d", SYMBOL(SYM_LQ), lqv);
2192 #endif // AP_OSD_EXTENDED_LNK_STATS
2194 void AP_OSD_Screen::draw_gps_latitude(uint8_t x, uint8_t y)
2196 AP_GPS & gps = AP::gps();
2197 const Location &loc = gps.location(); // loc.lat and loc.lng
2198 int32_t dec_portion, frac_portion;
2199 int32_t abs_lat = labs(loc.lat);
2201 dec_portion = loc.lat / 10000000L;
2202 frac_portion = abs_lat - labs(dec_portion)*10000000UL;
2204 backend->write(x, y, false, "%c%4ld.%07ld", SYMBOL(SYM_GPS_LAT), (long)dec_portion,(long)frac_portion);
2207 void AP_OSD_Screen::draw_gps_longitude(uint8_t x, uint8_t y)
2209 AP_GPS & gps = AP::gps();
2210 const Location &loc = gps.location(); // loc.lat and loc.lng
2211 int32_t dec_portion, frac_portion;
2212 int32_t abs_lon = labs(loc.lng);
2214 dec_portion = loc.lng / 10000000L;
2215 frac_portion = abs_lon - labs(dec_portion)*10000000UL;
2217 backend->write(x, y, false, "%c%4ld.%07ld", SYMBOL(SYM_GPS_LONG), (long)dec_portion,(long)frac_portion);
2220 void AP_OSD_Screen::draw_roll_angle(uint8_t x, uint8_t y)
2222 AP_AHRS &ahrs = AP::ahrs();
2223 uint16_t roll = abs(ahrs.roll_sensor) / 100;
2224 char r;
2225 if (ahrs.roll_sensor > 50) {
2226 r = SYMBOL(SYM_ROLLR);
2227 } else if (ahrs.roll_sensor < -50) {
2228 r = SYMBOL(SYM_ROLLL);
2229 } else {
2230 r = SYMBOL(SYM_ROLL0);
2232 backend->write(x, y, false, "%c%3d%c", r, roll, SYMBOL(SYM_DEGR));
2235 void AP_OSD_Screen::draw_pitch_angle(uint8_t x, uint8_t y)
2237 AP_AHRS &ahrs = AP::ahrs();
2238 uint16_t pitch = abs(ahrs.pitch_sensor) / 100;
2239 char p;
2240 if (ahrs.pitch_sensor > 50) {
2241 p = SYMBOL(SYM_PTCHUP);
2242 } else if (ahrs.pitch_sensor < -50) {
2243 p = SYMBOL(SYM_PTCHDWN);
2244 } else {
2245 p = SYMBOL(SYM_PTCH0);
2247 backend->write(x, y, false, "%c%3d%c", p, pitch, SYMBOL(SYM_DEGR));
2250 void AP_OSD_Screen::draw_temp(uint8_t x, uint8_t y)
2252 AP_Baro &barometer = AP::baro();
2253 float tmp = barometer.get_temperature();
2254 backend->write(x, y, false, "%3d%c", (int)u_scale(TEMPERATURE, tmp), u_icon(TEMPERATURE));
2258 void AP_OSD_Screen::draw_hdop(uint8_t x, uint8_t y)
2260 AP_GPS & gps = AP::gps();
2261 float hdp = gps.get_hdop() * 0.01f;
2262 backend->write(x, y, false, "%c%c%3.2f", SYMBOL(SYM_HDOP_L), SYMBOL(SYM_HDOP_R), (double)hdp);
2265 void AP_OSD_Screen::draw_waypoint(uint8_t x, uint8_t y)
2267 AP_AHRS &ahrs = AP::ahrs();
2268 int32_t angle_cd = osd->nav_info.wp_bearing - ahrs.yaw_sensor;
2269 if (osd->nav_info.wp_distance < 2.0f) {
2270 //avoid fast rotating arrow at small distances
2271 angle_cd = 0;
2273 char arrow = get_arrow_font_index(angle_cd);
2274 backend->write(x,y, false, "%c%2u%c",SYMBOL(SYM_WPNO), osd->nav_info.wp_number, arrow);
2275 draw_distance(x+4, y, osd->nav_info.wp_distance);
2278 void AP_OSD_Screen::draw_xtrack_error(uint8_t x, uint8_t y)
2280 backend->write(x, y, false, "%c", SYMBOL(SYM_XERR));
2281 draw_distance(x+1, y, osd->nav_info.wp_xtrack_error);
2284 void AP_OSD_Screen::draw_stat(uint8_t x, uint8_t y)
2286 backend->write(x+2, y, false, "%c%c%c", 0x4d,0x41,0x58);
2287 backend->write(x, y+1, false, "%c",SYMBOL(SYM_GSPD));
2288 backend->write(x+1, y+1, false, "%4d%c", (int)u_scale(SPEED, osd->_stats.max_speed_mps), u_icon(SPEED));
2289 backend->write(x, y+2, false, "%5.1f%c", (double)osd->_stats.max_current_a, SYMBOL(SYM_AMP));
2290 backend->write(x, y+3, false, "%5d%c", (int)u_scale(ALTITUDE, osd->_stats.max_alt_m), u_icon(ALTITUDE));
2291 backend->write(x, y+4, false, "%c", SYMBOL(SYM_HOME));
2292 draw_distance(x+1, y+4, osd->_stats.max_dist_m);
2293 backend->write(x, y+5, false, "%c", SYMBOL(SYM_DIST));
2294 draw_distance(x+1, y+5, osd->_stats.last_distance_m);
2297 void AP_OSD_Screen::draw_dist(uint8_t x, uint8_t y)
2299 backend->write(x, y, false, "%c", SYMBOL(SYM_DIST));
2300 draw_distance(x+1, y, osd->_stats.last_distance_m);
2303 void AP_OSD_Screen::draw_flightime(uint8_t x, uint8_t y)
2305 AP_Stats *stats = AP::stats();
2306 if (stats) {
2307 uint32_t t = stats->get_flight_time_s();
2308 backend->write(x, y, false, "%c%3u:%02u", SYMBOL(SYM_FLY), unsigned(t/60), unsigned(t%60));
2312 #if AP_BATTERY_ENABLED
2313 void AP_OSD_Screen::draw_eff(uint8_t x, uint8_t y)
2315 AP_BattMonitor &battery = AP::battery();
2316 Vector2f v;
2318 AP_AHRS &ahrs = AP::ahrs();
2319 WITH_SEMAPHORE(ahrs.get_semaphore());
2320 v = ahrs.groundspeed_vector();
2322 float speed = u_scale(SPEED,v.length());
2323 float current_amps;
2324 if ((speed > 2.0) && battery.current_amps(current_amps)) {
2325 backend->write(x, y, false, "%c%3d%c", SYMBOL(SYM_EFF),int(1000.0f*current_amps/speed),SYMBOL(SYM_MAH));
2326 } else {
2327 backend->write(x, y, false, "%c---%c", SYMBOL(SYM_EFF),SYMBOL(SYM_MAH));
2330 #endif // AP_BATTERY_ENABLED
2332 #if AP_BATTERY_ENABLED
2333 void AP_OSD_Screen::draw_climbeff(uint8_t x, uint8_t y)
2335 char unit_icon = u_icon(DISTANCE);
2336 Vector3f v;
2337 float vspd;
2338 do {
2340 auto &ahrs = AP::ahrs();
2341 WITH_SEMAPHORE(ahrs.get_semaphore());
2342 if (ahrs.get_velocity_NED(v)) {
2343 vspd = -v.z;
2344 break;
2347 auto &baro = AP::baro();
2348 WITH_SEMAPHORE(baro.get_semaphore());
2349 vspd = baro.get_climb_rate();
2350 } while (false);
2351 if (vspd < 0.0) {
2352 vspd = 0.0;
2354 AP_BattMonitor &battery = AP::battery();
2355 float amps;
2356 if (battery.current_amps(amps) && is_positive(amps)) {
2357 backend->write(x, y, false,"%c%c%3.1f%c",SYMBOL(SYM_PTCHUP),SYMBOL(SYM_EFF),(double)(3.6f * u_scale(VSPEED,vspd)/amps),unit_icon);
2358 } else {
2359 backend->write(x, y, false,"%c%c---%c",SYMBOL(SYM_PTCHUP),SYMBOL(SYM_EFF),unit_icon);
2362 #endif
2364 #if BARO_MAX_INSTANCES > 1
2365 void AP_OSD_Screen::draw_btemp(uint8_t x, uint8_t y)
2367 AP_Baro &barometer = AP::baro();
2368 float btmp = barometer.get_temperature(1);
2369 backend->write(x, y, false, "%3d%c", (int)u_scale(TEMPERATURE, btmp), u_icon(TEMPERATURE));
2371 #endif
2373 void AP_OSD_Screen::draw_atemp(uint8_t x, uint8_t y)
2375 #if AP_AIRSPEED_ENABLED
2376 AP_Airspeed *airspeed = AP_Airspeed::get_singleton();
2377 if (!airspeed) {
2378 return;
2380 float temperature = 0;
2381 airspeed->get_temperature(temperature);
2382 if (airspeed->healthy()) {
2383 backend->write(x, y, false, "%3d%c", (int)u_scale(TEMPERATURE, temperature), u_icon(TEMPERATURE));
2384 } else {
2385 backend->write(x, y, false, "--%c", u_icon(TEMPERATURE));
2387 #endif
2390 void AP_OSD_Screen::draw_bat2_vlt(uint8_t x, uint8_t y)
2392 draw_bat_volt(1,VoltageType::VOLTAGE,x,y);
2395 void AP_OSD_Screen::draw_bat2used(uint8_t x, uint8_t y)
2397 draw_batused(1, x, y);
2400 void AP_OSD_Screen::draw_aspd1(uint8_t x, uint8_t y)
2402 #if AP_AIRSPEED_ENABLED
2403 AP_Airspeed *airspeed = AP_Airspeed::get_singleton();
2404 if (!airspeed) {
2405 return;
2407 float asp1 = airspeed->get_airspeed();
2408 if (airspeed != nullptr && airspeed->healthy()) {
2409 backend->write(x, y, false, "%c%4d%c", SYMBOL(SYM_ASPD), (int)u_scale(SPEED, asp1), u_icon(SPEED));
2410 } else {
2411 backend->write(x, y, false, "%c ---%c", SYMBOL(SYM_ASPD), u_icon(SPEED));
2413 #endif
2416 void AP_OSD_Screen::draw_aspd2(uint8_t x, uint8_t y)
2418 #if AP_AIRSPEED_ENABLED
2419 AP_Airspeed *airspeed = AP_Airspeed::get_singleton();
2420 if (!airspeed) {
2421 return;
2423 float asp2 = airspeed->get_airspeed(1);
2424 if (airspeed != nullptr && airspeed->healthy(1)) {
2425 backend->write(x, y, false, "%c%4d%c", SYMBOL(SYM_ASPD), (int)u_scale(SPEED, asp2), u_icon(SPEED));
2426 } else {
2427 backend->write(x, y, false, "%c ---%c", SYMBOL(SYM_ASPD), u_icon(SPEED));
2429 #endif
2432 #if AP_RTC_ENABLED
2433 void AP_OSD_Screen::draw_clk(uint8_t x, uint8_t y)
2435 AP_RTC &rtc = AP::rtc();
2436 uint8_t hour, min, sec;
2437 uint16_t ms;
2438 if (!rtc.get_local_time(hour, min, sec, ms)) {
2439 backend->write(x, y, false, "%c--:--", SYMBOL(SYM_CLK));
2440 } else {
2441 backend->write(x, y, false, "%c%02u:%02u", SYMBOL(SYM_CLK), hour, min);
2444 #endif
2446 #if HAL_PLUSCODE_ENABLE
2447 void AP_OSD_Screen::draw_pluscode(uint8_t x, uint8_t y)
2449 AP_GPS & gps = AP::gps();
2450 const Location &loc = gps.location();
2451 char buff[16];
2452 if (gps.status() == AP_GPS::NO_GPS || gps.status() == AP_GPS::NO_FIX){
2453 backend->write(x, y, false, "--------+--");
2454 } else {
2455 AP_OLC::olc_encode(loc.lat, loc.lng, 10, buff, sizeof(buff));
2456 backend->write(x, y, false, "%s", buff);
2459 #endif
2462 support callsign display from a file called callsign.txt
2464 void AP_OSD_Screen::draw_callsign(uint8_t x, uint8_t y)
2466 #if AP_OSD_CALLSIGN_FROM_SD_ENABLED
2467 if (!callsign_data.load_attempted) {
2468 callsign_data.load_attempted = true;
2469 FileData *fd = AP::FS().load_file("callsign.txt");
2470 if (fd != nullptr) {
2471 uint32_t len = fd->length;
2472 // trim off whitespace
2473 while (len > 0 && isspace(fd->data[len-1])) {
2474 len--;
2476 callsign_data.str = strndup((const char *)fd->data, len);
2477 delete fd;
2480 if (callsign_data.str != nullptr) {
2481 backend->write(x, y, false, "%s", callsign_data.str);
2483 #endif
2486 void AP_OSD_Screen::draw_current2(uint8_t x, uint8_t y)
2488 draw_current(1, x, y);
2491 #if AP_VIDEOTX_ENABLED
2492 void AP_OSD_Screen::draw_vtx_power(uint8_t x, uint8_t y)
2494 AP_VideoTX *vtx = AP_VideoTX::get_singleton();
2495 if (!vtx) {
2496 return;
2498 uint16_t powr = 0;
2499 // If currently in pit mode, just render 0mW to the screen
2500 if(!vtx->has_option(AP_VideoTX::VideoOptions::VTX_PITMODE)){
2501 powr = vtx->get_power_mw();
2503 backend->write(x, y, !vtx->is_configuration_finished(), "%4hu%c", powr, SYMBOL(SYM_MW));
2505 #endif // AP_VIDEOTX_ENABLED
2507 #if AP_TERRAIN_AVAILABLE
2508 void AP_OSD_Screen::draw_hgt_abvterr(uint8_t x, uint8_t y)
2510 AP_Terrain *terrain = AP::terrain();
2512 float terrain_altitude;
2513 if (terrain != nullptr && terrain->height_above_terrain(terrain_altitude,true)) {
2514 bool blink = (osd->warn_terr != -1)? (terrain_altitude < osd->warn_terr) : false; //blink if warn_terr is not disabled and alt above terrain is below warning value
2515 backend->write(x, y, blink, "%4d%c%c", (int)u_scale(ALTITUDE, terrain_altitude), u_icon(ALTITUDE), SYMBOL(SYM_TERALT));
2516 } else {
2517 backend->write(x, y, false, " ---%c%c", u_icon(ALTITUDE),SYMBOL(SYM_TERALT));
2520 #endif
2522 #if AP_FENCE_ENABLED
2523 void AP_OSD_Screen::draw_fence(uint8_t x, uint8_t y)
2525 AC_Fence *fenceptr = AP::fence();
2526 if (fenceptr == nullptr) {
2527 return;
2529 if (fenceptr->enabled() && fenceptr->present()) {
2530 backend->write(x, y, fenceptr->get_breaches(), "%c", SYMBOL(SYM_FENCE_ENABLED));
2531 } else {
2532 backend->write(x, y, false, "%c", SYMBOL(SYM_FENCE_DISABLED));
2535 #endif
2537 #if AP_RANGEFINDER_ENABLED
2538 void AP_OSD_Screen::draw_rngf(uint8_t x, uint8_t y)
2540 RangeFinder *rangefinder = RangeFinder::get_singleton();
2541 if (rangefinder == nullptr) {
2542 return;
2544 if (rangefinder->status_orient(ROTATION_PITCH_270) < RangeFinder::Status::Good) {
2545 backend->write(x, y, false, "%c---%c", SYMBOL(SYM_RNGFD), u_icon(DISTANCE));
2546 } else {
2547 const float distance = rangefinder->distance_orient(ROTATION_PITCH_270);
2548 backend->write(x, y, false, "%c%4.1f%c", SYMBOL(SYM_RNGFD), u_scale(DISTANCE, distance), u_icon(DISTANCE));
2551 #endif
2553 #define DRAW_SETTING(n) if (n.enabled) draw_ ## n(n.xpos, n.ypos)
2555 #if HAL_WITH_OSD_BITMAP || HAL_WITH_MSP_DISPLAYPORT
2556 void AP_OSD_Screen::draw(void)
2558 if (!enabled || !backend) {
2559 return;
2561 //Note: draw order should be optimized.
2562 //Big and less important items should be drawn first,
2563 //so they will not overwrite more important ones.
2564 #if HAL_OSD_SIDEBAR_ENABLE
2565 DRAW_SETTING(sidebars);
2566 #endif
2568 DRAW_SETTING(message);
2569 DRAW_SETTING(horizon);
2570 DRAW_SETTING(compass);
2571 DRAW_SETTING(altitude);
2573 #if AP_TERRAIN_AVAILABLE
2574 DRAW_SETTING(hgt_abvterr);
2575 #endif
2577 #if AP_RANGEFINDER_ENABLED
2578 DRAW_SETTING(rngf);
2579 #endif
2580 DRAW_SETTING(waypoint);
2581 DRAW_SETTING(xtrack_error);
2582 DRAW_SETTING(bat_volt);
2583 DRAW_SETTING(bat2_vlt);
2584 DRAW_SETTING(avgcellvolt);
2585 DRAW_SETTING(avgcellrestvolt);
2586 DRAW_SETTING(restvolt);
2587 #if AP_RSSI_ENABLED
2588 DRAW_SETTING(rssi);
2589 DRAW_SETTING(link_quality);
2590 #endif
2591 DRAW_SETTING(current);
2592 DRAW_SETTING(batused);
2593 DRAW_SETTING(bat2used);
2594 DRAW_SETTING(sats);
2595 DRAW_SETTING(fltmode);
2596 DRAW_SETTING(gspeed);
2597 DRAW_SETTING(aspeed);
2598 DRAW_SETTING(aspd1);
2599 DRAW_SETTING(aspd2);
2600 DRAW_SETTING(vspeed);
2601 DRAW_SETTING(throttle);
2602 DRAW_SETTING(heading);
2603 DRAW_SETTING(wind);
2604 DRAW_SETTING(home);
2605 #if AP_RPM_ENABLED
2606 DRAW_SETTING(rrpm);
2607 #endif
2608 #if AP_FENCE_ENABLED
2609 DRAW_SETTING(fence);
2610 #endif
2611 DRAW_SETTING(roll_angle);
2612 DRAW_SETTING(pitch_angle);
2613 DRAW_SETTING(temp);
2614 #if BARO_MAX_INSTANCES > 1
2615 DRAW_SETTING(btemp);
2616 #endif
2617 DRAW_SETTING(atemp);
2618 DRAW_SETTING(hdop);
2619 DRAW_SETTING(flightime);
2620 #if AP_RTC_ENABLED
2621 DRAW_SETTING(clk);
2622 #endif
2623 #if AP_VIDEOTX_ENABLED
2624 DRAW_SETTING(vtx_power);
2625 #endif
2627 #if HAL_WITH_ESC_TELEM
2628 DRAW_SETTING(esc_temp);
2629 DRAW_SETTING(esc_rpm);
2630 DRAW_SETTING(esc_amps);
2631 #endif
2633 DRAW_SETTING(gps_latitude);
2634 DRAW_SETTING(gps_longitude);
2635 #if HAL_PLUSCODE_ENABLE
2636 DRAW_SETTING(pluscode);
2637 #endif
2638 DRAW_SETTING(dist);
2639 DRAW_SETTING(stat);
2640 DRAW_SETTING(climbeff);
2641 DRAW_SETTING(eff);
2642 DRAW_SETTING(callsign);
2643 DRAW_SETTING(current2);
2645 #if AP_OSD_EXTENDED_LNK_STATS
2646 DRAW_SETTING(rc_tx_power);
2647 DRAW_SETTING(rc_rssi_dbm);
2648 DRAW_SETTING(rc_snr);
2649 DRAW_SETTING(rc_active_antenna);
2650 DRAW_SETTING(rc_lq);
2651 #endif
2653 #endif
2654 #endif // OSD_ENABLED