pub enum Event {
Imu {
dt_s: f64,
imu: IMUData,
elapsed_s: f64,
},
Gnss {
meas: GPSPositionAndVelocityMeasurement,
elapsed_s: f64,
},
Altitude {
meas: RelativeAltitudeMeasurement,
elapsed_s: f64,
},
GravityAnomaly {
meas: GravityAnomalyMeasurement,
elapsed_s: f64,
},
MagneticAnomaly {
meas: MagneticAnomalyMeasurement,
elapsed_s: f64,
},
}
Expand description
A simulation event delivered to the filter in time order.
Events represent sensor updates or other observations that occur during
playback of recorded data. The event stream is built by combining raw
logged records with a GnssDegradationConfig
(for GNSS scheduling and
fault injection), and then fed to the UKF loop.
Each variant bundles both the measurement itself and the elapsed simulation time when it occurred. This allows the filter to advance its state correctly and to process updates at realistic intervals.
§Variants
Imu
: An inertial measurement unit (IMU) step, including the time delta since the previous step. Drives the prediction step.Gnss
: A GNSS position/velocity fix (possibly degraded or spoofed).Altitude
: A relative altitude or barometric measurement, constraining vertical drift.GravityAnomaly
: A gravity anomaly measurement, derived from accelerometer or dedicated gravimeter data and matched against a gravity anomaly map.MagneticAnomaly
: A magnetic anomaly measurement, derived from magnetometer data (magnitude or components) and matched against a magnetic anomaly map.
§Extensibility
You can add further variants (e.g., Pressure
, SonarDepth
, StarTracker
)
in the same style if more sensors are to be fused.
§Example
use strapdown::messages::Event;
use strapdown::IMUData;
use strapdown::filter::{GPSPositionAndVelocityMeasurement, GravityAnomalyMeasurement, MagneticAnomalyMeasurement};
use nalgebra::Vector3;
// An IMU event with 0.01 s timestep
let imu_event = Event::Imu {
dt_s: 0.01,
imu: IMUData { accel: Vector3::new(0.0, 0.1, -9.8),
gyro: Vector3::new(0.001, 0.0, 0.0) },
elapsed_s: 1.23,
};
// A GNSS event
let gnss_meas = GPSPositionAndVelocityMeasurement {
latitude: 39.95,
longitude: -75.16,
altitude: 30.0,
northward_velocity: 0.1,
eastward_velocity: -0.2,
horizontal_noise_std: 5.0,
vertical_noise_std: 10.0,
velocity_noise_std: 0.2,
};
let gnss_event = Event::Gnss { meas: gnss_meas, elapsed_s: 2.0 };
Variants§
Imu
IMU prediction step.
dt_s
: Time delta since the previous event (seconds).imu
: Inertial data record (accelerometer, gyroscope, etc.).elapsed_s
: Elapsed simulation time at this event (seconds).
Gnss
GNSS position/velocity measurement (possibly degraded or spoofed).
meas
: GNSS measurement structure.elapsed_s
: Elapsed simulation time at this fix (seconds).
Altitude
Relative altitude or barometric measurement.
meas
: Altitude measurement structure.elapsed_s
: Elapsed simulation time at this measurement (seconds).
GravityAnomaly
Gravity anomaly measurement, used for map matching against known gravity anomalies.
Typically expressed in milligals (mGal).
meas
: Gravity anomaly measurement structure.elapsed_s
: Elapsed simulation time (seconds).
MagneticAnomaly
Magnetic anomaly measurement, used for map matching against magnetic anomaly maps.
Typically expressed in nanoteslas (nT).
meas
: Magnetic anomaly measurement structure.elapsed_s
: Elapsed simulation time (seconds).
Trait Implementations§
Auto Trait Implementations§
impl Freeze for Event
impl RefUnwindSafe for Event
impl Send for Event
impl Sync for Event
impl Unpin for Event
impl UnwindSafe for Event
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,
Source§impl<SS, SP> SupersetOf<SS> for SPwhere
SS: SubsetOf<SP>,
impl<SS, SP> SupersetOf<SS> for SPwhere
SS: SubsetOf<SP>,
Source§fn to_subset(&self) -> Option<SS>
fn to_subset(&self) -> Option<SS>
self
from the equivalent element of its
superset. Read moreSource§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).Source§fn to_subset_unchecked(&self) -> SS
fn to_subset_unchecked(&self) -> SS
self.to_subset
but without any property checks. Always succeeds.Source§fn from_subset(element: &SS) -> SP
fn from_subset(element: &SS) -> SP
self
to the equivalent element of its superset.Source§impl<SS, SP> SupersetOf<SS> for SPwhere
SS: SubsetOf<SP>,
impl<SS, SP> SupersetOf<SS> for SPwhere
SS: SubsetOf<SP>,
Source§fn to_subset(&self) -> Option<SS>
fn to_subset(&self) -> Option<SS>
self
from the equivalent element of its
superset. Read moreSource§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).Source§fn to_subset_unchecked(&self) -> SS
fn to_subset_unchecked(&self) -> SS
self.to_subset
but without any property checks. Always succeeds.Source§fn from_subset(element: &SS) -> SP
fn from_subset(element: &SS) -> SP
self
to the equivalent element of its superset.