/
yaapu7.lua
1646 lines (1510 loc) · 50.1 KB
/
yaapu7.lua
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
--
-- A FRSKY SPort/FPort/FPort2 and TBS CRSF telemetry script for the Taranis class radios
-- based on ArduPilot's passthrough telemetry protocol
--
-- Author: Alessandro Apostoli, https://github.com/yaapu
--
-- This program is free software; you can redistribute it 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 program 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>.
--
--[[
ALARM_TYPE_MIN needs arming (min has to be reached first), value below level for grace, once armed is periodic, reset on landing
ALARM_TYPE_MAX no arming, value above level for grace, once armed is periodic, reset on landing
ALARM_TYPE_TIMER no arming, fired periodically, spoken time, reset on landing
ALARM_TYPE_BATT needs arming (min has to be reached first), value below level for grace, no reset on landing
{
1 = notified,
2 = alarm start,
3 = armed,
4 = type(0=min,1=max,2=timer,3=batt),
5 = grace duration
6 = ready
7 = last alarm
}
--]]
local unitScale = getGeneralSettings().imperial == 0 and 1 or 3.28084
local unitLabel = getGeneralSettings().imperial == 0 and "m" or "ft"
local unitLongScale = getGeneralSettings().imperial == 0 and 1/1000 or 1/1609.34
local unitLongLabel = getGeneralSettings().imperial == 0 and "km" or "mi"
local function doGarbageCollect()
collectgarbage()
collectgarbage()
end
local frameTypes = {}
-- copter
frameTypes[0] = "c"
frameTypes[2] = "c"
frameTypes[3] = "c"
frameTypes[4] = "c"
frameTypes[7] = "a"
frameTypes[13] = "c"
frameTypes[14] = "c"
frameTypes[15] = "c"
frameTypes[29] = "c"
-- plane
frameTypes[1] = "p"
frameTypes[16] = "p"
frameTypes[19] = "p"
frameTypes[20] = "p"
frameTypes[21] = "p"
frameTypes[22] = "p"
frameTypes[23] = "p"
frameTypes[24] = "p"
frameTypes[25] = "p"
frameTypes[28] = "p"
-- rover
frameTypes[10] = "r"
-- boat
frameTypes[11] = "b"
local frame = {}
local frameType = nil
local soundFileBasePath = "/SOUNDS/yaapu0"
local gpsStatuses = {
[0]="GPS",
[1]="Lock",
[2]="2D",
[3]="3D",
[4]="DG",
[5]="RT",
[6]="RT",
}
-- EMR,ALR,CRT,ERR,WRN,NOT,INF,DBG
local mavSeverity = {
[0] = "EMR",
[1] = "ALR",
[2] = "CRT",
[3] = "ERR",
[4] = "WRN",
[5] = "NOT",
[6] = "INF",
[7] = "DBG",
}
--------------------------------
-- FLVSS 1
local cell1min = 0
local cell1sum = 0
-- FLVSS 2
local cell2min = 0
local cell2sum = 0
-- FC 1
local cell1sumFC = 0
-- used to calculate cellcount
local cell1maxFC = 0
local cell2maxFC = 0
-- FC 2
local cell2sumFC = 0
--------------------------------
-- BATT
local battery = {0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0}
local cell1count = 0
local cell2count = 0
local batt1sources = {
vs = false,
fc = false
}
local batt2sources = {
vs = false,
fc = false
}
-- TELEMETRY
local noTelemetryData = 1
local hideNoTelemetry = false
local telemetry = {}
-- STATUS
telemetry.flightMode = 0
telemetry.simpleMode = 0
telemetry.landComplete = 0
telemetry.statusArmed = 0
telemetry.battFailsafe = 0
telemetry.ekfFailsafe = 0
telemetry.failsafe = 0
telemetry.fencePresent = 0
telemetry.fenceBreached = 0
telemetry.throttle = 0
telemetry.imuTemp = 0
-- GPS
telemetry.numSats = 0
telemetry.gpsStatus = 0
telemetry.gpsHdopC = 100
telemetry.gpsAlt = 0
-- BATT 1
telemetry.batt1volt = 0
telemetry.batt1current = 0
telemetry.batt1mah = 0
-- BATT 2
telemetry.batt2volt = 0
telemetry.batt2current = 0
telemetry.batt2mah = 0
-- HOME
telemetry.homeDist = 0
telemetry.homeAlt = 0
telemetry.homeAngle = -1
-- VELANDYAW
telemetry.vSpeed = 0
telemetry.hSpeed = 0
telemetry.yaw = 0
-- ROLLPITCH
telemetry.roll = 0
telemetry.pitch = 0
telemetry.range = 0
-- PARAMS
telemetry.frameType = -1
telemetry.batt1Capacity = 0
telemetry.batt2Capacity = 0
-- WP
telemetry.wpNumber = 0
telemetry.wpDistance = 0
telemetry.wpXTError = 0
telemetry.wpBearing = 0
telemetry.wpCommands = 0
-- VFR
telemetry.airspeed = 0
telemetry.throttle = 0
telemetry.baroAlt = 0
-- TOTAL DISTANCE
telemetry.totalDist = 0
--
telemetry.rpm1 = 0
telemetry.rpm2 = 0
--
telemetry.heightAboveTerrain = 0
telemetry.terrainUnhealthy = 0
-- FLIGHT TIME
local lastTimerStart = 0
-- MESSAGES
local msgBuffer = ""
local lastMsgValue = 0
local lastMsgTime = 0
local lastMessage
local statusBarMsg
local lastMessageSeverity = 0
local lastMessageCount = 1
local messageCount = 0
local messageRow = 0
local messages = {}
-- EVENTS
local lastStatusArmed = 0
local lastGpsStatus = 0
local lastFlightMode = 0
local lastSimpleMode = 0
-- BATTERY LEVELS
local batLevel = 99
local lastBattLevel = 13
-- TOTAL DISTANCE
local lastUpdateTotDist = 0
local lastSpeed = 0
-- STATUS
local status = {}
-- BLINK SUPPORT
local blinktime = getTime()
local blinkon = false
-- CRSF rssi support
local rssiCRSF = 0
status.showDualBattery = false
status.battAlertLevel1 = false
status.battAlertLevel2 = false
status.battsource = "na"
status.flightTime = 0 -- updated from model timer 3
status.timerRunning = 0 -- triggered by landcomplete from AP
status.showMinMaxValues = false
status.terrainLastData = getTime()
status.terrainEnabled = 0
status.airspeedEnabled = 0
-- 00 05 10 15 20 25 30 40 50 60 70 80 90
-- MIN MAX
local minmaxValues = {0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0}
-- LIBRARY LOADING
local libBasePath = "/SCRIPTS/TELEMETRY/yaapu/"
local menuLibFile = "menu7"
local drawLibFile = "draw7"
local drawLib = nil
local menuLib = nil
local resetLib = nil
local centerPanel = nil
local rightPanel = nil
local leftPanel = nil
local altView = nil
------------------------
-- CONFIGURATION
------------------------
local conf = {
language = "en",
battAlertLevel1 = 0,
battAlertLevel2 = 0,
battCapOverride1 = 0,
battCapOverride2 = 0,
disableAllSounds = false,
disableMsgBeep = 1,
timerAlert = 0,
minAltitudeAlert = 0,
maxAltitudeAlert = 0,
maxDistanceAlert = 0,
repeatAlertsPeriod = 10,
battConf = 1, -- 1=parallel,2=other
cell1Count = 0,
cell2Count = 0,
rangeFinderMax = 0,
horSpeedMultiplier = 1,
vertSpeedMultiplier = 1,
horSpeedLabel = "m",
vertSpeedLabel = "m/s",
centerPanel = nil,
rightPanel = nil,
leftPanel = nil,
altView = nil,
defaultBattSource = "na",
enablePX4Modes = false,
enableHaptic = false,
enableCRSF = false
}
--[[
ALARM_TYPE_MIN needs arming (min has to be reached first), value below level for grace, once armed is periodic, reset on landing
ALARM_TYPE_MAX no arming, value above level for grace, once armed is periodic, reset on landing
ALARM_TYPE_TIMER no arming, fired periodically, spoken time, reset on landing
ALARM_TYPE_BATT needs arming (min has to be reached first), value below level for grace, no reset on landing
{
1 = notified,
2 = alarm start,
3 = armed,
4 = type(0=min,1=max,2=timer,3=batt),
5 = grace duration
6 = ready
7 = last alarm
}
--]]
-------------------------
-- alarms
-------------------------
local alarms = {
--{ notified, alarm_start, armed, type(0=min,1=max,2=timer,3=batt), grace, ready, last_alarm}
{ false, 0 , false, 0, 0, false, 0}, --MIN_ALT
{ false, 0 , true, 1, 0, false, 0 }, --MAX_ALT
{ false, 0 , true, 1, 0, false, 0 }, --15
{ false, 0 , true, 1, 0, false, 0 }, --FS_EKF
{ false, 0 , true, 1, 0, false, 0 }, --FS_BAT
{ false, 0 , true, 2, 0, false, 0 }, --FLIGTH_TIME
{ false, 0 , false, 3, 4, false, 0 }, --BATT L1
{ false, 0 , false, 4, 4, false, 0 }, --BATT L2
{ false, 0 , true, 1, 0, false, 0 }, --FS
{ false, 0 , true, 1, 0, false, 0 }, --
{ false, 0 , true, 1, 0, false, 0 }, --
}
-------------------------
-- value transitions
-------------------------
local transitions = {
--{ last_value, last_changed, transition_done, delay }
{ 0, 0, false, 30 }, -- flightmode
}
-------------------------
-- message hash support
-------------------------
local shortHashes = {}
-- 16 bytes hashes
shortHashes[554623408] = false -- "554623408.wav", "Takeoff complete"
shortHashes[3025044912] = false -- "3025044912.wav", "SmartRTL deactiv"
shortHashes[3956583920] = false -- "3956583920.wav", "EKF2 IMU0 is usi"
shortHashes[1309405592] = false -- "1309405592.wav", "EKF3 IMU0 is usi"
shortHashes[4091124880] = true -- "4091124880.wav", "Reached command "
shortHashes[3311875476] = true -- "3311875476.wav", "Reached waypoint"
shortHashes[1997782032] = true -- "1997782032.wav", "Passed waypoint "
local shortHash = nil
local parseShortHash = false
local hashByteIndex = 0
local hash = 2166136261
local showMessages = false
local showConfigMenu = false
local showAltView = false
local loadCycle = 0
-- telemetry pop function, either SPort or CRSF
local telemetryPop = nil
-----------------------------
-- clears the loaded table
-- and recovers memory
-----------------------------
local function clearTable(t)
if type(t)=="table" then
for i,v in pairs(t) do
if type(v) == "table" then
clearTable(v)
end
t[i] = nil
end
end
t = nil
-- call collectgarbage twice
doGarbageCollect()
end
local function doLibrary(filename)
local success,f = pcall(loadScript,libBasePath..filename..".lua")
if success then
local ret = f()
doGarbageCollect()
return ret
else
doGarbageCollect()
return nil
end
end
local function unloadPanels()
clearTable(centerPanel)
clearTable(rightPanel)
clearTable(leftPanel)
centerPanel = nil
rightPanel = nil
leftPanel = nil
doGarbageCollect()
end
local function loadPanels()
if centerPanel == nil and loadCycle == 4 then
centerPanel = doLibrary(conf.centerPanel)
end
if rightPanel == nil and loadCycle == 6 then
rightPanel = doLibrary(conf.rightPanel)
end
if leftPanel == nil and loadCycle == 2 then
leftPanel = doLibrary(conf.leftPanel)
end
doGarbageCollect()
end
-- prevent same file from beeing played too fast
local lastSoundTime = 0
local function playSound(soundFile,skipHaptic)
if conf.enableHaptic and skipHaptic == nil then
playHaptic(12,0)
end
if conf.disableAllSounds then
return
end
-- prevent OpenTX play queue from getting too big
if soundFile == "../inf" then
if getTime() - lastSoundTime > 65 then
lastSoundTime = getTime()
else
return
end
end
playFile(soundFileBasePath .."/"..conf.language.."/".. soundFile..".wav")
end
----------------------------------------------
-- sound file has same name as flightmode all lowercase with .wav extension
----------------------------------------------
local function playFlightMode(flightMode)
if conf.enableHaptic then
playHaptic(12,0)
end
if conf.disableAllSounds then
return
end
if frame.flightModes then
if frame.flightModes[flightMode] ~= nil then
playFile(soundFileBasePath.."/"..conf.language.."/".. frame.flightModes[flightMode] .. ((frameType=="r" or frameType=="b") and "_r.wav" or ".wav"))
end
end
end
local function haversine(lat1, lon1, lat2, lon2)
lat1 = lat1 * math.pi / 180
lon1 = lon1 * math.pi / 180
lat2 = lat2 * math.pi / 180
lon2 = lon2 * math.pi / 180
lat_dist = lat2-lat1
lon_dist = lon2-lon1
lat_hsin = math.pow(math.sin(lat_dist/2),2)
lon_hsin = math.pow(math.sin(lon_dist/2),2)
a = lat_hsin + math.cos(lat1) * math.cos(lat2) * lon_hsin
return 2 * 6372.8 * math.asin(math.sqrt(a)) * 1000
end
local function formatMessage(severity, msg)
if lastMessageCount > 1 then
return string.format("%d:%s (x%d) %s", messageCount, mavSeverity[severity], lastMessageCount, msg)
else
return string.format("%d:%s %s", messageCount, mavSeverity[severity], msg)
end
end
--[[
--------------------
-- FNV HASH
--------------------
function fnv(str)
local hash = 2166136261
for char in string.gmatch(str, ".") do
hash = bit32.bxor(hash, string.byte(char))
hash = (hash * 16777619) % 2^32
end
return hash
end
--]]
local lastMsgTime = getTime()
local function pushMessage(severity, msg)
if conf.enableHaptic then
playHaptic(12,0)
end
local now = getTime()
if now - lastMsgTime > 50 then
local silence = conf.disableMsgBeep == 3 or (severity >=5 and conf.disableMsgBeep == 2)
if silence == false then
playSound("../" .. mavSeverity[severity],true)
end
lastMsgTime = now
end
if msg == lastMessage then
lastMessageCount = lastMessageCount + 1
else
messageCount = messageCount + lastMessageCount
lastMessageCount = 1
messageRow = messageRow + 1
end
local longMsg = formatMessage(severity,msg)
doGarbageCollect()
if #longMsg > 28 then
if msg == lastMessage then
messageRow = messageRow - 1
end
messages[(messageRow-1) % 9] = string.sub(longMsg, 1, 28)
statusBarMsg = messages[(messageRow-1) % 9]
messageRow = messageRow + 1
messages[(messageRow-1) % 9] = " "..string.sub(longMsg, 28+1, 60)
else
messages[(messageRow-1) % 9] = longMsg
statusBarMsg = longMsg
end
lastMessage = msg
lastMessageSeverity = severity
msg = nil
doGarbageCollect()
end
local function startTimer()
lastTimerStart = getTime()/100
model.setTimer(2,{mode=1})
end
local function stopTimer()
model.setTimer(2,{mode=0})
lastTimerStart = 0
end
local function reset()
---------------
-- BATT
---------------
cell1min = 0
cell1sum = 0
cell2min = 0
cell2sum = 0
cell1sumFC = 0
cell1maxFC = 0
cell2sumFC = 0
cell1count = 0
cell2count = 0
clearTable(minmaxValues)
minmaxValues = {0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0}
---------------
-- TELEMETRY
---------------
noTelemetryData = 1
hideNoTelemetry = false
---------------
-- FLIGHT TIME
---------------
lastTimerStart = 0
---------------
-- MESSAGES
---------------
msgBuffer = ""
lastMsgValue = 0
lastMsgTime = 0
lastMessage = nil
lastMessageSeverity = 0
lastMessageCount = 1
messageCount = 0
messageRow = 0
clearTable(messages)
messages = {}
---------------
-- EVENTS
---------------
lastStatusArmed = 0
lastGpsStatus = 0
lastFlightMode = 0
lastSimpleMode = 0
---------------
-- BATTERY LEVELS
---------------
batLevel = 99
lastBattLevel = 13
---------------
-- TOTAL DISTANCE
---------------
lastUpdateTotDist = 0
lastSpeed = 0
-- unload DRAW
clearTable(drawLib)
drawLib = nil
if resetLib == nil then
resetLib = doLibrary("reset")
end
-- reset all
resetLib.resetTelemetry(status,telemetry,battery,alarms,transitions)
-- release resources
clearTable(resetLib)
resetLib = nil
-- recover memory
doGarbageCollect()
-- done
pushMessage(6,"Telemetry reset done.")
playSound("yaapu")
end
local function updateHash(c)
hash = bit32.bxor(hash, c)
hash = (hash * 16777619) % 2^32
hashByteIndex = hashByteIndex+1
-- check if this hash matches any 16bytes prefix hash
if hashByteIndex == 16 then
parseShortHash = shortHashes[hash]
if parseShortHash ~= nil then
shortHash = hash
end
end
end
local function playHash()
-- try to play the hash sound file without checking for existence
-- OpenTX will gracefully ignore it :-)
playSound(tostring(shortHash == nil and hash or shortHash),true)
-- if required parse parameter and play it!
if parseShortHash == true then
local param = string.match(msgBuffer, ".*#(%d+).*")
if param ~= nil then
playNumber(tonumber(param),0)
end
end
end
local function resetHash()
-- reset hash for next string
parseShortHash = false
shortHash = nil
hash = 2166136261
hashByteIndex = 0
end
local function processTelemetry(appId, value, now)
if appId == 0x5006 then -- ROLLPITCH
-- roll [0,1800] ==> [-180,180]
telemetry.roll = (math.min(bit32.extract(value,0,11),1800) - 900) * 0.2
-- pitch [0,900] ==> [-90,90]
telemetry.pitch = (math.min(bit32.extract(value,11,10),900) - 450) * 0.2
-- #define ATTIANDRNG_RNGFND_OFFSET 21
-- number encoded on 11 bits: 10 bits for digits + 1 for 10^power
telemetry.range = bit32.extract(value,22,10) * (10^bit32.extract(value,21,1)) -- cm
elseif appId == 0x5005 then -- VELANDYAW
telemetry.vSpeed = bit32.extract(value,1,7) * (10^bit32.extract(value,0,1)) * (bit32.extract(value,8,1) == 1 and -1 or 1)
telemetry.yaw = bit32.extract(value,17,11) * 0.2
-- once detected it's sticky
if bit32.extract(value,28,1) == 1 then
telemetry.airspeed = bit32.extract(value,10,7) * (10^bit32.extract(value,9,1)) -- dm/s
else
telemetry.hSpeed = bit32.extract(value,10,7) * (10^bit32.extract(value,9,1)) -- dm/s
end
if status.airspeedEnabled == 0 then
status.airspeedEnabled = bit32.extract(value,28,1)
end
elseif appId == 0x5001 then -- AP STATUS
telemetry.flightMode = bit32.extract(value,0,5)
telemetry.simpleMode = bit32.extract(value,5,2)
telemetry.landComplete = bit32.extract(value,7,1)
telemetry.statusArmed = bit32.extract(value,8,1)
telemetry.battFailsafe = bit32.extract(value,9,1)
telemetry.ekfFailsafe = bit32.extract(value,10,2)
telemetry.failsafe = bit32.extract(value,12,1)
telemetry.fencePresent = bit32.extract(value,13,1)
telemetry.fenceBreached = telemetry.fencePresent == 1 and bit32.extract(value,14,1) or 0 -- we ignore fence breach if fence is disabled
telemetry.throttle = math.floor(0.5 + (bit32.extract(value,19,6) * (bit32.extract(value,25,1) == 1 and -1 or 1) * 1.58)) -- signed throttle [-63,63] -> [-100,100]
-- IMU temperature: 0 means temp =< 19°, 63 means temp => 82°
telemetry.imuTemp = bit32.extract(value,26,6) + 19 -- C°
elseif appId == 0x5002 then -- GPS STATUS
telemetry.numSats = bit32.extract(value,0,4)
-- offset 4: NO_GPS = 0, NO_FIX = 1, GPS_OK_FIX_2D = 2, GPS_OK_FIX_3D or GPS_OK_FIX_3D_DGPS or GPS_OK_FIX_3D_RTK_FLOAT or GPS_OK_FIX_3D_RTK_FIXED = 3
-- offset 14: 0: no advanced fix, 1: GPS_OK_FIX_3D_DGPS, 2: GPS_OK_FIX_3D_RTK_FLOAT, 3: GPS_OK_FIX_3D_RTK_FIXED
telemetry.gpsStatus = bit32.extract(value,4,2) + bit32.extract(value,14,2)
telemetry.gpsHdopC = bit32.extract(value,7,7) * (10^bit32.extract(value,6,1)) -- dm
telemetry.gpsAlt = bit32.extract(value,24,7) * (10^bit32.extract(value,22,2)) * (bit32.extract(value,31,1) == 1 and -1 or 1) -- dm
elseif appId == 0x5003 then -- BATT
telemetry.batt1volt = bit32.extract(value,0,9) -- dV
-- telemetry max is 51.1V, 51.2 is reported as 0.0, 52.3 is 0.1...60 is 88
-- if >= 12S and V > 51.1 ==> Vreal = 51.2 + telemetry.batt1volt
if conf.cell1Count >= 12 and telemetry.batt1volt < conf.cell1Count*20 then
-- assume a 2V as minimum acceptable "real" voltage
telemetry.batt1volt = 512 + telemetry.batt1volt
end
telemetry.batt1current = bit32.extract(value,10,7) * (10^bit32.extract(value,9,1)) --dA
telemetry.batt1mah = bit32.extract(value,17,15)
elseif appId == 0x5008 then -- BATT2
telemetry.batt2volt = bit32.extract(value,0,9)
-- telemetry max is 51.1V, 51.2 is reported as 0.0, 52.3 is 0.1...60 is 88
-- if >= 12S and V > 51.1 ==> Vreal = 51.2 + telemetry.batt1volt
if conf.cell2Count >= 12 and telemetry.batt2volt < conf.cell2Count*20 then
-- assume a 2Vx12 as minimum acceptable "real" voltage
telemetry.batt2volt = 512 + telemetry.batt2volt
end
telemetry.batt2current = bit32.extract(value,10,7) * (10^bit32.extract(value,9,1))
telemetry.batt2mah = bit32.extract(value,17,15)
elseif appId == 0x5004 then -- HOME
telemetry.homeDist = bit32.extract(value,2,10) * (10^bit32.extract(value,0,2))
telemetry.homeAlt = bit32.extract(value,14,10) * (10^bit32.extract(value,12,2)) * 0.1 * (bit32.extract(value,24,1) == 1 and -1 or 1) --m
telemetry.homeAngle = bit32.extract(value, 25, 7) * 3
elseif appId == 0x5000 then -- MESSAGES
if value ~= lastMsgValue then
lastMsgValue = value
local c
local msgEnd = false
for i=3,0,-1
do
c = bit32.extract(value,i*8,7)
if c ~= 0 then
msgBuffer = msgBuffer .. string.char(c)
updateHash(c)
else
msgEnd = true;
break;
end
end
doGarbageCollect()
if msgEnd then
-- push and display message
local severity = (bit32.extract(value,7,1) * 1) + (bit32.extract(value,15,1) * 2) + (bit32.extract(value,23,1) * 4)
pushMessage( severity, msgBuffer)
playHash()
resetHash()
msgBuffer = nil
-- recover memory
doGarbageCollect()
msgBuffer = ""
end
end
elseif appId == 0x5007 then -- PARAMS
local paramId = bit32.extract(value,24,4)
local paramValue = bit32.extract(value,0,24)
if paramId == 1 then
telemetry.frameType = paramValue
elseif paramId == 4 then
telemetry.batt1Capacity = paramValue
elseif paramId == 5 then
telemetry.batt2Capacity = paramValue
end
elseif appId == 0x5009 then -- WAYPOINTS @1Hz
telemetry.wpNumber = bit32.extract(value,0,10) -- wp index
telemetry.wpDistance = bit32.extract(value,12,10) * (10^bit32.extract(value,10,2)) -- meters
telemetry.wpXTError = bit32.extract(value,23,4) * (10^bit32.extract(value,22,1)) * (bit32.extract(value,27,1) == 1 and -1 or 1)-- meters
telemetry.wpBearing = bit32.extract(value,29,3) -- offset from cog with 45° resolution
elseif appId == 0x500A then -- 1 and 2
-- rpm1 and rpm2 are int16_t
local rpm1 = bit32.extract(value,0,16)
local rpm2 = bit32.extract(value,16,16)
telemetry.rpm1 = 10*(bit32.extract(value,15,1) == 0 and rpm1 or -1*(1+bit32.band(0x0000FFFF,bit32.bnot(rpm1)))) -- 2 complement if negative
telemetry.rpm2 = 10*(bit32.extract(value,31,1) == 0 and rpm2 or -1*(1+bit32.band(0x0000FFFF,bit32.bnot(rpm2)))) -- 2 complement if negative
elseif appId == 0x500B then --
telemetry.heightAboveTerrain = bit32.extract(value,2,10) * (10^bit32.extract(value,0,2)) * 0.1 * (bit32.extract(value,12,1) == 1 and -1 or 1) -- dm to meters
telemetry.terrainUnhealthy = bit32.extract(value,13,1)
status.terrainLastData = now
status.terrainEnabled = 1
--[[
elseif DATA_ID == 0x50F1 then -- RC CHANNELS
-- channels 1 - 32
local offset = bit32.extract(VALUE,0,4) * 4
rcchannels[1 + offset] = 100 * (bit32.extract(VALUE,4,6)/63) * (bit32.extract(VALUE,10,1) == 1 and -1 or 1)
rcchannels[2 + offset] = 100 * (bit32.extract(VALUE,11,6)/63) * (bit32.extract(VALUE,17,1) == 1 and -1 or 1)
rcchannels[3 + offset] = 100 * (bit32.extract(VALUE,18,6)/63) * (bit32.extract(VALUE,24,1) == 1 and -1 or 1)
rcchannels[4 + offset] = 100 * (bit32.extract(VALUE,25,6)/63) * (bit32.extract(VALUE,31,1) == 1 and -1 or 1)
--]]
elseif appId == 0x50F2 then -- VFR
telemetry.airspeed = bit32.extract(value,1,7) * (10^bit32.extract(value,0,1)) -- dm/s
telemetry.throttle = bit32.extract(value,8,7)
telemetry.baroAlt = bit32.extract(value,17,10) * (10^bit32.extract(value,15,2)) * 0.1 * (bit32.extract(value,27,1) == 1 and -1 or 1)
status.airspeedEnabled = 1
end
end
local function crossfirePop()
local now = getTime()
local command, data = crossfireTelemetryPop()
-- command is 0x80 CRSF_FRAMETYPE_ARDUPILOT
if (command == 0x80 or command == 0x7F) and data ~= nil then
-- actual payload starts at data[2]
if #data >= 7 and data[1] == 0xF0 then
local app_id = bit32.lshift(data[3],8) + data[2]
local value = bit32.lshift(data[7],24) + bit32.lshift(data[6],16) + bit32.lshift(data[5],8) + data[4]
return 0x00, 0x10, app_id, value
elseif #data > 4 and data[1] == 0xF1 then
-- minimum text messages of 1 char
local severity = data[2]
-- copy the terminator as well
for i=3,#data
do
msgBuffer = msgBuffer .. string.char(data[i])
-- hash support
updateHash(data[i])
end
pushMessage(severity, msgBuffer)
-- hash audio support
playHash()
-- hash reset
resetHash()
msgBuffer = nil
doGarbageCollect()
msgBuffer = ""
elseif #data >= 8 and data[1] == 0xF2 then
-- passthrough array
local app_id, value
for i=0,math.min(data[2]-1, 9)
do
app_id = bit32.lshift(data[4+(6*i)],8) + data[3+(6*i)]
value = bit32.lshift(data[8+(6*i)],24) + bit32.lshift(data[7+(6*i)],16) + bit32.lshift(data[6+(6*i)],8) + data[5+(6*i)]
--pushMessage(7,string.format("CRSF:%d - %04X:%08X",i, app_id, value))
processTelemetry(app_id, value, now)
end
noTelemetryData = 0
hideNoTelemetry = true
end
end
return nil, nil ,nil ,nil
end
local function telemetryEnabled()
if getRSSI() == 0 then
noTelemetryData = 1
end
return noTelemetryData == 0
end
local function getMaxValue(value,idx)
minmaxValues[idx] = math.max(value,minmaxValues[idx])
return status.showMinMaxValues and minmaxValues[idx] or value
end
local function calcMinValue(value,min)
return min == 0 and value or math.min( value, min )
end
-- returns the actual minimun only if both are > 0
local function getNonZeroMin(v1,v2)
return v1 == 0 and v2 or ( v2 == 0 and v1 or math.min(v1,v2))
end
local function calcCellCount()
-- cellcount override from menu
local c1 = 0
local c2 = 0
if conf.cell1Count ~= nil and conf.cell1Count > 0 then
c1 = conf.cell1Count
elseif batt1sources.vs == true and cell1count > 1 then
c1 = cell1count
else
c1 = math.floor( ((cell1maxFC*0.1) / 4.36) + 1)
end
if conf.cell2Count ~= nil and conf.cell2Count > 0 then
c2 = conf.cell2Count
elseif batt2sources.vs == true and cell2count > 1 then
c2 = cell2count
else
c2 = math.floor(((cell2maxFC*0.1)/4.36) + 1)
end
return c1,c2
end
-- gets the voltage based on source and min value, battId = [1|2]
local function getMinVoltageBySource(source, cell, cellFC, battId)
-- offset 0 for cell voltage, 2 for pack voltage
local offset = 0
--
if cell > 4.36*2 or cellFC > 4.36*2 then
offset = 2
end
--
if source == "vs" then
return status.showMinMaxValues == true and minmaxValues[2+offset+battId] or cell
elseif source == "fc" then
-- FC only tracks batt1 and batt2 no cell voltage tracking
local minmax = (offset == 2 and minmaxValues[battId] or minmaxValues[battId]/calcCellCount())
return status.showMinMaxValues == true and minmax or cellFC
end
--
return 0
end
local function getBatt1Capacity()
return conf.battCapOverride1 > 0 and conf.battCapOverride1*10 or telemetry.batt1Capacity
end
local function getBatt2Capacity()
return conf.battCapOverride2 > 0 and conf.battCapOverride2*10 or telemetry.batt2Capacity
end
local function calcFLVSSBatt(battIdx)
local cellMin,cellSum,cellCount
local battSources = battIdx == 1 and batt1sources or batt2sources
local cellResult = battIdx == 1 and getValue("Cels") or getValue("Cel2")
if type(cellResult) == "table" then
cellMin = 4.36
cellSum = 0
-- cellcount is global and shared
cellCount = #cellResult
for i, v in pairs(cellResult) do
cellSum = cellSum + v
if cellMin > v then
cellMin = v
end
end
-- if connected after script started
if battSources.vs == false then
status.battsource = "na"
end
if status.battsource == "na" then
status.battsource = "vs"
end
battSources.vs = true
else
battSources.vs = false
cellMin = 0
cellSum = 0
end
return cellMin,cellSum,cellCount,battSources
end
local function calcBattery()
------------
-- FLVSS 1
------------
cell1min, cell1sum, cell1count = calcFLVSSBatt(1) --1 = Cels
------------
-- FLVSS 2
------------
cell2min, cell2sum, cell2count = calcFLVSSBatt(2) --2 = Cel2
--------------------------------
-- flight controller battery 1
--------------------------------
if telemetry.batt1volt > 0 then
-- needed to calculate cell count
cell1maxFC = math.max(telemetry.batt1volt,cell1maxFC)
cell1sumFC = telemetry.batt1volt*0.1
if status.battsource == "na" then
status.battsource = "fc"
end
batt1sources.fc = true
else
batt1sources.fc = false
cell1sumFC = 0
end
--------------------------------
-- flight controller battery 2
--------------------------------
if telemetry.batt2volt > 0 then
cell2maxFC = math.max(telemetry.batt2volt,cell2maxFC)
cell2sumFC = telemetry.batt2volt*0.1
if status.battsource == "na" then
status.battsource = "fc"
end
batt2sources.fc = true
else
batt2sources.fc = false
cell2sumFC = 0
end
-- batt fc
minmaxValues[1] = calcMinValue(cell1sumFC,minmaxValues[1])
minmaxValues[2] = calcMinValue(cell2sumFC,minmaxValues[2])
-- cell flvss
minmaxValues[3] = calcMinValue(cell1min,minmaxValues[3])
minmaxValues[4] = calcMinValue(cell2min,minmaxValues[4])
-- batt flvss
minmaxValues[5] = calcMinValue(cell1sum,minmaxValues[5])
minmaxValues[6] = calcMinValue(cell2sum,minmaxValues[6])
------------------------------------------
-- table to pass battery info to panels
-- offsets are: 1 celm, 4 batt, 7 curr, 10 mah, 13 cap, indexing starts at 1
-- value = offset + [0 aggregate|1 for batt 1| 2 for batt2]
-- batt2 = 4 + 2 = 6
------------------------------------------
-- Note: these can be calculated. not necessary to track them as min/max
-- cell1minFC = cell1sumFC/calcCellCount()
-- cell2minFC = cell2sumFC/calcCellCount()
-- cell1minA2 = cell1sumA2/calcCellCount()
local count1,count2 = calcCellCount()
battery[1+1] = getMinVoltageBySource(status.battsource, cell1min, cell1sumFC/count1, 1)*100 --cel1m