CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutSign UpSign In
Ardupilot

Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.

GitHub Repository: Ardupilot/ardupilot
Path: blob/master/libraries/AP_Declination/generate/generate.py
Views: 1799
1
#!/usr/bin/env python3
2
'''
3
generate field tables from IGRF13. Note that this requires python3
4
'''
5
6
import igrf
7
import numpy as np
8
import datetime
9
from pathlib import Path
10
from pymavlink.rotmat import Vector3, Matrix3
11
import math
12
13
import argparse
14
parser = argparse.ArgumentParser(description='generate mag tables')
15
parser.add_argument('--sampling-res', type=int, default=10, help='sampling resolution, degrees')
16
parser.add_argument('--check-error', action='store_true', help='check max error')
17
parser.add_argument('--filename', type=str, default='tables.cpp', help='tables file')
18
19
args = parser.parse_args()
20
21
if not Path("AP_Declination.h").is_file():
22
raise OSError("Please run this tool from the AP_Declination directory")
23
24
25
def write_table(f,name, table):
26
'''write one table'''
27
f.write("const float AP_Declination::%s[%u][%u] = {\n" %
28
(name, NUM_LAT, NUM_LON))
29
for i in range(NUM_LAT):
30
f.write(" {")
31
for j in range(NUM_LON):
32
f.write("%.5ff" % table[i][j])
33
if j != NUM_LON-1:
34
f.write(",")
35
f.write("}")
36
if i != NUM_LAT-1:
37
f.write(",")
38
f.write("\n")
39
f.write("};\n\n")
40
41
date = datetime.datetime.now()
42
43
SAMPLING_RES = args.sampling_res
44
SAMPLING_MIN_LAT = -90
45
SAMPLING_MAX_LAT = 90
46
SAMPLING_MIN_LON = -180
47
SAMPLING_MAX_LON = 180
48
49
lats = np.arange(SAMPLING_MIN_LAT, SAMPLING_MAX_LAT+SAMPLING_RES, SAMPLING_RES)
50
lons = np.arange(SAMPLING_MIN_LON, SAMPLING_MAX_LON+SAMPLING_RES, SAMPLING_RES)
51
52
NUM_LAT = lats.size
53
NUM_LON = lons.size
54
55
intensity_table = np.empty((NUM_LAT, NUM_LON))
56
inclination_table = np.empty((NUM_LAT, NUM_LON))
57
declination_table = np.empty((NUM_LAT, NUM_LON))
58
59
max_error = 0
60
max_error_pos = None
61
max_error_field = None
62
63
def get_igrf(lat, lon):
64
'''return field as [declination_deg, inclination_deg, intensity_gauss]'''
65
mag = igrf.igrf(date, glat=lat, glon=lon, alt_km=0., isv=0, itype=1)
66
intensity = float(mag.total/1e5)
67
inclination = float(mag.incl)
68
declination = float(mag.decl)
69
return [declination, inclination, intensity]
70
71
def interpolate_table(table, latitude_deg, longitude_deg):
72
'''interpolate inside a table for a given lat/lon in degrees'''
73
# round down to nearest sampling resolution
74
min_lat = int(math.floor(latitude_deg / SAMPLING_RES) * SAMPLING_RES)
75
min_lon = int(math.floor(longitude_deg / SAMPLING_RES) * SAMPLING_RES)
76
77
# find index of nearest low sampling point
78
min_lat_index = int(math.floor(-(SAMPLING_MIN_LAT) + min_lat) / SAMPLING_RES)
79
min_lon_index = int(math.floor(-(SAMPLING_MIN_LON) + min_lon) / SAMPLING_RES)
80
81
# calculate intensity
82
data_sw = table[min_lat_index][min_lon_index]
83
data_se = table[min_lat_index][min_lon_index + 1]
84
data_ne = table[min_lat_index + 1][min_lon_index + 1]
85
data_nw = table[min_lat_index + 1][min_lon_index]
86
87
# perform bilinear interpolation on the four grid corners
88
data_min = ((longitude_deg - min_lon) / SAMPLING_RES) * (data_se - data_sw) + data_sw
89
data_max = ((longitude_deg - min_lon) / SAMPLING_RES) * (data_ne - data_nw) + data_nw
90
91
value = ((latitude_deg - min_lat) / SAMPLING_RES) * (data_max - data_min) + data_min
92
return value
93
94
95
'''
96
calculate magnetic field intensity and orientation, interpolating in tables
97
98
returns array [declination_deg, inclination_deg, intensity] or None
99
'''
100
def interpolate_field(latitude_deg, longitude_deg):
101
# limit to table bounds
102
if latitude_deg < SAMPLING_MIN_LAT:
103
return None
104
if latitude_deg >= SAMPLING_MAX_LAT:
105
return None
106
if longitude_deg < SAMPLING_MIN_LON:
107
return None
108
if longitude_deg >= SAMPLING_MAX_LON:
109
return None
110
111
intensity_gauss = interpolate_table(intensity_table, latitude_deg, longitude_deg)
112
declination_deg = interpolate_table(declination_table, latitude_deg, longitude_deg)
113
inclination_deg = interpolate_table(inclination_table, latitude_deg, longitude_deg)
114
115
return [declination_deg, inclination_deg, intensity_gauss]
116
117
def field_to_Vector3(mag):
118
'''return mGauss field from dec, inc and intensity'''
119
R = Matrix3()
120
mag_ef = Vector3(mag[2]*1000.0, 0.0, 0.0)
121
R.from_euler(0.0, -math.radians(mag[1]), math.radians(mag[0]))
122
return R * mag_ef
123
124
def test_error(lat, lon):
125
'''check for error from lat,lon'''
126
global max_error, max_error_pos, max_error_field
127
mag1 = get_igrf(lat, lon)
128
mag2 = interpolate_field(lat, lon)
129
ef1 = field_to_Vector3(mag1)
130
ef2 = field_to_Vector3(mag2)
131
err = (ef1 - ef2).length()
132
if err > max_error or err > 100:
133
print(lat, lon, err, ef1, ef2)
134
max_error = err
135
max_error_pos = (lat, lon)
136
max_error_field = ef1 - ef2
137
138
def test_max_error(lat, lon):
139
'''check for maximum error from lat,lon over SAMPLING_RES range'''
140
steps = 3
141
delta = SAMPLING_RES/steps
142
for i in range(steps):
143
for j in range(steps):
144
lat2 = lat + i * delta
145
lon2 = lon + j * delta
146
if lat2 >= SAMPLING_MAX_LAT or lon2 >= SAMPLING_MAX_LON:
147
continue
148
if lat2 <= SAMPLING_MIN_LAT or lon2 <= SAMPLING_MIN_LON:
149
continue
150
test_error(lat2, lon2)
151
152
for i,lat in enumerate(lats):
153
for j,lon in enumerate(lons):
154
mag = get_igrf(lat, lon)
155
declination_table[i][j] = mag[0]
156
inclination_table[i][j] = mag[1]
157
intensity_table[i][j] = mag[2]
158
159
with open(args.filename, 'w') as f:
160
f.write('''// this is an auto-generated file from the IGRF tables. Do not edit
161
// To re-generate run generate/generate.py
162
163
#include "AP_Declination.h"
164
165
''')
166
167
f.write('''const float AP_Declination::SAMPLING_RES = %u;
168
const float AP_Declination::SAMPLING_MIN_LAT = %u;
169
const float AP_Declination::SAMPLING_MAX_LAT = %u;
170
const float AP_Declination::SAMPLING_MIN_LON = %u;
171
const float AP_Declination::SAMPLING_MAX_LON = %u;
172
173
''' % (SAMPLING_RES,
174
SAMPLING_MIN_LAT,
175
SAMPLING_MAX_LAT,
176
SAMPLING_MIN_LON,
177
SAMPLING_MAX_LON))
178
179
180
write_table(f,'declination_table', declination_table)
181
write_table(f,'inclination_table', inclination_table)
182
write_table(f,'intensity_table', intensity_table)
183
184
if args.check_error:
185
print("Checking for maximum error")
186
for lat in range(-60,60,1):
187
for lon in range(-180,180,1):
188
test_max_error(lat, lon)
189
print("Generated with max error %.2f %s at (%.2f,%.2f)" % (
190
max_error, max_error_field, max_error_pos[0], max_error_pos[1]))
191
192
print("Table generated in %s" % args.filename)
193
194