ADCS.orbits.orbital_state module¶
- class ADCS.orbits.orbital_state.Orbital_State(ephem, J2000, R, V, S=None, B=None, rho=None, density_model=None, fast=False)[source]¶
Bases:
objectComplete dynamical and environmental representation of a spacecraft orbital state.
The state is defined by inertial position and velocity in the ECI/ICRF frame at an epoch expressed in J2000 centuries. The class also stores commonly-used derived quantities and environment vectors, including Earth-fixed coordinates, Sun vector, geomagnetic field vector (IGRF), atmospheric density, and frame transforms.
Notes
The
fastargument is accepted for backward compatibility but is ignored: this implementation always computes real Sun and geomagnetic field vectors and frame transforms.- Parameters:
ephem (Ephemeris) – Ephemeris object used for Earth and Sun position queries. If
None, a newEphemerisis constructed.J2000 (float) – Epoch in Julian centuries since J2000.
R (numpy.ndarray) – Position vector in ECI frame [km].
V (numpy.ndarray) – Velocity vector in ECI frame [km/s].
S (numpy.ndarray or None) – Optional Sun position vector in ECI frame [km]. If
None, it is computed.B (numpy.ndarray or None) – Optional geomagnetic field vector in ECI frame [T]. If
None, it is computed.rho (float or None) – Optional atmospheric density [kg/m^3]. If
None, it is computed usingDensityModel.density_model (DensityModel or None) – Atmospheric density interpolation model. If
None, a newDensityModelis constructed.fast (bool) – Backward-compatible parameter (ignored). Real environment vectors are always computed.
- classmethod from_dict(d, ephem, density_model=None, fast=True)[source]¶
Construct an orbital state from a dictionary.
Notes
The
fastargument is accepted for backward compatibility but is ignored.- Parameters:
d (dict) – Dictionary containing orbital state fields.
ephem (Ephemeris) – Ephemeris object.
density_model (DensityModel or None) – Atmospheric density model.
fast (bool) – Backward-compatible parameter (ignored).
- Returns:
Reconstructed orbital state.
- Return type:
- average(orbital_state_2, ratio=0.5, fast=False)[source]¶
Linearly interpolate between two orbital states.
- Parameters:
orbital_state_2 (Orbital_State) – Second orbital state.
ratio (float) – Interpolation ratio in [0, 1].
fast (bool) – Backward-compatible parameter (ignored).
- Returns:
Interpolated orbital state.
- Return type:
- copy()[source]¶
Return a deep copy of the orbital state.
This implementation avoids recomputing environment vectors and frame transforms.
- Returns:
Independent copy of the orbital state.
- Return type:
- ecef_to_eci(vec)[source]¶
Transform a vector from ECEF to ECI coordinates.
- Parameters:
vec (numpy.ndarray) – Vector in ECEF frame.
- Returns:
Vector in ECI frame.
- Return type:
numpy.ndarray
- ecef_to_geocentric(vec)[source]¶
Transform an ECEF vector to local geocentric coordinates.
- Parameters:
vec (numpy.ndarray) – Vector in ECEF frame.
- Returns:
Vector in geocentric basis.
- Return type:
numpy.ndarray
- eci_to_ecef(vec)[source]¶
Transform a vector from ECI to ECEF coordinates.
- Parameters:
vec (numpy.ndarray) – Vector in ECI frame.
- Returns:
Vector in ECEF frame.
- Return type:
numpy.ndarray
- eci_to_enu(vec)[source]¶
Transform a vector from ECI to local ENU frame.
- Parameters:
vec (numpy.ndarray) – Vector in ECI frame.
- Returns:
Vector in ENU frame.
- Return type:
numpy.ndarray
- enu_to_eci(vec)[source]¶
Transform a vector from ENU to ECI frame.
- Parameters:
vec (numpy.ndarray) – Vector in ENU frame.
- Returns:
Vector in ECI frame.
- Return type:
numpy.ndarray
- geocentric_to_ecef(vec)[source]¶
Transform a geocentric vector to ECEF coordinates.
- Parameters:
vec (numpy.ndarray) – Vector in geocentric basis.
- Returns:
Vector in ECEF frame.
- Return type:
numpy.ndarray
- get_b_eci()[source]¶
Compute the geomagnetic field vector in the ECI frame.
- Returns:
Magnetic field vector [Tesla].
- Return type:
numpy.ndarray
- get_state_vector(x)[source]¶
Retrieve cached or updated body-frame vectors.
- Parameters:
x (numpy.ndarray or None) – Current spacecraft state vector.
- Returns:
Dictionary of vectors and derivatives.
- Return type:
dict[str, numpy.ndarray]
- get_sun_eci()[source]¶
Compute the Sun position vector in the ECI frame.
- Returns:
Sun vector in ECI coordinates [km].
- Return type:
numpy.ndarray
- is_sunlit()[source]¶
Determine whether the spacecraft is illuminated by the Sun.
- Returns:
Trueif sunlit,Falseotherwise.- Return type:
bool
- j2000_to_tai()[source]¶
Convert J2000 centuries to TAI Julian date.
- Returns:
TAI Julian date.
- Return type:
float
- orbit_dynamics(J2_perturbation_on=True)[source]¶
Compute translational orbital dynamics at the current state.
- Parameters:
J2_perturbation_on (bool) – Enable J2 perturbation.
- Returns:
Time derivatives of position and velocity.
- Return type:
tuple[numpy.ndarray, numpy.ndarray]
- orbit_dynamics_jacobians(J2_perturbation_on=True)[source]¶
Compute Jacobians of the translational dynamics.
- Parameters:
J2_perturbation_on (bool) – Enable J2 perturbation.
- Returns:
Jacobian matrices of the dynamics.
- Return type:
tuple[numpy.ndarray, numpy.ndarray, numpy.ndarray, numpy.ndarray]
- propagate_jacobians(dt, J2_perturbation_on=True)[source]¶
Propagate state transition Jacobians using first-order integration.
- Parameters:
dt (float) – Time step in seconds.
J2_perturbation_on (bool) – Enable J2 perturbation.
- Returns:
State transition Jacobian blocks.
- Return type:
tuple[numpy.ndarray, numpy.ndarray, numpy.ndarray, numpy.ndarray]
- propagate_jacobians_rk4(dt, J2_perturbation_on=True)[source]¶
Propagate state transition Jacobians using RK4 integration.
- Parameters:
dt (float) – Time step in seconds.
J2_perturbation_on (bool) – Enable J2 perturbation.
- Returns:
State transition Jacobian blocks.
- Return type:
tuple[numpy.ndarray, numpy.ndarray, numpy.ndarray, numpy.ndarray]
- propagate_orbit(dt, J2_perturbation_on=True, fast=True)[source]¶
Propagate the orbital state forward using first-order integration.
- Parameters:
dt (float) – Time step in seconds.
J2_perturbation_on (bool) – Enable J2 perturbation.
fast (bool) – Backward-compatible parameter (ignored).
- Returns:
Propagated orbital state.
- Return type:
- propagate_orbit_rk4(dt, J2_perturbation_on=True, fast=True)[source]¶
Propagate the orbital state using fourth-order Runge–Kutta integration.
- Parameters:
dt (float) – Time step in seconds.
J2_perturbation_on (bool) – Enable J2 perturbation.
fast (bool) – Backward-compatible parameter (ignored).
- Returns:
Propagated orbital state.
- Return type: