strapdown/
sim.rs

1//! Simulation utilities and CSV data loading for strapdown inertial navigation.
2//!
3//! This module provides tools for simulating and evaluating strapdown inertial navigation systems.
4//! It is primarily designed to work with data produced from the [Sensor Logger](https://www.tszheichoi.com/sensorlogger)
5//! app, as such it makes assumptions about the data format and structure that that corresponds to
6//! how that app records data. That data is typically stored in CSV format and is represented by the
7//! `TestDataRecord` struct. This struct is fairly comprehensive and should be easily reusable for
8//! other applications. Modeling off of that struct is the `NavigationResult` struct which is used
9//! to store navigation solutions from simulations, such as dead reckoning or Kalman filtering.
10//!
11//! This module also provides basic functionality for analyzing canonical strapdown inertial navigation
12//! systems via the `dead_reckoning` and `closed_loop` functions. The `closed_loop` function in particular
13//! can also be used to simulate various types of GNSS-denied scenarios, such as intermittent, degraded,
14//! or intermittent and degraded GNSS via the measurement models provided in this module. You can install
15//! the programs that execute this generic simulation by installing the binary via `cargo install strapdown-rs`.
16use core::f64;
17use std::fmt::Display;
18use std::io::{self};
19use std::path::Path;
20
21use anyhow::{bail, Result};
22use chrono::{DateTime, Datelike, Duration, Utc};
23use nalgebra::{DMatrix, DVector, Vector3};
24use serde::{Deserialize, Serialize};
25use world_magnetic_model::GeomagneticField;
26use world_magnetic_model::time::{Date, Month};
27use world_magnetic_model::uom::si::angle::radian;
28use world_magnetic_model::uom::si::f32::{Angle, Length};
29use world_magnetic_model::uom::si::length::meter;
30
31use crate::earth::METERS_TO_DEGREES;
32use crate::filter::{
33    GPSPositionAndVelocityMeasurement, RelativeAltitudeMeasurement, StrapdownParams, UKF,
34};
35use crate::messages::{Event, EventStream};
36use crate::{IMUData, StrapdownState, forward};
37use health::{HealthLimits, HealthMonitor};
38
39/// Struct representing a single row of test data from the CSV file.
40///
41/// Fields correspond to columns in the CSV, with appropriate renaming for Rust style.
42/// This struct is setup to capture the data recorded from the [Sensor Logger](https://www.tszheichoi.com/sensorlogger) app.
43/// Primarily, this represents IMU data as (relative to the device) and GPS data.
44#[derive(Debug, Default, Deserialize, Serialize, Clone)]
45pub struct TestDataRecord {
46    /// Date-time string: YYYY-MM-DD hh:mm:ss+UTCTZ
47    //#[serde(with = "ts_seconds")]
48    pub time: DateTime<Utc>,
49    /// accuracy of the bearing (magnetic heading) in degrees
50    #[serde(rename = "bearingAccuracy")]
51    pub bearing_accuracy: f64,
52    /// accuracy of the speed in m/s
53    #[serde(rename = "speedAccuracy")]
54    pub speed_accuracy: f64,
55    /// accuracy of the altitude in meters
56    #[serde(rename = "verticalAccuracy")]
57    pub vertical_accuracy: f64,
58    /// accuracy of the horizontal position in meters
59    #[serde(rename = "horizontalAccuracy")]
60    pub horizontal_accuracy: f64,
61    /// Speed in m/s
62    pub speed: f64,
63    /// Bearing in degrees
64    pub bearing: f64,
65    /// Altitude in meters
66    pub altitude: f64,
67    /// Longitude in degrees
68    pub longitude: f64,
69    /// Latitude in degrees
70    pub latitude: f64,
71    /// Quaternion component representing the rotation around the z-axis
72    pub qz: f64,
73    /// Quaternion component representing the rotation around the y-axis
74    pub qy: f64,
75    /// Quaternion component representing the rotation around the x-axis
76    pub qx: f64,
77    /// Quaternion component representing the rotation around the w-axis
78    pub qw: f64,
79    /// Roll angle in radians
80    pub roll: f64,
81    /// Pitch angle in radians
82    pub pitch: f64,
83    /// Yaw angle in radians
84    pub yaw: f64,
85    /// Z-acceleration in m/s^2
86    pub acc_z: f64,
87    /// Y-acceleration in m/s^2
88    pub acc_y: f64,
89    /// X-acceleration in m/s^2
90    pub acc_x: f64,
91    /// Rotation rate around the z-axis in radians/s
92    pub gyro_z: f64,
93    /// Rotation rate around the y-axis in radians/s
94    pub gyro_y: f64,
95    /// Rotation rate around the x-axis in radians/s
96    pub gyro_x: f64,
97    /// Magnetic field strength in the z-direction in micro teslas
98    pub mag_z: f64,
99    /// Magnetic field strength in the y-direction in micro teslas
100    pub mag_y: f64,
101    /// Magnetic field strength in the x-direction in micro teslas
102    pub mag_x: f64,
103    /// Change in altitude in meters
104    #[serde(rename = "relativeAltitude")]
105    pub relative_altitude: f64,
106    /// pressure in millibars
107    pub pressure: f64,
108    /// Acceleration due to gravity in the z-direction in m/s^2
109    pub grav_z: f64,
110    /// Acceleration due to gravity in the y-direction in m/s^2
111    pub grav_y: f64,
112    /// Acceleration due to gravity in the x-direction in m/s^2
113    pub grav_x: f64,
114}
115impl TestDataRecord {
116    /// Reads a CSV file and returns a vector of `TestDataRecord` structs.
117    ///
118    /// # Arguments
119    /// * `path` - Path to the CSV file to read.
120    ///
121    /// # Returns
122    /// * `Ok(Vec<TestDataRecord>)` if successful.
123    /// * `Err` if the file cannot be read or parsed.
124    pub fn from_csv<P: AsRef<std::path::Path>>(
125        path: P,
126    ) -> Result<Vec<Self>, Box<dyn std::error::Error>> {
127        let mut rdr = csv::Reader::from_path(path)?;
128        let mut records = Vec::new();
129        for result in rdr.deserialize() {
130            let record: Self = result?;
131            records.push(record);
132        }
133        Ok(records)
134    }
135    /// Writes a vector of TestDataRecord structs to a CSV file.
136    ///
137    /// # Arguments
138    /// * `records` - Vector of TestDataRecord structs to write
139    /// * `path` - Path where the CSV file will be saved
140    ///
141    /// # Returns
142    /// * `io::Result<()>` - Ok if successful, Err otherwise
143    ///
144    /// # Example
145    ///
146    /// ```
147    /// use strapdown::sim::TestDataRecord;
148    /// use std::path::Path;
149    ///
150    /// let record = TestDataRecord {
151    ///     time: chrono::Utc::now(),
152    ///     bearing_accuracy: 0.1,
153    ///     speed_accuracy: 0.1,
154    ///     vertical_accuracy: 0.1,
155    ///     horizontal_accuracy: 0.1,
156    ///     speed: 1.0,
157    ///     bearing: 90.0,
158    ///     altitude: 100.0,
159    ///     longitude: -122.0,
160    ///     latitude: 37.0,
161    ///     qz: 0.0,
162    ///     qy: 0.0,
163    ///     qx: 0.0,
164    ///     qw: 1.0,
165    ///     roll: 0.0,
166    ///     pitch: 0.0,
167    ///     yaw: 0.0,
168    ///     acc_z: 9.81,
169    ///     acc_y: 0.0,
170    ///     acc_x: 0.0,
171    ///     gyro_z: 0.01,
172    ///     gyro_y: 0.01,
173    ///     gyro_x: 0.01,
174    ///     mag_z: 50.0,
175    ///     mag_y: -30.0,
176    ///     mag_x: -20.0,
177    ///     relative_altitude: 0.0,
178    ///     pressure: 1013.25,
179    ///     grav_z: 9.81,
180    ///     grav_y: 0.0,
181    ///     grav_x: 0.0,
182    /// };
183    /// let records = vec![record];
184    /// TestDataRecord::to_csv(&records, "data.csv")
185    ///    .expect("Failed to write test data to CSV");
186    /// // doctest cleanup
187    /// std::fs::remove_file("data.csv").unwrap();
188    /// ```
189    pub fn to_csv<P: AsRef<Path>>(records: &[Self], path: P) -> io::Result<()> {
190        let mut writer = csv::Writer::from_path(path)?;
191        for record in records {
192            writer.serialize(record)?;
193        }
194        writer.flush()?;
195        Ok(())
196    }
197}
198impl Display for TestDataRecord {
199    fn fmt(&self, f: &mut std::fmt::Formatter<'_>) -> std::fmt::Result {
200        write!(
201            f,
202            "TestDataRecord(time: {}, latitude: {}, longitude: {}, altitude: {}, speed: {}, bearing: {})",
203            self.time, self.latitude, self.longitude, self.altitude, self.speed, self.bearing
204        )
205    }
206}
207// ==== Helper structs for navigation simulations ====
208/// Struct representing the covariance diagonal of a navigation solution in NED coordinates.
209#[derive(Clone, Debug, Deserialize, Serialize)]
210pub struct NEDCovariance {
211    pub latitude_cov: f64,
212    pub longitude_cov: f64,
213    pub altitude_cov: f64,
214    pub velocity_n_cov: f64,
215    pub velocity_e_cov: f64,
216    pub velocity_d_cov: f64,
217    pub roll_cov: f64,
218    pub pitch_cov: f64,
219    pub yaw_cov: f64,
220    pub acc_bias_x_cov: f64,
221    pub acc_bias_y_cov: f64,
222    pub acc_bias_z_cov: f64,
223    pub gyro_bias_x_cov: f64,
224    pub gyro_bias_y_cov: f64,
225    pub gyro_bias_z_cov: f64,
226}
227/// Generic result struct for navigation simulations.
228///
229/// This structure contains a single row of position, velocity, and attitude vectors
230/// representing the navigation solution at a specific timestamp, along with the covariance diagonal,
231/// input IMU measurements, and derived geophysical values.
232///
233/// It can be used across different types of navigation simulations such as dead reckoning,
234/// Kalman filtering, or any other navigation algorithm.
235#[derive(Clone, Debug, Serialize, Deserialize)]
236pub struct NavigationResult {
237    /// Timestamp corresponding to the state
238    pub timestamp: DateTime<Utc>,
239    // ---- Navigation solution states ----
240    /// Latitude in radians
241    pub latitude: f64,
242    /// Longitude in radians
243    pub longitude: f64,
244    /// Altitude in meters
245    pub altitude: f64,
246    /// Northward velocity in m/s
247    pub velocity_north: f64,
248    /// Eastward velocity in m/s
249    pub velocity_east: f64,
250    /// Downward velocity in m/s
251    pub velocity_down: f64,
252    /// Roll angle in radians
253    pub roll: f64,
254    /// Pitch angle in radians
255    pub pitch: f64,
256    /// Yaw angle in radians
257    pub yaw: f64,
258    /// IMU accelerometer x-axis bias in m/s^2
259    pub acc_bias_x: f64,
260    /// IMU accelerometer y-axis bias in m/s^2
261    pub acc_bias_y: f64,
262    /// IMU accelerometer z-axis bias in m/s^2
263    pub acc_bias_z: f64,
264    /// IMU gyroscope x-axis bias in radians/s
265    pub gyro_bias_x: f64,
266    /// IMU gyroscope y-axis bias in radians/s
267    pub gyro_bias_y: f64,
268    /// IMU gyroscope z-axis bias in radians/s
269    pub gyro_bias_z: f64,
270    // ---- Covariance values for the navigation solution ----
271    /// Latitude covariance
272    pub latitude_cov: f64,
273    /// Longitude covariance
274    pub longitude_cov: f64,
275    /// Altitude covariance
276    pub altitude_cov: f64,
277    /// Northward velocity covariance
278    pub velocity_n_cov: f64,
279    /// Eastward velocity covariance
280    pub velocity_e_cov: f64,
281    /// Downward velocity covariance
282    pub velocity_d_cov: f64,
283    /// Roll covariance
284    pub roll_cov: f64,
285    /// Pitch covariance
286    pub pitch_cov: f64,
287    /// Yaw covariance
288    pub yaw_cov: f64,
289    /// Accelerometer x-axis bias covariance
290    pub acc_bias_x_cov: f64,
291    /// Accelerometer y-axis bias covariance
292    pub acc_bias_y_cov: f64,
293    /// Accelerometer z-axis bias covariance
294    pub acc_bias_z_cov: f64,
295    /// Gyroscope x-axis bias covariance
296    pub gyro_bias_x_cov: f64,
297    /// Gyroscope y-axis bias covariance
298    pub gyro_bias_y_cov: f64,
299    /// Gyroscope z-axis bias covariance
300    pub gyro_bias_z_cov: f64,
301}
302impl Default for NavigationResult {
303    fn default() -> Self {
304        NavigationResult {
305            timestamp: Utc::now(),
306            latitude: 0.0,
307            longitude: 0.0,
308            altitude: 0.0,
309            velocity_north: 0.0,
310            velocity_east: 0.0,
311            velocity_down: 0.0,
312            roll: 0.0,
313            pitch: 0.0,
314            yaw: 0.0,
315            acc_bias_x: 0.0,
316            acc_bias_y: 0.0,
317            acc_bias_z: 0.0,
318            gyro_bias_x: 0.0,
319            gyro_bias_y: 0.0,
320            gyro_bias_z: 0.0,
321            latitude_cov: 1e-6, // default covariance values
322            longitude_cov: 1e-6,
323            altitude_cov: 1e-6,
324            velocity_n_cov: 1e-6,
325            velocity_e_cov: 1e-6,
326            velocity_d_cov: 1e-6,
327            roll_cov: 1e-6,
328            pitch_cov: 1e-6,
329            yaw_cov: 1e-6,
330            acc_bias_x_cov: 1e-6,
331            acc_bias_y_cov: 1e-6,
332            acc_bias_z_cov: 1e-6,
333            gyro_bias_x_cov: 1e-6,
334            gyro_bias_y_cov: 1e-6,
335            gyro_bias_z_cov: 1e-6,
336        }
337    }
338}
339impl NavigationResult {
340    /// Creates a new NavigationResult with default values.
341    pub fn new() -> Self {
342        NavigationResult::default() // add in validation
343    }
344
345    /// Writes the NavigationResult to a CSV file.
346    ///
347    /// # Arguments
348    /// * `records` - Vector of NavigationResult structs to write
349    /// * `path` - Path where the CSV file will be saved
350    ///
351    /// # Returns
352    /// * `io::Result<()>` - Ok if successful, Err otherwise
353    pub fn to_csv<P: AsRef<Path>>(records: &[Self], path: P) -> io::Result<()> {
354        let mut writer = csv::Writer::from_path(path)?;
355        for record in records {
356            writer.serialize(record)?;
357        }
358        writer.flush()?;
359        Ok(())
360    }
361    /// Reads a CSV file and returns a vector of NavigationResult structs.
362    ///
363    /// # Arguments
364    /// * `path` - Path to the CSV file to read.
365    ///
366    /// # Returns
367    /// * `Ok(Vec<NavigationResult>)` if successful.
368    /// * `Err` if the file cannot be read or parsed.
369    pub fn from_csv<P: AsRef<std::path::Path>>(
370        path: P,
371    ) -> Result<Vec<Self>, Box<dyn std::error::Error>> {
372        let mut rdr = csv::Reader::from_path(path)?;
373        let mut records = Vec::new();
374        for result in rdr.deserialize() {
375            let record: Self = result?;
376            records.push(record);
377        }
378        Ok(records)
379    }
380}
381/// Convert DVectors containing the navigation state mean and covariance into a NavigationResult
382/// struct.
383///
384/// This implementation is useful for converting the output of a Kalman filter or UKF into a
385/// NavigationResult, which can then be used for further processing or analysis.
386///
387/// # Arguments
388/// - `timestamp`: The timestamp of the navigation solution.
389/// - `state`: A DVector containing the navigation state mean.
390/// - `covariance`: A DMatrix containing the covariance of the state.
391/// - `imu_data`: An IMUData struct containing the IMU measurements.
392/// - `mag_x`, `mag_y`, `mag_z`: Magnetic field strength in micro teslas.
393/// - `pressure`: Pressure in millibars.
394/// - `freeair`: Free-air gravity anomaly in mGal.
395///
396/// # Returns
397/// A NavigationResult struct containing the navigation solution.
398impl
399    From<(
400        &DateTime<Utc>,
401        &DVector<f64>,
402        &DMatrix<f64>,
403    )> for NavigationResult
404{
405    fn from(
406        (timestamp, state, covariance): (
407            &DateTime<Utc>,
408            &DVector<f64>,
409            &DMatrix<f64>,
410        ),
411    ) -> Self {
412        assert!(
413            state.len() == 15,
414            "State vector must have 15 elements; got {}",
415            state.len()
416        );
417        assert!(
418            covariance.nrows() == 15 && covariance.ncols() == 15,
419            "Covariance matrix must be 15x15"
420        );
421        let covariance = DVector::from_vec(covariance.diagonal().iter().map(|&x| x).collect());
422        let wmm_date: Date = Date::from_calendar_date(
423            timestamp.year(),
424            Month::try_from(timestamp.month() as u8).unwrap(),
425            timestamp.day() as u8,
426        )
427        .expect("Invalid date for world magnetic model");
428        let magnetic_field = GeomagneticField::new(
429            Length::new::<meter>(state[2] as f32),
430            Angle::new::<radian>(state[0] as f32),
431            Angle::new::<radian>(state[1] as f32),
432            wmm_date,
433        );
434        NavigationResult {
435            timestamp: *timestamp,
436            latitude: state[0].to_degrees(),
437            longitude: state[1].to_degrees(),
438            altitude: state[2],
439            velocity_north: state[3],
440            velocity_east: state[4],
441            velocity_down: state[5],
442            roll: state[6],
443            pitch: state[7],
444            yaw: state[8],
445            acc_bias_x: state[9],
446            acc_bias_y: state[10],
447            acc_bias_z: state[11],
448            gyro_bias_x: state[12],
449            gyro_bias_y: state[13],
450            gyro_bias_z: state[14],
451            latitude_cov: covariance[0],
452            longitude_cov: covariance[1],
453            altitude_cov: covariance[2],
454            velocity_n_cov: covariance[3],
455            velocity_e_cov: covariance[4],
456            velocity_d_cov: covariance[5],
457            roll_cov: covariance[6],
458            pitch_cov: covariance[7],
459            yaw_cov: covariance[8],
460            acc_bias_x_cov: covariance[9],
461            acc_bias_y_cov: covariance[10],
462            acc_bias_z_cov: covariance[11],
463            gyro_bias_x_cov: covariance[12],
464            gyro_bias_y_cov: covariance[13],
465            gyro_bias_z_cov: covariance[14],
466        }
467    }
468}
469/// Convert NED UKF to NavigationResult.
470///
471/// This implementation is useful for converting the output of a UKF into a
472/// NavigationResult, which can then be used for further processing or analysis.
473///
474/// # Arguments
475/// - `timestamp`: The timestamp of the navigation solution.
476/// - `ukf`: A reference to the UKF instance containing the navigation state mean and covariance.
477/// - `imu_data`: An IMUData struct containing the IMU measurements.
478/// - `magnetic_vector`: Magnetic field strength measurement in micro teslas (body frame x, y, z).
479/// - `pressure`: Pressure in millibars.
480///
481/// # Returns
482/// A NavigationResult struct containing the navigation solution.
483impl From<(&DateTime<Utc>, &UKF)> for NavigationResult {
484    fn from(
485        (timestamp, ukf): (
486            &DateTime<Utc>,
487            &UKF,
488        ),
489    ) -> Self {
490        let state = &ukf.get_mean();
491        let covariance = ukf.get_covariance();
492        NavigationResult {
493            timestamp: timestamp.clone(),
494            latitude: state[0].to_degrees(),
495            longitude: state[1].to_degrees(),
496            altitude: state[2],
497            velocity_north: state[3],
498            velocity_east: state[4],
499            velocity_down: state[5],
500            roll: state[6],
501            pitch: state[7],
502            yaw: state[8],
503            acc_bias_x: state[9],
504            acc_bias_y: state[10],
505            acc_bias_z: state[11],
506            gyro_bias_x: state[12],
507            gyro_bias_y: state[13],
508            gyro_bias_z: state[14],
509            latitude_cov: covariance[(0, 0)],
510            longitude_cov: covariance[(1, 1)],
511            altitude_cov: covariance[(2, 2)],
512            velocity_n_cov: covariance[(3, 3)],
513            velocity_e_cov: covariance[(4, 4)],
514            velocity_d_cov: covariance[(5, 5)],
515            roll_cov: covariance[(6, 6)],
516            pitch_cov: covariance[(7, 7)],
517            yaw_cov: covariance[(8, 8)],
518            acc_bias_x_cov: covariance[(9, 9)],
519            acc_bias_y_cov: covariance[(10, 10)],
520            acc_bias_z_cov: covariance[(11, 11)],
521            gyro_bias_x_cov: covariance[(12, 12)],
522            gyro_bias_y_cov: covariance[(13, 13)],
523            gyro_bias_z_cov: covariance[(14, 14)],
524        }
525    }
526}
527/// Convert StrapdownState to NavigationResult.
528///
529/// This implementation is useful for converting the output of a StrapdownState into a
530/// NavigationResult, which can then be used for further processing or analysis.
531///
532/// # Arguments
533/// - `timestamp`: The timestamp of the navigation solution.
534/// - `state`: A reference to the StrapdownState instance containing the navigation state.
535/// - `imu_data`: An IMUData struct containing the IMU measurements.
536/// - `magnetic_vector`: Magnetic field strength measurement in micro teslas (body frame x, y, z).
537/// - `pressure`: Pressure in millibars.
538/// # Returns
539/// A NavigationResult struct containing the navigation solution.
540impl
541    From<(
542        &DateTime<Utc>,
543        &StrapdownState,
544        &IMUData,
545        &Vector3<f64>,
546        &f64,
547    )> for NavigationResult
548{
549    fn from(
550        (timestamp, state, imu_data, magnetic_vector, pressure): (
551            &DateTime<Utc>,
552            &StrapdownState,
553            &IMUData,
554            &Vector3<f64>,
555            &f64,
556        ),
557    ) -> Self {
558        let wmm_date: Date = Date::from_calendar_date(
559            timestamp.year(),
560            Month::try_from(timestamp.month() as u8).unwrap(),
561            timestamp.day() as u8,
562        )
563        .expect("Invalid date for world magnetic model");
564        let magnetic_field = GeomagneticField::new(
565            Length::new::<meter>(state.altitude as f32),
566            Angle::new::<radian>(state.latitude as f32),
567            Angle::new::<radian>(state.longitude as f32),
568            wmm_date,
569        );
570        NavigationResult {
571            timestamp: timestamp.clone(),
572            latitude: state.latitude.to_degrees(),
573            longitude: state.longitude.to_degrees(),
574            altitude: state.altitude,
575            velocity_north: state.velocity_north,
576            velocity_east: state.velocity_east,
577            velocity_down: state.velocity_down,
578            roll: state.attitude.euler_angles().0,
579            pitch: state.attitude.euler_angles().1,
580            yaw: state.attitude.euler_angles().2,
581            acc_bias_x: 0.0, // StrapdownState does not store biases
582            acc_bias_y: 0.0,
583            acc_bias_z: 0.0,
584            gyro_bias_x: 0.0,
585            gyro_bias_y: 0.0,
586            gyro_bias_z: 0.0,
587            latitude_cov: f64::NAN, // default covariance values
588            longitude_cov: f64::NAN,
589            altitude_cov: f64::NAN,
590            velocity_n_cov: f64::NAN,
591            velocity_e_cov: f64::NAN,
592            velocity_d_cov: f64::NAN,
593            roll_cov: f64::NAN,
594            pitch_cov: f64::NAN,
595            yaw_cov: f64::NAN,
596            acc_bias_x_cov: f64::NAN,
597            acc_bias_y_cov: f64::NAN,
598            acc_bias_z_cov: f64::NAN,
599            gyro_bias_x_cov: f64::NAN,
600            gyro_bias_y_cov: f64::NAN,
601            gyro_bias_z_cov: f64::NAN,
602        }
603    }
604}
605/// Run dead reckoning or "open-loop" simulation using test data.
606///
607/// This function processes a sequence of sensor records through a StrapdownState, using
608/// the "forward" method to propagate the state based on IMU measurements. It initializes
609/// the StrapdownState with position, velocity, and attitude from the first record, and
610/// then applies the IMU measurements from subsequent records. It does not record the
611/// errors or confidence values, as this is a simple dead reckoning simulation and in testing
612/// these values would be used as a baseline for comparison. Keep in mind that this toolbox
613/// is designed for the local level frame of reference and the forward mechanization is typically
614/// only valid at lower latitude (e.g. < 60 degrees) and at low altitudes (e.g. < 1000m). With
615/// that, remember that dead reckoning is subject to drift and errors accumulate over time relative
616/// to the quality of the IMU data. Poor quality IMU data (e.g. MEMS grade IMUs) will lead to
617/// significant drift very quickly which may cause this function to produce unrealistic results,
618/// hang, or crash.
619///
620/// # Arguments
621/// * `records` - Vector of test data records containing IMU measurements and other sensor data
622///
623/// # Returns
624/// * `Vec<NavigationResult>` containing the sequence of StrapdownState instances over time,
625///   along with timestamps and time differences.
626pub fn dead_reckoning(records: &[TestDataRecord]) -> Vec<NavigationResult> {
627    if records.is_empty() {
628        return Vec::new();
629    }
630    // Initialize the result vector
631    let mut results = Vec::with_capacity(records.len());
632    // Initialize the StrapdownState with the first record
633    let first_record = &records[0];
634    let attitude = nalgebra::Rotation3::from_euler_angles(
635        first_record.roll,
636        first_record.pitch,
637        first_record.yaw,
638    );
639    let mut state = StrapdownState {
640        latitude: first_record.latitude.to_radians(),
641        longitude: first_record.longitude.to_radians(),
642        altitude: first_record.altitude,
643        velocity_north: first_record.speed * first_record.bearing.cos(),
644        velocity_east: first_record.speed * first_record.bearing.sin(),
645        velocity_down: 0.0, // initial velocities
646        attitude,
647        coordinate_convention: true,
648    };
649    // Store the initial state and metadata
650    results.push(NavigationResult::from((
651        &first_record.time,
652        &state.into(),
653        &DMatrix::from_diagonal(&DVector::from_element(15, 0.0)),
654    )));
655    let mut previous_time = records[0].time;
656    // Process each subsequent record
657    for record in records.iter().skip(1) {
658        // Try to calculate time difference from timestamps, default to 1 second if parsing fails
659        let current_time = record.time;
660        let dt = (current_time - previous_time).as_seconds_f64();
661        // Create IMU data from the record
662        let imu_data = IMUData {
663            accel: Vector3::new(record.acc_x, record.acc_y, record.acc_z),
664            gyro: Vector3::new(record.gyro_x, record.gyro_y, record.gyro_z),
665        };
666        forward(&mut state, imu_data, dt);
667        results.push(NavigationResult::from((
668            &current_time,
669            &state.into(),
670            &DMatrix::from_diagonal(&DVector::from_element(15, 0.0)),
671        )));
672        previous_time = record.time;
673    }
674    results
675}
676/// Closed-loop GPS-aided inertial navigation simulation.
677///
678/// This function simulates a closed-loop full-state navigation system where GPS measurements are used
679/// to correct the inertial navigation solution. It implements an Unscented Kalman Filter (UKF) to propagate
680/// the state and update it with GPS measurements when available.
681///
682/// # Arguments
683/// * `records` - Vector of test data records containing IMU measurements and GPS data.
684/// # Returns
685/// * `Vec<NavigationResult>` - A vector of navigation results containing the state estimates and covariances at each timestamp.
686pub fn closed_loop(ukf: &mut UKF, stream: EventStream) -> anyhow::Result<Vec<NavigationResult>> {
687    let start_time = stream.start_time;
688    let mut results: Vec<NavigationResult> = Vec::with_capacity(stream.events.len());
689    let total = stream.events.len();
690    let mut last_ts: Option<DateTime<Utc>> = None;
691    let mut monitor = HealthMonitor::new(HealthLimits::default());
692
693    for (i, event) in stream.events.into_iter().enumerate() {
694        // Print progress every 10 iterations
695        if i % 10 == 0 || i == total {
696            print!(
697                "\rProcessing data {:.2}%...",
698                (i as f64 / total as f64) * 100.0
699            );
700            //print_ukf(&ukf, record);
701            use std::io::Write;
702            std::io::stdout().flush().ok();
703        }
704        // Compute wall-clock time for this event
705        let elapsed_s = match &event {
706            Event::Imu { elapsed_s, .. } => *elapsed_s,
707            Event::Gnss { elapsed_s, .. } => *elapsed_s,
708            Event::Altitude { elapsed_s, .. } => *elapsed_s,
709            Event::GravityAnomaly { elapsed_s, .. } => *elapsed_s,
710            Event::MagneticAnomaly { elapsed_s, .. } => *elapsed_s,
711        };
712        let ts = start_time + Duration::milliseconds((elapsed_s * 1000.0).round() as i64);
713        // Apply event
714        match event {
715            Event::Imu { dt_s, imu, .. } => {
716                ukf.predict(imu, dt_s);
717                if let Err(e) = monitor.check(ukf.get_mean().as_slice(), &ukf.get_covariance(), None) {
718                    // log::error!("Health fail after predict at {} (#{i}): {e}", ts);
719                    bail!(e);
720                }
721            },
722            Event::Gnss { meas, .. } => {
723                ukf.update(meas);
724                if let Err(e) = monitor.check(ukf.get_mean().as_slice(), &ukf.get_covariance(), None) {
725                    // log::error!("Health fail after GNSS update at {} (#{i}): {e}", ts);
726                    bail!(e);
727                }
728            },
729            Event::Altitude { meas, .. } => {
730                ukf.update(meas);
731                if let Err(e) = monitor.check(ukf.get_mean().as_slice(), &ukf.get_covariance(), None) {
732                    // log::error!("Health fail after altitude update at {} (#{i}): {e}", ts);
733                    bail!(e);
734                }
735            },
736            Event::GravityAnomaly { meas, elapsed_s } => {
737                println!("Gravity anomaly detected: {:?} at {:?}s", meas, elapsed_s);
738            }
739            Event::MagneticAnomaly { meas, elapsed_s } => {
740                println!("Magnetic anomaly detected: {:?} at {:?}s", meas, elapsed_s);
741            }
742        }
743        // If timestamp changed, or it's the last event, record the previous state
744        if Some(ts) != last_ts {
745            if let Some(prev_ts) = last_ts {
746                results.push(NavigationResult::from((&prev_ts, &*ukf)));
747            }
748            last_ts = Some(ts);
749        }
750        // If this is the last event, also push
751        if i == total - 1 {
752            results.push(NavigationResult::from((&ts, &*ukf)));
753        }
754    }
755    println!("Done!");
756    Ok(results)
757}
758/// Print the UKF state and covariance for debugging purposes.
759pub fn print_ukf(ukf: &UKF, record: &TestDataRecord) {
760    println!(
761        "\rUKF position: ({:.4}, {:.4}, {:.4})  |  Covariance: {:.4e}, {:.4e}, {:.4}  |  Error: {:.4e}, {:.4e}, {:.4}",
762        ukf.get_mean()[0].to_degrees(),
763        ukf.get_mean()[1].to_degrees(),
764        ukf.get_mean()[2],
765        ukf.get_covariance()[(0, 0)],
766        ukf.get_covariance()[(1, 1)],
767        ukf.get_covariance()[(2, 2)],
768        ukf.get_mean()[0].to_degrees() - record.latitude,
769        ukf.get_mean()[1].to_degrees() - record.longitude,
770        ukf.get_mean()[2] - record.altitude
771    );
772    println!(
773        "\rUKF velocity: ({:.4}, {:.4}, {:.4})  | Covariance: {:.4}, {:.4}, {:.4}  | Error: {:.4}, {:.4}, {:.4}",
774        ukf.get_mean()[3],
775        ukf.get_mean()[4],
776        ukf.get_mean()[5],
777        ukf.get_covariance()[(3, 3)],
778        ukf.get_covariance()[(4, 4)],
779        ukf.get_covariance()[(5, 5)],
780        ukf.get_mean()[3] - record.speed * record.bearing.cos(),
781        ukf.get_mean()[4] - record.speed * record.bearing.sin(),
782        ukf.get_mean()[5] - 0.0 // Assuming no vertical velocity
783    );
784    println!(
785        "\rUKF attitude: ({:.4}, {:.4}, {:.4})  | Covariance: {:.4}, {:.4}, {:.4}  | Error: {:.4}, {:.4}, {:.4}",
786        ukf.get_mean()[6],
787        ukf.get_mean()[7],
788        ukf.get_mean()[8],
789        ukf.get_covariance()[(6, 6)],
790        ukf.get_covariance()[(7, 7)],
791        ukf.get_covariance()[(8, 8)],
792        ukf.get_mean()[6] - record.roll,
793        ukf.get_mean()[7] - record.pitch,
794        ukf.get_mean()[8] - record.yaw
795    );
796    println!(
797        "\rUKF accel biases: ({:.4}, {:.4}, {:.4})  | Covariance: {:.4e}, {:.4e}, {:.4e}",
798        ukf.get_mean()[9],
799        ukf.get_mean()[10],
800        ukf.get_mean()[11],
801        ukf.get_covariance()[(9, 9)],
802        ukf.get_covariance()[(10, 10)],
803        ukf.get_covariance()[(11, 11)]
804    );
805    println!(
806        "\rUKF gyro biases: ({:.4}, {:.4}, {:.4})  | Covariance: {:.4e}, {:.4e}, {:.4e}",
807        ukf.get_mean()[12],
808        ukf.get_mean()[13],
809        ukf.get_mean()[14],
810        ukf.get_covariance()[(12, 12)],
811        ukf.get_covariance()[(13, 13)],
812        ukf.get_covariance()[(14, 14)]
813    );
814}
815/// Helper function to initialize a UKF for closed-loop mode.
816///
817/// This function sets up the Unscented Kalman Filter (UKF) with initial pose, attitude covariance, and IMU biases based on
818/// the provided `TestDataRecord`. It initializes the UKF with position, velocity, attitude, and covariance matrices.
819/// Optional parameters for attitude covariance and IMU biases can be provided to customize the filter's initial state.
820///
821/// # Arguments
822///
823/// * `initial_pose` - A `TestDataRecord` containing the initial pose information.
824/// * `attitude_covariance` - Optional vector of f64 representing the initial attitude covariance (default is a small value).
825/// * `imu_biases` - Optional vector of f64 representing the initial IMU biases (default is a small value).
826///
827/// # Returns
828///
829/// * `UKF` - An instance of the Unscented Kalman Filter initialized with the provided parameters.
830pub fn initialize_ukf(
831    initial_pose: TestDataRecord,
832    attitude_covariance: Option<Vec<f64>>,
833    imu_biases: Option<Vec<f64>>,
834) -> UKF {
835    let ukf_params = StrapdownParams {
836        latitude: initial_pose.latitude,
837        longitude: initial_pose.longitude,
838        altitude: initial_pose.altitude,
839        northward_velocity: initial_pose.speed * initial_pose.bearing.cos(),
840        eastward_velocity: initial_pose.speed * initial_pose.bearing.sin(),
841        downward_velocity: 0.0, // Assuming no initial vertical velocity for simplicity
842        roll: initial_pose.roll,
843        pitch: initial_pose.pitch,
844        yaw: initial_pose.yaw,
845        in_degrees: true,
846    };
847    // Covariance parameters
848    let position_accuracy = initial_pose.horizontal_accuracy; //.sqrt();
849    let mut covariance_diagonal = vec![
850        (position_accuracy * METERS_TO_DEGREES).powf(2.0),
851        (position_accuracy * METERS_TO_DEGREES).powf(2.0),
852        initial_pose.vertical_accuracy.powf(2.0),
853        initial_pose.speed_accuracy.powf(2.0),
854        initial_pose.speed_accuracy.powf(2.0),
855        initial_pose.speed_accuracy.powf(2.0),
856    ];
857    // extend the covariance diagonal if attitude covariance is provided
858    match attitude_covariance {
859        Some(att_cov) => covariance_diagonal.extend(att_cov),
860        None => covariance_diagonal.extend(vec![1e-9; 3]), // Default values if not provided
861    }
862    // extend the covariance diagonal if imu biases are provided
863    let imu_bias = match imu_biases {
864        Some(imu_biases) => {
865            covariance_diagonal.extend(&imu_biases);
866            imu_biases
867        }
868        None => {
869            covariance_diagonal.extend(vec![1e-3; 6]);
870            vec![1e-3; 6] // Default values if not provided
871        }
872    };
873    //let mut process_noise_diagonal = vec![1e-9; 9]; // adds a minor amount of noise to base states
874    //process_noise_diagonal.extend(vec![1e-9; 6]); // Process noise for imu biases
875    let process_noise_diagonal = DVector::from_vec(vec![
876        1e-6, // position noise 1e-6
877        1e-6, // position noise 1e-6
878        1e-6, // altitude noise
879        1e-3, // velocity north noise
880        1e-3, // velocity east noise
881        1e-3, // velocity down noise
882        1e-5, // roll noise
883        1e-5, // pitch noise
884        1e-5, // yaw noise
885        1e-6, // acc bias x noise
886        1e-6, // acc bias y noise
887        1e-6, // acc bias z noise
888        1e-8, // gyro bias x noise
889        1e-8, // gyro bias y noise
890        1e-8, // gyro bias z noise
891    ]);
892    //DVector::from_vec(vec![0.0; 15]);
893    UKF::new(
894        ukf_params,
895        imu_bias,
896        None,
897        covariance_diagonal,
898        DMatrix::from_diagonal(&process_noise_diagonal),
899        1e-3, // Use a scalar for measurement noise as expected by UKF::new
900        2.0,
901        0.0,
902    )
903}
904
905pub mod health {
906    use super::*;
907
908    #[derive(Clone, Debug)]
909    pub struct HealthLimits {
910        pub lat_rad: (f64, f64),   // [-90°, +90°]
911        pub lon_rad: (f64, f64),   // [-180°, +180°]
912        pub alt_m:   (f64, f64),   // e.g., [-500, 15000]
913        pub speed_mps_max: f64,    // e.g., 120 m/s (road/low-altitude aircraft)
914        pub cov_diag_max: f64,     // e.g., 1e6
915        pub cond_max: f64,         // e.g., 1e12 (optional)
916        pub nis_pos_max: f64,      // e.g., 100 (huge outlier)
917        pub nis_pos_consec_fail: usize, // e.g., 20
918    }
919
920    impl Default for HealthLimits {
921        fn default() -> Self {
922            Self {
923                lat_rad: (-std::f64::consts::FRAC_PI_2, std::f64::consts::FRAC_PI_2),
924                lon_rad: (-std::f64::consts::PI, std::f64::consts::PI),
925                alt_m:   (-500.0, 15000.0),
926                speed_mps_max: 120.0,
927                cov_diag_max: 1e6,
928                cond_max: 1e12,
929                nis_pos_max: 100.0,
930                nis_pos_consec_fail: 20,
931            }
932        }
933    }
934
935    #[derive(Default, Clone, Debug)]
936    pub struct HealthMonitor {
937        limits: HealthLimits,
938        consec_nis_pos_fail: usize,
939    }
940
941    impl HealthMonitor {
942        pub fn new(limits: HealthLimits) -> Self { Self { limits, consec_nis_pos_fail: 0 } }
943
944        /// Call after **every event** (predict or update). Provide optional NIS when you have a GNSS update.
945        pub fn check(
946            &mut self,
947            x: &[f64],             // your mean_state slice
948            p: &nalgebra::DMatrix<f64>,
949            maybe_nis_pos: Option<f64>,
950        ) -> Result<()> {
951            // 1) Finite checks
952            if !x.iter().all(|v| v.is_finite()) { bail!("Non-finite state detected"); }
953            if !p.iter().all(|v| v.is_finite()) { bail!("Non-finite covariance detected"); }
954
955            // 2) Basic bounds (lat, lon, alt)
956            let lat = x[0]; let lon = x[1]; let alt = x[2];
957            if lat < self.limits.lat_rad.0 || lat > self.limits.lat_rad.1 { bail!("Latitude out of range: {lat}"); }
958            if lon < self.limits.lon_rad.0 || lon > self.limits.lon_rad.1 { bail!("Longitude out of range: {lon}"); }
959            if alt < self.limits.alt_m.0   || alt > self.limits.alt_m.1   { bail!("Altitude out of range: {alt} m"); }
960
961            // 3) Speed sanity (assumes NED velocities at indices 3..=5)
962            let v2 = x[3]*x[3] + x[4]*x[4] + x[5]*x[5];
963            if v2.is_finite() && v2.sqrt() > self.limits.speed_mps_max {
964                bail!("Speed exceeded: {:.2} m/s", v2.sqrt());
965            }
966
967            // 4) Covariance sanity: diagonals and simple SPD probe
968            for i in 0..p.nrows().min(p.ncols()) {
969                if p[(i,i)].is_sign_negative() { bail!("Negative variance on diagonal: idx={i}, val={}", p[(i,i)]); }
970                if p[(i,i)] > self.limits.cov_diag_max { bail!("Variance too large on diagonal idx={i}: {}", p[(i,i)]); }
971            }
972            // (Optional) rough condition estimate via Frobenius norm and inverse
973            // Skip if too expensive; enable only for debugging.
974            // if let Some(inv) = p.clone().try_inverse() {
975            //     let cond = p.norm_fro() * inv.norm_fro();
976            //     if !cond.is_finite() || cond > self.limits.cond_max { bail!("Covariance condition number too large: {cond:e}"); }
977            // }
978
979            // 5) GNSS gating streak (if a NIS was computed at update time)
980            if let Some(nis_pos) = maybe_nis_pos {
981                if !nis_pos.is_finite() || nis_pos.is_sign_negative() {
982                    bail!("Invalid NIS value: {nis_pos}");
983                }
984                if nis_pos > self.limits.nis_pos_max {
985                    self.consec_nis_pos_fail += 1;
986                    if self.consec_nis_pos_fail >= self.limits.nis_pos_consec_fail {
987                        bail!("Consecutive NIS exceedances: {} (> {}), last NIS={}",
988                            self.consec_nis_pos_fail, self.limits.nis_pos_consec_fail, nis_pos);
989                    }
990                } else {
991                    self.consec_nis_pos_fail = 0;
992                }
993            }
994
995            Ok(())
996        }
997    }
998}
999
1000#[cfg(test)]
1001mod tests {
1002    use super::*;
1003    use std::fs::File;
1004    use std::path::Path;
1005    use std::vec;
1006
1007    /// Generate a test record for northward motion at constant velocity (1 knot = 1852 m/h).
1008    /// This helper returns a Vec<TestDataRecord> for 1 hour, sampled once per second.
1009    fn generate_northward_motion_records() -> Vec<TestDataRecord> {
1010        let mut records: Vec<TestDataRecord> = Vec::with_capacity(3601);
1011        let start_lat: f64 = 0.0;
1012        let start_lon: f64 = 0.0;
1013        let start_alt: f64 = 0.0;
1014        let velocity_mps: f64 = 1852.0 / 3600.0; // 1 knot in m/s
1015        let earth_radius: f64 = 6371000.0_f64; // meters
1016
1017        for t in 0..3600 {
1018            // Each second, latitude increases by dlat = (v / R) * (180/pi)
1019            let dlat: f64 =
1020                (velocity_mps * t as f64) / earth_radius * (180.0 / std::f64::consts::PI);
1021            let time_str: String = format!("2023-01-01 00:{:02}:{:02}+00:00", t / 60, t % 60);
1022
1023            records.push(TestDataRecord {
1024                time: DateTime::parse_from_str(&time_str, "%Y-%m-%d %H:%M:%S%z")
1025                    .map(|dt| dt.with_timezone(&Utc))
1026                    .unwrap(),
1027                bearing_accuracy: 0.0,
1028                speed_accuracy: 0.0,
1029                vertical_accuracy: 0.0,
1030                horizontal_accuracy: 0.0,
1031                speed: velocity_mps,
1032                bearing: 0.0,
1033                altitude: start_alt,
1034                longitude: start_lon,
1035                latitude: start_lat + dlat,
1036                qz: 0.0,
1037                qy: 0.0,
1038                qx: 0.0,
1039                qw: 1.0,
1040                roll: 0.0,
1041                pitch: 0.0,
1042                yaw: 0.0,
1043                acc_z: 0.0,
1044                acc_y: 0.0,
1045                acc_x: 0.0,
1046                gyro_z: 0.0,
1047                gyro_y: 0.0,
1048                gyro_x: 0.0,
1049                mag_z: 0.0,
1050                mag_y: 0.0,
1051                mag_x: 0.0,
1052                relative_altitude: 0.0,
1053                pressure: 1000.0,
1054                grav_z: 9.81,
1055                grav_y: 0.0,
1056                grav_x: 0.0,
1057            });
1058        }
1059        records
1060    }
1061    #[test]
1062    fn test_generate_northward_motion_records_end_latitude() {
1063        let records = generate_northward_motion_records();
1064        // The last record should have latitude close to 0.016667 (1 knot north in 1 hour)
1065        let last = records.last().unwrap();
1066        let expected_lat = 0.016667;
1067        let tolerance = 1e-3;
1068        assert!(
1069            (last.latitude - expected_lat).abs() < tolerance,
1070            "Ending latitude {} not within {} of expected {}",
1071            last.latitude,
1072            tolerance,
1073            expected_lat
1074        );
1075        // write to CSV
1076        let northward = File::create("northward_motion.csv").unwrap();
1077        let mut writer = csv::Writer::from_writer(northward);
1078        for record in &records {
1079            writer.serialize(record).unwrap();
1080        }
1081        writer.flush().unwrap();
1082        // Clean up the test file
1083        let _ = std::fs::remove_file("northward_motion.csv");
1084    }
1085    /// Test that reading a missing file returns an error.
1086    #[test]
1087    fn test_test_data_record_from_csv_invalid_path() {
1088        let path = Path::new("nonexistent.csv");
1089        let result = TestDataRecord::from_csv(path);
1090        assert!(result.is_err(), "Should error on missing file");
1091    }
1092    /// Test writing TestDataRecord to CSV and reading it back
1093    #[test]
1094    fn test_data_record_to_and_from_csv() {
1095        // Read original records
1096        let path = Path::new("test_file.csv");
1097        let mut records: Vec<TestDataRecord> = vec![];
1098        // Create some test data records
1099        records.push(TestDataRecord {
1100            time: DateTime::parse_from_str("2023-01-01 00:00:00+00:00", "%Y-%m-%d %H:%M:%S%z")
1101                .unwrap()
1102                .with_timezone(&Utc),
1103            bearing_accuracy: 0.1,
1104            speed_accuracy: 0.1,
1105            vertical_accuracy: 0.1,
1106            horizontal_accuracy: 0.1,
1107            speed: 1.0,
1108            bearing: 90.0,
1109            altitude: 100.0,
1110            longitude: -122.0,
1111            latitude: 37.0,
1112            qz: 0.0,
1113            qy: 0.0,
1114            qx: 0.0,
1115            qw: 1.0,
1116            roll: 0.0,
1117            pitch: 0.0,
1118            yaw: 0.0,
1119            acc_z: 9.81,
1120            acc_y: 0.0,
1121            acc_x: 0.0,
1122            gyro_z: 0.01,
1123            gyro_y: 0.01,
1124            gyro_x: 0.01,
1125            mag_z: 50.0,
1126            mag_y: -30.0,
1127            mag_x: -20.0,
1128            relative_altitude: 5.0,
1129            pressure: 1013.25,
1130            grav_z: 9.81,
1131            grav_y: 0.0,
1132            grav_x: 0.0,
1133        });
1134        records.push(TestDataRecord {
1135            time: DateTime::parse_from_str("2023-01-01 00:01:00+00:00", "%Y-%m-%d %H:%M:%S%z")
1136                .unwrap()
1137                .with_timezone(&Utc),
1138            bearing_accuracy: 0.1,
1139            speed_accuracy: 0.1,
1140            vertical_accuracy: 0.1,
1141            horizontal_accuracy: 0.1,
1142            speed: 2.0,
1143            bearing: 180.0,
1144            altitude: 200.0,
1145            longitude: -121.0,
1146            latitude: 38.0,
1147            qz: 0.0,
1148            qy: 0.0,
1149            qx: 0.0,
1150            qw: 1.0,
1151            roll: 0.1,
1152            pitch: 0.1,
1153            yaw: 0.1,
1154            acc_z: 9.81,
1155            acc_y: 0.01,
1156            acc_x: -0.01,
1157            gyro_z: 0.02,
1158            gyro_y: -0.02,
1159            gyro_x: 0.02,
1160            mag_z: 55.0,
1161            mag_y: -25.0,
1162            mag_x: -15.0,
1163            relative_altitude: 10.0,
1164            pressure: 1012.25,
1165            grav_z: 9.81,
1166            grav_y: 0.01,
1167            grav_x: -0.01,
1168        });
1169        // Write to CSV
1170        TestDataRecord::to_csv(&records, path).expect("Failed to write test data to CSV");
1171        // Check to make sure the file exists
1172        assert!(path.exists(), "Test data CSV file should exist");
1173        // Read back from CSV
1174        let read_records =
1175            TestDataRecord::from_csv(path).expect("Failed to read test data from CSV");
1176        // Check that the read records match the original
1177        assert_eq!(
1178            read_records.len(),
1179            records.len(),
1180            "Record count should match"
1181        );
1182        for (i, record) in read_records.iter().enumerate() {
1183            assert_eq!(record.time, records[i].time, "Timestamps should match");
1184            assert!(
1185                (record.latitude - records[i].latitude).abs() < 1e-6,
1186                "Latitudes should match"
1187            );
1188            assert!(
1189                (record.longitude - records[i].longitude).abs() < 1e-6,
1190                "Longitudes should match"
1191            );
1192            assert!(
1193                (record.altitude - records[i].altitude).abs() < 1e-6,
1194                "Altitudes should match"
1195            );
1196            // Add more assertions as needed for other fields
1197        }
1198        // Clean up
1199        let _ = std::fs::remove_file(path);
1200    }
1201    #[test]
1202    fn test_navigation_result_new() {
1203        let nav = NavigationResult::default();
1204        //let expected_timestamp = chrono::Utc::now();
1205        //assert_eq!(nav.timestamp, expected_timestamp);
1206        assert_eq!(nav.latitude, 0.0);
1207        assert_eq!(nav.longitude, 0.0);
1208        assert_eq!(nav.altitude, 0.0);
1209        assert_eq!(nav.velocity_north, 0.0);
1210        assert_eq!(nav.velocity_east, 0.0);
1211        assert_eq!(nav.velocity_down, 0.0);
1212    }
1213    #[test]
1214    fn test_navigation_result_from_strapdown_state() {
1215        let mut state = StrapdownState::default();
1216        state.latitude = 1.0;
1217        state.longitude = 2.0;
1218        state.altitude = 3.0;
1219        state.velocity_north = 4.0;
1220        state.velocity_east = 5.0;
1221        state.velocity_down = 6.0;
1222        state.attitude = nalgebra::Rotation3::from_euler_angles(7.0, 8.0, 9.0);
1223
1224        let state_vector: DVector<f64> = DVector::from_vec(vec![
1225            state.latitude,
1226            state.longitude,
1227            state.altitude,
1228            state.velocity_north,
1229            state.velocity_east,
1230            state.velocity_down,
1231            state.attitude.euler_angles().0, // roll
1232            state.attitude.euler_angles().1, // pitch
1233            state.attitude.euler_angles().2, // yaw
1234            0.0,                             // acc_bias_x
1235            0.0,                             // acc_bias_y
1236            0.0,                             // acc_bias_z
1237            0.0,                             // gyro_bias_x
1238            0.0,                             // gyro_bias_y
1239            0.0,                             // gyro_bias_z
1240        ]);
1241        let timestamp = chrono::Utc::now();
1242        let nav = NavigationResult::from((
1243            &timestamp,
1244            &state_vector.into(),
1245            &DMatrix::from_diagonal(&DVector::from_element(15, 0.0)), // dummy covariance
1246        ));
1247        assert_eq!(nav.latitude, (1.0_f64).to_degrees());
1248        assert_eq!(nav.longitude, (2.0_f64).to_degrees());
1249        assert_eq!(nav.altitude, 3.0);
1250        assert_eq!(nav.velocity_north, 4.0);
1251        assert_eq!(nav.velocity_east, 5.0);
1252        assert_eq!(nav.velocity_down, 6.0);
1253    }
1254    #[test]
1255    fn test_navigation_result_to_csv_and_from_csv() {
1256        let mut nav = NavigationResult::new();
1257        nav.latitude = 1.0;
1258        nav.longitude = 2.0;
1259        nav.altitude = 3.0;
1260        nav.velocity_north = 4.0;
1261        nav.velocity_east = 5.0;
1262        nav.velocity_down = 6.0;
1263        //nav.attitude = nalgebra::Rotation3::from_euler_angles(0.1, 0.2, 0.3);
1264        let temp_file = std::env::temp_dir().join("test_nav_result.csv");
1265        NavigationResult::to_csv(&[nav.clone()], &temp_file).unwrap();
1266        let read = NavigationResult::from_csv(&temp_file).unwrap();
1267        assert_eq!(read.len(), 1);
1268        assert_eq!(read[0].latitude, 1.0);
1269        assert_eq!(read[0].longitude, 2.0);
1270        assert_eq!(read[0].altitude, 3.0);
1271        assert_eq!(read[0].velocity_north, 4.0);
1272        assert_eq!(read[0].velocity_east, 5.0);
1273        assert_eq!(read[0].velocity_down, 6.0);
1274        //assert!(read[0].attitude.matrix().abs_diff_eq(
1275        //    nalgebra::Rotation3::from_euler_angles(0.1, 0.2, 0.3).matrix(),
1276        //    1e-12
1277        //));
1278        let _ = std::fs::remove_file(&temp_file);
1279    }
1280    // #[test]
1281    // fn test_dead_reckoning_empty_and_single() {
1282    //     let empty: Vec<TestDataRecord> = vec![];
1283    //     let res = dead_reckoning(&empty);
1284    //     assert!(res.is_empty());
1285    //     let rec = TestDataRecord::from_csv("./data/test_data.csv")
1286    //         .ok()
1287    //         .and_then(|v| v.into_iter().next())
1288    //         .unwrap_or_else(|| TestDataRecord {
1289    //             time: chrono::Utc::now(),
1290    //             bearing_accuracy: 0.0,
1291    //             speed_accuracy: 0.0,
1292    //             vertical_accuracy: 0.0,
1293    //             horizontal_accuracy: 0.0,
1294    //             speed: 0.0,
1295    //             bearing: 0.0,
1296    //             altitude: 0.0,
1297    //             longitude: 0.0,
1298    //             latitude: 0.0,
1299    //             qz: 0.0,
1300    //             qy: 0.0,
1301    //             qx: 0.0,
1302    //             qw: 1.0,
1303    //             roll: 0.0,
1304    //             pitch: 0.0,
1305    //             yaw: 0.0,
1306    //             acc_z: 0.0,
1307    //             acc_y: 0.0,
1308    //             acc_x: 0.0,
1309    //             gyro_z: 0.0,
1310    //             gyro_y: 0.0,
1311    //             gyro_x: 0.0,
1312    //             mag_z: 0.0,
1313    //             mag_y: 0.0,
1314    //             mag_x: 0.0,
1315    //             relative_altitude: 0.0,
1316    //             pressure: 0.0,
1317    //             grav_z: 0.0,
1318    //             grav_y: 0.0,
1319    //             grav_x: 0.0,
1320    //         });
1321    //     let res = dead_reckoning(&[rec.clone()]);
1322    //     assert_eq!(res.len(), 1);
1323    //     let mut rec2 = rec.clone();
1324    //     rec2.time = chrono::Utc::now();
1325    //     let res = dead_reckoning(&[rec.clone(), rec2]);
1326    //     assert_eq!(res.len(), 2);
1327    // }
1328    #[test]
1329    fn test_closed_loop_minimal() {
1330        let rec = TestDataRecord::from_csv("./data/test_data.csv")
1331            .ok()
1332            .and_then(|v| v.into_iter().next())
1333            .unwrap_or_else(|| TestDataRecord {
1334                time: chrono::Utc::now(),
1335                bearing_accuracy: 0.0,
1336                speed_accuracy: 0.0,
1337                vertical_accuracy: 0.0,
1338                horizontal_accuracy: 0.0,
1339                speed: 0.0,
1340                bearing: 0.0,
1341                altitude: 0.0,
1342                longitude: 0.0,
1343                latitude: 0.0,
1344                qz: 0.0,
1345                qy: 0.0,
1346                qx: 0.0,
1347                qw: 1.0,
1348                roll: 0.0,
1349                pitch: 0.0,
1350                yaw: 0.0,
1351                acc_z: 0.0,
1352                acc_y: 0.0,
1353                acc_x: 0.0,
1354                gyro_z: 0.0,
1355                gyro_y: 0.0,
1356                gyro_x: 0.0,
1357                mag_z: 0.0,
1358                mag_y: 0.0,
1359                mag_x: 0.0,
1360                relative_altitude: 0.0,
1361                pressure: 0.0,
1362                grav_z: 0.0,
1363                grav_y: 0.0,
1364                grav_x: 0.0,
1365            });
1366
1367        // Initialize UKF
1368        let mut ukf = initialize_ukf(rec.clone(), None, None);
1369
1370        // Create a minimal EventStream with one IMU event
1371        let imu_data = IMUData {
1372            accel: nalgebra::Vector3::new(rec.acc_x, rec.acc_y, rec.acc_z),
1373            gyro: nalgebra::Vector3::new(rec.gyro_x, rec.gyro_y, rec.gyro_z),
1374        };
1375        let event = Event::Imu {
1376            dt_s: 1.0,
1377            imu: imu_data,
1378            elapsed_s: 0.0,
1379        };
1380        let stream = EventStream {
1381            start_time: rec.time,
1382            events: vec![event],
1383        };
1384
1385        let res = closed_loop(&mut ukf, stream);
1386        assert!(!res.unwrap().is_empty());
1387    }
1388    #[test]
1389    fn test_initialize_ukf_default_and_custom() {
1390        let rec = TestDataRecord {
1391            time: chrono::Utc::now(),
1392            bearing_accuracy: 0.0,
1393            speed_accuracy: 0.0,
1394            vertical_accuracy: 1.0,
1395            horizontal_accuracy: 4.0,
1396            speed: 1.0,
1397            bearing: 0.0,
1398            altitude: 10.0,
1399            longitude: 20.0,
1400            latitude: 30.0,
1401            qz: 0.0,
1402            qy: 0.0,
1403            qx: 0.0,
1404            qw: 1.0,
1405            roll: 0.0,
1406            pitch: 0.0,
1407            yaw: 0.0,
1408            acc_z: 0.0,
1409            acc_y: 0.0,
1410            acc_x: 0.0,
1411            gyro_z: 0.0,
1412            gyro_y: 0.0,
1413            gyro_x: 0.0,
1414            mag_z: 0.0,
1415            mag_y: 0.0,
1416            mag_x: 0.0,
1417            relative_altitude: 0.0,
1418            pressure: 0.0,
1419            grav_z: 0.0,
1420            grav_y: 0.0,
1421            grav_x: 0.0,
1422        };
1423        let ukf = initialize_ukf(rec.clone(), None, None);
1424        assert!(!ukf.get_mean().is_empty());
1425        let ukf2 = initialize_ukf(
1426            rec,
1427            Some(vec![0.1, 0.2, 0.3]),
1428            Some(vec![0.4, 0.5, 0.6, 0.7, 0.8, 0.9]),
1429        );
1430        assert!(!ukf2.get_mean().is_empty());
1431    }
1432}