Flight Path & INS Data
The following are key functions related to obtaining flight path & INS data.
Load Flight Data
MagNav.get_XYZ0
— Functionget_XYZ0(xyz_file::String,
traj_field::Symbol = :traj,
ins_field::Symbol = :ins_data;
info::String = splitpath(xyz_file)[end],
flight = 1,
line = 1,
year = 2023,
doy = 154,
dt = 0.1,
tt_sort::Bool = true,
silent::Bool = false)
Get the minimum dataset required for MagNav from saved CSV, HDF5, or MAT file. Not all fields within the XYZ0
flight data struct are required. The minimum data required in the CSV, HDF5, or MAT file includes:
lat
,lon
,alt
(position)mag_1_c
ORmag_1_uc
(scalar magnetometer measurements)
All other fields can be computed/simulated.
If a CSV or HDF5 file is provided, the possible columns/fields in the file are:
Field | Type | Description |
---|---|---|
dt | scalar | measurement time step [s] |
tt | vector | time [s] |
lat | vector | latitude [deg] |
lon | vector | longitude [deg] |
alt | vector | altitude [m] |
vn | vector | north velocity [m/s] |
ve | vector | east velocity [m/s] |
vd | vector | down velocity [m/s] |
fn | vector | north specific force [m/s] |
fe | vector | east specific force [m/s] |
fd | vector | down specific force [m/s] |
Cnb | 3x3xN | direction cosine matrix (body to navigation) [-], not valid for CSV file (use roll , pitch , & yaw instead) |
roll | vector | roll [deg] |
pitch | vector | pitch [deg] |
yaw | vector | yaw [deg] |
ins_dt | scalar | INS measurement time step [s] |
ins_tt | vector | INS time [s] |
ins_lat | vector | INS latitude [deg] |
ins_lon | vector | INS longitude [deg] |
ins_alt | vector | INS altitude [m] |
ins_vn | vector | INS north velocity [m/s] |
ins_ve | vector | INS east velocity [m/s] |
ins_vd | vector | INS down velocity [m/s] |
ins_fn | vector | INS north specific force [m/s] |
ins_fe | vector | INS east specific force [m/s] |
ins_fd | vector | INS down specific force [m/s] |
ins_Cnb | 3x3xN | INS direction cosine matrix (body to navigation) [-], not valid for CSV file (use ins_roll , ins_pitch , & ins_yaw instead) |
ins_roll | vector | INS roll [deg] |
ins_pitch | vector | INS pitch [deg] |
ins_yaw | vector | INS yaw [deg] |
ins_P | 17x17xN | INS covariance matrix, only relevant for simulated data, otherwise zeros [-], not valid for CSV file |
flux_a_x | vector | Flux A x-direction magnetic field [nT] |
flux_a_y | vector | Flux A y-direction magnetic field [nT] |
flux_a_z | vector | Flux A z-direction magnetic field [nT] |
flux_a_t | vector | Flux A total magnetic field [nT] |
flight | vector | flight number(s) |
line | vector | line number(s), i.e., segments within flight |
year | vector | year |
doy | vector | day of year |
diurnal | vector | measured diurnal, i.e., temporal variations or space weather effects [nT] |
igrf | vector | International Geomagnetic Reference Field (IGRF), i.e., core field [nT] |
mag_1_c | vector | Mag 1 compensated (clean) scalar magnetometer measurements [nT] |
mag_1_uc | vector | Mag 1 uncompensated (corrupted) scalar magnetometer measurements [nT] |
If a MAT file is provided, the above fields may also be provided, but the non-INS fields should be within the specified traj_field
MAT struct and the INS fields should be within the specified ins_field
MAT struct and without ins_
prefixes. This is the standard way the MATLAB-companion outputs data.
Arguments:
xyz_file
: path/name of flight data CSV, HDF5, or MAT file (.csv
,.h5
, or.mat
extension required)traj_field
: (optional) trajectory struct field within MAT file to use, not relevant for CSV or HDF5 fileins_field
: (optional) INS struct field within MAT file to use,:none
if unavailable, not relevant for CSV or HDF5 filett_sort
: (optional) if true, sort data by time (instead of line)silent
: (optional) if true, no print outs
If not provided in xyz_file
:
info
: (optional) flight data informationflight
: (optional) flight numberline
: (optional) line number, i.e., segment withinflight
year
: (optional) yeardoy
: (optional) day of yeardt
: (optional) measurement time step [s]
Returns:
xyz
:XYZ0
flight data struct
MagNav.get_XYZ20
— Functionget_XYZ20(xyz_h5::String;
info::String = splitpath(xyz_h5)[end],
tt_sort::Bool = true,
silent::Bool = false)
Get XYZ20
flight data from saved HDF5 file. Based on 2020 SGL data fields.
Arguments:
xyz_h5
: path/name of flight data HDF5 file (.h5
extension optional)info
: (optional) flight data informationtt_sort
: (optional) if true, sort data by time (instead of line)silent
: (optional) if true, no print outs
Returns:
xyz
:XYZ20
flight data struct
get_XYZ20(xyz_160_h5::String, xyz_h5::String;
info::String = splitpath(xyz_160_h5)[end] * " & " * splitpath(xyz_h5)[end],
silent::Bool = false)
Get 160 Hz (partial) XYZ20
flight data from saved HDF5 file and combine with 10 Hz XYZ20
flight data from another saved HDF5 file. Data is time sorted to ensure data is aligned.
Arguments:
xyz_160_h5
: path/name of 160 Hz flight data HDF5 file (.h5
extension optional)xyz_h5
: path/name of 10 Hz flight data HDF5 file (.h5
extension optional)info
: (optional) flight data informationsilent
: (optional) if true, no print outs
Returns:
xyz
:XYZ20
flight data struct
MagNav.get_XYZ
— Functionget_XYZ(flight::Symbol, df_flight::DataFrame;
tt_sort::Bool = true,
reorient_vec::Bool = false,
silent::Bool = false)
Get XYZ
flight data from saved HDF5 file via DataFrame lookup.
Arguments:
flight
: flight name (e.g.,:Flt1001
)df_flight
: lookup table (DataFrame) of flight data files
Field | Type | Description |
---|---|---|
flight | Symbol | flight name (e.g., :Flt1001 ) |
xyz_type | Symbol | subtype of XYZ to use for flight data {:XYZ0 ,:XYZ1 ,:XYZ20 ,:XYZ21 } |
xyz_set | Real | flight dataset number (used to prevent improper mixing of datasets, such as different magnetometer locations) |
xyz_file | String | path/name of flight data CSV, HDF5, or MAT file (.csv , .h5 , or .mat extension required) |
tt_sort
: (optional) if true, sort data by time (instead of line)reorient_vec
: (optional) if true, align vector magnetometer measurements with body framesilent
: (optional) if true, no print outs
Returns:
xyz
:XYZ
flight data struct
Create Flight Data
MagNav.create_XYZ0
— Functioncreate_XYZ0(mapS::Union{MapS,MapSd,MapS3D} = get_map(namad);
alt = 1000,
dt = 0.1,
t = 300,
v = 68,
ll1::Tuple = (),
ll2::Tuple = (),
N_waves::Int = 1,
attempts::Int = 10,
info::String = "Simulated data",
flight = 1,
line = 1,
year = 2023,
doy = 154,
mapV::MapV = get_map(emm720),
cor_sigma = 1.0,
cor_tau = 600.0,
cor_var = 1.0^2,
cor_drift = 0.001,
cor_perm_mag = 5.0,
cor_ind_mag = 5.0,
cor_eddy_mag = 0.5,
init_pos_sigma = 3.0,
init_alt_sigma = 0.001,
init_vel_sigma = 0.01,
init_att_sigma = deg2rad(0.01),
VRW_sigma = 0.000238,
ARW_sigma = 0.000000581,
baro_sigma = 1.0,
ha_sigma = 0.001,
a_hat_sigma = 0.01,
acc_sigma = 0.000245,
gyro_sigma = 0.00000000727,
fogm_sigma = 1.0,
baro_tau = 3600.0,
acc_tau = 3600.0,
gyro_tau = 3600.0,
fogm_tau = 600.0,
save_h5::Bool = false,
xyz_h5::String = "xyz_data.h5",
silent::Bool = false)
Create basic flight data. Assumes constant altitude (2D flight). No required arguments, though many are available to create custom data.
Trajectory Arguments:
mapS
: (optional)MapS
,MapSd
, orMapS3D
scalar magnetic anomaly map structalt
: (optional) altitude [m]dt
: (optional) measurement time step [s]t
: (optional) total flight time, ignored ifll2
is set [s]v
: (optional) approximate aircraft velocity [m/s]ll1
: (optional) initial (lat,lon) point [deg]ll2
: (optional) final (lat,lon) point [deg]N_waves
: (optional) number of sine waves along pathattempts
: (optional) maximum attempts at creating flight path onmapS
info
: (optional) flight data informationflight
: (optional) flight numberline
: (optional) line number, i.e., segment withinflight
year
: (optional) yeardoy
: (optional) day of yearmapV
: (optional)MapV
vector magnetic anomaly map structsave_h5
: (optional) if true, savexyz
toxyz_h5
xyz_h5
: (optional) path/name of flight data HDF5 file to save (.h5
extension optional)
Compensated Measurement Corruption Arguments:
cor_var
: (optional) corruption measurement (white) noise variance [nT^2]fogm_sigma
: (optional) FOGM catch-all bias [nT]fogm_tau
: (optional) FOGM catch-all time constant [s]
Uncompensated Measurement Corruption Arguments:
cor_sigma
: (optional) corruption FOGM catch-all bias [nT]cor_tau
: (optional) corruption FOGM catch-all time constant [s]cor_var
: (optional) corruption measurement (white) noise variance [nT^2]cor_drift
: (optional) corruption measurement linear drift [nT/s]cor_perm_mag
: (optional) corruption permanent field TL coef std devcor_ind_mag
: (optional) corruption induced field TL coef std devcor_eddy_mag
: (optional) corruption eddy current TL coef std dev
INS Arguments:
init_pos_sigma
: (optional) initial position uncertainty [m]init_alt_sigma
: (optional) initial altitude uncertainty [m]init_vel_sigma
: (optional) initial velocity uncertainty [m/s]init_att_sigma
: (optional) initial attitude uncertainty [rad]VRW_sigma
: (optional) velocity random walk [m/s^2 /sqrt(Hz)]ARW_sigma
: (optional) angular random walk [rad/s /sqrt(Hz)]baro_sigma
: (optional) barometer bias [m]ha_sigma
: (optional) barometer aiding altitude bias [m]a_hat_sigma
: (optional) barometer aiding vertical accel bias [m/s^2]acc_sigma
: (optional) accelerometer bias [m/s^2]gyro_sigma
: (optional) gyroscope bias [rad/s]baro_tau
: (optional) barometer time constant [s]acc_tau
: (optional) accelerometer time constant [s]gyro_tau
: (optional) gyroscope time constant [s]
General Arguments:
silent
: (optional) if true, no print outs
Returns:
xyz
:XYZ0
flight data struct