nyx_space::od::estimate::kfestimate

Struct KfEstimate

source
pub struct KfEstimate<T: State>{
    pub nominal_state: T,
    pub state_deviation: OVector<f64, <T as State>::Size>,
    pub covar: OMatrix<f64, <T as State>::Size, <T as State>::Size>,
    pub covar_bar: OMatrix<f64, <T as State>::Size, <T as State>::Size>,
    pub predicted: bool,
    pub stm: OMatrix<f64, <T as State>::Size, <T as State>::Size>,
}
Expand description

Kalman filter Estimate

Fields§

§nominal_state: T

The estimated state

§state_deviation: OVector<f64, <T as State>::Size>

The state deviation

§covar: OMatrix<f64, <T as State>::Size, <T as State>::Size>

The Covariance of this estimate

§covar_bar: OMatrix<f64, <T as State>::Size, <T as State>::Size>

The predicted covariance of this estimate

§predicted: bool

Whether or not this is a predicted estimate from a time update, or an estimate from a measurement

§stm: OMatrix<f64, <T as State>::Size, <T as State>::Size>

The STM used to compute this Estimate

Implementations§

source§

impl<T: State> KfEstimate<T>

source

pub fn from_covar( nominal_state: T, covar: OMatrix<f64, <T as State>::Size, <T as State>::Size>, ) -> Self

Initializes a new filter estimate from the nominal state (not dispersed) and the full covariance

source

pub fn from_diag( nominal_state: T, diag: OVector<f64, <T as State>::Size>, ) -> Self

Initializes a new filter estimate from the nominal state (not dispersed) and the diagonal of the covariance

source§

impl KfEstimate<Spacecraft>

source

pub fn disperse_from_diag( nominal_state: Spacecraft, dispersions: Vec<StateDispersion>, seed: Option<u128>, ) -> Result<Self, Box<dyn Error>>

Generates an initial Kalman filter state estimate dispersed from the nominal state using the provided standard deviation parameters.

The resulting estimate will have a diagonal covariance matrix constructed from the variances of each parameter. Limitation: This method may not work correctly for all Keplerian orbital elements, refer to https://github.com/nyx-space/nyx/issues/339 for details.

source

pub fn to_random_variable(&self) -> Result<MultivariateNormal, Box<dyn Error>>

Builds a multivariate random variable from this estimate’s nominal state and covariance, zero mean.

Examples found in repository?
examples/02_jwst_covar_monte_carlo/main.rs (line 132)
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
fn main() -> Result<(), Box<dyn Error>> {
    pel::init();
    // Dynamics models require planetary constants and ephemerides to be defined.
    // Let's start by grabbing those by using ANISE's latest MetaAlmanac.
    // For details, refer to https://github.com/nyx-space/anise/blob/master/data/latest.dhall.

    // Download the regularly update of the James Webb Space Telescope reconstucted (or definitive) ephemeris.
    // Refer to https://naif.jpl.nasa.gov/pub/naif/JWST/kernels/spk/aareadme.txt for details.
    let mut latest_jwst_ephem = MetaFile {
        uri: "https://naif.jpl.nasa.gov/pub/naif/JWST/kernels/spk/jwst_rec.bsp".to_string(),
        crc32: None,
    };
    latest_jwst_ephem.process(true)?;

    // Load this ephem in the general Almanac we're using for this analysis.
    let almanac = Arc::new(
        MetaAlmanac::latest()
            .map_err(Box::new)?
            .load_from_metafile(latest_jwst_ephem, true)?,
    );

    // By loading this ephemeris file in the ANISE GUI or ANISE CLI, we can find the NAIF ID of the JWST
    // in the BSP. We need this ID in order to query the ephemeris.
    const JWST_NAIF_ID: i32 = -170;
    // Let's build a frame in the J2000 orientation centered on the JWST.
    const JWST_J2000: Frame = Frame::from_ephem_j2000(JWST_NAIF_ID);

    // Since the ephemeris file is updated regularly, we'll just grab the latest state in the ephem.
    let (earliest_epoch, latest_epoch) = almanac.spk_domain(JWST_NAIF_ID)?;
    println!("JWST defined from {earliest_epoch} to {latest_epoch}");
    // Fetch the state, printing it in the Earth J2000 frame.
    let jwst_orbit = almanac.transform(JWST_J2000, EARTH_J2000, latest_epoch, None)?;
    println!("{jwst_orbit:x}");

    // Build the spacecraft
    // SRP area assumed to be the full sunshield and mass if 6200.0 kg, c.f. https://webb.nasa.gov/content/about/faqs/facts.html
    // SRP Coefficient of reflectivity assumed to be that of Kapton, i.e. 2 - 0.44 = 1.56, table 1 from https://amostech.com/TechnicalPapers/2018/Poster/Bengtson.pdf
    let jwst = Spacecraft::builder()
        .orbit(jwst_orbit)
        .srp(SrpConfig {
            area_m2: 21.197 * 14.162,
            cr: 1.56,
        })
        .dry_mass_kg(6200.0)
        .build();

    // Build up the spacecraft uncertainty builder.
    // We can use the spacecraft uncertainty structure to build this up.
    // We start by specifying the nominal state (as defined above), then the uncertainty in position and velocity
    // in the RIC frame. We could also specify the Cr, Cd, and mass uncertainties, but these aren't accounted for until
    // Nyx can also estimate the deviation of the spacecraft parameters.
    let jwst_uncertainty = SpacecraftUncertainty::builder()
        .nominal(jwst)
        .frame(LocalFrame::RIC)
        .x_km(0.5)
        .y_km(0.3)
        .z_km(1.5)
        .vx_km_s(1e-4)
        .vy_km_s(0.6e-3)
        .vz_km_s(3e-3)
        .build();

    println!("{jwst_uncertainty}");

    // Build the Kalman filter estimate.
    // Note that we could have used the KfEstimate structure directly (as seen throughout the OD integration tests)
    // but this approach requires quite a bit more boilerplate code.
    let jwst_estimate = jwst_uncertainty.to_estimate()?;

    // Set up the spacecraft dynamics.
    // We'll use the point masses of the Earth, Sun, Jupiter (barycenter, because it's in the DE440), and the Moon.
    // We'll also enable solar radiation pressure since the James Webb has a huge and highly reflective sun shield.

    let orbital_dyn = OrbitalDynamics::point_masses(vec![MOON, SUN, JUPITER_BARYCENTER]);
    let srp_dyn = SolarPressure::new(vec![EARTH_J2000, MOON_J2000], almanac.clone())?;

    // Finalize setting up the dynamics.
    let dynamics = SpacecraftDynamics::from_model(orbital_dyn, srp_dyn);

    // Build the propagator set up to use for the whole analysis.
    let setup = Propagator::default(dynamics);

    // All of the analysis will use this duration.
    let prediction_duration = 6.5 * Unit::Day;

    // === Covariance mapping ===
    // For the covariance mapping / prediction, we'll use the common orbit determination approach.
    // This is done by setting up a spacecraft OD process, and predicting for the analysis duration.

    let ckf = KF::no_snc(jwst_estimate);

    // Build the propagation instance for the OD process.
    let prop = setup.with(jwst.with_stm(), almanac.clone());
    let mut odp = SpacecraftODProcess::ckf(prop, ckf, None, almanac.clone());

    // Define the prediction step, i.e. how often we want to know the covariance.
    let step = 1_i64.minutes();
    // Finally, predict, and export the trajectory with covariance to a parquet file.
    odp.predict_for(step, prediction_duration)?;
    odp.to_parquet("./02_jwst_covar_map.parquet", ExportCfg::default())?;

    // === Monte Carlo framework ===
    // Nyx comes with a complete multi-threaded Monte Carlo frame. It's blazing fast.

    let my_mc = MonteCarlo::new(
        jwst, // Nominal state
        jwst_estimate.to_random_variable()?,
        "02_jwst".to_string(), // Scenario name
        None, // No specific seed specified, so one will be drawn from the computer's entropy.
    );

    let num_runs = 5_000;
    let rslts = my_mc.run_until_epoch(
        setup,
        almanac.clone(),
        jwst.epoch() + prediction_duration,
        num_runs,
    );

    assert_eq!(rslts.runs.len(), num_runs);
    // Finally, export these results, computing the eclipse percentage for all of these results.

    // For all of the resulting trajectories, we'll want to compute the percentage of penumbra and umbra.
    let eclipse_loc = EclipseLocator::cislunar(almanac.clone());
    let umbra_event = eclipse_loc.to_umbra_event();
    let penumbra_event = eclipse_loc.to_penumbra_event();

    rslts.to_parquet(
        "02_jwst_monte_carlo.parquet",
        Some(vec![&umbra_event, &penumbra_event]),
        ExportCfg::default(),
        almanac,
    )?;

    Ok(())
}
source

pub fn sigma_for(&self, param: StateParameter) -> Result<f64, AstroError>

Returns the 1-sigma uncertainty for a given parameter, in that parameter’s unit

This method uses the OrbitDual structure to compute the estimate in the hyperdual space and rotate the nominal covariance into that space.

source

pub fn keplerian_covar(&self) -> SMatrix<f64, 6, 6>

Returns the 6x6 covariance (i.e. square of the sigma/uncertainty) of the SMA, ECC, INC, RAAN, AOP, and True Anomaly.

Trait Implementations§

source§

impl<T: Clone + State> Clone for KfEstimate<T>

source§

fn clone(&self) -> KfEstimate<T>

Returns a copy of the value. Read more
1.6.0 · source§

fn clone_from(&mut self, source: &Self)

Performs copy-assignment from source. Read more
source§

impl<T: Debug + State> Debug for KfEstimate<T>

source§

fn fmt(&self, f: &mut Formatter<'_>) -> Result

Formats the value using the given formatter. Read more
source§

impl<T: State> Display for KfEstimate<T>

source§

fn fmt(&self, f: &mut Formatter<'_>) -> Result

Formats the value using the given formatter. Read more
source§

impl<T: State> Estimate<T> for KfEstimate<T>

source§

fn zeros(nominal_state: T) -> Self

An empty estimate. This is useful if wanting to store an estimate outside the scope of a filtering loop.
source§

fn nominal_state(&self) -> T

The nominal state as reported by the filter dynamics
source§

fn state_deviation(&self) -> OVector<f64, <T as State>::Size>

The state deviation as computed by the filter.
source§

fn covar(&self) -> OMatrix<f64, <T as State>::Size, <T as State>::Size>

The Covariance of this estimate. Will return the predicted covariance if this is a time update/prediction.
source§

fn predicted_covar( &self, ) -> OMatrix<f64, <T as State>::Size, <T as State>::Size>

The predicted covariance of this estimate from the time update
source§

fn predicted(&self) -> bool

Whether or not this is a predicted estimate from a time update, or an estimate from a measurement
source§

fn stm(&self) -> &OMatrix<f64, <T as State>::Size, <T as State>::Size>

The STM used to compute this Estimate
source§

fn set_state_deviation(&mut self, new_state: OVector<f64, <T as State>::Size>)

Sets the state deviation.
source§

fn set_covar( &mut self, new_covar: OMatrix<f64, <T as State>::Size, <T as State>::Size>, )

Sets the Covariance of this estimate
source§

fn epoch(&self) -> Epoch

Epoch of this Estimate
source§

fn set_epoch(&mut self, dt: Epoch)

source§

fn state(&self) -> T

The estimated state
source§

fn within_sigma(&self, sigma: f64) -> bool

Returns whether this estimate is within some bound The 68-95-99.7 rule is a good way to assess whether the filter is operating normally
source§

fn within_3sigma(&self) -> bool

Returns whether this estimate is within 3 sigma, which represent 99.7% for a Normal distribution
source§

impl<T: State> LowerExp for KfEstimate<T>

source§

fn fmt(&self, f: &mut Formatter<'_>) -> Result

Formats the value using the given formatter. Read more
source§

impl<T: State> Mul<f64> for KfEstimate<T>

source§

type Output = KfEstimate<T>

The resulting type after applying the * operator.
source§

fn mul(self, rhs: f64) -> Self::Output

Performs the * operation. Read more
source§

impl NavSolution<Spacecraft> for KfEstimate<Spacecraft>

source§

fn orbital_state(&self) -> Orbit

source§

fn expected_state(&self) -> Orbit

Returns the nominal state as computed by the dynamics
source§

impl<T: PartialEq + State> PartialEq for KfEstimate<T>

source§

fn eq(&self, other: &KfEstimate<T>) -> bool

Tests for self and other values to be equal, and is used by ==.
1.6.0 · source§

fn ne(&self, other: &Rhs) -> bool

Tests for !=. The default implementation is almost always sufficient, and should not be overridden without very good reason.
source§

impl<T: Copy + State> Copy for KfEstimate<T>

source§

impl<T: State> StructuralPartialEq for KfEstimate<T>

Auto Trait Implementations§

§

impl<T> !Freeze for KfEstimate<T>

§

impl<T> !RefUnwindSafe for KfEstimate<T>

§

impl<T> !Send for KfEstimate<T>

§

impl<T> !Sync for KfEstimate<T>

§

impl<T> !Unpin for KfEstimate<T>

§

impl<T> !UnwindSafe for KfEstimate<T>

Blanket Implementations§

source§

impl<T> Any for T
where T: 'static + ?Sized,

source§

fn type_id(&self) -> TypeId

Gets the TypeId of self. Read more
source§

impl<T> Borrow<T> for T
where T: ?Sized,

source§

fn borrow(&self) -> &T

Immutably borrows from an owned value. Read more
source§

impl<T> BorrowMut<T> for T
where T: ?Sized,

source§

fn borrow_mut(&mut self) -> &mut T

Mutably borrows from an owned value. Read more
source§

impl<T> CloneToUninit for T
where T: Clone,

source§

unsafe fn clone_to_uninit(&self, dst: *mut T)

🔬This is a nightly-only experimental API. (clone_to_uninit)
Performs copy-assignment from self to dst. Read more
source§

impl<T> From<T> for T

source§

fn from(t: T) -> T

Returns the argument unchanged.

§

impl<T> Instrument for T

§

fn instrument(self, span: Span) -> Instrumented<Self>

Instruments this type with the provided [Span], returning an Instrumented wrapper. Read more
§

fn in_current_span(self) -> Instrumented<Self>

Instruments this type with the current Span, returning an Instrumented wrapper. Read more
source§

impl<T, U> Into<U> for T
where U: From<T>,

source§

fn into(self) -> U

Calls U::from(self).

That is, this conversion is whatever the implementation of From<T> for U chooses to do.

source§

impl<T> IntoEither for T

source§

fn into_either(self, into_left: bool) -> Either<Self, Self>

Converts self into a Left variant of Either<Self, Self> if into_left is true. Converts self into a Right variant of Either<Self, Self> otherwise. Read more
source§

fn into_either_with<F>(self, into_left: F) -> Either<Self, Self>
where F: FnOnce(&Self) -> bool,

Converts self into a Left variant of Either<Self, Self> if into_left(&self) returns true. Converts self into a Right variant of Either<Self, Self> otherwise. Read more
§

impl<T> Pointable for T

§

const ALIGN: usize = _

The alignment of pointer.
§

type Init = T

The type for initializers.
§

unsafe fn init(init: <T as Pointable>::Init) -> usize

Initializes a with the given initializer. Read more
§

unsafe fn deref<'a>(ptr: usize) -> &'a T

Dereferences the given pointer. Read more
§

unsafe fn deref_mut<'a>(ptr: usize) -> &'a mut T

Mutably dereferences the given pointer. Read more
§

unsafe fn drop(ptr: usize)

Drops the object pointed to by the given pointer. Read more
source§

impl<T> Same for T

source§

type Output = T

Should always be Self
§

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

§

fn to_subset(&self) -> Option<SS>

The inverse inclusion map: attempts to construct self from the equivalent element of its superset. Read more
§

fn is_in_subset(&self) -> bool

Checks if self is actually part of its subset T (and can be converted to it).
§

fn to_subset_unchecked(&self) -> SS

Use with care! Same as self.to_subset but without any property checks. Always succeeds.
§

fn from_subset(element: &SS) -> SP

The inclusion map: converts self to the equivalent element of its superset.
source§

impl<T> ToOwned for T
where T: Clone,

source§

type Owned = T

The resulting type after obtaining ownership.
source§

fn to_owned(&self) -> T

Creates owned data from borrowed data, usually by cloning. Read more
source§

fn clone_into(&self, target: &mut T)

Uses borrowed data to replace owned data, usually by cloning. Read more
source§

impl<T> ToString for T
where T: Display + ?Sized,

source§

default fn to_string(&self) -> String

Converts the given value to a String. Read more
source§

impl<T, U> TryFrom<U> for T
where U: Into<T>,

source§

type Error = Infallible

The type returned in the event of a conversion error.
source§

fn try_from(value: U) -> Result<T, <T as TryFrom<U>>::Error>

Performs the conversion.
source§

impl<T, U> TryInto<U> for T
where U: TryFrom<T>,

source§

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

The type returned in the event of a conversion error.
source§

fn try_into(self) -> Result<U, <U as TryFrom<T>>::Error>

Performs the conversion.
§

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

§

fn vzip(self) -> V

§

impl<T> WithSubscriber for T

§

fn with_subscriber<S>(self, subscriber: S) -> WithDispatch<Self>
where S: Into<Dispatch>,

Attaches the provided Subscriber to this type, returning a [WithDispatch] wrapper. Read more
§

fn with_current_subscriber(self) -> WithDispatch<Self>

Attaches the current default Subscriber to this type, returning a [WithDispatch] wrapper. Read more
§

impl<T> Allocation for T
where T: RefUnwindSafe + Send + Sync,

source§

impl<T> Scalar for T
where T: 'static + Clone + PartialEq + Debug,