opengnc.guidance package

Submodules

opengnc.guidance.attitude_guidance module

Attitude guidance laws for Nadir, Sun, and Target pointing, and trajectory planning.

opengnc.guidance.attitude_guidance.attitude_blending(q1: ndarray, q2: ndarray, alpha: float) ndarray[source]

SLERP (Spherical Linear Interpolation) between two orientation quaternions.

Parameters:
  • q1 (np.ndarray) – First quaternion [x, y, z, w].

  • q2 (np.ndarray) – Second quaternion [x, y, z, w].

  • alpha (float) – Blending factor [0, 1].

Returns:

Blended/interpolated quaternion [x, y, z, w].

Return type:

np.ndarray

opengnc.guidance.attitude_guidance.eigenaxis_slew_path_planning(q_initial: ndarray, q_final: ndarray, time_span: ndarray) list[ndarray][source]

Generate an eigenaxis slew profile using Spherical Linear Interpolation (SLERP).

Parameters:
  • q_initial (np.ndarray) – Initial quaternion [x, y, z, w].

  • q_final (np.ndarray) – Final quaternion [x, y, z, w].

  • time_span (np.ndarray) – Normalized time values [0, 1] (N,).

Returns:

List of interpolated quaternions along the path.

Return type:

list[np.ndarray]

opengnc.guidance.attitude_guidance.nadir_pointing_reference(pos_eci: ndarray, vel_eci: ndarray) ndarray[source]

Generate a reference quaternion for Nadir pointing.

The target frame is defined as: - Z-axis: Points towards Earth center (Nadir). - Y-axis: Aligned with the negative of the orbit normal. - X-axis: Completes the right-handed frame (approximately velocity direction).

Parameters:
  • pos_eci (np.ndarray) – ECI position vector [m] (3,).

  • vel_eci (np.ndarray) – ECI velocity vector [m/s] (3,).

Returns:

Reference quaternion [x, y, z, w].

Return type:

np.ndarray

opengnc.guidance.attitude_guidance.sun_pointing_reference(sun_vec_eci: ndarray) ndarray[source]

Generate a reference quaternion for Sun pointing.

Primary objective is to align the spacecraft body X-axis with the Sun vector. Secondary objective is to minimize rotation about the Sun vector.

Parameters:

sun_vec_eci (np.ndarray) – ECI Sun direction vector (3,).

Returns:

Reference quaternion [x, y, z, w].

Return type:

np.ndarray

opengnc.guidance.attitude_guidance.target_tracking_reference(pos_eci: ndarray, target_pos_eci: ndarray) ndarray[source]

Generate a reference quaternion to track a target position.

The target frame is defined with the Z-axis aligned with the boresight (towards target).

Parameters:
  • pos_eci (np.ndarray) – ECI position vector of the spacecraft [m] (3,).

  • target_pos_eci (np.ndarray) – ECI position vector of the target [m] (3,).

Returns:

Reference quaternion [x, y, z, w].

Return type:

np.ndarray

opengnc.guidance.continuous_thrust module

Continuous thrust guidance laws including Q-law and ZEM/ZEV feedback.

opengnc.guidance.continuous_thrust.apollo_dps_guidance(t_go: float, pos: ndarray, vel: ndarray, pos_t: ndarray, vel_t: ndarray, accel_t: ndarray, gravity: ndarray | None = None) ndarray[source]

E-guidance (Apollo Descent Propulsion System style).

A polynomial guidance law targeting specific state and acceleration conditions.

Parameters:
  • t_go (float) – Time-to-go (s).

  • pos (np.ndarray) – Current position (m).

  • vel (np.ndarray) – Current velocity (m/s).

  • pos_t (np.ndarray) – Target position (m).

  • vel_t (np.ndarray) – Target velocity (m/s).

  • accel_t (np.ndarray) – Target acceleration (m/s^2).

  • gravity (np.ndarray, optional) – Local gravity acceleration (m/s^2).

Returns:

Commanded acceleration vector (m/s^2).

Return type:

np.ndarray

opengnc.guidance.continuous_thrust.direct_collocation_guidance(r0: ndarray, v0: ndarray, rf: ndarray, vf: ndarray, tf: float, mu: float, n_nodes: int = 20) ndarray | None[source]

Solve optimal transfer using Trapezoidal Direct Collocation.

This method discretizes the trajectory into n_nodes and solves for the state and control (acceleration) at each node, subject to dynamic and boundary constraints. The objective is to minimize the sum of acceleration squared (control effort proxy).

Parameters:
  • r0 (np.ndarray) – Initial state vectors (3,).

  • v0 (np.ndarray) – Initial state vectors (3,).

  • rf (np.ndarray) – Final target state vectors (3,).

  • vf (np.ndarray) – Final target state vectors (3,).

  • tf (float) – Fixed transfer time (s).

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

  • n_nodes (int, optional) – Number of discretization nodes. Default is 20.

Returns:

Optimized nodes of shape (n_nodes, 9) containing [r, v, a] at each node. Returns None if optimization fails.

Return type:

Optional[np.ndarray]

opengnc.guidance.continuous_thrust.gravity_turn_guidance(vel: ndarray, accel_mag: float, mode: str = 'descent') ndarray[source]

Gravity turn steering law.

Thrust is aligned with the velocity vector to minimize gravity losses and pointing errors during ascent or descent.

Parameters:
  • vel (np.ndarray) – Current velocity vector (m/s).

  • accel_mag (float) – Thrust acceleration magnitude to apply (m/s^2).

  • mode (str, optional) – ‘descent’ (anti-parallel to vel) or ‘ascent’ (parallel to vel).

Returns:

Thrust acceleration vector (m/s^2).

Return type:

np.ndarray

opengnc.guidance.continuous_thrust.indirect_optimal_guidance(r0: ndarray, v0: ndarray, rf: ndarray, vf: ndarray, tf: float, mu: float) tuple[ndarray | None, ndarray | None][source]

Solve minimum-energy transfer using Pontryagin’s Minimum Principle (PMP).

Numerical solution of the indirect optimal control problem formulated as a Boundary Value Problem (BVP). The objective is to minimize the integral of the square of the acceleration magnitude (control effort).

Parameters:
  • r0 (np.ndarray) – Initial position and velocity vectors (3,).

  • v0 (np.ndarray) – Initial position and velocity vectors (3,).

  • rf (np.ndarray) – Target position and velocity vectors (3,).

  • vf (np.ndarray) – Target position and velocity vectors (3,).

  • tf (float) – Transfer time (s).

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

Returns:

  • Time array (N,) if successful, else None.

  • Optimal acceleration profile (3, N) if successful, else None.

Return type:

Tuple[Optional[np.ndarray], Optional[np.ndarray]]

opengnc.guidance.continuous_thrust.q_law_guidance(r_eci: ndarray, v_eci: ndarray, target_oe: ndarray, mu: float, accel_max: float, weights: ndarray | None = None) ndarray[source]

Lyapunov-based Q-law guidance for low-thrust orbit transfers.

Targets the primary Keplerian elements $[a, e, i, Omega, omega]$ by minimizing a Lyapunov function based on proximity to target elements.

Parameters:
  • r_eci (np.ndarray) – Position vector in ECI frame [m] (3,).

  • v_eci (np.ndarray) – Velocity vector in ECI frame [m/s] (3,).

  • target_oe (np.ndarray) – Target Keplerian elements $[a, e, i, Omega, omega]$ (5,). Units should be consistent (m for semi-major axis, rad for angles).

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

  • accel_max (float) – Maximum thrust acceleration magnitude available (m/s^2).

  • weights (np.ndarray, optional) – Weights for each orbital element in the Q function (5,). If None, default weights are applied.

Returns:

Optimal thrust acceleration vector in ECI frame (m/s^2).

Return type:

np.ndarray

opengnc.guidance.continuous_thrust.zem_zev_guidance(pos: ndarray, vel: ndarray, pos_target: ndarray, vel_target: ndarray, t_go: float, gravity: ndarray | None = None) ndarray[source]

Zero-Effort Miss (ZEM) and Zero-Effort Velocity (ZEV) feedback guidance.

Commonly used for terminal intercept, rendezvous, or planetary landing.

Parameters:
  • pos (np.ndarray) – Current position vector (m).

  • vel (np.ndarray) – Current velocity vector (m/s).

  • pos_target (np.ndarray) – Target position vector (m).

  • vel_target (np.ndarray) – Target velocity vector (m/s).

  • t_go (float) – Time-to-go until intercept or landing (s).

  • gravity (np.ndarray, optional) – Local gravity acceleration vector (m/s^2). Default is zero.

Returns:

Commanded acceleration vector (m/s^2).

Return type:

np.ndarray

opengnc.guidance.formation_flying module

Formation Flying Control routines (Virtual Structure, Leader-Follower, Fuel-Balanced, and Distributed Consensus).

opengnc.guidance.formation_flying.distributed_consensus_control(states: ndarray, laplacian_matrix: ndarray, gains: ndarray) ndarray[source]

Compute consensus control for a distributed multi-agent system.

Uses the graph Laplacian matrix to drive agents towards a common state through local interactions only. $u_i = -K sum_{j} a_{ij} (x_i - x_j)$

Parameters:
  • states (np.ndarray) – (N, M) array of states for N agents.

  • laplacian_matrix (np.ndarray) – (N, N) graph Laplacian matrix ($L = D - A$).

  • gains (np.ndarray) – Gains applied to the consensus error protocol.

Returns:

(N, M) array of control inputs.

Return type:

np.ndarray

opengnc.guidance.formation_flying.fuel_balanced_formation_keeping(states: ndarray, fuel_levels: ndarray, base_weights: ndarray) ndarray[source]

Distribute control effort among formation to balance fuel consumption.

Spacecraft with higher fuel levels are assigned a larger proportion of the control effort to equalize fuel mass across the ensemble over time.

Parameters:
  • states (np.ndarray) – (N x M) array of states for N spacecraft.

  • fuel_levels (np.ndarray) – (N,) array of current fuel mass or percentages.

  • base_weights (np.ndarray) – (N, M) base control actions or priority weights.

Returns:

Fuel-balanced control actions.

Return type:

np.ndarray

opengnc.guidance.formation_flying.leader_follower_control(leader_state: ndarray, follower_state: ndarray, desired_relative_state: ndarray, gains: ndarray) ndarray[source]

Compute control command for a follower to maintain offset from a leader.

Parameters:
  • leader_state (np.ndarray) – State of the leader spacecraft.

  • follower_state (np.ndarray) – State of the follower spacecraft.

  • desired_relative_state (np.ndarray) – Target offset of follower from leader (follower_target - leader).

  • gains (np.ndarray) – Control feedback gains.

Returns:

Control command for the follower.

Return type:

np.ndarray

opengnc.guidance.formation_flying.virtual_structure_control(state_actual: ndarray, state_desired: ndarray, gains: ndarray) ndarray[source]

Compute control inputs to track a virtual structure formation.

Parameters:
  • state_actual (np.ndarray) – Current states of the spacecraft ensemble (N x state_dim).

  • state_desired (np.ndarray) – Desired states derived from the virtual structure (N x state_dim).

  • gains (np.ndarray) – Feedback gains (Proportional/Derivative or state-feedback).

Returns:

Computed control actions for each spacecraft (N x control_dim).

Return type:

np.ndarray

opengnc.guidance.maneuvers module

Orbital maneuver calculations (Hohmann, Bi-elliptic, Phasing, Plane Change).

opengnc.guidance.maneuvers.bi_elliptic_transfer(r1: float, r2: float, rb: float, mu: float = 398600.4418) tuple[float, float, float, float][source]

Calculate Bi-Elliptic transfer $Delta V$ and time.

More efficient than Hohmann if $r_2/r_1 > 15.58$.

Parameters:
  • r1 (float) – Initial radius (km).

  • r2 (float) – Final radius (km).

  • rb (float) – Intermediate apogee radius (km).

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

Returns:

(dv1, dv2, dv3, total_time).

Return type:

tuple[float, float, float, float]

opengnc.guidance.maneuvers.combined_plane_change(v1: float, v2: float, delta_i: float) float[source]

Calculate Delta-V for a combined maneuver (velocity magnitude + inclination).

Parameters:
  • v1 (float) – Initial velocity magnitude (km/s).

  • v2 (float) – Final velocity magnitude (km/s).

  • delta_i (float) – Plane change angle (radians).

Returns:

Delta-V required (km/s).

Return type:

float

opengnc.guidance.maneuvers.delta_v_budget(initial_mass: float, dv_total: float, isp: float) float[source]

Calculate required propellant mass using the Tsiolkovsky rocket equation.

Parameters:
  • initial_mass (float) – Initial mass of the spacecraft (kg).

  • dv_total (float) – Total Delta-V required (km/s).

  • isp (float) – Specific impulse of the propulsion system (s).

Returns:

Propellant mass required (kg).

Return type:

float

opengnc.guidance.maneuvers.hohmann_transfer(r1: float, r2: float, mu: float = 398600.4418) tuple[float, float, float][source]

Calculate Hohmann transfer $Delta V$ and time of flight.

Equations: - $Delta V_1 = sqrt{frac{mu}{r_1}} left( sqrt{frac{2r_2}{r_1+r_2}} - 1 right)$ - $Delta V_2 = sqrt{frac{mu}{r_2}} left( 1 - sqrt{frac{2r_1}{r_1+r_2}} right)$ - $t_{trans} = pi sqrt{frac{(r_1+r_2)^3}{8mu}}$

Parameters:
  • r1 (float) – Initial circular radius (km).

  • r2 (float) – Final circular radius (km).

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

Returns:

(dv1, dv2, time_of_flight) in km/s and s.

Return type:

tuple[float, float, float]

opengnc.guidance.maneuvers.optimal_combined_maneuver(r1: float, r2: float, delta_i: float, mu: float = 398600.4418) tuple[float, float, float][source]

Find optimal split of inclination change between two burns of a Hohmann transfer.

Minimizes total Delta-V by balancing the plane change between higher and lower velocity points.

Parameters:
  • r1 (float) – Initial circular orbit radius (km).

  • r2 (float) – Final circular orbit radius (km).

  • delta_i (float) – Total inclination change (radians).

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

Returns:

  • dv_total: Minimum total Delta-V (km/s).

  • di1: Inclination change at first burn (radians).

  • di2: Inclination change at second burn (radians).

Return type:

tuple[float, float, float]

opengnc.guidance.maneuvers.phasing_maneuver(a: float, t_phase: float, mu: float = 398600.4418) tuple[float, float][source]

Calculate Delta-V required for an orbital phasing maneuver.

Parameters:
  • a (float) – Semi-major axis of the current circular orbit (km).

  • t_phase (float) – Desired time difference to generate (s). Positive to wait (increase period), negative to catch up.

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

Returns:

  • total_dv: Total Delta-V (entry + exit) (km/s).

  • t_wait: Duration of the phasing orbit (s).

Return type:

tuple[float, float]

opengnc.guidance.maneuvers.plane_change(v_mag: float, delta_i: float) float[source]

Calculate Delta-V for a simple inclination plane change maneuver.

Parameters:
  • v_mag (float) – Current velocity magnitude (km/s).

  • delta_i (float) – Plane change angle (radians).

Returns:

Delta-V required (km/s).

Return type:

float

opengnc.guidance.maneuvers.raan_change(v_mag: float, inc: float, delta_raan: float) float[source]

Calculate Delta-V for a Right Ascension of Ascending Node (RAAN) change.

Assumes circular orbit and maneuver performed at the poles for max efficiency.

Parameters:
  • v_mag (float) – Orbital velocity (km/s).

  • inc (float) – Inclination (radians).

  • delta_raan (float) – Desired RAAN change (radians).

Returns:

Delta-V required (km/s).

Return type:

float

opengnc.guidance.porkchop module

Porkchop plot grid generation for interplanetary transfers.

opengnc.guidance.porkchop.generate_porkchop_grid(departure_dates: ndarray | list[float], arrival_dates: ndarray | list[float], r_dep_func: Callable[[float], ndarray], v_dep_func: Callable[[float], ndarray], r_arr_func: Callable[[float], ndarray], v_arr_func: Callable[[float], ndarray], mu: float = 398600.4418) dict[str, ndarray | list[float]][source]

Generate a grid of C3 and V-infinity values for interplanetary transfers.

Computes a ‘porkchop’ plot grid by solving Lambert’s problem for every combination of departure and arrival dates.

Parameters:
  • departure_dates (array-like) – List or array of departure times (e.g., seconds from J2000).

  • arrival_dates (array-like) – List or array of arrival times (e.g., seconds from J2000).

  • r_dep_func (Callable) – Function returning the planet’s position vector [3] at departure time t.

  • v_dep_func (Callable) – Function returning the planet’s velocity vector [3] at departure time t.

  • r_arr_func (Callable) – Function returning the destination’s position vector [3] at arrival time t.

  • v_arr_func (Callable) – Function returning the destination’s velocity vector [3] at arrival time t.

  • mu (float, optional) – Gravitational parameter of the central body. Default is Earth.

Returns:

Dictionary containing: - ‘departure_dates’: Copy of departure axes. - ‘arrival_dates’: Copy of arrival axes. - ‘c3’: (N_arr, N_dep) grid of Launch C3 values ($km^2/s^2$). - ‘v_inf_arr’: (N_arr, N_dep) grid of Arrival V-infinity ($km/s$). - ‘tof’: (N_arr, N_dep) grid of Time-of-flight (s).

Return type:

Dict

opengnc.guidance.rendezvous module

Rendezvous and Proximity Operations (RPO) guidance (Lambert, Clohessy-Wiltshire).

opengnc.guidance.rendezvous.cw_equations(r0: ndarray, v0: ndarray, n_mean: float, time: float) tuple[ndarray, ndarray][source]

Propagate relative state via Clohessy-Wiltshire (CW) equations.

The CW equations describe the relative motion of a deputy spacecraft with respect to a chief spacecraft in a circular orbit.

The position components are given by: $x(t) = (4 - 3cos(nt))x_0 + frac{sin(nt)}{n}dot{x}_0 + frac{2(1-cos(nt))}{n}dot{y}_0$ $y(t) = 6(sin(nt) - nt)x_0 + y_0 + frac{2(cos(nt)-1)}{n}dot{x}_0 + (frac{4sin(nt)}{n} - 3t)dot{y}_0$ $z(t) = cos(nt)z_0 + frac{sin(nt)}{n}dot{z}_0$

Parameters:
  • r0 (np.ndarray) – Initial relative position [x, y, z] in LVLH frame (km). x: Radial, y: Along-track, z: Cross-track.

  • v0 (np.ndarray) – Initial relative velocity [vx, vy, vz] in LVLH frame (km/s).

  • n_mean (float) – Mean motion of the target orbit (rad/s).

  • time (float) – Time interval to propagate (s).

Returns:

  • r_tnp.ndarray

    Relative position at time t (km).

  • v_tnp.ndarray

    Relative velocity at time t (km/s).

Return type:

tuple[np.ndarray, np.ndarray]

opengnc.guidance.rendezvous.cw_targeting(r0: ndarray, r_target: ndarray, time: float, n_mean: float) ndarray[source]

Calculate required initial velocity to reach a target position in time t.

Uses a two-impulse rendezvous first-burn logic within CW framework.

Parameters:
  • r0 (np.ndarray) – Initial relative position [x, y, z] (km).

  • r_target (np.ndarray) – Target relative position at time t [x, y, z] (km).

  • time (float) – Transfer time (s).

  • n_mean (float) – Mean motion of target orbit (rad/s).

Returns:

Required initial relative velocity v0 (km/s).

Return type:

np.ndarray

opengnc.guidance.rendezvous.is_within_corridor(r_rel: ndarray, axis: ndarray, cone_angle_deg: float) bool[source]

Check if the chaser is within a safe approach corridor (cone).

Parameters:
  • r_rel (np.ndarray) – Relative position vector (Chaser - Target).

  • axis (np.ndarray) – Direction of the corridor axis (e.g., -VBAR or -RBAR).

  • cone_angle_deg (float) – Half-angle of the approach cone (degrees).

Returns:

True if inside the corridor.

Return type:

bool

opengnc.guidance.rendezvous.optimize_rpo_collocation(r0: ndarray, v0: ndarray, rf: ndarray, vf: ndarray, dt: float, n_nodes: int = 10) dict[source]

Optimize a rendezvous trajectory using Hermite-Simpson collocation.

Minimizes total control effort (integral of acceleration squared).

Parameters:
  • r0 (np.ndarray) – Initial state.

  • v0 (np.ndarray) – Initial state.

  • rf (np.ndarray) – Final state.

  • vf (np.ndarray) – Final state.

  • dt (float) – Transfer time (s).

  • n_nodes (int, optional) – Number of collocation nodes. Default is 10.

Returns:

Optimized control profile and success status.

Return type:

dict

opengnc.guidance.rendezvous.primer_vector_analysis(r0: ndarray, v0: ndarray, rf: ndarray, vf: ndarray, dt: float, mu: float = 398600.4418) dict[source]

Evaluate the optimality of a two-impulse Lambert transfer using Primer Vector Theory.

Parameters:
  • r0 (np.ndarray) – Initial position vector.

  • v0 (np.ndarray) – Initial velocity vector.

  • rf (np.ndarray) – Final position vector.

  • vf (np.ndarray) – Final velocity vector.

  • dt (float) – Transfer time (s).

  • mu (float, optional) – Gravitational parameter.

Returns:

Optimality results including primer magnitudes and necessary flags.

Return type:

dict

opengnc.guidance.rendezvous.solve_lambert(r1: ndarray, r2: ndarray, dt: float, mu: float = 398600.4418, tm: int = 1) tuple[ndarray, ndarray][source]

Solve Lambert’s problem using a Universal Variable formulation.

Finds the required velocities at the initial and final positions for a given time of flight.

Parameters:
  • r1 (np.ndarray) – Initial position vector (km).

  • r2 (np.ndarray) – Final position vector (km).

  • dt (float) – Time of flight (s).

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

  • tm (int, optional) – Transfer mode (+1 for short way, -1 for long way). Default is +1.

Returns:

  • v1: Velocity vector at r1 (km/s).

  • v2: Velocity vector at r2 (km/s).

Return type:

tuple[np.ndarray, np.ndarray]

Raises:

ValueError – If the transfer angle is 180 degrees (singularity).

opengnc.guidance.rendezvous.solve_lambert_multi_rev(r1: ndarray, r2: ndarray, dt: float, mu: float = 398600.4418, n_rev: int = 0, branch: str = 'left') tuple[ndarray, ndarray][source]

Solve Lambert’s problem for N >= 0 revolutions using Izzo’s approach.

Parameters:
  • r1 (np.ndarray) – Initial position vector (km).

  • r2 (np.ndarray) – Final position vector (km).

  • dt (float) – Time of flight (s).

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

  • n_rev (int, optional) – Number of full revolutions (N >= 0). Default is 0.

  • branch (str, optional) – ‘left’ or ‘right’ branch for N > 0. Default is ‘left’.

Returns:

Velocity vectors v1, v2 (km/s).

Return type:

tuple[np.ndarray, np.ndarray]

Raises:
  • ValueError – If convergence fails for multi-rev transfer.

  • NotImplementedError – If velocity recovery for N > 0 is requested (currently pending implementation).

opengnc.guidance.rendezvous.tschauner_hempel_propagation(x0: ndarray, oe_target: tuple, dt: float, mu: float = 398600.4418) ndarray[source]

Propagate relative state using Tschauner-Hempel equations for elliptical orbits.

Computes the exact linear mapping using a numerical formulation of the Yamanaka-Ankersen State Transition Matrix (STM).

Parameters:
  • x0 (np.ndarray) – Initial relative state [x, y, z, vx, vy, vz] in LVLH (km, km/s).

  • oe_target (tuple) – Target orbital elements (a, e, i, raan, argp, nu0).

  • dt (float) – Time interval to propagate (s).

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

Returns:

Final relative state at time dt.

Return type:

np.ndarray

Module contents