Added EGM2008 world altitude correction.

This commit is contained in:
Mark Qvist 2024-03-26 14:18:42 +01:00
parent e2cb57d1fb
commit a2f04e23a6
8 changed files with 38285 additions and 20 deletions

File diff suppressed because one or more lines are too long

View File

@ -0,0 +1,18 @@
<PAMDataset>
<SRS>GEOGCS[&quot;WGS 84&quot;,DATUM[&quot;WGS_1984&quot;,SPHEROID[&quot;WGS 84&quot;,6378137,298.257223563,AUTHORITY[&quot;EPSG&quot;,&quot;7030&quot;]],AUTHORITY[&quot;EPSG&quot;,&quot;6326&quot;]],PRIMEM[&quot;Greenwich&quot;,0],UNIT[&quot;degree&quot;,0.017453292519943295769],AUTHORITY[&quot;EPSG&quot;,&quot;4326&quot;]]</SRS>
<GeoTransform>-0.04166666666666666,0.08333333333333333,0,90.04166666666666666,0,-0.08333333333333333</GeoTransform>
<Metadata>
<MDI key="Description">WGS84 EGM2008, 5-minute grid</MDI>
<MDI key="URL">http://earth-info.nga.mil/GandG/wgs84/gravitymod/egm2008</MDI>
<MDI key="DateTime">2009-08-29 18:45:00</MDI>
<MDI key="MaxBilinearError">0.478</MDI>
<MDI key="RMSBilinearError">0.012</MDI>
<MDI key="MaxCubicError">0.294</MDI>
<MDI key="RMSCubicError">0.005</MDI>
<MDI key="Offset">-108</MDI>
<MDI key="Scale">0.003</MDI>
<MDI key="AREA_OR_POINT">Point</MDI>
<MDI key="Vertical_Datum">WGS84</MDI>
<MDI key="Tie_Point_Location">pixel_corner</MDI>
</Metadata>
</PAMDataset>

View File

@ -0,0 +1,6 @@
0.08333333333333333
0
0
-0.08333333333333333
0
90

View File

@ -4,7 +4,7 @@ package.name = sideband
package.domain = io.unsigned
source.dir = .
source.include_exts = py,png,jpg,jpeg,webp,ttf,kv,pyi,typed,so,0,1,2,3,atlas,frag,html,css,js,whl,zip,gz,woff2,pdf,epub
source.include_exts = py,png,jpg,jpeg,webp,ttf,kv,pyi,typed,so,0,1,2,3,atlas,frag,html,css,js,whl,zip,gz,woff2,pdf,epub,pgm
source.include_patterns = assets/*,assets/fonts/*,share/*
source.exclude_patterns = app_storage/*,venv/*,Makefile,./Makefil*,requirements,precompiled/*,parked/*,./setup.py,Makef*,./Makefile,Makefile

View File

@ -1798,7 +1798,7 @@ class SidebandApp(MDApp):
self.information_screen.ids.information_scrollview.effect_cls = ScrollEffect
self.information_screen.ids.information_logo.icon = self.sideband.asset_dir+"/rns_256.png"
info = "This is "+self.root.ids.app_version_info.text+", on RNS v"+RNS.__version__+" and LXMF v"+LXMF.__version__+".\n\nHumbly build using the following open components:\n\n - [b]Reticulum[/b] (MIT License)\n - [b]LXMF[/b] (MIT License)\n - [b]KivyMD[/b] (MIT License)\n - [b]Kivy[/b] (MIT License)\n - [b]Python[/b] (PSF License)"+"\n\nGo to [u][ref=link]https://unsigned.io/donate[/ref][/u] to support the project.\n\nThe Sideband app is Copyright (c) 2024 Mark Qvist / unsigned.io\n\nPermission is granted to freely share and distribute binary copies of Sideband v"+__version__+" "+__variant__+", so long as no payment or compensation is charged for said distribution or sharing.\n\nIf you were charged or paid anything for this copy of Sideband, please report it to [b]license@unsigned.io[/b].\n\nTHIS IS EXPERIMENTAL SOFTWARE - SIDEBAND COMES WITH ABSOLUTELY NO WARRANTY - USE AT YOUR OWN RISK AND RESPONSIBILITY"
info = "This is "+self.root.ids.app_version_info.text+", on RNS v"+RNS.__version__+" and LXMF v"+LXMF.__version__+".\n\nHumbly build using the following open components:\n\n - [b]Reticulum[/b] (MIT License)\n - [b]LXMF[/b] (MIT License)\n - [b]KivyMD[/b] (MIT License)\n - [b]Kivy[/b] (MIT License)\n - [b]GeoidHeight[/b] (LGPL License)\n - [b]Python[/b] (PSF License)"+"\n\nGo to [u][ref=link]https://unsigned.io/donate[/ref][/u] to support the project.\n\nThe Sideband app is Copyright (c) 2024 Mark Qvist / unsigned.io\n\nPermission is granted to freely share and distribute binary copies of Sideband v"+__version__+" "+__variant__+", so long as no payment or compensation is charged for said distribution or sharing.\n\nIf you were charged or paid anything for this copy of Sideband, please report it to [b]license@unsigned.io[/b].\n\nTHIS IS EXPERIMENTAL SOFTWARE - SIDEBAND COMES WITH ABSOLUTELY NO WARRANTY - USE AT YOUR OWN RISK AND RESPONSIBILITY"
self.information_screen.ids.information_info.text = info
self.information_screen.ids.information_info.bind(on_ref_press=link_exec)

View File

@ -168,6 +168,8 @@ class SidebandCore():
self.icon_macos = self.asset_dir+"/icon_macos.png"
self.notification_icon = self.asset_dir+"/notification_icon.png"
os.environ["TELEMETER_GEOID_PATH"] = os.path.join(self.asset_dir, "geoids")
if not os.path.isdir(self.app_dir+"/app_storage"):
os.makedirs(self.app_dir+"/app_storage")

View File

@ -1,4 +1,7 @@
import os
import time
import mmap
import struct
import RNS
from math import pi, sin, cos, acos, asin, tan, atan, atan2
from math import radians, degrees, sqrt
@ -17,6 +20,7 @@ eccentricity_squared = 2*ellipsoid_flattening-pow(ellipsoid_flattening,2)
###############################
mean_earth_radius = (1/3)*(2*equatorial_radius+polar_radius)
geoid_height = None
def geocentric_latitude(geodetic_latitude):
e2 = eccentricity_squared
@ -290,19 +294,216 @@ def shared_radio_horizon(c1, c2,):
"antenna_distance": antenna_distance
}
def ghtest():
import pygeodesy
from pygeodesy.ellipsoidalKarney import LatLon
ginterpolator = pygeodesy.GeoidKarney("./assets/geoids/egm2008-5.pgm")
def geoid_offset(lat, lon):
global geoid_height
if geoid_height == None:
geoid_height = GeoidHeight()
return geoid_height.get(lat, lon)
# Make an example location
lat=51.416422
lon=-116.217151
def altitude_to_aamsl(alt, lat, lon):
if alt == None or lat == None or lon == None:
return None
else:
return alt-geoid_offset(lat, lon)
######################################################
# GeoidHeight class by Kim Vandry <vandry@TZoNE.ORG> #
# Originally ported fromGeographicLib/src/Geoid.cpp #
# LGPLv3 License #
######################################################
class GeoidHeight(object):
c0 = 240
c3 = (
( 9, -18, -88, 0, 96, 90, 0, 0, -60, -20),
( -9, 18, 8, 0, -96, 30, 0, 0, 60, -20),
( 9, -88, -18, 90, 96, 0, -20, -60, 0, 0),
(186, -42, -42, -150, -96, -150, 60, 60, 60, 60),
( 54, 162, -78, 30, -24, -90, -60, 60, -60, 60),
( -9, -32, 18, 30, 24, 0, 20, -60, 0, 0),
( -9, 8, 18, 30, -96, 0, -20, 60, 0, 0),
( 54, -78, 162, -90, -24, 30, 60, -60, 60, -60),
(-54, 78, 78, 90, 144, 90, -60, -60, -60, -60),
( 9, -8, -18, -30, -24, 0, 20, 60, 0, 0),
( -9, 18, -32, 0, 24, 30, 0, 0, -60, 20),
( 9, -18, -8, 0, -24, -30, 0, 0, 60, 20),
)
c0n = 372
c3n = (
( 0, 0, -131, 0, 138, 144, 0, 0, -102, -31),
( 0, 0, 7, 0, -138, 42, 0, 0, 102, -31),
( 62, 0, -31, 0, 0, -62, 0, 0, 0, 31),
(124, 0, -62, 0, 0, -124, 0, 0, 0, 62),
(124, 0, -62, 0, 0, -124, 0, 0, 0, 62),
( 62, 0, -31, 0, 0, -62, 0, 0, 0, 31),
( 0, 0, 45, 0, -183, -9, 0, 93, 18, 0),
( 0, 0, 216, 0, 33, 87, 0, -93, 12, -93),
( 0, 0, 156, 0, 153, 99, 0, -93, -12, -93),
( 0, 0, -45, 0, -3, 9, 0, 93, -18, 0),
( 0, 0, -55, 0, 48, 42, 0, 0, -84, 31),
( 0, 0, -7, 0, -48, -42, 0, 0, 84, 31),
)
c0s = 372
c3s = (
( 18, -36, -122, 0, 120, 135, 0, 0, -84, -31),
(-18, 36, -2, 0, -120, 51, 0, 0, 84, -31),
( 36, -165, -27, 93, 147, -9, 0, -93, 18, 0),
(210, 45, -111, -93, -57, -192, 0, 93, 12, 93),
(162, 141, -75, -93, -129, -180, 0, 93, -12, 93),
(-36, -21, 27, 93, 39, 9, 0, -93, -18, 0),
( 0, 0, 62, 0, 0, 31, 0, 0, 0, -31),
( 0, 0, 124, 0, 0, 62, 0, 0, 0, -62),
( 0, 0, 124, 0, 0, 62, 0, 0, 0, -62),
( 0, 0, 62, 0, 0, 31, 0, 0, 0, -31),
(-18, 36, -64, 0, 66, 51, 0, 0, -102, 31),
( 18, -36, 2, 0, -66, -51, 0, 0, 102, 31),
)
def __init__(self, name="egm2008-5.pgm"):
self.offset = None
self.scale = None
if "TELEMETER_GEOID_PATH" in os.environ:
geoid_dir = os.environ["TELEMETER_GEOID_PATH"]
else:
geoid_dir = "./"
pgm_path = os.path.join(geoid_dir, name)
RNS.log(f"Opening {pgm_path} as EGM for altitude correction", RNS.LOG_DEBUG)
with open(pgm_path, "rb") as f:
line = f.readline()
if line != b"P5\012" and line != b"P5\015\012":
raise Exception("No PGM header")
headerlen = len(line)
while True:
line = f.readline()
if len(line) == 0:
raise Exception("EOF before end of file header")
headerlen += len(line)
if line.startswith(b'# Offset '):
try:
self.offset = int(line[9:])
except ValueError as e:
raise Exception("Error reading offset", e)
elif line.startswith(b'# Scale '):
try:
self.scale = float(line[8:])
except ValueError as e:
raise Exception("Error reading scale", e)
elif not line.startswith(b'#'):
try:
self.width, self.height = list(map(int, line.split()))
except ValueError as e:
raise Exception("Bad PGM width&height line", e)
break
line = f.readline()
headerlen += len(line)
levels = int(line)
if levels != 65535:
raise Exception("PGM file must have 65535 gray levels")
if self.offset is None:
raise Exception("PGM file does not contain offset")
if self.scale is None:
raise Exception("PGM file does not contain scale")
if self.width < 2 or self.height < 2:
raise Exception("Raster size too small")
fd = f.fileno()
fullsize = os.fstat(fd).st_size
if fullsize - headerlen != self.width * self.height * 2:
raise Exception("File has the wrong length")
self.headerlen = headerlen
self.raw = mmap.mmap(fd, fullsize, mmap.MAP_SHARED, mmap.PROT_READ)
self.rlonres = self.width / 360.0
self.rlatres = (self.height - 1) / 180.0
self.ix = None
self.iy = None
def _rawval(self, ix, iy):
if iy < 0:
iy = -iy
ix += self.width/2
elif iy >= self.height:
iy = 2 * (self.height - 1) - iy
ix += self.width/2
if ix < 0:
ix += self.width
elif ix >= self.width:
ix -= self.width
return struct.unpack_from('>H', self.raw,
(iy * self.width + ix) * 2 + self.headerlen
)[0]
def get(self, lat, lon, cubic=True):
if lon < 0:
lon += 360
fy = (90 - lat) * self.rlatres
fx = lon * self.rlonres
iy = int(fy)
ix = int(fx)
fx -= ix
fy -= iy
if iy == self.height - 1:
iy -= 1
if ix != self.ix or iy != self.iy:
self.ix = ix
self.iy = iy
if not cubic:
self.v00 = self._rawval(ix, iy)
self.v01 = self._rawval(ix+1, iy)
self.v10 = self._rawval(ix, iy+1)
self.v11 = self._rawval(ix+1, iy+1)
else:
v = (
self._rawval(ix , iy - 1),
self._rawval(ix + 1, iy - 1),
self._rawval(ix - 1, iy ),
self._rawval(ix , iy ),
self._rawval(ix + 1, iy ),
self._rawval(ix + 2, iy ),
self._rawval(ix - 1, iy + 1),
self._rawval(ix , iy + 1),
self._rawval(ix + 1, iy + 1),
self._rawval(ix + 2, iy + 1),
self._rawval(ix , iy + 2),
self._rawval(ix + 1, iy + 2)
)
if iy == 0:
c3x = GeoidHeight.c3n
c0x = GeoidHeight.c0n
elif iy == self.height - 2:
c3x = GeoidHeight.c3s
c0x = GeoidHeight.c0s
else:
c3x = GeoidHeight.c3
c0x = GeoidHeight.c0
self.t = [
sum([ v[j] * c3x[j][i] for j in range(12) ]) / float(c0x)
for i in range(10)
]
if not cubic:
a = (1 - fx) * self.v00 + fx * self.v01
b = (1 - fx) * self.v10 + fx * self.v11
h = (1 - fy) * a + fy * b
else:
h = (
self.t[0] +
fx * (self.t[1] + fx * (self.t[3] + fx * self.t[6])) +
fy * (
self.t[2] + fx * (self.t[4] + fx * self.t[7]) +
fy * (self.t[5] + fx * self.t[8] + fy * self.t[9])
)
)
return self.offset + self.scale * h
# Get the geoid height
single_position=LatLon(lat, lon)
h = ginterpolator(single_position)
print(h)
# def tests():
# import RNS
@ -345,3 +546,19 @@ def ghtest():
# print("Euclidian = "+RNS.prettydistance(ed_own)+f" {fac*ed_own}")
# print("AzAlt = "+f" {aa[0]} / {aa[1]}")
# print("")
# def ghtest():
# import pygeodesy
# from pygeodesy.ellipsoidalKarney import LatLon
# ginterpolator = pygeodesy.GeoidKarney("./assets/geoids/egm2008-5.pgm")
# # Make an example location
# lat=51.416422
# lon=-116.217151
# if geoid_height == None:
# geoid_height = GeoidHeight()
# h2 = geoid_height.get(lat, lon)
# # Get the geoid height
# single_position=LatLon(lat, lon)
# h1 = ginterpolator(single_position)
# print(h1)
# print(h2)

View File

@ -5,7 +5,7 @@ import struct
import threading
from RNS.vendor import umsgpack as umsgpack
from .geo import orthodromic_distance, euclidian_distance
from .geo import orthodromic_distance, euclidian_distance, altitude_to_aamsl
from .geo import azalt, angle_to_horizon, radio_horizon, shared_radio_horizon
class Commands():
@ -680,6 +680,12 @@ class Location(Sensor):
self._raw = kwargs
self._last_update = time.time()
def get_aamsl(self):
if self.data["altitude"] == None or self.data["latitude"] == None or self.data["longitude"] == None:
return None
else:
return altitude_to_aamsl(self.data["altitude"], self.data["latitude"], self.data["longitude"])
def set_update_time(self, update_time):
self._synthesized_updates = True
self._last_update = update_time
@ -788,10 +794,12 @@ class Location(Sensor):
obj_ath = None
obj_rh = None
aamsl = None
if self.data["altitude"] != None and self.data["latitude"] != None and self.data["longitude"] != None:
coords = (self.data["latitude"], self.data["longitude"], self.data["altitude"])
aamsl = self.get_aamsl()
coords = (self.data["latitude"], self.data["longitude"], aamsl)
obj_ath = angle_to_horizon(coords)
obj_rh = radio_horizon(self.data["altitude"])
obj_rh = radio_horizon(aamsl)
rendered = {
"icon": "map-marker",
@ -799,7 +807,7 @@ class Location(Sensor):
"values": {
"latitude": self.data["latitude"],
"longitude": self.data["longitude"],
"altitude": self.data["altitude"],
"altitude": aamsl,
"speed": self.data["speed"],
"heading": self.data["bearing"],
"accuracy": self.data["accuracy"],
@ -811,13 +819,13 @@ class Location(Sensor):
if relative_to != None and "location" in relative_to.sensors:
slat = self.data["latitude"]; slon = self.data["longitude"]
salt = self.data["altitude"];
salt = aamsl
if salt == None: salt = 0
if slat != None and slon != None:
s = relative_to.sensors["location"]
d = s.data
if d != None and "latitude" in d and "longitude" in d and "altitude" in d:
lat = d["latitude"]; lon = d["longitude"]; alt = d["altitude"]
lat = d["latitude"]; lon = d["longitude"]; alt = altitude_to_aamsl(d["altitude"], lat, lon)
if lat != None and lon != None:
if alt == None: alt = 0
cs = (slat, slon, salt); cr = (lat, lon, alt)
@ -834,7 +842,7 @@ class Location(Sensor):
above_horizon = False
srh = shared_radio_horizon(cs, cr)
if self.data["altitude"] != None and d["altitude"] != None:
if salt != None and alt != None:
dalt = salt-alt
else:
dalt = None