mirror of https://github.com/ArduPilot/ardupilot
AP_Declination: Fixes ups for pyigrf
This commit is contained in:
parent
67a503d5d8
commit
f06b27e4a3
|
@ -3,7 +3,7 @@
|
|||
generate field tables from IGRF12
|
||||
'''
|
||||
|
||||
import pyigrf12 as igrf
|
||||
import igrf12 as igrf
|
||||
import numpy as np
|
||||
import datetime
|
||||
from pathlib import Path
|
||||
|
@ -54,7 +54,7 @@ if __name__ == '__main__':
|
|||
|
||||
for i,lat in enumerate(lats):
|
||||
for j,lon in enumerate(lons):
|
||||
mag = igrf.igrf(date=date, glat=lat, glon=lon, alt=0., isv=0, itype=1)
|
||||
mag = igrf.igrf(date, glat=lat, glon=lon, alt_km=0., isv=0, itype=1)
|
||||
intensity_table[i][j] = mag.total/1e5
|
||||
inclination_table[i][j] = mag.incl
|
||||
declination_table[i][j] = mag.decl
|
||||
|
|
Loading…
Reference in New Issue