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"
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>
51 #include <AP_Filesystem/AP_Filesystem.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>
62 const AP_Param::GroupInfo
AP_OSD_Screen::var_info
[] = {
65 // @DisplayName: Enable screen
66 // @Description: Enable this screen
67 // @Values: 0:Disabled,1:Enabled
69 AP_GROUPINFO_FLAGS("ENABLE", 1, AP_OSD_Screen
, enabled
, 0, AP_PARAM_FLAG_ENABLE
),
72 // @DisplayName: Transmitter switch screen minimum pwm
73 // @Description: This sets the PWM lower limit for this screen
76 AP_GROUPINFO("CHAN_MIN", 2, AP_OSD_Screen
, channel_min
, 900),
79 // @DisplayName: Transmitter switch screen maximum pwm
80 // @Description: This sets the PWM upper limit for this screen
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
91 // @DisplayName: ALTITUDE_X
92 // @Description: Horizontal position on screen
96 // @DisplayName: ALTITUDE_Y
97 // @Description: Vertical position on screen
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
111 // @Param: BAT_VOLT_Y
112 // @DisplayName: BATVOLT_Y
113 // @Description: Vertical position on screen
115 AP_SUBGROUPINFO(bat_volt
, "BAT_VOLT", 5, AP_OSD_Screen
, AP_OSD_Setting
),
118 // @DisplayName: RSSI_EN
119 // @Description: Displays RC signal strength
120 // @Values: 0:Disabled,1:Enabled
123 // @DisplayName: RSSI_X
124 // @Description: Horizontal position on screen
128 // @DisplayName: RSSI_Y
129 // @Description: Vertical position on screen
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
139 // @DisplayName: CURRENT_X
140 // @Description: Horizontal position on screen
144 // @DisplayName: CURRENT_Y
145 // @Description: Vertical position on screen
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
155 // @DisplayName: BATUSED_X
156 // @Description: Horizontal position on screen
160 // @DisplayName: BATUSED_Y
161 // @Description: Vertical position on screen
163 AP_SUBGROUPINFO(batused
, "BATUSED", 8, AP_OSD_Screen
, AP_OSD_Setting
),
166 // @DisplayName: SATS_EN
167 // @Description: Displays number of acquired satellites
168 // @Values: 0:Disabled,1:Enabled
171 // @DisplayName: SATS_X
172 // @Description: Horizontal position on screen
176 // @DisplayName: SATS_Y
177 // @Description: Vertical position on screen
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
187 // @DisplayName: FLTMODE_X
188 // @Description: Horizontal position on screen
192 // @DisplayName: FLTMODE_Y
193 // @Description: Vertical position on screen
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
203 // @DisplayName: MESSAGE_X
204 // @Description: Horizontal position on screen
208 // @DisplayName: MESSAGE_Y
209 // @Description: Vertical position on screen
211 AP_SUBGROUPINFO(message
, "MESSAGE", 11, AP_OSD_Screen
, AP_OSD_Setting
),
214 // @DisplayName: GSPEED_EN
215 // @Description: Displays GPS ground speed
216 // @Values: 0:Disabled,1:Enabled
219 // @DisplayName: GSPEED_X
220 // @Description: Horizontal position on screen
224 // @DisplayName: GSPEED_Y
225 // @Description: Vertical position on screen
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
235 // @DisplayName: HORIZON_X
236 // @Description: Horizontal position on screen
240 // @DisplayName: HORIZON_Y
241 // @Description: Vertical position on screen
243 AP_SUBGROUPINFO(horizon
, "HORIZON", 13, AP_OSD_Screen
, AP_OSD_Setting
),
246 // @DisplayName: HOME_EN
247 // @Description: Displays distance and relative direction to HOME
248 // @Values: 0:Disabled,1:Enabled
251 // @DisplayName: HOME_X
252 // @Description: Horizontal position on screen
256 // @DisplayName: HOME_Y
257 // @Description: Vertical position on screen
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
267 // @DisplayName: HEADING_X
268 // @Description: Horizontal position on screen
272 // @DisplayName: HEADING_Y
273 // @Description: Vertical position on screen
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
287 // @Param: THROTTLE_Y
288 // @DisplayName: THROTTLE_Y
289 // @Description: Vertical position on screen
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
299 // @DisplayName: COMPASS_X
300 // @Description: Horizontal position on screen
304 // @DisplayName: COMPASS_Y
305 // @Description: Vertical position on screen
307 AP_SUBGROUPINFO(compass
, "COMPASS", 17, AP_OSD_Screen
, AP_OSD_Setting
),
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
315 // @DisplayName: WIND_X
316 // @Description: Horizontal position on screen
320 // @DisplayName: WIND_Y
321 // @Description: Vertical position on screen
323 AP_SUBGROUPINFO(wind
, "WIND", 18, AP_OSD_Screen
, AP_OSD_Setting
),
327 // @DisplayName: ASPEED_EN
328 // @Description: Displays airspeed value being used by TECS (fused value)
329 // @Values: 0:Disabled,1:Enabled
332 // @DisplayName: ASPEED_X
333 // @Description: Horizontal position on screen
337 // @DisplayName: ASPEED_Y
338 // @Description: Vertical position on screen
340 AP_SUBGROUPINFO(aspeed
, "ASPEED", 19, AP_OSD_Screen
, AP_OSD_Setting
),
343 // @DisplayName: VSPEED_EN
344 // @Description: Displays climb rate
345 // @Values: 0:Disabled,1:Enabled
348 // @DisplayName: VSPEED_X
349 // @Description: Horizontal position on screen
353 // @DisplayName: VSPEED_Y
354 // @Description: Vertical position on screen
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
365 // @DisplayName: ESCTEMP_X
366 // @Description: Horizontal position on screen
370 // @DisplayName: ESCTEMP_Y
371 // @Description: Vertical position on screen
373 AP_SUBGROUPINFO(esc_temp
, "ESCTEMP", 21, AP_OSD_Screen
, AP_OSD_Setting
),
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
381 // @DisplayName: ESCRPM_X
382 // @Description: Horizontal position on screen
386 // @DisplayName: ESCRPM_Y
387 // @Description: Vertical position on screen
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
397 // @DisplayName: ESCAMPS_X
398 // @Description: Horizontal position on screen
402 // @DisplayName: ESCAMPS_Y
403 // @Description: Vertical position on screen
405 AP_SUBGROUPINFO(esc_amps
, "ESCAMPS", 23, AP_OSD_Screen
, AP_OSD_Setting
),
408 // @DisplayName: GPSLAT_EN
409 // @Description: Displays GPS latitude
410 // @Values: 0:Disabled,1:Enabled
413 // @DisplayName: GPSLAT_X
414 // @Description: Horizontal position on screen
418 // @DisplayName: GPSLAT_Y
419 // @Description: Vertical position on screen
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
429 // @DisplayName: GPSLONG_X
430 // @Description: Horizontal position on screen
434 // @DisplayName: GPSLONG_Y
435 // @Description: Vertical position on screen
437 AP_SUBGROUPINFO(gps_longitude
, "GPSLONG", 25, AP_OSD_Screen
, AP_OSD_Setting
),
440 // @DisplayName: ROLL_EN
441 // @Description: Displays degrees of roll from level
442 // @Values: 0:Disabled,1:Enabled
445 // @DisplayName: ROLL_X
446 // @Description: Horizontal position on screen
450 // @DisplayName: ROLL_Y
451 // @Description: Vertical position on screen
453 AP_SUBGROUPINFO(roll_angle
, "ROLL", 26, AP_OSD_Screen
, AP_OSD_Setting
),
456 // @DisplayName: PITCH_EN
457 // @Description: Displays degrees of pitch from level
458 // @Values: 0:Disabled,1:Enabled
461 // @DisplayName: PITCH_X
462 // @Description: Horizontal position on screen
466 // @DisplayName: PITCH_Y
467 // @Description: Vertical position on screen
469 AP_SUBGROUPINFO(pitch_angle
, "PITCH", 27, AP_OSD_Screen
, AP_OSD_Setting
),
472 // @DisplayName: TEMP_EN
473 // @Description: Displays temperature reported by primary barometer
474 // @Values: 0:Disabled,1:Enabled
477 // @DisplayName: TEMP_X
478 // @Description: Horizontal position on screen
482 // @DisplayName: TEMP_Y
483 // @Description: Vertical position on screen
485 AP_SUBGROUPINFO(temp
, "TEMP", 28, AP_OSD_Screen
, AP_OSD_Setting
),
488 // @DisplayName: HDOP_EN
489 // @Description: Displays Horizontal Dilution Of Position
490 // @Values: 0:Disabled,1:Enabled
493 // @DisplayName: HDOP_X
494 // @Description: Horizontal position on screen
498 // @DisplayName: HDOP_Y
499 // @Description: Vertical position on screen
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
513 // @Param: WAYPOINT_Y
514 // @DisplayName: WAYPOINT_Y
515 // @Description: Vertical position on screen
517 AP_SUBGROUPINFO(waypoint
, "WAYPOINT", 30, AP_OSD_Screen
, AP_OSD_Setting
),
520 // @DisplayName: XTRACK_EN
521 // @Description: Displays crosstrack error
522 // @Values: 0:Disabled,1:Enabled
525 // @DisplayName: XTRACK_X
526 // @Description: Horizontal position on screen
530 // @DisplayName: XTRACK_Y
531 // @Description: Vertical position on screen
533 AP_SUBGROUPINFO(xtrack_error
, "XTRACK", 31, AP_OSD_Screen
, AP_OSD_Setting
),
536 // @DisplayName: DIST_EN
537 // @Description: Displays total distance flown
538 // @Values: 0:Disabled,1:Enabled
541 // @DisplayName: DIST_X
542 // @Description: Horizontal position on screen
546 // @DisplayName: DIST_Y
547 // @Description: Vertical position on screen
549 AP_SUBGROUPINFO(dist
, "DIST", 32, AP_OSD_Screen
, AP_OSD_Setting
),
552 // @DisplayName: STATS_EN
553 // @Description: Displays flight stats
554 // @Values: 0:Disabled,1:Enabled
557 // @DisplayName: STATS_X
558 // @Description: Horizontal position on screen
562 // @DisplayName: STATS_Y
563 // @Description: Vertical position on screen
565 AP_SUBGROUPINFO(stat
, "STATS", 33, AP_OSD_Screen
, AP_OSD_Setting
),
568 // @DisplayName: FLTIME_EN
569 // @Description: Displays total flight time
570 // @Values: 0:Disabled,1:Enabled
573 // @DisplayName: FLTIME_X
574 // @Description: Horizontal position on screen
578 // @DisplayName: FLTIME_Y
579 // @Description: Vertical position on screen
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
593 // @Param: CLIMBEFF_Y
594 // @DisplayName: CLIMBEFF_Y
595 // @Description: Vertical position on screen
597 AP_SUBGROUPINFO(climbeff
, "CLIMBEFF", 35, AP_OSD_Screen
, AP_OSD_Setting
),
600 // @DisplayName: EFF_EN
601 // @Description: Displays flight efficiency (mAh/km or /mi)
602 // @Values: 0:Disabled,1:Enabled
605 // @DisplayName: EFF_X
606 // @Description: Horizontal position on screen
610 // @DisplayName: EFF_Y
611 // @Description: Vertical position on screen
613 AP_SUBGROUPINFO(eff
, "EFF", 36, AP_OSD_Screen
, AP_OSD_Setting
),
615 #if BARO_MAX_INSTANCES > 1
617 // @DisplayName: BTEMP_EN
618 // @Description: Displays temperature reported by secondary barometer
619 // @Values: 0:Disabled,1:Enabled
622 // @DisplayName: BTEMP_X
623 // @Description: Horizontal position on screen
627 // @DisplayName: BTEMP_Y
628 // @Description: Vertical position on screen
630 AP_SUBGROUPINFO(btemp
, "BTEMP", 37, AP_OSD_Screen
, AP_OSD_Setting
),
634 // @DisplayName: ATEMP_EN
635 // @Description: Displays temperature reported by primary airspeed sensor
636 // @Values: 0:Disabled,1:Enabled
639 // @DisplayName: ATEMP_X
640 // @Description: Horizontal position on screen
644 // @DisplayName: ATEMP_Y
645 // @Description: Vertical position on screen
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
659 // @Param: BAT2_VLT_Y
660 // @DisplayName: BAT2VLT_Y
661 // @Description: Vertical position on screen
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
675 // @Param: BAT2USED_Y
676 // @DisplayName: BAT2USED_Y
677 // @Description: Vertical position on screen
679 AP_SUBGROUPINFO(bat2used
, "BAT2USED", 40, AP_OSD_Screen
, AP_OSD_Setting
),
683 // @DisplayName: ASPD2_EN
684 // @Description: Displays airspeed reported directly from secondary airspeed sensor
685 // @Values: 0:Disabled,1:Enabled
688 // @DisplayName: ASPD2_X
689 // @Description: Horizontal position on screen
693 // @DisplayName: ASPD2_Y
694 // @Description: Vertical position on screen
696 AP_SUBGROUPINFO(aspd2
, "ASPD2", 41, AP_OSD_Screen
, AP_OSD_Setting
),
699 // @DisplayName: ASPD1_EN
700 // @Description: Displays airspeed reported directly from primary airspeed sensor
701 // @Values: 0:Disabled,1:Enabled
704 // @DisplayName: ASPD1_X
705 // @Description: Horizontal position on screen
709 // @DisplayName: ASPD1_Y
710 // @Description: Vertical position on screen
712 AP_SUBGROUPINFO(aspd1
, "ASPD1", 42, AP_OSD_Screen
, AP_OSD_Setting
),
715 // @DisplayName: CLK_EN
716 // @Description: Displays a clock panel based on AP_RTC local time
717 // @Values: 0:Disabled,1:Enabled
720 // @DisplayName: CLK_X
721 // @Description: Horizontal position on screen
725 // @DisplayName: CLK_Y
726 // @Description: Vertical position on screen
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
741 // @Param: SIDEBARS_Y
742 // @DisplayName: SIDEBARS_Y
743 // @Description: Vertical position on screen
745 AP_SUBGROUPINFO(sidebars
, "SIDEBARS", 44, AP_OSD_Screen
, AP_OSD_Setting
),
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)
759 // @Param: CRSSHAIR_Y
760 // @DisplayName: CRSSHAIR_Y
761 // @Description: Vertical position on screen (MSP OSD only)
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)
775 // @Param: HOMEDIST_Y
776 // @DisplayName: HOMEDIST_Y
777 // @Description: Vertical position on screen (MSP OSD only)
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
787 // @DisplayName: HOMEDIR_X
788 // @Description: Horizontal position on screen
792 // @DisplayName: HOMEDIR_Y
793 // @Description: Vertical position on screen
795 AP_SUBGROUPINFO(home_dir
, "HOMEDIR", 47, AP_OSD_Screen
, AP_OSD_Setting
),
798 // @DisplayName: POWER_EN
799 // @Description: Displays power (MSP OSD only)
800 // @Values: 0:Disabled,1:Enabled
803 // @DisplayName: POWER_X
804 // @Description: Horizontal position on screen
808 // @DisplayName: POWER_Y
809 // @Description: Vertical position on screen
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
823 // @Param: CELLVOLT_Y
824 // @DisplayName: CELL_VOLT_Y
825 // @Description: Vertical position on screen
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
835 // @DisplayName: BATT_BAR_X
836 // @Description: Horizontal position on screen
840 // @DisplayName: BATT_BAR_Y
841 // @Description: Vertical position on screen
843 AP_SUBGROUPINFO(batt_bar
, "BATTBAR", 50, AP_OSD_Screen
, AP_OSD_Setting
),
846 // @DisplayName: ARMING_EN
847 // @Description: Displays arming status (MSP OSD only)
848 // @Values: 0:Disabled,1:Enabled
851 // @DisplayName: ARMING_X
852 // @Description: Horizontal position on screen
856 // @DisplayName: ARMING_Y
857 // @Description: Vertical position on screen
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
873 // @Param: PLUSCODE_Y
874 // @DisplayName: PLUSCODE_Y
875 // @Description: Vertical position on screen
877 AP_SUBGROUPINFO(pluscode
, "PLUSCODE", 52, AP_OSD_Screen
, AP_OSD_Setting
),
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
891 // @Param: CALLSIGN_Y
892 // @DisplayName: CALLSIGN_Y
893 // @Description: Vertical position on screen
895 AP_SUBGROUPINFO(callsign
, "CALLSIGN", 53, AP_OSD_Screen
, AP_OSD_Setting
),
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
908 // @Param: CURRENT2_Y
909 // @DisplayName: CURRENT2_Y
910 // @Description: Vertical position on screen
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
921 // @DisplayName: VTX_PWR_X
922 // @Description: Horizontal position on screen
926 // @DisplayName: VTX_PWR_Y
927 // @Description: Vertical position on screen
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
939 // @DisplayName: TER_HGT_X
940 // @Description: Horizontal position on screen
944 // @DisplayName: TER_HGT_Y
945 // @Description: Vertical position on screen
947 AP_SUBGROUPINFO(hgt_abvterr
, "TER_HGT", 56, AP_OSD_Screen
, AP_OSD_Setting
),
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
960 // @Param: AVGCELLV_Y
961 // @DisplayName: AVGCELLV_Y
962 // @Description: Vertical position on screen
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
976 // @Param: RESTVOLT_Y
977 // @DisplayName: RESTVOLT_Y
978 // @Description: Vertical position on screen
980 AP_SUBGROUPINFO(restvolt
, "RESTVOLT", 58, AP_OSD_Screen
, AP_OSD_Setting
),
983 // @DisplayName: FENCE_EN
984 // @Description: Displays indication of fence enable and breach
985 // @Values: 0:Disabled,1:Enabled
988 // @DisplayName: FENCE_X
989 // @Description: Horizontal position on screen
993 // @DisplayName: FENCE_Y
994 // @Description: Vertical position on screen
996 AP_SUBGROUPINFO(fence
, "FENCE", 59, AP_OSD_Screen
, AP_OSD_Setting
),
999 // @DisplayName: RNGF_EN
1000 // @Description: Displays a rangefinder's distance in cm
1001 // @Values: 0:Disabled,1:Enabled
1004 // @DisplayName: RNGF_X
1005 // @Description: Horizontal position on screen
1009 // @DisplayName: RNGF_Y
1010 // @Description: Vertical position on screen
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
1024 // @Param: ACRVOLT_Y
1025 // @DisplayName: ACRVOLT_Y
1026 // @Description: Vertical position on screen
1028 AP_SUBGROUPINFO(avgcellrestvolt
, "ACRVOLT", 61, AP_OSD_Screen
, AP_OSD_Setting
),
1032 // @DisplayName: RPM_EN
1033 // @Description: Displays main rotor revs/min
1034 // @Values: 0:Disabled,1:Enabled
1037 // @DisplayName: RPM_X
1038 // @Description: Horizontal position on screen
1042 // @DisplayName: RPM_Y
1043 // @Description: Vertical position on screen
1045 AP_SUBGROUPINFO(rrpm
, "RPM", 62, AP_OSD_Screen
, AP_OSD_Setting
),
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
1061 // @DisplayName: LINK_Q_X
1062 // @Description: Horizontal position on screen
1066 // @DisplayName: LINK_Q_Y
1067 // @Description: Vertical position on screen
1069 AP_SUBGROUPINFO(link_quality
, "LINK_Q", 1, AP_OSD_Screen
, AP_OSD_Setting
),
1071 #if HAL_WITH_MSP_DISPLAYPORT
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
1077 AP_GROUPINFO("TXT_RES", 3, AP_OSD_Screen
, txt_resolution
, 0),
1080 // @DisplayName: Sets the font index for this screen (MSP DisplayPort only)
1081 // @Description: Sets the font index for this screen (MSP DisplayPort only)
1084 AP_GROUPINFO("FONT", 4, AP_OSD_Screen
, font_index
, 0),
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
1094 // @DisplayName: RC_PWR_X
1095 // @Description: Horizontal position on screen
1099 // @DisplayName: RC_PWR_Y
1100 // @Description: Vertical position on screen
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
1114 // @Param: RSSIDBM_Y
1115 // @DisplayName: RSSIDBM_Y
1116 // @Description: Vertical position on screen
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
1126 // @DisplayName: RC_SNR_X
1127 // @Description: Horizontal position on screen
1131 // @DisplayName: RC_SNR_Y
1132 // @Description: Vertical position on screen
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
1142 // @DisplayName: RC_ANT_X
1143 // @Description: Horizontal position on screen
1147 // @DisplayName: RC_ANT_Y
1148 // @Description: Vertical position on screen
1150 AP_SUBGROUPINFO(rc_active_antenna
, "RC_ANT", 8, AP_OSD_Screen
, AP_OSD_Setting
),
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
1158 // @DisplayName: RC_LQ_X
1159 // @Description: Horizontal position on screen
1163 // @DisplayName: RC_LQ_Y
1164 // @Description: Vertical position on screen
1166 AP_SUBGROUPINFO(rc_lq
, "RC_LQ", 9, AP_OSD_Screen
, AP_OSD_Setting
),
1169 #if HAL_WITH_ESC_TELEM
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.
1174 AP_GROUPINFO("ESC_IDX", 10, AP_OSD_Screen
, esc_index
, 0),
1181 uint8_t AP_OSD_AbstractScreen::symbols_lookup_table
[AP_OSD_NUM_SYMBOLS
];
1183 // Symbol indexes to acces _symbols[index][set]
1189 #define SYM_ALT_FT 5
1190 #define SYM_BATT_FULL 6
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
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
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
1267 #define SYM_TERALT 74
1268 #define SYM_FENCE_ENABLED 75
1269 #define SYM_FENCE_DISABLED 76
1270 #define SYM_RNGFD 77
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
1292 #define SYM_ARROW_RIGHT 97
1293 #define SYM_ARROW_LEFT 98
1296 #define SYM_BATT_UNKNOWN 100
1297 #define SYM_ROLL 101
1298 #define SYM_PITCH 102
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]
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
)
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
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
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
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
1358 SYM_NM
, //DISTANCE_LONG Nm
1359 SYM_DEGREES_C
//TEMPERATURE
1361 static const uint8_t* icons
[AP_OSD::UNITS_LAST
] = {
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
] = {
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
] = {
1396 0.0, //DISTANCE_LONG
1397 32.0, //TEMPERATURE F
1399 static const float scale_SI
[UNIT_TYPE_LAST
] = {
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
] = {
1421 static const float *offsets
[AP_OSD::UNITS_LAST
] = {
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
)
1445 AP_AHRS
&ahrs
= AP::ahrs();
1446 WITH_SEMAPHORE(ahrs
.get_semaphore());
1447 ahrs
.get_relative_position_D_home(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
;
1459 bool show_remaining_pct
= battery
.capacity_remaining_pct(pct
);
1460 uint8_t p
= (100 - pct
) / 16.6;
1462 case VoltageType::VOLTAGE
: {
1465 case VoltageType::RESTING_VOLTAGE
: {
1466 v
= battery
.voltage_resting_estimate(instance
);
1467 blinkvolt
= osd
->warn_restvolt
;
1470 case VoltageType::RESTING_CELL
: {
1471 blinkvolt
= osd
->warn_avgcellrestvolt
;
1472 v
= battery
.voltage_resting_estimate(instance
);
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
));
1487 } else { // use autodetected cell count
1488 v
= v
/ (uint8_t)(osd
->max_battery_voltage
* 0.2381 + 1);
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
));
1498 backend
->write(x
,y
, v
< blinkvolt
, "%2.1f%c", (double)v
, SYMBOL(SYM_VOLT
));
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
));
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
1531 void AP_OSD_Screen::draw_rssi(uint8_t x
, uint8_t y
)
1533 AP_RSSI
*ap_rssi
= AP_RSSI::get_singleton();
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();
1544 const int16_t lqv
= ap_rssi
->read_receiver_link_quality();
1546 backend
->write(x
, y
, false, "%c--", SYMBOL(SYM_LQ
));
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
)
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
));
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
);
1577 void AP_OSD_Screen::draw_fltmode(uint8_t x
, uint8_t y
)
1579 AP_Notify
* notify
= AP_Notify::get_singleton();
1581 if (AP_Notify::flags
.armed
) {
1582 arm
= SYMBOL(SYM_ARMED
);
1584 arm
= SYMBOL(SYM_DISARMED
);
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
)
1603 if (!AP::battery().consumed_mah(mah
, instance
)) {
1607 backend
->write(x
,y
, false, "%4d%c", (int)mah
, SYMBOL(SYM_MAH
));
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
);
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();
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
])) {
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) {
1653 start_position
= current_cycle
- message_scroll_delay
;
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
));
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
));
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());
1707 bool inverted
= false;
1708 AP::vehicle()->get_osd_roll_pitch_rad(roll
,pitch
);
1710 // Are we inverted? then flash horizon line
1711 if (abs(roll
) >= radians(90)) {
1714 // Aviation style AH instead of Betaflight FPV style
1715 if (inverted
&& check_option(AP_OSD::OPTION_AVIATION_AH
)) {
1718 //inverted roll AH (Russian HUD emulation)
1719 if (check_option(AP_OSD::OPTION_INVERTED_AH_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
);
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
) {
1769 } else if (distance_scaled
< 99.0f
) {
1771 } else if (distance_scaled
< 999.0f
) {
1776 } else if (distance_scaled
< 10.0f
) {
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());
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
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
);
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
));
1811 void AP_OSD_Screen::draw_rrpm(uint8_t x
, uint8_t y
)
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
1821 // No RPM because pointer is null
1824 int r_rpm
= static_cast<int>(_rrpm
);
1825 backend
->write(x
, y
, false, "%4d%c", (int)r_rpm
, SYMBOL(SYM_RPM
));
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
] = {
1860 // Get altitude and airspeed, scaled to appropriate units
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
));
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
));
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
] = {
1912 SYM_HEADING_DIVIDED_LINE
,
1916 SYM_HEADING_DIVIDED_LINE
,
1920 SYM_HEADING_DIVIDED_LINE
,
1924 SYM_HEADING_DIVIDED_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();
1945 const float length
= v
.length();
1946 if (length
> 1.0f
) {
1947 if (check_option(AP_OSD::OPTION_INVERTED_WIND
)) {
1950 angle
= angle
+ atan2f(v
.y
, v
.x
) - ahrs
.get_yaw();
1952 draw_speed(x
+ 1, y
, angle
, length
);
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());
1961 backend
->write(x
, y
, false, "%c", SYMBOL(SYM_WSPD
));
1964 void AP_OSD_Screen::draw_aspeed(uint8_t x
, uint8_t y
)
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
));
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
)
1982 AP_AHRS
&ahrs
= AP::ahrs();
1983 WITH_SEMAPHORE(ahrs
.get_semaphore());
1984 if (ahrs
.get_velocity_NED(v
)) {
1987 auto &baro
= AP::baro();
1988 WITH_SEMAPHORE(baro
.get_semaphore());
1989 vspd
= baro
.get_climb_rate();
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
);
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
));
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
)
2015 if (esc_index
> 0) {
2016 if (!AP::esc_telem().get_temperature(esc_index
-1, etemp
)) {
2020 else if (!AP::esc_telem().get_highest_temperature(etemp
)) {
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
)
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
)) {
2035 } else if (!AP::esc_telem().get_rpm(esc
, rpm
)) {
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
)
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
)) {
2051 } else if (!AP::esc_telem().get_current(esc
, amps
)) {
2054 backend
->write(x
, y
, false, "%4.1f%c", amps
, SYMBOL(SYM_AMP
));
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();
2070 if (tx_power
< 1000) {
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"
2074 backend
->write(x
, y
, false, "%3d%c", tx_power
, SYMBOL(SYM_MW
));
2077 const float value_w
= float(tx_power
) * 0.001f
;
2079 backend
->write(x
, y
, false, "%.2fW", value_w
);
2081 backend
->write(x
, y
, false, "%.2f%c", value_w
, SYMBOL(SYM_WATT
));
2086 backend
->write(x
, y
, false, "---%cW", SYMBOL(SYM_ALT_M
));
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;
2103 backend
->write(new_x
, y
, blink
, "%4dDBM", -rssidbm
);
2105 backend
->write(new_x
, y
, blink
, "%4d%c", -rssidbm
, SYMBOL(SYM_DBM
));
2109 backend
->write(new_x
, y
, blink
, "----DBM");
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
) {
2123 backend
->write(x
, y
, blink
, "SNR---DB");
2125 backend
->write(x
, y
, blink
, "%c---%c", SYMBOL(SYM_SNR
), SYMBOL(SYM_DB
));
2129 backend
->write(x
, y
, blink
, "SNR%3dDB", snr
);
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) {
2142 backend
->write(x
, y
, false, "ANT-");
2144 backend
->write(x
, y
, false, "%c-", SYMBOL(SYM_ANT
));
2148 backend
->write(x
, y
, false, "ANT%d", active_antenna
+ 1);
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
;
2165 backend
->write(x
, y
, blink
, "LQ--:--");
2167 backend
->write(x
, y
, blink
, "LQ--");
2171 backend
->write(x
, y
, blink
, "%c--:--", SYMBOL(SYM_LQ
));
2173 backend
->write(x
, y
, blink
, "%c--", SYMBOL(SYM_LQ
));
2179 backend
->write(x
, y
, blink
, "LQ%2d:%2d", rf_mode
, lqv
);
2181 backend
->write(x
, y
, blink
, "LQ%2d", lqv
);
2185 backend
->write(x
, y
, blink
, "%c%2d:%2d", SYMBOL(SYM_LQ
), rf_mode
, lqv
);
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;
2225 if (ahrs
.roll_sensor
> 50) {
2226 r
= SYMBOL(SYM_ROLLR
);
2227 } else if (ahrs
.roll_sensor
< -50) {
2228 r
= SYMBOL(SYM_ROLLL
);
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;
2240 if (ahrs
.pitch_sensor
> 50) {
2241 p
= SYMBOL(SYM_PTCHUP
);
2242 } else if (ahrs
.pitch_sensor
< -50) {
2243 p
= SYMBOL(SYM_PTCHDWN
);
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
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();
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();
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());
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
));
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
);
2340 auto &ahrs
= AP::ahrs();
2341 WITH_SEMAPHORE(ahrs
.get_semaphore());
2342 if (ahrs
.get_velocity_NED(v
)) {
2347 auto &baro
= AP::baro();
2348 WITH_SEMAPHORE(baro
.get_semaphore());
2349 vspd
= baro
.get_climb_rate();
2354 AP_BattMonitor
&battery
= AP::battery();
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
);
2359 backend
->write(x
, y
, false,"%c%c---%c",SYMBOL(SYM_PTCHUP
),SYMBOL(SYM_EFF
),unit_icon
);
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
));
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();
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
));
2385 backend
->write(x
, y
, false, "--%c", u_icon(TEMPERATURE
));
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();
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
));
2411 backend
->write(x
, y
, false, "%c ---%c", SYMBOL(SYM_ASPD
), u_icon(SPEED
));
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();
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
));
2427 backend
->write(x
, y
, false, "%c ---%c", SYMBOL(SYM_ASPD
), u_icon(SPEED
));
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
;
2438 if (!rtc
.get_local_time(hour
, min
, sec
, ms
)) {
2439 backend
->write(x
, y
, false, "%c--:--", SYMBOL(SYM_CLK
));
2441 backend
->write(x
, y
, false, "%c%02u:%02u", SYMBOL(SYM_CLK
), hour
, min
);
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();
2452 if (gps
.status() == AP_GPS::NO_GPS
|| gps
.status() == AP_GPS::NO_FIX
){
2453 backend
->write(x
, y
, false, "--------+--");
2455 AP_OLC::olc_encode(loc
.lat
, loc
.lng
, 10, buff
, sizeof(buff
));
2456 backend
->write(x
, y
, false, "%s", buff
);
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])) {
2476 callsign_data
.str
= strndup((const char *)fd
->data
, len
);
2480 if (callsign_data
.str
!= nullptr) {
2481 backend
->write(x
, y
, false, "%s", callsign_data
.str
);
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();
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
));
2517 backend
->write(x
, y
, false, " ---%c%c", u_icon(ALTITUDE
),SYMBOL(SYM_TERALT
));
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) {
2529 if (fenceptr
->enabled() && fenceptr
->present()) {
2530 backend
->write(x
, y
, fenceptr
->get_breaches(), "%c", SYMBOL(SYM_FENCE_ENABLED
));
2532 backend
->write(x
, y
, false, "%c", SYMBOL(SYM_FENCE_DISABLED
));
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) {
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
));
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
));
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
) {
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
);
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
);
2577 #if AP_RANGEFINDER_ENABLED
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
);
2589 DRAW_SETTING(link_quality
);
2591 DRAW_SETTING(current
);
2592 DRAW_SETTING(batused
);
2593 DRAW_SETTING(bat2used
);
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
);
2608 #if AP_FENCE_ENABLED
2609 DRAW_SETTING(fence
);
2611 DRAW_SETTING(roll_angle
);
2612 DRAW_SETTING(pitch_angle
);
2614 #if BARO_MAX_INSTANCES > 1
2615 DRAW_SETTING(btemp
);
2617 DRAW_SETTING(atemp
);
2619 DRAW_SETTING(flightime
);
2623 #if AP_VIDEOTX_ENABLED
2624 DRAW_SETTING(vtx_power
);
2627 #if HAL_WITH_ESC_TELEM
2628 DRAW_SETTING(esc_temp
);
2629 DRAW_SETTING(esc_rpm
);
2630 DRAW_SETTING(esc_amps
);
2633 DRAW_SETTING(gps_latitude
);
2634 DRAW_SETTING(gps_longitude
);
2635 #if HAL_PLUSCODE_ENABLE
2636 DRAW_SETTING(pluscode
);
2640 DRAW_SETTING(climbeff
);
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
);
2654 #endif // OSD_ENABLED