Initial commit

This commit is contained in:
unknown
2023-08-11 00:29:02 -04:00
commit 5ab7512417
629 changed files with 77781 additions and 0 deletions

View File

@@ -0,0 +1,101 @@
/*
This program is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
This program is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with this program. If not, see <http://www.gnu.org/licenses/>.
*/
/*
* Adam M Rivera
* With direction from: Andrew Tridgell, Jason Short, Justin Beech
*
* Adapted from: http://www.societyofrobots.com/robotforum/index.php?topic=11855.0
* Scott Ferguson
* scottfromscott@gmail.com
*
*/
#include "AP_Declination.h"
#include <cmath>
#include <inttypes.h>
/*
calculate magnetic field intensity and orientation
*/
bool AP_Declination::get_mag_field_ef(float latitude_deg, float longitude_deg, float &declination_deg)
{
bool valid_input_data = true;
/* round down to nearest sampling resolution */
int32_t min_lat = static_cast<int32_t>(static_cast<int32_t>(latitude_deg / SAMPLING_RES) * SAMPLING_RES);
int32_t min_lon = static_cast<int32_t>(static_cast<int32_t>(longitude_deg / SAMPLING_RES) * SAMPLING_RES);
/* for the rare case of hitting the bounds exactly
* the rounding logic wouldn't fit, so enforce it.
*/
/* limit to table bounds - required for maxima even when table spans full globe range */
if (latitude_deg <= SAMPLING_MIN_LAT) {
min_lat = static_cast<int32_t>(SAMPLING_MIN_LAT);
valid_input_data = false;
}
if (latitude_deg >= SAMPLING_MAX_LAT) {
min_lat = static_cast<int32_t>(static_cast<int32_t>(latitude_deg / SAMPLING_RES) * SAMPLING_RES - SAMPLING_RES);
valid_input_data = false;
}
if (longitude_deg <= SAMPLING_MIN_LON) {
min_lon = static_cast<int32_t>(SAMPLING_MIN_LON);
valid_input_data = false;
}
if (longitude_deg >= SAMPLING_MAX_LON) {
min_lon = static_cast<int32_t>(static_cast<int32_t>(longitude_deg / SAMPLING_RES) * SAMPLING_RES - SAMPLING_RES);
valid_input_data = false;
}
if(valid_input_data)
{
/* find index of nearest low sampling point */
uint32_t min_lat_index = static_cast<uint32_t>((-(SAMPLING_MIN_LAT) + min_lat) / SAMPLING_RES);
uint32_t min_lon_index = static_cast<uint32_t>((-(SAMPLING_MIN_LON) + min_lon) / SAMPLING_RES);
/* calculate declination */
float data_sw = declination_table[min_lat_index][min_lon_index];
float data_se = declination_table[min_lat_index][min_lon_index + 1];;
float data_ne = declination_table[min_lat_index + 1][min_lon_index + 1];
float data_nw = declination_table[min_lat_index + 1][min_lon_index];
/* perform bilinear interpolation on the four grid corners */
float data_min = ((longitude_deg - min_lon) / SAMPLING_RES) * (data_se - data_sw) + data_sw;
float data_max = ((longitude_deg - min_lon) / SAMPLING_RES) * (data_ne - data_nw) + data_nw;
declination_deg = ((latitude_deg - min_lat) / SAMPLING_RES) * (data_max - data_min) + data_min;
}
return valid_input_data;
}
/*
calculate magnetic field intensity and orientation
*/
float AP_Declination::get_declination(float latitude_deg, float longitude_deg)
{
float declination_deg=0;
if(get_mag_field_ef(latitude_deg, longitude_deg, declination_deg))
return declination_deg;
else
return 0;
}

View File

@@ -0,0 +1,32 @@
#pragma once
/*
magnetic data derived from WMM
*/
class AP_Declination
{
public:
/*
* Calculates the magnetic intensity, declination and inclination at a given WGS-84 latitude and longitude.
* Assumes a WGS-84 height of zero
* latitude and longitude have units of degrees
* declination and inclination are returned in degrees
* intensity is returned in Gauss
* Boolean returns false if latitude and longitude are outside the valid input range of +-60 latitude and +-180 longitude
*/
static bool get_mag_field_ef(float latitude_deg, float longitude_deg, float &declination_deg);
/*
get declination in degrees for a given latitude_deg and longitude_deg
*/
static float get_declination(float latitude_deg, float longitude_deg);
private:
static const float SAMPLING_RES;
static const float SAMPLING_MIN_LAT;
static const float SAMPLING_MAX_LAT;
static const float SAMPLING_MIN_LON;
static const float SAMPLING_MAX_LON;
static const float declination_table[37][73];
};

192
src/AP_Declination/gen12.py Normal file
View File

@@ -0,0 +1,192 @@
#!/usr/bin/env python3
'''
generate field tables from IGRF12. Note that this requires python3
'''
import igrf12 as igrf
import numpy as np
import datetime
from pathlib import Path
from pymavlink.rotmat import Vector3, Matrix3
import math
import argparse
parser = argparse.ArgumentParser(description='generate mag tables')
parser.add_argument('--sampling-res', type=int, default=5, help='sampling resolution, degrees')
parser.add_argument('--check-error', action='store_true', help='check max error')
parser.add_argument('--filename', type=str, default='tables.cpp', help='tables file')
args = parser.parse_args()
if not Path("AP_Declination.h").is_file():
raise OSError("Please run this tool from the AP_Declination directory")
def write_table(f,name, table):
'''write one table'''
f.write("const float AP_Declination::%s[%u][%u] = {\n" %
(name, NUM_LAT, NUM_LON))
for i in range(NUM_LAT):
f.write(" {")
for j in range(NUM_LON):
f.write("%.5ff" % 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")
date = datetime.datetime.now()
SAMPLING_RES = args.sampling_res
SAMPLING_MIN_LAT = -90
SAMPLING_MAX_LAT = 90
SAMPLING_MIN_LON = -180
SAMPLING_MAX_LON = 180
lats = np.arange(SAMPLING_MIN_LAT, SAMPLING_MAX_LAT+SAMPLING_RES, 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))
inclination_table = np.empty((NUM_LAT, NUM_LON))
declination_table = np.empty((NUM_LAT, NUM_LON))
max_error = 0
max_error_pos = None
max_error_field = None
def get_igrf(lat, lon):
'''return field as [declination_deg, inclination_deg, intensity_gauss]'''
mag = igrf.igrf(date, glat=lat, glon=lon, alt_km=0., isv=0, itype=1)
intensity = float(mag.total/1e5)
inclination = float(mag.incl)
declination = float(mag.decl)
return [declination, inclination, intensity]
def interpolate_table(table, latitude_deg, longitude_deg):
'''interpolate inside a table for a given lat/lon in degrees'''
# round down to nearest sampling resolution
min_lat = int(math.floor(latitude_deg / SAMPLING_RES) * SAMPLING_RES)
min_lon = int(math.floor(longitude_deg / SAMPLING_RES) * SAMPLING_RES)
# find index of nearest low sampling point
min_lat_index = int(math.floor(-(SAMPLING_MIN_LAT) + min_lat) / SAMPLING_RES)
min_lon_index = int(math.floor(-(SAMPLING_MIN_LON) + min_lon) / SAMPLING_RES)
# calculate intensity
data_sw = table[min_lat_index][min_lon_index]
data_se = table[min_lat_index][min_lon_index + 1]
data_ne = table[min_lat_index + 1][min_lon_index + 1]
data_nw = table[min_lat_index + 1][min_lon_index]
# perform bilinear interpolation on the four grid corners
data_min = ((longitude_deg - min_lon) / SAMPLING_RES) * (data_se - data_sw) + data_sw
data_max = ((longitude_deg - min_lon) / SAMPLING_RES) * (data_ne - data_nw) + data_nw
value = ((latitude_deg - min_lat) / SAMPLING_RES) * (data_max - data_min) + data_min
return value
'''
calculate magnetic field intensity and orientation, interpolating in tables
returns array [declination_deg, inclination_deg, intensity] or None
'''
def interpolate_field(latitude_deg, longitude_deg):
# limit to table bounds
if latitude_deg < SAMPLING_MIN_LAT:
return None
if latitude_deg >= SAMPLING_MAX_LAT:
return None
if longitude_deg < SAMPLING_MIN_LON:
return None
if longitude_deg >= SAMPLING_MAX_LON:
return None
intensity_gauss = interpolate_table(intensity_table, latitude_deg, longitude_deg)
declination_deg = interpolate_table(declination_table, latitude_deg, longitude_deg)
inclination_deg = interpolate_table(inclination_table, latitude_deg, longitude_deg)
return [declination_deg, inclination_deg, intensity_gauss]
def field_to_Vector3(mag):
'''return mGauss field from dec, inc and intensity'''
R = Matrix3()
mag_ef = Vector3(mag[2]*1000.0, 0.0, 0.0)
R.from_euler(0.0, -math.radians(mag[1]), math.radians(mag[0]))
return R * mag_ef
def test_error(lat, lon):
'''check for error from lat,lon'''
global max_error, max_error_pos, max_error_field
mag1 = get_igrf(lat, lon)
mag2 = interpolate_field(lat, lon)
ef1 = field_to_Vector3(mag1)
ef2 = field_to_Vector3(mag2)
err = (ef1 - ef2).length()
if err > max_error or err > 100:
print(lat, lon, err, ef1, ef2)
max_error = err
max_error_pos = (lat, lon)
max_error_field = ef1 - ef2
def test_max_error(lat, lon):
'''check for maximum error from lat,lon over SAMPLING_RES range'''
steps = 3
delta = SAMPLING_RES/steps
for i in range(steps):
for j in range(steps):
lat2 = lat + i * delta
lon2 = lon + j * delta
if lat2 >= SAMPLING_MAX_LAT or lon2 >= SAMPLING_MAX_LON:
continue
if lat2 <= SAMPLING_MIN_LAT or lon2 <= SAMPLING_MIN_LON:
continue
test_error(lat2, lon2)
for i,lat in enumerate(lats):
for j,lon in enumerate(lons):
mag = get_igrf(lat, lon)
declination_table[i][j] = mag[0]
inclination_table[i][j] = mag[1]
intensity_table[i][j] = mag[2]
with open(args.filename, '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
#include "AP_Declination.h"
''')
f.write('''const float AP_Declination::SAMPLING_RES = %u;
const float AP_Declination::SAMPLING_MIN_LAT = %u;
const float AP_Declination::SAMPLING_MAX_LAT = %u;
const float AP_Declination::SAMPLING_MIN_LON = %u;
const float AP_Declination::SAMPLING_MAX_LON = %u;
''' % (SAMPLING_RES,
SAMPLING_MIN_LAT,
SAMPLING_MAX_LAT,
SAMPLING_MIN_LON,
SAMPLING_MAX_LON))
write_table(f,'declination_table', declination_table)
# write_table(f,'inclination_table', inclination_table)
# write_table(f,'intensity_table', intensity_table)
if args.check_error:
print("Checking for maximum error")
for lat in range(-60,60,1):
for lon in range(-180,180,1):
test_max_error(lat, lon)
print("Generated with max error %.2f %s at (%.2f,%.2f)" % (
max_error, max_error_field, max_error_pos[0], max_error_pos[1]))
print("Table generated in %s" % args.filename)

192
src/AP_Declination/gen13.py Normal file
View File

@@ -0,0 +1,192 @@
#!/usr/bin/env python3
'''
generate field tables from IGRF12. Note that this requires python3
'''
import igrf
import numpy as np
import datetime
from pathlib import Path
from pymavlink.rotmat import Vector3, Matrix3
import math
import argparse
parser = argparse.ArgumentParser(description='generate mag tables')
parser.add_argument('--sampling-res', type=int, default=5, help='sampling resolution, degrees')
parser.add_argument('--check-error', action='store_true', help='check max error')
parser.add_argument('--filename', type=str, default='tables.cpp', help='tables file')
args = parser.parse_args()
if not Path("AP_Declination.h").is_file():
raise OSError("Please run this tool from the AP_Declination directory")
def write_table(f,name, table):
'''write one table'''
f.write("const float AP_Declination::%s[%u][%u] = {\n" %
(name, NUM_LAT, NUM_LON))
for i in range(NUM_LAT):
f.write(" {")
for j in range(NUM_LON):
f.write("%.5ff" % 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")
date = datetime.datetime.now()
SAMPLING_RES = args.sampling_res
SAMPLING_MIN_LAT = -90
SAMPLING_MAX_LAT = 90
SAMPLING_MIN_LON = -180
SAMPLING_MAX_LON = 180
lats = np.arange(SAMPLING_MIN_LAT, SAMPLING_MAX_LAT+SAMPLING_RES, 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))
inclination_table = np.empty((NUM_LAT, NUM_LON))
declination_table = np.empty((NUM_LAT, NUM_LON))
max_error = 0
max_error_pos = None
max_error_field = None
def get_igrf(lat, lon):
'''return field as [declination_deg, inclination_deg, intensity_gauss]'''
mag = igrf.igrf(date, glat=lat, glon=lon, alt_km=0., isv=0, itype=1)
intensity = float(mag.total/1e5)
inclination = float(mag.incl)
declination = float(mag.decl)
return [declination, inclination, intensity]
def interpolate_table(table, latitude_deg, longitude_deg):
'''interpolate inside a table for a given lat/lon in degrees'''
# round down to nearest sampling resolution
min_lat = int(math.floor(latitude_deg / SAMPLING_RES) * SAMPLING_RES)
min_lon = int(math.floor(longitude_deg / SAMPLING_RES) * SAMPLING_RES)
# find index of nearest low sampling point
min_lat_index = int(math.floor(-(SAMPLING_MIN_LAT) + min_lat) / SAMPLING_RES)
min_lon_index = int(math.floor(-(SAMPLING_MIN_LON) + min_lon) / SAMPLING_RES)
# calculate intensity
data_sw = table[min_lat_index][min_lon_index]
data_se = table[min_lat_index][min_lon_index + 1]
data_ne = table[min_lat_index + 1][min_lon_index + 1]
data_nw = table[min_lat_index + 1][min_lon_index]
# perform bilinear interpolation on the four grid corners
data_min = ((longitude_deg - min_lon) / SAMPLING_RES) * (data_se - data_sw) + data_sw
data_max = ((longitude_deg - min_lon) / SAMPLING_RES) * (data_ne - data_nw) + data_nw
value = ((latitude_deg - min_lat) / SAMPLING_RES) * (data_max - data_min) + data_min
return value
'''
calculate magnetic field intensity and orientation, interpolating in tables
returns array [declination_deg, inclination_deg, intensity] or None
'''
def interpolate_field(latitude_deg, longitude_deg):
# limit to table bounds
if latitude_deg < SAMPLING_MIN_LAT:
return None
if latitude_deg >= SAMPLING_MAX_LAT:
return None
if longitude_deg < SAMPLING_MIN_LON:
return None
if longitude_deg >= SAMPLING_MAX_LON:
return None
intensity_gauss = interpolate_table(intensity_table, latitude_deg, longitude_deg)
declination_deg = interpolate_table(declination_table, latitude_deg, longitude_deg)
inclination_deg = interpolate_table(inclination_table, latitude_deg, longitude_deg)
return [declination_deg, inclination_deg, intensity_gauss]
def field_to_Vector3(mag):
'''return mGauss field from dec, inc and intensity'''
R = Matrix3()
mag_ef = Vector3(mag[2]*1000.0, 0.0, 0.0)
R.from_euler(0.0, -math.radians(mag[1]), math.radians(mag[0]))
return R * mag_ef
def test_error(lat, lon):
'''check for error from lat,lon'''
global max_error, max_error_pos, max_error_field
mag1 = get_igrf(lat, lon)
mag2 = interpolate_field(lat, lon)
ef1 = field_to_Vector3(mag1)
ef2 = field_to_Vector3(mag2)
err = (ef1 - ef2).length()
if err > max_error or err > 100:
print(lat, lon, err, ef1, ef2)
max_error = err
max_error_pos = (lat, lon)
max_error_field = ef1 - ef2
def test_max_error(lat, lon):
'''check for maximum error from lat,lon over SAMPLING_RES range'''
steps = 3
delta = SAMPLING_RES/steps
for i in range(steps):
for j in range(steps):
lat2 = lat + i * delta
lon2 = lon + j * delta
if lat2 >= SAMPLING_MAX_LAT or lon2 >= SAMPLING_MAX_LON:
continue
if lat2 <= SAMPLING_MIN_LAT or lon2 <= SAMPLING_MIN_LON:
continue
test_error(lat2, lon2)
for i,lat in enumerate(lats):
for j,lon in enumerate(lons):
mag = get_igrf(lat, lon)
declination_table[i][j] = mag[0]
inclination_table[i][j] = mag[1]
intensity_table[i][j] = mag[2]
with open(args.filename, '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
#include "AP_Declination.h"
''')
f.write('''const float AP_Declination::SAMPLING_RES = %u;
const float AP_Declination::SAMPLING_MIN_LAT = %u;
const float AP_Declination::SAMPLING_MAX_LAT = %u;
const float AP_Declination::SAMPLING_MIN_LON = %u;
const float AP_Declination::SAMPLING_MAX_LON = %u;
''' % (SAMPLING_RES,
SAMPLING_MIN_LAT,
SAMPLING_MAX_LAT,
SAMPLING_MIN_LON,
SAMPLING_MAX_LON))
write_table(f,'declination_table', declination_table)
# write_table(f,'inclination_table', inclination_table)
# write_table(f,'intensity_table', intensity_table)
if args.check_error:
print("Checking for maximum error")
for lat in range(-60,60,1):
for lon in range(-180,180,1):
test_max_error(lat, lon)
print("Generated with max error %.2f %s at (%.2f,%.2f)" % (
max_error, max_error_field, max_error_pos[0], max_error_pos[1]))
print("Table generated in %s" % args.filename)

View File

@@ -0,0 +1,51 @@
// this is an auto-generated file from the IGRF tables. Do not edit
// To re-generate run generate/generate.py
#include "AP_Declination.h"
const float AP_Declination::SAMPLING_RES = 5;
const float AP_Declination::SAMPLING_MIN_LAT = -90;
const float AP_Declination::SAMPLING_MAX_LAT = 90;
const float AP_Declination::SAMPLING_MIN_LON = -180;
const float AP_Declination::SAMPLING_MAX_LON = 180;
const float AP_Declination::declination_table[37][73] = {
{149.03407f,144.03407f,139.03406f,134.03407f,129.03407f,124.03407f,119.03407f,114.03407f,109.03407f,104.03407f,99.03407f,94.03407f,89.03407f,84.03407f,79.03407f,74.03407f,69.03407f,64.03407f,59.03407f,54.03407f,49.03407f,44.03407f,39.03407f,34.03407f,29.03407f,24.03407f,19.03407f,14.03407f,9.03407f,4.03407f,-0.96593f,-5.96593f,-10.96593f,-15.96593f,-20.96593f,-25.96593f,-30.96593f,-35.96593f,-40.96593f,-45.96593f,-50.96593f,-55.96593f,-60.96593f,-65.96593f,-70.96593f,-75.96593f,-80.96593f,-85.96593f,-90.96593f,-95.96593f,-100.96593f,-105.96593f,-110.96593f,-115.96593f,-120.96593f,-125.96593f,-130.96593f,-135.96593f,-140.96593f,-145.96593f,-150.96593f,-155.96593f,-160.96593f,-165.96593f,-170.96593f,-175.96593f,179.03407f,174.03407f,169.03407f,164.03407f,159.03407f,154.03407f,149.03407f},
{141.51289f,135.86793f,130.30584f,124.83080f,119.44524f,114.14996f,108.94426f,103.82624f,98.79295f,93.84061f,88.96488f,84.16095f,79.42378f,74.74820f,70.12900f,65.56103f,61.03928f,56.55886f,52.11505f,47.70332f,43.31927f,38.95864f,34.61732f,30.29126f,25.97650f,21.66913f,17.36530f,13.06118f,8.75303f,4.43715f,0.10991f,-4.23218f,-8.59252f,-12.97431f,-17.38060f,-21.81426f,-26.27793f,-30.77408f,-35.30500f,-39.87280f,-44.47949f,-49.12697f,-53.81710f,-58.55174f,-63.33279f,-68.16223f,-73.04212f,-77.97468f,-82.96221f,-88.00713f,-93.11192f,-98.27905f,-103.51089f,-108.80960f,-114.17698f,-119.61431f,-125.12214f,-130.70013f,-136.34680f,-142.05937f,-147.83358f,-153.66357f,-159.54185f,-165.45931f,-171.40534f,-177.36808f,176.66527f,170.70806f,164.77375f,158.87542f,153.02536f,147.23465f,141.51289f},
{129.30529f,123.04797f,117.07812f,111.38491f,105.95127f,100.75625f,95.77688f,90.98956f,86.37108f,81.89932f,77.55367f,73.31535f,69.16756f,65.09554f,61.08654f,57.12978f,53.21631f,49.33881f,45.49142f,41.66942f,37.86901f,34.08694f,30.32023f,26.56590f,22.82063f,19.08063f,15.34145f,11.59791f,7.84418f,4.07382f,0.28004f,-3.54407f,-7.40526f,-11.30984f,-15.26336f,-19.27045f,-23.33467f,-27.45845f,-31.64311f,-35.88907f,-40.19599f,-44.56309f,-48.98945f,-53.47437f,-58.01768f,-62.62012f,-67.28359f,-72.01144f,-76.80870f,-81.68223f,-86.64085f,-91.69542f,-96.85886f,-102.14600f,-107.57345f,-113.15916f,-118.92185f,-124.88005f,-131.05078f,-137.44774f,-144.07903f,-150.94447f,-158.03286f,-165.31961f,-172.76553f,179.68260f,172.08924f,164.52508f,157.06086f,149.76098f,142.67847f,135.85203f,129.30530f},
{110.25505f,104.17460f,98.66441f,93.63327f,88.99997f,84.69384f,80.65388f,76.82752f,73.16943f,69.64048f,66.20704f,62.84045f,59.51673f,56.21635f,52.92405f,49.62874f,46.32321f,43.00388f,39.67033f,36.32482f,32.97161f,29.61614f,26.26424f,22.92114f,19.59060f,16.27413f,12.97028f,9.67439f,6.37844f,3.07147f,-0.25981f,-3.63001f,-7.05394f,-10.54543f,-14.11625f,-17.77518f,-21.52749f,-25.37470f,-29.31471f,-33.34230f,-37.44981f,-41.62809f,-45.86746f,-50.15868f,-54.49391f,-58.86750f,-63.27664f,-67.72194f,-72.20787f,-76.74318f,-81.34129f,-86.02075f,-90.80586f,-95.72746f,-100.82390f,-106.14225f,-111.73969f,-117.68467f,-124.05749f,-130.94884f,-138.45456f,-146.66322f,-155.63318f,-165.35821f,-175.72937f,173.48623f,162.62307f,152.04575f,142.06085f,132.86000f,124.51417f,117.00338f,110.25505f},
{85.76021f,81.52735f,77.79070f,74.43416f,71.37193f,68.53750f,65.87661f,63.34292f,60.89542f,58.49697f,56.11379f,53.71552f,51.27574f,48.77254f,46.18931f,43.51519f,40.74548f,37.88166f,34.93116f,31.90679f,28.82578f,25.70857f,22.57709f,19.45288f,16.35486f,13.29723f,10.28748f,7.32498f,4.40043f,1.49621f,-1.41215f,-4.35362f,-7.35868f,-10.45619f,-13.67038f,-17.01862f,-20.50988f,-24.14424f,-27.91339f,-31.80187f,-35.78895f,-39.85088f,-43.96312f,-48.10247f,-52.24874f,-56.38605f,-60.50365f,-64.59643f,-68.66507f,-72.71624f,-76.76272f,-80.82387f,-84.92649f,-89.10641f,-93.41127f,-97.90497f,-102.67492f,-107.84353f,-113.58678f,-120.16345f,-127.95920f,-137.54085f,-149.67212f,-165.09730f,176.27330f,156.41262f,138.33488f,123.68413f,112.33089f,103.49538f,96.44591f,90.65322f,85.76021f},
{63.49063f,61.53268f,59.70157f,57.98263f,56.36269f,54.82753f,53.36027f,51.94025f,50.54250f,49.13776f,47.69331f,46.17455f,44.54727f,42.78015f,40.84742f,38.73085f,36.42148f,33.92045f,31.23933f,28.39991f,25.43322f,22.37797f,19.27812f,16.17948f,13.12567f,10.15346f,7.28821f,4.54010f,1.90186f,-0.65133f,-3.15956f,-5.67358f,-8.24878f,-10.93849f,-13.78779f,-16.82860f,-20.07661f,-23.53033f,-27.17213f,-30.97101f,-34.88671f,-38.87435f,-42.88883f,-46.88860f,-50.83823f,-54.70981f,-58.48343f,-62.14677f,-65.69440f,-69.12673f,-72.44904f,-75.67052f,-78.80366f,-81.86412f,-84.87128f,-87.85003f,-90.83455f,-93.87592f,-97.05823f,-100.53633f,-104.63927f,-110.22502f,-120.43804f,-157.26638f,111.32321f,89.31102f,81.43675f,76.75453f,73.28001f,70.40353f,67.88022f,65.59556f,63.49063f},
{48.02742f,47.38464f,46.65758f,45.89153f,45.11833f,44.35876f,43.62354f,42.91339f,42.21835f,41.51709f,40.77709f,39.95632f,39.00664f,37.87857f,36.52647f,34.91338f,33.01482f,30.82138f,28.34023f,25.59577f,22.62934f,19.49783f,16.27080f,13.02555f,9.84030f,6.78585f,3.91665f,1.26296f,-1.17444f,-3.42572f,-5.54885f,-7.62229f,-9.73470f,-11.97351f,-14.41415f,-17.11133f,-20.09307f,-23.35827f,-26.87804f,-30.60072f,-34.45961f,-38.38184f,-42.29652f,-46.14062f,-49.86226f,-53.42145f,-56.78910f,-59.94509f,-62.87577f,-65.57122f,-68.02220f,-70.21645f,-72.13432f,-73.74302f,-74.98855f,-75.78285f,-75.98080f,-75.33518f,-73.40197f,-69.32885f,-61.37994f,-46.16169f,-20.32594f,8.41772f,27.60663f,37.97792f,43.51550f,46.49369f,48.02544f,48.68241f,48.78368f,48.52307f,48.02742f},
{38.02510f,37.95792f,37.73497f,37.41456f,37.04227f,36.65341f,36.27445f,35.92281f,35.60472f,35.31207f,35.01947f,34.68350f,34.24514f,33.63540f,32.78320f,31.62363f,30.10536f,28.19618f,25.88705f,23.19480f,20.16366f,16.86521f,13.39569f,9.86956f,6.40899f,3.12978f,0.12611f,-2.54307f,-4.86312f,-6.86630f,-8.62717f,-10.25201f,-11.86455f,-13.59071f,-15.54422f,-17.81359f,-20.45089f,-23.46424f,-26.81646f,-30.43193f,-34.21032f,-38.04311f,-41.82809f,-45.47842f,-48.92573f,-52.11873f,-55.01953f,-57.59932f,-59.83411f,-61.70043f,-63.17020f,-64.20414f,-64.74344f,-64.69915f,-63.93902f,-62.27080f,-59.42157f,-55.01852f,-48.59713f,-39.71493f,-28.30159f,-15.18866f,-2.13379f,9.17958f,18.04877f,24.61647f,29.33790f,32.66390f,34.94945f,36.45643f,37.37842f,37.86274f,38.02510f},
{31.27326f,31.45631f,31.46505f,31.35356f,31.16598f,30.93929f,30.70590f,30.49422f,30.32590f,30.21035f,30.13820f,30.07626f,29.96635f,29.72894f,29.27146f,28.49916f,27.32664f,25.68808f,23.54579f,20.89697f,17.77899f,14.27223f,10.49883f,6.61468f,2.79343f,-0.79613f,-4.01459f,-6.77252f,-9.04210f,-10.85792f,-12.30759f,-13.51606f,-14.62889f,-15.79881f,-17.17497f,-18.89010f,-21.04162f,-23.66988f,-26.74447f,-30.16844f,-33.80096f,-37.48828f,-41.09001f,-44.49284f,-47.61215f,-50.38612f,-52.76791f,-54.71886f,-56.20341f,-57.18453f,-57.61810f,-57.44541f,-56.58460f,-54.92446f,-52.32546f,-48.63487f,-43.72300f,-37.54431f,-30.21313f,-22.05560f,-13.58090f,-5.35314f,2.16813f,8.71933f,14.22506f,18.73400f,22.35164f,25.19521f,27.37356f,28.98370f,30.11459f,30.85085f,31.27326f},
{26.36786f,26.66604f,26.79441f,26.79796f,26.71209f,26.56667f,26.39096f,26.21608f,26.07315f,25.98705f,25.96761f,26.00071f,26.04227f,26.01707f,25.82354f,25.34414f,24.45955f,23.06449f,21.08311f,18.48260f,15.28457f,11.57281f,7.49449f,3.25012f,-0.93058f,-4.82388f,-8.24909f,-11.09616f,-13.33660f,-15.01667f,-16.23676f,-17.12582f,-17.82207f,-18.46870f,-19.22186f,-20.25387f,-21.73172f,-23.76952f,-26.38065f,-29.46427f,-32.83736f,-36.29065f,-39.63654f,-42.73095f,-45.47164f,-47.78552f,-49.61560f,-50.91277f,-51.63194f,-51.72970f,-51.16052f,-49.87079f,-47.79505f,-44.86273f,-41.02406f,-36.29488f,-30.80107f,-24.78755f,-18.56808f,-12.43986f,-6.61997f,-1.23543f,3.65142f,8.01587f,11.85648f,15.18803f,18.03396f,20.41861f,22.36396f,23.89345f,25.03898f,25.84526f,26.36786f},
{22.56366f,22.90784f,23.10037f,23.17771f,23.16431f,23.07834f,22.93915f,22.77223f,22.60923f,22.48299f,22.41865f,22.42306f,22.47451f,22.51543f,22.45039f,22.15168f,21.47314f,20.27092f,18.42743f,15.87477f,12.61470f,8.73294f,4.40295f,-0.12806f,-4.57495f,-8.66629f,-12.19482f,-15.04947f,-17.22075f,-18.78121f,-19.84870f,-20.54584f,-20.97449f,-21.22186f,-21.39810f,-21.67766f,-22.29853f,-23.49197f,-25.37615f,-27.89268f,-30.83411f,-33.93295f,-36.94491f,-39.68626f,-42.03008f,-43.88606f,-45.18341f,-45.86344f,-45.87958f,-45.19889f,-43.79984f,-41.66647f,-38.78692f,-35.16910f,-30.87803f,-26.07520f,-21.01921f,-16.00229f,-11.25498f,-6.88718f,-2.90022f,0.75638f,4.13078f,7.24498f,10.09921f,12.68564f,14.99541f,17.01707f,18.73549f,20.13796f,21.22534f,22.01993f,22.56366f},
{19.49262f,19.83667f,20.05379f,20.17527f,20.21649f,20.18386f,20.08413f,19.93130f,19.74919f,19.56928f,19.42437f,19.33850f,19.31400f,19.31803f,19.27228f,19.05075f,18.49032f,17.41469f,15.66762f,13.14805f,9.84083f,5.83792f,1.34298f,-3.35039f,-7.91048f,-12.03590f,-15.51510f,-18.25608f,-20.28181f,-21.69740f,-22.63861f,-23.21706f,-23.48665f,-23.45490f,-23.14501f,-22.68034f,-22.32882f,-22.44219f,-23.29750f,-24.95324f,-27.23460f,-29.83995f,-32.46585f,-34.87275f,-36.88902f,-38.39021f,-39.28263f,-39.49980f,-39.00659f,-37.80142f,-35.90945f,-33.36829f,-30.22080f,-26.53208f,-22.42894f,-18.12682f,-13.89950f,-9.99029f,-6.52460f,-3.48752f,-0.77184f,1.74639f,4.15087f,6.46808f,8.68408f,10.77078f,12.70017f,14.44314f,15.96584f,17.23560f,18.23538f,18.97548f,19.49262f},
{16.97883f,17.28956f,17.49736f,17.63270f,17.70634f,17.71651f,17.65855f,17.53276f,17.34953f,17.13148f,16.91161f,16.72537f,16.59606f,16.51570f,16.42639f,16.21007f,15.69455f,14.67963f,12.97884f,10.46657f,7.11982f,3.04546f,-1.51809f,-6.23618f,-10.74800f,-14.74718f,-18.03985f,-20.56352f,-22.37111f,-23.58964f,-24.36165f,-24.78315f,-24.86525f,-24.54807f,-23.77488f,-22.60092f,-21.27530f,-20.21522f,-19.84302f,-20.38356f,-21.77840f,-23.76039f,-25.99255f,-28.16627f,-30.03382f,-31.40672f,-32.15138f,-32.19178f,-31.51307f,-30.15554f,-28.19296f,-25.70283f,-22.75199f,-19.41794f,-15.83548f,-12.22185f,-8.83494f,-5.87650f,-3.41043f,-1.35484f,0.45563f,2.18421f,3.92991f,5.71280f,7.50009f,9.24384f,10.90154f,12.43396f,13.79691f,14.94542f,15.85090f,16.51678f,16.97883f},
{14.93100f,15.18635f,15.35662f,15.47564f,15.55491f,15.58961f,15.56703f,15.47431f,15.30624f,15.07283f,14.80278f,14.53815f,14.31797f,14.15367f,14.00355f,13.75659f,13.23581f,12.22632f,10.52389f,7.99180f,4.61181f,0.51478f,-4.02546f,-8.64514f,-12.97740f,-16.73466f,-19.75345f,-21.99705f,-23.53093f,-24.48178f,-24.98225f,-25.11094f,-24.85499f,-24.12625f,-22.83827f,-21.01546f,-18.87808f,-16.83573f,-15.35794f,-14.78584f,-15.21092f,-16.48364f,-18.30551f,-20.32696f,-22.21443f,-23.69113f,-24.56305f,-24.73343f,-24.20144f,-23.03963f,-21.35203f,-19.23024f,-16.73747f,-13.93871f,-10.95723f,-8.00232f,-5.32287f,-3.10447f,-1.38474f,-0.04693f,1.11102f,2.28032f,3.57005f,4.99114f,6.49051f,8.00055f,9.46670f,10.84386f,12.08259f,13.13004f,13.94893f,14.53733f,14.93100f},
{13.28884f,13.47634f,13.58779f,13.66435f,13.72339f,13.76191f,13.76240f,13.70032f,13.55523f,13.32445f,13.03181f,12.72354f,12.44868f,12.22913f,12.02987f,11.74116f,11.18301f,10.13578f,8.39265f,5.82183f,2.42246f,-1.64568f,-6.07995f,-10.50575f,-14.57210f,-18.02426f,-20.72791f,-22.65695f,-23.86739f,-24.46549f,-24.56529f,-24.23837f,-23.48116f,-22.23069f,-20.43350f,-18.13422f,-15.53294f,-12.97246f,-10.85242f,-9.51146f,-9.13413f,-9.71333f,-11.06429f,-12.87374f,-14.77095f,-16.40698f,-17.52234f,-17.98440f,-17.78613f,-17.00868f,-15.76235f,-14.13365f,-12.17100f,-9.92237f,-7.49803f,-5.10053f,-2.97708f,-1.31256f,-0.13817f,0.67997f,1.36924f,2.14363f,3.12084f,4.30256f,5.61549f,6.97286f,8.30960f,9.57771f,10.72621f,11.69738f,12.44649f,12.96552f,13.28884f},
{12.00282f,12.11837f,12.15757f,12.17280f,12.19200f,12.21760f,12.22925f,12.19160f,12.07031f,11.85230f,11.55870f,11.23943f,10.94829f,10.70784f,10.47867f,10.14549f,9.52682f,8.40876f,6.59772f,3.98239f,0.58868f,-3.39652f,-7.65593f,-11.82437f,-15.58129f,-18.70505f,-21.07796f,-22.66697f,-23.50437f,-23.67076f,-23.26901f,-22.38660f,-21.06689f,-19.31693f,-17.15424f,-14.65992f,-12.00100f,-9.41297f,-7.16151f,-5.50215f,-4.63707f,-4.66326f,-5.52593f,-7.00714f,-8.76960f,-10.44558f,-11.73428f,-12.46586f,-12.61021f,-12.23504f,-11.43824f,-10.29086f,-8.82422f,-7.07057f,-5.12746f,-3.18888f,-1.49978f,-0.24872f,0.52992f,0.97589f,1.33296f,1.83313f,2.60175f,3.63251f,4.83366f,6.10049f,7.35848f,8.55851f,9.65054f,10.57405f,11.27692f,11.74307f,12.00282f},
{11.02739f,11.07622f,11.03933f,10.98421f,10.95339f,10.95728f,10.97332f,10.95552f,10.85678f,10.65621f,10.37470f,10.06586f,9.78388f,9.54402f,9.29421f,8.90939f,8.20943f,6.99576f,5.10152f,2.44783f,-0.90855f,-4.76162f,-8.79704f,-12.67530f,-16.11016f,-18.90310f,-20.93772f,-22.16415f,-22.59233f,-22.28944f,-21.36612f,-19.94707f,-18.14186f,-16.03876f,-13.72227f,-11.29101f,-8.85774f,-6.54187f,-4.47450f,-2.81373f,-1.73949f,-1.40345f,-1.85076f,-2.96503f,-4.47910f,-6.05292f,-7.37991f,-8.26855f,-8.66438f,-8.61274f,-8.19097f,-7.45133f,-6.40875f,-5.08083f,-3.55055f,-1.99810f,-0.66017f,0.27351f,0.76201f,0.94296f,1.06764f,1.38006f,2.01197f,2.95171f,4.09310f,5.31622f,6.53807f,7.70883f,8.78033f,9.68993f,10.37726f,10.81542f,11.02739f},
{10.31472f,10.31453f,10.21064f,10.08863f,10.00885f,9.99151f,10.01233f,10.01480f,9.93992f,9.76023f,9.49687f,9.20560f,8.93764f,8.69695f,8.41641f,7.96184f,7.15858f,5.83066f,3.84646f,1.16583f,-2.12473f,-5.81072f,-9.59542f,-13.17310f,-16.28734f,-18.75062f,-20.43922f,-21.28955f,-21.30455f,-20.55871f,-19.18683f,-17.35463f,-15.22699f,-12.95067f,-10.64994f,-8.42037f,-6.31911f,-4.37056f,-2.60134f,-1.08831f,0.02271f,0.55979f,0.41503f,-0.37545f,-1.61611f,-3.01321f,-4.27793f,-5.21498f,-5.75467f,-5.92327f,-5.77955f,-5.35984f,-4.66555f,-3.70057f,-2.53081f,-1.31665f,-0.27875f,0.39794f,0.66647f,0.65655f,0.61794f,0.79941f,1.33742f,2.21923f,3.33090f,4.54215f,5.76289f,6.94188f,8.03189f,8.96743f,9.67821f,10.12326f,10.31472f},
{9.80548f,9.79028f,9.64547f,9.47571f,9.36084f,9.33236f,9.36559f,9.39496f,9.35049f,9.19753f,8.95471f,8.67610f,8.40722f,8.14125f,7.79987f,7.24526f,6.31330f,4.85459f,2.77572f,0.07573f,-3.13325f,-6.63665f,-10.16260f,-13.43910f,-16.23268f,-18.36079f,-19.69530f,-20.17293f,-19.80955f,-18.70301f,-17.01472f,-14.93600f,-12.65708f,-10.34921f,-8.15147f,-6.15117f,-4.36707f,-2.76097f,-1.28854f,0.03431f,1.09685f,1.72693f,1.78209f,1.24223f,0.24367f,-0.96603f,-2.12362f,-3.04027f,-3.64042f,-3.93935f,-3.98483f,-3.80402f,-3.38988f,-2.73468f,-1.88594f,-0.97956f,-0.21314f,0.24019f,0.33045f,0.17587f,0.01620f,0.09717f,0.55809f,1.39034f,2.48092f,3.69622f,4.94135f,6.16231f,7.31051f,8.31580f,9.09607f,9.59342f,9.80548f},
{9.42061f,9.44269f,9.30332f,9.12372f,9.00240f,8.98309f,9.04347f,9.11226f,9.11026f,8.99373f,8.77341f,8.49585f,8.19865f,7.86787f,7.42197f,6.72779f,5.63702f,4.02821f,1.84470f,-0.87850f,-4.00778f,-7.33151f,-10.60178f,-13.57573f,-16.03952f,-17.81956f,-18.79634f,-18.92464f,-18.24753f,-16.88942f,-15.02701f,-12.85350f,-10.55488f,-8.30042f,-6.23006f,-4.42721f,-2.89364f,-1.55859f,-0.33464f,0.80608f,1.78575f,2.44363f,2.62210f,2.26394f,1.45958f,0.41666f,-0.62651f,-1.49054f,-2.09912f,-2.46332f,-2.62771f,-2.61823f,-2.42568f,-2.03452f,-1.47479f,-0.85584f,-0.34717f,-0.10352f,-0.17336f,-0.45104f,-0.71330f,-0.72444f,-0.34439f,0.42720f,1.48729f,2.70684f,3.98949f,5.27733f,6.51771f,7.63398f,8.53135f,9.13351f,9.42061f},
{9.06167f,9.18888f,9.12145f,8.99011f,8.90745f,8.92905f,9.03842f,9.16380f,9.21986f,9.15208f,8.95740f,8.66861f,8.31352f,7.87545f,7.27827f,6.40186f,5.11835f,3.33424f,1.02632f,-1.73833f,-4.80645f,-7.96686f,-10.98954f,-13.65607f,-15.77517f,-17.19456f,-17.82061f,-17.64000f,-16.72654f,-15.22262f,-13.30303f,-11.14274f,-8.90508f,-6.74344f,-4.79255f,-3.13707f,-1.77821f,-0.63553f,0.39969f,1.38495f,2.27215f,2.91947f,3.16817f,2.93852f,2.28580f,1.38356f,0.44726f,-0.35315f,-0.94224f,-1.33011f,-1.56318f,-1.67227f,-1.65234f,-1.48524f,-1.18690f,-0.84095f,-0.58630f,-0.55399f,-0.78557f,-1.18630f,-1.55248f,-1.66345f,-1.38052f,-0.69135f,0.31782f,1.52948f,2.84936f,4.21519f,5.56830f,6.82494f,7.87909f,8.63751f,9.06167f},
{8.62618f,8.93281f,9.01770f,9.00969f,9.02653f,9.13240f,9.31934f,9.52089f,9.65030f,9.64274f,9.47763f,9.16936f,8.73421f,8.15557f,7.36859f,6.27213f,4.76201f,2.77242f,0.31104f,-2.52526f,-5.56242f,-8.58411f,-11.37133f,-13.72824f,-15.49367f,-16.55163f,-16.84874f,-16.40943f,-15.33257f,-13.76490f,-11.86461f,-9.77763f,-7.63798f,-5.57870f,-3.72678f,-2.17026f,-0.91907f,0.10149f,1.00480f,1.86583f,2.66250f,3.27711f,3.56090f,3.42364f,2.89396f,2.11484f,1.27906f,0.54622f,-0.00961f,-0.39793f,-0.66810f,-0.85870f,-0.97354f,-0.99760f,-0.93791f,-0.85565f,-0.85902f,-1.05158f,-1.46225f,-2.00284f,-2.48854f,-2.71585f,-2.54958f,-1.96518f,-1.02907f,0.15686f,1.50304f,2.94303f,4.41141f,5.81867f,7.05190f,8.00611f,8.62618f},
{8.03598f,8.58889f,8.90722f,9.10460f,9.29148f,9.53362f,9.83144f,10.12834f,10.34195f,10.40095f,10.26805f,9.93790f,9.41372f,8.67870f,7.68051f,6.33877f,4.57424f,2.34883f,-0.29949f,-3.24365f,-6.28574f,-9.19890f,-11.77071f,-13.82904f,-15.25085f,-15.96729f,-15.97208f,-15.32534f,-14.14138f,-12.55967f,-10.71423f,-8.72028f,-6.68390f,-4.71835f,-2.94131f,-1.44306f,-0.24548f,0.71138f,1.53327f,2.30225f,3.01804f,3.59034f,3.88945f,3.82508f,3.40637f,2.74729f,2.01530f,1.35615f,0.84103f,0.46213f,0.16922f,-0.08321f,-0.30987f,-0.50356f,-0.66827f,-0.84729f,-1.11973f,-1.55925f,-2.17664f,-2.88418f,-3.51211f,-3.87370f,-3.83930f,-3.37449f,-2.52699f,-1.38270f,-0.02562f,1.47393f,3.04430f,4.59297f,6.00644f,7.17616f,8.03598f},
{7.26404f,8.10965f,8.72719f,9.20363f,9.62912f,10.06111f,10.50424f,10.91333f,11.21567f,11.34011f,11.23825f,10.88772f,10.27813f,9.38958f,8.17873f,6.58333f,4.54783f,2.06192f,-0.80497f,-3.89324f,-6.97776f,-9.81797f,-12.20704f,-13.99879f,-15.11266f,-15.52991f,-15.28958f,-14.48074f,-13.22442f,-11.64711f,-9.85865f,-7.94820f,-5.99936f,-4.10802f,-2.38106f,-0.90774f,0.27922f,1.22103f,2.00764f,2.71959f,3.37356f,3.90798f,4.21895f,4.22501f,3.92204f,3.39553f,2.78286f,2.20986f,1.74142f,1.37229f,1.05518f,0.74140f,0.40656f,0.04769f,-0.34062f,-0.78836f,-1.34780f,-2.06152f,-2.91742f,-3.82180f,-4.61460f,-5.12394f,-5.22760f,-4.88549f,-4.13094f,-3.03660f,-1.68184f,-0.14054f,1.51063f,3.17937f,4.75791f,6.14267f,7.26404f},
{6.34227f,7.49980f,8.45427f,9.25999f,9.97710f,10.64486f,11.26504f,11.80143f,12.19363f,12.37738f,12.30115f,11.93159f,11.24603f,10.21813f,8.80747f,6.96409f,4.65257f,1.88967f,-1.22203f,-4.48748f,-7.65190f,-10.46036f,-12.71276f,-14.29025f,-15.15384f,-15.33028f,-14.89618f,-13.96132f,-12.64812f,-11.07016f,-9.31841f,-7.46382f,-5.57411f,-3.73068f,-2.02814f,-0.55067f,0.66167f,1.63144f,2.42842f,3.12502f,3.74960f,4.26821f,4.60649f,4.69831f,4.53154f,4.16345f,3.69621f,3.22841f,2.81353f,2.44841f,2.09234f,1.69868f,1.23732f,0.69634f,0.06726f,-0.66937f,-1.54107f,-2.55884f,-3.68421f,-4.81193f,-5.78656f,-6.44890f,-6.68609f,-6.45751f,-5.78812f,-4.74191f,-3.39558f,-1.82633f,-0.11412f,1.65171f,3.37355f,4.95911f,6.34227f},
{5.34603f,6.80801f,8.10430f,9.25699f,10.29292f,11.22674f,12.05003f,12.72994f,13.21683f,13.45645f,13.40063f,13.01148f,12.25724f,11.10344f,9.50726f,7.42475f,4.83602f,1.78342f,-1.59607f,-5.06954f,-8.35132f,-11.17309f,-13.34331f,-14.77010f,-15.45135f,-15.45050f,-14.87171f,-13.83788f,-12.47064f,-10.87411f,-9.12779f,-7.29256f,-5.42650f,-3.59932f,-1.89257f,-0.38187f,0.88983f,1.92927f,2.78537f,3.51820f,4.16232f,4.70759f,5.10911f,5.31921f,5.32149f,5.14594f,4.85608f,4.51693f,4.16472f,3.79586f,3.37783f,2.87062f,2.24401f,1.48161f,0.57414f,-0.48708f,-1.70528f,-3.05949f,-4.48253f,-5.85376f,-7.01874f,-7.82967f,-8.18534f,-8.05000f,-7.44677f,-6.43620f,-5.09470f,-3.50236f,-1.74074f,0.10559f,1.95098f,3.71728f,5.34602f},
{4.36709f,6.10488f,7.71807f,9.20246f,10.55497f,11.76498f,12.80925f,13.65183f,14.24831f,14.55221f,14.52007f,14.11282f,13.29243f,12.01646f,10.23708f,7.91232f,5.03471f,1.67141f,-2.00440f,-5.71963f,-9.15722f,-12.03748f,-14.17954f,-15.51759f,-16.08076f,-15.96010f,-15.27810f,-14.16492f,-12.74067f,-11.10407f,-9.32963f,-7.47469f,-5.59264f,-3.74422f,-1.99849f,-0.42053f,0.94775f,2.10162f,3.07144f,3.90327f,4.63269f,5.26717f,5.78686f,6.16168f,6.37295f,6.42579f,6.34523f,6.15957f,5.88255f,5.50540f,5.00183f,4.34036f,3.49569f,2.45339f,1.20932f,-0.23035f,-1.84210f,-3.57115f,-5.31961f,-6.94925f,-8.30504f,-9.25096f,-9.70058f,-9.62856f,-9.06263f,-8.06501f,-6.71413f,-5.09269f,-3.28245f,-1.36256f,0.59288f,2.51929f,4.36709f},
{3.48737f,5.45970f,7.34454f,9.11998f,10.76124f,12.23717f,13.50952f,14.53448f,15.26589f,15.65824f,15.66825f,15.25358f,14.36932f,12.96465f,10.98567f,8.39137f,5.18696f,1.46745f,-2.55250f,-6.55480f,-10.19002f,-13.17005f,-15.32853f,-16.62638f,-17.12030f,-16.92228f,-16.16643f,-14.98607f,-13.49940f,-11.80230f,-9.96824f,-8.05483f,-6.11394f,-4.20003f,-2.37140f,-0.68273f,0.82764f,2.14800f,3.29410f,4.29846f,5.19322f,5.99555f,6.70272f,7.29764f,7.75970f,8.07335f,8.22969f,8.22157f,8.03688f,7.65536f,7.05088f,6.19784f,5.07787f,3.68463f,2.02710f,0.13435f,-1.93649f,-4.09162f,-6.19897f,-8.10123f,-9.64329f,-10.70357f,-11.21502f,-11.16885f,-10.60359f,-9.58792f,-8.20440f,-6.53817f,-4.67039f,-2.67498f,-0.61648f,1.45157f,3.48737f},
{2.75808f,4.92150f,7.02575f,9.03975f,10.92660f,12.64250f,14.13788f,15.35986f,16.25497f,16.77081f,16.85591f,16.45736f,15.51755f,13.97287f,11.76046f,8.83973f,5.23237f,1.07075f,-3.37550f,-7.73185f,-11.61289f,-14.72687f,-16.92941f,-18.21294f,-18.66191f,-18.40634f,-17.58827f,-16.34172f,-14.78238f,-13.00400f,-11.08009f,-9.06954f,-7.02398f,-4.99357f,-3.02836f,-1.17413f,0.53514f,2.08423f,3.47831f,4.73777f,5.88765f,6.94645f,7.91880f,8.79384f,9.54832f,10.15131f,10.56789f,10.76100f,10.69226f,10.32337f,9.61907f,8.55160f,7.10615f,5.28689f,3.12374f,0.67999f,-1.94104f,-4.59536f,-7.10950f,-9.30500f,-11.02932f,-12.18080f,-12.71873f,-12.65788f,-12.05373f,-10.98552f,-9.54170f,-7.80971f,-5.86969f,-3.79108f,-1.63131f,0.56380f,2.75808f},
{2.18511f,4.50396f,6.78193f,8.98511f,11.07254f,12.99554f,14.69879f,16.12226f,17.20311f,17.87639f,18.07415f,17.72311f,16.74237f,15.04512f,12.55069f,9.21484f,5.08111f,0.33741f,-4.66447f,-9.46997f,-13.65027f,-16.91840f,-19.16613f,-20.42842f,-20.82260f,-20.49754f,-19.60237f,-18.27083f,-16.61550f,-14.72741f,-12.67917f,-10.52984f,-8.33033f,-6.12736f,-3.96470f,-1.88120f,0.09329f,1.94189f,3.66217f,5.26356f,6.76108f,8.16726f,9.48488f,10.70242f,11.79287f,12.71521f,13.41758f,13.84105f,13.92351f,13.60388f,12.82695f,11.54972f,9.74994f,7.43733f,4.66650f,1.54813f,-1.74846f,-5.00873f,-8.00386f,-10.53041f,-12.44318f,-13.66949f,-14.20444f,-14.09440f,-13.41755f,-12.26697f,-10.73807f,-8.92042f,-6.89286f,-4.72127f,-2.45833f,-0.14526f,2.18511f},
{1.72053f,4.17297f,6.59438f,8.95134f,11.20364f,13.30308f,15.19344f,16.81081f,18.08389f,18.93317f,19.26896f,18.98863f,17.97530f,16.10272f,13.25527f,9.37362f,4.52871f,-1.00461f,-6.74269f,-12.11065f,-16.62809f,-20.03220f,-22.27725f,-23.45977f,-23.73964f,-23.28809f,-22.26206f,-20.79488f,-18.99544f,-16.95096f,-14.73125f,-12.39338f,-9.98585f,-7.55149f,-5.12863f,-2.75055f,-0.44367f,1.77430f,3.89494f,5.91760f,7.84559f,9.68075f,11.41785f,13.03988f,14.51531f,15.79744f,16.82551f,17.52703f,17.82085f,17.62109f,16.84267f,15.41052f,13.27453f,10.43204f,6.95518f,3.01260f,-1.13218f,-5.15905f,-8.75773f,-11.69139f,-13.82848f,-15.13789f,-15.66248f,-15.48890f,-14.72326f,-13.47499f,-11.84717f,-9.93137f,-7.80527f,-5.53214f,-3.16198f,-0.73388f,1.72053f},
{1.25648f,3.83346f,6.38361f,8.87461f,11.26836f,13.51909f,15.57188f,17.36120f,18.80886f,19.82102f,20.28386f,20.05887f,18.98034f,16.86251f,13.53001f,8.89097f,3.05679f,-3.54903f,-10.22329f,-16.21814f,-21.01624f,-24.43081f,-26.52507f,-27.48288f,-27.51630f,-26.82066f,-25.55979f,-23.86524f,-21.84075f,-19.56791f,-17.11151f,-14.52415f,-11.84978f,-9.12619f,-6.38628f,-3.65838f,-0.96593f,1.67288f,4.24497f,6.74115f,9.15377f,11.47351f,13.68563f,15.76654f,17.68097f,19.38009f,20.80043f,21.86327f,22.47451f,22.52518f,21.89433f,20.45753f,18.10673f,14.78776f,10.55570f,5.62879f,0.39675f,-4.65483f,-9.08010f,-12.58457f,-15.05374f,-16.51320f,-17.06846f,-16.85678f,-16.01828f,-14.68187f,-12.95989f,-10.94687f,-8.72027f,-6.34224f,-3.86191f,-1.31827f,1.25648f},
{0.61274f,3.30609f,5.97339f,8.58191f,11.09408f,13.46503f,15.63979f,17.55005f,19.10974f,20.20899f,20.70620f,20.41900f,19.11786f,16.53390f,12.40662f,6.61050f,-0.63393f,-8.60491f,-16.24674f,-22.64559f,-27.36876f,-30.42378f,-32.04157f,-32.50592f,-32.07420f,-30.95517f,-29.31063f,-27.26407f,-24.90971f,-22.32016f,-19.55232f,-16.65182f,-13.65621f,-10.59718f,-7.50200f,-4.39430f,-1.29461f,1.77927f,4.81167f,7.78814f,10.69402f,13.51268f,16.22331f,18.79876f,21.20313f,23.38945f,25.29705f,26.84843f,27.94548f,28.46508f,28.25526f,27.13565f,24.91066f,21.41082f,16.57999f,10.60085f,3.97961f,-2.54106f,-8.24894f,-12.70524f,-15.79057f,-17.60170f,-18.32929f,-18.17960f,-17.33926f,-15.96496f,-14.18379f,-12.09725f,-9.78580f,-7.31305f,-4.72954f,-2.07615f,0.61273f},
{-0.51780f,2.25318f,4.99425f,7.66865f,10.23485f,12.64332f,14.83254f,16.72371f,18.21347f,19.16381f,19.38869f,18.63855f,16.59029f,12.86697f,7.14422f,-0.58466f,-9.65920f,-18.74956f,-26.50752f,-32.23849f,-35.92738f,-37.89259f,-38.51301f,-38.11560f,-36.95302f,-35.21298f,-33.03368f,-30.51738f,-27.74077f,-24.76235f,-21.62771f,-18.37317f,-15.02848f,-11.61858f,-8.16494f,-4.68647f,-1.20023f,2.27799f,5.73306f,9.14986f,12.51243f,15.80303f,19.00093f,22.08101f,25.01199f,27.75429f,30.25706f,32.45424f,34.25895f,35.55571f,36.19006f,35.95632f,34.58787f,31.76497f,27.17577f,20.68735f,12.62891f,3.95837f,-4.05513f,-10.47137f,-14.98139f,-17.73202f,-19.04365f,-19.24250f,-18.60128f,-17.33187f,-15.59484f,-13.51153f,-11.17436f,-8.65479f,-6.00927f,-3.28385f,-0.51781f},
{-2.94630f,-0.27015f,2.35392f,4.87475f,7.23381f,9.35996f,11.16265f,12.52250f,13.27822f,13.20942f,12.01747f,9.31709f,4.67824f,-2.19503f,-11.07895f,-20.88160f,-29.97238f,-37.12710f,-41.99746f,-44.82656f,-46.03905f,-46.03089f,-45.11248f,-43.51276f,-41.39774f,-38.88807f,-36.07244f,-33.01710f,-29.77243f,-26.37748f,-22.86313f,-19.25438f,-15.57188f,-11.83313f,-8.05336f,-4.24613f,-0.42389f,3.40158f,7.21877f,11.01604f,14.78119f,18.50092f,22.16027f,25.74181f,29.22467f,32.58313f,35.78478f,38.78779f,41.53690f,43.95751f,45.94660f,47.35884f,47.98567f,47.52511f,45.54571f,41.47140f,34.68705f,24.97739f,13.30733f,1.91060f,-7.18982f,-13.36551f,-16.99104f,-18.69892f,-19.03825f,-18.41248f,-17.10439f,-15.31181f,-13.17571f,-10.79953f,-8.26212f,-5.62654f,-2.94631f},
{-15.37669f,-14.26728f,-13.44233f,-13.07088f,-13.34672f,-14.49663f,-16.77455f,-20.42235f,-25.56851f,-32.05942f,-39.32137f,-46.45545f,-52.60312f,-57.27376f,-60.37929f,-62.07479f,-62.59922f,-62.18728f,-61.03725f,-59.30634f,-57.11599f,-54.55931f,-51.70786f,-48.61705f,-45.33014f,-41.88134f,-38.29801f,-34.60230f,-30.81233f,-26.94317f,-23.00747f,-19.01601f,-14.97808f,-10.90183f,-6.79450f,-2.66261f,1.48783f,5.65122f,9.82224f,13.99568f,18.16641f,22.32918f,26.47854f,30.60867f,34.71317f,38.78489f,42.81557f,46.79548f,50.71283f,54.55307f,58.29770f,61.92271f,65.39604f,68.67369f,71.69330f,74.36332f,76.54363f,78.00924f,78.37835f,76.96295f,72.45838f,62.44065f,43.87018f,19.37226f,-0.18356f,-11.16707f,-16.48422f,-18.69494f,-19.20397f,-18.76390f,-17.80785f,-16.61220f,-15.37669f},
{-172.49255f,-167.49255f,-162.49255f,-157.49255f,-152.49255f,-147.49255f,-142.49256f,-137.49255f,-132.49255f,-127.49255f,-122.49255f,-117.49255f,-112.49255f,-107.49255f,-102.49255f,-97.49255f,-92.49255f,-87.49255f,-82.49255f,-77.49255f,-72.49256f,-67.49255f,-62.49256f,-57.49255f,-52.49256f,-47.49255f,-42.49255f,-37.49255f,-32.49255f,-27.49256f,-22.49255f,-17.49256f,-12.49255f,-7.49256f,-2.49256f,2.50744f,7.50745f,12.50745f,17.50744f,22.50744f,27.50744f,32.50744f,37.50744f,42.50744f,47.50744f,52.50745f,57.50744f,62.50744f,67.50744f,72.50744f,77.50744f,82.50744f,87.50744f,92.50744f,97.50744f,102.50744f,107.50744f,112.50744f,117.50744f,122.50744f,127.50744f,132.50744f,137.50744f,142.50744f,147.50744f,152.50744f,157.50744f,162.50744f,167.50744f,172.50744f,177.50744f,-177.49256f,-172.49256f}
};

View File

@@ -0,0 +1,72 @@
#!/usr/bin/env python3
'''
generate field tables from IGRF12. Note that this requires python3
'''
import igrf as igrf
import numpy as np
import datetime
from pathlib import Path
from pymavlink.rotmat import Vector3, Matrix3
import math
import argparse
parser = argparse.ArgumentParser(description='generate mag tables')
parser.add_argument('--sampling-res', type=int, default=5, help='sampling resolution, degrees')
parser.add_argument('--check-error', action='store_true', help='check max error')
parser.add_argument('--filename', type=str, default='tables.cpp', help='tables file')
args = parser.parse_args()
if not Path("AP_Declination.h").is_file():
raise OSError("Please run this tool from the AP_Declination directory")
def write_table(f,name, table):
'''write one table'''
f.write("const float AP_Declination::%s[%u][%u] = {\n" %
(name, NUM_LAT, NUM_LON))
for i in range(NUM_LAT):
f.write(" {")
for j in range(NUM_LON):
f.write("%.5ff" % 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")
date = datetime.datetime.now()
SAMPLING_RES = args.sampling_res
SAMPLING_MIN_LAT = -90
SAMPLING_MAX_LAT = 90
SAMPLING_MIN_LON = -180
SAMPLING_MAX_LON = 180
lats = np.arange(SAMPLING_MIN_LAT, SAMPLING_MAX_LAT+SAMPLING_RES, 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))
inclination_table = np.empty((NUM_LAT, NUM_LON))
declination_table = np.empty((NUM_LAT, NUM_LON))
max_error = 0
max_error_pos = None
max_error_field = None
def get_igrf(lat, lon):
'''return field as [declination_deg, inclination_deg, intensity_gauss]'''
mag = igrf.igrf(date, glat=lat, glon=lon, alt_km=0., isv=0, itype=1)
intensity = float(mag.total/1e5)
inclination = float(mag.incl)
declination = float(mag.decl)
return [declination, inclination, intensity]
print("%f" % get_igrf(40.5795,-74.1502)[0])