Skip to content

Commit

Permalink
Merge pull request #261 from iNavFlight/development
Browse files Browse the repository at this point in the history
v1.6.1
  • Loading branch information
teckel12 authored Mar 29, 2019
2 parents ea8b800 + 1457e14 commit 96fd4dc
Show file tree
Hide file tree
Showing 34 changed files with 392 additions and 104 deletions.
7 changes: 6 additions & 1 deletion README.md
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
## INAV Lua Telemetry Flight Status for Taranis/Horus - v1.6.0
## INAV Lua Telemetry Flight Status for Taranis/Horus - v1.6.1

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

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

#### Altitude graph view

![sample](assets/iNavQX7alt.png "Altitude graph view on Q X7 and X-Lite")  
![sample](assets/iNavX9Dalt.png "Altitude graph view on Taranis X9D, X9D+ and X9E")

#### Horus view

![sample](assets/iNavHorus.png "View on Horus transmitters")
Expand Down
Binary file modified assets/iNavHorus.png
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Binary file added assets/iNavQX7alt.png
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Binary file added assets/iNavX9Dalt.png
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Binary file modified assets/iNavX9Dvideo.png
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Binary file modified dist/SCRIPTS/TELEMETRY/iNav.lua
Binary file not shown.
Binary file modified dist/SCRIPTS/TELEMETRY/iNav.luac
Binary file not shown.
Binary file added dist/SCRIPTS/TELEMETRY/iNav/alt.luac
Binary file not shown.
Binary file modified dist/SCRIPTS/TELEMETRY/iNav/config.luac
Binary file not shown.
Binary file modified dist/SCRIPTS/TELEMETRY/iNav/crsf.luac
Binary file not shown.
Binary file modified dist/SCRIPTS/TELEMETRY/iNav/horus.luac
Binary file not shown.
Binary file modified dist/SCRIPTS/TELEMETRY/iNav/lang_de.luac
Binary file not shown.
Binary file modified dist/SCRIPTS/TELEMETRY/iNav/lang_es.luac
Binary file not shown.
Binary file modified dist/SCRIPTS/TELEMETRY/iNav/lang_fr.luac
Binary file not shown.
Binary file modified dist/SCRIPTS/TELEMETRY/iNav/menu.luac
Binary file not shown.
Binary file modified dist/SCRIPTS/TELEMETRY/iNav/other.luac
Binary file not shown.
Binary file modified dist/SCRIPTS/TELEMETRY/iNav/pics/bg.png
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Binary file modified dist/SCRIPTS/TELEMETRY/iNav/radar.luac
Binary file not shown.
Binary file modified dist/SCRIPTS/TELEMETRY/iNav/reset.luac
Binary file not shown.
3 changes: 2 additions & 1 deletion dist/WIDGETS/iNav/main.lua
Original file line number Diff line number Diff line change
@@ -1,3 +1,4 @@
local buildMode = ...
local iNav
local options = {
{ "Restore", BOOL, 0},
Expand All @@ -8,7 +9,7 @@ local TELE_PATH = "/SCRIPTS/TELEMETRY/"

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

Expand Down
Binary file modified dist/WIDGETS/iNav/main.luac
Binary file not shown.
12 changes: 6 additions & 6 deletions src/iNav.lua
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,7 @@
-- Docs: https://github.com/iNavFlight/LuaTelemetry

local buildMode = ...
local VERSION = "1.6.0"
local VERSION = "1.6.1"
local FILE_PATH = "/SCRIPTS/TELEMETRY/iNav/"
local SMLCD = LCD_W < 212
local HORUS = LCD_W >= 480
Expand Down Expand Up @@ -128,8 +128,8 @@ local function background()
data.cell = getValue(data.a4_id)
data.cellMin = getValue(data.a4Min_id)
else
if data.batt / data.cells > 4.3 or data.batt / data.cells < 2.2 then
data.cells = math.floor(data.batt / 4.3) + 1
if data.batt / data.cells > config[29].v or data.batt / data.cells < 2.2 then
data.cells = math.floor(data.batt / config[29].v) + 1
end
data.cell = data.batt / data.cells
data.cellMin = data.battMin / data.cells
Expand Down Expand Up @@ -389,10 +389,10 @@ end

local function run(event)
-- Run background function manually on Horus
if HORUS then
if HORUS and data.startup == 0 then
background()
end

-- Startup message
if data.startup == 1 then
data.startupTime = getTime()
Expand Down Expand Up @@ -460,7 +460,7 @@ local function run(event)
if data.v ~= config[25].v then
view = nil
collectgarbage()
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"))))()
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")))))()
data.v = config[25].v
end
view(data, config, modes, units, labels, gpsDegMin, hdopGraph, icons, calcTrig, calcDir, VERSION, SMLCD, FLASH, FILE_PATH)
Expand Down
207 changes: 207 additions & 0 deletions src/iNav/alt.lua
Original file line number Diff line number Diff line change
@@ -0,0 +1,207 @@
local function view(data, config, modes, units, labels, gpsDegMin, hdopGraph, icons, calcTrig, calcDir, VERSION, SMLCD, FLASH, FILE_PATH)

local LEFT_DIV = 36
local LEFT_POS = SMLCD and LEFT_DIV or 73
local RIGHT_POS = SMLCD and LCD_W - 31 or LCD_W - 53
local X_CNTR = (RIGHT_POS + LEFT_POS) / 2 - 1
local gpsFlags = SMLSIZE + RIGHT + ((not data.telem or not data.gpsFix) and FLASH or 0)
local tmp, pitch

-- Startup message
if data.startup == 2 then
if not SMLCD then
lcd.drawText(LEFT_POS + 8, 28, "Lua Telemetry")
end
lcd.drawText(X_CNTR - 10, SMLCD and 29 or 40, "v" .. VERSION)
end

-- Flight modes
tmp = X_CNTR - (SMLCD and 16 or 19)
lcd.drawText(tmp + 1, 9, modes[data.modeId].t, SMLSIZE + modes[data.modeId].f)
if data.headFree then
lcd.drawText(tmp, 9, "HF", SMLSIZE + FLASH + RIGHT)
end

-- Pitch calculation
if data.pitchRoll then
pitch = ((math.abs(data.roll) > 900 and -1 or 1) * (270 - data.pitch / 10) % 180) - 90
else
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
end
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))

-- Bottom center
if SMLCD then
if data.showDir and (not data.armed or not data.telem) then
-- GPS coords
lcd.drawText(RIGHT_POS, 50, config[16].v == 0 and string.format("%.5f", data.gpsLatLon.lat) or gpsDegMin(data.gpsLatLon.lat, true), gpsFlags)
lcd.drawText(RIGHT_POS, 57, config[16].v == 0 and string.format("%.5f", data.gpsLatLon.lon) or gpsDegMin(data.gpsLatLon.lon, false), gpsFlags)
else
-- Distance
tmp = data.showMax and data.distanceMax or data.distanceLast
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)
-- Altitude
tmp = data.showMax and data.altitudeMax or data.altitude
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))
if data.altHold then
icons.lock(RIGHT_POS - 6, 50)
end
end
end
-- Min/Max
if not data.showDir and data.showMax then
lcd.drawText(RIGHT_POS, 9, "\192", SMLSIZE + RIGHT)
end

if data.startup == 0 then
-- Altitude graph
local BOTTOM = SMLCD and 47 or 63
if data.armed and getTime() >= data.altLst + (config[28].v * 100) then
data.alt[data.altCur] = data.altitude
data.altCur = data.altCur == 60 and 1 or data.altCur + 1
data.altLst = getTime()
data.altMin = 0
data.altMax = data.alt_unit == 10 and 50 or 30
for i = 1, 60 do
data.altMin = math.min(data.altMin, data.alt[i])
data.altMax = math.max(data.altMax, data.alt[i])
end
data.altMax = math.ceil(data.altMax / (data.alt_unit == 10 and 10 or 5)) * (data.alt_unit == 10 and 10 or 5)
end
local height = SMLCD and 30 or 40
tmp = height / (data.altMax - data.altMin)
for i = 1, 60 do
cx = RIGHT_POS - 61 + i
cy = BOTTOM - (data.alt[((data.altCur - 2 + i) % 60) + 1] - data.altMin) * tmp
lcd.drawLine(cx, cy, cx, BOTTOM, SOLID, FORCE)
if (i ~= 1 or not SMLCD) and (i - 1) % (60 / config[28].v) == 0 then
lcd.drawLine(cx, BOTTOM - height, cx, BOTTOM, DOTTED, SMLCD and 0 or GREY_DEFAULT)
end
end
if data.altMin < -1 then
cy = data.altMin * tmp + BOTTOM
lcd.drawLine(RIGHT_POS - 60, cy, RIGHT_POS, cy, DOTTED, 0)
end
if not SMLCD then
lcd.drawText(RIGHT_POS - 60, 19, math.floor(data.altMax + 0.5) .. units[data.alt_unit], SMLSIZE + RIGHT)
end

-- Orientation
if not SMLCD and data.telem then
if data.showDir or data.headingRef < 0 then
lcd.drawText(LEFT_POS + 12, 29, "N", SMLSIZE)
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)
tmp = data.heading
else
tmp = data.heading - data.headingRef
end
local r1 = math.rad(tmp)
local r2 = math.rad(tmp + 145)
local r3 = math.rad(tmp - 145)
local x1, y1, x2, y2, x3, y3 = calcDir(r1, r2, r3, LEFT_POS + 14, 45, 7)
if data.headingHold then
lcd.drawFilledRectangle((x2 + x3) / 2 - 1, (y2 + y3) / 2 - 1, 3, 3, SOLID)
else
lcd.drawLine(x2, y2, x3, y3, SMLCD and DOTTED or SOLID, FORCE + (SMLCD and 0 or GREY_DEFAULT))
end
lcd.drawLine(x1, y1, x2, y2, SOLID, FORCE)
lcd.drawLine(x1, y1, x3, y3, SOLID, FORCE)
end
end

-- Variometer
if config[7].v % 2 == 1 then
lcd.drawLine(RIGHT_POS, 8, RIGHT_POS, 63, SOLID, FORCE)
lcd.drawLine(RIGHT_POS + (SMLCD and 4 or 6), 8, RIGHT_POS + (SMLCD and 4 or 6), 63, SOLID, FORCE)
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)
if data.armed then
tmp = 35 - math.floor(varioSpeed * 27 + 0.5)
for i = 35, tmp, (tmp > 35 and 1 or -1) do
local w = SMLCD and (tmp > 35 and i + 1 or 35 - i) % 3 or (tmp > 35 and i + 1 or 35 - i) % 4
if w < (SMLCD and 2 or 3) then
lcd.drawLine(RIGHT_POS + 1 + w, i, RIGHT_POS + (SMLCD and 3 or 5) - w, i, SOLID, 0)
end
end
end
else
lcd.drawLine(RIGHT_POS, 8, RIGHT_POS, 63, SOLID, FORCE)
end

-- Right data - GPS
lcd.drawText(LCD_W, data.crsf and 20 or 8, data.satellites % 100, MIDSIZE + RIGHT + data.telemFlags)
icons.gps(LCD_W - (SMLCD and 23 or 22), data.crsf and 24 or 12)
if data.crsf then
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)
else
lcd.drawText(LCD_W + 1, SMLCD and 43 or 24, math.floor(data.gpsAlt + 0.5) .. units[data.gpsAlt_unit], gpsFlags)
end
if SMLCD then
if data.crsf == false then
lcd.drawText(LCD_W + 1, config[22].v == 0 and 32 or 22, "HDOP", RIGHT + SMLSIZE)
end
hdopGraph(LCD_W - 12, config[22].v == 0 and (data.crsf and 37 or 24) or 31, MIDSIZE, SMLCD)
else
hdopGraph(LCD_W - 39, data.crsf and 24 or 10, MIDSIZE, SMLCD)
if data.crsf == false then
lcd.drawText(LCD_W - (config[22].v == 0 and 24 or 25), config[22].v == 0 and 18 or 20, "HDOP", RIGHT + SMLSIZE)
end
lcd.drawText(LCD_W + 1, 33, config[16].v == 0 and string.format("%.5f", data.gpsLatLon.lat) or gpsDegMin(data.gpsLatLon.lat, true), gpsFlags)
lcd.drawText(LCD_W + 1, 42, config[16].v == 0 and string.format("%.5f", data.gpsLatLon.lon) or gpsDegMin(data.gpsLatLon.lon, false), gpsFlags)
lcd.drawText(RIGHT_POS + 8, 57, data.crsf and "LQ" or "RSSI", SMLSIZE)
end
lcd.drawLine(RIGHT_POS + (config[7].v % 2 == 1 and (SMLCD and 5 or 7) or 0), 50, LCD_W, 50, SOLID, FORCE)
local rssiFlags = RIGHT + ((not data.telem or data.rssi < data.rssiLow) and FLASH or 0)
data.rssiLast = 100
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)
lcd.drawText(LCD_W, 57, data.crsf and "%" or "dB", SMLSIZE + rssiFlags)

-- Left data - Battery
lcd.drawLine(LEFT_DIV, 8, LEFT_DIV, 63, SOLID, FORCE)
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
if data.showFuel then
if config[23].v == 0 then
lcd.drawText(LEFT_DIV - 5, data.showCurr and 8 or 12, data.fuel, DBLSIZE + RIGHT + tmp)
lcd.drawText(LEFT_DIV, data.showCurr and 17 or 21, "%", SMLSIZE + RIGHT + tmp)
else
lcd.drawText(LEFT_DIV, data.showCurr and 8 or 10, data.fuel, MIDSIZE + RIGHT + tmp)
lcd.drawText(LEFT_DIV, data.showCurr and 20 or 23, config[23].l[config[23].v], SMLSIZE + RIGHT + tmp)
end
end
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)
lcd.drawText(LEFT_DIV, data.showCurr and 34 or 41, "V", SMLSIZE + RIGHT + tmp)
if data.showCurr then
tmp = data.showMax and data.currentMax or data.current
lcd.drawText(LEFT_DIV - 5, 42, tmp >= 99.5 and math.floor(tmp + 0.5) or string.format("%.1f", tmp), MIDSIZE + RIGHT + data.telemFlags)
lcd.drawText(LEFT_DIV, 47, "A", SMLSIZE + RIGHT + data.telemFlags)
end
lcd.drawLine(0, data.showCurr and 55 or 53, LEFT_DIV, data.showCurr and 55 or 53, SOLID, FORCE)
tmp = data.showMax and data.speedMax or data.speed
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)

-- Left data - Wide screen
if not SMLCD then
lcd.drawLine(LEFT_POS, 8, LEFT_POS, 63, SOLID, FORCE)
-- Altitude
tmp = data.showMax and data.altitudeMax or data.altitude
local tmp2 = data.alt_unit == 9 and 6 or 2
lcd.drawText(LEFT_DIV + 2, 9, "Alt", SMLSIZE)
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))
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))
if data.altHold then
icons.lock(LEFT_POS - 6, 9)
end
-- Distance
tmp = data.showMax and data.distanceMax or data.distanceLast
tmp2 = data.dist_unit == 9 and (tmp < 1000 and 6 or 11) or (tmp < 1000 and 2 or 10)
lcd.drawText(LEFT_DIV + 2, 30, "Dist", SMLSIZE)
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)
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)
--Pitch
lcd.drawLine(LEFT_DIV, 50, LEFT_POS, 50, SOLID, FORCE)
lcd.drawText(LEFT_DIV + 5, 54, pitch > 0 and "\194" or (pitch == 0 and "->" or "\195"), SMLSIZE)
lcd.drawText(LEFT_POS, 53, "\64", SMLSIZE + RIGHT + data.telemFlags)
lcd.drawText(LEFT_POS - 4, 52, pitch, MIDSIZE + RIGHT + data.telemFlags)
end
end

return view
3 changes: 2 additions & 1 deletion src/iNav/build.lua
Original file line number Diff line number Diff line change
Expand Up @@ -33,11 +33,12 @@ crsf = loadScript(FILE_PATH .. "other", env)(config, data, units, getTelemetryId
loadScript(FILE_PATH .. "view", env)()
loadScript(FILE_PATH .. "pilot", env)()
loadScript(FILE_PATH .. "radar", env)()
loadScript(FILE_PATH .. "alt", env)()
loadScript(FILE_PATH .. "horus", env)()
loadScript(FILE_PATH .. "menu", env)()

if buildMode == nil then
loadScript("/WIDGETS/iNav/main", env)()
loadScript("/WIDGETS/iNav/main", env)(true)
end

return 0
48 changes: 25 additions & 23 deletions src/iNav/config.lua
Original file line number Diff line number Diff line change
Expand Up @@ -5,30 +5,32 @@ local config = {
{ o = 1, t = "Battery View", c = 1, v = 1, i = 1, l = {[0] = "Cell", "Total"} },
{ 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 },
{ 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 },
{ o = 16, t = "Voice Alerts", c = 1, v = 2, x = 2, i = 1, l = {[0] = "Off", "Critical", "All"} },
{ o = 17, t = "Feedback", c = 1, v = 3, x = 3, i = 1, l = {[0] = "Off", "Haptic", "Beeper", "All"} },
{ o = 10, t = "Max Altitude", c = 4, x = 9999, b = 9 },
{ o = 14, t = "Variometer", c = 1, v = 0, i = 1, x = 3, l = {[0] = "Off", "Graph", "Voice", "Both"} },
{ o = 18, t = "RTH Feedback", c = 1, v = 1, i = 1, l = {[0] = "Off", "On"}, b = 17 },
{ o = 19, t = "HeadFree Feedback",c = 1, v = 1, i = 1, l = {[0] = "Off", "On"}, b = 17 },
{ o = 20, t = "RSSI Feedback", c = 1, v = 1, i = 1, l = {[0] = "Off", "On"}, b = 17 },
{ o = 18, t = "Voice Alerts", c = 1, v = 2, x = 2, i = 1, l = {[0] = "Off", "Critical", "All"} },
{ o = 19, t = "Feedback", c = 1, v = 3, x = 3, i = 1, l = {[0] = "Off", "Haptic", "Beeper", "All"} },
{ o = 11, t = "Max Altitude", c = 4, x = 9999, b = 10 },
{ o = 15, t = "Variometer", c = 1, v = 0, i = 1, x = 3, l = {[0] = "Off", "Graph", "Voice", "Both"} },
{ o = 20, t = "RTH Feedback", c = 1, v = 1, i = 1, l = {[0] = "Off", "On"}, b = 18 },
{ o = 21, t = "HeadFree Feedback",c = 1, v = 1, i = 1, l = {[0] = "Off", "On"}, b = 18 },
{ o = 22, t = "RSSI Feedback", c = 1, v = 1, i = 1, l = {[0] = "Off", "On"}, b = 18 },
{ o = 2, t = "Battery Alerts", c = 1, v = 2, x = 2, i = 1, l = {[0] = "Off", "Critical", "All"} },
{ o = 9, t = "Altitude Alert", c = 1, v = 1, i = 1, l = {[0] = "Off", "On"} },
{ o = 11, t = "Timer", c = 1, v = 1, x = 4, i = 1, l = {[0] = "Off", "Auto", "Timer1", "Timer2", "Timer3"} },
{ o = 13, t = "Rx Voltage", c = 1, v = 1, i = 1, l = {[0] = "Off", "On"} },
{ o = 27, t = "GPS", c = 1, v = 0, x = 0, i = 0, l = {[0] = { lat = 0, lon = 0 }} },
{ o = 26, t = "GPS Coordinates", c = 1, v = 0, i = 1, l = {[0] = "Decimal", "Deg/Min"} },
{ o = 8, t = "Fuel Critical", c = 2, v = 20, m = 1, x = 40, i = 1, a = "%", b = 2 },
{ o = 7, t = "Fuel Low", c = 2, v = 30, m = 2, x = 50, i = 1, a = "%", b = 2 },
{ 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"} },
{ o = 22, t = "Speed Sensor", c = 1, v = 0, i = 1, l = {[0] = "GPS", "Pitot"} },
{ o = 25, t = "GPS Warning", c = 2, v = 3.5, d = true, m = 1.0, x = 5.0, i = 0.5, a = " HDOP" },
{ o = 24, t = "GPS HDOP View", c = 1, v = 0, i = 1, l = {[0] = "Graph", "Decimal"} },
{ o = 5, t = "Fuel Unit", c = 1, v = 0, i = 1, x = 2, l = {[0] = "Percent", "mAh", "mWh"} },
{ 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} },
{ o = 23, t = "View Mode", c = 1, v = 0, i = 1, x = 2, l = {[0] = "Classic", "Pilot", "Radar"} },
{ o = 21, t = "AltHold Center FB",c = 1, v = 0, i = 1, l = {[0] = "Off", "On"}, b = 17 },
{ o = 6, t = "Battery Capacity", c = 5, v = 1500, m = 150, x = 9950, i = 50, a = "mAh" },
{ o = 10, t = "Altitude Alert", c = 1, v = 1, i = 1, l = {[0] = "Off", "On"} },
{ o = 12, t = "Timer", c = 1, v = 1, x = 4, i = 1, l = {[0] = "Off", "Auto", "Timer1", "Timer2", "Timer3"} },
{ o = 14, t = "Rx Voltage", c = 1, v = 1, i = 1, l = {[0] = "Off", "On"} },
{ o = 29, t = "GPS", c = 1, v = 0, x = 0, i = 0, l = {[0] = { lat = 0, lon = 0 }} },
{ o = 28, t = "GPS Coordinates", c = 1, v = 0, i = 1, l = {[0] = "Decimal", "Deg/Min"} },
{ o = 9, t = "Fuel Critical", c = 2, v = 20, m = 1, x = 40, i = 1, a = "%", b = 2 },
{ o = 8, t = "Fuel Low", c = 2, v = 30, m = 2, x = 50, i = 1, a = "%", b = 2 },
{ 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"} },
{ o = 24, t = "Speed Sensor", c = 1, v = 0, i = 1, l = {[0] = "GPS", "Pitot"} },
{ o = 27, t = "GPS Warning", c = 2, v = 3.5, d = true, m = 1.0, x = 5.0, i = 0.5, a = " HDOP" },
{ o = 26, t = "GPS HDOP View", c = 1, v = 0, i = 1, l = {[0] = "Graph", "Decimal"} },
{ o = 6, t = "Fuel Unit", c = 1, v = 0, i = 1, x = 2, l = {[0] = "Percent", "mAh", "mWh"} },
{ 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} },
{ o = 25, t = "View Mode", c = 1, v = 0, i = 1, x = 3, l = {[0] = "Classic", "Pilot", "Radar", "Altitude"} },
{ o = 23, t = "AltHold Center FB",c = 1, v = 0, i = 1, l = {[0] = "Off", "On"}, b = 18 },
{ o = 7, t = "Battery Capacity", c = 5, v = 1500, m = 150, x = 9950, i = 50, a = "mAh" },
{ o = 17, t = "Altitude Graph", c = 1, v = 0, x = 6, i = 1, l = {[0] = "Off", 1, 2, 3, 4, 5, 6}, a = " Min" },
{ o = 5, t = "Cell Calculation", c = 2, v = 4.3, d = true, m = 4.2, x = 4.5, i = 0.1, a = "V" },
}

return config
9 changes: 8 additions & 1 deletion src/iNav/crsf.lua
Original file line number Diff line number Diff line change
Expand Up @@ -38,7 +38,14 @@ local function crsf(data)
end
data.heading = math.deg(tmp)
if data.showFuel and config[23].v == 0 then
data.fuel = math.min(math.floor((1 - data.fuel / config[27].v) * 100 + 0.5), 100)
if data.fuelEst == -1 and data.cell > 0 then
if data.fuel < 25 and config[29].v - data.cell >= 0.2 then
data.fuelEst = math.min(1- (data.cell - config[2].v + 0.1) / (config[29].v - config[2].v), 1) * config[27].v
else
data.fuelEst = 0
end
end
data.fuel = math.min(math.floor((1 - (data.fuel + data.fuelEst) / config[27].v) * 100 + 0.5), 100)
end
data.fm = getValue(data.fm_id)
data.modePrev = data.mode
Expand Down
Loading

0 comments on commit 96fd4dc

Please sign in to comment.