pub struct KfEstimate<T: State>where
DefaultAllocator: Allocator<<T as State>::Size> + Allocator<<T as State>::Size, <T as State>::Size> + Allocator<<T as State>::VecLength>,
<DefaultAllocator as Allocator<<T as State>::Size>>::Buffer<f64>: Copy,
<DefaultAllocator as Allocator<<T as State>::Size, <T as State>::Size>>::Buffer<f64>: Copy,{
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>where
DefaultAllocator: Allocator<<T as State>::Size> + Allocator<<T as State>::Size, <T as State>::Size> + Allocator<<T as State>::VecLength>,
<DefaultAllocator as Allocator<<T as State>::Size>>::Buffer<f64>: Copy,
<DefaultAllocator as Allocator<<T as State>::Size, <T as State>::Size>>::Buffer<f64>: Copy,
impl<T: State> KfEstimate<T>where
DefaultAllocator: Allocator<<T as State>::Size> + Allocator<<T as State>::Size, <T as State>::Size> + Allocator<<T as State>::VecLength>,
<DefaultAllocator as Allocator<<T as State>::Size>>::Buffer<f64>: Copy,
<DefaultAllocator as Allocator<<T as State>::Size, <T as State>::Size>>::Buffer<f64>: Copy,
Source§impl KfEstimate<Spacecraft>
impl KfEstimate<Spacecraft>
Sourcepub fn disperse_from_diag(
nominal_state: Spacecraft,
dispersions: Vec<StateDispersion>,
seed: Option<u128>,
) -> Result<Self, Box<dyn Error>>
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.
Sourcepub fn to_random_variable(&self) -> Result<MvnSpacecraft, Box<dyn Error>>
pub fn to_random_variable(&self) -> Result<MvnSpacecraft, Box<dyn Error>>
Builds a multivariate random variable from this estimate’s nominal state and covariance, zero mean.
Examples found in repository?
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 162 163 164 165
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, BTreeMap::new(), 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(
&TrackingDataArc::default(),
"./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(())
}
Sourcepub fn sigma_for(&self, param: StateParameter) -> Result<f64, AstroError>
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.
Sourcepub fn keplerian_covar(&self) -> SMatrix<f64, 6, 6>
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>where
DefaultAllocator: Allocator<<T as State>::Size> + Allocator<<T as State>::Size, <T as State>::Size> + Allocator<<T as State>::VecLength>,
<DefaultAllocator as Allocator<<T as State>::Size>>::Buffer<f64>: Copy,
<DefaultAllocator as Allocator<<T as State>::Size, <T as State>::Size>>::Buffer<f64>: Copy,
impl<T: Clone + State> Clone for KfEstimate<T>where
DefaultAllocator: Allocator<<T as State>::Size> + Allocator<<T as State>::Size, <T as State>::Size> + Allocator<<T as State>::VecLength>,
<DefaultAllocator as Allocator<<T as State>::Size>>::Buffer<f64>: Copy,
<DefaultAllocator as Allocator<<T as State>::Size, <T as State>::Size>>::Buffer<f64>: Copy,
Source§fn clone(&self) -> KfEstimate<T>
fn clone(&self) -> KfEstimate<T>
1.0.0 · Source§fn clone_from(&mut self, source: &Self)
fn clone_from(&mut self, source: &Self)
source
. Read moreSource§impl<T: Debug + State> Debug for KfEstimate<T>where
DefaultAllocator: Allocator<<T as State>::Size> + Allocator<<T as State>::Size, <T as State>::Size> + Allocator<<T as State>::VecLength>,
<DefaultAllocator as Allocator<<T as State>::Size>>::Buffer<f64>: Copy,
<DefaultAllocator as Allocator<<T as State>::Size, <T as State>::Size>>::Buffer<f64>: Copy,
impl<T: Debug + State> Debug for KfEstimate<T>where
DefaultAllocator: Allocator<<T as State>::Size> + Allocator<<T as State>::Size, <T as State>::Size> + Allocator<<T as State>::VecLength>,
<DefaultAllocator as Allocator<<T as State>::Size>>::Buffer<f64>: Copy,
<DefaultAllocator as Allocator<<T as State>::Size, <T as State>::Size>>::Buffer<f64>: Copy,
Source§impl<T: State> Display for KfEstimate<T>where
DefaultAllocator: Allocator<<T as State>::Size> + Allocator<<T as State>::Size, <T as State>::Size> + Allocator<<T as State>::VecLength>,
<DefaultAllocator as Allocator<<T as State>::Size>>::Buffer<f64>: Copy,
<DefaultAllocator as Allocator<<T as State>::Size, <T as State>::Size>>::Buffer<f64>: Copy,
impl<T: State> Display for KfEstimate<T>where
DefaultAllocator: Allocator<<T as State>::Size> + Allocator<<T as State>::Size, <T as State>::Size> + Allocator<<T as State>::VecLength>,
<DefaultAllocator as Allocator<<T as State>::Size>>::Buffer<f64>: Copy,
<DefaultAllocator as Allocator<<T as State>::Size, <T as State>::Size>>::Buffer<f64>: Copy,
Source§impl<T: State> Estimate<T> for KfEstimate<T>where
DefaultAllocator: Allocator<<T as State>::Size> + Allocator<<T as State>::Size, <T as State>::Size> + Allocator<<T as State>::VecLength>,
<DefaultAllocator as Allocator<<T as State>::Size>>::Buffer<f64>: Copy,
<DefaultAllocator as Allocator<<T as State>::Size, <T as State>::Size>>::Buffer<f64>: Copy,
impl<T: State> Estimate<T> for KfEstimate<T>where
DefaultAllocator: Allocator<<T as State>::Size> + Allocator<<T as State>::Size, <T as State>::Size> + Allocator<<T as State>::VecLength>,
<DefaultAllocator as Allocator<<T as State>::Size>>::Buffer<f64>: Copy,
<DefaultAllocator as Allocator<<T as State>::Size, <T as State>::Size>>::Buffer<f64>: Copy,
Source§fn zeros(nominal_state: T) -> Self
fn zeros(nominal_state: T) -> Self
Source§fn nominal_state(&self) -> T
fn nominal_state(&self) -> T
Source§fn state_deviation(&self) -> OVector<f64, <T as State>::Size>
fn state_deviation(&self) -> OVector<f64, <T as State>::Size>
Source§fn covar(&self) -> OMatrix<f64, <T as State>::Size, <T as State>::Size>
fn covar(&self) -> OMatrix<f64, <T as State>::Size, <T as State>::Size>
Source§fn predicted_covar(
&self,
) -> OMatrix<f64, <T as State>::Size, <T as State>::Size>
fn predicted_covar( &self, ) -> OMatrix<f64, <T as State>::Size, <T as State>::Size>
Source§fn predicted(&self) -> bool
fn predicted(&self) -> bool
Source§fn stm(&self) -> &OMatrix<f64, <T as State>::Size, <T as State>::Size>
fn stm(&self) -> &OMatrix<f64, <T as State>::Size, <T as State>::Size>
Source§fn set_state_deviation(&mut self, new_state: OVector<f64, <T as State>::Size>)
fn set_state_deviation(&mut self, new_state: OVector<f64, <T as State>::Size>)
Source§fn set_covar(
&mut self,
new_covar: OMatrix<f64, <T as State>::Size, <T as State>::Size>,
)
fn set_covar( &mut self, new_covar: OMatrix<f64, <T as State>::Size, <T as State>::Size>, )
fn set_epoch(&mut self, dt: Epoch)
Source§fn within_sigma(&self, sigma: f64) -> bool
fn within_sigma(&self, sigma: f64) -> bool
Source§fn within_3sigma(&self) -> bool
fn within_3sigma(&self) -> bool
Source§impl<T: State> LowerExp for KfEstimate<T>where
DefaultAllocator: Allocator<<T as State>::Size> + Allocator<<T as State>::Size, <T as State>::Size> + Allocator<<T as State>::VecLength>,
<DefaultAllocator as Allocator<<T as State>::Size>>::Buffer<f64>: Copy,
<DefaultAllocator as Allocator<<T as State>::Size, <T as State>::Size>>::Buffer<f64>: Copy,
impl<T: State> LowerExp for KfEstimate<T>where
DefaultAllocator: Allocator<<T as State>::Size> + Allocator<<T as State>::Size, <T as State>::Size> + Allocator<<T as State>::VecLength>,
<DefaultAllocator as Allocator<<T as State>::Size>>::Buffer<f64>: Copy,
<DefaultAllocator as Allocator<<T as State>::Size, <T as State>::Size>>::Buffer<f64>: Copy,
Source§impl<T: State> Mul<f64> for KfEstimate<T>where
DefaultAllocator: Allocator<<T as State>::Size> + Allocator<<T as State>::Size, <T as State>::Size> + Allocator<<T as State>::VecLength>,
<DefaultAllocator as Allocator<<T as State>::Size>>::Buffer<f64>: Copy,
<DefaultAllocator as Allocator<<T as State>::Size, <T as State>::Size>>::Buffer<f64>: Copy,
impl<T: State> Mul<f64> for KfEstimate<T>where
DefaultAllocator: Allocator<<T as State>::Size> + Allocator<<T as State>::Size, <T as State>::Size> + Allocator<<T as State>::VecLength>,
<DefaultAllocator as Allocator<<T as State>::Size>>::Buffer<f64>: Copy,
<DefaultAllocator as Allocator<<T as State>::Size, <T as State>::Size>>::Buffer<f64>: Copy,
fn orbital_state(&self) -> Orbit
Source§fn expected_state(&self) -> Orbit
fn expected_state(&self) -> Orbit
Source§impl<T: PartialEq + State> PartialEq for KfEstimate<T>where
DefaultAllocator: Allocator<<T as State>::Size> + Allocator<<T as State>::Size, <T as State>::Size> + Allocator<<T as State>::VecLength>,
<DefaultAllocator as Allocator<<T as State>::Size>>::Buffer<f64>: Copy,
<DefaultAllocator as Allocator<<T as State>::Size, <T as State>::Size>>::Buffer<f64>: Copy,
impl<T: PartialEq + State> PartialEq for KfEstimate<T>where
DefaultAllocator: Allocator<<T as State>::Size> + Allocator<<T as State>::Size, <T as State>::Size> + Allocator<<T as State>::VecLength>,
<DefaultAllocator as Allocator<<T as State>::Size>>::Buffer<f64>: Copy,
<DefaultAllocator as Allocator<<T as State>::Size, <T as State>::Size>>::Buffer<f64>: Copy,
impl<T: Copy + State> Copy for KfEstimate<T>where
DefaultAllocator: Allocator<<T as State>::Size> + Allocator<<T as State>::Size, <T as State>::Size> + Allocator<<T as State>::VecLength>,
<DefaultAllocator as Allocator<<T as State>::Size>>::Buffer<f64>: Copy,
<DefaultAllocator as Allocator<<T as State>::Size, <T as State>::Size>>::Buffer<f64>: Copy,
impl<T: State> StructuralPartialEq for KfEstimate<T>where
DefaultAllocator: Allocator<<T as State>::Size> + Allocator<<T as State>::Size, <T as State>::Size> + Allocator<<T as State>::VecLength>,
<DefaultAllocator as Allocator<<T as State>::Size>>::Buffer<f64>: Copy,
<DefaultAllocator as Allocator<<T as State>::Size, <T as State>::Size>>::Buffer<f64>: Copy,
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> BorrowMut<T> for Twhere
T: ?Sized,
impl<T> BorrowMut<T> for Twhere
T: ?Sized,
Source§fn borrow_mut(&mut self) -> &mut T
fn borrow_mut(&mut self) -> &mut T
Source§impl<T> CloneToUninit for Twhere
T: Clone,
impl<T> CloneToUninit for Twhere
T: Clone,
§impl<T> Instrument for T
impl<T> Instrument for T
§fn instrument(self, span: Span) -> Instrumented<Self>
fn instrument(self, span: Span) -> Instrumented<Self>
§fn in_current_span(self) -> Instrumented<Self>
fn in_current_span(self) -> Instrumented<Self>
Source§impl<T> IntoEither for T
impl<T> IntoEither for T
Source§fn into_either(self, into_left: bool) -> Either<Self, Self>
fn into_either(self, into_left: bool) -> Either<Self, Self>
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 moreSource§fn into_either_with<F>(self, into_left: F) -> Either<Self, Self>
fn into_either_with<F>(self, into_left: F) -> Either<Self, Self>
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
impl<T> Pointable for T
§impl<SS, SP> SupersetOf<SS> for SPwhere
SS: SubsetOf<SP>,
impl<SS, SP> SupersetOf<SS> for SPwhere
SS: SubsetOf<SP>,
§fn to_subset(&self) -> Option<SS>
fn to_subset(&self) -> Option<SS>
self
from the equivalent element of its
superset. Read more§fn is_in_subset(&self) -> bool
fn is_in_subset(&self) -> bool
self
is actually part of its subset T
(and can be converted to it).§fn to_subset_unchecked(&self) -> SS
fn to_subset_unchecked(&self) -> SS
self.to_subset
but without any property checks. Always succeeds.§fn from_subset(element: &SS) -> SP
fn from_subset(element: &SS) -> SP
self
to the equivalent element of its superset.