mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_Declination: 2to3, IGRF API update
use built-in IGRF total, incl, decl computations
This commit is contained in:
parent
ebcdf4c9c6
commit
67a503d5d8
@ -6,93 +6,81 @@ generate field tables from IGRF12
|
|||||||
import pyigrf12 as igrf
|
import pyigrf12 as igrf
|
||||||
import numpy as np
|
import numpy as np
|
||||||
import datetime
|
import datetime
|
||||||
import os.path
|
from pathlib import Path
|
||||||
import sys
|
|
||||||
from math import sqrt, pi, atan2, asin
|
|
||||||
|
|
||||||
if not os.path.isfile("AP_Declination.h"):
|
if not Path("AP_Declination.h").is_file():
|
||||||
print("Please run this tool from the AP_Declination directory")
|
raise OSError("Please run this tool from the AP_Declination directory")
|
||||||
sys.exit(1)
|
|
||||||
|
|
||||||
|
|
||||||
def field_to_angles(x, y, z):
|
def write_table(f,name, table):
|
||||||
intensity = sqrt(x**2+y**2+z**2)
|
'''write one table'''
|
||||||
r2d = 180.0 / pi
|
f.write("const float AP_Declination::%s[%u][%u] = {\n" %
|
||||||
declination = r2d * atan2(y, x)
|
(name, NUM_LAT, NUM_LON))
|
||||||
inclination = r2d * asin(z / intensity)
|
for i in range(NUM_LAT):
|
||||||
return [intensity, inclination, declination]
|
f.write(" {")
|
||||||
|
for j in range(NUM_LON):
|
||||||
|
f.write("%.5f" % table[i][j])
|
||||||
|
if j != NUM_LON-1:
|
||||||
|
f.write(",")
|
||||||
|
f.write("}")
|
||||||
|
if i != NUM_LAT-1:
|
||||||
|
f.write(",")
|
||||||
|
f.write("\n")
|
||||||
|
f.write("};\n\n")
|
||||||
|
|
||||||
|
|
||||||
isv = 0
|
|
||||||
date = datetime.datetime.now()
|
|
||||||
itype = 1
|
|
||||||
alt = 0.0
|
|
||||||
|
|
||||||
SAMPLING_RES = 10
|
|
||||||
SAMPLING_MIN_LAT = -90
|
|
||||||
SAMPLING_MAX_LAT = 90
|
|
||||||
SAMPLING_MIN_LON = -180
|
|
||||||
SAMPLING_MAX_LON = 180
|
|
||||||
|
|
||||||
NUM_LAT = 1 + (SAMPLING_MAX_LAT - SAMPLING_MIN_LAT) / SAMPLING_RES
|
if __name__ == '__main__':
|
||||||
NUM_LON = 1 + (SAMPLING_MAX_LON - SAMPLING_MIN_LON) / SAMPLING_RES
|
|
||||||
|
|
||||||
intensity_table = np.empty((NUM_LAT, NUM_LON))
|
date = datetime.datetime.now()
|
||||||
inclination_table = np.empty((NUM_LAT, NUM_LON))
|
# date = datetime.date(2018,2,20)
|
||||||
declination_table = np.empty((NUM_LAT, NUM_LON))
|
|
||||||
|
|
||||||
for i in range(NUM_LAT):
|
SAMPLING_RES = 10
|
||||||
for j in range(NUM_LON):
|
SAMPLING_MIN_LAT = -90
|
||||||
lat = SAMPLING_MIN_LAT + i*SAMPLING_RES
|
SAMPLING_MAX_LAT = 90
|
||||||
lon = SAMPLING_MIN_LON + j*SAMPLING_RES
|
SAMPLING_MIN_LON = -180
|
||||||
x, y, z, f, d = igrf.gridigrf12(date, isv, itype, alt, lat, lon)
|
SAMPLING_MAX_LON = 180
|
||||||
intensity, I, D = field_to_angles(x, y, z)
|
|
||||||
intensity_table[i][j] = intensity * 0.00001
|
|
||||||
inclination_table[i][j] = I
|
|
||||||
declination_table[i][j] = D
|
|
||||||
|
|
||||||
tfile = open("tables.cpp", 'w')
|
lats = np.arange(SAMPLING_MIN_LAT, SAMPLING_MAX_LAT+SAMPLING_RES, SAMPLING_RES)
|
||||||
tfile.write('''// this is an auto-generated file from the IGRF tables. Do not edit
|
lons = np.arange(SAMPLING_MIN_LON, SAMPLING_MAX_LON+SAMPLING_RES, SAMPLING_RES)
|
||||||
|
|
||||||
|
NUM_LAT = lats.size
|
||||||
|
NUM_LON = lons.size
|
||||||
|
|
||||||
|
intensity_table = np.empty((NUM_LAT, NUM_LON))
|
||||||
|
inclination_table = np.empty((NUM_LAT, NUM_LON))
|
||||||
|
declination_table = np.empty((NUM_LAT, NUM_LON))
|
||||||
|
|
||||||
|
for i,lat in enumerate(lats):
|
||||||
|
for j,lon in enumerate(lons):
|
||||||
|
mag = igrf.igrf(date=date, glat=lat, glon=lon, alt=0., isv=0, itype=1)
|
||||||
|
intensity_table[i][j] = mag.total/1e5
|
||||||
|
inclination_table[i][j] = mag.incl
|
||||||
|
declination_table[i][j] = mag.decl
|
||||||
|
|
||||||
|
with open("tables.cpp", 'w') as f:
|
||||||
|
f.write('''// this is an auto-generated file from the IGRF tables. Do not edit
|
||||||
// To re-generate run generate/generate.py
|
// To re-generate run generate/generate.py
|
||||||
|
|
||||||
#include "AP_Declination.h"
|
#include "AP_Declination.h"
|
||||||
|
|
||||||
''')
|
''')
|
||||||
|
|
||||||
tfile.write('''
|
f.write('''const float AP_Declination::SAMPLING_RES = %u;
|
||||||
const float AP_Declination::SAMPLING_RES = %u;
|
|
||||||
const float AP_Declination::SAMPLING_MIN_LAT = %u;
|
const float AP_Declination::SAMPLING_MIN_LAT = %u;
|
||||||
const float AP_Declination::SAMPLING_MAX_LAT = %u;
|
const float AP_Declination::SAMPLING_MAX_LAT = %u;
|
||||||
const float AP_Declination::SAMPLING_MIN_LON = %u;
|
const float AP_Declination::SAMPLING_MIN_LON = %u;
|
||||||
const float AP_Declination::SAMPLING_MAX_LON = %u;
|
const float AP_Declination::SAMPLING_MAX_LON = %u;
|
||||||
|
|
||||||
''' % (SAMPLING_RES,
|
''' % (SAMPLING_RES,
|
||||||
SAMPLING_MIN_LAT,
|
SAMPLING_MIN_LAT,
|
||||||
SAMPLING_MAX_LAT,
|
SAMPLING_MAX_LAT,
|
||||||
SAMPLING_MIN_LON,
|
SAMPLING_MIN_LON,
|
||||||
SAMPLING_MAX_LON))
|
SAMPLING_MAX_LON))
|
||||||
|
|
||||||
|
|
||||||
def write_table(name, table):
|
write_table(f,'declination_table', declination_table)
|
||||||
'''write one table'''
|
write_table(f,'inclination_table', inclination_table)
|
||||||
tfile.write("const float AP_Declination::%s[%u][%u] = {\n" %
|
write_table(f,'intensity_table', intensity_table)
|
||||||
(name, NUM_LAT, NUM_LON))
|
|
||||||
for i in range(NUM_LAT):
|
|
||||||
tfile.write(" {")
|
|
||||||
for j in range(NUM_LON):
|
|
||||||
tfile.write("%.5f" % table[i][j])
|
|
||||||
if j != NUM_LON-1:
|
|
||||||
tfile.write(",")
|
|
||||||
tfile.write("}")
|
|
||||||
if i != NUM_LAT-1:
|
|
||||||
tfile.write(",")
|
|
||||||
tfile.write("\n")
|
|
||||||
tfile.write("};\n\n")
|
|
||||||
|
|
||||||
|
|
||||||
write_table('declination_table', declination_table)
|
|
||||||
write_table('inclination_table', inclination_table)
|
|
||||||
write_table('intensity_table', intensity_table)
|
|
||||||
|
|
||||||
|
|
||||||
tfile.close()
|
|
||||||
|
Loading…
Reference in New Issue
Block a user