-
Notifications
You must be signed in to change notification settings - Fork 166
Expand file tree
/
Copy pathmain.lua
More file actions
1760 lines (1584 loc) · 59.5 KB
/
main.lua
File metadata and controls
1760 lines (1584 loc) · 59.5 KB
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 widget for the Ethos OS
-- 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>.
local HUD_W = 240
local HUD_H = 150
local HUD_X = (480 - HUD_W)/2
local HUD_Y = 18
local function getTime()
-- os.clock() resolution is 0.01 secs
return os.clock()*100 -- 1/100th
end
local function getBitmapsPath()
-- local path from script root
return "./../../bitmaps/"
end
local function getLogsPath()
-- local path from script root
return "./../../logs/"
end
local function getYaapuBitmapsPath()
-- local path from script root
return "./bitmaps/"
end
local function getYaapuAudioPath()
-- local path from script root
return "./audio/"
end
local function getYaapuLibPath()
-- local path from script root
return "./lib/"
end
local ethosVersion = system.getVersion()
local status = {
-- telemetry
telemetry = {
-- STATUS
flightMode = 0,
simpleMode = 0,
landComplete = 0,
statusArmed = 0,
battFailsafe = 0,
ekfFailsafe = 0,
failsafe = 0,
imuTemp = 0,
fencePresent = 0,
fenceBreached = 0,
-- GPS
numSats = 0,
gpsStatus = 0,
gpsHdopC = 100,
gpsAlt = 0,
-- BATT 1
batt1volt = 0,
batt1current = 0,
batt1mah = 0,
-- BATT 2
batt2volt = 0,
batt2current = 0,
batt2mah = 0,
-- HOME
homeDist = 0,
homeAlt = 0,
homeAngle = -1,
-- VELANDYAW
vSpeed = 0,
hSpeed = 0,
yaw = 0,
-- ROLLPITCH
roll = 0,
pitch = 0,
range = 0,
-- PARAMS
frameType = -1,
batt1Capacity = 0,
batt2Capacity = 0,
-- GPS
lat = nil,
lon = nil,
homeLat = nil,
homeLon = nil,
strLat = "N/A",
strLon = "N/A",
-- WP
wpNumber = 0,
wpDistance = 0,
wpXTError = 0,
wpBearing = 0,
wpCommands = 0,
wpOffsetFromCog = 0,
-- VFR
airspeed = 0,
throttle = 0,
baroAlt = 0,
-- Total distance
totalDist = 0,
travelLat = nil,
travelLon = nil,
-- RPM
rpm1 = 0,
rpm2 = 0,
-- TERRAIN
heightAboveTerrain = 0,
terrainUnhealthy = 0,
-- WIND
trueWindSpeed = 0,
trueWindAngle = 0,
apparentWindSpeed = 0,
apparentWindAngle = 0,
-- RSSI
rssi = 0,
rssiCRSF = 0,
},
-- configuration
conf = {
language = "en",
languageId = 1,
defaultBattSourceId = 1, -- auto
battery1Source = nil,
battery2Source = nil,
battAlertLevel1 = 375,
battAlertLevel2 = 350,
battCapOverride1 = 0,
battCapOverride2 = 0,
disableAllSounds = false,
disableMsgBeep = 1,
enableHaptic = false,
timerAlert = 0,
repeatAlertsPeriod = 10,
minAltitudeAlert = 0,
maxAltitudeAlert = 0,
maxDistanceAlert = 0,
battConf = 1,
cell1Count = 0,
cell2Count = 0,
enableBattPercByVoltage = false,
rangeFinderMax=0,
horSpeedUnit = 1,
horSpeedMultiplier=1,
horSpeedLabel = "m/s",
vertSpeedUnit = 1,
vertSpeedMultiplier=1,
vertSpeedLabel = "m/s",
distUnit = 1,
distUnitLabel = "m",
distUnitScale = 1,
distUnitLong = 1,
distUnitLongLabel = "km",
distUnitLongScale = 0.001,
maxHdopAlert = 2,
enablePX4Modes = false,
enableCRSF = false,
-- map support
mapTypeId = 1,
mapType = "GoogleSatelliteMap", -- applies to gmapcacther only
googleZoomDefault = 18,
googleZoomMax = 20,
googleZoomMin = 1,
gmapZoomDefault = 0,
gmapZoomMax = 17,
gmapZoomMin = -2,
mapZoomMax = 20,
mapZoomMin = 1,
mapTrailDots = 10,
enableMapGrid = true,
screenToggleChannelId = 0,
screenWheelChannelId = 0,
screenWheelChannelDelay = 20,
gpsFormat = 2, -- decimal
mapProvider = 2, -- 1 GMapCatcher, 2 Google
enableRPM = 3,
enableWIND = true,
plotSource1 = 1,
plotSource2 = 1,
-- layout
layout = 1,
-- external sport support
telemetrySource = 1,
-- test only
num = 0, -- test da rimuovere
-- top bar
linkQualitySource = nil,
linkStatusSource2 = nil,
linkStatusSource3 = nil,
linkStatusSource4 = nil,
-- gps
gpsSource = nil,
mapTilesStorage = 1,
mapTilesStoragePathPrefix = "SD:",
},
-- gps fix status
gpsStatuses = {
[0]={"No", "GPS"},
[1]={"No", "Lock"},
[2]={"2D", ""},
[3]={"3D", ""},
[4]={"DGPS",""},
[5]={"RTK", "Flt"},
[6]={"RTK", "Fxd"},
},
-- mavlink severity
mavSeverity = {
[0] = { "EMR", lcd.RGB(248, 109, 0) },
[1] = { "ALR", lcd.RGB(248, 109, 0) },
[2] = { "CRT", lcd.RGB(248, 109, 0) },
[3] = { "ERR", lcd.RGB(248, 109, 0) },
[4] = { "WRN", lcd.RGB(248, 109, 0) },
[5] = { "NTC", lcd.RGB(0, 255, 0) },
[6] = { "INF", lcd.RGB(255, 255, 255) },
[7] = { "DBG", lcd.RGB(255, 255, 255) },
},
-- panels
layoutFilenames = {
"layout_default",
"layout_map",
"layout_plot",
},
centerPanelFilenames = {
"center_panel"
},
rightPanelFilenames = {
"right_panel",
"right_panel_2",
},
leftPanelFilenames = {
"left_panel",
"left_panel",
},
counter = 0,
-- layout
lastScreen = 1, -- allows to switch to a different screen on same widget
loadCycle = 0,
layout = { nil, nil, nil },
-- FLVSS 1
cell1min = 0,
cell1sum = 0,
-- FLVSS 2
cell2min = 0,
cell2sum = 0,
-- FC 1
cell1sumFC = 0,
cell1maxFC = 0,
-- FC 2
cell2sumFC = 0,
cell2maxFC = 0,
-- battery
cell1count = 0,
cell2count = 0,
battsource = "fc",
batt1sources = {
vs = false,
fc = false
},
batt2sources = {
vs = false,
fc = false
},
-- flight time
lastTimerStart = 0,
timerRunning = 0,
flightTime = 0,
-- events
lastStatusArmed = 0,
lastGpsStatus = 0,
lastFlightMode = 0,
lastSimpleMode = 0,
-- battery levels
batLevel = 99,
battLevel1 = false,
battLevel2 = false,
lastBattLevel = 14,
-- messages
messages = {},
msgBuffer = "",
lastMsgValue = 0,
lastMsgTime = 0,
lastMessage = nil,
lastMessageSeverity = 0,
lastMessageCount = 1,
messageCount = 0,
messageOffset = 0,
messageAutoScroll = true,
-- telemetry status
noTelemetryData = 1,
hideNoTelemetry = false,
showDualBattery = false,
showMinMaxValues = false,
-- maps
screenTogglePage = 1,
mapZoomLevel = 19,
-- flightmode
strFlightMode = nil,
modelString = nil,
-- terrain
terrainEnabled = 0,
terrainLastData = getTime(),
-- airspeed
airspeedEnabled = 0,
-- PLOT data
plotSources = nil,
-- waypoint
cog = nil,
lastLat = nil,
lastLon = nil,
wpEnabled = 0,
wpEnabledMode = 0,
-- dynamic layout element hiding
hidePower = 0,
hideEfficiency = 0,
-- blinking suppport
blinkon = false,
-- traveled distance support
avgSpeed = 0,
lastUpdateTotDist = 0,
lastInvalidate = getTime(),
-- telemetry params
paramId = nil,
paramValue = nil,
-- message hash support
shortHash = nil,
parseShortHash = false,
hashByteIndex = 0,
hash = 0,
hash_a = 0,
hash_b = 0,
currentModel = model.name(),
pauseTelemetry = false,
-- fletcher24 bytes hashes
shortHashes = {
[1934808] = false, -- Soaring: Enabled
[2074081] = false, -- Soaring: Disabled
[2397669] = false, -- Soaring: reached upper altitude
[2246114] = false, -- Soaring: reached lower altitude
[2860491] = false, -- Soaring: thermal weak
[2262475] = true, -- reached command:
[3466823] = true, -- reached waypoint:
[4597275] = true, -- Passed waypoint:
[3843641] = false, -- Takeoff complete
[1865209] = false, -- Smart RTL deactivated
[4170928] = false, -- GPS home acquired
[4224177] = false, -- GPS home acquired
},
---------------------------------
-- ALARMS
---------------------------------
--[[
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 = {
--{ 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 , false, 1, 0, false, 0 }, --MAX_ALT
{ false, 0 , false, 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 }, --FENCE
{ false, 0 , true, 1, 0, false, 0 }, --TERRAIN
},
transitions = {
--{ last_value, last_changed, transition_done, delay }
{ 0, 0, false, 30 },
},
---------------------------
-- BATTERY TABLE
---------------------------
battery = {0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0},
batLevels = {0,5,10,15,20,25,30,40,50,60,70,80,90},
minmaxValues = {0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0},
-- UNIT CONVERSION
unitConversion = {},
battPercByVoltage = {},
wpEnabledModeList = {
['AUTO'] = 1,
['GUIDED'] = 1,
['LOITER'] = 1,
['RTL'] = 1,
['QRTL'] = 1,
['QLOITER'] = 1,
['QLAND'] = 1,
['FOLLOW'] = 1,
['ZIGZAG'] = 1,
},
colors = {
white = WHITE,
red = RED,
green = GREEN,
black = BLACK,
yellow = lcd.RGB(255,206,0),
panelLabel = lcd.RGB(150,150,150),
panelText = lcd.RGB(255,255,255),
panelBackground = lcd.RGB(56,60,56),
barBackground = BLACK,
barText = WHITE,
hudSky = lcd.RGB(123,157,255),
hudTerrain = lcd.RGB(100,185,95),
hudDashes = lcd.RGB(250, 205, 205),
hudLines = lcd.RGB(220, 220, 220),
hudSideText = lcd.RGB(0,238,49),
hudText = lcd.RGB(255,255,255),
rpmBar = lcd.RGB(240,192,0),
background = lcd.RGB(60, 60, 60)
},
}
status.frameNames = nil -- require "/scripts/yaapu/lib/frame_names"
status.frameTypes = nil -- require "/scripts/yaapu/lib/frame_types"
status.frame = {}
local libs = {
drawLib = nil,
hudLib = nil,
resetLib = nil,
utils = nil,
mapLib = nil,
sport = nil,
}
--[[
UNIT_AMPERE
UNIT_AMPERE_HOUR
UNIT_CELSIUS
UNIT_CENTIMETER
UNIT_CENTIMETER_PER_SECOND
UNIT_DB
UNIT_DBM
UNIT_DEGREE
UNIT_FAHRENHEIT
UNIT_FOOT
UNIT_FOOT_PER_SECOND
UNIT_G
UNIT_HERTZ
UNIT_HOUR
UNIT_KILOMETER
UNIT_KNOT
UNIT_KPH
UNIT_METER
UNIT_METER_PER_SECOND
UNIT_MICROSECOND
UNIT_MILLIAMPERE
UNIT_MILLIAMPERE_HOUR
UNIT_MILLILITER
UNIT_MILLILITER_PER_MINUTE
UNIT_MILLILITER_PER_PULSE
UNIT_MILLISECOND
UNIT_MILLIVOLT
UNIT_MILLIWATT
UNIT_MINUTE
UNIT_MPH
UNIT_PERCENT
UNIT_RADIAN
UNIT_RPM
UNIT_SECOND
UNIT_VOLT
UNIT_WATT
]]
-- { value, decimals, unit}
status.luaSourcesConfig = {}
status.luaSourcesConfig.Voltage = {0, 1, UNIT_VOLT, nil, 0.1}
status.luaSourcesConfig.Current = {0, 1, UNIT_AMPERE, nil, 0.1}
status.luaSourcesConfig.Battery = {0, 0, UNIT_PERCENT, nil, 1}
status.luaSourcesConfig.ArmStatus = {0, 0, nil, "statusArmed", 1}
status.luaSourcesConfig.FlightMode = {0, 0, nil, "flightMode", 1}
status.luaSourcesConfig.Heading = {0, 0, UNIT_DEGREE, "yaw", 1}
status.luaSourcesConfig.Altitude = {0, 0, UNIT_METER, "homeAlt", 1}
status.luaSourcesConfig.GPSAltitude = {0, 0, UNIT_METER, "gpsAlt", 0.1}
status.luaSourcesConfig.AirSpeed = {0, 1, UNIT_METER_PER_SECOND, "airspeed", 0.1}
status.luaSourcesConfig.GroundSpeed = {0, 1, UNIT_METER_PER_SECOND, "hSpeed", 0.1}
status.luaSourcesConfig.VSpeed = {0, 1, UNIT_METER_PER_SECOND, "vSpeed", 0.1}
status.luaSourcesConfig.Rpm1 = {0, 0, UNIT_RPM, "rpm1" ,1}
status.luaSourcesConfig.Rpm2 = {0, 0, UNIT_RPM, "rpm2", 1}
status.luaSourcesConfig.Throttle = {0, 0, UNIT_PERCENT, "throttle", 1}
status.luaSourcesConfig.Roll = {0, 0, UNIT_DEGREE, "roll", 1}
status.luaSourcesConfig.Pitch = {0, 0, UNIT_DEGREE, "pitch", 1}
local function sourceWakeup(source)
if source ~= nil then
local v = status.luaSourcesConfig[source:name()]
if source:name() == "Voltage" then
source:value(status.battery[4] * v[5])
elseif source:name() == "Current" then
source:value(status.battery[7] * v[5])
elseif source:name() == "Battery" then
source:value(status.battery[16] * v[5])
else
if v[2] == 0 then
source:value(tonumber(status.telemetry[v[4]])==nil and 0 or math.floor(0.5 + status.telemetry[v[4]] * v[5]))
else
source:value(tonumber(status.telemetry[v[4]])==nil and 0 or (status.telemetry[v[4]] * v[5]))
end
end
end
end
local function loadLib(name)
local lib = dofile(getYaapuLibPath()..name..".lua")
if lib.init ~= nil then
lib.init(status, libs)
end
return lib
end
local function initLibs()
if status.frameNames == nil then
status.frameNames = loadLib("frame_names")
end
if status.frameTypes == nil then
status.frameTypes = loadLib("frame_types")
end
if libs.utils == nil then
libs.utils = loadLib("utils")
end
if libs.drawLib == nil then
libs.drawLib = loadLib("drawlib")
end
if libs.hudLib == nil then
libs.hudLib = loadLib("hudlib")
end
if libs.resetLib == nil then
libs.resetLib = loadLib("resetlib")
end
if libs.mapLib == nil then
libs.mapLib = loadLib("maplib")
end
if libs.sportLib == nil then
libs.sportLib = loadLib("sport")
end
end
function checkLandingStatus()
if status.timerRunning == 0 and status.telemetry.landComplete == 1 and status.lastTimerStart == 0 then
libs.utils.startTimer()
end
if status.timerRunning == 1 and status.telemetry.landComplete == 0 and status.lastTimerStart ~= 0 then
libs.utils.stopTimer()
-- play landing complete anly if motorts are armed
if status.telemetry.statusArmed == 1 then
utils.playSound("landing")
end
end
status.timerRunning = status.telemetry.landComplete
end
function checkCellVoltage()
if status.battery[1] <= 0 then
return
end
-- check alarms
libs.utils.checkAlarm(status.conf.battAlertLevel1, status.battery[1], 7, -1, "batalert1", status.conf.repeatAlertsPeriod)
libs.utils.checkAlarm(status.conf.battAlertLevel2, status.battery[1], 8, -1, "batalert2", status.conf.repeatAlertsPeriod)
-- cell bgcolor is sticky but gets triggered with alarms
if status.battLevel1 == false then status.battLevel1 = status.alarms[7][1] end
if status.battLevel2 == false then status.battLevel2 = status.alarms[8][1] end
--print("BATT L1",status.alarms[7][1],status.alarms[7][2],status.alarms[7][3],status.alarms[7][4],status.alarms[7][5],status.alarms[7][6],status.alarms[7][7])
end
function checkEvents()
libs.utils.loadFlightModes()
-- silence alarms when showing min/max values
if status.showMinMaxValues == false then
local alt = status.terrainEnabled == 1 and status.telemetry.heightAboveTerrain or status.telemetry.homeAlt
libs.utils.checkAlarm(status.conf.minAltitudeAlert, alt, 1, -1, "minalt", status.conf.repeatAlertsPeriod)
libs.utils.checkAlarm(status.conf.maxAltitudeAlert, alt, 2, 1, "maxalt", status.conf.repeatAlertsPeriod)
libs.utils.checkAlarm(status.conf.maxDistanceAlert, status.telemetry.homeDist, 3, 1, "maxdist", status.conf.repeatAlertsPeriod)
libs.utils.checkAlarm(1, 2*status.telemetry.ekfFailsafe, 4, 1, "ekf", status.conf.repeatAlertsPeriod)
libs.utils.checkAlarm(1, 2*status.telemetry.battFailsafe, 5, 1, "lowbat", status.conf.repeatAlertsPeriod)
libs.utils.checkAlarm(1, 2*status.telemetry.failsafe, 9, 1, "failsafe", status.conf.repeatAlertsPeriod)
libs.utils.checkAlarm(1, 2*status.telemetry.fenceBreached, 10, 1, "fencebreach", status.conf.repeatAlertsPeriod)
libs.utils.checkAlarm(1, 2*status.telemetry.terrainUnhealthy, 11, 1, "terrainko", status.conf.repeatAlertsPeriod)
libs.utils.checkAlarm(status.conf.timerAlert, status.flightTime, 6, 1, "timealert", status.conf.timerAlert)
end
if status.conf.enableBattPercByVoltage == true then
status.batLevel = libs.utils.getBattPercByCell(status.battery[1]*0.01)
else
if (status.battery[13] > 0) then
status.batLevel = (1 - (status.battery[10]/status.battery[13]))*100
else
status.batLevel = 99
end
end
for l=1,13 do
-- trigger alarm as as soon as it falls below level + 1 (i.e 91%,81%,71%,...)
if status.batLevel <= status.batLevels[l] + 1 and l < status.lastBattLevel then
status.lastBattLevel = l
libs.utils.playSound("bat"..status.batLevels[l])
break
end
end
if status.telemetry.statusArmed == 1 and status.lastStatusArmed == 0 then
status.lastStatusArmed = status.telemetry.statusArmed
libs.utils.playSound("armed")
if status.telemetry.fencePresent == 1 then
libs.utils.playSound("fence")
end
-- reset home on arming
status.telemetry.homeLat = nil
status.telemetry.homeLon = nil
elseif status.telemetry.statusArmed == 0 and status.lastStatusArmed == 1 then
status.lastStatusArmed = status.telemetry.statusArmed
libs.utils.playSound("disarmed")
end
if status.telemetry.gpsStatus > 2 and status.lastGpsStatus <= 2 then
status.lastGpsStatus = status.telemetry.gpsStatus
libs.utils.playSound("gpsfix")
elseif status.telemetry.gpsStatus <= 2 and status.lastGpsStatus > 2 then
status.lastGpsStatus = status.telemetry.gpsStatus
libs.utils.playSound("gpsnofix")
end
-- home detecting code
if status.telemetry.homeLat == nil then
if status.telemetry.gpsStatus > 2 and status.telemetry.homeAngle ~= -1 then
status.telemetry.homeLat, status.telemetry.homeLon = libs.utils.getLatLonFromAngleAndDistance(status.telemetry.homeAngle, status.telemetry.homeDist)
end
end
-- flightmode transitions have a grace period to prevent unwanted flightmode call out
-- on quick radio mode switches
if status.telemetry.frameType ~= -1 and libs.utils.checkTransition(1,status.telemetry.flightMode) then
libs.utils.playSoundByFlightMode(status.telemetry.flightMode)
-- check if we should enable waypoint plotting for this flight mode
-- supported modes are AUTO, GUIDED, LOITER, RTL, QRTL, QLOITER, QLAND, FOLLOW, ZIGZAG
-- see /MAVProxy/modules/mavproxy_map/__init__.py
if status.wpEnabledModeList[string.upper(status.frame.flightModes[status.telemetry.flightMode])] == 1 then
status.wpEnabledMode = 1
else
status.wpEnabledMode = 0
end
--print('luaDebug', status.wpEnabledMode)
end
if status.telemetry.simpleMode ~= status.lastSimpleMode then
if status.telemetry.simpleMode == 0 then
libs.utils.playSound( status.lastSimpleMode == 1 and "simpleoff" or "ssimpleoff" )
else
libs.utils.playSound( status.telemetry.simpleMode == 1 and "simpleon" or "ssimpleon" )
end
status.lastSimpleMode = status.telemetry.simpleMode
end
end
local function checkSize(widget)
w, h = lcd.getWindowSize()
text_w, text_h = lcd.getTextSize("")
lcd.font(FONT_STD)
lcd.drawText(w/2, (h - text_h)/2, w.." x "..h, CENTERED)
return true
end
local function createOnce(widget)
-- only this widget instance will run bg tasks
status.currentModel = model.name()
widget.runBgTasks = true
libs.utils.playSound("yaapu")
libs.utils.pushMessage(7, "Yaapu Telemetry Widget 1.4.1".. " ("..'bad9e8b'..")")
-- create the YaapuTimer if missing
local timer = model.getTimer("Yaapu")
if timer == nil then
print("TIMER CREATED")
timer = model.createTimer()
timer:name("Yaapu")
if ethosVersion.major == 1 and ethosVersion.minor <= 4 then
timer:countdownStart(0)
timer:audioMode(AUDIO_MUTE)
timer:activeCondition({category=CATEGORY_NONE})
else
timer:countdownStart(0)
timer:startCondition({category=CATEGORY_NONE})
end
end
libs.utils.stopTimer()
-- get a reference to the plotSources table
--status.plotSources = menuLib.plotSources
end
local function reset(widget)
if status.telemetry.statusArmed == 1 then
libs.utils.pushMessage(1,"Reset ignored while armed")
return
end
libs.resetLib.reset(widget)
end
local function loadLayout(widget)
lcd.pen(SOLID)
lcd.color(lcd.RGB(20, 20, 20))
lcd.drawFilledRectangle(40, 70, 400, 140)
lcd.color(status.colors.white)
lcd.drawRectangle(40, 70, 400, 140,3)
lcd.color(status.colors.white)
lcd.font(FONT_XXL)
lcd.drawText(240, 100, "loading layout...", CENTERED)
if widget.screen == 1 then
if widget.leftPanel == nil then
--print("LEFT")
widget.leftPanel = loadLib(status.leftPanelFilenames[widget.leftPanelIndex])
return
end
if widget.centerPanel == nil then
--print("CENTER")
widget.centerPanel = loadLib(status.centerPanelFilenames[widget.centerPanelIndex])
return
end
if widget.rightPanel == nil then
--print("RIGHT")
widget.rightPanel = loadLib(status.rightPanelFilenames[widget.rightPanelIndex])
return
end
end
if status.layout[widget.screen] == nil then
--print("LAYOUT")
status.layout[widget.screen] = loadLib(status.layoutFilenames[widget.screen])
end
widget.ready = true
end
status.blinkTimer = getTime()
local updateCog = 0
local sportConn = nil
local sportPacket = {
physId = 0,
primId = 0,
appId = 0,
data = 0,
}
-- 5Hz
local function task1(now)
-- update GPS coordinates
-- update gps telemetry data
local gpsData = {}
if status.conf.gpsSource ~= nil then
local latSrc = system.getSource({name=status.conf.gpsSource:name(),options=OPTION_LATITUDE})
local lonSrc = system.getSource({name=status.conf.gpsSource:name(),options=OPTION_LONGITUDE})
if latSrc ~= nil and lonSrc ~= nil then
gpsData.lat = latSrc:value()
gpsData.lon = lonSrc:value()
end
end
if gpsData.lat ~= nil and gpsData.lon ~= nil then
status.telemetry.lat = gpsData.lat
status.telemetry.lon = gpsData.lon
end
-- update total distance as often as po
libs.utils.updateTotalDist()
end
-- 2Hz
local function task2(now)
-- rssi
if status.conf.enableCRSF then
-- apply same algo used by ardupilot to estimate a 0-100 rssi value
-- rssi = roundf((1.0f - (rssi_dbm - 50.0f) / 70.0f) * 255.0f);
local rssi_dbm = math.abs(libs.utils.getSourceValue("1RSS"))
if libs.utils.getSourceValue("ANT") ~= 0 then
rssi_dbm = math.abs(libs.utils.getSourceValue("2RSS"))
end
status.telemetry.rssiCRSF = math.min(100, math.floor(0.5 + ((1-(rssi_dbm - 50)/70)*100)))
end
status.telemetry.rssi = libs.utils.getRSSI()
-- update battery
libs.utils.calcBattery()
checkEvents()
checkLandingStatus()
checkCellVoltage()
end
-- 1Hz
local function task3(now)
if status.telemetry.lat ~= nil and status.telemetry.lon ~= nil then
if status.conf.gpsFormat == 1 then
-- DMS
status.telemetry.strLat = libs.utils.decToDMSFull(status.telemetry.lat)
status.telemetry.strLon = libs.utils.decToDMSFull(status.telemetry.lon, status.telemetry.lat)
else
-- decimal
status.telemetry.strLat = string.format("%.06f", status.telemetry.lat)
status.telemetry.strLon = string.format("%.06f", status.telemetry.lon)
end
end
-- if we do not see terrain data for more than 5 sec we assume TERRAIN_ENABLE = 0
if status.terrainEnabled == 1 and now - status.terrainLastData > 500 then
status.terrainEnabled = 0
status.telemetry.terrainUnhealthy = 0
end
if status.currentModel ~= model.name() then
status.currentModel = model.name()
libs.resetLib.reset()
end
end
-- 1Hz
local function task4(now)
libs.utils.updateFlightTime()
if status.telemetry.lat ~= nil and status.telemetry.lon ~= nil then
if updateCog == 1 then
-- update COG
if status.lastLat ~= nil and status.lastLon ~= nil and status.lastLat ~= status.telemetry.lat and status.lastLon ~= status.telemetry.lon then
local cog = libs.utils.getAngleFromLatLon(status.lastLat, status.lastLon, status.telemetry.lat, status.telemetry.lon)
status.cog = cog ~= nil and cog or status.cog
end
updateCog = 0
else
-- update last GPS coords
status.lastLat = status.telemetry.lat
status.lastLon = status.telemetry.lon
-- process wpLat and wpLon updates
if status.wpEnabled == 1 then
status.wpLat, status.wpLon = libs.utils.getLatLonFromAngleAndDistance(status.telemetry.wpBearing, status.telemetry.wpDistance)
end
updateCog = 1
end
end
-- lua sources update
pcall(sourceWakeup)
-- flight mode
if status.frame.flightModes then
status.strFlightMode = status.frame.flightModes[status.telemetry.flightMode]
if status.strFlightMode ~= nil and status.telemetry.simpleMode > 0 then
local strSimpleMode = status.telemetry.simpleMode == 1 and "(S)" or "(SS)"
status.strFlightMode = string.format("%s%s",status.strFlightMode,strSimpleMode)
end
end
end
-- 1Hz
local function task5(now)
-- layout background callback
for screen=1,4
do
if status.layout[screen] ~= nil and status.layout[screen].background ~= nil then
status.layout[screen].background(widget)
end
end
-- top bar model frame and name
if status.modelString == nil then
local fn = status.frameNames[status.telemetry.frameType]
if fn ~= nil then
status.modelString = model.name()
end
else
if model.name() ~= status.modelString then
print("*********** modelChange *************")
libs.resetLib.reset()
end
end
end
-- 0.5Hz
local function task6(now)
-- if we do not see terrain data for more than 5 sec we assume TERRAIN_ENABLE = 0
if status.terrainEnabled == 1 and now - status.terrainLastData > 500 then
status.terrainEnabled = 0
status.telemetry.terrainUnhealthy = 0
end
if status.currentModel ~= model.name() then
status.currentModel = model.name()
libs.resetLib.reset()
end
end
local tasks = {
{0, 20, task1}, -- 5.0Hz
{0, 50, task2}, -- 2.0Hz
{0, 50, task3}, -- 2.0Hz
{0, 50, task4}, -- 2.0Hz
{0, 100, task5}, -- 1.0Hz
{0, 200, task6}, -- 0.5Hz
}
local function checkTaskTimeConstraints(now, taskId)
return (now - tasks[taskId][1]) >= tasks[taskId][2]
end
local function runScheduler(tasks)
local now = getTime()
local maxDelayTaskId = -1
local maxDelay = 0
local delay = 0
for taskId=1,#tasks
do
delay = (now - (tasks[taskId][1]))/tasks[taskId][2]
if (delay >= maxDelay and checkTaskTimeConstraints(now, taskId)) then
maxDelay = delay
maxDelayTaskId = taskId
end
end
if maxDelayTaskId < 0 then
return maxDelayTaskId
end
tasks[maxDelayTaskId][1] = now;
tasks[maxDelayTaskId][3](getTime())
end
local bg_counter = 0
local bg_rate = 0
local bg_timer = 0
local function bgtasks(widget)
-- background rate calculator
-- skip first iteration
if bg_rate == 0 then
bg_rate = bg_counter
end
bg_counter=bg_counter+1
local now = getTime()
if now - bg_timer > 100 then
bg_rate = bg_rate*0.5 + bg_counter*0.5
bg_counter = 0
bg_timer = now
end
-- blinking support
local now = getTime()
status.counter = status.counter + 1
------------------------------