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