generate.py 2.4 KB

1234567891011121314151617181920212223242526272829303132333435363738394041424344454647484950515253545556575859606162636465666768697071727374757677787980818283848586
  1. #!/usr/bin/env python
  2. '''
  3. generate field tables from IGRF12
  4. '''
  5. import igrf12 as igrf
  6. import numpy as np
  7. import datetime
  8. from pathlib import Path
  9. if not Path("AP_Declination.h").is_file():
  10. raise OSError("Please run this tool from the AP_Declination directory")
  11. def write_table(f,name, table):
  12. '''write one table'''
  13. f.write("const float AP_Declination::%s[%u][%u] = {\n" %
  14. (name, NUM_LAT, NUM_LON))
  15. for i in range(NUM_LAT):
  16. f.write(" {")
  17. for j in range(NUM_LON):
  18. f.write("%.5ff" % table[i][j])
  19. if j != NUM_LON-1:
  20. f.write(",")
  21. f.write("}")
  22. if i != NUM_LAT-1:
  23. f.write(",")
  24. f.write("\n")
  25. f.write("};\n\n")
  26. if __name__ == '__main__':
  27. date = datetime.datetime.now()
  28. # date = datetime.date(2018,2,20)
  29. SAMPLING_RES = 10
  30. SAMPLING_MIN_LAT = -90
  31. SAMPLING_MAX_LAT = 90
  32. SAMPLING_MIN_LON = -180
  33. SAMPLING_MAX_LON = 180
  34. lats = np.arange(SAMPLING_MIN_LAT, SAMPLING_MAX_LAT+SAMPLING_RES, SAMPLING_RES)
  35. lons = np.arange(SAMPLING_MIN_LON, SAMPLING_MAX_LON+SAMPLING_RES, SAMPLING_RES)
  36. NUM_LAT = lats.size
  37. NUM_LON = lons.size
  38. intensity_table = np.empty((NUM_LAT, NUM_LON))
  39. inclination_table = np.empty((NUM_LAT, NUM_LON))
  40. declination_table = np.empty((NUM_LAT, NUM_LON))
  41. for i,lat in enumerate(lats):
  42. for j,lon in enumerate(lons):
  43. mag = igrf.igrf(date, glat=lat, glon=lon, alt_km=0., isv=0, itype=1)
  44. intensity_table[i][j] = mag.total/1e5
  45. inclination_table[i][j] = mag.incl
  46. declination_table[i][j] = mag.decl
  47. with open("tables.cpp", 'w') as f:
  48. f.write('''// this is an auto-generated file from the IGRF tables. Do not edit
  49. // To re-generate run generate/generate.py
  50. #include "AP_Declination.h"
  51. ''')
  52. f.write('''const float AP_Declination::SAMPLING_RES = %u;
  53. const float AP_Declination::SAMPLING_MIN_LAT = %u;
  54. const float AP_Declination::SAMPLING_MAX_LAT = %u;
  55. const float AP_Declination::SAMPLING_MIN_LON = %u;
  56. const float AP_Declination::SAMPLING_MAX_LON = %u;
  57. ''' % (SAMPLING_RES,
  58. SAMPLING_MIN_LAT,
  59. SAMPLING_MAX_LAT,
  60. SAMPLING_MIN_LON,
  61. SAMPLING_MAX_LON))
  62. write_table(f,'declination_table', declination_table)
  63. write_table(f,'inclination_table', inclination_table)
  64. write_table(f,'intensity_table', intensity_table)