nyx_space::od::estimate

Trait Estimate

Source
pub trait Estimate<T: State>
where Self: Clone + PartialEq + Sized + Display, DefaultAllocator: Allocator<<T as State>::Size> + Allocator<<T as State>::Size, <T as State>::Size> + Allocator<<T as State>::VecLength>,
{
Show 14 methods // Required methods fn zeros(state: T) -> Self; fn state_deviation(&self) -> OVector<f64, <T as State>::Size>; fn nominal_state(&self) -> T; fn 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>; fn set_state_deviation( &mut self, new_state: OVector<f64, <T as State>::Size>, ); fn set_covar( &mut self, new_covar: OMatrix<f64, <T as State>::Size, <T as State>::Size>, ); fn predicted(&self) -> bool; fn stm(&self) -> &OMatrix<f64, <T as State>::Size, <T as State>::Size>; // Provided methods fn epoch(&self) -> Epoch { ... } fn set_epoch(&mut self, dt: Epoch) { ... } fn state(&self) -> T { ... } fn within_sigma(&self, sigma: f64) -> bool { ... } fn within_3sigma(&self) -> bool { ... }
}
Expand description

Stores an Estimate, as the result of a time_update or measurement_update.

Required Methods§

Source

fn zeros(state: T) -> Self

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

Source

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

The state deviation as computed by the filter.

Source

fn nominal_state(&self) -> T

The nominal state as reported by the filter dynamics

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 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 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

Provided Methods§

Source

fn epoch(&self) -> Epoch

Epoch of this Estimate

Examples found in repository?
examples/04_lro_od/main.rs (line 271)
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
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
fn main() -> Result<(), Box<dyn Error>> {
    pel::init();

    // ====================== //
    // === ALMANAC SET UP === //
    // ====================== //

    // Dynamics models require planetary constants and ephemerides to be defined.
    // Let's start by grabbing those by using ANISE's MetaAlmanac.

    let data_folder: PathBuf = [env!("CARGO_MANIFEST_DIR"), "examples", "04_lro_od"]
        .iter()
        .collect();

    let meta = data_folder.join("lro-dynamics.dhall");

    // Load this ephem in the general Almanac we're using for this analysis.
    let mut almanac = MetaAlmanac::new(meta.to_string_lossy().to_string())
        .map_err(Box::new)?
        .process(true)
        .map_err(Box::new)?;

    let mut moon_pc = almanac.planetary_data.get_by_id(MOON)?;
    moon_pc.mu_km3_s2 = 4902.74987;
    almanac.planetary_data.set_by_id(MOON, moon_pc)?;

    let mut earth_pc = almanac.planetary_data.get_by_id(EARTH)?;
    earth_pc.mu_km3_s2 = 398600.436;
    almanac.planetary_data.set_by_id(EARTH, earth_pc)?;

    // Save this new kernel for reuse.
    // In an operational context, this would be part of the "Lock" process, and should not change throughout the mission.
    almanac
        .planetary_data
        .save_as(&data_folder.join("lro-specific.pca"), true)?;

    // Lock the almanac (an Arc is a read only structure).
    let almanac = Arc::new(almanac);

    // Orbit determination requires a Trajectory structure, which can be saved as parquet file.
    // In our case, the trajectory comes from the BSP file, so we need to build a Trajectory from the almanac directly.
    // To query the Almanac, we need to build the LRO frame in the J2000 orientation in our case.
    // Inspecting the LRO BSP in the ANISE GUI shows us that NASA has assigned ID -85 to LRO.
    let lro_frame = Frame::from_ephem_j2000(-85);

    // To build the trajectory we need to provide a spacecraft template.
    let sc_template = Spacecraft::builder()
        .dry_mass_kg(1018.0) // Launch masses
        .fuel_mass_kg(900.0)
        .srp(SrpConfig {
            // SRP configuration is arbitrary, but we will be estimating it anyway.
            area_m2: 3.9 * 2.7,
            cr: 0.96,
        })
        .orbit(Orbit::zero(MOON_J2000)) // Setting a zero orbit here because it's just a template
        .build();
    // Now we can build the trajectory from the BSP file.
    // We'll arbitrarily set the tracking arc to 48 hours with a one minute time step.
    let traj_as_flown = Traj::from_bsp(
        lro_frame,
        MOON_J2000,
        almanac.clone(),
        sc_template,
        5.seconds(),
        Some(Epoch::from_str("2024-01-01 00:00:00 UTC")?),
        Some(Epoch::from_str("2024-01-02 00:00:00 UTC")?),
        Aberration::LT,
        Some("LRO".to_string()),
    )?;

    println!("{traj_as_flown}");

    // ====================== //
    // === MODEL MATCHING === //
    // ====================== //

    // Set up the spacecraft dynamics.

    // Specify that the orbital dynamics must account for the graviational pull of the Earth and the Sun.
    // The gravity of the Moon will also be accounted for since the spaceraft in a lunar orbit.
    let mut orbital_dyn = OrbitalDynamics::point_masses(vec![EARTH, SUN, JUPITER_BARYCENTER]);

    // We want to include the spherical harmonics, so let's download the gravitational data from the Nyx Cloud.
    // We're using the GRAIL JGGRX model.
    let mut jggrx_meta = MetaFile {
        uri: "http://public-data.nyxspace.com/nyx/models/Luna_jggrx_1500e_sha.tab.gz".to_string(),
        crc32: Some(0x6bcacda8), // Specifying the CRC32 avoids redownloading it if it's cached.
    };
    // And let's download it if we don't have it yet.
    jggrx_meta.process(true)?;

    // Build the spherical harmonics.
    // The harmonics must be computed in the body fixed frame.
    // We're using the long term prediction of the Moon principal axes frame.
    let moon_pa_frame = MOON_PA_FRAME.with_orient(31008);
    // let moon_pa_frame = IAU_MOON_FRAME;
    let sph_harmonics = Harmonics::from_stor(
        almanac.frame_from_uid(moon_pa_frame)?,
        HarmonicsMem::from_shadr(&jggrx_meta.uri, 80, 80, true)?,
    );

    // Include the spherical harmonics into the orbital dynamics.
    orbital_dyn.accel_models.push(sph_harmonics);

    // We define the solar radiation pressure, using the default solar flux and accounting only
    // for the eclipsing caused by the Earth and Moon.
    // Note that by default, enabling the SolarPressure model will also enable the estimation of the coefficient of reflectivity.
    let srp_dyn = SolarPressure::new(vec![EARTH_J2000, MOON_J2000], almanac.clone())?;

    // Finalize setting up the dynamics, specifying the force models (orbital_dyn) separately from the
    // acceleration models (SRP in this case). Use `from_models` to specify multiple accel models.
    let dynamics = SpacecraftDynamics::from_model(orbital_dyn, srp_dyn);

    println!("{dynamics}");

    // Now we can build the propagator.
    let setup = Propagator::default_dp78(dynamics.clone());

    // For reference, let's build the trajectory with Nyx's models from that LRO state.
    let (sim_final, traj_as_sim) = setup
        .with(*traj_as_flown.first(), almanac.clone())
        .until_epoch_with_traj(traj_as_flown.last().epoch())?;

    println!("SIM INIT:  {:x}", traj_as_flown.first());
    println!("SIM FINAL: {sim_final:x}");
    // Compute RIC difference between SIM and LRO ephem
    let sim_lro_delta = sim_final
        .orbit
        .ric_difference(&traj_as_flown.last().orbit)?;
    println!("{traj_as_sim}");
    println!(
        "SIM v LRO - RIC Position (m): {:.3}",
        sim_lro_delta.radius_km * 1e3
    );
    println!(
        "SIM v LRO - RIC Velocity (m/s): {:.3}",
        sim_lro_delta.velocity_km_s * 1e3
    );

    traj_as_sim.ric_diff_to_parquet(
        &traj_as_flown,
        "./04_lro_sim_truth_error.parquet",
        ExportCfg::default(),
    )?;

    // ==================== //
    // === OD SIMULATOR === //
    // ==================== //

    // After quite some time trying to exactly match the model, we still end up with an oscillatory difference on the order of 150 meters between the propagated state
    // and the truth LRO state.

    // Therefore, we will actually run an estimation from a dispersed LRO state.
    // The sc_seed is the true LRO state from the BSP.
    let sc_seed = *traj_as_flown.first();

    // Load the Deep Space Network ground stations.
    // Nyx allows you to build these at runtime but it's pretty static so we can just load them from YAML.
    let ground_station_file: PathBuf = [
        env!("CARGO_MANIFEST_DIR"),
        "examples",
        "04_lro_od",
        "dsn-network.yaml",
    ]
    .iter()
    .collect();

    let devices = GroundStation::load_named(ground_station_file)?;

    // Typical OD software requires that you specify your own tracking schedule or you'll have overlapping measurements.
    // Nyx can build a tracking schedule for you based on the first station with access.
    let trkconfg_yaml: PathBuf = [
        env!("CARGO_MANIFEST_DIR"),
        "examples",
        "04_lro_od",
        "tracking-cfg.yaml",
    ]
    .iter()
    .collect();

    let configs: BTreeMap<String, TrkConfig> = TrkConfig::load_named(trkconfg_yaml)?;

    // Build the tracking arc simulation to generate a "standard measurement".
    let mut trk = TrackingArcSim::<Spacecraft, GroundStation>::new(
        devices.clone(),
        traj_as_flown.clone(),
        configs,
    )?;

    trk.build_schedule(almanac.clone())?;
    let arc = trk.generate_measurements(almanac.clone())?;
    // Save the simulated tracking data
    arc.to_parquet_simple("./04_lro_simulated_tracking.parquet")?;

    // We'll note that in our case, we have continuous coverage of LRO when the vehicle is not behind the Moon.
    println!("{arc}");

    // Now that we have simulated measurements, we'll run the orbit determination.

    // ===================== //
    // === OD ESTIMATION === //
    // ===================== //

    let sc = SpacecraftUncertainty::builder()
        .nominal(sc_seed)
        .frame(LocalFrame::RIC)
        .x_km(0.5)
        .y_km(0.5)
        .z_km(0.5)
        .vx_km_s(5e-3)
        .vy_km_s(5e-3)
        .vz_km_s(5e-3)
        .build();

    // Build the filter initial estimate, which we will reuse in the filter.
    let initial_estimate = sc.to_estimate()?;

    println!("== FILTER STATE ==\n{sc_seed:x}\n{initial_estimate}");

    let kf = KF::new(
        // Increase the initial covariance to account for larger deviation.
        initial_estimate,
        // Until https://github.com/nyx-space/nyx/issues/351, we need to specify the SNC in the acceleration of the Moon J2000 frame.
        SNC3::from_diagonal(10 * Unit::Minute, &[1e-12, 1e-12, 1e-12]),
    );

    // We'll set up the OD process to reject measurements whose residuals are move than 3 sigmas away from what we expect.
    let mut odp = SpacecraftODProcess::ckf(
        setup.with(initial_estimate.state().with_stm(), almanac.clone()),
        kf,
        devices,
        Some(ResidRejectCrit::default()),
        almanac.clone(),
    );

    odp.process_arc(&arc)?;

    let ric_err = traj_as_flown
        .at(odp.estimates.last().unwrap().epoch())?
        .orbit
        .ric_difference(&odp.estimates.last().unwrap().orbital_state())?;
    println!("== RIC at end ==");
    println!("RIC Position (m): {}", ric_err.radius_km * 1e3);
    println!("RIC Velocity (m/s): {}", ric_err.velocity_km_s * 1e3);

    odp.to_parquet(&arc, "./04_lro_od_results.parquet", ExportCfg::default())?;

    // In our case, we have the truth trajectory from NASA.
    // So we can compute the RIC state difference between the real LRO ephem and what we've just estimated.
    // Export the OD trajectory first.
    let od_trajectory = odp.to_traj()?;
    // Build the RIC difference.
    od_trajectory.ric_diff_to_parquet(
        &traj_as_flown,
        "./04_lro_od_truth_error.parquet",
        ExportCfg::default(),
    )?;

    Ok(())
}
Source

fn set_epoch(&mut self, dt: Epoch)

Source

fn state(&self) -> T

The estimated state

Examples found in repository?
examples/04_lro_od/main.rs (line 261)
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
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
fn main() -> Result<(), Box<dyn Error>> {
    pel::init();

    // ====================== //
    // === ALMANAC SET UP === //
    // ====================== //

    // Dynamics models require planetary constants and ephemerides to be defined.
    // Let's start by grabbing those by using ANISE's MetaAlmanac.

    let data_folder: PathBuf = [env!("CARGO_MANIFEST_DIR"), "examples", "04_lro_od"]
        .iter()
        .collect();

    let meta = data_folder.join("lro-dynamics.dhall");

    // Load this ephem in the general Almanac we're using for this analysis.
    let mut almanac = MetaAlmanac::new(meta.to_string_lossy().to_string())
        .map_err(Box::new)?
        .process(true)
        .map_err(Box::new)?;

    let mut moon_pc = almanac.planetary_data.get_by_id(MOON)?;
    moon_pc.mu_km3_s2 = 4902.74987;
    almanac.planetary_data.set_by_id(MOON, moon_pc)?;

    let mut earth_pc = almanac.planetary_data.get_by_id(EARTH)?;
    earth_pc.mu_km3_s2 = 398600.436;
    almanac.planetary_data.set_by_id(EARTH, earth_pc)?;

    // Save this new kernel for reuse.
    // In an operational context, this would be part of the "Lock" process, and should not change throughout the mission.
    almanac
        .planetary_data
        .save_as(&data_folder.join("lro-specific.pca"), true)?;

    // Lock the almanac (an Arc is a read only structure).
    let almanac = Arc::new(almanac);

    // Orbit determination requires a Trajectory structure, which can be saved as parquet file.
    // In our case, the trajectory comes from the BSP file, so we need to build a Trajectory from the almanac directly.
    // To query the Almanac, we need to build the LRO frame in the J2000 orientation in our case.
    // Inspecting the LRO BSP in the ANISE GUI shows us that NASA has assigned ID -85 to LRO.
    let lro_frame = Frame::from_ephem_j2000(-85);

    // To build the trajectory we need to provide a spacecraft template.
    let sc_template = Spacecraft::builder()
        .dry_mass_kg(1018.0) // Launch masses
        .fuel_mass_kg(900.0)
        .srp(SrpConfig {
            // SRP configuration is arbitrary, but we will be estimating it anyway.
            area_m2: 3.9 * 2.7,
            cr: 0.96,
        })
        .orbit(Orbit::zero(MOON_J2000)) // Setting a zero orbit here because it's just a template
        .build();
    // Now we can build the trajectory from the BSP file.
    // We'll arbitrarily set the tracking arc to 48 hours with a one minute time step.
    let traj_as_flown = Traj::from_bsp(
        lro_frame,
        MOON_J2000,
        almanac.clone(),
        sc_template,
        5.seconds(),
        Some(Epoch::from_str("2024-01-01 00:00:00 UTC")?),
        Some(Epoch::from_str("2024-01-02 00:00:00 UTC")?),
        Aberration::LT,
        Some("LRO".to_string()),
    )?;

    println!("{traj_as_flown}");

    // ====================== //
    // === MODEL MATCHING === //
    // ====================== //

    // Set up the spacecraft dynamics.

    // Specify that the orbital dynamics must account for the graviational pull of the Earth and the Sun.
    // The gravity of the Moon will also be accounted for since the spaceraft in a lunar orbit.
    let mut orbital_dyn = OrbitalDynamics::point_masses(vec![EARTH, SUN, JUPITER_BARYCENTER]);

    // We want to include the spherical harmonics, so let's download the gravitational data from the Nyx Cloud.
    // We're using the GRAIL JGGRX model.
    let mut jggrx_meta = MetaFile {
        uri: "http://public-data.nyxspace.com/nyx/models/Luna_jggrx_1500e_sha.tab.gz".to_string(),
        crc32: Some(0x6bcacda8), // Specifying the CRC32 avoids redownloading it if it's cached.
    };
    // And let's download it if we don't have it yet.
    jggrx_meta.process(true)?;

    // Build the spherical harmonics.
    // The harmonics must be computed in the body fixed frame.
    // We're using the long term prediction of the Moon principal axes frame.
    let moon_pa_frame = MOON_PA_FRAME.with_orient(31008);
    // let moon_pa_frame = IAU_MOON_FRAME;
    let sph_harmonics = Harmonics::from_stor(
        almanac.frame_from_uid(moon_pa_frame)?,
        HarmonicsMem::from_shadr(&jggrx_meta.uri, 80, 80, true)?,
    );

    // Include the spherical harmonics into the orbital dynamics.
    orbital_dyn.accel_models.push(sph_harmonics);

    // We define the solar radiation pressure, using the default solar flux and accounting only
    // for the eclipsing caused by the Earth and Moon.
    // Note that by default, enabling the SolarPressure model will also enable the estimation of the coefficient of reflectivity.
    let srp_dyn = SolarPressure::new(vec![EARTH_J2000, MOON_J2000], almanac.clone())?;

    // Finalize setting up the dynamics, specifying the force models (orbital_dyn) separately from the
    // acceleration models (SRP in this case). Use `from_models` to specify multiple accel models.
    let dynamics = SpacecraftDynamics::from_model(orbital_dyn, srp_dyn);

    println!("{dynamics}");

    // Now we can build the propagator.
    let setup = Propagator::default_dp78(dynamics.clone());

    // For reference, let's build the trajectory with Nyx's models from that LRO state.
    let (sim_final, traj_as_sim) = setup
        .with(*traj_as_flown.first(), almanac.clone())
        .until_epoch_with_traj(traj_as_flown.last().epoch())?;

    println!("SIM INIT:  {:x}", traj_as_flown.first());
    println!("SIM FINAL: {sim_final:x}");
    // Compute RIC difference between SIM and LRO ephem
    let sim_lro_delta = sim_final
        .orbit
        .ric_difference(&traj_as_flown.last().orbit)?;
    println!("{traj_as_sim}");
    println!(
        "SIM v LRO - RIC Position (m): {:.3}",
        sim_lro_delta.radius_km * 1e3
    );
    println!(
        "SIM v LRO - RIC Velocity (m/s): {:.3}",
        sim_lro_delta.velocity_km_s * 1e3
    );

    traj_as_sim.ric_diff_to_parquet(
        &traj_as_flown,
        "./04_lro_sim_truth_error.parquet",
        ExportCfg::default(),
    )?;

    // ==================== //
    // === OD SIMULATOR === //
    // ==================== //

    // After quite some time trying to exactly match the model, we still end up with an oscillatory difference on the order of 150 meters between the propagated state
    // and the truth LRO state.

    // Therefore, we will actually run an estimation from a dispersed LRO state.
    // The sc_seed is the true LRO state from the BSP.
    let sc_seed = *traj_as_flown.first();

    // Load the Deep Space Network ground stations.
    // Nyx allows you to build these at runtime but it's pretty static so we can just load them from YAML.
    let ground_station_file: PathBuf = [
        env!("CARGO_MANIFEST_DIR"),
        "examples",
        "04_lro_od",
        "dsn-network.yaml",
    ]
    .iter()
    .collect();

    let devices = GroundStation::load_named(ground_station_file)?;

    // Typical OD software requires that you specify your own tracking schedule or you'll have overlapping measurements.
    // Nyx can build a tracking schedule for you based on the first station with access.
    let trkconfg_yaml: PathBuf = [
        env!("CARGO_MANIFEST_DIR"),
        "examples",
        "04_lro_od",
        "tracking-cfg.yaml",
    ]
    .iter()
    .collect();

    let configs: BTreeMap<String, TrkConfig> = TrkConfig::load_named(trkconfg_yaml)?;

    // Build the tracking arc simulation to generate a "standard measurement".
    let mut trk = TrackingArcSim::<Spacecraft, GroundStation>::new(
        devices.clone(),
        traj_as_flown.clone(),
        configs,
    )?;

    trk.build_schedule(almanac.clone())?;
    let arc = trk.generate_measurements(almanac.clone())?;
    // Save the simulated tracking data
    arc.to_parquet_simple("./04_lro_simulated_tracking.parquet")?;

    // We'll note that in our case, we have continuous coverage of LRO when the vehicle is not behind the Moon.
    println!("{arc}");

    // Now that we have simulated measurements, we'll run the orbit determination.

    // ===================== //
    // === OD ESTIMATION === //
    // ===================== //

    let sc = SpacecraftUncertainty::builder()
        .nominal(sc_seed)
        .frame(LocalFrame::RIC)
        .x_km(0.5)
        .y_km(0.5)
        .z_km(0.5)
        .vx_km_s(5e-3)
        .vy_km_s(5e-3)
        .vz_km_s(5e-3)
        .build();

    // Build the filter initial estimate, which we will reuse in the filter.
    let initial_estimate = sc.to_estimate()?;

    println!("== FILTER STATE ==\n{sc_seed:x}\n{initial_estimate}");

    let kf = KF::new(
        // Increase the initial covariance to account for larger deviation.
        initial_estimate,
        // Until https://github.com/nyx-space/nyx/issues/351, we need to specify the SNC in the acceleration of the Moon J2000 frame.
        SNC3::from_diagonal(10 * Unit::Minute, &[1e-12, 1e-12, 1e-12]),
    );

    // We'll set up the OD process to reject measurements whose residuals are move than 3 sigmas away from what we expect.
    let mut odp = SpacecraftODProcess::ckf(
        setup.with(initial_estimate.state().with_stm(), almanac.clone()),
        kf,
        devices,
        Some(ResidRejectCrit::default()),
        almanac.clone(),
    );

    odp.process_arc(&arc)?;

    let ric_err = traj_as_flown
        .at(odp.estimates.last().unwrap().epoch())?
        .orbit
        .ric_difference(&odp.estimates.last().unwrap().orbital_state())?;
    println!("== RIC at end ==");
    println!("RIC Position (m): {}", ric_err.radius_km * 1e3);
    println!("RIC Velocity (m/s): {}", ric_err.velocity_km_s * 1e3);

    odp.to_parquet(&arc, "./04_lro_od_results.parquet", ExportCfg::default())?;

    // In our case, we have the truth trajectory from NASA.
    // So we can compute the RIC state difference between the real LRO ephem and what we've just estimated.
    // Export the OD trajectory first.
    let od_trajectory = odp.to_traj()?;
    // Build the RIC difference.
    od_trajectory.ric_diff_to_parquet(
        &traj_as_flown,
        "./04_lro_od_truth_error.parquet",
        ExportCfg::default(),
    )?;

    Ok(())
}
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

Dyn Compatibility§

This trait is not dyn compatible.

In older versions of Rust, dyn compatibility was called "object safety", so this trait is not object safe.

Implementors§