-
Notifications
You must be signed in to change notification settings - Fork 1.5k
/
Copy pathosd_dji_hd.c
1498 lines (1340 loc) · 58.9 KB
/
osd_dji_hd.c
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
400
401
402
403
404
405
406
407
408
409
410
411
412
413
414
415
416
417
418
419
420
421
422
423
424
425
426
427
428
429
430
431
432
433
434
435
436
437
438
439
440
441
442
443
444
445
446
447
448
449
450
451
452
453
454
455
456
457
458
459
460
461
462
463
464
465
466
467
468
469
470
471
472
473
474
475
476
477
478
479
480
481
482
483
484
485
486
487
488
489
490
491
492
493
494
495
496
497
498
499
500
501
502
503
504
505
506
507
508
509
510
511
512
513
514
515
516
517
518
519
520
521
522
523
524
525
526
527
528
529
530
531
532
533
534
535
536
537
538
539
540
541
542
543
544
545
546
547
548
549
550
551
552
553
554
555
556
557
558
559
560
561
562
563
564
565
566
567
568
569
570
571
572
573
574
575
576
577
578
579
580
581
582
583
584
585
586
587
588
589
590
591
592
593
594
595
596
597
598
599
600
601
602
603
604
605
606
607
608
609
610
611
612
613
614
615
616
617
618
619
620
621
622
623
624
625
626
627
628
629
630
631
632
633
634
635
636
637
638
639
640
641
642
643
644
645
646
647
648
649
650
651
652
653
654
655
656
657
658
659
660
661
662
663
664
665
666
667
668
669
670
671
672
673
674
675
676
677
678
679
680
681
682
683
684
685
686
687
688
689
690
691
692
693
694
695
696
697
698
699
700
701
702
703
704
705
706
707
708
709
710
711
712
713
714
715
716
717
718
719
720
721
722
723
724
725
726
727
728
729
730
731
732
733
734
735
736
737
738
739
740
741
742
743
744
745
746
747
748
749
750
751
752
753
754
755
756
757
758
759
760
761
762
763
764
765
766
767
768
769
770
771
772
773
774
775
776
777
778
779
780
781
782
783
784
785
786
787
788
789
790
791
792
793
794
795
796
797
798
799
800
801
802
803
804
805
806
807
808
809
810
811
812
813
814
815
816
817
818
819
820
821
822
823
824
825
826
827
828
829
830
831
832
833
834
835
836
837
838
839
840
841
842
843
844
845
846
847
848
849
850
851
852
853
854
855
856
857
858
859
860
861
862
863
864
865
866
867
868
869
870
871
872
873
874
875
876
877
878
879
880
881
882
883
884
885
886
887
888
889
890
891
892
893
894
895
896
897
898
899
900
901
902
903
904
905
906
907
908
909
910
911
912
913
914
915
916
917
918
919
920
921
922
923
924
925
926
927
928
929
930
931
932
933
934
935
936
937
938
939
940
941
942
943
944
945
946
947
948
949
950
951
952
953
954
955
956
957
958
959
960
961
962
963
964
965
966
967
968
969
970
971
972
973
974
975
976
977
978
979
980
981
982
983
984
985
986
987
988
989
990
991
992
993
994
995
996
997
998
999
1000
/*
* This file is part of INAV.
*
* This Source Code Form is subject to the terms of the Mozilla Public
* License, v. 2.0. If a copy of the MPL was not distributed with this file,
* You can obtain one at http://mozilla.org/MPL/2.0/.
*
* Alternatively, the contents of this file may be used under the terms
* of the GNU General Public License Version 3, as described below:
*
* This file is free software: you may copy, redistribute and/or modify
* it under the terms of the GNU General Public License as published by the
* Free Software Foundation, either version 3 of the License, or (at your
* option) any later version.
*
* This file is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General
* Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see http://www.gnu.org/licenses/.
*
* @author Konstantin Sharlaimov ([email protected])
*/
#include <stdbool.h>
#include <stdint.h>
#include <string.h>
#include "platform.h"
#include "build/debug.h"
#include "build/version.h"
#include "common/streambuf.h"
#include "common/utils.h"
#include "common/maths.h"
#include "common/time.h"
#include "common/crc.h"
#include "config/parameter_group.h"
#include "config/parameter_group_ids.h"
#include "fc/fc_core.h"
#include "fc/config.h"
#include "fc/controlrate_profile.h"
#include "fc/fc_msp.h"
#include "fc/fc_msp_box.h"
#include "fc/runtime_config.h"
#include "fc/settings.h"
#include "fc/rc_adjustments.h"
#include "flight/imu.h"
#include "flight/pid.h"
#include "flight/mixer.h"
#include "io/serial.h"
#include "io/gps.h"
#include "io/osd.h"
#include "io/osd_dji_hd.h"
#include "io/osd_common.h"
#include "rx/rx.h"
#include "sensors/sensors.h"
#include "sensors/gyro.h"
#include "sensors/battery.h"
#include "sensors/rangefinder.h"
#include "sensors/acceleration.h"
#include "sensors/esc_sensor.h"
#include "sensors/temperature.h"
#include "sensors/pitotmeter.h"
#include "sensors/boardalignment.h"
#include "msp/msp.h"
#include "msp/msp_protocol.h"
#include "msp/msp_serial.h"
#include "common/string_light.h"
#include "navigation/navigation.h"
#include "navigation/navigation_private.h"
#include "common/constants.h"
#include "scheduler/scheduler.h"
#include "common/printf.h"
#include <stdlib.h>
#include "rx/rx.h"
#include "fc/rc_controls.h"
#if defined(USE_DJI_HD_OSD)
#define DJI_MSP_BAUDRATE 115200
#define DJI_ARMING_DISABLE_FLAGS_COUNT 25
#define DJI_OSD_WARNING_COUNT 16
#define DJI_OSD_TIMER_COUNT 2
#define DJI_OSD_FLAGS_OSD_FEATURE (1 << 0)
#define EFFICIENCY_UPDATE_INTERVAL (5 * 1000)
#define RC_RX_LINK_LOST_MSG "!RC RX LINK LOST!"
// Adjust OSD_MESSAGE's default position when
// changing OSD_MESSAGE_LENGTH
#define OSD_MESSAGE_LENGTH 28
#define OSD_ALTERNATING_CHOICES(ms, num_choices) ((millis() / ms) % num_choices)
#define _CONST_STR_SIZE(s) ((sizeof(s)/sizeof(s[0]))-1) // -1 to avoid counting final '\0'
// Wrap all string constants intenteded for display as messages with
// this macro to ensure compile time length validation.
#define OSD_MESSAGE_STR(x) ({ \
STATIC_ASSERT(_CONST_STR_SIZE(x) <= OSD_MESSAGE_LENGTH, message_string_ ## __COUNTER__ ## _too_long); \
x; \
})
/*
* DJI HD goggles use MSPv1 compatible with Betaflight 4.1.0
* DJI uses a subset of messages and assume fixed bit positions for flight modes
*
* To avoid compatibility issues we maintain a separate MSP command processor
* but reuse the packet decoder to minimize code duplication
*/
PG_REGISTER_WITH_RESET_TEMPLATE(djiOsdConfig_t, djiOsdConfig, PG_DJI_OSD_CONFIG, 3);
PG_RESET_TEMPLATE(djiOsdConfig_t, djiOsdConfig,
.use_name_for_messages = SETTING_DJI_USE_NAME_FOR_MESSAGES_DEFAULT,
.esc_temperature_source = SETTING_DJI_ESC_TEMP_SOURCE_DEFAULT,
.messageSpeedSource = SETTING_DJI_MESSAGE_SPEED_SOURCE_DEFAULT,
.rssi_source = SETTING_DJI_RSSI_SOURCE_DEFAULT,
.useAdjustments = SETTING_DJI_USE_ADJUSTMENTS_DEFAULT,
.craftNameAlternatingDuration = SETTING_DJI_CN_ALTERNATING_DURATION_DEFAULT
);
#define RSSI_BOUNDARY(PERCENT) (RSSI_MAX_VALUE / 100 * PERCENT)
typedef enum {
DJI_OSD_CN_MESSAGES,
DJI_OSD_CN_THROTTLE,
DJI_OSD_CN_THROTTLE_AUTO_THR,
DJI_OSD_CN_AIR_SPEED,
DJI_OSD_CN_EFFICIENCY,
DJI_OSD_CN_DISTANCE,
DJI_OSD_CN_ADJUSTEMNTS,
DJI_OSD_CN_MAX_ELEMENTS
} DjiCraftNameElements_t;
// External dependency on looptime
extern timeDelta_t cycleTime;
// MSP packet decoder state structure
static mspPort_t djiMspPort;
// Mapping table between DJI PID and INAV PID (order is different)
const uint8_t djiPidIndexMap[] = {
PID_ROLL, // DJI: PID_ROLL
PID_PITCH, // DJI: PID_PITCH
PID_YAW, // DJI: PID_YAW
PID_LEVEL, // DJI: PID_LEVEL
PID_HEADING // DJI: PID_MAG
};
typedef struct {
int itemIndex; // INAV OSD item
features_e depFeature; // INAV feature that item is dependent on
} djiOsdMapping_t;
const djiOsdMapping_t djiOSDItemIndexMap[] = {
{ OSD_RSSI_VALUE, 0 }, // DJI: OSD_RSSI_VALUE
{ OSD_MAIN_BATT_VOLTAGE, FEATURE_VBAT }, // DJI: OSD_MAIN_BATT_VOLTAGE
{ OSD_CROSSHAIRS, 0 }, // DJI: OSD_CROSSHAIRS
{ OSD_ARTIFICIAL_HORIZON, 0 }, // DJI: OSD_ARTIFICIAL_HORIZON
{ OSD_HORIZON_SIDEBARS, 0 }, // DJI: OSD_HORIZON_SIDEBARS
{ OSD_ONTIME, 0 }, // DJI: OSD_ITEM_TIMER_1
{ OSD_FLYTIME, 0 }, // DJI: OSD_ITEM_TIMER_2
{ OSD_FLYMODE, 0 }, // DJI: OSD_FLYMODE
{ OSD_CRAFT_NAME, 0 }, // DJI: OSD_CRAFT_NAME
{ OSD_THROTTLE_POS, 0 }, // DJI: OSD_THROTTLE_POS
{ OSD_VTX_CHANNEL, 0 }, // DJI: OSD_VTX_CHANNEL
{ OSD_CURRENT_DRAW, FEATURE_CURRENT_METER }, // DJI: OSD_CURRENT_DRAW
{ OSD_MAH_DRAWN, FEATURE_CURRENT_METER }, // DJI: OSD_MAH_DRAWN
{ OSD_GPS_SPEED, FEATURE_GPS }, // DJI: OSD_GPS_SPEED
{ OSD_GPS_SATS, FEATURE_GPS }, // DJI: OSD_GPS_SATS
{ OSD_ALTITUDE, 0 }, // DJI: OSD_ALTITUDE
{ OSD_ROLL_PIDS, 0 }, // DJI: OSD_ROLL_PIDS
{ OSD_PITCH_PIDS, 0 }, // DJI: OSD_PITCH_PIDS
{ OSD_YAW_PIDS, 0 }, // DJI: OSD_YAW_PIDS
{ OSD_POWER, 0 }, // DJI: OSD_POWER
{ -1, 0 }, // DJI: OSD_PIDRATE_PROFILE
{ -1, 0 }, // DJI: OSD_WARNINGS
{ OSD_MAIN_BATT_CELL_VOLTAGE, 0 }, // DJI: OSD_AVG_CELL_VOLTAGE
{ OSD_GPS_LON, FEATURE_GPS }, // DJI: OSD_GPS_LON
{ OSD_GPS_LAT, FEATURE_GPS }, // DJI: OSD_GPS_LAT
{ OSD_DEBUG, 0 }, // DJI: OSD_DEBUG
{ OSD_ATTITUDE_PITCH, 0 }, // DJI: OSD_PITCH_ANGLE
{ OSD_ATTITUDE_ROLL, 0 }, // DJI: OSD_ROLL_ANGLE
{ -1, 0 }, // DJI: OSD_MAIN_BATT_USAGE
{ -1, 0 }, // DJI: OSD_DISARMED
{ OSD_HOME_DIR, FEATURE_GPS }, // DJI: OSD_HOME_DIR
{ OSD_HOME_DIST, FEATURE_GPS }, // DJI: OSD_HOME_DIST
{ OSD_HEADING, 0 }, // DJI: OSD_NUMERICAL_HEADING
{ OSD_VARIO_NUM, 0 }, // DJI: OSD_NUMERICAL_VARIO
{ -1, 0 }, // DJI: OSD_COMPASS_BAR
{ OSD_ESC_TEMPERATURE, 0 }, // DJI: OSD_ESC_TEMPERATURE
{ OSD_ESC_RPM, 0 }, // DJI: OSD_ESC_RPM
{ OSD_REMAINING_FLIGHT_TIME_BEFORE_RTH, FEATURE_CURRENT_METER }, // DJI: OSD_REMAINING_TIME_ESTIMATE
{ OSD_RTC_TIME, 0 }, // DJI: OSD_RTC_DATETIME
{ -1, 0 }, // DJI: OSD_ADJUSTMENT_RANGE
{ -1, 0 }, // DJI: OSD_CORE_TEMPERATURE
{ -1, 0 }, // DJI: OSD_ANTI_GRAVITY
{ -1, 0 }, // DJI: OSD_G_FORCE
{ -1, 0 }, // DJI: OSD_MOTOR_DIAG
{ -1, 0 }, // DJI: OSD_LOG_STATUS
{ -1, 0 }, // DJI: OSD_FLIP_ARROW
{ -1, 0 }, // DJI: OSD_LINK_QUALITY
{ OSD_TRIP_DIST, FEATURE_GPS }, // DJI: OSD_FLIGHT_DIST
{ -1, 0 }, // DJI: OSD_STICK_OVERLAY_LEFT
{ -1, 0 }, // DJI: OSD_STICK_OVERLAY_RIGHT
{ -1, 0 }, // DJI: OSD_DISPLAY_NAME
{ -1, 0 }, // DJI: OSD_ESC_RPM_FREQ
{ -1, 0 }, // DJI: OSD_RATE_PROFILE_NAME
{ -1, 0 }, // DJI: OSD_PID_PROFILE_NAME
{ -1, 0 }, // DJI: OSD_PROFILE_NAME
{ -1, 0 }, // DJI: OSD_RSSI_DBM_VALUE
{ -1, 0 }, // DJI: OSD_RC_CHANNELS
};
const int djiOSDStatisticsMap[] = {
-1, // DJI: OSD_STAT_RTC_DATE_TIME
-1, // DJI: OSD_STAT_TIMER_1
-1, // DJI: OSD_STAT_TIMER_2
-1, // DJI: OSD_STAT_MAX_SPEED
-1, // DJI: OSD_STAT_MAX_DISTANCE
-1, // DJI: OSD_STAT_MIN_BATTERY
-1, // DJI: OSD_STAT_END_BATTERY
-1, // DJI: OSD_STAT_BATTERY
-1, // DJI: OSD_STAT_MIN_RSSI
-1, // DJI: OSD_STAT_MAX_CURRENT
-1, // DJI: OSD_STAT_USED_MAH
-1, // DJI: OSD_STAT_MAX_ALTITUDE
-1, // DJI: OSD_STAT_BLACKBOX
-1, // DJI: OSD_STAT_BLACKBOX_NUMBER
-1, // DJI: OSD_STAT_MAX_G_FORCE
-1, // DJI: OSD_STAT_MAX_ESC_TEMP
-1, // DJI: OSD_STAT_MAX_ESC_RPM
-1, // DJI: OSD_STAT_MIN_LINK_QUALITY
-1, // DJI: OSD_STAT_FLIGHT_DISTANCE
-1, // DJI: OSD_STAT_MAX_FFT
-1, // DJI: OSD_STAT_TOTAL_FLIGHTS
-1, // DJI: OSD_STAT_TOTAL_TIME
-1, // DJI: OSD_STAT_TOTAL_DIST
-1, // DJI: OSD_STAT_MIN_RSSI_DBM
};
void djiOsdSerialInit(void)
{
memset(&djiMspPort, 0, sizeof(mspPort_t));
serialPortConfig_t *portConfig = findSerialPortConfig(FUNCTION_DJI_HD_OSD);
if (!portConfig) {
return;
}
serialPort_t *serialPort = openSerialPort(portConfig->identifier, FUNCTION_DJI_HD_OSD, NULL, NULL, DJI_MSP_BAUDRATE, MODE_RXTX, SERIAL_NOT_INVERTED);
if (serialPort) {
resetMspPort(&djiMspPort, serialPort);
}
}
static void djiPackBoxModeBitmask(boxBitmask_t * flightModeBitmask)
{
memset(flightModeBitmask, 0, sizeof(boxBitmask_t));
// Map flight modes to DJI-supported bits
switch(getFlightModeForTelemetry()) {
case FLM_MANUAL:
case FLM_ACRO:
case FLM_ACRO_AIR:
// DJI: No bits set = ACRO
break;
case FLM_ANGLE:
bitArraySet(flightModeBitmask->bits, 1); // DJI: 1 << 1 : ANGLE
break;
case FLM_HORIZON:
bitArraySet(flightModeBitmask->bits, 2); // DJI: 1 << 2
break;
case FLM_RTH:
bitArraySet(flightModeBitmask->bits, 5); // DJI: 1 << 5 : GPS_RESQUE
break;
case FLM_CRUISE:
bitArraySet(flightModeBitmask->bits, 3); // DJI: 1 << 3 : technically HEADFREE
break;
case FLM_FAILSAFE:
bitArraySet(flightModeBitmask->bits, 4); // DJI: 1 << 4
break;
case FLM_LAUNCH:
case FLM_ALTITUDE_HOLD:
case FLM_POSITION_HOLD:
case FLM_MISSION:
case FLM_ANGLEHOLD:
default:
// Unsupported ATM, keep at ANGLE
bitArraySet(flightModeBitmask->bits, 1); // DJI: 1 << 1 : ANGLE
}
// Set ARMED mode
if (ARMING_FLAG(ARMED)) {
bitArraySet(flightModeBitmask->bits, 0); // DJI: 1 << 0 : ARMED
}
}
static uint32_t djiPackArmingDisabledFlags(void)
{
// TODO: Map INAV arming disabled flags to DJI/BF ones
// https://github.com/betaflight/betaflight/blob/c6e5882dd91fa20d246b8f8af10cf6c92876bc3d/src/main/fc/runtime_config.h#L42
// For now hide everything in ARMING_DISABLED_ARM_SWITCH (bit 24)
return isArmingDisabled() ? (1 << 24) : 0;
}
#if defined(USE_OSD)
static uint32_t djiEncodeOSDEnabledWarnings(void)
{
// TODO:
return 0;
}
static void djiSerializeOSDConfigReply(sbuf_t *dst)
{
// Only send supported flag - always
sbufWriteU8(dst, DJI_OSD_FLAGS_OSD_FEATURE);
// 7456 video system (AUTO/PAL/NTSC)
sbufWriteU8(dst, osdConfig()->video_system);
// Configuration
sbufWriteU8(dst, osdConfig()->units);
// Alarms
sbufWriteU8(dst, osdConfig()->rssi_alarm);
sbufWriteU16(dst, currentBatteryProfile->capacity.warning);
// OSD_ITEM_COUNT (previously was timer alarm)
sbufWriteU8(dst, 0);
sbufWriteU8(dst, ARRAYLEN(djiOSDItemIndexMap));
// Altitude alarm
sbufWriteU16(dst, osdConfig()->alt_alarm);
// OSD element position and visibility
for (unsigned i = 0; i < ARRAYLEN(djiOSDItemIndexMap); i++) {
const int inavOSDIdx = djiOSDItemIndexMap[i].itemIndex;
// We call OSD item supported if it doesn't have dependencies or all feature-dependencies are satistied
const bool itemIsSupported = ((djiOSDItemIndexMap[i].depFeature == 0) || feature(djiOSDItemIndexMap[i].depFeature));
if (inavOSDIdx >= 0 && itemIsSupported) {
// Position & visibility are encoded in 16 bits, and is the same between BF/DJI.
// However INAV supports co-ords of 0-63 and has 3 layouts, while BF has co-ords 0-31 and visibility profiles.
// Re-encode for co-ords of 0-31 and map the layout to all three BF profiles.
uint16_t itemPos = osdLayoutsConfig()->item_pos[0][inavOSDIdx];
uint16_t itemPosSD = OSD_POS_SD(OSD_X(itemPos), OSD_Y(itemPos));
// Workarounds for certain OSD element positions
// INAV calculates these dynamically, while DJI expects the config to have defined coordinates
switch(inavOSDIdx) {
case OSD_CROSSHAIRS:
itemPosSD = OSD_POS_SD(15, 8);
break;
case OSD_ARTIFICIAL_HORIZON:
itemPosSD = OSD_POS_SD(9, 8);
break;
case OSD_HORIZON_SIDEBARS:
itemPosSD = OSD_POS_SD(16, 7);
break;
}
// Enforce visibility in 3 BF OSD profiles
if (OSD_VISIBLE(itemPos)) {
itemPosSD |= (0x3000 | OSD_VISIBLE_FLAG_SD);
}
sbufWriteU16(dst, itemPosSD);
}
else {
// Hide OSD elements unsupported by INAV
sbufWriteU16(dst, 0);
}
}
// Post flight statistics
sbufWriteU8(dst, ARRAYLEN(djiOSDStatisticsMap));
for (unsigned i = 0; i < ARRAYLEN(djiOSDStatisticsMap); i++ ) {
if (djiOSDStatisticsMap[i] >= 0) {
// FIXME: Map post-flight statistics from INAV to BF/DJI
sbufWriteU8(dst, 0);
}
else {
sbufWriteU8(dst, 0);
}
}
// Timers
sbufWriteU8(dst, DJI_OSD_TIMER_COUNT);
for (int i = 0; i < DJI_OSD_TIMER_COUNT; i++) {
// STUB: We don't support BF's OSD timers
sbufWriteU16(dst, 0);
}
// Enabled warnings
// API < 1.41 stub, kept for compatibility
sbufWriteU16(dst, djiEncodeOSDEnabledWarnings() & 0xFFFF);
// API >= 1.41
// Send the warnings count and 32bit enabled warnings flags.
sbufWriteU8(dst, DJI_OSD_WARNING_COUNT);
sbufWriteU32(dst, djiEncodeOSDEnabledWarnings());
// DJI OSD expects 1 OSD profile
sbufWriteU8(dst, 1);
sbufWriteU8(dst, 1);
// No OSD stick overlay
sbufWriteU8(dst, 0);
// API >= 1.43
// Camera frame element width/height - magic numbers taken from Betaflight source
//sbufWriteU8(dst, DJI_OSD_SCREEN_WIDTH); // osdConfig()->camera_frame_width
//sbufWriteU8(dst, DJI_OSD_SCREEN_HEIGHT); // osdConfig()->camera_frame_height
}
static char * osdArmingDisabledReasonMessage(void)
{
switch (isArmingDisabledReason()) {
case ARMING_DISABLED_FAILSAFE_SYSTEM:
// See handling of FAILSAFE_RX_LOSS_MONITORING in failsafe.c
if (failsafePhase() == FAILSAFE_RX_LOSS_MONITORING) {
if (failsafeIsReceivingRxData()) {
// If we're not using sticks, it means the ARM switch
// hasn't been off since entering FAILSAFE_RX_LOSS_MONITORING
// yet
return OSD_MESSAGE_STR("DISARM!");
}
// Not receiving RX data
return OSD_MESSAGE_STR(RC_RX_LINK_LOST_MSG);
}
return OSD_MESSAGE_STR("FAILSAFE");
case ARMING_DISABLED_NOT_LEVEL:
return OSD_MESSAGE_STR("!LEVEL");
case ARMING_DISABLED_SENSORS_CALIBRATING:
return OSD_MESSAGE_STR("CALIBRATING");
case ARMING_DISABLED_SYSTEM_OVERLOADED:
return OSD_MESSAGE_STR("OVERLOAD");
case ARMING_DISABLED_NAVIGATION_UNSAFE:
// Check the exact reason
switch (navigationIsBlockingArming(NULL)) {
case NAV_ARMING_BLOCKER_NONE:
break;
case NAV_ARMING_BLOCKER_MISSING_GPS_FIX:
return OSD_MESSAGE_STR("NO GPS FIX");
case NAV_ARMING_BLOCKER_NAV_IS_ALREADY_ACTIVE:
return OSD_MESSAGE_STR("DISABLE NAV");
case NAV_ARMING_BLOCKER_FIRST_WAYPOINT_TOO_FAR:
return OSD_MESSAGE_STR("1ST WYP TOO FAR");
case NAV_ARMING_BLOCKER_JUMP_WAYPOINT_ERROR:
return OSD_MESSAGE_STR("WYP MISCONFIGURED");
}
break;
case ARMING_DISABLED_COMPASS_NOT_CALIBRATED:
return OSD_MESSAGE_STR("COMPS CALIB");
case ARMING_DISABLED_ACCELEROMETER_NOT_CALIBRATED:
return OSD_MESSAGE_STR("ACC CALIB");
case ARMING_DISABLED_ARM_SWITCH:
return OSD_MESSAGE_STR("DISARM!");
case ARMING_DISABLED_HARDWARE_FAILURE:
return OSD_MESSAGE_STR("ERR HW!");
// {
// if (!HW_SENSOR_IS_HEALTHY(getHwGyroStatus())) {
// return OSD_MESSAGE_STR("GYRO FAILURE");
// }
// if (!HW_SENSOR_IS_HEALTHY(getHwAccelerometerStatus())) {
// return OSD_MESSAGE_STR("ACCELEROMETER FAILURE");
// }
// if (!HW_SENSOR_IS_HEALTHY(getHwCompassStatus())) {
// return OSD_MESSAGE_STR("COMPASS FAILURE");
// }
// if (!HW_SENSOR_IS_HEALTHY(getHwBarometerStatus())) {
// return OSD_MESSAGE_STR("BAROMETER FAILURE");
// }
// if (!HW_SENSOR_IS_HEALTHY(getHwGPSStatus())) {
// return OSD_MESSAGE_STR("GPS FAILURE");
// }
// if (!HW_SENSOR_IS_HEALTHY(getHwRangefinderStatus())) {
// return OSD_MESSAGE_STR("RANGE FINDER FAILURE");
// }
// if (!HW_SENSOR_IS_HEALTHY(getHwPitotmeterStatus())) {
// return OSD_MESSAGE_STR("PITOT METER FAILURE");
// }
// }
// return OSD_MESSAGE_STR("HARDWARE FAILURE");
case ARMING_DISABLED_BOXFAILSAFE:
return OSD_MESSAGE_STR("FAILSAFE ENABLED");
case ARMING_DISABLED_RC_LINK:
return OSD_MESSAGE_STR("NO RC LINK");
case ARMING_DISABLED_THROTTLE:
return OSD_MESSAGE_STR("THROTTLE!");
case ARMING_DISABLED_ROLLPITCH_NOT_CENTERED:
return OSD_MESSAGE_STR("ROLLPITCH!");
case ARMING_DISABLED_SERVO_AUTOTRIM:
return OSD_MESSAGE_STR("AUTOTRIM!");
case ARMING_DISABLED_OOM:
return OSD_MESSAGE_STR("MEM LOW");
case ARMING_DISABLED_INVALID_SETTING:
return OSD_MESSAGE_STR("ERR SETTING");
case ARMING_DISABLED_CLI:
return OSD_MESSAGE_STR("CLI");
case ARMING_DISABLED_PWM_OUTPUT_ERROR:
return OSD_MESSAGE_STR("PWM ERR");
case ARMING_DISABLED_NO_PREARM:
return OSD_MESSAGE_STR("NO PREARM");
case ARMING_DISABLED_DSHOT_BEEPER:
return OSD_MESSAGE_STR("MOTOR BEEPER ACTIVE");
// Cases without message
case ARMING_DISABLED_LANDING_DETECTED:
FALLTHROUGH;
case ARMING_DISABLED_CMS_MENU:
FALLTHROUGH;
case ARMING_DISABLED_OSD_MENU:
FALLTHROUGH;
case ARMING_DISABLED_ALL_FLAGS:
FALLTHROUGH;
case ARMED:
FALLTHROUGH;
case SIMULATOR_MODE_HITL:
FALLTHROUGH;
case SIMULATOR_MODE_SITL:
FALLTHROUGH;
case WAS_EVER_ARMED:
break;
}
return NULL;
}
static char * osdFailsafePhaseMessage(void)
{
// See failsafe.h for each phase explanation
switch (failsafePhase()) {
case FAILSAFE_RETURN_TO_HOME:
// XXX: Keep this in sync with OSD_FLYMODE.
return OSD_MESSAGE_STR("(RTH)");
case FAILSAFE_LANDING:
// This should be considered an emergengy landing
return OSD_MESSAGE_STR("(EMRGY LANDING)");
case FAILSAFE_RX_LOSS_MONITORING:
// Only reachable from FAILSAFE_LANDED, which performs
// a disarm. Since aircraft has been disarmed, we no
// longer show failsafe details.
FALLTHROUGH;
case FAILSAFE_LANDED:
// Very brief, disarms and transitions into
// FAILSAFE_RX_LOSS_MONITORING. Note that it prevents
// further rearming via ARMING_DISABLED_FAILSAFE_SYSTEM,
// so we'll show the user how to re-arm in when
// that flag is the reason to prevent arming.
FALLTHROUGH;
case FAILSAFE_RX_LOSS_IDLE:
// This only happens when user has chosen NONE as FS
// procedure. The recovery messages should be enough.
FALLTHROUGH;
case FAILSAFE_IDLE:
// Failsafe not active
FALLTHROUGH;
case FAILSAFE_RX_LOSS_DETECTED:
// Very brief, changes to FAILSAFE_RX_LOSS_RECOVERED
// or the FS procedure immediately.
FALLTHROUGH;
case FAILSAFE_RX_LOSS_RECOVERED:
// Exiting failsafe
break;
}
return NULL;
}
static char * osdFailsafeInfoMessage(void)
{
if (failsafeIsReceivingRxData()) {
// User must move sticks to exit FS mode
return OSD_MESSAGE_STR("!MOVE STICKS TO EXIT FS!");
}
return OSD_MESSAGE_STR(RC_RX_LINK_LOST_MSG);
}
static char * navigationStateMessage(void)
{
switch (NAV_Status.state) {
case MW_NAV_STATE_NONE:
break;
case MW_NAV_STATE_RTH_START:
return OSD_MESSAGE_STR("STARTING RTH");
case MW_NAV_STATE_RTH_CLIMB:
return OSD_MESSAGE_STR("ADJUSTING RTH ALTITUDE");
case MW_NAV_STATE_RTH_ENROUTE:
// TODO: Break this up between climb and head home
return OSD_MESSAGE_STR("EN ROUTE TO HOME");
case MW_NAV_STATE_HOLD_INFINIT:
// Used by HOLD flight modes. No information to add.
break;
case MW_NAV_STATE_HOLD_TIMED:
// TODO: Maybe we can display a count down
return OSD_MESSAGE_STR("HOLDING WAYPOINT");
break;
case MW_NAV_STATE_WP_ENROUTE:
// TODO: Show WP number
return OSD_MESSAGE_STR("TO WP");
case MW_NAV_STATE_PROCESS_NEXT:
return OSD_MESSAGE_STR("PREPARING FOR NEXT WAYPOINT");
case MW_NAV_STATE_DO_JUMP:
// Not used
break;
case MW_NAV_STATE_LAND_START:
// Not used
break;
case MW_NAV_STATE_EMERGENCY_LANDING:
return OSD_MESSAGE_STR("EMRGY LANDING");
case MW_NAV_STATE_LAND_IN_PROGRESS:
return OSD_MESSAGE_STR("LANDING");
case MW_NAV_STATE_HOVER_ABOVE_HOME:
if (STATE(FIXED_WING_LEGACY)) {
return OSD_MESSAGE_STR("LOITERING AROUND HOME");
}
return OSD_MESSAGE_STR("HOVERING");
case MW_NAV_STATE_LANDED:
return OSD_MESSAGE_STR("LANDED");
case MW_NAV_STATE_LAND_SETTLE:
return OSD_MESSAGE_STR("PREPARING TO LAND");
case MW_NAV_STATE_LAND_START_DESCENT:
// Not used
break;
}
return NULL;
}
/**
* Converts velocity based on the current unit system (kmh or mph).
* @param alt Raw velocity (i.e. as taken from gpsSol.groundSpeed in centimeters/second)
*/
static int32_t osdConvertVelocityToUnit(int32_t vel)
{
switch (osdConfig()->units) {
case OSD_UNIT_UK:
FALLTHROUGH;
case OSD_UNIT_METRIC_MPH:
FALLTHROUGH;
case OSD_UNIT_IMPERIAL:
return CMSEC_TO_CENTIMPH(vel) / 100; // Convert to mph
case OSD_UNIT_GA:
return CMSEC_TO_CENTIKNOTS(vel) / 100; // Convert to Knots
case OSD_UNIT_METRIC:
return CMSEC_TO_CENTIKPH(vel) / 100; // Convert to kmh
}
// Unreachable
return -1;
}
/**
* Converts velocity into a string based on the current unit system.
* @param alt Raw velocity (i.e. as taken from gpsSol.groundSpeed in centimeters/seconds)
*/
void osdDJIFormatVelocityStr(char* buff)
{
char sourceBuf[4];
int vel = 0;
switch (djiOsdConfig()->messageSpeedSource) {
case OSD_SPEED_SOURCE_GROUND:
strcpy(sourceBuf, "GRD");
vel = gpsSol.groundSpeed;
break;
case OSD_SPEED_SOURCE_3D:
strcpy(sourceBuf, "3D");
vel = osdGet3DSpeed();
break;
case OSD_SPEED_SOURCE_AIR:
strcpy(sourceBuf, "AIR");
#ifdef USE_PITOT
vel = getAirspeedEstimate();
#endif
break;
}
switch (osdConfig()->units) {
case OSD_UNIT_UK:
FALLTHROUGH;
case OSD_UNIT_METRIC_MPH:
FALLTHROUGH;
case OSD_UNIT_IMPERIAL:
tfp_sprintf(buff, "%s %3d MPH", sourceBuf, (int)osdConvertVelocityToUnit(vel));
break;
case OSD_UNIT_GA:
tfp_sprintf(buff, "%s %3d KT", sourceBuf, (int)osdConvertVelocityToUnit(vel));
break;
case OSD_UNIT_METRIC:
tfp_sprintf(buff, "%s %3d KPH", sourceBuf, (int)osdConvertVelocityToUnit(vel));
break;
}
}
static void osdDJIFormatThrottlePosition(char *buff, bool autoThr )
{
int16_t thr = rxGetChannelValue(THROTTLE);
if (autoThr && navigationIsControllingThrottle()) {
thr = rcCommand[THROTTLE];
}
tfp_sprintf(buff, "%3ld%s", (unsigned long)((constrain(thr, PWM_RANGE_MIN, PWM_RANGE_MAX) - PWM_RANGE_MIN) * 100 / (PWM_RANGE_MAX - PWM_RANGE_MIN)), "%THR");
}
/**
* Converts distance into a string based on the current unit system.
* @param dist Distance in centimeters
*/
static void osdDJIFormatDistanceStr(char *buff, int32_t dist)
{
int32_t centifeet;
switch (osdConfig()->units) {
case OSD_UNIT_UK:
FALLTHROUGH;
case OSD_UNIT_IMPERIAL:
centifeet = CENTIMETERS_TO_CENTIFEET(dist);
if (abs(centifeet) < FEET_PER_MILE * 100 / 2) {
// Show feet when dist < 0.5mi
tfp_sprintf(buff, "%d%s", (int)(centifeet / 100), "FT");
}
else {
// Show miles when dist >= 0.5mi
tfp_sprintf(buff, "%d.%02d%s", (int)(centifeet / (100*FEET_PER_MILE)),
(abs(centifeet) % (100 * FEET_PER_MILE)) / FEET_PER_MILE, "Mi");
}
break;
case OSD_UNIT_GA:
centifeet = CENTIMETERS_TO_CENTIFEET(dist);
if (abs(centifeet) < FEET_PER_NAUTICALMILE * 100 / 2) {
// Show feet when dist < 0.5mi
tfp_sprintf(buff, "%d%s", (int)(centifeet / 100), "FT");
}
else {
// Show miles when dist >= 0.5mi
tfp_sprintf(buff, "%d.%02d%s", (int)(centifeet / (100 * FEET_PER_NAUTICALMILE)),
(int)((abs(centifeet) % (int)(100 * FEET_PER_NAUTICALMILE)) / FEET_PER_NAUTICALMILE), "NM");
}
break;
case OSD_UNIT_METRIC_MPH:
FALLTHROUGH;
case OSD_UNIT_METRIC:
if (abs(dist) < METERS_PER_KILOMETER * 100) {
// Show meters when dist < 1km
tfp_sprintf(buff, "%d%s", (int)(dist / 100), "M");
}
else {
// Show kilometers when dist >= 1km
tfp_sprintf(buff, "%d.%02d%s", (int)(dist / (100*METERS_PER_KILOMETER)),
(abs(dist) % (100 * METERS_PER_KILOMETER)) / METERS_PER_KILOMETER, "KM");
}
break;
}
}
static void osdDJIEfficiencyMahPerKM(char *buff)
{
// amperage is in centi amps, speed is in cms/s. We want
// mah/km. Values over 999 are considered useless and
// displayed as "---""
static pt1Filter_t eFilterState;
static timeUs_t efficiencyUpdated = 0;
int32_t value = 0;
timeUs_t currentTimeUs = micros();
timeDelta_t efficiencyTimeDelta = cmpTimeUs(currentTimeUs, efficiencyUpdated);
if ((STATE(GPS_FIX)
#ifdef USE_GPS_FIX_ESTIMATION
|| STATE(GPS_ESTIMATED_FIX)
#endif
) && gpsSol.groundSpeed > 0) {
if (efficiencyTimeDelta >= EFFICIENCY_UPDATE_INTERVAL) {
value = pt1FilterApply4(&eFilterState, ((float)getAmperage() / gpsSol.groundSpeed) / 0.0036f,
1, US2S(efficiencyTimeDelta));
efficiencyUpdated = currentTimeUs;
} else {
value = eFilterState.state;
}
}
if (value > 0 && value <= 999) {
tfp_sprintf(buff, "%3d%s", (int)value, "mAhKM");
} else {
tfp_sprintf(buff, "%s", "---mAhKM");
}
}
static void osdDJIAdjustmentMessage(char *buff, uint8_t adjustmentFunction)
{
switch (adjustmentFunction) {
case ADJUSTMENT_RC_EXPO:
tfp_sprintf(buff, "RCE %d", currentControlRateProfile->stabilized.rcExpo8);
break;
case ADJUSTMENT_RC_YAW_EXPO:
tfp_sprintf(buff, "RCYE %3d", currentControlRateProfile->stabilized.rcYawExpo8);
break;
case ADJUSTMENT_MANUAL_RC_EXPO:
tfp_sprintf(buff, "MRCE %3d", currentControlRateProfile->manual.rcExpo8);
break;
case ADJUSTMENT_MANUAL_RC_YAW_EXPO:
tfp_sprintf(buff, "MRCYE %3d", currentControlRateProfile->manual.rcYawExpo8);
break;
case ADJUSTMENT_THROTTLE_EXPO:
tfp_sprintf(buff, "TE %3d", currentControlRateProfile->throttle.rcExpo8);
break;
case ADJUSTMENT_PITCH_ROLL_RATE:
tfp_sprintf(buff, "PRR %3d %3d", currentControlRateProfile->stabilized.rates[FD_PITCH], currentControlRateProfile->stabilized.rates[FD_ROLL]);
break;
case ADJUSTMENT_PITCH_RATE:
tfp_sprintf(buff, "PR %3d", currentControlRateProfile->stabilized.rates[FD_PITCH]);
break;
case ADJUSTMENT_ROLL_RATE:
tfp_sprintf(buff, "RR %3d", currentControlRateProfile->stabilized.rates[FD_ROLL]);
break;
case ADJUSTMENT_MANUAL_PITCH_ROLL_RATE:
tfp_sprintf(buff, "MPRR %3d %3d", currentControlRateProfile->manual.rates[FD_PITCH], currentControlRateProfile->manual.rates[FD_ROLL]);
break;
case ADJUSTMENT_MANUAL_PITCH_RATE:
tfp_sprintf(buff, "MPR %3d", currentControlRateProfile->manual.rates[FD_PITCH]);
break;
case ADJUSTMENT_MANUAL_ROLL_RATE:
tfp_sprintf(buff, "MRR %3d", currentControlRateProfile->manual.rates[FD_ROLL]);
break;
case ADJUSTMENT_YAW_RATE:
tfp_sprintf(buff, "YR %3d", currentControlRateProfile->stabilized.rates[FD_YAW]);
break;
case ADJUSTMENT_MANUAL_YAW_RATE:
tfp_sprintf(buff, "MYR %3d", currentControlRateProfile->manual.rates[FD_YAW]);
break;
case ADJUSTMENT_PITCH_ROLL_P:
tfp_sprintf(buff, "PRP %3d %3d", pidBankMutable()->pid[PID_PITCH].P, pidBankMutable()->pid[PID_ROLL].P);
break;
case ADJUSTMENT_PITCH_P:
tfp_sprintf(buff, "PP %3d", pidBankMutable()->pid[PID_PITCH].P);
break;
case ADJUSTMENT_ROLL_P:
tfp_sprintf(buff, "RP %3d", pidBankMutable()->pid[PID_ROLL].P);
break;
case ADJUSTMENT_PITCH_ROLL_I:
tfp_sprintf(buff, "PRI %3d %3d", pidBankMutable()->pid[PID_PITCH].I, pidBankMutable()->pid[PID_ROLL].I);
break;
case ADJUSTMENT_PITCH_I:
tfp_sprintf(buff, "PI %3d", pidBankMutable()->pid[PID_PITCH].I);
break;
case ADJUSTMENT_ROLL_I:
tfp_sprintf(buff, "RI %3d", pidBankMutable()->pid[PID_ROLL].I);
break;
case ADJUSTMENT_PITCH_ROLL_D:
tfp_sprintf(buff, "PRD %3d %3d", pidBankMutable()->pid[PID_PITCH].D, pidBankMutable()->pid[PID_ROLL].D);
break;
case ADJUSTMENT_PITCH_ROLL_FF:
tfp_sprintf(buff, "PRFF %3d %3d", pidBankMutable()->pid[PID_PITCH].FF, pidBankMutable()->pid[PID_ROLL].FF);
break;
case ADJUSTMENT_PITCH_D:
tfp_sprintf(buff, "PD %3d", pidBankMutable()->pid[PID_PITCH].D);
break;
case ADJUSTMENT_PITCH_FF:
tfp_sprintf(buff, "PFF %3d", pidBankMutable()->pid[PID_PITCH].FF);
break;
case ADJUSTMENT_ROLL_D:
tfp_sprintf(buff, "RD %3d", pidBankMutable()->pid[PID_ROLL].D);
break;
case ADJUSTMENT_ROLL_FF:
tfp_sprintf(buff, "RFF %3d", pidBankMutable()->pid[PID_ROLL].FF);
break;
case ADJUSTMENT_YAW_P:
tfp_sprintf(buff, "YP %3d", pidBankMutable()->pid[PID_YAW].P);
break;
case ADJUSTMENT_YAW_I:
tfp_sprintf(buff, "YI %3d", pidBankMutable()->pid[PID_YAW].I);
break;
case ADJUSTMENT_YAW_D:
tfp_sprintf(buff, "YD %3d", pidBankMutable()->pid[PID_YAW].D);
break;
case ADJUSTMENT_YAW_FF:
tfp_sprintf(buff, "YFF %3d", pidBankMutable()->pid[PID_YAW].FF);
break;
case ADJUSTMENT_NAV_FW_CRUISE_THR:
tfp_sprintf(buff, "CR %4d", currentBatteryProfileMutable->nav.fw.cruise_throttle);
break;
case ADJUSTMENT_NAV_FW_PITCH2THR:
tfp_sprintf(buff, "P2T %3d", currentBatteryProfileMutable->nav.fw.pitch_to_throttle);
break;
case ADJUSTMENT_ROLL_BOARD_ALIGNMENT:
tfp_sprintf(buff, "RBA %3d", boardAlignment()->rollDeciDegrees);
break;
case ADJUSTMENT_PITCH_BOARD_ALIGNMENT:
tfp_sprintf(buff, "PBA %3d", boardAlignment()->pitchDeciDegrees);
break;
case ADJUSTMENT_LEVEL_P:
tfp_sprintf(buff, "LP %3d", pidBankMutable()->pid[PID_LEVEL].P);
break;
case ADJUSTMENT_LEVEL_I:
tfp_sprintf(buff, "LI %3d", pidBankMutable()->pid[PID_LEVEL].I);
break;
case ADJUSTMENT_LEVEL_D:
tfp_sprintf(buff, "LD %3d", pidBankMutable()->pid[PID_LEVEL].D);
break;
case ADJUSTMENT_POS_XY_P:
tfp_sprintf(buff, "PXYP %3d", pidBankMutable()->pid[PID_POS_XY].P);
break;
case ADJUSTMENT_POS_XY_I:
tfp_sprintf(buff, "PXYI %3d", pidBankMutable()->pid[PID_POS_XY].I);
break;
case ADJUSTMENT_POS_XY_D:
tfp_sprintf(buff, "PXYD %3d", pidBankMutable()->pid[PID_POS_XY].D);
break;
case ADJUSTMENT_POS_Z_P:
tfp_sprintf(buff, "PZP %3d", pidBankMutable()->pid[PID_POS_Z].P);
break;
case ADJUSTMENT_POS_Z_I:
tfp_sprintf(buff, "PZI %3d", pidBankMutable()->pid[PID_POS_Z].I);
break;
case ADJUSTMENT_POS_Z_D:
tfp_sprintf(buff, "PZD %3d", pidBankMutable()->pid[PID_POS_Z].D);
break;
case ADJUSTMENT_HEADING_P:
tfp_sprintf(buff, "HP %3d", pidBankMutable()->pid[PID_HEADING].P);
break;
case ADJUSTMENT_VEL_XY_P:
tfp_sprintf(buff, "VXYP %3d", pidBankMutable()->pid[PID_VEL_XY].P);
break;
case ADJUSTMENT_VEL_XY_I:
tfp_sprintf(buff, "VXYI %3d", pidBankMutable()->pid[PID_VEL_XY].I);
break;
case ADJUSTMENT_VEL_XY_D:
tfp_sprintf(buff, "VXYD %3d", pidBankMutable()->pid[PID_VEL_XY].D);
break;
case ADJUSTMENT_VEL_Z_P:
tfp_sprintf(buff, "VZP %3d", pidBankMutable()->pid[PID_VEL_Z].P);
break;
case ADJUSTMENT_VEL_Z_I:
tfp_sprintf(buff, "VZI %3d", pidBankMutable()->pid[PID_VEL_Z].I);
break;
case ADJUSTMENT_VEL_Z_D:
tfp_sprintf(buff, "VZD %3d", pidBankMutable()->pid[PID_VEL_Z].D);
break;
case ADJUSTMENT_FW_MIN_THROTTLE_DOWN_PITCH_ANGLE:
tfp_sprintf(buff, "MTDPA %4d", navConfigMutable()->fw.minThrottleDownPitchAngle);
break;
case ADJUSTMENT_TPA:
tfp_sprintf(buff, "TPA %3d", currentControlRateProfile->throttle.dynPID);
break;
case ADJUSTMENT_TPA_BREAKPOINT:
tfp_sprintf(buff, "TPABP %4d", currentControlRateProfile->throttle.pa_breakpoint);
break;
case ADJUSTMENT_NAV_FW_CONTROL_SMOOTHNESS:
tfp_sprintf(buff, "CSM %3d", navConfigMutable()->fw.control_smoothness);
break;
#ifdef USE_MULTI_MISSION
case ADJUSTMENT_NAV_WP_MULTI_MISSION_INDEX:
tfp_sprintf(buff, "WPI %3d", navConfigMutable()->general.waypoint_multi_mission_index);
break;
#endif
default:
tfp_sprintf(buff, "UNSUPPORTED");
break;
}
}
static bool osdDJIFormatAdjustments(char *buff)
{
uint8_t adjustmentFunctions[MAX_SIMULTANEOUS_ADJUSTMENT_COUNT];
uint8_t adjustmentCount = getActiveAdjustmentFunctions(adjustmentFunctions);
if (adjustmentCount > 0 && buff != NULL) {
osdDJIAdjustmentMessage(buff, adjustmentFunctions[OSD_ALTERNATING_CHOICES(DJI_ALTERNATING_DURATION_LONG, adjustmentCount)]);
}
return adjustmentCount > 0;
}
static bool djiFormatMessages(char *buff)
{
bool haveMessage = false;
char messageBuf[MAX(SETTING_MAX_NAME_LENGTH, OSD_MESSAGE_LENGTH+1)];
if (ARMING_FLAG(ARMED)) {
// Aircraft is armed. We might have up to 6