Skip to content

Commit

Permalink
AP_Declination: added generation of field tables
Browse files Browse the repository at this point in the history
we can re-generate with a python script. This also extends the tables
from -90 to +90 latitude
  • Loading branch information
tridge committed Nov 1, 2017
1 parent 316121c commit 95ba9ed
Show file tree
Hide file tree
Showing 4 changed files with 178 additions and 55 deletions.
7 changes: 0 additions & 7 deletions libraries/AP_Declination/AP_Declination.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -34,13 +34,6 @@
*/
bool AP_Declination::get_mag_field_ef(float latitude_deg, float longitude_deg, float &intensity_gauss, float &declination_deg, float &inclination_deg)
{
/* set this always to the sampling in degrees for the table below */
const float SAMPLING_RES = 10.0f;
const float SAMPLING_MIN_LAT = -60.0f;
const float SAMPLING_MAX_LAT = 60.0f;
const float SAMPLING_MIN_LON = -180.0f;
const float SAMPLING_MAX_LON = 180.0f;

bool valid_input_data = true;

/* round down to nearest sampling resolution */
Expand Down
12 changes: 9 additions & 3 deletions libraries/AP_Declination/AP_Declination.h
Original file line number Diff line number Diff line change
Expand Up @@ -22,7 +22,13 @@ class AP_Declination
static float get_declination(float latitude_deg, float longitude_deg);

private:
static const float declination_table[13][37];
static const float inclination_table[13][37];
static const float intensity_table[13][37];
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[19][37];
static const float inclination_table[19][37];
static const float intensity_table[19][37];
};
98 changes: 98 additions & 0 deletions libraries/AP_Declination/generate/generate.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,98 @@
#!/usr/bin/env python
'''
generate field tables from IGRF12
'''

import pyigrf12 as igrf
import numpy as np
import datetime
import os.path
import sys
from math import sqrt, pi, atan2, asin

if not os.path.isfile("AP_Declination.h"):
print("Please run this tool from the AP_Declination directory")
sys.exit(1)

def field_to_angles(x,y,z):
intensity = sqrt(x**2+y**2+z**2)
r2d = 180.0 / pi
declination = r2d * atan2(y, x)
inclination = r2d * asin(z / intensity)
return [intensity, inclination, declination]

isv = 0
date = datetime.datetime.now()
itype = 1
alt = 0.0

lat = -35.362917
lon = 149.165130

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
NUM_LON = 1 + (SAMPLING_MAX_LON - SAMPLING_MIN_LON) / SAMPLING_RES

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 in range(NUM_LAT):
for j in range(NUM_LON):
lat = SAMPLING_MIN_LAT + i*SAMPLING_RES
lon = SAMPLING_MIN_LON + j*SAMPLING_RES
x, y, z, f, d = igrf.gridigrf12(date, isv, itype, alt, lat, lon)
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')
tfile.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"
''')

tfile.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))

def write_table(name, table):
'''write one table'''
tfile.write("const float AP_Declination::%s[%u][%u] = {\n" % (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

0 comments on commit 95ba9ed

Please sign in to comment.