[][src]Struct nyx_space::dynamics::celestial::CelestialDynamicsStm

pub struct CelestialDynamicsStm<'a> {
    pub state: State,
    pub bodies: Vec<i32>,
    pub stm: Matrix6<f64>,
    pub cosm: Option<&'a Cosm>,
    pub correction: LTCorr,
    // some fields omitted
}

CelestialDynamicsStm provides the equations of motion for any celestial dynamic, with state transition matrix computation.

Fields

state: Statebodies: Vec<i32>stm: Matrix6<f64>cosm: Option<&'a Cosm>correction: LTCorr

Methods

impl<'a> CelestialDynamicsStm<'a>[src]

pub fn new(state: State, bodies: Vec<i32>, cosm: &'a Cosm) -> Self[src]

Initialize third body dynamics given the EXB IDs and a Cosm

pub fn two_body(state: State) -> Self[src]

Initializes a CelestialDynamicsStm which does not simulate the gravity pull of other celestial objects but the primary one.

pub fn as_state(&self) -> State[src]

Provides a copy to the state.

pub fn set_orbital_state(&mut self, new_t: f64, new_state: &Vector6<f64>)[src]

Used only to set the orbital state, useful for Extended Kalman Filters.

pub fn state_ctor(
    &self,
    t: f64,
    in_state: &VectorN<f64, U42>
) -> (State, Matrix6<f64>)
[src]

Rebuild the state and STM from the provided vector

Trait Implementations

impl<'a> AutoDiffDynamics for CelestialDynamicsStm<'a>[src]

type HyperStateSize = U7

Defines the state size of the estimated state

type STMSize = U6

impl<'a> Clone for CelestialDynamicsStm<'a>[src]

impl<'a> Dynamics for CelestialDynamicsStm<'a>[src]

type StateSize = U42

Defines the state size for these dynamics. It must be imported from nalgebra.

type StateType = (State, Matrix6<f64>)

Defines the type which will be published on the propagator channel

fn time(&self) -> f64[src]

Returns the relative time to the propagator. Use prop.dynamics.state.dt for absolute time

fn state(&self) -> Self::StateType[src]

Returns the celestial state and the state transition matrix

impl<'a> Estimable<State> for CelestialDynamicsStm<'a>[src]

type LinStateSize = U6

Defines the state size of the estimated state

fn set_estimated_state(&mut self, new_state: VectorN<f64, Self::LinStateSize>)[src]

Returns the estimated state

Auto Trait Implementations

impl<'a> !RefUnwindSafe for CelestialDynamicsStm<'a>

impl<'a> !Send for CelestialDynamicsStm<'a>

impl<'a> !Sync for CelestialDynamicsStm<'a>

impl<'a> Unpin for CelestialDynamicsStm<'a>

impl<'a> !UnwindSafe for CelestialDynamicsStm<'a>

Blanket Implementations

impl<T> Any for T where
    T: 'static + ?Sized
[src]

impl<T> Borrow<T> for T where
    T: ?Sized
[src]

impl<T> BorrowMut<T> for T where
    T: ?Sized
[src]

impl<T> From<T> for T[src]

impl<T, U> Into<U> for T where
    U: From<T>, 
[src]

impl<T> Same<T> for T

type Output = T

Should always be Self

impl<SS, SP> SupersetOf<SS> for SP where
    SS: SubsetOf<SP>, 

impl<T> ToOwned for T where
    T: Clone
[src]

type Owned = T

The resulting type after obtaining ownership.

impl<T, U> TryFrom<U> for T where
    U: Into<T>, 
[src]

type Error = Infallible

The type returned in the event of a conversion error.

impl<T, U> TryInto<U> for T where
    U: TryFrom<T>, 
[src]

type Error = <U as TryFrom<T>>::Error

The type returned in the event of a conversion error.

impl<V, T> VZip<V> for T where
    V: MultiLane<T>,