Browse Source

AP_Declination: 2to3, IGRF API update

use built-in IGRF total, incl, decl computations
mission-4.1.18
scivision 7 years ago committed by Andrew Tridgell
parent
commit
67a503d5d8
  1. 94
      libraries/AP_Declination/generate/generate.py

94
libraries/AP_Declination/generate/generate.py

@ -6,27 +6,35 @@ 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
if __name__ == '__main__':
date = datetime.datetime.now() date = datetime.datetime.now()
itype = 1 # date = datetime.date(2018,2,20)
alt = 0.0
SAMPLING_RES = 10 SAMPLING_RES = 10
SAMPLING_MIN_LAT = -90 SAMPLING_MIN_LAT = -90
@ -34,33 +42,32 @@ SAMPLING_MAX_LAT = 90
SAMPLING_MIN_LON = -180 SAMPLING_MIN_LON = -180
SAMPLING_MAX_LON = 180 SAMPLING_MAX_LON = 180
NUM_LAT = 1 + (SAMPLING_MAX_LAT - SAMPLING_MIN_LAT) / SAMPLING_RES lats = np.arange(SAMPLING_MIN_LAT, SAMPLING_MAX_LAT+SAMPLING_RES, SAMPLING_RES)
NUM_LON = 1 + (SAMPLING_MAX_LON - SAMPLING_MIN_LON) / SAMPLING_RES 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)) intensity_table = np.empty((NUM_LAT, NUM_LON))
inclination_table = np.empty((NUM_LAT, NUM_LON)) inclination_table = np.empty((NUM_LAT, NUM_LON))
declination_table = np.empty((NUM_LAT, NUM_LON)) declination_table = np.empty((NUM_LAT, NUM_LON))
for i in range(NUM_LAT): for i,lat in enumerate(lats):
for j in range(NUM_LON): for j,lon in enumerate(lons):
lat = SAMPLING_MIN_LAT + i*SAMPLING_RES mag = igrf.igrf(date=date, glat=lat, glon=lon, alt=0., isv=0, itype=1)
lon = SAMPLING_MIN_LON + j*SAMPLING_RES intensity_table[i][j] = mag.total/1e5
x, y, z, f, d = igrf.gridigrf12(date, isv, itype, alt, lat, lon) inclination_table[i][j] = mag.incl
intensity, I, D = field_to_angles(x, y, z) declination_table[i][j] = mag.decl
intensity_table[i][j] = intensity * 0.00001
inclination_table[i][j] = I with open("tables.cpp", 'w') as f:
declination_table[i][j] = D f.write('''// this is an auto-generated file from the IGRF tables. Do not edit
tfile = open("tables.cpp", 'w')
tfile.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;
@ -73,26 +80,7 @@ const float AP_Declination::SAMPLING_MAX_LON = %u;
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…
Cancel
Save