API: Structs
The following is a full listing of the custom structs within the package.
Magnetic Anomaly Maps
MagNav.Map — TypeMap{T2 <: AbstractFloat}Abstract type Map for a magnetic anomaly map.
MagNav.MapS — TypeMapS{T2 <: AbstractFloat} <: Map{T2}Scalar magnetic anomaly map struct. Subtype of Map.
| Field | Type | Description |
|---|---|---|
info | String | map information |
map | Matrix{T2} | ny x nx scalar magnetic anomaly map [nT] |
xx | Vector{T2} | nx map x-direction (longitude) coordinates [rad] |
yy | Vector{T2} | ny map y-direction (latitude) coordinates [rad] |
alt | T2 | map altitude [m] |
mask | BitMatrix | ny x nx mask for valid (not filled-in) map data |
MagNav.MapSd — TypeMapSd{T2 <: AbstractFloat} <: Map{T2}Scalar magnetic anomaly map struct used to store an additional altitude map for drape maps. Subtype of Map.
| Field | Type | Description |
|---|---|---|
info | String | map information |
map | Matrix{T2} | ny x nx scalar magnetic anomaly map [nT] |
xx | Vector{T2} | nx map x-direction (longitude) coordinates [rad] |
yy | Vector{T2} | ny map y-direction (latitude) coordinates [rad] |
alt | Matrix{T2} | ny x nx altitude map [m] |
mask | BitMatrix | ny x nx mask for valid (not filled-in) map data |
MagNav.MapS3D — TypeMapS3D{T2 <: AbstractFloat} <: Map{T2}3D (multi-level) scalar magnetic anomaly map struct. Subtype of Map.
| Field | Type | Description |
|---|---|---|
info | String | map information |
map | Array{T2,3} | ny x nx x nz 3D (multi-level) scalar magnetic anomaly map [nT] |
xx | Vector{T2} | nx map x-direction (longitude) coordinates [rad] |
yy | Vector{T2} | ny map y-direction (latitude) coordinates [rad] |
alt | Vector{T2} | nz map altitude levels [m] |
mask | BitArray{3} | ny x nx x nz mask for valid (not filled-in) map data |
MagNav.MapV — TypeMapV{T2 <: AbstractFloat} <: Map{T2}Vector magnetic anomaly map struct. Subtype of Map.
| Field | Type | Description |
|---|---|---|
info | String | map information |
mapX | Matrix{T2} | ny x nx x-direction magnetic anomaly map [nT] |
mapY | Matrix{T2} | ny x nx y-direction magnetic anomaly map [nT] |
mapZ | Matrix{T2} | ny x nx z-direction magnetic anomaly map [nT] |
xx | Vector{T2} | nx map x-direction (longitude) coordinates [rad] |
yy | Vector{T2} | ny map y-direction (latitude) coordinates [rad] |
alt | T2 | map altitude [m] |
mask | BitMatrix | ny x nx mask for valid (not filled-in) map data |
MagNav.Map_Cache — TypeMap_CacheMap cache struct, mutable.
| Field | Type | Description |
|---|---|---|
maps | Vector{MapS{Float64}} | vector of MapS scalar magnetic anomaly map structs |
map_sort_ind | Vector{Int64} | maps indices sorted by altitude |
fallback | MapS{Float64} | fallback MapS scalar magnetic anomaly map struct |
map_cache | Dict | maps cache of scalar map interpolation functions (f(lat,lon)) at multiple altitudes |
fallback_cache | Dict | fallback cache of scalar map interpolation functions (f(lat,lon)) at multiple altitudes |
dz | Real | step size between map altitude levels [m] |
Vector Magnetometer
MagNav.MagV — TypeMagV{T2 <: AbstractFloat}Vector magnetometer measurement struct.
| Field | Type | Description |
|---|---|---|
x | Vector{T2} | x-direction magnetic field [nT] |
y | Vector{T2} | y-direction magnetic field [nT] |
z | Vector{T2} | z-direction magnetic field [nT] |
t | Vector{T2} | total magnetic field [nT] |
Flight Paths
MagNav.Path — TypePath{T1 <: Signed, T2 <: AbstractFloat} <: Path{T1, T2}Abstract type Path for a flight path.
MagNav.Traj — TypeTraj{T1 <: Signed, T2 <: AbstractFloat}Trajectory struct, i.e., GPS or other truth flight data. Subtype of Path.
| Field | Type | Description |
|---|---|---|
N | T1 | number of samples (instances) |
dt | T2 | measurement time step [s] |
tt | Vector{T2} | time [s] |
lat | Vector{T2} | latitude [rad] |
lon | Vector{T2} | longitude [rad] |
alt | Vector{T2} | altitude [m] |
vn | Vector{T2} | north velocity [m/s] |
ve | Vector{T2} | east velocity [m/s] |
vd | Vector{T2} | down velocity [m/s] |
fn | Vector{T2} | north specific force [m/s] |
fe | Vector{T2} | east specific force [m/s] |
fd | Vector{T2} | down specific force [m/s] |
Cnb | Array{T2,3} | 3 x 3 x N direction cosine matrix (body to navigation) [-] |
MagNav.INS — TypeINS{T1 <: Signed, T2 <: AbstractFloat} <: Path{T1, T2}Inertial navigation system (INS) struct. Subtype of Path.
| Field | Type | Description |
|---|---|---|
N | T1 | number of samples (instances) |
dt | T2 | measurement time step [s] |
tt | Vector{T2} | time [s] |
lat | Vector{T2} | latitude [rad] |
lon | Vector{T2} | longitude [rad] |
alt | Vector{T2} | altitude [m] |
vn | Vector{T2} | north velocity [m/s] |
ve | Vector{T2} | east velocity [m/s] |
vd | Vector{T2} | down velocity [m/s] |
fn | Vector{T2} | north specific force [m/s] |
fe | Vector{T2} | east specific force [m/s] |
fd | Vector{T2} | down specific force [m/s] |
Cnb | Array{T2,3} | 3 x 3 x N direction cosine matrix (body to navigation) [-] |
P | Array{T2,3} | 17 x 17 x N covariance matrix, only relevant for simulated data, otherwise zeros [-] |
Flight Data
MagNav.XYZ — TypeXYZ{T1 <: Signed, T2 <: AbstractFloat}Abstract type XYZ for flight data. Simplest subtype is XYZ0.
MagNav.XYZ0 — TypeXYZ0{T1 <: Signed, T2 <: AbstractFloat} <: XYZ{T1, T2}Subtype of XYZ containing the minimum dataset required for MagNav.
| Field | Type | Description |
|---|---|---|
info | String | dataset information |
traj | Traj{T1,T2} | trajectory struct |
ins | INS{T1,T2} | inertial navigation system struct |
flux_a | MagV{T2} | Flux A vector magnetometer measurement struct |
flight | Vector{T2} | flight number(s) |
line | Vector{T2} | line number(s), i.e., segments within flight |
year | Vector{T2} | year |
doy | Vector{T2} | day of year |
diurnal | Vector{T2} | measured diurnal, i.e., temporal variations or space weather effects [nT] |
igrf | Vector{T2} | International Geomagnetic Reference Field (IGRF), i.e., core field [nT] |
mag_1_c | Vector{T2} | Mag 1 compensated (clean) scalar magnetometer measurements [nT] |
mag_1_uc | Vector{T2} | Mag 1 uncompensated (corrupted) scalar magnetometer measurements [nT] |
MagNav.XYZ1 — TypeXYZ1{T1 <: Signed, T2 <: AbstractFloat} <: XYZ{T1, T2}Subtype of XYZ containing a flexible dataset for future use. NaNs may be used in place of any unused fields (e.g., aux_3) when creating struct.
| Field | Type | Description |
|---|---|---|
info | String | dataset information |
traj | Traj{T1,T2} | trajectory struct |
ins | INS{T1,T2} | inertial navigation system struct |
flux_a | MagV{T2} | Flux A vector magnetometer measurement struct |
flux_b | MagV{T2} | Flux B vector magnetometer measurement struct |
flight | Vector{T2} | flight number(s) |
line | Vector{T2} | line number(s), i.e., segments within flight |
year | Vector{T2} | year |
doy | Vector{T2} | day of year |
diurnal | Vector{T2} | measured diurnal, i.e., temporal variations or space weather effects [nT] |
igrf | Vector{T2} | International Geomagnetic Reference Field (IGRF), i.e., core field [nT] |
mag_1_c | Vector{T2} | Mag 1 compensated (clean) scalar magnetometer measurements [nT] |
mag_2_c | Vector{T2} | Mag 2 compensated (clean) scalar magnetometer measurements [nT] |
mag_3_c | Vector{T2} | Mag 3 compensated (clean) scalar magnetometer measurements [nT] |
mag_1_uc | Vector{T2} | Mag 1 uncompensated (corrupted) scalar magnetometer measurements [nT] |
mag_2_uc | Vector{T2} | Mag 2 uncompensated (corrupted) scalar magnetometer measurements [nT] |
mag_3_uc | Vector{T2} | Mag 3 uncompensated (corrupted) scalar magnetometer measurements [nT] |
aux_1 | Vector{T2} | flexible-use auxiliary data 1 |
aux_2 | Vector{T2} | flexible-use auxiliary data 2 |
aux_3 | Vector{T2} | flexible-use auxiliary data 3 |
MagNav.XYZ20 — TypeXYZ20{T1 <: Signed, T2 <: AbstractFloat} <: XYZ{T1, T2}Subtype of XYZ for 2020 SGL datasets.
| Field | Type | Description |
|---|---|---|
info | String | dataset information |
traj | Traj{T1,T2} | trajectory struct |
ins | INS{T1,T2} | inertial navigation system struct |
flux_a | MagV{T2} | Flux A vector magnetometer measurement struct |
flux_b | MagV{T2} | Flux B vector magnetometer measurement struct |
flux_c | MagV{T2} | Flux C vector magnetometer measurement struct |
flux_d | MagV{T2} | Flux D vector magnetometer measurement struct |
flight | Vector{T2} | flight number(s) |
line | Vector{T2} | line number(s), i.e., segments within flight |
year | Vector{T2} | year |
doy | Vector{T2} | day of year |
utm_x | Vector{T2} | x-coordinate, WGS-84 UTM zone 18N [m] |
utm_y | Vector{T2} | y-coordinate, WGS-84 UTM zone 18N [m] |
utm_z | Vector{T2} | z-coordinate, GPS altitude above WGS-84 ellipsoid [m] |
msl | Vector{T2} | z-coordinate, GPS altitude above EGM2008 Geoid [m] |
baro | Vector{T2} | barometric altimeter [m] |
diurnal | Vector{T2} | measured diurnal, i.e., temporal variations or space weather effects [nT] |
igrf | Vector{T2} | International Geomagnetic Reference Field (IGRF), i.e., core field [nT] |
mag_1_c | Vector{T2} | Mag 1 compensated (clean) scalar magnetometer measurements [nT] |
mag_1_lag | Vector{T2} | Mag 1 lag-corrected scalar magnetometer measurements [nT] |
mag_1_dc | Vector{T2} | Mag 1 diurnal-corrected scalar magnetometer measurements [nT] |
mag_1_igrf | Vector{T2} | Mag 1 IGRF & diurnal-corrected scalar magnetometer measurements [nT] |
mag_1_uc | Vector{T2} | Mag 1 uncompensated (corrupted) scalar magnetometer measurements [nT] |
mag_2_uc | Vector{T2} | Mag 2 uncompensated (corrupted) scalar magnetometer measurements [nT] |
mag_3_uc | Vector{T2} | Mag 3 uncompensated (corrupted) scalar magnetometer measurements [nT] |
mag_4_uc | Vector{T2} | Mag 4 uncompensated (corrupted) scalar magnetometer measurements [nT] |
mag_5_uc | Vector{T2} | Mag 5 uncompensated (corrupted) scalar magnetometer measurements [nT] |
mag_6_uc | Vector{T2} | Mag 6 uncompensated (corrupted) scalar magnetometer measurements [nT] |
ogs_mag | Vector{T2} | OGS survey diurnal-corrected, levelled, magnetic field [nT] |
ogs_alt | Vector{T2} | OGS survey, GPS altitude (WGS-84) [m] |
ins_wander | Vector{T2} | INS-computed wander angle (ccw from north) [rad] |
ins_roll | Vector{T2} | INS-computed aircraft roll [deg] |
ins_pitch | Vector{T2} | INS-computed aircraft pitch [deg] |
ins_yaw | Vector{T2} | INS-computed aircraft yaw [deg] |
roll_rate | Vector{T2} | avionics-computed roll rate [deg/s] |
pitch_rate | Vector{T2} | avionics-computed pitch rate [deg/s] |
yaw_rate | Vector{T2} | avionics-computed yaw rate [deg/s] |
ins_acc_x | Vector{T2} | INS x-acceleration [m/s^2] |
ins_acc_y | Vector{T2} | INS y-acceleration [m/s^2] |
ins_acc_z | Vector{T2} | INS z-acceleration [m/s^2] |
lgtl_acc | Vector{T2} | avionics-computed longitudinal (forward) acceleration [g] |
ltrl_acc | Vector{T2} | avionics-computed lateral (starboard) acceleration [g] |
nrml_acc | Vector{T2} | avionics-computed normal (vertical) acceleration [g] |
pitot_p | Vector{T2} | avionics-computed pitot pressure [kPa] |
static_p | Vector{T2} | avionics-computed static pressure [kPa] |
total_p | Vector{T2} | avionics-computed total pressure [kPa] |
cur_com_1 | Vector{T2} | current sensor: aircraft radio 1 [A] |
cur_ac_hi | Vector{T2} | current sensor: air conditioner fan high [A] |
cur_ac_lo | Vector{T2} | current sensor: air conditioner fan low [A] |
cur_tank | Vector{T2} | current sensor: cabin fuel pump [A] |
cur_flap | Vector{T2} | current sensor: flap motor [A] |
cur_strb | Vector{T2} | current sensor: strobe lights [A] |
cur_srvo_o | Vector{T2} | current sensor: INS outer servo [A] |
cur_srvo_m | Vector{T2} | current sensor: INS middle servo [A] |
cur_srvo_i | Vector{T2} | current sensor: INS inner servo [A] |
cur_heat | Vector{T2} | current sensor: INS heater [A] |
cur_acpwr | Vector{T2} | current sensor: aircraft power [A] |
cur_outpwr | Vector{T2} | current sensor: system output power [A] |
cur_bat_1 | Vector{T2} | current sensor: battery 1 [A] |
cur_bat_2 | Vector{T2} | current sensor: battery 2 [A] |
vol_acpwr | Vector{T2} | voltage sensor: aircraft power [V] |
vol_outpwr | Vector{T2} | voltage sensor: system output power [V] |
vol_bat_1 | Vector{T2} | voltage sensor: battery 1 [V] |
vol_bat_2 | Vector{T2} | voltage sensor: battery 2 [V] |
vol_res_p | Vector{T2} | voltage sensor: resolver board (+) [V] |
vol_res_n | Vector{T2} | voltage sensor: resolver board (-) [V] |
vol_back_p | Vector{T2} | voltage sensor: backplane (+) [V] |
vol_back_n | Vector{T2} | voltage sensor: backplane (-) [V] |
vol_gyro_1 | Vector{T2} | voltage sensor: gyroscope 1 [V] |
vol_gyro_2 | Vector{T2} | voltage sensor: gyroscope 2 [V] |
vol_acc_p | Vector{T2} | voltage sensor: INS accelerometers (+) [V] |
vol_acc_n | Vector{T2} | voltage sensor: INS accelerometers (-) [V] |
vol_block | Vector{T2} | voltage sensor: block [V] |
vol_back | Vector{T2} | voltage sensor: backplane [V] |
vol_srvo | Vector{T2} | voltage sensor: servos [V] |
vol_cabt | Vector{T2} | voltage sensor: cabinet [V] |
vol_fan | Vector{T2} | voltage sensor: cooling fan [V] |
aux_1 | Vector{T2} | flexible-use auxiliary data 1 |
aux_2 | Vector{T2} | flexible-use auxiliary data 2 |
aux_3 | Vector{T2} | flexible-use auxiliary data 3 |
MagNav.XYZ21 — TypeXYZ21{T1 <: Signed, T2 <: AbstractFloat} <: XYZ{T1, T2}Subtype of XYZ for 2021 SGL datasets.
| Field | Type | Description |
|---|---|---|
info | String | dataset information |
traj | Traj{T1,T2} | trajectory struct |
ins | INS{T1,T2} | inertial navigation system struct |
flux_a | MagV{T2} | Flux A vector magnetometer measurement struct |
flux_b | MagV{T2} | Flux B vector magnetometer measurement struct |
flux_c | MagV{T2} | Flux C vector magnetometer measurement struct |
flux_d | MagV{T2} | Flux D vector magnetometer measurement struct |
flight | Vector{T2} | flight number(s) |
line | Vector{T2} | line number(s), i.e., segments within flight |
year | Vector{T2} | year |
doy | Vector{T2} | day of year |
utm_x | Vector{T2} | x-coordinate, WGS-84 UTM zone 18N [m] |
utm_y | Vector{T2} | y-coordinate, WGS-84 UTM zone 18N [m] |
utm_z | Vector{T2} | z-coordinate, GPS altitude above WGS-84 ellipsoid [m] |
msl | Vector{T2} | z-coordinate, GPS altitude above EGM2008 Geoid [m] |
baro | Vector{T2} | barometric altimeter [m] |
diurnal | Vector{T2} | measured diurnal, i.e., temporal variations or space weather effects [nT] |
igrf | Vector{T2} | International Geomagnetic Reference Field (IGRF), i.e., core field [nT] |
mag_1_c | Vector{T2} | Mag 1 compensated (clean) scalar magnetometer measurements [nT] |
mag_1_uc | Vector{T2} | Mag 1 uncompensated (corrupted) scalar magnetometer measurements [nT] |
mag_2_uc | Vector{T2} | Mag 2 uncompensated (corrupted) scalar magnetometer measurements [nT] |
mag_3_uc | Vector{T2} | Mag 3 uncompensated (corrupted) scalar magnetometer measurements [nT] |
mag_4_uc | Vector{T2} | Mag 4 uncompensated (corrupted) scalar magnetometer measurements [nT] |
mag_5_uc | Vector{T2} | Mag 5 uncompensated (corrupted) scalar magnetometer measurements [nT] |
cur_com_1 | Vector{T2} | current sensor: aircraft radio 1 [A] |
cur_ac_hi | Vector{T2} | current sensor: air conditioner fan high [A] |
cur_ac_lo | Vector{T2} | current sensor: air conditioner fan low [A] |
cur_tank | Vector{T2} | current sensor: cabin fuel pump [A] |
cur_flap | Vector{T2} | current sensor: flap motor [A] |
cur_strb | Vector{T2} | current sensor: strobe lights [A] |
vol_block | Vector{T2} | voltage sensor: block [V] |
vol_back | Vector{T2} | voltage sensor: backplane [V] |
vol_cabt | Vector{T2} | voltage sensor: cabinet [V] |
vol_fan | Vector{T2} | voltage sensor: cooling fan [V] |
aux_1 | Vector{T2} | flexible-use auxiliary data 1 |
aux_2 | Vector{T2} | flexible-use auxiliary data 2 |
aux_3 | Vector{T2} | flexible-use auxiliary data 3 |
Output Wrappers
MagNav.FILTres — TypeFILTres{T2 <: AbstractFloat}Filter results struct.
| Field | Type | Description |
|---|---|---|
x | Matrix{T2} | filtered states, i.e., E(xt y1,..,y_t) |
P | Array{T2,3} | non-linear covariance matrix |
r | Matrix{T2} | measurement residuals [nT] |
c | Bool | if true, filter converged |
MagNav.CRLBout — TypeCRLBout{T2 <: AbstractFloat}Cramér–Rao lower bound extracted output struct.
| Field | Type | Description |
|---|---|---|
lat_std | Vector{T2} | latitude 1-σ [rad] |
lon_std | Vector{T2} | longitude 1-σ [rad] |
alt_std | Vector{T2} | altitude 1-σ [m] |
vn_std | Vector{T2} | north velocity 1-σ [m/s] |
ve_std | Vector{T2} | east velocity 1-σ [m/s] |
vd_std | Vector{T2} | down velocity 1-σ [m/s] |
tn_std | Vector{T2} | north tilt (attitude) 1-σ [rad] |
te_std | Vector{T2} | east tilt (attitude) 1-σ [rad] |
td_std | Vector{T2} | down tilt (attitude) 1-σ [rad] |
fogm_std | Vector{T2} | FOGM 1-σ [nT] |
n_std | Vector{T2} | northing 1-σ [m] |
e_std | Vector{T2} | easting 1-σ [m] |
MagNav.INSout — TypeINSout{T2 <: AbstractFloat}Inertial navigation system extracted output struct.
| Field | Type | Description |
|---|---|---|
lat_std | Vector{T2} | latitude 1-σ [rad] |
lon_std | Vector{T2} | longitude 1-σ [rad] |
alt_std | Vector{T2} | altitude 1-σ [m] |
n_std | Vector{T2} | northing 1-σ [m] |
e_std | Vector{T2} | easting 1-σ [m] |
lat_err | Vector{T2} | latitude error [rad] |
lon_err | Vector{T2} | longitude error [rad] |
alt_err | Vector{T2} | altitude error [m] |
n_err | Vector{T2} | northing error [m] |
e_err | Vector{T2} | easting error [m] |
MagNav.FILTout — TypeFILTout{T1 <: Signed, T2 <: AbstractFloat} <: Path{T1, T2}Filter extracted output struct. Subtype of Path.
| Field | Type | Description |
|---|---|---|
N | T1 | number of samples (instances) |
dt | T2 | measurement time step [s] |
tt | Vector{T2} | time [s] |
lat | Vector{T2} | latitude [rad] |
lon | Vector{T2} | longitude [rad] |
alt | Vector{T2} | altitude [m] |
vn | Vector{T2} | north velocity [m/s] |
ve | Vector{T2} | east velocity [m/s] |
vd | Vector{T2} | down velocity [m/s] |
tn | Vector{T2} | north tilt (attitude) [rad] |
te | Vector{T2} | east tilt (attitude) [rad] |
td | Vector{T2} | down tilt (attitude) [rad] |
ha | Vector{T2} | barometer aiding altitude [m] |
ah | Vector{T2} | barometer aiding vertical acceleration [m/s^2] |
ax | Vector{T2} | x accelerometer [m/s^2] |
ay | Vector{T2} | y accelerometer [m/s^2] |
az | Vector{T2} | z accelerometer [m/s^2] |
gx | Vector{T2} | x gyroscope [rad/s] |
gy | Vector{T2} | y gyroscope [rad/s] |
gz | Vector{T2} | z gyroscope [rad/s] |
fogm | Vector{T2} | FOGM catch-all [nT] |
lat_std | Vector{T2} | latitude 1-σ [rad] |
lon_std | Vector{T2} | longitude 1-σ [rad] |
alt_std | Vector{T2} | altitude 1-σ [m] |
vn_std | Vector{T2} | north velocity 1-σ [m/s] |
ve_std | Vector{T2} | east velocity 1-σ [m/s] |
vd_std | Vector{T2} | down velocity 1-σ [m/s] |
tn_std | Vector{T2} | north tilt (attitude) 1-σ [rad] |
te_std | Vector{T2} | east tilt (attitude) 1-σ [rad] |
td_std | Vector{T2} | down tilt (attitude) 1-σ [rad] |
ha_std | Vector{T2} | barometer aiding altitude 1-σ [m] |
ah_std | Vector{T2} | barometer aiding vertical acceleration 1-σ [m/s^2] |
ax_std | Vector{T2} | x accelerometer 1-σ [m/s^2] |
ay_std | Vector{T2} | y accelerometer 1-σ [m/s^2] |
az_std | Vector{T2} | z accelerometer 1-σ [m/s^2] |
gx_std | Vector{T2} | x gyroscope 1-σ [rad/s] |
gy_std | Vector{T2} | y gyroscope 1-σ [rad/s] |
gz_std | Vector{T2} | z gyroscope 1-σ [rad/s] |
fogm_std | Vector{T2} | FOGM catch-all 1-σ [nT] |
n_std | Vector{T2} | northing 1-σ [m] |
e_std | Vector{T2} | easting 1-σ [m] |
lat_err | Vector{T2} | latitude error [rad] |
lon_err | Vector{T2} | longitude error [rad] |
alt_err | Vector{T2} | altitude error [m] |
vn_err | Vector{T2} | north velocity error [m/s] |
ve_err | Vector{T2} | east velocity error [m/s] |
vd_err | Vector{T2} | down velocity error [m/s] |
tn_err | Vector{T2} | north tilt (attitude) error [rad] |
te_err | Vector{T2} | east tilt (attitude) error [rad] |
td_err | Vector{T2} | down tilt (attitude) error [rad] |
n_err | Vector{T2} | northing error [m] |
e_err | Vector{T2} | easting error [m] |
Real-time EKF
MagNav.EKF_RT — TypeEKF_RTReal-time (RT) extended Kalman filter (EKF) struct, mutable.
| Field | Type | Description |
|---|---|---|
P | Matrix{Float64} | non-linear covariance matrix |
Qd | Matrix{Float64} | discrete time process/system noise matrix |
R | Float64 | measurement (white) noise variance |
baro_tau | Float64 | barometer time constant [s] |
acc_tau | Float64 | accelerometer time constant [s] |
gyro_tau | Float64 | gyroscope time constant [s] |
fogm_tau | Float64 | FOGM catch-all time constant [s] |
date | Float64 | measurement date (decimal year) for IGRF [yr] |
core | Bool | if true, include core magnetic field in measurement |
nx | Int64 | total state dimension |
ny | Int64 | measurement dimension |
t | Float64 | time [s] |
x | Vector{Float64} | filtered states, i.e., E(xt y1,..,y_t) |
r | Vector{Float64} | measurement residual |
Compensation Parameters
MagNav.CompParams — TypeCompParamsAbstract type CompParams for aeromagnetic compensation parameters.
MagNav.LinCompParams — TypeLinCompParams <: CompParamsLinear aeromagnetic compensation parameters struct. Subtype of CompParams.
To see default parameters, type LinCompParams().
General Parameters:
| Parameter | Type | Description |
|---|---|---|
version | VersionNumber | MagNav.jl version used to generate this struct |
features_setup | Vector{Symbol} | vector of features to include, only used for model_type = :elasticnet, :plsr |
features_no_norm | Vector{Symbol} | vector of features to not normalize, only used for model_type = :elasticnet, :plsr |
model_type | Symbol | aeromagnetic compensation model type (see below) |
y_type | Symbol | y target type (see below) |
use_mag | Symbol | uncompensated scalar magnetometer to use for y target vector {:mag_1_uc, etc.}, only used for y_type = :c, :d, :e |
use_vec | Symbol | vector magnetometer (fluxgate) to use for "external" Tolles-Lawson A matrix {:flux_a, etc.}, only used for model_type = :TL, :mod_TL, :map_TL |
data_norms | Tuple | length-4 tuple of data normalizations, (A_bias,A_scale,y_bias,y_scale) for model_type = :TL, :mod_TL, :map_TL or (x_bias,x_scale,y_bias,y_scale) for model_type = :elasticnet, :plsr |
model | Tuple | linear model coefficients |
terms | Vector{Symbol} | Tolles-Lawson terms to use for Tolles-Lawson A matrix (or matrices) within x data matrix {:permanent,:induced,:eddy}, only used for model_type = :elasticnet, :plsr |
terms_A | Vector{Symbol} | Tolles-Lawson terms to use for "external" Tolles-Lawson A matrix {:permanent,:induced,:eddy,:bias}, only used for model_type = :TL, :mod_TL, :map_TL |
sub_diurnal | Bool | if true, subtract diurnal from scalar magnetometer measurements |
sub_igrf | Bool | if true, subtract IGRF from scalar magnetometer measurements |
bpf_mag | Bool | if true, bpf scalar magnetometer measurements in x data matrix, only used for model_type = :elasticnet, :plsr |
reorient_vec | Bool | if true, align vector magnetometers (fluxgates) with body frame |
norm_type_A | Symbol | normalization for "external" Tolles-Lawson A matrix, only used for model_type = :TL, :mod_TL, :map_TL (see below) |
norm_type_x | Symbol | normalization for x data matrix, only used for model_type = :elasticnet, :plsr (see below) |
norm_type_y | Symbol | normalization for y target vector (see below) |
model_typeoptions::TL= classical Tolles-Lawson:mod_TL= modified Tolles-Lawson:map_TL= map-based Tolles-Lawson:elasticnet= elastic net (ridge regression and/or Lasso):plsr: = partial least squares regression (PLSR)
y_typeoptions::a= anomaly field #1, compensated tail stinger total field scalar magnetometer measurements:b= anomaly field #2, interpolatedmagnetic anomaly mapvalues:c= aircraft field #1, difference between uncompensated cabin total field scalar magnetometer measurements and interpolatedmagnetic anomaly mapvalues:d= aircraft field #2, difference between uncompensated cabin and compensated tail stinger total field scalar magnetometer measurements:e= BPF'd total field, bandpass filtered uncompensated cabin total field scalar magnetometer measurements
norm_typeoptions::standardize= Z-score normalization:normalize= min-max normalization:scale= scale by maximum absolute value, bias = 0:none= scale by 1, bias = 0
Linear Model-Specific Parameters:
| Parameter | Type | Description |
|---|---|---|
k_plsr | Int64 | number of components, only used for model_type = :plsr |
λ_TL | Float64 | ridge parameter, only used for model_type = :TL, :mod_TL, :map_TL |
MagNav.NNCompParams — TypeNNCompParams <: CompParamsNeural network-based aeromagnetic compensation parameters struct. Subtype of CompParams.
To see default parameters, type NNCompParams().
General Parameters:
| Parameter | Type | Description |
|---|---|---|
version | VersionNumber | MagNav.jl version used to generate this struct |
features_setup | Vector{Symbol} | vector of features to include |
features_no_norm | Vector{Symbol} | vector of features to not normalize |
model_type | Symbol | aeromagnetic compensation model type (see below) |
y_type | Symbol | y target type (see below) |
use_mag | Symbol | uncompensated scalar magnetometer to use for y target vector {:mag_1_uc, etc.}, only used for y_type = :c, :d, :e |
use_vec | Symbol | vector magnetometer (fluxgate) to use for "external" Tolles-Lawson A matrix {:flux_a, etc.}, not used for model_type = :m1 |
data_norms | Tuple | length-7 tuple of data normalizations, (A_bias,A_scale,v_scale,x_bias,x_scale,y_bias,y_scale) |
model | Chain | neural network model |
terms | Vector{Symbol} | Tolles-Lawson terms to use for Tolles-Lawson A matrix (or matrices) within x data matrix {:permanent,:induced,:eddy} |
terms_A | Vector{Symbol} | Tolles-Lawson terms to use for "external" Tolles-Lawson A matrix {:permanent,:induced,:eddy,:bias}, not used for model_type = :m1 |
sub_diurnal | Bool | if true, subtract diurnal from scalar magnetometer measurements |
sub_igrf | Bool | if true, subtract IGRF from scalar magnetometer measurements |
bpf_mag | Bool | if true, bpf scalar magnetometer measurements in x data matrix |
reorient_vec | Bool | if true, align vector magnetometers (fluxgates) with body frame |
norm_type_A | Symbol | normalization for "external" Tolles-Lawson A matrix, only used for model_type = :m2* (see below) |
norm_type_x | Symbol | normalization for x data matrix (see below) |
norm_type_y | Symbol | normalization for y target vector (see below) |
model_typeoptions are broken into 3 architectures, with1being a standard feedforward neural network and2&3being used in conjunction with Tolles-Lawson:m1= standard feedforward neural network (NN):m2a= NN determines Tolles-Lawson (TL) coefficients:m2b= NN determines additive correction to classical TL:m2c= NN determines additive correction to classical TL, TL coefficients tuned as well:m2d= NN determines additive correction to each TL coefficient:m3tl= no NN, TL coefficients fine-tuned via SGD, without Taylor expansion fory_type = :b, :c(for testing):m3s= NN determines scalar correction to TL, using expanded TL vector terms for explainability:m3v= NN determines vector correction to TL, using expanded TL vector terms for explainability:m3sc=:m3swith curriculum learning based on TL error:m3vc=:m3vwith curriculum learning based on TL error:m3w=:m3swith window NN for temporal dataset:m3tf=:m3swith time series transformer for temporal dataset
y_typeoptions::a= anomaly field #1, compensated tail stinger total field scalar magnetometer measurements:b= anomaly field #2, interpolatedmagnetic anomaly mapvalues:c= aircraft field #1, difference between uncompensated cabin total field scalar magnetometer measurements and interpolatedmagnetic anomaly mapvalues:d= aircraft field #2, difference between uncompensated cabin and compensated tail stinger total field scalar magnetometer measurements:e= BPF'd total field, bandpass filtered uncompensated cabin total field scalar magnetometer measurements
norm_typeoptions::standardize= Z-score normalization:normalize= min-max normalization:scale= scale by maximum absolute value, bias = 0:none= scale by 1, bias = 0
Neural Network-Based Model-Specific Parameters:
| Parameter | Type | Description |
|---|---|---|
TL_coef | Vector{Float64} | Tolles-Lawson coefficients, not used for model_type = :m1, :m2a |
η_adam | Float64 | learning rate for Adam optimizer |
epoch_adam | Int64 | number of epochs for Adam optimizer |
epoch_lbfgs | Int64 | number of epochs for LBFGS optimizer |
hidden | Vector{Int64} | hidden layers & nodes (e.g., [8,8] for 2 hidden layers, 8 nodes each) |
activation | Function | activation function (see below) |
loss | Function | loss function (see below) |
batchsize | Int64 | mini-batch size |
frac_train | Float64 | fraction of training data used for training (remainder for validation), only used for Adam optimizer |
α_sgl | Float64 | Lasso (α_sgl=0) vs group Lasso (α_sgl=1) balancing parameter {0:1} |
λ_sgl | Float64 | sparse group Lasso parameter, typically ~1e-5 (if non-zero) |
k_pca | Int64 | number of components for pre-processing with PCA + whitening, -1 to ignore |
drop_fi | Bool | if true, perform drop-column feature importance |
drop_fi_bson | String | path/name of drop-column feature importance data BSON file to save/load (.bson extension optional) |
drop_fi_csv | String | path/name of drop-column feature importance data CSV file to save (.csv extension optional) |
perm_fi | Bool | if true, perform permutation feature importance |
perm_fi_csv | String | path/name of permutation feature importance data CSV file to save (.csv extension optional) |
activationoptions, which can be visualized by runningplot_activation():relu= rectified linear unitσ= sigmoid (logistic function)swish= self-gatedtanh= hyperbolic tan
lossoptions:mse= mean squared errormae= mean absolute errorhuber_loss= mean Huber loss