Skip to content
Merged
Show file tree
Hide file tree
Changes from 2 commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
1 change: 0 additions & 1 deletion src/main/fc/settings.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -1168,7 +1168,6 @@ groups:
members:
- name: inav_auto_mag_decl
field: automatic_mag_declination
condition: NAV_AUTO_MAG_DECLINATION
type: bool
- name: inav_gravity_cal_tolerance
field: gravity_calibration_tolerance
Expand Down
63 changes: 63 additions & 0 deletions src/main/navigation/navigation_declination_gen.c
Original file line number Diff line number Diff line change
@@ -0,0 +1,63 @@
/* this file is automatically generated by src/utils/declination.py - DO NOT EDIT! */


/* Updated on 2019-05-16 19:59:45.672184 */


#include <stdint.h>



#if defined(NAV_AUTO_MAG_DECLINATION_PRECISE)
#define SAMPLING_RES 10.00000f
#define SAMPLING_MIN_LON -180.00000f
#define SAMPLING_MAX_LON 180.00000f
#define SAMPLING_MIN_LAT -90.00000f
#define SAMPLING_MAX_LAT 90.00000f

static const float declination_table[19][37] = {
{149.21545f,139.21545f,129.21545f,119.21545f,109.21545f,99.21545f,89.21545f,79.21545f,69.21545f,59.21545f,49.21545f,39.21545f,29.21545f,19.21545f,9.21545f,-0.78455f,-10.78455f,-20.78455f,-30.78455f,-40.78455f,-50.78455f,-60.78455f,-70.78455f,-80.78455f,-90.78455f,-100.78455f,-110.78455f,-120.78455f,-130.78455f,-140.78455f,-150.78455f,-160.78455f,-170.78455f,179.21545f,169.21545f,159.21545f,149.21545f},
{129.49173f,117.24379f,106.10409f,95.92286f,86.51411f,77.69583f,69.30955f,61.22803f,53.35622f,45.62814f,38.00071f,30.44524f,22.93795f,15.45138f,7.94874f,0.38309f,-7.29841f,-15.14665f,-23.20230f,-31.49030f,-40.01947f,-48.78754f,-57.79007f,-67.03110f,-76.53295f,-86.34401f,-96.54357f,-107.24276f,-118.57946f,-130.70159f,-143.72988f,-157.69312f,-172.44642f,172.37735f,157.31228f,142.89420f,129.49173f},
{85.58549f,77.67225f,71.30884f,65.86377f,60.92589f,56.17990f,51.37001f,46.30480f,40.87538f,35.06788f,28.95999f,22.69753f,16.44959f,10.34723f,4.42361f,-1.41547f,-7.36729f,-13.65814f,-20.45428f,-27.80115f,-35.61613f,-43.73164f,-51.96263f,-60.16701f,-68.28139f,-76.33426f,-84.45291f,-92.88710f,-102.08596f,-112.90534f,-127.14324f,-148.72029f,177.01697f,138.42469f,112.13402f,96.22709f,85.58549f},
{47.63660f,46.34868f,44.88668f,43.46724f,42.13334f,40.75578f,39.03991f,36.60567f,33.13133f,28.48297f,22.78165f,16.40811f,9.93011f,3.92458f,-1.26916f,-5.73344f,-9.95561f,-14.59663f,-20.17634f,-26.83800f,-34.30473f,-42.04900f,-49.54378f,-56.41737f,-62.46557f,-67.58445f,-71.67147f,-74.48888f,-75.41488f,-72.72854f,-60.65739f,-20.78150f,26.31817f,42.64478f,47.39885f,48.29568f,47.63660f},
{30.97061f,31.18244f,30.92007f,30.51421f,30.19783f,30.07382f,29.96272f,29.32724f,27.44230f,23.71829f,17.99066f,10.70786f,2.93356f,-4.02123f,-9.25421f,-12.72420f,-15.16719f,-17.68585f,-21.36741f,-26.80526f,-33.62817f,-40.77079f,-47.22749f,-52.37678f,-55.85085f,-57.33789f,-56.38997f,-52.20324f,-43.65581f,-30.23589f,-13.76879f,1.84396f,13.87138f,22.01689f,27.05355f,29.80197f,30.97061f},
{22.35701f,22.87747f,22.95380f,22.77246f,22.50130f,22.37009f,22.48347f,22.51381f,21.59756f,18.63829f,12.92222f,4.75452f,-4.29892f,-12.13023f,-17.44827f,-20.36076f,-21.71093f,-22.23838f,-22.95576f,-25.55066f,-30.56100f,-36.48539f,-41.58017f,-44.82620f,-45.65465f,-43.72977f,-38.84914f,-30.98997f,-21.09926f,-11.31468f,-3.00404f,3.97652f,9.93802f,14.84528f,18.57977f,21.04644f,22.35701f},
{16.83374f,17.31701f,17.52984f,17.52512f,17.27497f,16.89826f,16.64631f,16.52197f,15.82359f,13.20018f,7.50544f,-1.01430f,-10.31063f,-17.86218f,-22.52054f,-24.77956f,-25.51811f,-24.67883f,-22.16922f,-20.17352f,-21.46713f,-25.48482f,-29.63408f,-31.91043f,-31.42054f,-28.23519f,-22.87573f,-15.95318f,-8.88587f,-3.41726f,0.43088f,3.87433f,7.44305f,10.85242f,13.73685f,15.75505f,16.83374f},
{13.16653f,13.42584f,13.56856f,13.64914f,13.49908f,13.04415f,12.54312f,12.17294f,11.33249f,8.62333f,2.85124f,-5.49975f,-14.06214f,-20.49962f,-23.98868f,-24.97282f,-24.13471f,-21.32697f,-16.43179f,-11.33581f,-9.07326f,-10.72561f,-14.43596f,-17.29905f,-17.69300f,-15.77796f,-12.24267f,-7.56947f,-3.00400f,-0.11834f,1.39928f,3.14408f,5.63638f,8.32414f,10.72028f,12.39111f,13.16653f},
{10.90437f,10.88236f,10.81163f,10.86511f,10.80010f,10.39894f,9.91702f,9.49494f,8.41184f,5.36760f,-0.47690f,-8.26124f,-15.66061f,-20.76090f,-22.78986f,-21.89942f,-18.89020f,-14.52921f,-9.53528f,-4.91597f,-1.91353f,-1.76484f,-4.25201f,-7.17489f,-8.55660f,-8.15241f,-6.39303f,-3.54345f,-0.64444f,0.81130f,1.15035f,2.11074f,4.17898f,6.59237f,8.80142f,10.33532f,10.90437f},
{9.69156f,9.50282f,9.23338f,9.25605f,9.28344f,8.98186f,8.56848f,8.04846f,6.56771f,3.06569f,-2.75457f,-9.75616f,-15.91853f,-19.62874f,-20.10653f,-17.62100f,-13.38807f,-8.80249f,-4.83206f,-1.62618f,0.85458f,1.72352f,0.35339f,-2.00271f,-3.58526f,-3.93648f,-3.30170f,-1.78891f,-0.13334f,0.41999f,0.14853f,0.72192f,2.61852f,5.02104f,7.34668f,9.06648f,9.69156f},
{8.99220f,9.02256f,8.80901f,8.93941f,9.15462f,8.99412f,8.49413f,7.54605f,5.38233f,1.29060f,-4.51973f,-10.72800f,-15.61393f,-17.87879f,-17.08037f,-13.87843f,-9.54744f,-5.34026f,-2.15287f,0.11672f,2.02473f,3.04733f,2.31093f,0.47960f,-0.96646f,-1.54925f,-1.53032f,-1.00772f,-0.42112f,-0.63497f,-1.37540f,-1.17754f,0.48492f,2.94585f,5.61932f,7.87900f,8.99220f},
{8.04368f,8.88487f,9.24731f,9.76871f,10.30385f,10.32830f,9.60849f,7.94603f,4.81731f,-0.08975f,-6.10101f,-11.65411f,-15.25677f,-16.15822f,-14.52060f,-11.22653f,-7.24580f,-3.44558f,-0.61333f,1.25309f,2.76805f,3.73177f,3.36695f,1.97948f,0.74967f,0.13075f,-0.18979f,-0.42444f,-0.85420f,-1.93961f,-3.28866f,-3.62225f,-2.35247f,0.08639f,3.11990f,6.05468f,8.04368f},
{6.44887f,8.52898f,10.00772f,11.25814f,12.19628f,12.38325f,11.43950f,9.05774f,4.87180f,-1.07081f,-7.58681f,-12.76972f,-15.34699f,-15.21292f,-13.06213f,-9.80318f,-6.10115f,-2.52848f,0.26062f,2.11110f,3.47313f,4.40612f,4.43031f,3.60979f,2.68625f,2.01876f,1.34276f,0.35243f,-1.18272f,-3.35038f,-5.50704f,-6.45531f,-5.60558f,-3.25332f,0.01287f,3.49652f,6.44887f},
{4.61309f,7.91484f,10.67459f,12.86217f,14.28349f,14.59916f,13.44634f,10.43327f,5.19620f,-1.95110f,-9.25904f,-14.43995f,-16.45824f,-15.72227f,-13.22423f,-9.85034f,-6.14231f,-2.53072f,0.48676f,2.68447f,4.29956f,5.52570f,6.19623f,6.20084f,5.73301f,4.92006f,3.60085f,1.53163f,-1.39438f,-4.87688f,-7.94536f,-9.43097f,-8.85100f,-6.51552f,-3.06017f,0.84306f,4.61309f},
{3.21875f,7.41586f,11.19354f,14.28261f,16.32057f,16.89633f,15.56524f,11.80300f,5.20653f,-3.55470f,-11.97809f,-17.43029f,-19.22616f,-18.17302f,-15.37952f,-11.69571f,-7.65025f,-3.63286f,-0.01295f,2.99661f,5.46716f,7.56207f,9.25413f,10.31810f,10.49165f,9.54146f,7.26006f,3.54973f,-1.33752f,-6.50635f,-10.55663f,-12.38793f,-11.79132f,-9.25449f,-5.49875f,-1.18292f,3.21875f},
{2.52051f,7.33138f,11.79037f,15.58977f,18.29190f,19.30865f,17.85567f,12.95067f,3.98293f,-7.53431f,-17.54806f,-23.19596f,-24.60407f,-23.07402f,-19.77569f,-15.49637f,-10.73649f,-5.85097f,-1.12175f,3.26826f,7.26895f,10.88888f,14.03678f,16.41453f,17.52792f,16.76756f,13.54324f,7.61980f,-0.22282f,-7.89770f,-13.19396f,-15.21847f,-14.33135f,-11.37454f,-7.18383f,-2.40863f,2.52051f},
{2.02983f,7.36989f,12.37081f,16.71056f,19.89761f,21.11515f,18.97400f,11.40232f,-2.70274f,-18.81527f,-29.66002f,-33.88571f,-33.57644f,-30.58814f,-26.04521f,-20.59815f,-14.64262f,-8.44459f,-2.20066f,3.93897f,9.85468f,15.42277f,20.45728f,24.64081f,27.44761f,28.04182f,25.18387f,17.54097f,5.49796f,-6.72811f,-14.58218f,-17.34691f,-16.39748f,-13.14509f,-8.58967f,-3.38880f,2.02983f},
{0.42359f,5.67280f,10.45897f,14.18719f,15.84273f,13.44387f,3.31185f,-17.06908f,-37.86930f,-48.41039f,-50.74957f,-48.66334f,-44.20871f,-38.40471f,-31.78712f,-24.66267f,-17.22360f,-9.60278f,-1.90231f,5.78964f,13.38658f,20.79088f,27.87654f,34.46122f,40.25514f,44.75763f,47.03469f,45.25758f,36.18138f,17.77476f,-1.60905f,-12.11869f,-14.89059f,-13.37813f,-9.65915f,-4.84192f,0.42359f},
{-178.76222f,-168.76222f,-158.76222f,-148.76222f,-138.76222f,-128.76222f,-118.76222f,-108.76222f,-98.76222f,-88.76222f,-78.76222f,-68.76222f,-58.76222f,-48.76222f,-38.76222f,-28.76222f,-18.76222f,-8.76222f,1.23778f,11.23778f,21.23778f,31.23778f,41.23778f,51.23778f,61.23778f,71.23778f,81.23778f,91.23778f,101.23778f,111.23778f,121.23778f,131.23778f,141.23778f,151.23778f,161.23778f,171.23778f,-178.76222f}
};

#else /* !NAV_AUTO_MAG_DECLINATION_PRECISE */
#define SAMPLING_RES 10.00000f
#define SAMPLING_MIN_LON -180.00000f
#define SAMPLING_MAX_LON 180.00000f
#define SAMPLING_MIN_LAT -60.00000f
#define SAMPLING_MAX_LAT 60.00000f

static const int8_t declination_table[13][37] = {
{48,46,45,43,42,41,39,37,33,28,23,16,10,4,-1,-6,-10,-15,-20,-27,-34,-42,-50,-56,-62,-68,-72,-74,-75,-73,-61,-21,26,43,47,48,48},
{31,31,31,31,30,30,30,29,27,24,18,11,3,-4,-9,-13,-15,-18,-21,-27,-34,-41,-47,-52,-56,-57,-56,-52,-44,-30,-14,2,14,22,27,30,31},
{22,23,23,23,23,22,22,23,22,19,13,5,-4,-12,-17,-20,-22,-22,-23,-26,-31,-36,-42,-45,-46,-44,-39,-31,-21,-11,-3,4,10,15,19,21,22},
{17,17,18,18,17,17,17,17,16,13,8,-1,-10,-18,-23,-25,-26,-25,-22,-20,-21,-25,-30,-32,-31,-28,-23,-16,-9,-3,0,4,7,11,14,16,17},
{13,13,14,14,13,13,13,12,11,9,3,-5,-14,-20,-24,-25,-24,-21,-16,-11,-9,-11,-14,-17,-18,-16,-12,-8,-3,0,1,3,6,8,11,12,13},
{11,11,11,11,11,10,10,9,8,5,0,-8,-16,-21,-23,-22,-19,-15,-10,-5,-2,-2,-4,-7,-9,-8,-6,-4,-1,1,1,2,4,7,9,10,11},
{10,10,9,9,9,9,9,8,7,3,-3,-10,-16,-20,-20,-18,-13,-9,-5,-2,1,2,0,-2,-4,-4,-3,-2,0,0,0,1,3,5,7,9,10},
{9,9,9,9,9,9,8,8,5,1,-5,-11,-16,-18,-17,-14,-10,-5,-2,0,2,3,2,0,-1,-2,-2,-1,0,-1,-1,-1,0,3,6,8,9},
{8,9,9,10,10,10,10,8,5,0,-6,-12,-15,-16,-15,-11,-7,-3,-1,1,3,4,3,2,1,0,0,0,-1,-2,-3,-4,-2,0,3,6,8},
{6,9,10,11,12,12,11,9,5,-1,-8,-13,-15,-15,-13,-10,-6,-3,0,2,3,4,4,4,3,2,1,0,-1,-3,-6,-6,-6,-3,0,3,6},
{5,8,11,13,14,15,13,10,5,-2,-9,-14,-16,-16,-13,-10,-6,-3,0,3,4,6,6,6,6,5,4,2,-1,-5,-8,-9,-9,-7,-3,1,5},
{3,7,11,14,16,17,16,12,5,-4,-12,-17,-19,-18,-15,-12,-8,-4,0,3,5,8,9,10,10,10,7,4,-1,-7,-11,-12,-12,-9,-5,-1,3},
{3,7,12,16,18,19,18,13,4,-8,-18,-23,-25,-23,-20,-15,-11,-6,-1,3,7,11,14,16,18,17,14,8,0,-8,-13,-15,-14,-11,-7,-2,3}
};

#endif
28 changes: 1 addition & 27 deletions src/main/navigation/navigation_geo.c
Original file line number Diff line number Diff line change
Expand Up @@ -43,32 +43,7 @@
#include "navigation/navigation.h"
#include "navigation/navigation_private.h"


#if defined(NAV_AUTO_MAG_DECLINATION)
/* Declination calculation code from PX4 project */
/* set this always to the sampling in degrees for the table below */
#define SAMPLING_RES 10.0f
#define SAMPLING_MIN_LAT -60.0f
#define SAMPLING_MAX_LAT 60.0f
#define SAMPLING_MIN_LON -180.0f
#define SAMPLING_MAX_LON 180.0f

static const int8_t declination_table[13][37] = \
{
{ 46, 45, 44, 42, 41, 40, 38, 36, 33, 28, 23, 16, 10, 4, -1, -5, -9, -14, -19, -26, -33, -40, -48, -55, -61, -66, -71, -74, -75, -72, -61, -25, 22, 40, 45, 47, 46 },
{ 30, 30, 30, 30, 29, 29, 29, 29, 27, 24, 18, 11, 3, -3, -9, -12, -15, -17, -21, -26, -32, -39, -45, -51, -55, -57, -56, -53, -44, -31, -14, 0, 13, 21, 26, 29, 30 },
{ 21, 22, 22, 22, 22, 22, 22, 22, 21, 18, 13, 5, -3, -11, -17, -20, -21, -22, -23, -25, -29, -35, -40, -44, -45, -44, -40, -32, -22, -12, -3, 3, 9, 14, 18, 20, 21 },
{ 16, 17, 17, 17, 17, 17, 16, 16, 16, 13, 8, 0, -9, -16, -21, -24, -25, -25, -23, -20, -21, -24, -28, -31, -31, -29, -24, -17, -9, -3, 0, 4, 7, 10, 13, 15, 16 },
{ 12, 13, 13, 13, 13, 13, 12, 12, 11, 9, 3, -4, -12, -19, -23, -24, -24, -22, -17, -12, -9, -10, -13, -17, -18, -16, -13, -8, -3, 0, 1, 3, 6, 8, 10, 12, 12 },
{ 10, 10, 10, 10, 10, 10, 10, 9, 9, 6, 0, -6, -14, -20, -22, -22, -19, -15, -10, -6, -2, -2, -4, -7, -8, -8, -7, -4, 0, 1, 1, 2, 4, 6, 8, 10, 10 },
{ 9, 9, 9, 9, 9, 9, 8, 8, 7, 4, -1, -8, -15, -19, -20, -18, -14, -9, -5, -2, 0, 1, 0, -2, -3, -4, -3, -2, 0, 0, 0, 1, 3, 5, 7, 8, 9 },
{ 8, 8, 8, 9, 9, 9, 8, 8, 6, 2, -3, -9, -15, -18, -17, -14, -10, -6, -2, 0, 1, 2, 2, 0, -1, -1, -2, -1, 0, 0, 0, 0, 1, 3, 5, 7, 8 },
{ 8, 9, 9, 10, 10, 10, 10, 8, 5, 0, -5, -11, -15, -16, -15, -12, -8, -4, -1, 0, 2, 3, 2, 1, 0, 0, 0, 0, 0, -1, -2, -2, -1, 0, 3, 6, 8 },
{ 6, 9, 10, 11, 12, 12, 11, 9, 5, 0, -7, -12, -15, -15, -13, -10, -7, -3, 0, 1, 2, 3, 3, 3, 2, 1, 0, 0, -1, -3, -4, -5, -5, -2, 0, 3, 6 },
{ 5, 8, 11, 13, 15, 15, 14, 11, 5, -1, -9, -14, -17, -16, -14, -11, -7, -3, 0, 1, 3, 4, 5, 5, 5, 4, 3, 1, -1, -4, -7, -8, -8, -6, -2, 1, 5 },
{ 4, 8, 12, 15, 17, 18, 16, 12, 5, -3, -12, -18, -20, -19, -16, -13, -8, -4, -1, 1, 4, 6, 8, 9, 9, 9, 7, 3, -1, -6, -10, -12, -11, -9, -5, 0, 4 },
{ 3, 9, 14, 17, 20, 21, 19, 14, 4, -8, -19, -25, -26, -25, -21, -17, -12, -7, -2, 1, 5, 9, 13, 15, 16, 16, 13, 7, 0, -7, -12, -15, -14, -11, -6, -1, 3 },
};
#include "navigation/navigation_declination_gen.c"

static float get_lookup_table_val(unsigned lat_index, unsigned lon_index)
{
Expand Down Expand Up @@ -131,7 +106,6 @@ float geoCalculateMagDeclination(const gpsLocation_t * llh) // degrees units

return ((lat - min_lat) / SAMPLING_RES) * (declination_max - declination_min) + declination_min;
}
#endif

void geoSetOrigin(gpsOrigin_t *origin, const gpsLocation_t *llh, geoOriginResetMode_e resetMode)
{
Expand Down
13 changes: 6 additions & 7 deletions src/main/navigation/navigation_pos_estimator.c
Original file line number Diff line number Diff line change
Expand Up @@ -209,15 +209,14 @@ void onNewGPSData(void)
isFirstGPSUpdate = true;
}

#if defined(NAV_AUTO_MAG_DECLINATION)
/* Automatic magnetic declination calculation - do this once */
static bool magDeclinationSet = false;
if (positionEstimationConfig()->automatic_mag_declination && !magDeclinationSet) {
imuSetMagneticDeclination(geoCalculateMagDeclination(&newLLH));
magDeclinationSet = true;
if(STATE(GPS_FIX_HOME)){
static bool magDeclinationSet = false;
if (positionEstimationConfig()->automatic_mag_declination && !magDeclinationSet) {
imuSetMagneticDeclination(geoCalculateMagDeclination(&newLLH));
magDeclinationSet = true;
}
}
#endif

/* Process position update if GPS origin is already set, or precision is good enough */
// FIXME: Add HDOP check for acquisition of GPS origin
/* Set GPS origin or reset the origin altitude - keep initial pre-arming altitude at zero */
Expand Down
1 change: 0 additions & 1 deletion src/main/target/ANYFCF7/target.h
Original file line number Diff line number Diff line change
Expand Up @@ -151,7 +151,6 @@
#define SENSORS_SET (SENSOR_ACC|SENSOR_MAG|SENSOR_BARO)

#define USE_NAV
#define NAV_AUTO_MAG_DECLINATION
#define NAV_GPS_GLITCH_DETECTION

#define USE_ADC
Expand Down
1 change: 0 additions & 1 deletion src/main/target/FISHDRONEF4/target.h
Original file line number Diff line number Diff line change
Expand Up @@ -160,7 +160,6 @@

// *************** NAV *****************************
#define USE_NAV
#define NAV_AUTO_MAG_DECLINATION
#define NAV_GPS_GLITCH_DETECTION
#define NAV_MAX_WAYPOINTS 60

Expand Down
3 changes: 2 additions & 1 deletion src/main/target/common.h
Original file line number Diff line number Diff line change
Expand Up @@ -103,6 +103,8 @@
#define BOOTLOG_DESCRIPTIONS

#define NAV_NON_VOLATILE_WAYPOINT_CLI
#define NAV_AUTO_MAG_DECLINATION_PRECISE

#else // FLASH_SIZE < 256
#define LOG_LEVEL_MAXIMUM LOG_LEVEL_ERROR
#endif
Expand All @@ -121,7 +123,6 @@
#define USE_GPS_PROTO_NMEA
#define USE_GPS_PROTO_NAZA
#define USE_GPS_PROTO_MTK
#define NAV_AUTO_MAG_DECLINATION
#define NAV_GPS_GLITCH_DETECTION
#define NAV_NON_VOLATILE_WAYPOINT_STORAGE
#define USE_TELEMETRY_HOTT
Expand Down
133 changes: 133 additions & 0 deletions src/utils/declination.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,133 @@
#!/usr/bin/env python

# Ported from https://github.com/ArduPilot/ardupilot/tree/master/libraries/AP_Declination/generate
# Run this script with python3!
# To install the igrf module, use python3 -m pip install --user igrf12
# Note that it requires a fortran compiler

'''
generate field tables from IGRF12
'''

import collections
import datetime
import pathlib
import sys

import igrf12
import numpy as np

SAMPLING_RES = 10
SAMPLING_MIN_LAT = -90
SAMPLING_MAX_LAT = 90
SAMPLING_MIN_LON = -180
SAMPLING_MAX_LON = 180

# This is used for flash constrained environments. We limit
# the latitude range to [-60, 60], so the values fit in an int8_t
SAMPLING_COMPACT_MIN_LAT = -60
SAMPLING_COMPACT_MAX_LAT = 60

PREPROCESSOR_SYMBOL = 'NAV_AUTO_MAG_DECLINATION_PRECISE'

Query = collections.namedtuple('Query', ['date', 'res', 'min_lat', 'max_lat', 'min_lon', 'max_lon'])
Result = collections.namedtuple('Result', ['query', 'lats', 'lons', 'declination', 'inclination', 'intensity'])

def write_table(f, name, table, compact):
'''write one table'''

if compact:
format_entry = lambda x: '%d' % round(x)
table_type = 'int8_t'
else:
table_type = 'float'
format_entry = lambda x: '%.5ff' % x

num_lat = len(table)
num_lon = len(table[0])

f.write("static const %s %s[%u][%u] = {\n" %
(table_type, name, num_lat, num_lon))
for i in range(num_lat):
f.write(" {")
for j in range(num_lon):
f.write(format_entry(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")

def declination_tables(query):
lats = np.arange(query.min_lat, query.max_lat + query.res, query.res)
lons = np.arange(query.min_lon, query.max_lon + query.res, query.res)

num_lat = lats.size
num_lon = lons.size

intensity = np.empty((num_lat, num_lon))
inclination = np.empty((num_lat, num_lon))
declination = np.empty((num_lat, num_lon))

for i, lat in enumerate(lats):
for j, lon in enumerate(lons):
mag = igrf12.igrf(date, glat=lat, glon=lon, alt_km=0., isv=0, itype=1)
intensity[i][j] = mag.total / 1e5
inclination[i][j] = mag.incl
declination[i][j] = mag.decl

return Result(query=query, lats=lats, lons=lons,
declination=declination, inclination=inclination, intensity=intensity)

def generate_constants(f, query):
f.write('#define SAMPLING_RES\t\t%.5ff\n' % query.res)
f.write('#define SAMPLING_MIN_LON\t%.5ff\n' % query.min_lon)
f.write('#define SAMPLING_MAX_LON\t%.5ff\n' % query.max_lon)
f.write('#define SAMPLING_MIN_LAT\t%.5ff\n' % query.min_lat)
f.write('#define SAMPLING_MAX_LAT\t%.5ff\n' % query.max_lat)
f.write('\n')

def generate_tables(f, query, compact):
result = declination_tables(query)
write_table(f, 'declination_table', result.declination, compact)

# We're not using these tables for now
#if not compact:
# write_table(f, 'inclination_table', result.inclination, False)
# write_table(f, 'intensity_table', result.intensity, False)

def generate_code(f, date):

compact_query = Query(date=date, res=SAMPLING_RES,
min_lat=SAMPLING_COMPACT_MIN_LAT, max_lat=SAMPLING_COMPACT_MAX_LAT,
min_lon=SAMPLING_MIN_LON, max_lon=SAMPLING_MAX_LON)

precise_query = Query(date=date, res=SAMPLING_RES,
min_lat=SAMPLING_MIN_LAT, max_lat=SAMPLING_MAX_LAT,
min_lon=SAMPLING_MIN_LON, max_lon=SAMPLING_MAX_LON)

f.write('/* this file is automatically generated by src/utils/declination.py - DO NOT EDIT! */\n\n\n')
f.write('/* Updated on %s */\n\n\n' % date)
f.write('#include <stdint.h>\n\n')


f.write('\n\n#if defined(%s)\n' % PREPROCESSOR_SYMBOL)
generate_constants(f, precise_query)
generate_tables(f, precise_query, False)
# We're not using these tables for now
# write_table(f, 'inclination_table', inclination_table)
# write_table(f, 'intensity_table', intensity_table)
f.write('#else /* !%s */\n' % PREPROCESSOR_SYMBOL)
generate_constants(f, compact_query)
generate_tables(f, compact_query, True)
f.write('#endif\n')

if __name__ == '__main__':

output = pathlib.PurePath(__file__).parent / '..' / 'main' / 'navigation' / 'navigation_declination_gen.c'
date = datetime.datetime.now()

with open(output, 'w') as f:
generate_code(f, date)