Skip to main content

Inertial Navigation Utilities

Project description

Inertial Navigation Utilities

Key Design Concepts

Functions

This library provides forward mechanization of inertial measurement unit sensor values (accelerometer and gyroscope readings) to get position, velocity, and attitude as well as inverse mechanization to get sensor values from position, velocity, and attitude. It also includes tools to calculate velocity from geodetic position over time, to estimate attitude from velocity, to estimate wind velocity from ground-track velocity and yaw angle, and to generate navigation paths from waypoints.

Accuracy

The mechanization algorithms in this library make no simplifying assumptions. The Earth is defined as an ellipsoid. Any deviations of the truth from this simple shape can be captured by more complex gravity models. The algorithms use a single frequency update structure which is much simpler than the common two-frequency update structure and just as, if not more, accurate.

Duality

The forward and inverse mechanization functions are perfect duals of each other. This means that if you started with a profile of position, velocity, and attitude and passed these into the inverse mechanization algorithm to get sensor values and then passed those sensor values into the forward mechanization algorithm, you would get back the original position, velocity, and attitude profiles. The only error would be due to finite-precision rounding.

Vectorization

When possible, the functions are vectorized in order to handle processing batches of values. A set of scalars is a 1D array. A set of vectors is a 2D array, with each vector in a column. So, a (3, 7) array is a set of seven vectors, each with 3 elements. If an input matrix does not have 3 rows, it will be assumed that the rows of the matrix are vectors.

An example of the vectorization in this library is the inv_mech (inverse mechanization) algorithm. There is no for loop to iterate through time; rather the entire algorithm has been vectorized. This results in an over 100x speed increase.

Extended Kalman Filter

An extended Kalman filter can be implemented using this library. The mech_step function applies the mechanization equations to a single time step. It returns the time derivatives of the states. The jacobian function calculates the continuous-domain Jacobian of the dynamics function. While this does mean that the user must then manually integrate the derivatives and discretize the Jacobian, this gives the user greater flexibility to decide how to discretize them.

The example code below is meant to run within a for loop stepping through time, where k is the time index:

# Inputs
fbbi = fbbi_t[:, k] # specific forces (m/s^2)
wbbi = wbbi_t[:, k] # rotation rates (rad/s)
z = z_t[:, k] # GPS position (rad, rad, m)

# Update
S = H @ Ph @ H.T + R # innovation covariance (3, 3)
Si = np.linalg.inv(S) # inverse (3, 3)
Kg = Ph @ H.T @ Si # Kalman gain (9, 3)
Ph -= Kg @ H @ Ph # update to state covariance (9, 9)
r = z - llh # innovation (3,)
dx = Kg @ r # changes to states (9,)
llh += dx[:3] # add change in position
vne += dx[3:6] # add change in velocity
# matrix exponential of skew-symmetric matrix
Psi = r3f.rodrigues_rotation(dx[6:])
Cnb = Psi.T @ Cnb

# Save results.
tllh_t[:, k] = llh.copy()
tvne_t[:, k] = vne.copy()
trpy_t[:, k] = r3f.dcm_to_rpy(Cnb.T)

# Get the Jacobian and propagate the state covariance.
F = inu.jacobian(fbbi, llh, vne, Cnb)
Phi = I + (F*T)@(I + (F*T/2)) # 2nd-order expm(F T)
Ph = Phi @ Ph @ Phi.T + Qd

# Get the state derivatives.
Dllh, Dvne, wbbn = inu.mech_step(fbbi, wbbi, llh, vne, Cnb)

# Integrate (forward Euler).
llh += Dllh * T # change applies linearly
vne += Dvne * T # change applies linearly
Cnb[:, :] = Cnb @ r3f.rodrigues_rotation(wbbn * T)
Cnb[:, :] = r3f.orthonormalize_dcm(Cnb)

# Update progress bar.
inu.progress(k, K)

In the example above, H should be a (3, 9) matrix with ones along the diagonal. The Qd should be the (9, 9) discretized dynamics noise covariance matrix. The R should be the (3, 3) measurement noise covariance matrix. Note that forward Euler integration has been performed on the state derivatives and a second-order approximation to the matrix exponential has been implemented to discretize the continuous-time Jacobian.

Functions

Mechanization: mech and mech_step

llh_t, vne_t, rpy_t = inu.mech(fbbi_t, wbbi_t,
    llh0, vne0, rpy0, T, hae_t=None,
    baro_name=None, grav_model=somigliana,
    show_progress=True):
Dllh, Dvne, wbbn = inu.mech_step(fbbi, wbbi,
    llh, vne, Cnb, hb=None, baro=None,
    grav_model=somigliana)

The mech function performs forward mechanization of accelerometer and gyroscope sensor values, given the initial conditions for position, velocity, and attitude. This function processes an entire time-history profile of sensor values and returns the path solution for the corresponding span of time. If you would prefer to mechanize only one step at a time, you can call the mech_step function instead. Actually, the mech function does call the mech_step function within a for loop.

The mech function can override the height solution with whatever is provided for hae_t. If a barometric altimeter is named (one of eight names), hae_t will be treated as the barometric altitude. Similarly, the mech_step function can take a barometric model, generated by the Baro class.

Inverse Mechanization: inv_mech

fbbi_t, wbbi_t = inu.inv_mech(llh_t, rpy_t, T, grav_model=somigliana)

The inv_mech function performs inverse mechanization, meaning it takes path information in the form of position and attitude over time and estimates the corresponding sensor values for an accelerometer and gyroscope. This function is fully vectorized, so there is no for loop internally. Note that the velocity is internally calculated from position over time.

Path Generation

path = inu.waypoints(points, seg_len=1.0, radius_min=10.0,
    plot=True, ax=None, res=1.0,
    color="tab:blue", warncolor="tab:orange")

The class waypoints will take a (2, Np) array of waypoints, points, and create an interactive plot connecting the waypoints with quadratic Bezier curves. These curves can be manipulated by moving, creating, and deleting the waypoints. The field path.B will contain the North, East, Down coordinates of the navigation path.

pc_t = inu.path_pretzel(K,
    radius=1000.0, height=100.0,
    cycles=1.0, twists=1)
pc_t = inu.path_grid(seg_len,
    spacing=300.0, length=1600.0,
    rows=6)
pc_t = inu.path_spiral(seg_len,
    spacing=300.0, cycles=3)
pc_t = inu.path_clover(seg_len,
    radius=10000.0, cycles=3)

Several, pre-defined navigation paths are also provided. These will return the North, East, Down coordinates of the navigation path. The user can then convert these to geodetic coordinates with either the r3f.curvilinear_to_geodetic or r3f.tangent_to_geodetic function.

t, vne_t, rpy_t = inu.llh_to_tva(llh_t, T)
vne_t = inu.llh_to_vne(llh_t, T)
rpy_t = inu.vne_to_rpy(vne_t, grav_t, T, alpha=0.06, wind=None)

With a navigation path, llh_t, the velocity and attitude can be estimated assuming coordinated turns.

Estimate Horizontal Winds: est_wind

wind_t = inu.est_wind(vne_t, yaw_t)

If you have heading information as well as velocity information, then you can calculate the velocity vector due to wind using the est_wind function.

Jacobian: jacobian

F = inu.jacobian(fbbi, llh, vne, Cnb, baro=None)

The Jacobian of the dynamics is calculated using the jacobian function. This is a square matrix whose elements are the derivatives with respect to state of the continuous-domain, time-derivatives of states. For example, the time derivative of latitude is

So, the derivative of this with respect to height above ellipsoid is

The order of the states is position (latitude, longitude, height), velocity (North, East, down), and attitude. So, the above partial derivative would be found in element (1,3) (base-1 indexing) of the Jacobian matrix.

The representation of attitude is complicated. This library uses 3x3 direction cosine matrices (DCMs) to process attitude. The rate of change in attitude is represented by a tilt error vector. So, the last three states in the Jacobian are the x, y, and z tilt errors. This makes a grand total of 9 states, so the Jacobian is a 9x9 matrix.

The above code example (and the ekf_gps.py script in the examples folder) shows how to use the Jacobian.

Discretization: vanloan

Phi, Bd, Qd = inu.vanloan(F, B=None, Q=None, T=None)

The extended Kalman filter (EKF) example above shows a reduced-order approximation to the matrix exponential of the Jacobian. The Q dynamics noise covariance matrix also needs to be discretized. This was done with a first-order approximation by just multiplying it by the sampling period T. This is reasonably accurate and computationally fast. However, it is an approximation. The mathematically accurate way to discretize the Jacobian and Q is to use the van Loan method. This is implemented with the vanloan function.

Orientation: ned_enu

vec = inu.ned_enu(vec)

This library assumes all local-level coordinates are in the North, East, down orientation. If your coordinates are in the East, North, up orientation or you wish for the final results to be converted to that orientation, use the ned_enu function.

Project details


Download files

Download the file for your platform. If you're not sure which to choose, learn more about installing packages.

Source Distribution

inu-2.2.3.tar.gz (24.3 kB view details)

Uploaded Source

Built Distribution

If you're not sure about the file name format, learn more about wheel file names.

inu-2.2.3-py3-none-any.whl (23.3 kB view details)

Uploaded Python 3

File details

Details for the file inu-2.2.3.tar.gz.

File metadata

  • Download URL: inu-2.2.3.tar.gz
  • Upload date:
  • Size: 24.3 kB
  • Tags: Source
  • Uploaded using Trusted Publishing? No
  • Uploaded via: twine/6.1.0 CPython/3.13.2

File hashes

Hashes for inu-2.2.3.tar.gz
Algorithm Hash digest
SHA256 851711e20d79a69146861c669f935eed45dca02b3ce31ed1e1a025c76307cb5f
MD5 0a39da4e349b3d478347cfdcb43ebad9
BLAKE2b-256 b0314ab58024ac4cd07b55ee1d4c3a218098460cd64729bf7ad93eb411bcee0d

See more details on using hashes here.

File details

Details for the file inu-2.2.3-py3-none-any.whl.

File metadata

  • Download URL: inu-2.2.3-py3-none-any.whl
  • Upload date:
  • Size: 23.3 kB
  • Tags: Python 3
  • Uploaded using Trusted Publishing? No
  • Uploaded via: twine/6.1.0 CPython/3.13.2

File hashes

Hashes for inu-2.2.3-py3-none-any.whl
Algorithm Hash digest
SHA256 723f2f8d552ddc16753608435db06d0366cd0f6cf4a71fb827aa416452ba1db9
MD5 9ba46488e1c9c5843d7b010464563122
BLAKE2b-256 2cd2268dca9b59d7533a866f0ed7e87ec44b3e571a58b0ce184ae91d7dca4a73

See more details on using hashes here.

Supported by

AWS Cloud computing and Security Sponsor Datadog Monitoring Depot Continuous Integration Fastly CDN Google Download Analytics Pingdom Monitoring Sentry Error logging StatusPage Status page