opengnc.navigation package

Submodules

opengnc.navigation.angle_only_nav module

Navigation using Line-of-Sight (LOS) measurements (unit vectors).

class opengnc.navigation.angle_only_nav.AngleOnlyNavigation(x0: ndarray, p0: ndarray, q_mat: ndarray, r_mat: ndarray, use_j2: bool = True, mu: float = 398600441800000.0, re: float = 6378137.0)[source]

Bases: OrbitDeterminationEKF

Angles-Only Navigation (AON) using Line-of-Sight (LOS) unit vectors.

Estimates the spacecraft state by tracking unit vectors to known celestial or terrestrial targets. Inherits dynamics from OrbitDeterminationEKF.

Parameters:
  • x_initial (np.ndarray) – Initial 6D state vector $[mathbf{r}, mathbf{v}]^T$ (m, m/s).

  • p_initial (np.ndarray) – Initial estimation error covariance ($6times 6$).

  • q_mat (np.ndarray) – Process noise covariance ($6times 6$).

  • r_mat (np.ndarray) – Measurement noise covariance for the unit vector ($3times 3$).

  • mu (float, optional) – Gravitational parameter ($m^3/s^2$).

update_unit_vector(u_meas: ndarray, target_pos_eci: ndarray) None[source]

Update the state estimate using a measured LOS unit vector $mathbf{u}$.

Measurement Model: $mathbf{z} = frac{mathbf{r}_t - mathbf{r}}{rho} + nu$ Jacobian: $mathbf{H}_r = -frac{1}{rho} (mathbf{I} - mathbf{u}mathbf{u}^T)$

Parameters:
  • u_meas (np.ndarray) – Measured unit vector in ECI frame.

  • target_pos_eci (np.ndarray) – Known coordinates of the target (m).

opengnc.navigation.batch_ls module

Differential Correction using Batch Least Squares for Orbit Determination.

class opengnc.navigation.batch_ls.BatchLeastSquaresOD(x_guess: ndarray, mu: float = 398600441500000.0)[source]

Bases: object

Differential Correction via Batch Least Squares for Orbit Determination.

Iteratively refines the spacecraft state by minimizing weighted residuals over a batch of observations. Normal Equations: $(mathbf{H}^T mathbf{W} mathbf{H}) Delta mathbf{x} = mathbf{H}^T mathbf{W} mathbf{b}$.

Parameters:
  • x_guess (np.ndarray) – Initial 6D state guess $[mathbf{r}, mathbf{v}]^T$ (m, m/s).

  • mu (float, optional) – Gravitational parameter ($m^3/s^2$). Default is Earth.

solve(observations: ndarray, times: ndarray, max_iter: int = 15, tol: float = 1e-06) ndarray[source]

Iteratively solve the Batch LS problem.

Parameters:
  • observations (np.ndarray) – Position observations $[r_x, r_y, r_z]$ (N, 3) (m).

  • times (np.ndarray) – Observation timestamps (N,) (s).

  • max_iter (int, optional) – Maximum iterations. Default 15.

  • tol (float, optional) – Convergence tolerance. Default 1e-6.

Returns:

Estimated state vector at $t=0$ (6,).

Return type:

np.ndarray

opengnc.navigation.gps_nav module

Navigation using GNSS (GPS) position and velocity measurements.

class opengnc.navigation.gps_nav.GPSNavigation(x0: ndarray, p0: ndarray, q_mat: ndarray, r_mat: ndarray, use_j2: bool = True, mu: float = 398600441800000.0, re: float = 6378137.0)[source]

Bases: OrbitDeterminationEKF

GNSS-based Navigation using absolute Position and Velocity measurements.

Processes PVT (Position, Velocity, Time) solutions from a receiver to correct the integrated orbital state. Inherits dynamics from OrbitDeterminationEKF.

update_gps(r_meas: ndarray, v_meas: ndarray | None = None, gps_cov: ndarray | None = None, **kwargs: Any) None[source]

Update state estimate using GNSS Cartesian measurements.

Parameters:
  • r_meas (np.ndarray) – Measured ECI position (m).

  • v_meas (np.ndarray, optional) – Measured ECI velocity (m/s).

  • gps_cov (np.ndarray, optional) – Direct measurement covariance matrix.

  • **kwargs (dict) – Additional parameters (e.g., R_gps).

opengnc.navigation.iod module

Initial Orbit Determination (IOD) methods (Gibbs, Gauss, Laplace).

opengnc.navigation.iod.gauss_iod(rho_hat1: ndarray, rho_hat2: ndarray, rho_hat3: ndarray, t1: float, t2: float, t3: float, r_obs1: ndarray, r_obs2: ndarray, r_obs3: ndarray, mu: float = 398600441500000.0) ndarray[source]

Angles-only IOD via Gauss method with iterative refinement.

Solves for slant ranges using an 8th-order polynomial and performs iterative refinement using Herrick-Gibbs for stability.

Parameters:
  • rho_hat1 (np.ndarray) – Line-of-Sight unit vectors in ECI.

  • rho_hat2 (np.ndarray) – Line-of-Sight unit vectors in ECI.

  • rho_hat3 (np.ndarray) – Line-of-Sight unit vectors in ECI.

  • t1 (float) – Observation times (s).

  • t2 (float) – Observation times (s).

  • t3 (float) – Observation times (s).

  • r_obs1 (np.ndarray) – Observer position vectors in ECI (m).

  • r_obs2 (np.ndarray) – Observer position vectors in ECI (m).

  • r_obs3 (np.ndarray) – Observer position vectors in ECI (m).

  • mu (float, optional) – Gravitational parameter ($m^3/s^2$).

Returns:

ECI State vector $[r, v]$ at $t_2$ (m, m/s).

Return type:

np.ndarray

opengnc.navigation.iod.gibbs_iod(r1: ndarray, r2: ndarray, r3: ndarray, mu: float = 398600441500000.0) ndarray[source]

Initial Orbit Determination (IOD) via Gibbs method.

Suitable for three position vectors with angular separation > 5 degrees. Formula: $mathbf{v}_2 = sqrt{frac{mu}{N D}} left( frac{mathbf{D} times mathbf{r}_2}{r_2} + mathbf{S} right)$.

Parameters:
  • r1 (np.ndarray) – ECI position vectors (m) at three distinct times.

  • r2 (np.ndarray) – ECI position vectors (m) at three distinct times.

  • r3 (np.ndarray) – ECI position vectors (m) at three distinct times.

  • mu (float, optional) – Gravitational parameter ($m^3/s^2$). Default is Earth.

Returns:

Velocity vector at the second observation time $mathbf{v}_2$ (m/s).

Return type:

np.ndarray

opengnc.navigation.iod.herrick_gibbs_iod(r1: ndarray, r2: ndarray, r3: ndarray, dt21: float, dt32: float, mu: float = 398600441500000.0) ndarray[source]

Initial Orbit Determination via Herrick-Gibbs method.

Best for short-arc observations (angular separation < 5 degrees).

Parameters:
  • r1 (np.ndarray) – ECI position vectors (m).

  • r2 (np.ndarray) – ECI position vectors (m).

  • r3 (np.ndarray) – ECI position vectors (m).

  • dt21 (float) – Time interval $t_2 - t_1$ (s).

  • dt32 (float) – Time interval $t_3 - t_2$ (s).

  • mu (float, optional) – Gravitational parameter ($m^3/s^2$).

Returns:

Velocity vector $mathbf{v}_2$ (m/s).

Return type:

np.ndarray

opengnc.navigation.iod.laplace_iod(rho_hat: ndarray, rho_dot: ndarray, rho_ddot: ndarray, r_obs: ndarray, v_obs: ndarray, a_obs: ndarray, mu: float = 398600441500000.0) ndarray[source]

Orbit determination from line-of-sight derivatives (Laplace method).

Parameters:
  • rho_hat (np.ndarray) – LOS unit vector and its first/second time derivatives.

  • rho_dot (np.ndarray) – LOS unit vector and its first/second time derivatives.

  • rho_ddot (np.ndarray) – LOS unit vector and its first/second time derivatives.

  • r_obs (np.ndarray) – Observer Cartesian state and acceleration at epoch.

  • v_obs (np.ndarray) – Observer Cartesian state and acceleration at epoch.

  • a_obs (np.ndarray) – Observer Cartesian state and acceleration at epoch.

  • mu (float, optional) – Gravitational parameter ($m^3/s^2$).

Returns:

ECI State vector $[r, v]$ at epoch.

Return type:

np.ndarray

opengnc.navigation.iod.laplace_iod_from_observations(rho_hats: list[ndarray], rs_obs: list[ndarray], times: list[float], mu: float = 398600441500000.0) ndarray[source]

Perform Laplace IOD from three standard LOS observations.

Estimates derivatives using Lagrange interpolation.

Parameters:
  • rho_hats (List[np.ndarray]) – Three LOS unit vectors.

  • rs_obs (List[np.ndarray]) – Three observer position vectors.

  • times (List[float]) – Three observation timestamps.

  • mu (float, optional) – Gravitational parameter.

Returns:

State vector at $t_2$ (6,) (m, m/s).

Return type:

np.ndarray

opengnc.navigation.orbit_determination module

Extended Kalman Filter for Orbit Determination (OD-EKF).

class opengnc.navigation.orbit_determination.OrbitDeterminationEKF(x0: ndarray, p0: ndarray, q_mat: ndarray, r_mat: ndarray, use_j2: bool = True, mu: float = 398600441800000.0, re: float = 6378137.0)[source]

Bases: object

Extended Kalman Filter for Orbit Determination (OD-EKF).

Estimates the 6D Cartesian state $mathbf{x} = [mathbf{r}, mathbf{v}]^T$ in the ECI frame. Supports multi-model dynamics (Two-body, J2) and RK4-based state prediction.

Parameters:
  • x0 (np.ndarray) – Initial state vector $[r_x, r_y, r_z, v_x, v_y, v_z]$ (m, m/s).

  • p0 (np.ndarray) – Initial $6times 6$ estimation error covariance matrix.

  • q_mat (np.ndarray) – Process noise covariance matrix $mathbf{Q} in mathbb{R}^{6times 6}$.

  • r_mat (np.ndarray) – Measurement noise covariance matrix $mathbf{R} in mathbb{R}^{3times 3}$.

  • use_j2 (bool, optional) – Whether to include J2 perturbations. Default is True.

  • mu (float, optional) – Gravitational parameter ($m^3/s^2$).

  • re (float, optional) – Earth radius (m).

property covariance: ndarray

Estimation error covariance matrix $mathbf{P}$.

predict(dt: float) None[source]

Perform EKF prediction step ($x^-, P^-$).

Parameters:

dt (float) – Step size (s).

property state: ndarray

Estimated orbit state vector $[r, v]^T$.

update(z_pos: ndarray) None[source]

Update state estimate using position measurement $mathbf{z} = mathbf{r} + nu$.

Parameters:

z_pos (np.ndarray) – ECI Position measurement (m).

opengnc.navigation.relative_nav module

EKF for relative navigation using Clohessy-Wiltshire (Hill) dynamics.

class opengnc.navigation.relative_nav.RelativeNavigationEKF(x0: ndarray, p0: ndarray, q_mat: ndarray, r_mat: ndarray, mean_motion: float)[source]

Bases: object

Relative Navigation EKF via Clohessy-Wiltshire (Hill) Dynamics.

Estimates the 6D relative state $delta mathbf{x} = [delta mathbf{r}, delta mathbf{v}]^T$ in the Hill (RSW) frame. Assumes a circular target orbit.

Parameters:
  • x0 (np.ndarray) – Initial relative state $[x, y, z, dot{x}, dot{y}, dot{z}]^T$ (m, m/s).

  • p0 (np.ndarray) – Initial estimation covariance ($6times 6$).

  • q_mat (np.ndarray) – Process noise covariance ($6times 6$).

  • r_mat (np.ndarray) – Measurement noise covariance ($3times 3$).

  • mean_motion (float) – Target mean motion $n = sqrt{mu/a^3}$ (rad/s).

predict(dt: float) None[source]

Predict relative state using the analytical CW transition matrix $Phi(t)$.

Parameters:

dt (float) – Predict step (s).

property state: ndarray

Estimated relative state $[delta mathbf{r}, delta mathbf{v}]^T$.

update(z_rel_pos: ndarray) None[source]

Update estimate using a 3D relative position measurement.

Parameters:

z_rel_pos (np.ndarray) – Relative position vector in Hill frame (m).

opengnc.navigation.surface_nav module

Lander/Rover surface navigation EKF using landmark tracking.

class opengnc.navigation.surface_nav.SurfaceNavigationEKF(x0: ndarray, p0: ndarray, q_mat: ndarray, r_mat: ndarray)[source]

Bases: object

Surface Navigation EKF for Landers or Rovers.

Estimates 6D state $mathbf{x} = [mathbf{r}, mathbf{v}]^T$ in a local surface-fixed frame using constant acceleration kinematics and landmark observations.

Parameters:
  • x0 (np.ndarray) – Initial state $[x, y, z, v_x, v_y, v_z]^T$ (m, m/s).

  • p0 (np.ndarray) – Initial estimation error covariance ($6times 6$).

  • q_mat (np.ndarray) – Process noise covariance ($6times 6$).

  • r_mat (np.ndarray) – Measurement noise covariance for relative landmark tracking ($3times 3$).

predict(dt: float, accel: ndarray | None = None) None[source]

Perform kinematic state prediction.

Parameters:
  • dt (float) – Propagation step (s).

  • accel (np.ndarray, optional) – IMU acceleration or commanded thrust (m/s^2).

property state: ndarray

Estimated 6D rover state vector.

update_landmark(z_obs: ndarray, landmark_pos: ndarray) None[source]

Update state using an observed relative vector to a known landmark.

Measurement model: $mathbf{z} = mathbf{r}_{land} - mathbf{r}_{Rover} + nu$.

Parameters:
  • z_obs (np.ndarray) – Measured relative vector (m).

  • landmark_pos (np.ndarray) – Known coordinates of the landmark (m).

opengnc.navigation.terrain_nav module

Terrain-Relative Navigation (TRN) feature matching and localization update.

class opengnc.navigation.terrain_nav.FeatureMatchingTRN(map_database: list[ndarray])[source]

Bases: object

Terrain-Relative Navigation (TRN) Feature Matcher.

Correlates observed landmarks (from sensors like LIDAR or cameras) with a known map database using efficient nearest-neighbor search.

Parameters:

map_database (List[np.ndarray]) – List of absolute landmark coordinates (m).

match_features(observed_features: list[ndarray], dist_threshold: float = 10.0) list[tuple[ndarray, ndarray]][source]

Match observed features to the global map.

Parameters:
  • observed_features (List[np.ndarray]) – Landmarks relative to the current vehicle state (m).

  • dist_threshold (float, optional) – Max distance for correlation (m). Default is 10.0.

Returns:

Pairs of (Map Position, Observed Position).

Return type:

List[Tuple[np.ndarray, np.ndarray]]

opengnc.navigation.terrain_nav.map_relative_localization_update(x_state: ndarray, p_cov: ndarray, matches: list[tuple[ndarray, ndarray]], r_noise: ndarray) tuple[ndarray, ndarray][source]

EKF Measurement Update using TRN feature matches.

Corrects the global state estimate using residuals between map-known landmarks and their estimated positions.

Parameters:
  • x_state (np.ndarray) – Current filter state $[mathbf{r}, …]^T$.

  • p_cov (np.ndarray) – Estimation covariance matrix.

  • matches (List[Tuple[np.ndarray, np.ndarray]]) – Landmark correspondences from match_features.

  • r_noise (np.ndarray) – Sensor noise covariance ($3times 3$).

Returns:

  • updated_x (np.ndarray) – Updated state estimate.

  • updated_p (np.ndarray) – Updated covariance matrix.

Module contents

class opengnc.navigation.AngleOnlyNavigation(x0: ndarray, p0: ndarray, q_mat: ndarray, r_mat: ndarray, use_j2: bool = True, mu: float = 398600441800000.0, re: float = 6378137.0)[source]

Bases: OrbitDeterminationEKF

Angles-Only Navigation (AON) using Line-of-Sight (LOS) unit vectors.

Estimates the spacecraft state by tracking unit vectors to known celestial or terrestrial targets. Inherits dynamics from OrbitDeterminationEKF.

Parameters:
  • x_initial (np.ndarray) – Initial 6D state vector $[mathbf{r}, mathbf{v}]^T$ (m, m/s).

  • p_initial (np.ndarray) – Initial estimation error covariance ($6times 6$).

  • q_mat (np.ndarray) – Process noise covariance ($6times 6$).

  • r_mat (np.ndarray) – Measurement noise covariance for the unit vector ($3times 3$).

  • mu (float, optional) – Gravitational parameter ($m^3/s^2$).

update_unit_vector(u_meas: ndarray, target_pos_eci: ndarray) None[source]

Update the state estimate using a measured LOS unit vector $mathbf{u}$.

Measurement Model: $mathbf{z} = frac{mathbf{r}_t - mathbf{r}}{rho} + nu$ Jacobian: $mathbf{H}_r = -frac{1}{rho} (mathbf{I} - mathbf{u}mathbf{u}^T)$

Parameters:
  • u_meas (np.ndarray) – Measured unit vector in ECI frame.

  • target_pos_eci (np.ndarray) – Known coordinates of the target (m).

class opengnc.navigation.FeatureMatchingTRN(map_database: list[ndarray])[source]

Bases: object

Terrain-Relative Navigation (TRN) Feature Matcher.

Correlates observed landmarks (from sensors like LIDAR or cameras) with a known map database using efficient nearest-neighbor search.

Parameters:

map_database (List[np.ndarray]) – List of absolute landmark coordinates (m).

match_features(observed_features: list[ndarray], dist_threshold: float = 10.0) list[tuple[ndarray, ndarray]][source]

Match observed features to the global map.

Parameters:
  • observed_features (List[np.ndarray]) – Landmarks relative to the current vehicle state (m).

  • dist_threshold (float, optional) – Max distance for correlation (m). Default is 10.0.

Returns:

Pairs of (Map Position, Observed Position).

Return type:

List[Tuple[np.ndarray, np.ndarray]]

class opengnc.navigation.GPSNavigation(x0: ndarray, p0: ndarray, q_mat: ndarray, r_mat: ndarray, use_j2: bool = True, mu: float = 398600441800000.0, re: float = 6378137.0)[source]

Bases: OrbitDeterminationEKF

GNSS-based Navigation using absolute Position and Velocity measurements.

Processes PVT (Position, Velocity, Time) solutions from a receiver to correct the integrated orbital state. Inherits dynamics from OrbitDeterminationEKF.

update_gps(r_meas: ndarray, v_meas: ndarray | None = None, gps_cov: ndarray | None = None, **kwargs: Any) None[source]

Update state estimate using GNSS Cartesian measurements.

Parameters:
  • r_meas (np.ndarray) – Measured ECI position (m).

  • v_meas (np.ndarray, optional) – Measured ECI velocity (m/s).

  • gps_cov (np.ndarray, optional) – Direct measurement covariance matrix.

  • **kwargs (dict) – Additional parameters (e.g., R_gps).

class opengnc.navigation.OrbitDeterminationEKF(x0: ndarray, p0: ndarray, q_mat: ndarray, r_mat: ndarray, use_j2: bool = True, mu: float = 398600441800000.0, re: float = 6378137.0)[source]

Bases: object

Extended Kalman Filter for Orbit Determination (OD-EKF).

Estimates the 6D Cartesian state $mathbf{x} = [mathbf{r}, mathbf{v}]^T$ in the ECI frame. Supports multi-model dynamics (Two-body, J2) and RK4-based state prediction.

Parameters:
  • x0 (np.ndarray) – Initial state vector $[r_x, r_y, r_z, v_x, v_y, v_z]$ (m, m/s).

  • p0 (np.ndarray) – Initial $6times 6$ estimation error covariance matrix.

  • q_mat (np.ndarray) – Process noise covariance matrix $mathbf{Q} in mathbb{R}^{6times 6}$.

  • r_mat (np.ndarray) – Measurement noise covariance matrix $mathbf{R} in mathbb{R}^{3times 3}$.

  • use_j2 (bool, optional) – Whether to include J2 perturbations. Default is True.

  • mu (float, optional) – Gravitational parameter ($m^3/s^2$).

  • re (float, optional) – Earth radius (m).

property covariance: ndarray

Estimation error covariance matrix $mathbf{P}$.

predict(dt: float) None[source]

Perform EKF prediction step ($x^-, P^-$).

Parameters:

dt (float) – Step size (s).

property state: ndarray

Estimated orbit state vector $[r, v]^T$.

update(z_pos: ndarray) None[source]

Update state estimate using position measurement $mathbf{z} = mathbf{r} + nu$.

Parameters:

z_pos (np.ndarray) – ECI Position measurement (m).

class opengnc.navigation.RelativeNavigationEKF(x0: ndarray, p0: ndarray, q_mat: ndarray, r_mat: ndarray, mean_motion: float)[source]

Bases: object

Relative Navigation EKF via Clohessy-Wiltshire (Hill) Dynamics.

Estimates the 6D relative state $delta mathbf{x} = [delta mathbf{r}, delta mathbf{v}]^T$ in the Hill (RSW) frame. Assumes a circular target orbit.

Parameters:
  • x0 (np.ndarray) – Initial relative state $[x, y, z, dot{x}, dot{y}, dot{z}]^T$ (m, m/s).

  • p0 (np.ndarray) – Initial estimation covariance ($6times 6$).

  • q_mat (np.ndarray) – Process noise covariance ($6times 6$).

  • r_mat (np.ndarray) – Measurement noise covariance ($3times 3$).

  • mean_motion (float) – Target mean motion $n = sqrt{mu/a^3}$ (rad/s).

predict(dt: float) None[source]

Predict relative state using the analytical CW transition matrix $Phi(t)$.

Parameters:

dt (float) – Predict step (s).

property state: ndarray

Estimated relative state $[delta mathbf{r}, delta mathbf{v}]^T$.

update(z_rel_pos: ndarray) None[source]

Update estimate using a 3D relative position measurement.

Parameters:

z_rel_pos (np.ndarray) – Relative position vector in Hill frame (m).

class opengnc.navigation.SurfaceNavigationEKF(x0: ndarray, p0: ndarray, q_mat: ndarray, r_mat: ndarray)[source]

Bases: object

Surface Navigation EKF for Landers or Rovers.

Estimates 6D state $mathbf{x} = [mathbf{r}, mathbf{v}]^T$ in a local surface-fixed frame using constant acceleration kinematics and landmark observations.

Parameters:
  • x0 (np.ndarray) – Initial state $[x, y, z, v_x, v_y, v_z]^T$ (m, m/s).

  • p0 (np.ndarray) – Initial estimation error covariance ($6times 6$).

  • q_mat (np.ndarray) – Process noise covariance ($6times 6$).

  • r_mat (np.ndarray) – Measurement noise covariance for relative landmark tracking ($3times 3$).

predict(dt: float, accel: ndarray | None = None) None[source]

Perform kinematic state prediction.

Parameters:
  • dt (float) – Propagation step (s).

  • accel (np.ndarray, optional) – IMU acceleration or commanded thrust (m/s^2).

property state: ndarray

Estimated 6D rover state vector.

update_landmark(z_obs: ndarray, landmark_pos: ndarray) None[source]

Update state using an observed relative vector to a known landmark.

Measurement model: $mathbf{z} = mathbf{r}_{land} - mathbf{r}_{Rover} + nu$.

Parameters:
  • z_obs (np.ndarray) – Measured relative vector (m).

  • landmark_pos (np.ndarray) – Known coordinates of the landmark (m).

opengnc.navigation.gauss_iod(rho_hat1: ndarray, rho_hat2: ndarray, rho_hat3: ndarray, t1: float, t2: float, t3: float, r_obs1: ndarray, r_obs2: ndarray, r_obs3: ndarray, mu: float = 398600441500000.0) ndarray[source]

Angles-only IOD via Gauss method with iterative refinement.

Solves for slant ranges using an 8th-order polynomial and performs iterative refinement using Herrick-Gibbs for stability.

Parameters:
  • rho_hat1 (np.ndarray) – Line-of-Sight unit vectors in ECI.

  • rho_hat2 (np.ndarray) – Line-of-Sight unit vectors in ECI.

  • rho_hat3 (np.ndarray) – Line-of-Sight unit vectors in ECI.

  • t1 (float) – Observation times (s).

  • t2 (float) – Observation times (s).

  • t3 (float) – Observation times (s).

  • r_obs1 (np.ndarray) – Observer position vectors in ECI (m).

  • r_obs2 (np.ndarray) – Observer position vectors in ECI (m).

  • r_obs3 (np.ndarray) – Observer position vectors in ECI (m).

  • mu (float, optional) – Gravitational parameter ($m^3/s^2$).

Returns:

ECI State vector $[r, v]$ at $t_2$ (m, m/s).

Return type:

np.ndarray

opengnc.navigation.gibbs_iod(r1: ndarray, r2: ndarray, r3: ndarray, mu: float = 398600441500000.0) ndarray[source]

Initial Orbit Determination (IOD) via Gibbs method.

Suitable for three position vectors with angular separation > 5 degrees. Formula: $mathbf{v}_2 = sqrt{frac{mu}{N D}} left( frac{mathbf{D} times mathbf{r}_2}{r_2} + mathbf{S} right)$.

Parameters:
  • r1 (np.ndarray) – ECI position vectors (m) at three distinct times.

  • r2 (np.ndarray) – ECI position vectors (m) at three distinct times.

  • r3 (np.ndarray) – ECI position vectors (m) at three distinct times.

  • mu (float, optional) – Gravitational parameter ($m^3/s^2$). Default is Earth.

Returns:

Velocity vector at the second observation time $mathbf{v}_2$ (m/s).

Return type:

np.ndarray

opengnc.navigation.herrick_gibbs_iod(r1: ndarray, r2: ndarray, r3: ndarray, dt21: float, dt32: float, mu: float = 398600441500000.0) ndarray[source]

Initial Orbit Determination via Herrick-Gibbs method.

Best for short-arc observations (angular separation < 5 degrees).

Parameters:
  • r1 (np.ndarray) – ECI position vectors (m).

  • r2 (np.ndarray) – ECI position vectors (m).

  • r3 (np.ndarray) – ECI position vectors (m).

  • dt21 (float) – Time interval $t_2 - t_1$ (s).

  • dt32 (float) – Time interval $t_3 - t_2$ (s).

  • mu (float, optional) – Gravitational parameter ($m^3/s^2$).

Returns:

Velocity vector $mathbf{v}_2$ (m/s).

Return type:

np.ndarray

opengnc.navigation.laplace_iod(rho_hat: ndarray, rho_dot: ndarray, rho_ddot: ndarray, r_obs: ndarray, v_obs: ndarray, a_obs: ndarray, mu: float = 398600441500000.0) ndarray[source]

Orbit determination from line-of-sight derivatives (Laplace method).

Parameters:
  • rho_hat (np.ndarray) – LOS unit vector and its first/second time derivatives.

  • rho_dot (np.ndarray) – LOS unit vector and its first/second time derivatives.

  • rho_ddot (np.ndarray) – LOS unit vector and its first/second time derivatives.

  • r_obs (np.ndarray) – Observer Cartesian state and acceleration at epoch.

  • v_obs (np.ndarray) – Observer Cartesian state and acceleration at epoch.

  • a_obs (np.ndarray) – Observer Cartesian state and acceleration at epoch.

  • mu (float, optional) – Gravitational parameter ($m^3/s^2$).

Returns:

ECI State vector $[r, v]$ at epoch.

Return type:

np.ndarray

opengnc.navigation.laplace_iod_from_observations(rho_hats: list[ndarray], rs_obs: list[ndarray], times: list[float], mu: float = 398600441500000.0) ndarray[source]

Perform Laplace IOD from three standard LOS observations.

Estimates derivatives using Lagrange interpolation.

Parameters:
  • rho_hats (List[np.ndarray]) – Three LOS unit vectors.

  • rs_obs (List[np.ndarray]) – Three observer position vectors.

  • times (List[float]) – Three observation timestamps.

  • mu (float, optional) – Gravitational parameter.

Returns:

State vector at $t_2$ (6,) (m, m/s).

Return type:

np.ndarray

opengnc.navigation.map_relative_localization_update(x_state: ndarray, p_cov: ndarray, matches: list[tuple[ndarray, ndarray]], r_noise: ndarray) tuple[ndarray, ndarray][source]

EKF Measurement Update using TRN feature matches.

Corrects the global state estimate using residuals between map-known landmarks and their estimated positions.

Parameters:
  • x_state (np.ndarray) – Current filter state $[mathbf{r}, …]^T$.

  • p_cov (np.ndarray) – Estimation covariance matrix.

  • matches (List[Tuple[np.ndarray, np.ndarray]]) – Landmark correspondences from match_features.

  • r_noise (np.ndarray) – Sensor noise covariance ($3times 3$).

Returns:

  • updated_x (np.ndarray) – Updated state estimate.

  • updated_p (np.ndarray) – Updated covariance matrix.