2 -- An FRSKY S.Port <passthrough protocol> based Telemetry script for Taranis X7
4 -- Copyright (C) 2018. Alessandro Apostoli
5 -- https://github.com/yaapu
7 -- This program is free software; you can redistribute it and/or modify
8 -- it under the terms of the GNU General Public License as published by
9 -- the Free Software Foundation; either version 3 of the License, or
10 -- (at your option) any later version.
12 -- This program is distributed in the hope that it will be useful,
13 -- but WITHOUT ANY WARRANTY, without even the implied warranty of
14 -- MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
15 -- GNU General Public License for more details.
17 -- You should have received a copy of the GNU General Public License
18 -- along with this program; if not, see <http://www.gnu.org/licenses>.
20 -- Passthrough protocol reference:
21 -- https://cdn.rawgit.com/ArduPilot/ardupilot_wiki/33cd0c2c/images/FrSky_Passthrough_protocol.xlsx
23 -- Borrowed some code from the LI-xx BATTCHECK v3.30 script
24 -- http://frskytaranis.forumactif.org/t2800-lua-download-un-testeur-de-batterie-sur-la-radio
27 local cellfull
, cellempty
= 4.2, 3.00
28 local cell
= {0, 0, 0, 0, 0 ,0}
29 local cellsumfull
, cellsumempty
, cellsumtype
, cellsum
= 0, 0, 0, 0
31 local i
, cellmin
, cellresult
= 0, cellfull
, 0, 0
36 MAV_TYPE_GENERIC=0, /* Generic micro air vehicle. | */
37 MAV_TYPE_FIXED_WING=1, /* Fixed wing aircraft. | */
38 MAV_TYPE_QUADROTOR=2, /* Quadrotor | */
39 MAV_TYPE_COAXIAL=3, /* Coaxial helicopter | */
40 MAV_TYPE_HELICOPTER=4, /* Normal helicopter with tail rotor. | */
41 MAV_TYPE_ANTENNA_TRACKER=5, /* Ground installation | */
42 MAV_TYPE_GCS=6, /* Operator control unit / ground control station | */
43 MAV_TYPE_AIRSHIP=7, /* Airship, controlled | */
44 MAV_TYPE_FREE_BALLOON=8, /* Free balloon, uncontrolled | */
45 MAV_TYPE_ROCKET=9, /* Rocket | */
46 MAV_TYPE_GROUND_ROVER=10, /* Ground rover | */
47 MAV_TYPE_SURFACE_BOAT=11, /* Surface vessel, boat, ship | */
48 MAV_TYPE_SUBMARINE=12, /* Submarine | */
49 MAV_TYPE_HEXAROTOR=13, /* Hexarotor | */
50 MAV_TYPE_OCTOROTOR=14, /* Octorotor | */
51 MAV_TYPE_TRICOPTER=15, /* Tricopter | */
52 MAV_TYPE_FLAPPING_WING=16, /* Flapping wing | */
53 MAV_TYPE_KITE=17, /* Kite | */
54 MAV_TYPE_ONBOARD_CONTROLLER=18, /* Onboard companion controller | */
55 MAV_TYPE_VTOL_DUOROTOR=19, /* Two-rotor VTOL using control surfaces in vertical operation in addition. Tailsitter. | */
56 MAV_TYPE_VTOL_QUADROTOR=20, /* Quad-rotor VTOL using a V-shaped quad config in vertical operation. Tailsitter. | */
57 MAV_TYPE_VTOL_TILTROTOR=21, /* Tiltrotor VTOL | */
58 MAV_TYPE_VTOL_RESERVED2=22, /* VTOL reserved 2 | */
59 MAV_TYPE_VTOL_RESERVED3=23, /* VTOL reserved 3 | */
60 MAV_TYPE_VTOL_RESERVED4=24, /* VTOL reserved 4 | */
61 MAV_TYPE_VTOL_RESERVED5=25, /* VTOL reserved 5 | */
62 MAV_TYPE_GIMBAL=26, /* Onboard gimbal | */
63 MAV_TYPE_ADSB=27, /* Onboard ADSB peripheral | */
64 MAV_TYPE_PARAFOIL=28, /* Steerable, nonrigid airfoil | */
65 MAV_TYPE_DODECAROTOR=29, /* Dodecarotor | */
69 frameTypes
[0] = "copter"
70 frameTypes
[1] = "plane"
71 frameTypes
[2] = "copter"
72 frameTypes
[3] = "copter"
73 frameTypes
[4] = "copter"
79 frameTypes
[10] = "rover"
80 frameTypes
[11] = "boat"
82 frameTypes
[13] = "copter"
83 frameTypes
[14] = "copter"
84 frameTypes
[15] = "copter"
85 frameTypes
[16] = "plane"
88 frameTypes
[19] = "plane"
89 frameTypes
[20] = "plane"
90 frameTypes
[21] = "plane"
91 frameTypes
[22] = "plane"
92 frameTypes
[23] = "plane"
93 frameTypes
[24] = "plane"
94 frameTypes
[25] = "plane"
97 frameTypes
[28] = "plane"
98 frameTypes
[29] = "copter"
101 local flightModes
= {}
102 flightModes
["copter"] = {}
103 flightModes
["plane"] = {}
104 flightModes
["rover"] = {}
105 -- copter flight modes
106 flightModes
["copter"][0]=""
107 flightModes
["copter"][1]="Stabilize"
108 flightModes
["copter"][2]="Acro"
109 flightModes
["copter"][3]="AltHold"
110 flightModes
["copter"][4]="Auto"
111 flightModes
["copter"][5]="Guided"
112 flightModes
["copter"][6]="Loiter"
113 flightModes
["copter"][7]="RTL"
114 flightModes
["copter"][8]="Circle"
115 flightModes
["copter"][9]=""
116 flightModes
["copter"][10]="Land"
117 flightModes
["copter"][11]=""
118 flightModes
["copter"][12]="Drift"
119 flightModes
["copter"][13]=""
120 flightModes
["copter"][14]="Sport"
121 flightModes
["copter"][15]="Flip"
122 flightModes
["copter"][16]="AutoTune"
123 flightModes
["copter"][17]="PosHold"
124 flightModes
["copter"][18]="Brake"
125 flightModes
["copter"][19]="Throw"
126 flightModes
["copter"][20]="Avoid ADSB"
127 flightModes
["copter"][21]="Guided NO GPS"
128 -- plane flight modes
129 flightModes
["plane"][0]="Manual"
130 flightModes
["plane"][1]="Circle"
131 flightModes
["plane"][2]="Stabilize"
132 flightModes
["plane"][3]="Training"
133 flightModes
["plane"][4]="Acro"
134 flightModes
["plane"][5]="FlyByWireA"
135 flightModes
["plane"][6]="FlyByWireB"
136 flightModes
["plane"][7]="Cruise"
137 flightModes
["plane"][8]="Autotune"
138 flightModes
["plane"][9]=""
139 flightModes
["plane"][10]="Auto"
140 flightModes
["plane"][11]="RTL"
141 flightModes
["plane"][12]="Loiter"
142 flightModes
["plane"][13]=""
143 flightModes
["plane"][14]="Avoid ADSB"
144 flightModes
["plane"][15]="Guided"
145 flightModes
["plane"][16]="Initializing"
146 flightModes
["plane"][17]="QStabilize"
147 flightModes
["plane"][18]="QHover"
148 flightModes
["plane"][19]="QLoiter"
149 flightModes
["plane"][20]="Qland"
150 flightModes
["plane"][21]="QRTL"
151 -- rover flight modes
152 flightModes
["rover"][0]="Manual"
153 flightModes
["rover"][1]="Acro"
154 flightModes
["rover"][2]=""
155 flightModes
["rover"][3]="Steering"
156 flightModes
["rover"][4]="Hold"
157 flightModes
["rover"][5]=""
158 flightModes
["rover"][6]=""
159 flightModes
["rover"][7]=""
160 flightModes
["rover"][8]=""
161 flightModes
["rover"][9]=""
162 flightModes
["rover"][10]="Auto"
163 flightModes
["rover"][11]="RTL"
164 flightModes
["rover"][12]="SmartRTL"
165 flightModes
["rover"][13]=""
166 flightModes
["rover"][14]=""
167 flightModes
["rover"][15]="Guided"
168 flightModes
["rover"][16]="Initializing"
169 flightModes
["rover"][17]=""
170 flightModes
["rover"][18]=""
171 flightModes
["rover"][19]=""
172 flightModes
["rover"][20]=""
173 flightModes
["rover"][21]=""
175 local soundFileBasePath
= "/SOUNDS/yaapu0/en"
176 local soundFiles
= {}
178 soundFiles
["bat5"] = "bat5.wav"
179 soundFiles
["bat10"] = "bat10.wav"
180 soundFiles
["bat15"] = "bat15.wav"
181 soundFiles
["bat20"] = "bat20.wav"
182 soundFiles
["bat25"] = "bat25.wav"
183 soundFiles
["bat30"] = "bat30.wav"
184 soundFiles
["bat40"] = "bat40.wav"
185 soundFiles
["bat50"] = "bat50.wav"
186 soundFiles
["bat60"] = "bat60.wav"
187 soundFiles
["bat70"] = "bat70.wav"
188 soundFiles
["bat80"] = "bat80.wav"
189 soundFiles
["bat90"] = "bat90.wav"
191 soundFiles
["gpsfix"] = "gpsfix.wav"
192 soundFiles
["gpsnofix"] = "gpsnofix.wav"
194 soundFiles
["lowbat"] = "lowbat.wav"
195 soundFiles
["ekf"] = "ekf.wav"
197 soundFiles
["yaapu"] = "yaapu.wav"
198 soundFiles
["landing"] = "landing.wav"
199 soundFiles
["armed"] = "armed.wav"
200 soundFiles
["disarmed"] = "disarmed.wav"
202 local soundFilesByFrameTypeAndFlightMode
= {}
203 soundFilesByFrameTypeAndFlightMode
["copter"] = {}
204 soundFilesByFrameTypeAndFlightMode
["plane"] = {}
205 soundFilesByFrameTypeAndFlightMode
["rover"] = {}
207 soundFilesByFrameTypeAndFlightMode
["copter"][0]=""
208 soundFilesByFrameTypeAndFlightMode
["copter"][1]="stabilize.wav"
209 soundFilesByFrameTypeAndFlightMode
["copter"][2]="acro.wav"
210 soundFilesByFrameTypeAndFlightMode
["copter"][3]="althold.wav"
211 soundFilesByFrameTypeAndFlightMode
["copter"][4]="auto.wav"
212 soundFilesByFrameTypeAndFlightMode
["copter"][5]="guided.wav"
213 soundFilesByFrameTypeAndFlightMode
["copter"][6]="loiter.wav"
214 soundFilesByFrameTypeAndFlightMode
["copter"][7]="rtl.wav"
215 soundFilesByFrameTypeAndFlightMode
["copter"][8]="circle.wav"
216 soundFilesByFrameTypeAndFlightMode
["copter"][9]=""
217 soundFilesByFrameTypeAndFlightMode
["copter"][10]="land.wav"
218 soundFilesByFrameTypeAndFlightMode
["copter"][11]=""
219 soundFilesByFrameTypeAndFlightMode
["copter"][12]="drift.wav"
220 soundFilesByFrameTypeAndFlightMode
["copter"][13]=""
221 soundFilesByFrameTypeAndFlightMode
["copter"][14]="sport.wav"
222 soundFilesByFrameTypeAndFlightMode
["copter"][15]="flip.wav"
223 soundFilesByFrameTypeAndFlightMode
["copter"][16]="loiter.wav"
224 soundFilesByFrameTypeAndFlightMode
["copter"][17]="poshold.wav"
225 soundFilesByFrameTypeAndFlightMode
["copter"][18]="brake"
226 soundFilesByFrameTypeAndFlightMode
["copter"][19]="throw.wav"
227 soundFilesByFrameTypeAndFlightMode
["copter"][20]="avoidadbs"
228 soundFilesByFrameTypeAndFlightMode
["copter"][21]="guidednogps"
230 soundFilesByFrameTypeAndFlightMode
["plane"][0]="manual.wav"
231 soundFilesByFrameTypeAndFlightMode
["plane"][1]="circle.wav"
232 soundFilesByFrameTypeAndFlightMode
["plane"][2]="stabilize.wav"
233 soundFilesByFrameTypeAndFlightMode
["plane"][3]="training.wav"
234 soundFilesByFrameTypeAndFlightMode
["plane"][4]="acro.wav"
235 soundFilesByFrameTypeAndFlightMode
["plane"][5]="flybywirea.wav"
236 soundFilesByFrameTypeAndFlightMode
["plane"][6]="flybywireb.wav"
237 soundFilesByFrameTypeAndFlightMode
["plane"][7]="cruise.wav"
238 soundFilesByFrameTypeAndFlightMode
["plane"][8]="autotune.wav"
239 soundFilesByFrameTypeAndFlightMode
["plane"][9]=""
240 soundFilesByFrameTypeAndFlightMode
["plane"][10]="auto.wav"
241 soundFilesByFrameTypeAndFlightMode
["plane"][11]="rtl.wav"
242 soundFilesByFrameTypeAndFlightMode
["plane"][12]="loiter.wav"
243 soundFilesByFrameTypeAndFlightMode
["plane"][13]=""
244 soundFilesByFrameTypeAndFlightMode
["plane"][14]="avoidadbs"
245 soundFilesByFrameTypeAndFlightMode
["plane"][15]="guided.wav"
246 soundFilesByFrameTypeAndFlightMode
["plane"][16]="initializing.wav"
247 soundFilesByFrameTypeAndFlightMode
["plane"][17]="qstabilize.wav"
248 soundFilesByFrameTypeAndFlightMode
["plane"][18]="qhover.wav"
249 soundFilesByFrameTypeAndFlightMode
["plane"][19]="qloiter.wav"
250 soundFilesByFrameTypeAndFlightMode
["plane"][20]="qland.wav"
251 soundFilesByFrameTypeAndFlightMode
["plane"][21]="qrtl.wav"
253 soundFilesByFrameTypeAndFlightMode
["rover"][0]="manual_r.wav"
254 soundFilesByFrameTypeAndFlightMode
["rover"][1]="acro_r.wav"
255 soundFilesByFrameTypeAndFlightMode
["rover"][2]=""
256 soundFilesByFrameTypeAndFlightMode
["rover"][3]="steering_r.wav"
257 soundFilesByFrameTypeAndFlightMode
["rover"][4]="hold_r.wav"
258 soundFilesByFrameTypeAndFlightMode
["rover"][5]=""
259 soundFilesByFrameTypeAndFlightMode
["rover"][6]=""
260 soundFilesByFrameTypeAndFlightMode
["rover"][7]=""
261 soundFilesByFrameTypeAndFlightMode
["rover"][8]=""
262 soundFilesByFrameTypeAndFlightMode
["rover"][9]=""
263 soundFilesByFrameTypeAndFlightMode
["rover"][10]="auto_r.wav"
264 soundFilesByFrameTypeAndFlightMode
["rover"][11]="rtl_r.wav"
265 soundFilesByFrameTypeAndFlightMode
["rover"][12]="smartrtl_r.wav"
266 soundFilesByFrameTypeAndFlightMode
["rover"][13]=""
267 soundFilesByFrameTypeAndFlightMode
["rover"][14]=""
268 soundFilesByFrameTypeAndFlightMode
["rover"][15]="guided_r.wav"
269 soundFilesByFrameTypeAndFlightMode
["rover"][16]="initializing.wav"
270 soundFilesByFrameTypeAndFlightMode
["rover"][17]=""
271 soundFilesByFrameTypeAndFlightMode
["rover"][18]=""
272 soundFilesByFrameTypeAndFlightMode
["rover"][19]=""
273 soundFilesByFrameTypeAndFlightMode
["rover"][20]=""
274 soundFilesByFrameTypeAndFlightMode
["rover"][21]=""
276 local gpsStatuses
= {}
277 gpsStatuses
[0]="NoGPS"
278 gpsStatuses
[1]="NoLock"
279 gpsStatuses
[2]="2DFIX"
280 gpsStatuses
[3]="3DFix"
282 local mavSeverity
= {}
295 local landComplete
= 0
296 local statusArmed
= 0
297 local batteryFailsafe
= 0
298 local lastBatteryFailsafe
= 0
299 local ekfFailsafe
= 0
300 local lastEkfFailsafe
= 0
309 local battCurrent
= 0
313 local battCurrent2
= 0
319 -- MESSAGES max 10 lines
320 local messageBuffer
= ""
321 local messageHistory
= {}
324 local messageDuplicate
= 1
325 local lastMessage
= ""
326 local lastMessageValue
= 0
327 local lastMessageTime
= 0
336 local SENSOR_ID
,FRAME_ID
,DATA_ID
,VALUE
340 local paramId
,paramValue
342 local battFailsafeVoltage
= 0
343 local battFailsafeCapacity
= 0
344 local battCapacity
= 0
351 local noTelemetryData
= 1
353 local function playSound(soundFile
)
354 playFile(soundFileBasePath
.. "/" .. soundFiles
[soundFile
])
357 local function playSoundByFrameTypeAndFlightMode(frameType
,flightMode
)
358 playFile(soundFileBasePath
.. "/" .. soundFilesByFrameTypeAndFlightMode
[frameTypes
[frameType]]
[flightMode
])
361 local function getValueOrDefault(value
)
362 local tmp
= getValue(value
)
369 local function pushMessage(severity
, msg
)
370 if ( severity
< 4) then
376 if msg
== lastMessage
then
377 messageDuplicate
= messageDuplicate
+ 1
378 if messageDuplicate
> 1 then
379 if string.len(mm
) > 19 then
380 mm
= string.sub(mm
,1,19)
381 messageHistory
[messageIdx
- 1] = string.format("%d.%s %-20s (x%d)", messageIdx
- 1, mavSeverity
[severity
], mm
, messageDuplicate
)
383 messageHistory
[messageIdx
- 1] = string.format("%d.%s %s (x%d)", messageIdx
- 1, mavSeverity
[severity
], msg
, messageDuplicate
)
387 messageHistory
[messageIdx
] = string.format("%d.%s %s", messageIdx
, mavSeverity
[severity
], msg
)
388 messageIdx
= messageIdx
+ 1
392 lastMessageTime
= getTime() -- valore in secondi
396 local lastTimerStart
= 0
398 local function startTimer()
399 lastTimerStart
= getTime()/100
402 local function stopTimer()
403 seconds
= seconds
+ getTime()/100 - lastTimerStart
407 local function symFrameType()
408 local ch11
= getValue("ch11")
409 if (ch11
< -300) then
411 elseif ch11
< 300 then
418 local function symTimer()
419 thrOut
= getValue("thr")
420 if (thrOut
> -500 ) then
427 local function symGPS()
428 thrOut
= getValue("thr")
429 if (thrOut
> 0 ) then
436 elseif thrOut
> -500 then
453 local function symBatt()
454 thrOut
= getValue("thr")
455 if (thrOut
> 0 ) then
456 LIPObatt
= 1350 + ((thrOut
)*0.01 * 30)
457 LIPOcelm
= LIPObatt
/4
458 battCurrent
= 100 + ((thrOut
)*0.01 * 30)
459 battVolt
= LIPObatt
*0.1
464 homeDist
= math
.abs(thrOut
)*2
465 flightMode
= math
.floor(20*math
.abs(thrOut
)*0.001)
469 -- simulates attitude by using channel 1 for roll, channel 2 for pitch and channel 4 for yaw
470 local function symAttitude()
474 -- roll [-1024,1024] ==> [-180,180]
475 rollCh
= getValue("ch1") * 0.175
476 -- pitch [1024,-1024] ==> [-90,90]
477 pitchCh
= getValue("ch2") * 0.0878
478 -- yaw [-1024,1024] ==> [0,360]
479 yawCh
= getValue("ch10")
480 if ( yawCh
>= 0) then
481 yawCh
= yawCh
* 0.175
483 yawCh
= 360 + (yawCh
* 0.175)
490 local function symHome()
493 -- home angle in deg [0-360]
494 S2Ch
= getValue("ch12")
495 yawCh
= getValue("ch4")
498 if ( yawCh
>= 0) then
499 yawCh
= yawCh
* 0.175
501 yawCh
= 360 + (yawCh
* 0.175)
506 S2Ch
= 360 + (S2Ch
* 0.175)
508 if (thrOut
> 0 ) then
516 local function processTelemetry()
517 SENSOR_ID
,FRAME_ID
,DATA_ID
,VALUE
= sportTelemetryPop()
527 if ( FRAME_ID
== 0x10) then
529 if ( DATA_ID
== 0x5006) then -- ROLLPITCH
530 -- roll [0,1800] ==> [-180,180]
531 roll
= (bit32
.extract(VALUE
,0,11) - 900) * 0.2
532 -- pitch [0,900] ==> [-90,90]
533 pitch
= (bit32
.extract(VALUE
,11,10) - 450) * 0.2
534 elseif ( DATA_ID
== 0x5005) then -- VELANDYAW
535 vSpeed
= bit32
.extract(VALUE
,1,7) * (10^bit32
.extract(VALUE
,0,1))
536 if (bit32
.extract(VALUE
,8,1) == 1) then
539 hSpeed
= bit32
.extract(VALUE
,10,7) * (10^bit32
.extract(VALUE
,9,1))
540 yaw
= bit32
.extract(VALUE
,17,11) * 0.2
541 elseif ( DATA_ID
== 0x5001) then -- AP STATUS
542 flightMode
= bit32
.extract(VALUE
,0,5)
543 simpleMode
= bit32
.extract(VALUE
,5,2)
544 landComplete
= bit32
.extract(VALUE
,7,1)
545 statusArmed
= bit32
.extract(VALUE
,8,1)
546 batteryFailsafe
= bit32
.extract(VALUE
,9,1)
547 ekfFailsafe
= bit32
.extract(VALUE
,10,2)
548 elseif ( DATA_ID
== 0x5002) then -- GPS STATUS
549 numSats
= bit32
.extract(VALUE
,0,4)
550 gpsStatus
= bit32
.extract(VALUE
,4,2)
551 gpsHdopC
= bit32
.extract(VALUE
,7,7) * (10^bit32
.extract(VALUE
,6,1)) -- dm
552 gpsAlt
= bit32
.extract(VALUE
,24,7) * (10^bit32
.extract(VALUE
,22,2)) -- dm
553 if (bit32
.extract(VALUE
,31,1) == 1) then
556 elseif ( DATA_ID
== 0x5003) then -- BATT
557 battVolt
= bit32
.extract(VALUE
,0,9)
558 battCurrent
= bit32
.extract(VALUE
,10,7) * (10^bit32
.extract(VALUE
,9,1))
559 battMah
= bit32
.extract(VALUE
,17,15)
560 elseif ( DATA_ID
== 0x5008) then -- BATT2
561 battVolt2
= bit32
.extract(VALUE
,0,9)
562 battCurrent2
= bit32
.extract(VALUE
,10,7) * (10^bit32
.extract(VALUE
,9,1))
563 battMah2
= bit32
.extract(VALUE
,17,15)
564 elseif ( DATA_ID
== 0x5004) then -- HOME
565 homeDist
= bit32
.extract(VALUE
,2,10) * (10^bit32
.extract(VALUE
,0,2))
566 homeAlt
= bit32
.extract(VALUE
,14,10) * (10^bit32
.extract(VALUE
,12,2)) * 0.1
567 if (bit32
.extract(VALUE
,24,1) == 1) then
568 homeAlt
= homeAlt
* -1
570 homeAngle
= bit32
.extract(VALUE
, 25, 7) * 3
571 elseif ( DATA_ID
== 0x5000) then -- MESSAGES
572 if (VALUE
~= lastMessageValue
) then
573 lastMessageValue
= VALUE
574 c1
= bit32
.extract(VALUE
,0,7)
575 c2
= bit32
.extract(VALUE
,8,7)
576 c3
= bit32
.extract(VALUE
,16,7)
577 c4
= bit32
.extract(VALUE
,24,7)
578 messageBuffer
= messageBuffer
.. string.char(c4
)
579 messageBuffer
= messageBuffer
.. string.char(c3
)
580 messageBuffer
= messageBuffer
.. string.char(c2
)
581 messageBuffer
= messageBuffer
.. string.char(c1
)
582 if (c1
== 0 or c2
== 0 or c3
== 0 or c4
== 0) then
583 severity
= (bit32
.extract(VALUE
,15,1) * 4) + (bit32
.extract(VALUE
,23,1) * 2) + (bit32
.extract(VALUE
,30,1) * 1)
584 pushMessage( severity
, messageBuffer
)
588 elseif ( DATA_ID
== 0x5007) then -- PARAMS
589 paramId
= bit32
.extract(VALUE
,24,4)
590 paramValue
= bit32
.extract(VALUE
,0,24)
592 frameType
= paramValue
593 elseif paramId
== 2 then
594 battFailsafeVoltage
= paramValue
595 elseif paramId
== 3 then
596 battFailsafeCapacity
= paramValue
597 elseif paramId
== 4 then
598 battCapacity
= paramValue
604 local function telemetryEnabled()
605 if getValue("RxBt") == 0 then
609 return noTelemetryData
== 0
612 local battSource
= "na"
614 local function calcBattery()
619 cellResult
= getValue("Cels")
621 if type(cellResult
) == "table" then
624 for i
= 1, #cell
do cell
[i
] = 0 end
625 cellsumtype
= #cellResult
626 for i
, v
in pairs(cellResult
) do
627 cellsum
= cellsum
+ v
634 -- cels is not defined let's check if A2 is defined
636 battA2
= getValue("A2")
642 elseif battA2
> 17 then
644 elseif battA2
> 13 then
650 cellmin
= battA2
/cellCount
653 -- A2 is not defined, last chance is battVolt
656 cellsum
= battVolt
*0.1
659 elseif cellsum
> 17 then
661 elseif cellsum
> 13 then
667 cellmin
= cellsum
/cellCount
672 LIPOcelm
= cellmin
*100
673 LIPObatt
= cellsum
*100
676 local function drawBattery()
677 if (battCapacity
> 0) then
678 LIPOperc
= (1 - (battMah
/battCapacity
))*100
682 lcd
.drawRectangle(maxX
+1,17,28,16,SOLID
)
683 lcd
.drawFilledRectangle(maxX
+1,17,28,16,SOLID
)
684 -- display battery voltage
685 lcd
.drawText(maxX
+ 28, 19, "v", SMLSIZE
+RIGHT
+INVERS
)
686 lcd
.drawNumber(lcd
.getLastLeftPos(), 18, LIPObatt
, PREC2
+RIGHT
+INVERS
)
687 -- display battery current
688 lcd
.drawText(maxX
+ 28, 26, "A", SMLSIZE
+RIGHT
+INVERS
)
689 lcd
.drawNumber(lcd
.getLastLeftPos(), 26, battCurrent
, SMLSIZE
+PREC1
+RIGHT
+INVERS
)
691 -- display lowest cell voltage
692 if LIPOcelm
< 350 then
693 lcd
.drawNumber(maxX
+ 30, 16, LIPOcelm
, DBLSIZE
+BLINK
+PREC2
)
695 lcd
.drawNumber(maxX
+ 30, 16, LIPOcelm
, DBLSIZE
+PREC2
)
697 lcd
.drawText(lcd
.getLastRightPos(), 17, "v", SMLSIZE
)
698 lcd
.drawText(128, 25, battSource
, SMLSIZE
+RIGHT
)
700 -- display capacity %
702 lcd
.drawText(128, yy
, "Ah", SMLSIZE
+RIGHT
)
703 lcd
.drawNumber(lcd
.getLastLeftPos(), yy
, battCapacity
/100, SMLSIZE
+PREC1
+RIGHT
)
704 lcd
.drawText(lcd
.getLastLeftPos(), yy
, "/", SMLSIZE
+RIGHT
)
705 lcd
.drawNumber(lcd
.getLastLeftPos(), yy
, battMah
/100, SMLSIZE
+PREC1
+RIGHT
)
707 lcd
.drawRectangle(maxX
+1,yy
-2,17,12,SOLID
)
708 lcd
.drawFilledRectangle(maxX
+1,yy
-2,17,12,SOLID
)
710 lcd
.drawText(maxX
+17, yy
, "%", SMLSIZE
+INVERS
+RIGHT
)
711 lcd
.drawNumber(lcd
.getLastLeftPos(), yy
-1, LIPOperc
, INVERS
+RIGHT
)
714 local function drawFlightMode()
715 lcd
.drawFilledRectangle(0,0, 128, 9, SOLID
)
716 lcd
.drawRectangle(0, 0, 128, 9, SOLID
)
718 if (not telemetryEnabled()) then
719 lcd
.drawFilledRectangle((128-100)/2,18, 100, 30, SOLID
)
720 lcd
.drawText(17, 29, "no telemetry data", INVERS
)
724 local strMode
= flightModes
[frameTypes
[frameType]]
[flightMode
]
726 lcd
.drawText(1, 1, strMode
, SMLSIZE
+INVERS
)
728 if ( simpleMode
== 1) then
729 lcd
.drawText(lcd
.getLastRightPos(), 1, "(S)", SMLSIZE
+INVERS
)
732 if (statusArmed
== 1) then
733 lcd
.drawText(18, 47, "ARMED", SMLSIZE
+INVERS
)
735 lcd
.drawText(12, 47, "DISARMED", SMLSIZE
+INVERS
+BLINK
)
739 local function drawHome()
743 lcd
.drawLine(xx
,13,xx
+ 8,13, SOLID
, 0)
745 lcd
.drawLine(xx
+1,12,xx
+ 2,11, SOLID
, 0)
746 lcd
.drawLine(xx
+1,14,xx
+ 2,15, SOLID
, 0)
748 lcd
.drawLine(xx
+7,12,xx
+ 6,11, SOLID
, 0)
749 lcd
.drawLine(xx
+7,14,xx
+ 6,15, SOLID
, 0)
751 lcd
.drawNumber(xx
+ 11, yy
, homeDist
, SMLSIZE
)
752 lcd
.drawText(lcd
.getLastRightPos(), yy
, "m",SMLSIZE
)
755 local function drawMessage()
756 lcd
.drawFilledRectangle(0,55, 212, 9, SOLID
)
757 lcd
.drawRectangle(0, 55, 212, 9, SOLID
)
758 local now
= getTime()
759 if (now
- lastMessageTime
) > 300 then
760 lcd
.drawText(1, 56, messageHistory
[messageIdx
-1],SMLSIZE
+INVERS
)
762 lcd
.drawText(1, 56, messageHistory
[messageIdx
-1],SMLSIZE
+INVERS
+BLINK
)
766 local function drawAllMessages()
768 if (messageIdx
<= 6) then
769 for i
= 1, messageIdx
- 1 do
770 lcd
.drawText(1, 1+10*(idx
- 1), messageHistory
[i
],SMLSIZE
)
774 for i
= messageIdx
- 6,messageIdx
- 1 do
775 lcd
.drawText(1, 1+10*(idx
-1), messageHistory
[i
],SMLSIZE
)
781 local function drawGPSStatus()
785 lcd
.drawRectangle(xx
,yy
- 1,50,15,SOLID
)
787 local strStatus
= gpsStatuses
[gpsStatus
]
790 if gpsStatus
> 2 then
791 lcd
.drawFilledRectangle(xx
,yy
- 1,50,15,SOLID
)
792 if homeAngle
~= -1 then
796 lcd
.drawText(xx
+ 2, yy
, strStatus
, SMLSIZE
+INVERS
)
797 lcd
.drawNumber(128, yy
, numSats
, SMLSIZE
+INVERS
+RIGHT
)
798 lcd
.drawText(xx
+ 2, yy
+ 7, "Hdop ", SMLSIZE
+INVERS
)
800 if gpsHdopC
> 100 then
801 lcd
.drawText(128, yy
+ 7, "10+", SMLSIZE
+INVERS
+RIGHT
+flags
)
803 lcd
.drawNumber(128, yy
+ 7, gpsHdopC
, SMLSIZE
+INVERS
+RIGHT
+PREC1
+flags
)
806 lcd
.drawText(xx
+ 5, yy
+ 3, strStatus
, BLINK
)
810 local function drawGrid()
811 lcd
.drawLine(maxX
, 0, maxX
, 63, SOLID
, 0)
814 local timerRunning
= 0
816 local function checkLandingStatus()
817 if ( timerRunning
== 0 and landComplete
== 1 and lastTimerStart
== 0) then
820 if (timerRunning
== 1 and landComplete
== 0 and lastTimerStart
~= 0) then
824 timerRunning
= landComplete
828 local function calcFlightTime()
830 if ( lastTimerStart
~= 0) then
831 elapsed
= getTime()/100 - lastTimerStart
833 flightTime
= elapsed
+ seconds
836 -- draws a line centered at ox,oy with given angle and length W/O CROPPING
837 local function drawLine(ox
,oy
,angle
,len
,style
,maxX
,maxY
)
838 local xx
= math
.cos(math
.rad(angle
)) * len
* 0.5
839 local yy
= math
.sin(math
.rad(angle
)) * len
* 0.5
846 lcd
.drawLine(x1
,y1
,x2
,y2
, style
,0)
849 -- draws a line centered at ox,oy with given angle and length WITH CROPPING
850 local function drawCroppedLine(ox
,oy
,angle
,len
,style
,maxX
,maxY
)
852 local xx
= math
.cos(math
.rad(angle
)) * len
* 0.5
853 local yy
= math
.sin(math
.rad(angle
)) * len
* 0.5
860 if (x1
>= maxX
and x2
>= maxX
) then
864 y1
= y1
- math
.tan(math
.rad(angle
)) * (maxX
- x1
)
868 y2
= y2
+ math
.tan(math
.rad(angle
)) * (maxX
- x2
)
871 lcd
.drawLine(x1
,y1
,x2
,y2
, style
,0)
874 local function drawFailsafe()
875 if ekfFailsafe
> 0 then
876 if lastEkfFailsafe
== 0 then
879 lcd
.drawText(maxX
/2 - 28, 47, "EKF FAILSAFE", SMLSIZE
+INVERS
+BLINK
)
881 if batteryFailsafe
> 0 then
882 if lastBatteryFailsafe
== 0 then
885 lcd
.drawText(maxX
/2 - 28, 47, "BAT FAILSAFE", SMLSIZE
+INVERS
+BLINK
)
887 lastEkfFailsafe
= ekfFailsafe
888 lastBatteryFailsafe
= batteryFailsafe
891 local function drawPitch()
894 -- horizon min max +/- 30°
900 if (pitch
< -30) then
904 -- y normalized at 32 +/-20 (0.75 = 20/32)
906 -- horizon, lower half of HUD filled in grey
907 --lcd.drawFilledRectangle(minX,y,maxX-minX,maxY-y + 1,GREY_DEFAULT)
909 -- center indicators for vSpeed and alt
911 lcd
.drawLine(minX
,32 - 5,minX
+ width
,32 - 5, SOLID
, 0)
912 lcd
.drawLine(minX
,32 + 4,minX
+ width
,32 + 4, SOLID
, 0)
913 lcd
.drawLine(minX
+ width
+ 1,32 + 4,minX
+ width
+ 5,32, SOLID
, 0)
914 lcd
.drawLine(minX
+ width
+ 1,32 - 4,minX
+ width
+ 5,32, SOLID
, 0)
915 lcd
.drawPoint(minX
+ width
+ 5,32)
917 lcd
.drawLine(maxX
- width
- 1,32 - 5,maxX
- 1,32 - 5,SOLID
,0)
918 lcd
.drawLine(maxX
- width
- 1,32 + 4,maxX
- 1,32 + 4,SOLID
,0)
919 lcd
.drawLine(maxX
- width
- 2,32 + 4,maxX
- width
- 6,32, SOLID
, 0)
920 lcd
.drawLine(maxX
- width
- 2,32 - 4,maxX
- width
- 6,32, SOLID
, 0)
921 lcd
.drawPoint(maxX
- width
- 6,32)
922 -- center value based on char count
924 if homeAlt
< 10 then -- 2 digits with decimal
925 lcd
.drawNumber(maxX
- 1,32 - 3,homeAlt
* 10,SMLSIZE
+PREC1
+RIGHT
)
927 lcd
.drawNumber(maxX
- 1 + 2,32 - 3,homeAlt
,SMLSIZE
+RIGHT
)
930 if homeAlt
> -10 then -- 1 digit with sign
931 lcd
.drawNumber(maxX
- 1,32 - 3,homeAlt
* 10,SMLSIZE
+PREC1
+RIGHT
)
932 else -- 3 digits with sign
933 lcd
.drawNumber(maxX
- 1,32 - 3,homeAlt
,SMLSIZE
+RIGHT
)
937 if (vSpeed
> 999) then
938 lcd
.drawNumber(minX
+ 1,32 - 3,vSpeed
*0.1,SMLSIZE
)
939 elseif (vSpeed
< -99) then
940 lcd
.drawNumber(minX
+ 1,32 - 3,vSpeed
* 0.1,SMLSIZE
)
942 lcd
.drawNumber(minX
+ 1,32 - 3,vSpeed
,SMLSIZE
+PREC1
)
944 -- up pointing center arrow
945 local x
= math
.floor(maxX
/2)
946 lcd
.drawLine(x
-10,34 + 5,x
,34 ,SOLID
,0)
947 lcd
.drawLine(x
+1 ,34 ,x
+ 10, 34 + 5,SOLID
,0)
950 local function drawRoll()
952 local r2
= 10 --vertical distance between roll horiz segments
953 local cx
,cy
,dx
,dy
,ccx
,ccy
,cccx
,cccy
954 -- no roll ==> segments are vertical, offsets are multiples of r2
965 -- center line offsets
966 dx
= math
.cos(math
.rad(90 - r
)) * -pitch
967 dy
= math
.sin(math
.rad(90 - r
)) * pitch
969 cx
= math
.cos(math
.rad(90 - r
)) * r2
970 cy
= math
.sin(math
.rad(90 - r
)) * r2
972 ccx
= math
.cos(math
.rad(90 - r
)) * 2 * r2
973 ccy
= math
.sin(math
.rad(90 - r
)) * 2 * r2
975 cccx
= math
.cos(math
.rad(90 - r
)) * 3 * r2
976 cccy
= math
.sin(math
.rad(90 - r
)) * 3 * r2
978 local x
= math
.floor(maxX
/2)
979 drawCroppedLine(dx
+ x
- cccx
,dy
+ 32 + cccy
,r
,4,DOTTED
,maxX
,maxY
)
980 drawCroppedLine(dx
+ x
- ccx
,dy
+ 32 + ccy
,r
,6,DOTTED
,maxX
,maxY
)
981 drawCroppedLine(dx
+ x
- cx
,dy
+ 32 + cy
,r
,9,DOTTED
,maxX
,maxY
)
982 drawCroppedLine(dx
+ x
,dy
+ 32,r
,16,SOLID
,maxX
,maxY
)
983 drawCroppedLine(dx
+ x
+ cx
,dy
+ 32 - cy
,r
,9,DOTTED
,maxX
,maxY
)
984 drawCroppedLine(dx
+ x
+ ccx
,dy
+ 32 - ccy
,r
,6,DOTTED
,maxX
,maxY
)
985 drawCroppedLine(dx
+ x
+ cccx
,dy
+ 32 - cccy
,r
,4,DOTTED
,maxX
,maxY
)
988 local function roundTo(val
,int
)
989 return math
.floor(val
/int
) * int
992 local function drawYaw()
993 local northX
= math
.floor(maxX
/2) - 2
994 local offset
= northX
- 4
995 local yawRounded
= math
.floor(yaw
)
996 local yawWindow
= roundTo(yaw
,10)
997 local maxXHalf
= math
.floor(maxX
/2)
998 local yawWindowOn
= false
999 local flags
= SMLSIZE
1000 if (not(yawWindow
== 0 or yawWindow
== 90 or yawWindow
== 180 or yawWindow
== 270 or yawWindow
== 360)) then
1004 if (yawRounded
== 0 or yawRounded
== 360) then
1005 lcd
.drawText(northX
- offset
, minY
+1, "W", SMLSIZE
)
1006 lcd
.drawText(northX
, minY
+1, "N", flags
)
1007 lcd
.drawText(northX
+ offset
, minY
+1, "E", SMLSIZE
)
1008 elseif (yawRounded
== 90) then
1009 lcd
.drawText(northX
- offset
, minY
+1, "N", SMLSIZE
)
1010 lcd
.drawText(northX
, minY
+1, "E", flags
)
1011 lcd
.drawText(northX
+ offset
, minY
+1, "S", SMLSIZE
)
1012 elseif (yawRounded
== 180) then
1013 lcd
.drawText(northX
- offset
, minY
+1, "W", SMLSIZE
)
1014 lcd
.drawText(northX
, minY
+1, "S", flags
)
1015 lcd
.drawText(northX
+ offset
, minY
+1, "E", SMLSIZE
)
1016 elseif (yawRounded
== 270) then
1017 lcd
.drawText(northX
- offset
, minY
+1, "S", SMLSIZE
)
1018 lcd
.drawText(northX
, minY
+1, "W", flags
)
1019 lcd
.drawText(northX
+ offset
, minY
+1, "N", SMLSIZE
)
1020 elseif ( yaw
> 0 and yaw
< 90) then
1021 northX
= (maxXHalf
- 2) - 0.3*yaw
1022 lcd
.drawText(northX
, minY
+1, "N", flags
)
1023 lcd
.drawText(northX
+ offset
, minY
+1, "E", SMLSIZE
)
1025 lcd
.drawText(northX
+ offset
+ offset
, minY
+1, "S", SMLSIZE
)
1027 elseif ( yaw
> 90 and yaw
< 180) then
1028 northX
= (maxXHalf
- 2) - 0.3*(yaw
- 180)
1029 lcd
.drawText(northX
- offset
, minY
+1, "E", SMLSIZE
)
1030 lcd
.drawText(northX
, minY
+1, "S", flags
)
1032 lcd
.drawText(northX
+ offset
, minY
+1, "W", SMLSIZE
)
1034 elseif ( yaw
> 180 and yaw
< 270) then
1035 northX
= (maxXHalf
- 2) - 0.3*(yaw
- 270)
1036 lcd
.drawText(northX
, minY
+1, "W", SMLSIZE
)
1037 lcd
.drawText(northX
- offset
, minY
+1, "S", flags
)
1039 lcd
.drawText(northX
- offset
- offset
, minY
+1, "E", SMLSIZE
)
1041 elseif ( yaw
> 270 and yaw
< 360) then
1042 northX
= (maxXHalf
- 2) - 0.3*(yaw
- 360)
1043 lcd
.drawText(northX
, minY
+1, "N", SMLSIZE
)
1044 lcd
.drawText(northX
- offset
, minY
+1, "W", flags
)
1046 lcd
.drawText(northX
- offset
- offset
, minY
+1, "S", SMLSIZE
)
1049 lcd
.drawText(northX
+ offset
, minY
+1, "E", SMLSIZE
)
1052 lcd
.drawLine(minX
, minY
+7, maxX
, minY
+7, SOLID
, 0)
1057 elseif (yaw
< 100) then
1062 lcd
.drawNumber(minX
+ offset
+ xx
, minY
, yaw
, MIDSIZE
+INVERS
)
1065 local function drawHud()
1071 local function drawHomeDirection()
1072 local ox
= maxX
+ 14
1074 local angle
= math
.floor( yaw
- homeAngle
)
1075 if ( math
.abs(angle
) > 45 and math
.abs(angle
) < 315) then
1081 local x1
= ox
+ r1
* math
.cos(math
.rad(angle
- 90))
1082 local y1
= oy
+ r1
* math
.sin(math
.rad(angle
- 90))
1083 local x2
= ox
+ r2
* math
.cos(math
.rad(angle
- 90 + 120))
1084 local y2
= oy
+ r2
* math
.sin(math
.rad(angle
- 90 + 120))
1085 local x3
= ox
+ r2
* math
.cos(math
.rad(angle
- 90 - 120))
1086 local y3
= oy
+ r2
* math
.sin(math
.rad(angle
- 90 - 120))
1088 lcd
.drawLine(x1
,y1
,x2
,y2
,SOLID
,1)
1089 lcd
.drawLine(x1
,y1
,x3
,y3
,SOLID
,1)
1090 lcd
.drawLine(ox
,oy
,x2
,y2
,SOLID
,1)
1091 lcd
.drawLine(ox
,oy
,x3
,y3
,SOLID
,1)
1094 local function drawFlightTime()
1095 lcd
.drawText(maxX
, 1, "T:", SMLSIZE
+INVERS
)
1096 lcd
.drawTimer(lcd
.getLastRightPos(), 1, flightTime
, SMLSIZE
+INVERS
)
1099 local function drawRSSI()
1100 local rssi
= getRSSI()
1101 lcd
.drawText(128, 1, rssi
, SMLSIZE
+INVERS
+RIGHT
)
1102 lcd
.drawText(lcd
.getLastLeftPos(), 1, "Rssi:", SMLSIZE
+INVERS
+RIGHT
)
1105 local function drawTxVoltage()
1106 txVId
=getFieldInfo("tx-voltage").id
1107 txV
= getValue(txVId
)*10
1109 lcd
.drawText(128, 10, "v", SMLSIZE
+RIGHT
)
1110 lcd
.drawNumber(lcd
.getLastLeftPos(), 10, txV
, SMLSIZE
+PREC1
+RIGHT
)
1111 lcd
.drawText(lcd
.getLastLeftPos(), 10, "Tx:", SMLSIZE
+RIGHT
)
1115 local lastStatusArmed
= 0
1116 local lastGpsStatus
= 0
1117 local lastFlightMode
= 0
1118 local lastBattLevel
= 0
1120 local batLevels
= {}
1135 local function checkSoundEvents()
1136 if (battCapacity
> 0) then
1137 batLevel
= (1 - (battMah
/battCapacity
))*100
1142 if batLevel
< (batLevels
[lastBattLevel
] + 1) and lastBattLevel
<= 11 then
1143 playSound("bat"..batLevels
[lastBattLevel
])
1144 lastBattLevel
= lastBattLevel
+ 1
1147 if statusArmed
== 1 and lastStatusArmed
== 0 then
1148 lastStatusArmed
= statusArmed
1150 elseif statusArmed
== 0 and lastStatusArmed
== 1 then
1151 lastStatusArmed
= statusArmed
1152 playSound("disarmed")
1155 if gpsStatus
> 2 and lastGpsStatus
<= 2 then
1156 lastGpsStatus
= gpsStatus
1158 elseif gpsStatus
<= 2 and lastGpsStatus
> 2 then
1159 lastGpsStatus
= gpsStatus
1160 playSound("gpsnofix")
1163 if flightMode
~= lastFlightMode
then
1164 lastFlightMode
= flightMode
1165 playSoundByFrameTypeAndFlightMode(frameType
,flightMode
)
1168 --------------------------------------------------------------------------------
1170 --------------------------------------------------------------------------------
1171 local showMessages
= false
1172 local showConfig
= false
1174 local function background()
1180 local function symMode()
1189 local function run(event
)
1191 if event
== EVT_ENTER_BREAK
then
1192 showMessages
= not showMessages
1195 if (clock % 8 == 0) then
1202 if showMessages
then
1215 checkLandingStatus()
1229 local function init()
1230 pushMessage(6,"Yaapu X7 script v1.1")
1234 --------------------------------------------------------------------------------
1236 --------------------------------------------------------------------------------
1237 return {run
=run
, background
=background
, init
=init
}