Skip to content

Commit 96fd4dc

Browse files
authored
Merge pull request #261 from iNavFlight/development
v1.6.1
2 parents ea8b800 + 1457e14 commit 96fd4dc

34 files changed

+392
-104
lines changed

Diff for: README.md

+6-1
Original file line numberDiff line numberDiff line change
@@ -1,4 +1,4 @@
1-
## INAV Lua Telemetry Flight Status for Taranis/Horus - v1.6.0
1+
## INAV Lua Telemetry Flight Status for Taranis/Horus - v1.6.1
22

33
### FrSky SmartPort(S.Port), D-series, F.Port & TBS Crossfire telemetry on Taranis & Horus transmitters
44

@@ -23,6 +23,11 @@
2323
![sample](assets/iNavQX7radar.png "Radar view on Q X7 and X-Lite")  
2424
![sample](assets/iNavX9Dradar.png "Radar view on Taranis X9D, X9D+ and X9E")
2525

26+
#### Altitude graph view
27+
28+
![sample](assets/iNavQX7alt.png "Altitude graph view on Q X7 and X-Lite")  
29+
![sample](assets/iNavX9Dalt.png "Altitude graph view on Taranis X9D, X9D+ and X9E")
30+
2631
#### Horus view
2732

2833
![sample](assets/iNavHorus.png "View on Horus transmitters")

Diff for: assets/iNavHorus.png

798 Bytes
Loading

Diff for: assets/iNavQX7alt.png

4.46 KB
Loading

Diff for: assets/iNavX9Dalt.png

6.61 KB
Loading

Diff for: assets/iNavX9Dvideo.png

-9.23 KB
Loading

Diff for: dist/SCRIPTS/TELEMETRY/iNav.lua

70 Bytes
Binary file not shown.

Diff for: dist/SCRIPTS/TELEMETRY/iNav.luac

70 Bytes
Binary file not shown.

Diff for: dist/SCRIPTS/TELEMETRY/iNav/alt.luac

8.28 KB
Binary file not shown.

Diff for: dist/SCRIPTS/TELEMETRY/iNav/config.luac

227 Bytes
Binary file not shown.

Diff for: dist/SCRIPTS/TELEMETRY/iNav/crsf.luac

206 Bytes
Binary file not shown.

Diff for: dist/SCRIPTS/TELEMETRY/iNav/horus.luac

1.17 KB
Binary file not shown.

Diff for: dist/SCRIPTS/TELEMETRY/iNav/lang_de.luac

127 Bytes
Binary file not shown.

Diff for: dist/SCRIPTS/TELEMETRY/iNav/lang_es.luac

106 Bytes
Binary file not shown.

Diff for: dist/SCRIPTS/TELEMETRY/iNav/lang_fr.luac

148 Bytes
Binary file not shown.

Diff for: dist/SCRIPTS/TELEMETRY/iNav/menu.luac

382 Bytes
Binary file not shown.

Diff for: dist/SCRIPTS/TELEMETRY/iNav/other.luac

74 Bytes
Binary file not shown.

Diff for: dist/SCRIPTS/TELEMETRY/iNav/pics/bg.png

151 Bytes
Loading

Diff for: dist/SCRIPTS/TELEMETRY/iNav/radar.luac

0 Bytes
Binary file not shown.

Diff for: dist/SCRIPTS/TELEMETRY/iNav/reset.luac

436 Bytes
Binary file not shown.

Diff for: dist/WIDGETS/iNav/main.lua

+2-1
Original file line numberDiff line numberDiff line change
@@ -1,3 +1,4 @@
1+
local buildMode = ...
12
local iNav
23
local options = {
34
{ "Restore", BOOL, 0},
@@ -8,7 +9,7 @@ local TELE_PATH = "/SCRIPTS/TELEMETRY/"
89

910
-- Build with Companion
1011
local v, r, m, i, e = getVersion()
11-
if string.sub(r, -4) == "simu" then
12+
if string.sub(r, -4) == "simu" and buildMode ~= true then
1213
loadScript(TELE_PATH .. "iNav", "tc")(true)
1314
end
1415

Diff for: dist/WIDGETS/iNav/main.luac

14 Bytes
Binary file not shown.

Diff for: src/iNav.lua

+6-6
Original file line numberDiff line numberDiff line change
@@ -3,7 +3,7 @@
33
-- Docs: https://github.com/iNavFlight/LuaTelemetry
44

55
local buildMode = ...
6-
local VERSION = "1.6.0"
6+
local VERSION = "1.6.1"
77
local FILE_PATH = "/SCRIPTS/TELEMETRY/iNav/"
88
local SMLCD = LCD_W < 212
99
local HORUS = LCD_W >= 480
@@ -128,8 +128,8 @@ local function background()
128128
data.cell = getValue(data.a4_id)
129129
data.cellMin = getValue(data.a4Min_id)
130130
else
131-
if data.batt / data.cells > 4.3 or data.batt / data.cells < 2.2 then
132-
data.cells = math.floor(data.batt / 4.3) + 1
131+
if data.batt / data.cells > config[29].v or data.batt / data.cells < 2.2 then
132+
data.cells = math.floor(data.batt / config[29].v) + 1
133133
end
134134
data.cell = data.batt / data.cells
135135
data.cellMin = data.battMin / data.cells
@@ -389,10 +389,10 @@ end
389389

390390
local function run(event)
391391
-- Run background function manually on Horus
392-
if HORUS then
392+
if HORUS and data.startup == 0 then
393393
background()
394394
end
395-
395+
396396
-- Startup message
397397
if data.startup == 1 then
398398
data.startupTime = getTime()
@@ -460,7 +460,7 @@ local function run(event)
460460
if data.v ~= config[25].v then
461461
view = nil
462462
collectgarbage()
463-
view = loadfile(FILE_PATH .. (HORUS and "horus.luac" or (config[25].v == 1 and "pilot.luac" or (config[25].v == 0 and "view.luac" or "radar.luac"))))()
463+
view = loadfile(FILE_PATH .. (HORUS and "horus.luac" or (config[25].v == 0 and "view.luac" or (config[25].v == 1 and "pilot.luac" or (config[25].v == 2 and "radar.luac" or "alt.luac")))))()
464464
data.v = config[25].v
465465
end
466466
view(data, config, modes, units, labels, gpsDegMin, hdopGraph, icons, calcTrig, calcDir, VERSION, SMLCD, FLASH, FILE_PATH)

Diff for: src/iNav/alt.lua

+207
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,207 @@
1+
local function view(data, config, modes, units, labels, gpsDegMin, hdopGraph, icons, calcTrig, calcDir, VERSION, SMLCD, FLASH, FILE_PATH)
2+
3+
local LEFT_DIV = 36
4+
local LEFT_POS = SMLCD and LEFT_DIV or 73
5+
local RIGHT_POS = SMLCD and LCD_W - 31 or LCD_W - 53
6+
local X_CNTR = (RIGHT_POS + LEFT_POS) / 2 - 1
7+
local gpsFlags = SMLSIZE + RIGHT + ((not data.telem or not data.gpsFix) and FLASH or 0)
8+
local tmp, pitch
9+
10+
-- Startup message
11+
if data.startup == 2 then
12+
if not SMLCD then
13+
lcd.drawText(LEFT_POS + 8, 28, "Lua Telemetry")
14+
end
15+
lcd.drawText(X_CNTR - 10, SMLCD and 29 or 40, "v" .. VERSION)
16+
end
17+
18+
-- Flight modes
19+
tmp = X_CNTR - (SMLCD and 16 or 19)
20+
lcd.drawText(tmp + 1, 9, modes[data.modeId].t, SMLSIZE + modes[data.modeId].f)
21+
if data.headFree then
22+
lcd.drawText(tmp, 9, "HF", SMLSIZE + FLASH + RIGHT)
23+
end
24+
25+
-- Pitch calculation
26+
if data.pitchRoll then
27+
pitch = ((math.abs(data.roll) > 900 and -1 or 1) * (270 - data.pitch / 10) % 180) - 90
28+
else
29+
pitch = math.deg(math.atan2(data.accx * (data.accz >= 0 and -1 or 1), math.sqrt(data.accy * data.accy + data.accz * data.accz))) * -1
30+
end
31+
pitch = pitch >= 0 and (pitch < 1 and 0 or math.floor(pitch + 0.5)) or (pitch > -1 and 0 or math.ceil(pitch - 0.5))
32+
33+
-- Bottom center
34+
if SMLCD then
35+
if data.showDir and (not data.armed or not data.telem) then
36+
-- GPS coords
37+
lcd.drawText(RIGHT_POS, 50, config[16].v == 0 and string.format("%.5f", data.gpsLatLon.lat) or gpsDegMin(data.gpsLatLon.lat, true), gpsFlags)
38+
lcd.drawText(RIGHT_POS, 57, config[16].v == 0 and string.format("%.5f", data.gpsLatLon.lon) or gpsDegMin(data.gpsLatLon.lon, false), gpsFlags)
39+
else
40+
-- Distance
41+
tmp = data.showMax and data.distanceMax or data.distanceLast
42+
lcd.drawText(LEFT_POS + 25, 57, data.startup > 0 and "Dist " or (tmp < 1000 and math.floor(tmp + 0.5) .. units[data.dist_unit] or (string.format("%.1f", tmp / (data.dist_unit == 9 and 1000 or 5280)) .. (data.dist_unit == 9 and "km" or "mi"))), SMLSIZE + RIGHT + data.telemFlags)
43+
-- Altitude
44+
tmp = data.showMax and data.altitudeMax or data.altitude
45+
lcd.drawText(RIGHT_POS, 57, data.startup > 0 and "Alt" or (math.floor(tmp + 0.5) .. units[data.alt_unit]), SMLSIZE + RIGHT + ((not data.telem or tmp + 0.5 >= config[6].v) and FLASH or 0))
46+
if data.altHold then
47+
icons.lock(RIGHT_POS - 6, 50)
48+
end
49+
end
50+
end
51+
-- Min/Max
52+
if not data.showDir and data.showMax then
53+
lcd.drawText(RIGHT_POS, 9, "\192", SMLSIZE + RIGHT)
54+
end
55+
56+
if data.startup == 0 then
57+
-- Altitude graph
58+
local BOTTOM = SMLCD and 47 or 63
59+
if data.armed and getTime() >= data.altLst + (config[28].v * 100) then
60+
data.alt[data.altCur] = data.altitude
61+
data.altCur = data.altCur == 60 and 1 or data.altCur + 1
62+
data.altLst = getTime()
63+
data.altMin = 0
64+
data.altMax = data.alt_unit == 10 and 50 or 30
65+
for i = 1, 60 do
66+
data.altMin = math.min(data.altMin, data.alt[i])
67+
data.altMax = math.max(data.altMax, data.alt[i])
68+
end
69+
data.altMax = math.ceil(data.altMax / (data.alt_unit == 10 and 10 or 5)) * (data.alt_unit == 10 and 10 or 5)
70+
end
71+
local height = SMLCD and 30 or 40
72+
tmp = height / (data.altMax - data.altMin)
73+
for i = 1, 60 do
74+
cx = RIGHT_POS - 61 + i
75+
cy = BOTTOM - (data.alt[((data.altCur - 2 + i) % 60) + 1] - data.altMin) * tmp
76+
lcd.drawLine(cx, cy, cx, BOTTOM, SOLID, FORCE)
77+
if (i ~= 1 or not SMLCD) and (i - 1) % (60 / config[28].v) == 0 then
78+
lcd.drawLine(cx, BOTTOM - height, cx, BOTTOM, DOTTED, SMLCD and 0 or GREY_DEFAULT)
79+
end
80+
end
81+
if data.altMin < -1 then
82+
cy = data.altMin * tmp + BOTTOM
83+
lcd.drawLine(RIGHT_POS - 60, cy, RIGHT_POS, cy, DOTTED, 0)
84+
end
85+
if not SMLCD then
86+
lcd.drawText(RIGHT_POS - 60, 19, math.floor(data.altMax + 0.5) .. units[data.alt_unit], SMLSIZE + RIGHT)
87+
end
88+
89+
-- Orientation
90+
if not SMLCD and data.telem then
91+
if data.showDir or data.headingRef < 0 then
92+
lcd.drawText(LEFT_POS + 12, 29, "N", SMLSIZE)
93+
lcd.drawText(LEFT_POS + 25 - (data.heading < 100 and 3 or 0) - (data.heading < 10 and 3 or 0), 57, math.floor(data.heading + 0.5) % 360 .. "\64", SMLSIZE + RIGHT + data.telemFlags)
94+
tmp = data.heading
95+
else
96+
tmp = data.heading - data.headingRef
97+
end
98+
local r1 = math.rad(tmp)
99+
local r2 = math.rad(tmp + 145)
100+
local r3 = math.rad(tmp - 145)
101+
local x1, y1, x2, y2, x3, y3 = calcDir(r1, r2, r3, LEFT_POS + 14, 45, 7)
102+
if data.headingHold then
103+
lcd.drawFilledRectangle((x2 + x3) / 2 - 1, (y2 + y3) / 2 - 1, 3, 3, SOLID)
104+
else
105+
lcd.drawLine(x2, y2, x3, y3, SMLCD and DOTTED or SOLID, FORCE + (SMLCD and 0 or GREY_DEFAULT))
106+
end
107+
lcd.drawLine(x1, y1, x2, y2, SOLID, FORCE)
108+
lcd.drawLine(x1, y1, x3, y3, SOLID, FORCE)
109+
end
110+
end
111+
112+
-- Variometer
113+
if config[7].v % 2 == 1 then
114+
lcd.drawLine(RIGHT_POS, 8, RIGHT_POS, 63, SOLID, FORCE)
115+
lcd.drawLine(RIGHT_POS + (SMLCD and 4 or 6), 8, RIGHT_POS + (SMLCD and 4 or 6), 63, SOLID, FORCE)
116+
local varioSpeed = math.log(1 + math.min(math.abs(0.6 * (data.vspeed_unit == 6 and data.vspeed / 3.28084 or data.vspeed)), 10)) / 2.4 * (data.vspeed < 0 and -1 or 1)
117+
if data.armed then
118+
tmp = 35 - math.floor(varioSpeed * 27 + 0.5)
119+
for i = 35, tmp, (tmp > 35 and 1 or -1) do
120+
local w = SMLCD and (tmp > 35 and i + 1 or 35 - i) % 3 or (tmp > 35 and i + 1 or 35 - i) % 4
121+
if w < (SMLCD and 2 or 3) then
122+
lcd.drawLine(RIGHT_POS + 1 + w, i, RIGHT_POS + (SMLCD and 3 or 5) - w, i, SOLID, 0)
123+
end
124+
end
125+
end
126+
else
127+
lcd.drawLine(RIGHT_POS, 8, RIGHT_POS, 63, SOLID, FORCE)
128+
end
129+
130+
-- Right data - GPS
131+
lcd.drawText(LCD_W, data.crsf and 20 or 8, data.satellites % 100, MIDSIZE + RIGHT + data.telemFlags)
132+
icons.gps(LCD_W - (SMLCD and 23 or 22), data.crsf and 24 or 12)
133+
if data.crsf then
134+
lcd.drawText(LCD_W, SMLCD and 9 or 11, data.tpwr < 1000 and data.tpwr .. "mW" or data.tpwr / 1000 .. "W", SMLSIZE + RIGHT + data.telemFlags)
135+
else
136+
lcd.drawText(LCD_W + 1, SMLCD and 43 or 24, math.floor(data.gpsAlt + 0.5) .. units[data.gpsAlt_unit], gpsFlags)
137+
end
138+
if SMLCD then
139+
if data.crsf == false then
140+
lcd.drawText(LCD_W + 1, config[22].v == 0 and 32 or 22, "HDOP", RIGHT + SMLSIZE)
141+
end
142+
hdopGraph(LCD_W - 12, config[22].v == 0 and (data.crsf and 37 or 24) or 31, MIDSIZE, SMLCD)
143+
else
144+
hdopGraph(LCD_W - 39, data.crsf and 24 or 10, MIDSIZE, SMLCD)
145+
if data.crsf == false then
146+
lcd.drawText(LCD_W - (config[22].v == 0 and 24 or 25), config[22].v == 0 and 18 or 20, "HDOP", RIGHT + SMLSIZE)
147+
end
148+
lcd.drawText(LCD_W + 1, 33, config[16].v == 0 and string.format("%.5f", data.gpsLatLon.lat) or gpsDegMin(data.gpsLatLon.lat, true), gpsFlags)
149+
lcd.drawText(LCD_W + 1, 42, config[16].v == 0 and string.format("%.5f", data.gpsLatLon.lon) or gpsDegMin(data.gpsLatLon.lon, false), gpsFlags)
150+
lcd.drawText(RIGHT_POS + 8, 57, data.crsf and "LQ" or "RSSI", SMLSIZE)
151+
end
152+
lcd.drawLine(RIGHT_POS + (config[7].v % 2 == 1 and (SMLCD and 5 or 7) or 0), 50, LCD_W, 50, SOLID, FORCE)
153+
local rssiFlags = RIGHT + ((not data.telem or data.rssi < data.rssiLow) and FLASH or 0)
154+
data.rssiLast = 100
155+
lcd.drawText(LCD_W - (data.crsf and 6 or 10), 52, math.min(data.showMax and data.rssiMin or data.rssiLast, data.crsf and 100 or 99), MIDSIZE + rssiFlags)
156+
lcd.drawText(LCD_W, 57, data.crsf and "%" or "dB", SMLSIZE + rssiFlags)
157+
158+
-- Left data - Battery
159+
lcd.drawLine(LEFT_DIV, 8, LEFT_DIV, 63, SOLID, FORCE)
160+
tmp = (not data.telem or data.cell < config[3].v or (data.showFuel and config[23].v == 0 and data.fuel <= config[17].v)) and FLASH or 0
161+
if data.showFuel then
162+
if config[23].v == 0 then
163+
lcd.drawText(LEFT_DIV - 5, data.showCurr and 8 or 12, data.fuel, DBLSIZE + RIGHT + tmp)
164+
lcd.drawText(LEFT_DIV, data.showCurr and 17 or 21, "%", SMLSIZE + RIGHT + tmp)
165+
else
166+
lcd.drawText(LEFT_DIV, data.showCurr and 8 or 10, data.fuel, MIDSIZE + RIGHT + tmp)
167+
lcd.drawText(LEFT_DIV, data.showCurr and 20 or 23, config[23].l[config[23].v], SMLSIZE + RIGHT + tmp)
168+
end
169+
end
170+
lcd.drawText(LEFT_DIV - 5, data.showCurr and 25 or 32, string.format(config[1].v == 0 and "%.2f" or "%.1f", config[1].v == 0 and (data.showMax and data.cellMin or data.cell) or (data.showMax and data.battMin or data.batt)), DBLSIZE + RIGHT + tmp)
171+
lcd.drawText(LEFT_DIV, data.showCurr and 34 or 41, "V", SMLSIZE + RIGHT + tmp)
172+
if data.showCurr then
173+
tmp = data.showMax and data.currentMax or data.current
174+
lcd.drawText(LEFT_DIV - 5, 42, tmp >= 99.5 and math.floor(tmp + 0.5) or string.format("%.1f", tmp), MIDSIZE + RIGHT + data.telemFlags)
175+
lcd.drawText(LEFT_DIV, 47, "A", SMLSIZE + RIGHT + data.telemFlags)
176+
end
177+
lcd.drawLine(0, data.showCurr and 55 or 53, LEFT_DIV, data.showCurr and 55 or 53, SOLID, FORCE)
178+
tmp = data.showMax and data.speedMax or data.speed
179+
lcd.drawText(LEFT_DIV, data.showCurr and 57 or 56, tmp >= 99.5 and math.floor(tmp + 0.5) .. units[data.speed_unit] or string.format("%.1f", tmp) .. units[data.speed_unit], SMLSIZE + RIGHT + data.telemFlags)
180+
181+
-- Left data - Wide screen
182+
if not SMLCD then
183+
lcd.drawLine(LEFT_POS, 8, LEFT_POS, 63, SOLID, FORCE)
184+
-- Altitude
185+
tmp = data.showMax and data.altitudeMax or data.altitude
186+
local tmp2 = data.alt_unit == 9 and 6 or 2
187+
lcd.drawText(LEFT_DIV + 2, 9, "Alt", SMLSIZE)
188+
lcd.drawText(LEFT_POS - tmp2, data.alt_unit == 9 and 21 or 17, units[data.alt_unit], SMLSIZE + ((not data.telem or tmp + 0.5 >= config[6].v) and FLASH or 0))
189+
lcd.drawText(LEFT_POS - tmp2, 16, math.floor(tmp + 0.5), MIDSIZE + RIGHT + ((not data.telem or tmp + 0.5 >= config[6].v) and FLASH or 0))
190+
if data.altHold then
191+
icons.lock(LEFT_POS - 6, 9)
192+
end
193+
-- Distance
194+
tmp = data.showMax and data.distanceMax or data.distanceLast
195+
tmp2 = data.dist_unit == 9 and (tmp < 1000 and 6 or 11) or (tmp < 1000 and 2 or 10)
196+
lcd.drawText(LEFT_DIV + 2, 30, "Dist", SMLSIZE)
197+
lcd.drawText(LEFT_POS - tmp2, (data.dist_unit == 9 or tmp >= 1000) and 42 or 38, tmp < 1000 and units[data.dist_unit] or (data.dist_unit == 9 and "km" or "mi"), SMLSIZE + data.telemFlags)
198+
lcd.drawText(LEFT_POS - tmp2, 37, tmp < 1000 and math.floor(tmp + 0.5) or string.format("%.1f", tmp / (data.dist_unit == 9 and 1000 or 5280)), MIDSIZE + RIGHT + data.telemFlags)
199+
--Pitch
200+
lcd.drawLine(LEFT_DIV, 50, LEFT_POS, 50, SOLID, FORCE)
201+
lcd.drawText(LEFT_DIV + 5, 54, pitch > 0 and "\194" or (pitch == 0 and "->" or "\195"), SMLSIZE)
202+
lcd.drawText(LEFT_POS, 53, "\64", SMLSIZE + RIGHT + data.telemFlags)
203+
lcd.drawText(LEFT_POS - 4, 52, pitch, MIDSIZE + RIGHT + data.telemFlags)
204+
end
205+
end
206+
207+
return view

Diff for: src/iNav/build.lua

+2-1
Original file line numberDiff line numberDiff line change
@@ -33,11 +33,12 @@ crsf = loadScript(FILE_PATH .. "other", env)(config, data, units, getTelemetryId
3333
loadScript(FILE_PATH .. "view", env)()
3434
loadScript(FILE_PATH .. "pilot", env)()
3535
loadScript(FILE_PATH .. "radar", env)()
36+
loadScript(FILE_PATH .. "alt", env)()
3637
loadScript(FILE_PATH .. "horus", env)()
3738
loadScript(FILE_PATH .. "menu", env)()
3839

3940
if buildMode == nil then
40-
loadScript("/WIDGETS/iNav/main", env)()
41+
loadScript("/WIDGETS/iNav/main", env)(true)
4142
end
4243

4344
return 0

Diff for: src/iNav/config.lua

+25-23
Original file line numberDiff line numberDiff line change
@@ -5,30 +5,32 @@ local config = {
55
{ o = 1, t = "Battery View", c = 1, v = 1, i = 1, l = {[0] = "Cell", "Total"} },
66
{ o = 3, t = "Cell Low", c = 2, v = 3.5, d = true, m = 2.7, x = 3.9, i = 0.1, a = "V", b = 2 },
77
{ o = 4, t = "Cell Critical", c = 2, v = 3.4, d = true, m = 2.6, x = 3.8, i = 0.1, a = "V", b = 2 },
8-
{ o = 16, t = "Voice Alerts", c = 1, v = 2, x = 2, i = 1, l = {[0] = "Off", "Critical", "All"} },
9-
{ o = 17, t = "Feedback", c = 1, v = 3, x = 3, i = 1, l = {[0] = "Off", "Haptic", "Beeper", "All"} },
10-
{ o = 10, t = "Max Altitude", c = 4, x = 9999, b = 9 },
11-
{ o = 14, t = "Variometer", c = 1, v = 0, i = 1, x = 3, l = {[0] = "Off", "Graph", "Voice", "Both"} },
12-
{ o = 18, t = "RTH Feedback", c = 1, v = 1, i = 1, l = {[0] = "Off", "On"}, b = 17 },
13-
{ o = 19, t = "HeadFree Feedback",c = 1, v = 1, i = 1, l = {[0] = "Off", "On"}, b = 17 },
14-
{ o = 20, t = "RSSI Feedback", c = 1, v = 1, i = 1, l = {[0] = "Off", "On"}, b = 17 },
8+
{ o = 18, t = "Voice Alerts", c = 1, v = 2, x = 2, i = 1, l = {[0] = "Off", "Critical", "All"} },
9+
{ o = 19, t = "Feedback", c = 1, v = 3, x = 3, i = 1, l = {[0] = "Off", "Haptic", "Beeper", "All"} },
10+
{ o = 11, t = "Max Altitude", c = 4, x = 9999, b = 10 },
11+
{ o = 15, t = "Variometer", c = 1, v = 0, i = 1, x = 3, l = {[0] = "Off", "Graph", "Voice", "Both"} },
12+
{ o = 20, t = "RTH Feedback", c = 1, v = 1, i = 1, l = {[0] = "Off", "On"}, b = 18 },
13+
{ o = 21, t = "HeadFree Feedback",c = 1, v = 1, i = 1, l = {[0] = "Off", "On"}, b = 18 },
14+
{ o = 22, t = "RSSI Feedback", c = 1, v = 1, i = 1, l = {[0] = "Off", "On"}, b = 18 },
1515
{ o = 2, t = "Battery Alerts", c = 1, v = 2, x = 2, i = 1, l = {[0] = "Off", "Critical", "All"} },
16-
{ o = 9, t = "Altitude Alert", c = 1, v = 1, i = 1, l = {[0] = "Off", "On"} },
17-
{ o = 11, t = "Timer", c = 1, v = 1, x = 4, i = 1, l = {[0] = "Off", "Auto", "Timer1", "Timer2", "Timer3"} },
18-
{ o = 13, t = "Rx Voltage", c = 1, v = 1, i = 1, l = {[0] = "Off", "On"} },
19-
{ o = 27, t = "GPS", c = 1, v = 0, x = 0, i = 0, l = {[0] = { lat = 0, lon = 0 }} },
20-
{ o = 26, t = "GPS Coordinates", c = 1, v = 0, i = 1, l = {[0] = "Decimal", "Deg/Min"} },
21-
{ o = 8, t = "Fuel Critical", c = 2, v = 20, m = 1, x = 40, i = 1, a = "%", b = 2 },
22-
{ o = 7, t = "Fuel Low", c = 2, v = 30, m = 2, x = 50, i = 1, a = "%", b = 2 },
23-
{ o = 12, t = "Tx Voltage", c = 1, v = SMLCD and 1 or 2, x = SMLCD and 1 or 2, i = 1, l = {[0] = "Number", "Graph", "Both"} },
24-
{ o = 22, t = "Speed Sensor", c = 1, v = 0, i = 1, l = {[0] = "GPS", "Pitot"} },
25-
{ o = 25, t = "GPS Warning", c = 2, v = 3.5, d = true, m = 1.0, x = 5.0, i = 0.5, a = " HDOP" },
26-
{ o = 24, t = "GPS HDOP View", c = 1, v = 0, i = 1, l = {[0] = "Graph", "Decimal"} },
27-
{ o = 5, t = "Fuel Unit", c = 1, v = 0, i = 1, x = 2, l = {[0] = "Percent", "mAh", "mWh"} },
28-
{ o = 15, t = "Vario Steps", c = 1, v = 3, m = 0, x = 9, i = 1, l = {[0] = 1, 2, 5, 10, 15, 20, 25, 30, 40, 50} },
29-
{ o = 23, t = "View Mode", c = 1, v = 0, i = 1, x = 2, l = {[0] = "Classic", "Pilot", "Radar"} },
30-
{ o = 21, t = "AltHold Center FB",c = 1, v = 0, i = 1, l = {[0] = "Off", "On"}, b = 17 },
31-
{ o = 6, t = "Battery Capacity", c = 5, v = 1500, m = 150, x = 9950, i = 50, a = "mAh" },
16+
{ o = 10, t = "Altitude Alert", c = 1, v = 1, i = 1, l = {[0] = "Off", "On"} },
17+
{ o = 12, t = "Timer", c = 1, v = 1, x = 4, i = 1, l = {[0] = "Off", "Auto", "Timer1", "Timer2", "Timer3"} },
18+
{ o = 14, t = "Rx Voltage", c = 1, v = 1, i = 1, l = {[0] = "Off", "On"} },
19+
{ o = 29, t = "GPS", c = 1, v = 0, x = 0, i = 0, l = {[0] = { lat = 0, lon = 0 }} },
20+
{ o = 28, t = "GPS Coordinates", c = 1, v = 0, i = 1, l = {[0] = "Decimal", "Deg/Min"} },
21+
{ o = 9, t = "Fuel Critical", c = 2, v = 20, m = 1, x = 40, i = 1, a = "%", b = 2 },
22+
{ o = 8, t = "Fuel Low", c = 2, v = 30, m = 2, x = 50, i = 1, a = "%", b = 2 },
23+
{ o = 13, t = "Tx Voltage", c = 1, v = SMLCD and 1 or 2, x = SMLCD and 1 or 2, i = 1, l = {[0] = "Number", "Graph", "Both"} },
24+
{ o = 24, t = "Speed Sensor", c = 1, v = 0, i = 1, l = {[0] = "GPS", "Pitot"} },
25+
{ o = 27, t = "GPS Warning", c = 2, v = 3.5, d = true, m = 1.0, x = 5.0, i = 0.5, a = " HDOP" },
26+
{ o = 26, t = "GPS HDOP View", c = 1, v = 0, i = 1, l = {[0] = "Graph", "Decimal"} },
27+
{ o = 6, t = "Fuel Unit", c = 1, v = 0, i = 1, x = 2, l = {[0] = "Percent", "mAh", "mWh"} },
28+
{ o = 16, t = "Vario Steps", c = 1, v = 3, m = 0, x = 9, i = 1, l = {[0] = 1, 2, 5, 10, 15, 20, 25, 30, 40, 50} },
29+
{ o = 25, t = "View Mode", c = 1, v = 0, i = 1, x = 3, l = {[0] = "Classic", "Pilot", "Radar", "Altitude"} },
30+
{ o = 23, t = "AltHold Center FB",c = 1, v = 0, i = 1, l = {[0] = "Off", "On"}, b = 18 },
31+
{ o = 7, t = "Battery Capacity", c = 5, v = 1500, m = 150, x = 9950, i = 50, a = "mAh" },
32+
{ o = 17, t = "Altitude Graph", c = 1, v = 0, x = 6, i = 1, l = {[0] = "Off", 1, 2, 3, 4, 5, 6}, a = " Min" },
33+
{ o = 5, t = "Cell Calculation", c = 2, v = 4.3, d = true, m = 4.2, x = 4.5, i = 0.1, a = "V" },
3234
}
3335

3436
return config

Diff for: src/iNav/crsf.lua

+8-1
Original file line numberDiff line numberDiff line change
@@ -38,7 +38,14 @@ local function crsf(data)
3838
end
3939
data.heading = math.deg(tmp)
4040
if data.showFuel and config[23].v == 0 then
41-
data.fuel = math.min(math.floor((1 - data.fuel / config[27].v) * 100 + 0.5), 100)
41+
if data.fuelEst == -1 and data.cell > 0 then
42+
if data.fuel < 25 and config[29].v - data.cell >= 0.2 then
43+
data.fuelEst = math.min(1- (data.cell - config[2].v + 0.1) / (config[29].v - config[2].v), 1) * config[27].v
44+
else
45+
data.fuelEst = 0
46+
end
47+
end
48+
data.fuel = math.min(math.floor((1 - (data.fuel + data.fuelEst) / config[27].v) * 100 + 0.5), 100)
4249
end
4350
data.fm = getValue(data.fm_id)
4451
data.modePrev = data.mode

0 commit comments

Comments
 (0)