Model 3 Training & Explainability

This file is best viewed in a Pluto notebook. To run it this way, from the MagNav.jl directory, do:

julia> using Pluto
julia> Pluto.run() # select & open notebook

This is a reactive notebook, so feel free to change any parameters of interest, like adding/removing features to the model, changing the number of training epochs, switching between versions of model 3 (scalar is :m3s, vector is :m3v), or different training & testing lines.

Import packages and DataFrames

The DataFrames listed below provide useful information about the flight data collected by Sander Geophysics Ltd. (SGL) & magnetic anomaly maps.

DataframeDescription
df_mapmap files relevant for SGL flights
df_calSGL calibration flight lines
df_flightSGL flight files
df_allall flight lines
df_navall navigation-capable flight lines
df_eventpilot-recorded in-flight events
begin
    cd(@__DIR__)
    # uncomment line below to use local MagNav.jl (downloaded folder)
    # using Pkg; Pkg.activate("../"); Pkg.instantiate()
    using MagNav
    using CSV, DataFrames
    using Plots: plot, plot!
    using Random: seed!
    using Statistics: mean, median, std
    seed!(33); # for reproducibility
    include("dataframes_setup.jl"); # setup DataFrames
end;

Train a (linear) Tolles-Lawson model

Select Flight 1006 (see readme), load the flight data, & get the Boolean indices for a specific calibration flight line that is used to fit the Tolles-Lawson coefficients. The full list of SGL flights is in df_flight, & the full list of calibration flight line options is in df_cal.

flight_train = :Flt1006; # select flight, full list in df_flight
reorient_vec = true; # align vector magnetometers with aircraft body frame
xyz_train = get_XYZ(flight_train, df_flight;
                    reorient_vec=reorient_vec, silent=true); # load flight data
begin # select a calibration flight line to train Tolles-Lawson on
    println(df_cal[df_cal.flight .== flight_train, :])
    TL_i   = 6 # select first calibration box of 1006.04
    TL_ind = get_ind(xyz_train;tt_lim=[df_cal.t_start[TL_i],df_cal.t_end[TL_i]])
end;

Select magnetometers & parameters to be used with Tolles-Lawson.

begin # try modifying these parameters
    use_mag = :mag_4_uc
    use_vec = :flux_d
    terms   = [:permanent,:induced,:eddy]
    flux    = getfield(xyz_train,use_vec)
    comp_params_lin_init = LinCompParams(model_type   = :TL,
                                         y_type       = :e,
                                         use_mag      = use_mag,
                                         use_vec      = use_vec,
                                         terms_A      = terms,
                                         sub_diurnal  = false,
                                         sub_igrf     = false,
                                         reorient_vec = reorient_vec)
end;
begin
    tt = (xyz_train.traj.tt[TL_ind] .- xyz_train.traj.tt[TL_ind][1]) / 60
    p1 = plot(xlab="time [min]",ylab="magnetic field [nT]",dpi=200,
              ylim=(51000,55000))
    plot!(p1, tt, xyz_train.igrf[TL_ind],     lab="IGRF core field")
    plot!(p1, tt, xyz_train.mag_1_c[TL_ind],  lab="compensated tail stinger")
    plot!(p1, tt, xyz_train.mag_4_uc[TL_ind], lab="uncompensated Mag 4")
    plot!(p1, tt, xyz_train.flux_a.t[TL_ind], lab="vector Flux A, total field")
end
begin # Tolles-Lawson calibration
    (comp_params_lin, _, _, err_TL) =
        comp_train(comp_params_lin_init, xyz_train, TL_ind)
    TL_a_4 = comp_params_lin.model[1]
end;

Select a flight line from Flight 1006 (see readme) to compare different compensation models. The full list of navigation-capable flight lines is in df_nav.

begin
    flight_test = :Flt1006 # select flight, full list in df_flight
    println(df_nav[df_nav.flight .== flight_test, :])
    xyz_test   = get_XYZ(flight_test, df_flight;
                         reorient_vec=reorient_vec, silent=true) # load flight data
    lines_test = [1006.08]
    ind_test   = get_ind(xyz_test, lines_test, df_nav) # get Boolean indices
end;

Perform Tolles-Lawson compensation on lines_test. The full list of SGL flights is in df_flight, the full list of maps is in df_map, & the full list of flight lines is in df_all.

comp_test(comp_params_lin, lines_test, df_all, df_flight, df_map);

Model 3 training

Create a low-pass (not the default, bandpass)-filtered version of the coefficients to preserve the Earth field, which helps to remove a bias term in the Tolles-Lawson (TL) fitting.

This shows how the bandpass filter causes a bias in the compensation (filtering out the Earth field). That is not a problem for navigating, but it is preferred to not have the neural network learn a simple correction that could be accounted for more simply by Tolles-Lawson.

 # create Tolles-Lawson coefficients with use_vec & use_mag
TL_coef = create_TL_coef(getfield(xyz_train,use_vec),
                         getfield(xyz_train,use_mag)-xyz_train.mag_1_c, TL_ind;
                         terms=terms, pass1=0.0, pass2=0.9);
begin # create Tolles-Lawson `A` matrix & perform compensation
    A = create_TL_A(flux,TL_ind)
    mag_1_sgl_TL_train = xyz_train.mag_1_c[TL_ind]
    mag_4_uc_TL_train  = xyz_train.mag_4_uc[TL_ind]
    mag_4_c_bpf        = mag_4_uc_TL_train - A*TL_a_4
    mag_4_c_lpf        = mag_4_uc_TL_train - A*TL_coef
    p2 = plot(xlab="time [min]",ylab="magnetic field [nT]",dpi=200,
              ylim=(52000,55000))
    plot!(p2, tt, mag_1_sgl_TL_train, lab="ground truth")
    plot!(p2, tt, mag_4_c_lpf,        lab="low-pass filtered TL")
    plot!(p2, tt, mag_4_c_bpf,        lab="bandpass filtered TL")
end

Training data & parameters

Set the training lines (all from the same flight in this example), select a model type, features for the neural network, & intialize all of this using the NNCompParams data structure, which keeps all these configuration/learning settings in one place. For model 3, it is important to not normalize Tolles-Lawson A matrix, unlike the x input data matrix & y target vector.

begin
    lines_train = [1006.03, 1006.04, 1006.05, 1006.06]
    ind_train   = get_ind(xyz_train, lines_train, df_all) # get Boolean indices
    model_type  = :m3s
    features    = [:mag_4_uc, :lpf_cur_com_1, :lpf_cur_strb, :lpf_cur_outpwr, :lpf_cur_ac_lo, :TL_A_flux_a]
end;
comp_params_init = NNCompParams(features_setup = features,
                                model_type     = model_type,
                                y_type         = :d,
                                use_mag        = use_mag,
                                use_vec        = use_vec,
                                terms          = [:permanent,:induced,:eddy],
                                terms_A        = [:permanent,:induced,:eddy],
                                sub_diurnal    = false,
                                sub_igrf       = false,
                                bpf_mag        = false,
                                reorient_vec   = reorient_vec,
                                norm_type_A    = :none,
                                norm_type_x    = :normalize,
                                norm_type_y    = :normalize,
                                TL_coef        = TL_coef,
                                η_adam         = 0.001,
                                epoch_adam     = 100,
                                epoch_lbfgs    = 0,
                                hidden         = [8,4],
                                batchsize      = 2048,
                                frac_train     = 13/17);
# neural network calibration
(comp_params, y_train, y_train_hat, err_train, _) =
    comp_train(comp_params_init, xyz_train, ind_train;
               xyz_test = xyz_test,
               ind_test = ind_test);

Evaluate test line performance & return additional terms that are useful for visualizing the compensation performance

# neural network compensation
(TL_perm, TL_induced, TL_eddy, TL_aircraft, B_unit, _, y_nn, _, y, y_hat, _, _) =
    comp_m3_test(comp_params, lines_test, df_nav, df_flight, df_map);

Ultimately, the compensated magnetometer values are used with a navigation algorithm, an extended Kalman filter (EKF) here. To prepare the flight data & map for the navigation filter, a few more objects are needed:

  • traj: trajectory (GPS) data structure

  • ins: INS data structure

  • itp_mapS: interpolated map to pass to the filter to use for measurement evaluations

  • (P0, Qd, R): initialized covariance & noise matrices for the filter

begin
    map_name = df_nav[df_nav.line .== lines_test[1], :map_name][1]
    traj = get_traj(xyz_test,ind_test) # trajectory (GPS) struct
    ins  = get_ins(xyz_test,ind_test;N_zero_ll=1) # INS struct, "zero" lat/lon to match first `traj` data point
    mapS = get_map(map_name,df_map) # load map data
    # get map values & map interpolation function
    (map_val,itp_mapS) = get_map_val(mapS,traj;return_itp=true)
end;

Compensate the magnetometer

Compute the compensated magnetometer values consistent with the :d setting in NNCompParams, that is, a correction has been learned that can be removed from the uncompensated measurement, producing the compensated measurement. The figure below illustrates performance as compared to the uncompensated figure above.

An assumed constant map-magnetometer bias is removed here, which is approximated at the first measurement. The diurnal & core (IGRF) fields must be included to leave only the nearly constant bias, if any.

begin
    mag_4_c = xyz_test.mag_4_uc[ind_test] - y_hat # neural network compensation
    mag_4_c .+= (map_val + (xyz_test.diurnal + xyz_test.igrf)[ind_test] - mag_4_c)[1]
    # first-order Gauss-Markov noise values
    (sigma,tau) = get_autocor(mag_4_c - map_val)
end
(55, 16)
begin
    tt_test = (xyz_test.traj.tt[ind_test] .- xyz_test.traj.tt[ind_test][1]) / 60
    p3 = plot(xlab="time [min]",ylab="magnetic field [nT]",dpi=200,
              ylim=(52900,53700))
    plot!(p3, tt_test, map_val + (xyz_test.diurnal + xyz_test.igrf)[ind_test],
                                                   lab="map value")
    plot!(p3, tt_test, xyz_test.mag_1_c[ind_test], lab="compensated tail stinger")
    plot!(p3, tt_test, mag_4_c,                    lab="compensated Mag 4")
end

Navigation

Create a navigation filter model. Only the most relevant navigation filter parameters are shown.

(P0,Qd,R) = create_model(traj.dt,traj.lat[1];
                         init_pos_sigma = 0.1,
                         init_alt_sigma = 1.0,
                         init_vel_sigma = 1.0,
                         meas_var       = sigma^2, # increase if mag_use is bad
                         fogm_sigma     = sigma,
                         fogm_tau       = tau);
begin
    mag_use = mag_4_c
    (crlb_out,ins_out,filt_out) = run_filt(traj,ins,mag_use,itp_mapS,:ekf;
                                           P0,Qd,R,core=true)
    drms_out = round(Int,sqrt(mean(filt_out.n_err.^2+filt_out.e_err.^2)))
end;

Compensation and navigation animation

Make an animation of the navigation performance, keeping track of each component of the compensation terms emitted by model 3, projected into a 2D plane (north/east, removing the vertical components) to make visualization simpler. Ideally, you should see that the knowledge-integrated architecture in model 3 is mostly accounting for variations in the compensation field arising from the map/plane maneuvers in the Tolles-Lawson (TL) component, whereas the neural network (NN) correction is addressing any deviations due to current/voltage fluctuations.

Increase (or decrease) the skip_every argument to exclude (or include) more frames, which speeds up (or slows down) the rendering time & decrease (or increase) the file size.

g1 = gif_animation_m3(TL_perm, TL_induced, TL_eddy, TL_aircraft, B_unit,
                      y_nn, y, y_hat, xyz_test, filt_out.lat, filt_out.lon;
                      ind=ind_test, skip_every=20, tt_lim=(3.0,9.5))

Show detailed filter performance using plot_filt_err

(p4,p5) = plot_filt_err(traj, filt_out, crlb_out);
p4
p5