gnss_filters module

Classes for GNSS-based Kalman Filter implementations

class gnss_filters.GNSSEKF(init_dict, params_dict)[source]

Bases: BaseExtendedKalmanFilter

GNSS-only EKF implementation.

States: 3D position, 3D velocity and clock bias (in m). The state vector is \(\bar{x} = [x, y, z, v_x, v_y, v_y, b]^T\)

params_dict

Dictionary of parameters that may include the following.

Type:

dict

delta_t

Time between prediction instances

Type:

float

motion_type

Type of motion (stationary or constant_velocity)

Type:

string

measure_type

NavData types (pseudorange)

Type:

string

_abc_impl = <_abc_data object>
dyn_model(u, predict_dict=None)[source]

Nonlinear dynamics

Parameters:
  • u (np.ndarray) – Control signal, not used for propagation

  • predict_dict (dict) – Additional prediction parameters, including delta_t updates.

Returns:

new_x – Propagated state

Return type:

np.ndarray

linearize_dynamics(predict_dict=None)[source]

Linearization of dynamics model

Parameters:

predict_dict (dict) – Additional predict parameters, not used in current implementation

Returns:

  • A (np.ndarray) – Linear dynamics model depending on motion_type

  • predict_dict (dict) – Dictionary of prediction parameters.

linearize_measurements(update_dict)[source]

Linearization of measurement model

Parameters:

update_dict (dict) – Update dictionary containing satellite positions with key pos_sv_m.

Returns:

H – Jacobian of measurement model, of dimension #measurements x #states

Return type:

np.ndarray

measure_model(update_dict)[source]

Measurement model

Pseudorange model adds true range and clock bias estimate: \(\rho = \sqrt{(x-x_{sv})^2 + (y-y_{sv})^2 + (z-z_{sv})^2} + b\). See [1] for more details and models.

pos_sv_m must be a key in update_dict and must be an array of shape [3 x N] with rows of x_sv_m, y_sv_m, and z_sv_m in that order.

Parameters:

update_dict (dict) – Update dictionary containing satellite positions with key pos_sv_m.

Returns:

z – Expected measurement, depending on type (pseudorange)

Return type:

np.ndarray

References

gnss_filters.solve_gnss_ekf(measurements, init_dict=None, params_dict=None, delta_t_decimals=-2)[source]

Runs a GNSS Extended Kalman Filter across each timestep.

Runs an Extended Kalman Filter across each timestep and adds a new row for the receiver’s position and clock bias.

Parameters:
  • measurements (gnss_lib_py.navdata.navdata.NavData) – Instance of the NavData class

  • init_dict (dict) – Initialization dict with initial states and covariances.

  • params_dict (dict) – Dictionary of parameters for GNSS EKF.

Returns:

state_estimate – Estimated receiver position in ECEF frame in meters and the estimated receiver clock bias also in meters as an instance of the NavData class with shape (4 x # unique timesteps) and the following rows: x_rx_m, y_rx_m, z_rx_m, b_rx_m.

Return type:

gnss_lib_py.navdata.navdata.NavData