use core::f64;
use log::{debug, info, warn};
use std::fmt::{Debug, Display};
use std::io::{self, Read, Write};
use std::path::Path;
use std::time::{Duration as StdDuration, Instant};
use anyhow::{Result, bail};
use chrono::{DateTime, Duration, Utc};
use nalgebra::{DMatrix, DVector, Vector3};
use serde::{Deserialize, Deserializer, Serialize};
#[cfg(feature = "clap")]
use clap::{Args, ValueEnum};
use crate::NavigationFilter;
use crate::earth::METERS_TO_DEGREES;
use crate::kalman::{InitialState, UnscentedKalmanFilter};
use crate::messages::{Event, EventStream, GnssFaultModel, GnssScheduler};
use crate::{IMUData, StrapdownState, forward};
use health::HealthMonitor;
pub use execution::{ExecutionLimits, ExecutionMonitor};
pub use health::HealthLimits;
pub const DEFAULT_PROCESS_NOISE: [f64; 15] = [
1e-6, 1e-6, 1e-4, 1e-3, 1e-3, 1e-3, 1e-5, 1e-5, 1e-5, 1e-6, 1e-6, 1e-6, 1e-8, 1e-8, 1e-8, ];
pub const DEFAULT_MAX_WALL_CLOCK_RATIO: f64 = 0.25;
pub const DEFAULT_MAX_WALL_CLOCK_S: f64 = 1200.0;
pub const DEFAULT_MAX_NO_PROGRESS_S: f64 = 600.0;
fn de_f64_nan<'de, D>(deserializer: D) -> Result<f64, D::Error>
where
D: Deserializer<'de>,
{
let opt = Option::<String>::deserialize(deserializer)?;
match opt {
None => Ok(f64::NAN),
Some(s) => {
let t = s.trim();
if t.is_empty() || t.eq_ignore_ascii_case("nan") || t.eq_ignore_ascii_case("null") {
return Ok(f64::NAN);
}
t.parse::<f64>().map_err(serde::de::Error::custom)
}
}
}
#[derive(Debug, Default, Deserialize, Serialize, Clone)]
pub struct TestDataRecord {
pub time: DateTime<Utc>,
#[serde(rename = "bearingAccuracy", deserialize_with = "de_f64_nan")]
pub bearing_accuracy: f64,
#[serde(rename = "speedAccuracy", deserialize_with = "de_f64_nan")]
pub speed_accuracy: f64,
#[serde(rename = "verticalAccuracy", deserialize_with = "de_f64_nan")]
pub vertical_accuracy: f64,
#[serde(rename = "horizontalAccuracy", deserialize_with = "de_f64_nan")]
pub horizontal_accuracy: f64,
#[serde(deserialize_with = "de_f64_nan")]
pub speed: f64,
#[serde(deserialize_with = "de_f64_nan")]
pub bearing: f64,
#[serde(deserialize_with = "de_f64_nan")]
pub altitude: f64,
#[serde(deserialize_with = "de_f64_nan")]
pub longitude: f64,
#[serde(deserialize_with = "de_f64_nan")]
pub latitude: f64,
#[serde(deserialize_with = "de_f64_nan")]
pub qz: f64,
#[serde(deserialize_with = "de_f64_nan")]
pub qy: f64,
#[serde(deserialize_with = "de_f64_nan")]
pub qx: f64,
#[serde(deserialize_with = "de_f64_nan")]
pub qw: f64,
#[serde(deserialize_with = "de_f64_nan")]
pub roll: f64,
#[serde(deserialize_with = "de_f64_nan")]
pub pitch: f64,
#[serde(deserialize_with = "de_f64_nan")]
pub yaw: f64,
#[serde(deserialize_with = "de_f64_nan")]
pub acc_z: f64,
#[serde(deserialize_with = "de_f64_nan")]
pub acc_y: f64,
#[serde(deserialize_with = "de_f64_nan")]
pub acc_x: f64,
#[serde(deserialize_with = "de_f64_nan")]
pub gyro_z: f64,
#[serde(deserialize_with = "de_f64_nan")]
pub gyro_y: f64,
#[serde(deserialize_with = "de_f64_nan")]
pub gyro_x: f64,
#[serde(deserialize_with = "de_f64_nan")]
pub mag_z: f64,
#[serde(deserialize_with = "de_f64_nan")]
pub mag_y: f64,
#[serde(deserialize_with = "de_f64_nan")]
pub mag_x: f64,
#[serde(rename = "relativeAltitude", deserialize_with = "de_f64_nan")]
pub relative_altitude: f64,
#[serde(deserialize_with = "de_f64_nan")]
pub pressure: f64,
#[serde(deserialize_with = "de_f64_nan")]
pub grav_z: f64,
#[serde(deserialize_with = "de_f64_nan")]
pub grav_y: f64,
#[serde(deserialize_with = "de_f64_nan")]
pub grav_x: f64,
}
impl TestDataRecord {
pub fn from_csv<P: AsRef<std::path::Path>>(
path: P,
) -> Result<Vec<Self>, Box<dyn std::error::Error>> {
let mut rdr = csv::ReaderBuilder::new()
.has_headers(true)
.flexible(true)
.trim(csv::Trim::All)
.from_path(path)?;
let mut records = Vec::new();
for (i, result) in rdr.deserialize::<Self>().enumerate() {
match result {
Ok(r) => records.push(r),
Err(e) => {
warn!("Skipping row {} due to parse error: {e}", i + 1);
}
}
}
Ok(records)
}
pub fn to_csv<P: AsRef<Path>>(records: &[Self], path: P) -> io::Result<()> {
let mut writer = csv::Writer::from_path(path)?;
for record in records {
writer.serialize(record)?;
}
writer.flush()?;
Ok(())
}
pub fn to_hdf5<P: AsRef<Path>>(records: &[Self], path: P) -> Result<()> {
use hdf5::File;
let file = File::create(path)?;
let n = records.len();
if n == 0 {
let _group = file.create_group("test_data")?;
return Ok(());
}
let group = file.create_group("test_data")?;
let timestamps: Result<Vec<hdf5::types::VarLenAscii>> = records
.iter()
.map(|r| {
hdf5::types::VarLenAscii::from_ascii(&r.time.to_rfc3339())
.map_err(|e| anyhow::anyhow!("Failed to encode timestamp as ASCII: {}", e))
})
.collect();
let timestamps = timestamps?;
let ds_time = group
.new_dataset::<hdf5::types::VarLenAscii>()
.shape([n])
.create("time")?;
ds_time.write(×tamps)?;
macro_rules! write_f64_field {
($field_name:literal, $field:ident) => {{
let data: Vec<f64> = records.iter().map(|r| r.$field).collect();
let ds = group.new_dataset::<f64>().shape([n]).create($field_name)?;
ds.write(&data)?;
}};
}
write_f64_field!("bearing_accuracy", bearing_accuracy);
write_f64_field!("speed_accuracy", speed_accuracy);
write_f64_field!("vertical_accuracy", vertical_accuracy);
write_f64_field!("horizontal_accuracy", horizontal_accuracy);
write_f64_field!("speed", speed);
write_f64_field!("bearing", bearing);
write_f64_field!("altitude", altitude);
write_f64_field!("longitude", longitude);
write_f64_field!("latitude", latitude);
write_f64_field!("qz", qz);
write_f64_field!("qy", qy);
write_f64_field!("qx", qx);
write_f64_field!("qw", qw);
write_f64_field!("roll", roll);
write_f64_field!("pitch", pitch);
write_f64_field!("yaw", yaw);
write_f64_field!("acc_z", acc_z);
write_f64_field!("acc_y", acc_y);
write_f64_field!("acc_x", acc_x);
write_f64_field!("gyro_z", gyro_z);
write_f64_field!("gyro_y", gyro_y);
write_f64_field!("gyro_x", gyro_x);
write_f64_field!("mag_z", mag_z);
write_f64_field!("mag_y", mag_y);
write_f64_field!("mag_x", mag_x);
write_f64_field!("relative_altitude", relative_altitude);
write_f64_field!("pressure", pressure);
write_f64_field!("grav_z", grav_z);
write_f64_field!("grav_y", grav_y);
write_f64_field!("grav_x", grav_x);
Ok(())
}
pub fn to_mcap<P: AsRef<Path>>(records: &[Self], path: P) -> io::Result<()> {
use mcap::{Writer, records::MessageHeader};
use std::collections::BTreeMap;
use std::fs::File;
use std::io::BufWriter;
let file = File::create(path)?;
let buf_writer = BufWriter::new(file);
let mut writer = Writer::new(buf_writer).map_err(io::Error::other)?;
let schema_name = "TestDataRecord";
let schema_encoding = "msgpack";
let schema_data = b"TestDataRecord struct serialized with MessagePack";
let schema_id = writer
.add_schema(schema_name, schema_encoding, schema_data)
.map_err(io::Error::other)?;
let metadata = BTreeMap::new();
let channel_id = writer
.add_channel(schema_id, "sensor_data", "msgpack", &metadata)
.map_err(io::Error::other)?;
for (seq, record) in records.iter().enumerate() {
let data = rmp_serde::to_vec(record)
.map_err(|e| io::Error::new(io::ErrorKind::InvalidData, e))?;
let timestamp_nanos = record.time.timestamp_nanos_opt().ok_or_else(|| {
io::Error::new(io::ErrorKind::InvalidData, "Timestamp out of range")
})?;
let header = MessageHeader {
channel_id,
sequence: seq as u32,
log_time: timestamp_nanos as u64,
publish_time: timestamp_nanos as u64,
};
writer
.write_to_known_channel(&header, &data)
.map_err(io::Error::other)?;
}
writer.finish().map_err(io::Error::other)?;
Ok(())
}
pub fn from_hdf5<P: AsRef<Path>>(path: P) -> Result<Vec<Self>> {
use hdf5::File;
let file = File::open(path)?;
let group = file.group("test_data")?;
if let Ok(ds_time) = group.dataset("time") {
let timestamps: Vec<hdf5::types::VarLenAscii> = ds_time.read_raw()?;
let n = timestamps.len();
if n == 0 {
return Ok(Vec::new());
}
macro_rules! read_f64_field {
($field_name:literal) => {{
let ds = group.dataset($field_name)?;
let data: Vec<f64> = ds.read_raw()?;
data
}};
}
let bearing_accuracy = read_f64_field!("bearing_accuracy");
let speed_accuracy = read_f64_field!("speed_accuracy");
let vertical_accuracy = read_f64_field!("vertical_accuracy");
let horizontal_accuracy = read_f64_field!("horizontal_accuracy");
let speed = read_f64_field!("speed");
let bearing = read_f64_field!("bearing");
let altitude = read_f64_field!("altitude");
let longitude = read_f64_field!("longitude");
let latitude = read_f64_field!("latitude");
let qz = read_f64_field!("qz");
let qy = read_f64_field!("qy");
let qx = read_f64_field!("qx");
let qw = read_f64_field!("qw");
let roll = read_f64_field!("roll");
let pitch = read_f64_field!("pitch");
let yaw = read_f64_field!("yaw");
let acc_z = read_f64_field!("acc_z");
let acc_y = read_f64_field!("acc_y");
let acc_x = read_f64_field!("acc_x");
let gyro_z = read_f64_field!("gyro_z");
let gyro_y = read_f64_field!("gyro_y");
let gyro_x = read_f64_field!("gyro_x");
let mag_z = read_f64_field!("mag_z");
let mag_y = read_f64_field!("mag_y");
let mag_x = read_f64_field!("mag_x");
let relative_altitude = read_f64_field!("relative_altitude");
let pressure = read_f64_field!("pressure");
let grav_z = read_f64_field!("grav_z");
let grav_y = read_f64_field!("grav_y");
let grav_x = read_f64_field!("grav_x");
let mut records = Vec::with_capacity(n);
for i in 0..n {
let time = DateTime::parse_from_rfc3339(timestamps[i].as_str())
.map_err(|e| anyhow::anyhow!("Failed to parse timestamp: {}", e))?
.with_timezone(&Utc);
records.push(TestDataRecord {
time,
bearing_accuracy: bearing_accuracy[i],
speed_accuracy: speed_accuracy[i],
vertical_accuracy: vertical_accuracy[i],
horizontal_accuracy: horizontal_accuracy[i],
speed: speed[i],
bearing: bearing[i],
altitude: altitude[i],
longitude: longitude[i],
latitude: latitude[i],
qz: qz[i],
qy: qy[i],
qx: qx[i],
qw: qw[i],
roll: roll[i],
pitch: pitch[i],
yaw: yaw[i],
acc_z: acc_z[i],
acc_y: acc_y[i],
acc_x: acc_x[i],
gyro_z: gyro_z[i],
gyro_y: gyro_y[i],
gyro_x: gyro_x[i],
mag_z: mag_z[i],
mag_y: mag_y[i],
mag_x: mag_x[i],
relative_altitude: relative_altitude[i],
pressure: pressure[i],
grav_z: grav_z[i],
grav_y: grav_y[i],
grav_x: grav_x[i],
});
}
Ok(records)
} else {
Ok(Vec::new())
}
}
pub fn to_netcdf<P: AsRef<Path>>(records: &[Self], path: P) -> Result<()> {
if records.is_empty() {
bail!("Cannot write empty records to netCDF");
}
let n = records.len();
let mut file = netcdf::create(path)?;
file.add_dimension("time", n)?;
macro_rules! add_and_write {
($file:expr, $name:expr, $data:expr) => {{
let mut var = $file.add_variable::<f64>($name, &["time"])?;
var.put_values(&$data, ..)?;
}};
}
let times: Vec<f64> = records.iter().map(|r| r.time.timestamp() as f64).collect();
let bearing_accuracy: Vec<f64> = records.iter().map(|r| r.bearing_accuracy).collect();
let speed_accuracy: Vec<f64> = records.iter().map(|r| r.speed_accuracy).collect();
let vertical_accuracy: Vec<f64> = records.iter().map(|r| r.vertical_accuracy).collect();
let horizontal_accuracy: Vec<f64> = records.iter().map(|r| r.horizontal_accuracy).collect();
let speed: Vec<f64> = records.iter().map(|r| r.speed).collect();
let bearing: Vec<f64> = records.iter().map(|r| r.bearing).collect();
let altitude: Vec<f64> = records.iter().map(|r| r.altitude).collect();
let longitude: Vec<f64> = records.iter().map(|r| r.longitude).collect();
let latitude: Vec<f64> = records.iter().map(|r| r.latitude).collect();
let qz: Vec<f64> = records.iter().map(|r| r.qz).collect();
let qy: Vec<f64> = records.iter().map(|r| r.qy).collect();
let qx: Vec<f64> = records.iter().map(|r| r.qx).collect();
let qw: Vec<f64> = records.iter().map(|r| r.qw).collect();
let roll: Vec<f64> = records.iter().map(|r| r.roll).collect();
let pitch: Vec<f64> = records.iter().map(|r| r.pitch).collect();
let yaw: Vec<f64> = records.iter().map(|r| r.yaw).collect();
let acc_z: Vec<f64> = records.iter().map(|r| r.acc_z).collect();
let acc_y: Vec<f64> = records.iter().map(|r| r.acc_y).collect();
let acc_x: Vec<f64> = records.iter().map(|r| r.acc_x).collect();
let gyro_z: Vec<f64> = records.iter().map(|r| r.gyro_z).collect();
let gyro_y: Vec<f64> = records.iter().map(|r| r.gyro_y).collect();
let gyro_x: Vec<f64> = records.iter().map(|r| r.gyro_x).collect();
let mag_z: Vec<f64> = records.iter().map(|r| r.mag_z).collect();
let mag_y: Vec<f64> = records.iter().map(|r| r.mag_y).collect();
let mag_x: Vec<f64> = records.iter().map(|r| r.mag_x).collect();
let relative_altitude: Vec<f64> = records.iter().map(|r| r.relative_altitude).collect();
let pressure: Vec<f64> = records.iter().map(|r| r.pressure).collect();
let grav_z: Vec<f64> = records.iter().map(|r| r.grav_z).collect();
let grav_y: Vec<f64> = records.iter().map(|r| r.grav_y).collect();
let grav_x: Vec<f64> = records.iter().map(|r| r.grav_x).collect();
add_and_write!(file, "time", times);
add_and_write!(file, "bearingAccuracy", bearing_accuracy);
add_and_write!(file, "speedAccuracy", speed_accuracy);
add_and_write!(file, "verticalAccuracy", vertical_accuracy);
add_and_write!(file, "horizontalAccuracy", horizontal_accuracy);
add_and_write!(file, "speed", speed);
add_and_write!(file, "bearing", bearing);
add_and_write!(file, "altitude", altitude);
add_and_write!(file, "longitude", longitude);
add_and_write!(file, "latitude", latitude);
add_and_write!(file, "qz", qz);
add_and_write!(file, "qy", qy);
add_and_write!(file, "qx", qx);
add_and_write!(file, "qw", qw);
add_and_write!(file, "roll", roll);
add_and_write!(file, "pitch", pitch);
add_and_write!(file, "yaw", yaw);
add_and_write!(file, "acc_z", acc_z);
add_and_write!(file, "acc_y", acc_y);
add_and_write!(file, "acc_x", acc_x);
add_and_write!(file, "gyro_z", gyro_z);
add_and_write!(file, "gyro_y", gyro_y);
add_and_write!(file, "gyro_x", gyro_x);
add_and_write!(file, "mag_z", mag_z);
add_and_write!(file, "mag_y", mag_y);
add_and_write!(file, "mag_x", mag_x);
add_and_write!(file, "relativeAltitude", relative_altitude);
add_and_write!(file, "pressure", pressure);
add_and_write!(file, "grav_z", grav_z);
add_and_write!(file, "grav_y", grav_y);
add_and_write!(file, "grav_x", grav_x);
Ok(())
}
pub fn from_netcdf<P: AsRef<Path>>(path: P) -> Result<Vec<Self>> {
let file = netcdf::open(path)?;
let time_var = file
.variable("time")
.ok_or_else(|| anyhow::anyhow!("time variable not found"))?;
let times: Vec<f64> = time_var.get_values(..)?;
let n = times.len();
macro_rules! read_var {
($file:expr, $name:expr) => {{
let var = $file
.variable($name)
.ok_or_else(|| anyhow::anyhow!(concat!($name, " variable not found")))?;
let data: Vec<f64> = var.get_values(..)?;
data
}};
}
let bearing_accuracy = read_var!(file, "bearingAccuracy");
let speed_accuracy = read_var!(file, "speedAccuracy");
let vertical_accuracy = read_var!(file, "verticalAccuracy");
let horizontal_accuracy = read_var!(file, "horizontalAccuracy");
let speed = read_var!(file, "speed");
let bearing = read_var!(file, "bearing");
let altitude = read_var!(file, "altitude");
let longitude = read_var!(file, "longitude");
let latitude = read_var!(file, "latitude");
let qz = read_var!(file, "qz");
let qy = read_var!(file, "qy");
let qx = read_var!(file, "qx");
let qw = read_var!(file, "qw");
let roll = read_var!(file, "roll");
let pitch = read_var!(file, "pitch");
let yaw = read_var!(file, "yaw");
let acc_z = read_var!(file, "acc_z");
let acc_y = read_var!(file, "acc_y");
let acc_x = read_var!(file, "acc_x");
let gyro_z = read_var!(file, "gyro_z");
let gyro_y = read_var!(file, "gyro_y");
let gyro_x = read_var!(file, "gyro_x");
let mag_z = read_var!(file, "mag_z");
let mag_y = read_var!(file, "mag_y");
let mag_x = read_var!(file, "mag_x");
let relative_altitude = read_var!(file, "relativeAltitude");
let pressure = read_var!(file, "pressure");
let grav_z = read_var!(file, "grav_z");
let grav_y = read_var!(file, "grav_y");
let grav_x = read_var!(file, "grav_x");
let mut records = Vec::with_capacity(n);
for i in 0..n {
let time = DateTime::from_timestamp(times[i] as i64, 0)
.ok_or_else(|| anyhow::anyhow!("Invalid timestamp"))?
.with_timezone(&Utc);
records.push(TestDataRecord {
time,
bearing_accuracy: bearing_accuracy[i],
speed_accuracy: speed_accuracy[i],
vertical_accuracy: vertical_accuracy[i],
horizontal_accuracy: horizontal_accuracy[i],
speed: speed[i],
bearing: bearing[i],
altitude: altitude[i],
longitude: longitude[i],
latitude: latitude[i],
qz: qz[i],
qy: qy[i],
qx: qx[i],
qw: qw[i],
roll: roll[i],
pitch: pitch[i],
yaw: yaw[i],
acc_z: acc_z[i],
acc_y: acc_y[i],
acc_x: acc_x[i],
gyro_z: gyro_z[i],
gyro_y: gyro_y[i],
gyro_x: gyro_x[i],
mag_z: mag_z[i],
mag_y: mag_y[i],
mag_x: mag_x[i],
relative_altitude: relative_altitude[i],
pressure: pressure[i],
grav_z: grav_z[i],
grav_y: grav_y[i],
grav_x: grav_x[i],
});
}
Ok(records)
}
pub fn from_mcap<P: AsRef<Path>>(path: P) -> Result<Vec<Self>, Box<dyn std::error::Error>> {
use mcap::MessageStream;
use std::fs::File;
let file = File::open(path)?;
let mapped = unsafe { memmap2::Mmap::map(&file)? };
let message_stream = MessageStream::new(&mapped)?;
let mut records = Vec::new();
for message_result in message_stream {
let message = message_result?;
let record: Self = rmp_serde::from_slice(&message.data)?;
records.push(record);
}
Ok(records)
}
}
impl Display for TestDataRecord {
fn fmt(&self, f: &mut std::fmt::Formatter<'_>) -> std::fmt::Result {
write!(
f,
"TestDataRecord(time: {}, latitude: {}, longitude: {}, altitude: {}, speed: {}, bearing: {})",
self.time, self.latitude, self.longitude, self.altitude, self.speed, self.bearing
)
}
}
#[derive(Clone, Debug, Deserialize, Serialize)]
pub struct NEDCovariance {
pub latitude_cov: f64,
pub longitude_cov: f64,
pub altitude_cov: f64,
pub velocity_n_cov: f64,
pub velocity_e_cov: f64,
pub velocity_v_cov: f64,
pub roll_cov: f64,
pub pitch_cov: f64,
pub yaw_cov: f64,
pub acc_bias_x_cov: f64,
pub acc_bias_y_cov: f64,
pub acc_bias_z_cov: f64,
pub gyro_bias_x_cov: f64,
pub gyro_bias_y_cov: f64,
pub gyro_bias_z_cov: f64,
}
#[derive(Clone, Debug, Serialize, Deserialize)]
pub struct NavigationResult {
pub timestamp: DateTime<Utc>,
pub latitude: f64,
pub longitude: f64,
pub altitude: f64,
pub velocity_north: f64,
pub velocity_east: f64,
pub velocity_vertical: f64,
pub roll: f64,
pub pitch: f64,
pub yaw: f64,
pub acc_bias_x: f64,
pub acc_bias_y: f64,
pub acc_bias_z: f64,
pub gyro_bias_x: f64,
pub gyro_bias_y: f64,
pub gyro_bias_z: f64,
pub latitude_cov: f64,
pub longitude_cov: f64,
pub altitude_cov: f64,
pub velocity_n_cov: f64,
pub velocity_e_cov: f64,
pub velocity_v_cov: f64,
pub roll_cov: f64,
pub pitch_cov: f64,
pub yaw_cov: f64,
pub acc_bias_x_cov: f64,
pub acc_bias_y_cov: f64,
pub acc_bias_z_cov: f64,
pub gyro_bias_x_cov: f64,
pub gyro_bias_y_cov: f64,
pub gyro_bias_z_cov: f64,
}
impl Default for NavigationResult {
fn default() -> Self {
NavigationResult {
timestamp: Utc::now(),
latitude: 0.0,
longitude: 0.0,
altitude: 0.0,
velocity_north: 0.0,
velocity_east: 0.0,
velocity_vertical: 0.0,
roll: 0.0,
pitch: 0.0,
yaw: 0.0,
acc_bias_x: 0.0,
acc_bias_y: 0.0,
acc_bias_z: 0.0,
gyro_bias_x: 0.0,
gyro_bias_y: 0.0,
gyro_bias_z: 0.0,
latitude_cov: 1e-6, longitude_cov: 1e-6,
altitude_cov: 1e-6,
velocity_n_cov: 1e-6,
velocity_e_cov: 1e-6,
velocity_v_cov: 1e-6,
roll_cov: 1e-6,
pitch_cov: 1e-6,
yaw_cov: 1e-6,
acc_bias_x_cov: 1e-6,
acc_bias_y_cov: 1e-6,
acc_bias_z_cov: 1e-6,
gyro_bias_x_cov: 1e-6,
gyro_bias_y_cov: 1e-6,
gyro_bias_z_cov: 1e-6,
}
}
}
impl NavigationResult {
pub fn new() -> Self {
NavigationResult::default() }
pub fn to_csv<P: AsRef<Path>>(records: &[Self], path: P) -> io::Result<()> {
let mut writer = csv::Writer::from_path(path)?;
for record in records {
writer.serialize(record)?;
}
writer.flush()?;
Ok(())
}
pub fn from_csv<P: AsRef<std::path::Path>>(
path: P,
) -> Result<Vec<Self>, Box<dyn std::error::Error>> {
let mut rdr = csv::Reader::from_path(path)?;
let mut records = Vec::new();
for result in rdr.deserialize() {
let record: Self = result?;
records.push(record);
}
Ok(records)
}
pub fn to_hdf5<P: AsRef<Path>>(records: &[Self], path: P) -> Result<()> {
use hdf5::File;
let file = File::create(path)?;
let n = records.len();
if n == 0 {
let _group = file.create_group("navigation_results")?;
return Ok(());
}
let group = file.create_group("navigation_results")?;
let timestamps: Result<Vec<hdf5::types::VarLenAscii>> = records
.iter()
.map(|r| {
hdf5::types::VarLenAscii::from_ascii(&r.timestamp.to_rfc3339())
.map_err(|e| anyhow::anyhow!("Failed to encode timestamp as ASCII: {}", e))
})
.collect();
let timestamps = timestamps?;
let ds_time = group
.new_dataset::<hdf5::types::VarLenAscii>()
.shape([n])
.create("timestamp")?;
ds_time.write(×tamps)?;
macro_rules! write_f64_field {
($field_name:literal, $field:ident) => {{
let data: Vec<f64> = records.iter().map(|r| r.$field).collect();
let ds = group.new_dataset::<f64>().shape([n]).create($field_name)?;
ds.write(&data)?;
}};
}
write_f64_field!("latitude", latitude);
write_f64_field!("longitude", longitude);
write_f64_field!("altitude", altitude);
write_f64_field!("velocity_north", velocity_north);
write_f64_field!("velocity_east", velocity_east);
write_f64_field!("velocity_vertical", velocity_vertical);
write_f64_field!("roll", roll);
write_f64_field!("pitch", pitch);
write_f64_field!("yaw", yaw);
write_f64_field!("acc_bias_x", acc_bias_x);
write_f64_field!("acc_bias_y", acc_bias_y);
write_f64_field!("acc_bias_z", acc_bias_z);
write_f64_field!("gyro_bias_x", gyro_bias_x);
write_f64_field!("gyro_bias_y", gyro_bias_y);
write_f64_field!("gyro_bias_z", gyro_bias_z);
write_f64_field!("latitude_cov", latitude_cov);
write_f64_field!("longitude_cov", longitude_cov);
write_f64_field!("altitude_cov", altitude_cov);
write_f64_field!("velocity_n_cov", velocity_n_cov);
write_f64_field!("velocity_e_cov", velocity_e_cov);
write_f64_field!("velocity_v_cov", velocity_v_cov);
write_f64_field!("roll_cov", roll_cov);
write_f64_field!("pitch_cov", pitch_cov);
write_f64_field!("yaw_cov", yaw_cov);
write_f64_field!("acc_bias_x_cov", acc_bias_x_cov);
write_f64_field!("acc_bias_y_cov", acc_bias_y_cov);
write_f64_field!("acc_bias_z_cov", acc_bias_z_cov);
write_f64_field!("gyro_bias_x_cov", gyro_bias_x_cov);
write_f64_field!("gyro_bias_y_cov", gyro_bias_y_cov);
write_f64_field!("gyro_bias_z_cov", gyro_bias_z_cov);
Ok(())
}
pub fn from_hdf5<P: AsRef<Path>>(path: P) -> Result<Vec<Self>> {
use hdf5::File;
let file = File::open(path)?;
let group = file.group("navigation_results")?;
if let Ok(ds_time) = group.dataset("timestamp") {
let timestamps: Vec<hdf5::types::VarLenAscii> = ds_time.read_raw()?;
let n = timestamps.len();
if n == 0 {
return Ok(Vec::new());
}
macro_rules! read_f64_field {
($field_name:literal) => {{
let ds = group.dataset($field_name)?;
let data: Vec<f64> = ds.read_raw()?;
data
}};
}
let latitude = read_f64_field!("latitude");
let longitude = read_f64_field!("longitude");
let altitude = read_f64_field!("altitude");
let velocity_north = read_f64_field!("velocity_north");
let velocity_east = read_f64_field!("velocity_east");
let velocity_vertical = read_f64_field!("velocity_vertical");
let roll = read_f64_field!("roll");
let pitch = read_f64_field!("pitch");
let yaw = read_f64_field!("yaw");
let acc_bias_x = read_f64_field!("acc_bias_x");
let acc_bias_y = read_f64_field!("acc_bias_y");
let acc_bias_z = read_f64_field!("acc_bias_z");
let gyro_bias_x = read_f64_field!("gyro_bias_x");
let gyro_bias_y = read_f64_field!("gyro_bias_y");
let gyro_bias_z = read_f64_field!("gyro_bias_z");
let latitude_cov = read_f64_field!("latitude_cov");
let longitude_cov = read_f64_field!("longitude_cov");
let altitude_cov = read_f64_field!("altitude_cov");
let velocity_n_cov = read_f64_field!("velocity_n_cov");
let velocity_e_cov = read_f64_field!("velocity_e_cov");
let velocity_v_cov = read_f64_field!("velocity_v_cov");
let roll_cov = read_f64_field!("roll_cov");
let pitch_cov = read_f64_field!("pitch_cov");
let yaw_cov = read_f64_field!("yaw_cov");
let acc_bias_x_cov = read_f64_field!("acc_bias_x_cov");
let acc_bias_y_cov = read_f64_field!("acc_bias_y_cov");
let acc_bias_z_cov = read_f64_field!("acc_bias_z_cov");
let gyro_bias_x_cov = read_f64_field!("gyro_bias_x_cov");
let gyro_bias_y_cov = read_f64_field!("gyro_bias_y_cov");
let gyro_bias_z_cov = read_f64_field!("gyro_bias_z_cov");
let mut records = Vec::with_capacity(n);
for i in 0..n {
let timestamp = DateTime::parse_from_rfc3339(timestamps[i].as_str())
.map_err(|e| anyhow::anyhow!("Failed to parse timestamp: {}", e))?
.with_timezone(&Utc);
records.push(NavigationResult {
timestamp,
latitude: latitude[i],
longitude: longitude[i],
altitude: altitude[i],
velocity_north: velocity_north[i],
velocity_east: velocity_east[i],
velocity_vertical: velocity_vertical[i],
roll: roll[i],
pitch: pitch[i],
yaw: yaw[i],
acc_bias_x: acc_bias_x[i],
acc_bias_y: acc_bias_y[i],
acc_bias_z: acc_bias_z[i],
gyro_bias_x: gyro_bias_x[i],
gyro_bias_y: gyro_bias_y[i],
gyro_bias_z: gyro_bias_z[i],
latitude_cov: latitude_cov[i],
longitude_cov: longitude_cov[i],
altitude_cov: altitude_cov[i],
velocity_n_cov: velocity_n_cov[i],
velocity_e_cov: velocity_e_cov[i],
velocity_v_cov: velocity_v_cov[i],
roll_cov: roll_cov[i],
pitch_cov: pitch_cov[i],
yaw_cov: yaw_cov[i],
acc_bias_x_cov: acc_bias_x_cov[i],
acc_bias_y_cov: acc_bias_y_cov[i],
acc_bias_z_cov: acc_bias_z_cov[i],
gyro_bias_x_cov: gyro_bias_x_cov[i],
gyro_bias_y_cov: gyro_bias_y_cov[i],
gyro_bias_z_cov: gyro_bias_z_cov[i],
});
}
Ok(records)
} else {
Ok(Vec::new())
}
}
pub fn to_netcdf<P: AsRef<Path>>(records: &[Self], path: P) -> Result<()> {
if records.is_empty() {
bail!("Cannot write empty records to netCDF");
}
let n = records.len();
let mut file = netcdf::create(path)?;
file.add_dimension("time", n)?;
macro_rules! add_and_write {
($file:expr, $name:expr, $data:expr) => {{
let mut var = $file.add_variable::<f64>($name, &["time"])?;
var.put_values(&$data, ..)?;
}};
}
let timestamps: Vec<f64> = records
.iter()
.map(|r| r.timestamp.timestamp() as f64)
.collect();
let latitude: Vec<f64> = records.iter().map(|r| r.latitude).collect();
let longitude: Vec<f64> = records.iter().map(|r| r.longitude).collect();
let altitude: Vec<f64> = records.iter().map(|r| r.altitude).collect();
let velocity_north: Vec<f64> = records.iter().map(|r| r.velocity_north).collect();
let velocity_east: Vec<f64> = records.iter().map(|r| r.velocity_east).collect();
let velocity_vertical: Vec<f64> = records.iter().map(|r| r.velocity_vertical).collect();
let roll: Vec<f64> = records.iter().map(|r| r.roll).collect();
let pitch: Vec<f64> = records.iter().map(|r| r.pitch).collect();
let yaw: Vec<f64> = records.iter().map(|r| r.yaw).collect();
let acc_bias_x: Vec<f64> = records.iter().map(|r| r.acc_bias_x).collect();
let acc_bias_y: Vec<f64> = records.iter().map(|r| r.acc_bias_y).collect();
let acc_bias_z: Vec<f64> = records.iter().map(|r| r.acc_bias_z).collect();
let gyro_bias_x: Vec<f64> = records.iter().map(|r| r.gyro_bias_x).collect();
let gyro_bias_y: Vec<f64> = records.iter().map(|r| r.gyro_bias_y).collect();
let gyro_bias_z: Vec<f64> = records.iter().map(|r| r.gyro_bias_z).collect();
let latitude_cov: Vec<f64> = records.iter().map(|r| r.latitude_cov).collect();
let longitude_cov: Vec<f64> = records.iter().map(|r| r.longitude_cov).collect();
let altitude_cov: Vec<f64> = records.iter().map(|r| r.altitude_cov).collect();
let velocity_n_cov: Vec<f64> = records.iter().map(|r| r.velocity_n_cov).collect();
let velocity_e_cov: Vec<f64> = records.iter().map(|r| r.velocity_e_cov).collect();
let velocity_v_cov: Vec<f64> = records.iter().map(|r| r.velocity_v_cov).collect();
let roll_cov: Vec<f64> = records.iter().map(|r| r.roll_cov).collect();
let pitch_cov: Vec<f64> = records.iter().map(|r| r.pitch_cov).collect();
let yaw_cov: Vec<f64> = records.iter().map(|r| r.yaw_cov).collect();
let acc_bias_x_cov: Vec<f64> = records.iter().map(|r| r.acc_bias_x_cov).collect();
let acc_bias_y_cov: Vec<f64> = records.iter().map(|r| r.acc_bias_y_cov).collect();
let acc_bias_z_cov: Vec<f64> = records.iter().map(|r| r.acc_bias_z_cov).collect();
let gyro_bias_x_cov: Vec<f64> = records.iter().map(|r| r.gyro_bias_x_cov).collect();
let gyro_bias_y_cov: Vec<f64> = records.iter().map(|r| r.gyro_bias_y_cov).collect();
let gyro_bias_z_cov: Vec<f64> = records.iter().map(|r| r.gyro_bias_z_cov).collect();
add_and_write!(file, "timestamp", timestamps);
add_and_write!(file, "latitude", latitude);
add_and_write!(file, "longitude", longitude);
add_and_write!(file, "altitude", altitude);
add_and_write!(file, "velocity_north", velocity_north);
add_and_write!(file, "velocity_east", velocity_east);
add_and_write!(file, "velocity_vertical", velocity_vertical);
add_and_write!(file, "roll", roll);
add_and_write!(file, "pitch", pitch);
add_and_write!(file, "yaw", yaw);
add_and_write!(file, "acc_bias_x", acc_bias_x);
add_and_write!(file, "acc_bias_y", acc_bias_y);
add_and_write!(file, "acc_bias_z", acc_bias_z);
add_and_write!(file, "gyro_bias_x", gyro_bias_x);
add_and_write!(file, "gyro_bias_y", gyro_bias_y);
add_and_write!(file, "gyro_bias_z", gyro_bias_z);
add_and_write!(file, "latitude_cov", latitude_cov);
add_and_write!(file, "longitude_cov", longitude_cov);
add_and_write!(file, "altitude_cov", altitude_cov);
add_and_write!(file, "velocity_n_cov", velocity_n_cov);
add_and_write!(file, "velocity_e_cov", velocity_e_cov);
add_and_write!(file, "velocity_v_cov", velocity_v_cov);
add_and_write!(file, "roll_cov", roll_cov);
add_and_write!(file, "pitch_cov", pitch_cov);
add_and_write!(file, "yaw_cov", yaw_cov);
add_and_write!(file, "acc_bias_x_cov", acc_bias_x_cov);
add_and_write!(file, "acc_bias_y_cov", acc_bias_y_cov);
add_and_write!(file, "acc_bias_z_cov", acc_bias_z_cov);
add_and_write!(file, "gyro_bias_x_cov", gyro_bias_x_cov);
add_and_write!(file, "gyro_bias_y_cov", gyro_bias_y_cov);
add_and_write!(file, "gyro_bias_z_cov", gyro_bias_z_cov);
Ok(())
}
pub fn from_netcdf<P: AsRef<Path>>(path: P) -> Result<Vec<Self>> {
let file = netcdf::open(path)?;
let time_var = file
.variable("timestamp")
.ok_or_else(|| anyhow::anyhow!("timestamp variable not found"))?;
let timestamps: Vec<f64> = time_var.get_values(..)?;
let n = timestamps.len();
macro_rules! read_var {
($file:expr, $name:expr) => {{
let var = $file
.variable($name)
.ok_or_else(|| anyhow::anyhow!(concat!($name, " variable not found")))?;
let data: Vec<f64> = var.get_values(..)?;
data
}};
}
let latitude = read_var!(file, "latitude");
let longitude = read_var!(file, "longitude");
let altitude = read_var!(file, "altitude");
let velocity_north = read_var!(file, "velocity_north");
let velocity_east = read_var!(file, "velocity_east");
let velocity_vertical = read_var!(file, "velocity_vertical");
let roll = read_var!(file, "roll");
let pitch = read_var!(file, "pitch");
let yaw = read_var!(file, "yaw");
let acc_bias_x = read_var!(file, "acc_bias_x");
let acc_bias_y = read_var!(file, "acc_bias_y");
let acc_bias_z = read_var!(file, "acc_bias_z");
let gyro_bias_x = read_var!(file, "gyro_bias_x");
let gyro_bias_y = read_var!(file, "gyro_bias_y");
let gyro_bias_z = read_var!(file, "gyro_bias_z");
let latitude_cov = read_var!(file, "latitude_cov");
let longitude_cov = read_var!(file, "longitude_cov");
let altitude_cov = read_var!(file, "altitude_cov");
let velocity_n_cov = read_var!(file, "velocity_n_cov");
let velocity_e_cov = read_var!(file, "velocity_e_cov");
let velocity_v_cov = read_var!(file, "velocity_v_cov");
let roll_cov = read_var!(file, "roll_cov");
let pitch_cov = read_var!(file, "pitch_cov");
let yaw_cov = read_var!(file, "yaw_cov");
let acc_bias_x_cov = read_var!(file, "acc_bias_x_cov");
let acc_bias_y_cov = read_var!(file, "acc_bias_y_cov");
let acc_bias_z_cov = read_var!(file, "acc_bias_z_cov");
let gyro_bias_x_cov = read_var!(file, "gyro_bias_x_cov");
let gyro_bias_y_cov = read_var!(file, "gyro_bias_y_cov");
let gyro_bias_z_cov = read_var!(file, "gyro_bias_z_cov");
let mut records = Vec::with_capacity(n);
for i in 0..n {
let timestamp = DateTime::from_timestamp(timestamps[i] as i64, 0)
.ok_or_else(|| anyhow::anyhow!("Invalid timestamp"))?
.with_timezone(&Utc);
records.push(NavigationResult {
timestamp,
latitude: latitude[i],
longitude: longitude[i],
altitude: altitude[i],
velocity_north: velocity_north[i],
velocity_east: velocity_east[i],
velocity_vertical: velocity_vertical[i],
roll: roll[i],
pitch: pitch[i],
yaw: yaw[i],
acc_bias_x: acc_bias_x[i],
acc_bias_y: acc_bias_y[i],
acc_bias_z: acc_bias_z[i],
gyro_bias_x: gyro_bias_x[i],
gyro_bias_y: gyro_bias_y[i],
gyro_bias_z: gyro_bias_z[i],
latitude_cov: latitude_cov[i],
longitude_cov: longitude_cov[i],
altitude_cov: altitude_cov[i],
velocity_n_cov: velocity_n_cov[i],
velocity_e_cov: velocity_e_cov[i],
velocity_v_cov: velocity_v_cov[i],
roll_cov: roll_cov[i],
pitch_cov: pitch_cov[i],
yaw_cov: yaw_cov[i],
acc_bias_x_cov: acc_bias_x_cov[i],
acc_bias_y_cov: acc_bias_y_cov[i],
acc_bias_z_cov: acc_bias_z_cov[i],
gyro_bias_x_cov: gyro_bias_x_cov[i],
gyro_bias_y_cov: gyro_bias_y_cov[i],
gyro_bias_z_cov: gyro_bias_z_cov[i],
});
}
Ok(records)
}
pub fn to_mcap<P: AsRef<Path>>(records: &[Self], path: P) -> io::Result<()> {
use mcap::{Writer, records::MessageHeader};
use std::collections::BTreeMap;
use std::fs::File;
use std::io::BufWriter;
let file = File::create(path)?;
let buf_writer = BufWriter::new(file);
let mut writer = Writer::new(buf_writer).map_err(io::Error::other)?;
let schema_name = "NavigationResult";
let schema_encoding = "msgpack";
let schema_data = b"NavigationResult struct serialized with MessagePack";
let schema_id = writer
.add_schema(schema_name, schema_encoding, schema_data)
.map_err(io::Error::other)?;
let metadata = BTreeMap::new();
let channel_id = writer
.add_channel(schema_id, "navigation_results", "msgpack", &metadata)
.map_err(io::Error::other)?;
for (seq, record) in records.iter().enumerate() {
let data = rmp_serde::to_vec(record)
.map_err(|e| io::Error::new(io::ErrorKind::InvalidData, e))?;
let timestamp_nanos = record.timestamp.timestamp_nanos_opt().ok_or_else(|| {
io::Error::new(io::ErrorKind::InvalidData, "Timestamp out of range")
})?;
let header = MessageHeader {
channel_id,
sequence: seq as u32,
log_time: timestamp_nanos as u64,
publish_time: timestamp_nanos as u64,
};
writer
.write_to_known_channel(&header, &data)
.map_err(io::Error::other)?;
}
writer.finish().map_err(io::Error::other)?;
Ok(())
}
pub fn from_mcap<P: AsRef<Path>>(path: P) -> Result<Vec<Self>, Box<dyn std::error::Error>> {
use mcap::MessageStream;
use std::fs::File;
let file = File::open(path)?;
let mapped = unsafe { memmap2::Mmap::map(&file)? };
let message_stream = MessageStream::new(&mapped)?;
let mut records = Vec::new();
for message_result in message_stream {
let message = message_result?;
let record: Self = rmp_serde::from_slice(&message.data)?;
records.push(record);
}
Ok(records)
}
}
impl From<(&DateTime<Utc>, &DVector<f64>, &DMatrix<f64>)> for NavigationResult {
fn from(
(timestamp, state, covariance): (&DateTime<Utc>, &DVector<f64>, &DMatrix<f64>),
) -> Self {
assert!(
state.len() == 15,
"State vector must have 15 elements; got {}",
state.len()
);
assert!(
covariance.nrows() == 15 && covariance.ncols() == 15,
"Covariance matrix must be 15x15"
);
let covariance = DVector::from_vec(covariance.diagonal().iter().copied().collect());
NavigationResult {
timestamp: *timestamp,
latitude: state[0].to_degrees(),
longitude: state[1].to_degrees(),
altitude: state[2],
velocity_north: state[3],
velocity_east: state[4],
velocity_vertical: state[5],
roll: state[6],
pitch: state[7],
yaw: state[8],
acc_bias_x: state[9],
acc_bias_y: state[10],
acc_bias_z: state[11],
gyro_bias_x: state[12],
gyro_bias_y: state[13],
gyro_bias_z: state[14],
latitude_cov: covariance[0],
longitude_cov: covariance[1],
altitude_cov: covariance[2],
velocity_n_cov: covariance[3],
velocity_e_cov: covariance[4],
velocity_v_cov: covariance[5],
roll_cov: covariance[6],
pitch_cov: covariance[7],
yaw_cov: covariance[8],
acc_bias_x_cov: covariance[9],
acc_bias_y_cov: covariance[10],
acc_bias_z_cov: covariance[11],
gyro_bias_x_cov: covariance[12],
gyro_bias_y_cov: covariance[13],
gyro_bias_z_cov: covariance[14],
}
}
}
impl From<(&DateTime<Utc>, &UnscentedKalmanFilter)> for NavigationResult {
fn from((timestamp, ukf): (&DateTime<Utc>, &UnscentedKalmanFilter)) -> Self {
let state = &ukf.get_estimate();
let covariance = ukf.get_certainty();
NavigationResult {
timestamp: *timestamp,
latitude: state[0].to_degrees(),
longitude: state[1].to_degrees(),
altitude: state[2],
velocity_north: state[3],
velocity_east: state[4],
velocity_vertical: state[5],
roll: state[6],
pitch: state[7],
yaw: state[8],
acc_bias_x: state[9],
acc_bias_y: state[10],
acc_bias_z: state[11],
gyro_bias_x: state[12],
gyro_bias_y: state[13],
gyro_bias_z: state[14],
latitude_cov: covariance[(0, 0)],
longitude_cov: covariance[(1, 1)],
altitude_cov: covariance[(2, 2)],
velocity_n_cov: covariance[(3, 3)],
velocity_e_cov: covariance[(4, 4)],
velocity_v_cov: covariance[(5, 5)],
roll_cov: covariance[(6, 6)],
pitch_cov: covariance[(7, 7)],
yaw_cov: covariance[(8, 8)],
acc_bias_x_cov: covariance[(9, 9)],
acc_bias_y_cov: covariance[(10, 10)],
acc_bias_z_cov: covariance[(11, 11)],
gyro_bias_x_cov: covariance[(12, 12)],
gyro_bias_y_cov: covariance[(13, 13)],
gyro_bias_z_cov: covariance[(14, 14)],
}
}
}
impl From<(&DateTime<Utc>, &crate::kalman::ExtendedKalmanFilter)> for NavigationResult {
fn from((timestamp, ekf): (&DateTime<Utc>, &crate::kalman::ExtendedKalmanFilter)) -> Self {
let state = &ekf.get_estimate();
let covariance = ekf.get_certainty();
NavigationResult {
timestamp: *timestamp,
latitude: state[0].to_degrees(),
longitude: state[1].to_degrees(),
altitude: state[2],
velocity_north: state[3],
velocity_east: state[4],
velocity_vertical: state[5],
roll: state[6],
pitch: state[7],
yaw: state[8],
acc_bias_x: if state.len() > 9 { state[9] } else { 0.0 },
acc_bias_y: if state.len() > 10 { state[10] } else { 0.0 },
acc_bias_z: if state.len() > 11 { state[11] } else { 0.0 },
gyro_bias_x: if state.len() > 12 { state[12] } else { 0.0 },
gyro_bias_y: if state.len() > 13 { state[13] } else { 0.0 },
gyro_bias_z: if state.len() > 14 { state[14] } else { 0.0 },
latitude_cov: covariance[(0, 0)],
longitude_cov: covariance[(1, 1)],
altitude_cov: covariance[(2, 2)],
velocity_n_cov: covariance[(3, 3)],
velocity_e_cov: covariance[(4, 4)],
velocity_v_cov: covariance[(5, 5)],
roll_cov: covariance[(6, 6)],
pitch_cov: covariance[(7, 7)],
yaw_cov: covariance[(8, 8)],
acc_bias_x_cov: if covariance.nrows() > 9 {
covariance[(9, 9)]
} else {
0.0
},
acc_bias_y_cov: if covariance.nrows() > 10 {
covariance[(10, 10)]
} else {
0.0
},
acc_bias_z_cov: if covariance.nrows() > 11 {
covariance[(11, 11)]
} else {
0.0
},
gyro_bias_x_cov: if covariance.nrows() > 12 {
covariance[(12, 12)]
} else {
0.0
},
gyro_bias_y_cov: if covariance.nrows() > 13 {
covariance[(13, 13)]
} else {
0.0
},
gyro_bias_z_cov: if covariance.nrows() > 14 {
covariance[(14, 14)]
} else {
0.0
},
}
}
}
impl From<(&DateTime<Utc>, &StrapdownState)> for NavigationResult {
fn from((timestamp, state): (&DateTime<Utc>, &StrapdownState)) -> Self {
NavigationResult {
timestamp: *timestamp,
latitude: state.latitude.to_degrees(),
longitude: state.longitude.to_degrees(),
altitude: state.altitude,
velocity_north: state.velocity_north,
velocity_east: state.velocity_east,
velocity_vertical: state.velocity_vertical,
roll: state.attitude.euler_angles().0,
pitch: state.attitude.euler_angles().1,
yaw: state.attitude.euler_angles().2,
acc_bias_x: 0.0, acc_bias_y: 0.0,
acc_bias_z: 0.0,
gyro_bias_x: 0.0,
gyro_bias_y: 0.0,
gyro_bias_z: 0.0,
latitude_cov: f64::NAN, longitude_cov: f64::NAN,
altitude_cov: f64::NAN,
velocity_n_cov: f64::NAN,
velocity_e_cov: f64::NAN,
velocity_v_cov: f64::NAN,
roll_cov: f64::NAN,
pitch_cov: f64::NAN,
yaw_cov: f64::NAN,
acc_bias_x_cov: f64::NAN,
acc_bias_y_cov: f64::NAN,
acc_bias_z_cov: f64::NAN,
gyro_bias_x_cov: f64::NAN,
gyro_bias_y_cov: f64::NAN,
gyro_bias_z_cov: f64::NAN,
}
}
}
impl NavigationResult {
pub fn from_particle_filter(
timestamp: &DateTime<Utc>,
mean: &DVector<f64>,
cov: &DMatrix<f64>,
) -> Self {
assert_eq!(mean.len(), 9, "Particle filter state must have 9 elements");
assert_eq!(
cov.shape(),
(9, 9),
"Particle filter covariance must be 9x9"
);
NavigationResult {
timestamp: *timestamp,
latitude: mean[0].to_degrees(),
longitude: mean[1].to_degrees(),
altitude: mean[2],
velocity_north: mean[3],
velocity_east: mean[4],
velocity_vertical: mean[5],
roll: mean[6],
pitch: mean[7],
yaw: mean[8],
acc_bias_x: 0.0, acc_bias_y: 0.0,
acc_bias_z: 0.0,
gyro_bias_x: 0.0,
gyro_bias_y: 0.0,
gyro_bias_z: 0.0,
latitude_cov: cov[(0, 0)],
longitude_cov: cov[(1, 1)],
altitude_cov: cov[(2, 2)],
velocity_n_cov: cov[(3, 3)],
velocity_e_cov: cov[(4, 4)],
velocity_v_cov: cov[(5, 5)],
roll_cov: cov[(6, 6)],
pitch_cov: cov[(7, 7)],
yaw_cov: cov[(8, 8)],
acc_bias_x_cov: f64::NAN,
acc_bias_y_cov: f64::NAN,
acc_bias_z_cov: f64::NAN,
gyro_bias_x_cov: f64::NAN,
gyro_bias_y_cov: f64::NAN,
gyro_bias_z_cov: f64::NAN,
}
}
}
pub fn dead_reckoning(records: &[TestDataRecord]) -> Vec<NavigationResult> {
if records.is_empty() {
return Vec::new();
}
let mut results = Vec::with_capacity(records.len());
let first_record = &records[0];
let attitude = nalgebra::Rotation3::from_euler_angles(
first_record.roll,
first_record.pitch,
first_record.yaw,
);
let mut state = StrapdownState {
latitude: first_record.latitude.to_radians(),
longitude: first_record.longitude.to_radians(),
altitude: first_record.altitude,
velocity_north: first_record.speed * first_record.bearing.cos(),
velocity_east: first_record.speed * first_record.bearing.sin(),
velocity_vertical: 0.0, attitude,
is_enu: true,
};
results.push(NavigationResult::from((&first_record.time, &state)));
let mut previous_time = records[0].time;
for record in records.iter().skip(1) {
let current_time = record.time;
let dt = (current_time - previous_time).as_seconds_f64();
let imu_data = IMUData {
accel: Vector3::new(record.acc_x, record.acc_y, record.acc_z),
gyro: Vector3::new(record.gyro_x, record.gyro_y, record.gyro_z),
};
forward(&mut state, imu_data, dt);
results.push(NavigationResult::from((¤t_time, &state)));
previous_time = record.time;
}
results
}
pub fn run_closed_loop<F: NavigationFilter>(
filter: &mut F,
stream: EventStream,
health_limits: Option<HealthLimits>,
execution_limits: Option<ExecutionLimits>,
) -> anyhow::Result<Vec<NavigationResult>> {
let start_time = stream.start_time;
let mut results: Vec<NavigationResult> = Vec::with_capacity(stream.events.len());
let total = stream.events.len();
let mut monitor = HealthMonitor::new(health_limits.unwrap_or_default());
let sim_duration_s = stream
.events
.last()
.map(|event| match event {
Event::Imu { elapsed_s, .. } => *elapsed_s,
Event::Measurement { elapsed_s, .. } => *elapsed_s,
})
.unwrap_or(0.0);
let mut execution_monitor =
execution_limits.map(|limits| ExecutionMonitor::new(limits, sim_duration_s));
info!(
"Starting closed-loop navigation filter with {} events",
total
);
let mean = filter.get_estimate();
let cov = filter.get_certainty();
results.push(NavigationResult::from((&start_time, &mean, &cov)));
debug!("Initial filter state at {}: {:?}", start_time, mean);
let mut last_ts = Some(start_time);
for (i, event) in stream.events.into_iter().enumerate() {
if i % 10 == 0 || i == total {
let mean = filter.get_estimate();
let cov = filter.get_certainty();
let lat = mean[0].to_degrees();
let lon = mean[1].to_degrees();
let alt = mean[2];
let pos_std_lat = cov[(0, 0)].sqrt().to_degrees();
let pos_std_lon = cov[(1, 1)].sqrt().to_degrees();
let pos_std_alt = cov[(2, 2)].sqrt();
let pos_rms = (pos_std_lat.powi(2) + pos_std_lon.powi(2) + pos_std_alt.powi(2)).sqrt();
info!(
"[{:.1}%] Event {}/{} | Pos: ({:.6}°, {:.6}°, {:.1}m) | Vel: ({:.2} m/s, {:.2} m/s, {:.2} m/s) | σ: ({:.2e}°, {:.2e}°, {:.2}m) | RMS: {:.2e}",
(i as f64 / total as f64) * 100.0,
i,
total,
lat,
lon,
alt,
mean[3],
mean[4],
mean[5],
pos_std_lat,
pos_std_lon,
pos_std_alt,
pos_rms
);
}
let elapsed_s = match &event {
Event::Imu { elapsed_s, .. } => *elapsed_s,
Event::Measurement { elapsed_s, .. } => *elapsed_s,
};
let ts = start_time + Duration::milliseconds((elapsed_s * 1000.0).round() as i64);
match event {
Event::Imu { dt_s, imu, .. } => {
filter.predict(&imu, dt_s);
let mean = filter.get_estimate();
let cov = filter.get_certainty();
if let Err(e) = monitor.check(mean.as_slice(), &cov, None) {
log::error!("Health fail after propagate at {} (#{i}): {e}", ts);
bail!(e);
}
}
Event::Measurement { meas, .. } => {
filter.update(meas.as_ref());
let mean = filter.get_estimate();
let cov = filter.get_certainty();
if let Err(e) = monitor.check(mean.as_slice(), &cov, None) {
log::error!("Health fail after measurement update at {} (#{i}): {e}", ts);
bail!(e);
}
}
}
if let Some(ref mut monitor) = execution_monitor {
monitor.check("closed-loop")?;
monitor.mark_progress();
}
if Some(ts) != last_ts {
if let Some(prev_ts) = last_ts {
if prev_ts != start_time {
let mean = filter.get_estimate();
let cov = filter.get_certainty();
results.push(NavigationResult::from((&prev_ts, &mean, &cov)));
debug!("Filter state at {}: {:?}", ts, mean);
}
}
last_ts = Some(ts);
}
if i == total - 1 {
let mean = filter.get_estimate();
let cov = filter.get_certainty();
results.push(NavigationResult::from((&ts, &mean, &cov)));
debug!("Filter state at {}: {:?}", ts, mean);
last_ts = Some(ts);
}
}
debug!("Closed-loop simulation complete");
Ok(results)
}
pub fn print_ukf(ukf: &UnscentedKalmanFilter, record: &TestDataRecord) {
debug!(
"UKF position: ({:.4}, {:.4}, {:.4}) | Covariance: {:.4e}, {:.4e}, {:.4} | Error: {:.4e}, {:.4e}, {:.4}",
ukf.get_estimate()[0].to_degrees(),
ukf.get_estimate()[1].to_degrees(),
ukf.get_estimate()[2],
ukf.get_certainty()[(0, 0)],
ukf.get_certainty()[(1, 1)],
ukf.get_certainty()[(2, 2)],
ukf.get_estimate()[0].to_degrees() - record.latitude,
ukf.get_estimate()[1].to_degrees() - record.longitude,
ukf.get_estimate()[2] - record.altitude
);
debug!(
"UKF velocity: ({:.4}, {:.4}, {:.4}) | Covariance: {:.4}, {:.4}, {:.4} | Error: {:.4}, {:.4}, {:.4}",
ukf.get_estimate()[3],
ukf.get_estimate()[4],
ukf.get_estimate()[5],
ukf.get_certainty()[(3, 3)],
ukf.get_certainty()[(4, 4)],
ukf.get_certainty()[(5, 5)],
ukf.get_estimate()[3] - record.speed * record.bearing.cos(),
ukf.get_estimate()[4] - record.speed * record.bearing.sin(),
ukf.get_estimate()[5] - 0.0 );
debug!(
"UKF attitude: ({:.4}, {:.4}, {:.4}) | Covariance: {:.4}, {:.4}, {:.4} | Error: {:.4}, {:.4}, {:.4}",
ukf.get_estimate()[6],
ukf.get_estimate()[7],
ukf.get_estimate()[8],
ukf.get_certainty()[(6, 6)],
ukf.get_certainty()[(7, 7)],
ukf.get_certainty()[(8, 8)],
ukf.get_estimate()[6] - record.roll,
ukf.get_estimate()[7] - record.pitch,
ukf.get_estimate()[8] - record.yaw
);
debug!(
"UKF accel biases: ({:.4}, {:.4}, {:.4}) | Covariance: {:.4e}, {:.4e}, {:.4e}",
ukf.get_estimate()[9],
ukf.get_estimate()[10],
ukf.get_estimate()[11],
ukf.get_certainty()[(9, 9)],
ukf.get_certainty()[(10, 10)],
ukf.get_certainty()[(11, 11)]
);
debug!(
"UKF gyro biases: ({:.4}, {:.4}, {:.4}) | Covariance: {:.4e}, {:.4e}, {:.4e}",
ukf.get_estimate()[12],
ukf.get_estimate()[13],
ukf.get_estimate()[14],
ukf.get_certainty()[(12, 12)],
ukf.get_certainty()[(13, 13)],
ukf.get_certainty()[(14, 14)]
);
}
#[derive(Debug, Clone, Default)]
pub struct UkfConfig {
pub attitude_covariance: Option<Vec<f64>>,
pub imu_biases: Option<Vec<f64>>,
pub imu_biases_covariance: Option<Vec<f64>>,
pub other_states: Option<Vec<f64>>,
pub other_states_covariance: Option<Vec<f64>>,
pub process_noise_diagonal: Option<Vec<f64>>,
pub ukf_alpha: Option<f64>,
pub ukf_beta: Option<f64>,
pub ukf_kappa: Option<f64>,
}
pub fn initialize_ukf(initial_pose: TestDataRecord, config: UkfConfig) -> UnscentedKalmanFilter {
let initial_state = InitialState {
latitude: initial_pose.latitude,
longitude: initial_pose.longitude,
altitude: initial_pose.altitude,
northward_velocity: initial_pose.speed * initial_pose.bearing.cos(),
eastward_velocity: initial_pose.speed * initial_pose.bearing.sin(),
vertical_velocity: 0.0, roll: if initial_pose.roll.is_nan() {
0.0
} else {
initial_pose.roll
},
pitch: if initial_pose.pitch.is_nan() {
0.0
} else {
initial_pose.pitch
},
yaw: if initial_pose.yaw.is_nan() {
0.0
} else {
initial_pose.yaw
},
in_degrees: true,
is_enu: true,
};
let process_noise_diagonal = match config.process_noise_diagonal {
Some(pn) => pn,
None => DEFAULT_PROCESS_NOISE.to_vec(),
};
let position_accuracy = initial_pose.horizontal_accuracy; let position_std_rad = (position_accuracy * METERS_TO_DEGREES).to_radians();
let mut covariance_diagonal = vec![
position_std_rad.powf(2.0),
position_std_rad.powf(2.0),
initial_pose.vertical_accuracy.powf(2.0),
initial_pose.speed_accuracy.powf(2.0),
initial_pose.speed_accuracy.powf(2.0),
initial_pose.speed_accuracy.powf(2.0),
];
match config.attitude_covariance {
Some(att_cov) => covariance_diagonal.extend(att_cov),
None => covariance_diagonal.extend(vec![1e-9; 3]), }
let imu_biases = match config.imu_biases {
Some(imu_biases) => {
covariance_diagonal.extend(match config.imu_biases_covariance {
Some(imu_cov) => imu_cov,
None => vec![1e-3; 6], });
imu_biases
}
None => {
covariance_diagonal.extend(vec![1e-3; 6]);
vec![1e-3; 6] }
};
let other_states = match config.other_states {
Some(other_states) => {
covariance_diagonal.extend(match config.other_states_covariance {
Some(other_cov) => other_cov,
None => vec![1e-3; other_states.len()], });
Some(other_states)
}
None => None,
};
assert!(
covariance_diagonal.len() == 15 + other_states.as_ref().map_or(0, |v| v.len()),
"Covariance diagonal length mismatch: expected {}, got {}",
15 + other_states.as_ref().map_or(0, |v| v.len()),
covariance_diagonal.len()
);
assert!(
process_noise_diagonal.len() == 15 + other_states.as_ref().map_or(0, |v| v.len()),
"Process noise diagonal length mismatch: expected {}, got {}",
15 + other_states.as_ref().map_or(0, |v| v.len()),
process_noise_diagonal.len()
);
assert!(
process_noise_diagonal.len() == covariance_diagonal.len(),
"Process noise and covariance diagonal length mismatch: {} vs {}",
process_noise_diagonal.len(),
covariance_diagonal.len()
);
let process_noise = DMatrix::from_diagonal(&DVector::from_vec(process_noise_diagonal));
UnscentedKalmanFilter::new(
initial_state,
imu_biases,
other_states,
covariance_diagonal,
process_noise,
config.ukf_alpha.unwrap_or(1e-3),
config.ukf_beta.unwrap_or(2.0),
config.ukf_kappa.unwrap_or(0.0),
)
}
#[allow(clippy::too_many_arguments)]
pub fn initialize_ekf(
initial_pose: TestDataRecord,
attitude_covariance: Option<Vec<f64>>,
imu_biases: Option<Vec<f64>>,
imu_biases_covariance: Option<Vec<f64>>,
process_noise_diagonal: Option<Vec<f64>>,
use_biases: bool,
) -> crate::kalman::ExtendedKalmanFilter {
use crate::kalman::ExtendedKalmanFilter;
let initial_state = InitialState {
latitude: initial_pose.latitude,
longitude: initial_pose.longitude,
altitude: initial_pose.altitude,
northward_velocity: initial_pose.speed * initial_pose.bearing.to_radians().cos(),
eastward_velocity: initial_pose.speed * initial_pose.bearing.to_radians().sin(),
vertical_velocity: 0.0,
roll: if initial_pose.roll.is_nan() {
0.0
} else {
initial_pose.roll
},
pitch: if initial_pose.pitch.is_nan() {
0.0
} else {
initial_pose.pitch
},
yaw: if initial_pose.yaw.is_nan() {
0.0
} else {
initial_pose.yaw
},
in_degrees: true,
is_enu: true,
};
let state_size = if use_biases { 15 } else { 9 };
let process_noise_diagonal = match process_noise_diagonal {
Some(pn) => {
assert!(
pn.len() == state_size,
"Process noise diagonal length mismatch: expected {}, got {}",
state_size,
pn.len()
);
pn
}
None => {
if use_biases {
DEFAULT_PROCESS_NOISE.to_vec()
} else {
DEFAULT_PROCESS_NOISE[0..9].to_vec()
}
}
};
let position_accuracy = initial_pose.horizontal_accuracy;
let mut covariance_diagonal = vec![
(position_accuracy * METERS_TO_DEGREES).powf(2.0),
(position_accuracy * METERS_TO_DEGREES).powf(2.0),
initial_pose.vertical_accuracy.powf(2.0),
initial_pose.speed_accuracy.powf(2.0),
initial_pose.speed_accuracy.powf(2.0),
initial_pose.speed_accuracy.powf(2.0),
];
match attitude_covariance {
Some(att_cov) => {
assert!(
att_cov.len() == 3,
"Attitude covariance must have 3 elements"
);
covariance_diagonal.extend(att_cov);
}
None => covariance_diagonal.extend(vec![1e-9; 3]),
}
let imu_biases_vec = if use_biases {
match imu_biases {
Some(biases) => {
assert!(biases.len() == 6, "IMU biases must have 6 elements");
covariance_diagonal.extend(match imu_biases_covariance {
Some(imu_cov) => {
assert!(
imu_cov.len() == 6,
"IMU bias covariance must have 6 elements"
);
imu_cov
}
None => vec![1e-3; 6],
});
biases
}
None => {
covariance_diagonal.extend(vec![1e-3; 6]);
vec![0.0; 6]
}
}
} else {
vec![0.0; 6] };
assert!(
covariance_diagonal.len() == state_size,
"Covariance diagonal length mismatch: expected {}, got {}",
state_size,
covariance_diagonal.len()
);
let process_noise = DMatrix::from_diagonal(&DVector::from_vec(process_noise_diagonal));
ExtendedKalmanFilter::new(
initial_state,
imu_biases_vec,
covariance_diagonal,
process_noise,
use_biases,
)
}
#[allow(clippy::too_many_arguments)]
pub fn initialize_eskf(
initial_pose: TestDataRecord,
attitude_covariance: Option<Vec<f64>>,
imu_biases: Option<Vec<f64>>,
imu_biases_covariance: Option<Vec<f64>>,
process_noise_diagonal: Option<Vec<f64>>,
) -> crate::kalman::ErrorStateKalmanFilter {
use crate::kalman::ErrorStateKalmanFilter;
let initial_state = InitialState {
latitude: initial_pose.latitude,
longitude: initial_pose.longitude,
altitude: initial_pose.altitude,
northward_velocity: initial_pose.speed * initial_pose.bearing.to_radians().cos(),
eastward_velocity: initial_pose.speed * initial_pose.bearing.to_radians().sin(),
vertical_velocity: 0.0,
roll: if initial_pose.roll.is_nan() {
0.0
} else {
initial_pose.roll
},
pitch: if initial_pose.pitch.is_nan() {
0.0
} else {
initial_pose.pitch
},
yaw: if initial_pose.yaw.is_nan() {
0.0
} else {
initial_pose.yaw
},
in_degrees: true,
is_enu: true,
};
let state_size = 15;
let process_noise_diagonal = match process_noise_diagonal {
Some(pn) => {
assert!(
pn.len() == state_size,
"Process noise diagonal length mismatch: expected {}, got {}",
state_size,
pn.len()
);
pn
}
None => DEFAULT_PROCESS_NOISE.to_vec(),
};
let imu_biases = match imu_biases {
Some(biases) => {
assert!(
biases.len() == 6,
"IMU biases length mismatch: expected 6, got {}",
biases.len()
);
biases
}
None => vec![0.0; 6],
};
let mut error_covariance_diagonal = vec![
1e-6, 1e-6, 1e-4, 1e-3, 1e-3, 1e-3, ];
error_covariance_diagonal.extend(match attitude_covariance {
Some(att_cov) => {
assert!(
att_cov.len() == 3,
"Attitude covariance length mismatch: expected 3, got {}",
att_cov.len()
);
att_cov
}
None => vec![1e-5; 3], });
error_covariance_diagonal.extend(match imu_biases_covariance {
Some(bias_cov) => {
assert!(
bias_cov.len() == 6,
"IMU bias covariance length mismatch: expected 6, got {}",
bias_cov.len()
);
bias_cov
}
None => {
vec![
1e-6, 1e-6, 1e-6, 1e-8, 1e-8, 1e-8, ]
}
});
assert!(
error_covariance_diagonal.len() == state_size,
"Error covariance diagonal length mismatch: expected {}, got {}",
state_size,
error_covariance_diagonal.len()
);
let process_noise = DMatrix::from_diagonal(&DVector::from_vec(process_noise_diagonal));
ErrorStateKalmanFilter::new(
initial_state,
imu_biases,
error_covariance_diagonal,
process_noise,
)
}
pub fn print_sim_status<F: NavigationFilter>(filter: &F) {
let mean = filter.get_estimate();
let cov = filter.get_certainty();
let lat = mean[0].to_degrees();
let lon = mean[1].to_degrees();
let alt = mean[2];
let pos_std_lat = cov[(0, 0)].sqrt().to_degrees();
let pos_std_lon = cov[(1, 1)].sqrt().to_degrees();
let pos_std_alt = cov[(2, 2)].sqrt();
let pos_rms = (pos_std_lat.powi(2) + pos_std_lon.powi(2) + pos_std_alt.powi(2)).sqrt();
debug!(
"\rPos: ({:.6}°, {:.6}°, {:.1}m) | σ: ({:.2e}°, {:.2e}°, {:.2}m) | RMS: {:.2e}",
lat, lon, alt, pos_std_lat, pos_std_lon, pos_std_alt, pos_rms
);
}
pub mod execution {
use super::*;
#[derive(Clone, Debug, Serialize, Deserialize)]
pub struct ExecutionLimits {
#[serde(default = "default_max_wall_clock_ratio")]
pub max_wall_clock_ratio: f64,
#[serde(default = "default_max_wall_clock_s")]
pub max_wall_clock_s: f64,
#[serde(default = "default_max_no_progress_s")]
pub max_no_progress_s: f64,
}
fn default_max_wall_clock_ratio() -> f64 {
DEFAULT_MAX_WALL_CLOCK_RATIO
}
fn default_max_wall_clock_s() -> f64 {
DEFAULT_MAX_WALL_CLOCK_S
}
fn default_max_no_progress_s() -> f64 {
DEFAULT_MAX_NO_PROGRESS_S
}
impl Default for ExecutionLimits {
fn default() -> Self {
Self {
max_wall_clock_ratio: default_max_wall_clock_ratio(),
max_wall_clock_s: default_max_wall_clock_s(),
max_no_progress_s: default_max_no_progress_s(),
}
}
}
#[derive(Clone, Debug)]
pub struct ExecutionMonitor {
start_time: Instant,
last_progress: Instant,
max_wall_clock: Option<StdDuration>,
max_no_progress: Option<StdDuration>,
}
impl ExecutionMonitor {
pub fn new(limits: ExecutionLimits, sim_duration_s: f64) -> Self {
let max_wall_clock = compute_max_wall_clock(
sim_duration_s,
limits.max_wall_clock_ratio,
limits.max_wall_clock_s,
);
let max_no_progress = if limits.max_no_progress_s > 0.0 {
Some(StdDuration::from_secs_f64(limits.max_no_progress_s))
} else {
None
};
let now = Instant::now();
Self {
start_time: now,
last_progress: now,
max_wall_clock,
max_no_progress,
}
}
pub fn check(&mut self, context: &str) -> Result<()> {
let now = Instant::now();
if let Some(max_wall_clock) = self.max_wall_clock
&& now.duration_since(self.start_time) > max_wall_clock
{
bail!(
"Execution timeout ({context}): exceeded wall-clock limit of {:.2} s",
max_wall_clock.as_secs_f64()
);
}
if let Some(max_no_progress) = self.max_no_progress {
let since_progress = now.duration_since(self.last_progress);
if since_progress > max_no_progress {
bail!(
"Execution timeout ({context}): no progress for {:.2} s (limit {:.2} s)",
since_progress.as_secs_f64(),
max_no_progress.as_secs_f64()
);
}
}
Ok(())
}
pub fn mark_progress(&mut self) {
self.last_progress = Instant::now();
}
}
fn compute_max_wall_clock(
sim_duration_s: f64,
max_ratio: f64,
max_wall_clock_s: f64,
) -> Option<StdDuration> {
let mut max_s = None;
if sim_duration_s > 0.0 && max_ratio > 0.0 {
max_s = Some(sim_duration_s * max_ratio);
}
if max_wall_clock_s > 0.0 {
max_s = Some(match max_s {
Some(current) => current.min(max_wall_clock_s),
None => max_wall_clock_s,
});
}
max_s.and_then(|s| {
if s > 0.0 {
Some(StdDuration::from_secs_f64(s))
} else {
None
}
})
}
}
pub mod health {
use super::*;
#[derive(Clone, Debug)]
pub struct HealthLimits {
pub lat_rad: (f64, f64), pub lon_rad: (f64, f64), pub alt_m: (f64, f64), pub speed_mps_max: f64, pub cov_diag_max: f64, pub cond_max: f64, pub nis_pos_max: f64, pub nis_pos_consec_fail: usize, }
impl Default for HealthLimits {
fn default() -> Self {
Self {
lat_rad: (-std::f64::consts::FRAC_PI_2, std::f64::consts::FRAC_PI_2),
lon_rad: (-std::f64::consts::PI, std::f64::consts::PI),
alt_m: (-100000000.0, 100000000.0), speed_mps_max: 500.0,
cov_diag_max: 1e15,
cond_max: 1e12,
nis_pos_max: 100.0,
nis_pos_consec_fail: 20,
}
}
}
#[derive(Default, Clone, Debug)]
pub struct HealthMonitor {
limits: HealthLimits,
consec_nis_pos_fail: usize,
}
impl HealthMonitor {
pub fn new(limits: HealthLimits) -> Self {
Self {
limits,
consec_nis_pos_fail: 0,
}
}
pub fn check(
&mut self,
x: &[f64], p: &nalgebra::DMatrix<f64>,
maybe_nis_pos: Option<f64>,
) -> Result<()> {
if !x.iter().all(|v| v.is_finite()) {
bail!("Non-finite state detected");
}
if !p.iter().all(|v| v.is_finite()) {
bail!("Non-finite covariance detected");
}
let lat = x[0];
let lon = x[1];
let alt = x[2];
if lat < self.limits.lat_rad.0 || lat > self.limits.lat_rad.1 {
bail!("Latitude out of range: {lat}");
}
if lon < self.limits.lon_rad.0 || lon > self.limits.lon_rad.1 {
bail!("Longitude out of range: {lon}");
}
if alt < self.limits.alt_m.0 || alt > self.limits.alt_m.1 {
bail!("Altitude out of range: {alt} m");
}
for i in 0..p.nrows().min(p.ncols()) {
if p[(i, i)].is_sign_negative() {
bail!("Negative variance on diagonal: idx={i}, val={}", p[(i, i)]);
}
if p[(i, i)] > self.limits.cov_diag_max {
bail!("Variance too large on diagonal idx={i}: {}", p[(i, i)]);
}
}
if let Some(nis_pos) = maybe_nis_pos {
if !nis_pos.is_finite() || nis_pos.is_sign_negative() {
bail!("Invalid NIS value: {nis_pos}");
}
if nis_pos > self.limits.nis_pos_max {
self.consec_nis_pos_fail += 1;
if self.consec_nis_pos_fail >= self.limits.nis_pos_consec_fail {
bail!(
"Consecutive NIS exceedances: {} (> {}), last NIS={}",
self.consec_nis_pos_fail,
self.limits.nis_pos_consec_fail,
nis_pos
);
}
} else {
self.consec_nis_pos_fail = 0;
}
}
Ok(())
}
}
}
#[derive(Copy, Clone, Debug)]
#[cfg_attr(feature = "clap", derive(ValueEnum))]
pub enum SchedKind {
Passthrough,
Fixed,
Duty,
}
#[derive(Clone, Debug)]
#[cfg_attr(feature = "clap", derive(Args))]
pub struct SchedulerArgs {
#[cfg_attr(feature = "clap", arg(long, value_enum, default_value_t = SchedKind::Passthrough))]
pub sched: SchedKind,
#[cfg_attr(feature = "clap", arg(long, default_value_t = 1.0))]
pub interval_s: f64,
#[cfg_attr(feature = "clap", arg(long, default_value_t = 0.0))]
pub phase_s: f64,
#[cfg_attr(feature = "clap", arg(long, default_value_t = 10.0))]
pub on_s: f64,
#[cfg_attr(feature = "clap", arg(long, default_value_t = 10.0))]
pub off_s: f64,
#[cfg_attr(feature = "clap", arg(long, default_value_t = 0.0))]
pub duty_phase_s: f64,
}
#[derive(Copy, Clone, Debug)]
#[cfg_attr(feature = "clap", derive(ValueEnum))]
pub enum FaultKind {
None,
Degraded,
Slowbias,
Hijack,
}
#[derive(Clone, Debug)]
#[cfg_attr(feature = "clap", derive(Args))]
pub struct FaultArgs {
#[cfg_attr(feature = "clap", arg(long, value_enum, default_value_t = FaultKind::None))]
pub fault: FaultKind,
#[cfg_attr(feature = "clap", arg(long, default_value_t = 0.99))]
pub rho_pos: f64,
#[cfg_attr(feature = "clap", arg(long, default_value_t = 3.0))]
pub sigma_pos_m: f64,
#[cfg_attr(feature = "clap", arg(long, default_value_t = 0.95))]
pub rho_vel: f64,
#[cfg_attr(feature = "clap", arg(long, default_value_t = 0.3))]
pub sigma_vel_mps: f64,
#[cfg_attr(feature = "clap", arg(long, default_value_t = 5.0))]
pub r_scale: f64,
#[cfg_attr(feature = "clap", arg(long, default_value_t = 0.02))]
pub drift_n_mps: f64,
#[cfg_attr(feature = "clap", arg(long, default_value_t = 0.0))]
pub drift_e_mps: f64,
#[cfg_attr(feature = "clap", arg(long, default_value_t = 1e-6))]
pub q_bias: f64,
#[cfg_attr(feature = "clap", arg(long, default_value_t = 0.0))]
pub rotate_omega_rps: f64,
#[cfg_attr(feature = "clap", arg(long, default_value_t = 50.0))]
pub hijack_offset_n_m: f64,
#[cfg_attr(feature = "clap", arg(long, default_value_t = 0.0))]
pub hijack_offset_e_m: f64,
#[cfg_attr(feature = "clap", arg(long, default_value_t = 120.0))]
pub hijack_start_s: f64,
#[cfg_attr(feature = "clap", arg(long, default_value_t = 60.0))]
pub hijack_duration_s: f64,
}
pub fn build_scheduler(a: &SchedulerArgs) -> GnssScheduler {
match a.sched {
SchedKind::Passthrough => GnssScheduler::PassThrough,
SchedKind::Fixed => GnssScheduler::FixedInterval {
interval_s: a.interval_s,
phase_s: a.phase_s,
},
SchedKind::Duty => GnssScheduler::DutyCycle {
on_s: a.on_s,
off_s: a.off_s,
start_phase_s: a.duty_phase_s,
},
}
}
pub fn build_fault(a: &FaultArgs) -> GnssFaultModel {
match a.fault {
FaultKind::None => GnssFaultModel::None,
FaultKind::Degraded => GnssFaultModel::Degraded {
rho_pos: a.rho_pos,
sigma_pos_m: a.sigma_pos_m,
rho_vel: a.rho_vel,
sigma_vel_mps: a.sigma_vel_mps,
r_scale: a.r_scale,
},
FaultKind::Slowbias => GnssFaultModel::SlowBias {
drift_n_mps: a.drift_n_mps,
drift_e_mps: a.drift_e_mps,
q_bias: a.q_bias,
rotate_omega_rps: a.rotate_omega_rps,
},
FaultKind::Hijack => GnssFaultModel::Hijack {
offset_n_m: a.hijack_offset_n_m,
offset_e_m: a.hijack_offset_e_m,
start_s: a.hijack_start_s,
duration_s: a.hijack_duration_s,
},
}
}
#[derive(Clone, Copy, Debug, Serialize, Deserialize)]
#[cfg_attr(feature = "clap", derive(ValueEnum))]
#[serde(rename_all = "kebab-case")]
pub enum SimulationMode {
DeadReckoning,
OpenLoop,
ClosedLoop,
ParticleFilter,
Synthetic,
}
#[derive(Clone, Copy, Debug, Serialize, Deserialize)]
#[cfg_attr(feature = "clap", derive(ValueEnum))]
#[serde(rename_all = "kebab-case")]
#[derive(Default)]
pub enum FilterType {
#[default]
Ukf,
Ekf,
Eskf,
}
#[derive(Clone, Copy, Debug, Serialize, Deserialize)]
#[cfg_attr(feature = "clap", derive(ValueEnum))]
#[serde(rename_all = "kebab-case")]
#[derive(Default)]
pub enum ParticleFilterType {
#[default]
Standard,
RaoBlackwellized,
Velocity,
}
#[derive(Clone, Debug, Serialize, Deserialize)]
pub struct ClosedLoopConfig {
#[serde(default)]
pub filter: FilterType,
#[serde(default = "default_ukf_alpha")]
pub ukf_alpha: f64,
#[serde(default = "default_ukf_beta")]
pub ukf_beta: f64,
#[serde(default = "default_ukf_kappa")]
pub ukf_kappa: f64,
}
impl Default for ClosedLoopConfig {
fn default() -> Self {
Self {
filter: FilterType::Ukf,
ukf_alpha: default_ukf_alpha(),
ukf_beta: default_ukf_beta(),
ukf_kappa: default_ukf_kappa(),
}
}
}
#[derive(Clone, Debug, Serialize, Deserialize)]
pub struct ParticleFilterConfig {
#[serde(default = "default_num_particles")]
pub num_particles: usize,
#[serde(default = "default_position_init_std_m")]
pub position_init_std_m: Vec<f64>,
#[serde(default = "default_velocity_init_std_mps")]
pub velocity_init_std_mps: f64,
#[serde(default = "default_attitude_init_std_rad")]
pub attitude_init_std_rad: f64,
#[serde(default = "default_position_process_noise_std_m")]
pub position_process_noise_std_m: Vec<f64>,
#[serde(default = "default_velocity_process_noise_std_mps")]
pub velocity_process_noise_std_mps: f64,
#[serde(default = "default_attitude_process_noise_std_rad")]
pub attitude_process_noise_std_rad: f64,
#[serde(default = "default_geo_bias_init_std")]
pub geo_bias_init_std: f64,
#[serde(default = "default_geo_bias_process_noise_std")]
pub geo_bias_process_noise_std: f64,
#[serde(default = "default_zero_vertical_velocity")]
pub zero_vertical_velocity: bool,
#[serde(default = "default_zero_vertical_velocity_std_mps")]
pub zero_vertical_velocity_std_mps: f64,
}
fn default_zero_vertical_velocity() -> bool {
true
}
fn default_zero_vertical_velocity_std_mps() -> f64 {
0.1
}
fn default_ukf_alpha() -> f64 {
1e-3
}
fn default_ukf_beta() -> f64 {
2.0
}
fn default_ukf_kappa() -> f64 {
0.0
}
fn default_num_particles() -> usize {
100
}
fn default_position_init_std_m() -> Vec<f64> {
vec![10.0, 10.0, 5.0]
}
fn default_velocity_init_std_mps() -> f64 {
1.0
}
fn default_attitude_init_std_rad() -> f64 {
0.1
}
fn default_position_process_noise_std_m() -> Vec<f64> {
vec![1.0, 1.0, 1.0]
}
fn default_velocity_process_noise_std_mps() -> f64 {
1e-3
}
fn default_attitude_process_noise_std_rad() -> f64 {
0.01
}
fn default_geo_bias_init_std() -> f64 {
1.0
}
fn default_geo_bias_process_noise_std() -> f64 {
1e-3
}
impl Default for ParticleFilterConfig {
fn default() -> Self {
Self {
num_particles: default_num_particles(),
position_init_std_m: default_position_init_std_m(),
velocity_init_std_mps: default_velocity_init_std_mps(),
attitude_init_std_rad: default_attitude_init_std_rad(),
position_process_noise_std_m: default_position_process_noise_std_m(),
velocity_process_noise_std_mps: default_velocity_process_noise_std_mps(),
attitude_process_noise_std_rad: default_attitude_process_noise_std_rad(),
geo_bias_init_std: default_geo_bias_init_std(),
geo_bias_process_noise_std: default_geo_bias_process_noise_std(),
zero_vertical_velocity: default_zero_vertical_velocity(),
zero_vertical_velocity_std_mps: default_zero_vertical_velocity_std_mps(),
}
}
}
#[derive(Clone, Copy, Debug, PartialEq, Eq, Serialize, Deserialize)]
#[serde(rename_all = "lowercase")]
#[cfg_attr(feature = "clap", derive(ValueEnum))]
pub enum LogLevel {
Off,
Error,
Warn,
Info,
Debug,
Trace,
}
impl LogLevel {
pub fn as_str(&self) -> &'static str {
match self {
LogLevel::Off => "off",
LogLevel::Error => "error",
LogLevel::Warn => "warn",
LogLevel::Info => "info",
LogLevel::Debug => "debug",
LogLevel::Trace => "trace",
}
}
}
#[derive(Clone, Debug, Serialize, Deserialize)]
pub struct LoggingConfig {
#[serde(default = "default_log_level")]
pub level: LogLevel,
#[serde(default, skip_serializing_if = "Option::is_none")]
pub file: Option<String>,
}
fn default_log_level() -> LogLevel {
LogLevel::Info
}
impl Default for LoggingConfig {
fn default() -> Self {
Self {
level: default_log_level(),
file: None,
}
}
}
#[derive(Clone, Debug, Serialize, Deserialize)]
pub struct SimulationConfig {
#[serde(default = "default_input")]
pub input: String,
#[serde(default = "default_output")]
pub output: String,
pub mode: SimulationMode,
#[serde(default = "default_seed")]
pub seed: u64,
#[serde(default)]
pub parallel: bool,
#[serde(default)]
pub generate_plot: bool,
#[serde(default)]
pub execution_limits: ExecutionLimits,
#[serde(default)]
pub logging: LoggingConfig,
#[serde(default, skip_serializing_if = "Option::is_none")]
pub closed_loop: Option<ClosedLoopConfig>,
#[serde(default, skip_serializing_if = "Option::is_none")]
pub particle_filter: Option<ParticleFilterConfig>,
#[serde(default, skip_serializing_if = "Option::is_none")]
pub geophysical: Option<GeophysicalConfig>,
#[serde(default)]
pub gnss_degradation: crate::messages::GnssDegradationConfig,
#[serde(default, skip_serializing_if = "Option::is_none")]
pub synthetic: Option<SyntheticConfig>,
}
fn default_input() -> String {
"input.csv".to_string()
}
fn default_output() -> String {
"output.csv".to_string()
}
fn default_seed() -> u64 {
42
}
impl Default for SimulationConfig {
fn default() -> Self {
Self {
input: "input.csv".to_string(),
output: "output.csv".to_string(),
mode: SimulationMode::ClosedLoop,
seed: default_seed(),
parallel: false,
generate_plot: false,
execution_limits: ExecutionLimits::default(),
logging: LoggingConfig::default(),
closed_loop: Some(ClosedLoopConfig::default()),
particle_filter: None,
geophysical: None,
gnss_degradation: crate::messages::GnssDegradationConfig::default(),
synthetic: None,
}
}
}
impl SimulationConfig {
pub fn to_json<P: AsRef<Path>>(&self, path: P) -> io::Result<()> {
let file = std::fs::File::create(path)?;
serde_json::to_writer_pretty(file, self).map_err(io::Error::other)
}
pub fn from_json<P: AsRef<Path>>(path: P) -> io::Result<Self> {
let file = std::fs::File::open(path)?;
serde_json::from_reader(file).map_err(io::Error::other)
}
pub fn to_yaml<P: AsRef<Path>>(&self, path: P) -> io::Result<()> {
let mut file = std::fs::File::create(path)?;
let s = serde_yaml::to_string(self).map_err(io::Error::other)?;
file.write_all(s.as_bytes())
}
pub fn from_yaml<P: AsRef<Path>>(path: P) -> io::Result<Self> {
let file = std::fs::File::open(path)?;
serde_yaml::from_reader(file).map_err(io::Error::other)
}
pub fn to_toml<P: AsRef<Path>>(&self, path: P) -> io::Result<()> {
let mut file = std::fs::File::create(path)?;
let s = toml::to_string_pretty(self).map_err(io::Error::other)?;
file.write_all(s.as_bytes())
}
pub fn from_toml<P: AsRef<Path>>(path: P) -> io::Result<Self> {
let mut s = String::new();
let mut file = std::fs::File::open(path)?;
file.read_to_string(&mut s)?;
toml::from_str(&s).map_err(io::Error::other)
}
pub fn to_file<P: AsRef<Path>>(&self, path: P) -> io::Result<()> {
let p = path.as_ref();
let ext = p
.extension()
.and_then(|s| s.to_str())
.map(|s| s.to_lowercase());
match ext.as_deref() {
Some("json") => self.to_json(p),
Some("yaml") | Some("yml") => self.to_yaml(p),
Some("toml") => self.to_toml(p),
_ => Err(io::Error::new(
io::ErrorKind::InvalidInput,
"unsupported file extension (expected .json, .yaml, .yml, or .toml)",
)),
}
}
pub fn from_file<P: AsRef<Path>>(path: P) -> io::Result<Self> {
let p = path.as_ref();
let ext = p
.extension()
.and_then(|s| s.to_str())
.map(|s| s.to_lowercase());
match ext.as_deref() {
Some("json") => Self::from_json(p),
Some("yaml") | Some("yml") => Self::from_yaml(p),
Some("toml") => Self::from_toml(p),
_ => Err(io::Error::new(
io::ErrorKind::InvalidInput,
"unsupported file extension (expected .json, .yaml, .yml, or .toml)",
)),
}
}
}
#[derive(Clone, Copy, Debug, Serialize, Deserialize)]
#[cfg_attr(feature = "clap", derive(ValueEnum))]
#[serde(rename_all = "lowercase")]
#[derive(Default)]
pub enum GeoMeasurementType {
#[default]
Gravity,
Magnetic,
}
#[derive(Clone, Copy, Debug, Serialize, Deserialize)]
#[cfg_attr(feature = "clap", derive(ValueEnum))]
#[serde(rename_all = "snake_case")]
#[derive(Default)]
pub enum GeoResolution {
OneDegree,
ThirtyMinutes,
TwentyMinutes,
FifteenMinutes,
TenMinutes,
SixMinutes,
FiveMinutes,
FourMinutes,
ThreeMinutes,
TwoMinutes,
#[default]
OneMinute,
ThirtySeconds,
FifteenSeconds,
ThreeSeconds,
OneSecond,
}
#[derive(Clone, Debug, Default, Serialize, Deserialize)]
pub struct GeophysicalConfig {
#[serde(default, skip_serializing_if = "Option::is_none")]
pub gravity_resolution: Option<GeoResolution>,
#[serde(default, skip_serializing_if = "Option::is_none")]
pub gravity_bias: Option<f64>,
#[serde(default, skip_serializing_if = "Option::is_none")]
pub gravity_noise_std: Option<f64>,
#[serde(default, skip_serializing_if = "Option::is_none")]
pub gravity_map_file: Option<String>,
#[serde(default, skip_serializing_if = "Option::is_none")]
pub magnetic_resolution: Option<GeoResolution>,
#[serde(default, skip_serializing_if = "Option::is_none")]
pub magnetic_bias: Option<f64>,
#[serde(default, skip_serializing_if = "Option::is_none")]
pub magnetic_noise_std: Option<f64>,
#[serde(default, skip_serializing_if = "Option::is_none")]
pub magnetic_map_file: Option<String>,
#[serde(default, skip_serializing_if = "Option::is_none")]
pub geo_frequency_s: Option<f64>,
}
fn default_gravity_noise_std() -> f64 {
100.0
}
fn default_magnetic_noise_std() -> f64 {
150.0
}
impl GeophysicalConfig {
pub fn get_gravity_noise_std(&self) -> f64 {
self.gravity_noise_std
.unwrap_or_else(default_gravity_noise_std)
}
pub fn get_magnetic_noise_std(&self) -> f64 {
self.magnetic_noise_std
.unwrap_or_else(default_magnetic_noise_std)
}
pub fn get_gravity_bias(&self) -> f64 {
self.gravity_bias.unwrap_or(0.0)
}
pub fn get_magnetic_bias(&self) -> f64 {
self.magnetic_bias.unwrap_or(0.0)
}
}
#[derive(Clone, Debug, Serialize, Deserialize)]
pub struct GeonavSimulationConfig {
pub input: String,
pub output: String,
#[serde(default)]
pub filter: FilterType,
#[serde(default = "default_seed")]
pub seed: u64,
#[serde(default)]
pub parallel: bool,
#[serde(default)]
pub generate_plot: bool,
#[serde(default)]
pub logging: LoggingConfig,
#[serde(default)]
pub geophysical: GeophysicalConfig,
#[serde(default)]
pub gnss_degradation: crate::messages::GnssDegradationConfig,
}
impl Default for GeonavSimulationConfig {
fn default() -> Self {
Self {
input: "input.csv".to_string(),
output: "output.csv".to_string(),
filter: FilterType::Ukf,
seed: default_seed(),
parallel: false,
generate_plot: false,
logging: LoggingConfig::default(),
geophysical: GeophysicalConfig::default(),
gnss_degradation: crate::messages::GnssDegradationConfig::default(),
}
}
}
impl GeonavSimulationConfig {
pub fn to_json<P: AsRef<Path>>(&self, path: P) -> io::Result<()> {
let file = std::fs::File::create(path)?;
serde_json::to_writer_pretty(file, self).map_err(io::Error::other)
}
pub fn from_json<P: AsRef<Path>>(path: P) -> io::Result<Self> {
let file = std::fs::File::open(path)?;
serde_json::from_reader(file).map_err(io::Error::other)
}
pub fn to_yaml<P: AsRef<Path>>(&self, path: P) -> io::Result<()> {
let mut file = std::fs::File::create(path)?;
let s = serde_yaml::to_string(self).map_err(io::Error::other)?;
file.write_all(s.as_bytes())
}
pub fn from_yaml<P: AsRef<Path>>(path: P) -> io::Result<Self> {
let file = std::fs::File::open(path)?;
serde_yaml::from_reader(file).map_err(io::Error::other)
}
pub fn to_toml<P: AsRef<Path>>(&self, path: P) -> io::Result<()> {
let mut file = std::fs::File::create(path)?;
let s = toml::to_string_pretty(self).map_err(io::Error::other)?;
file.write_all(s.as_bytes())
}
pub fn from_toml<P: AsRef<Path>>(path: P) -> io::Result<Self> {
let mut s = String::new();
let mut file = std::fs::File::open(path)?;
file.read_to_string(&mut s)?;
toml::from_str(&s).map_err(io::Error::other)
}
pub fn to_file<P: AsRef<Path>>(&self, path: P) -> io::Result<()> {
let p = path.as_ref();
let ext = p
.extension()
.and_then(|s| s.to_str())
.map(|s| s.to_lowercase());
match ext.as_deref() {
Some("json") => self.to_json(p),
Some("yaml") | Some("yml") => self.to_yaml(p),
Some("toml") => self.to_toml(p),
_ => Err(io::Error::new(
io::ErrorKind::InvalidInput,
"unsupported file extension (expected .json, .yaml, .yml, or .toml)",
)),
}
}
pub fn from_file<P: AsRef<Path>>(path: P) -> io::Result<Self> {
let p = path.as_ref();
let ext = p
.extension()
.and_then(|s| s.to_str())
.map(|s| s.to_lowercase());
match ext.as_deref() {
Some("json") => Self::from_json(p),
Some("yaml") | Some("yml") => Self::from_yaml(p),
Some("toml") => Self::from_toml(p),
_ => Err(io::Error::new(
io::ErrorKind::InvalidInput,
"unsupported file extension (expected .json, .yaml, .yml, or .toml)",
)),
}
}
}
#[derive(Clone, Debug, Serialize, Deserialize)]
pub struct SyntheticInitialState {
pub latitude_deg: f64,
pub longitude_deg: f64,
pub altitude_m: f64,
#[serde(default)]
pub velocity_north_mps: f64,
#[serde(default)]
pub velocity_east_mps: f64,
#[serde(default)]
pub velocity_down_mps: f64,
#[serde(default)]
pub roll_deg: f64,
#[serde(default)]
pub pitch_deg: f64,
#[serde(default)]
pub yaw_deg: f64,
#[serde(default)]
pub angular_velocity_x_dps: f64,
#[serde(default)]
pub angular_velocity_y_dps: f64,
#[serde(default)]
pub angular_velocity_z_dps: f64,
#[serde(default)]
pub is_enu: bool,
}
impl Default for SyntheticInitialState {
fn default() -> Self {
Self {
latitude_deg: 0.0,
longitude_deg: 0.0,
altitude_m: 0.0,
velocity_north_mps: 0.0,
velocity_east_mps: 0.0,
velocity_down_mps: 0.0,
roll_deg: 0.0,
pitch_deg: 0.0,
yaw_deg: 0.0,
angular_velocity_x_dps: 0.0,
angular_velocity_y_dps: 0.0,
angular_velocity_z_dps: 0.0,
is_enu: false,
}
}
}
fn default_sample_rate_hz() -> f64 {
10.0
}
fn default_gnss_horizontal_noise_m() -> f64 {
2.5
}
fn default_gnss_vertical_noise_m() -> f64 {
5.0
}
fn default_baro_noise_std_pa() -> f64 {
50.0
}
#[derive(Clone, Debug, Serialize, Deserialize)]
pub struct SyntheticConfig {
pub output: String,
#[serde(default)]
pub initial_state: SyntheticInitialState,
pub duration_s: f64,
#[serde(default = "default_sample_rate_hz")]
pub sample_rate_hz: f64,
#[serde(default)]
pub imu_quality: crate::IMUQuality,
#[serde(default = "default_seed")]
pub seed: u64,
#[serde(default)]
pub no_noise: bool,
#[serde(default = "default_gnss_horizontal_noise_m")]
pub gnss_horizontal_noise_m: f64,
#[serde(default = "default_gnss_vertical_noise_m")]
pub gnss_vertical_noise_m: f64,
#[serde(default = "default_baro_noise_std_pa")]
pub baro_noise_std_pa: f64,
}
impl SyntheticConfig {
pub fn to_file<P: AsRef<Path>>(&self, path: P) -> io::Result<()> {
let p = path.as_ref();
let ext = p
.extension()
.and_then(|s| s.to_str())
.map(|s| s.to_lowercase());
match ext.as_deref() {
Some("json") => {
let json = serde_json::to_string_pretty(self)
.map_err(|e| io::Error::new(io::ErrorKind::InvalidData, e))?;
std::fs::write(p, json)
}
Some("yaml") | Some("yml") => {
let yaml = serde_yaml::to_string(self)
.map_err(|e| io::Error::new(io::ErrorKind::InvalidData, e))?;
std::fs::write(p, yaml)
}
Some("toml") => {
let toml = toml::to_string_pretty(self)
.map_err(|e| io::Error::new(io::ErrorKind::InvalidData, e))?;
std::fs::write(p, toml)
}
_ => Err(io::Error::new(
io::ErrorKind::InvalidInput,
"unsupported file extension (expected .json, .yaml, .yml, or .toml)",
)),
}
}
pub fn from_file<P: AsRef<Path>>(path: P) -> io::Result<Self> {
let p = path.as_ref();
let ext = p
.extension()
.and_then(|s| s.to_str())
.map(|s| s.to_lowercase());
let contents = std::fs::read_to_string(p)?;
match ext.as_deref() {
Some("json") => serde_json::from_str(&contents)
.map_err(|e| io::Error::new(io::ErrorKind::InvalidData, e)),
Some("yaml") | Some("yml") => serde_yaml::from_str(&contents)
.map_err(|e| io::Error::new(io::ErrorKind::InvalidData, e)),
Some("toml") => {
toml::from_str(&contents).map_err(|e| io::Error::new(io::ErrorKind::InvalidData, e))
}
_ => Err(io::Error::new(
io::ErrorKind::InvalidInput,
"unsupported file extension (expected .json, .yaml, .yml, or .toml)",
)),
}
}
}
fn compute_perfect_imu(
state: &crate::StrapdownState,
angular_velocity_body_rps: Vector3<f64>,
) -> crate::IMUData {
use crate::earth;
let lat_deg = state.latitude.to_degrees();
let velocity = Vector3::new(
state.velocity_north,
state.velocity_east,
state.velocity_vertical,
);
let omega_ie_nav = earth::earth_rate_lla(&lat_deg);
let omega_en_nav = earth::transport_rate(&lat_deg, &state.altitude, &velocity);
let c_nb = state.attitude.matrix();
let earth_body = c_nb.transpose() * (omega_ie_nav + omega_en_nav);
let gyro = angular_velocity_body_rps + earth_body;
let omega_en_skew = earth::vector_to_skew_symmetric(&omega_en_nav);
let omega_ie_skew = earth::vector_to_skew_symmetric(&omega_ie_nav);
let coriolis = (omega_en_skew + 2.0 * omega_ie_skew) * velocity;
let g = earth::gravity(&lat_deg, &state.altitude);
let g_nav = if state.is_enu {
Vector3::new(0.0, 0.0, -g)
} else {
Vector3::new(0.0, 0.0, g)
};
let f_nav = coriolis - g_nav;
let accel = c_nb.transpose() * f_nav;
crate::IMUData { accel, gyro }
}
pub fn generate_synthetic(
config: &SyntheticConfig,
rng: &mut rand::rngs::StdRng,
) -> (Vec<NavigationResult>, Vec<TestDataRecord>) {
use crate::earth;
use rand::Rng;
use rand_distr::Normal;
let s = &config.initial_state;
let attitude = nalgebra::Rotation3::from_euler_angles(
s.roll_deg.to_radians(),
s.pitch_deg.to_radians(),
s.yaw_deg.to_radians(),
);
let mut state = crate::StrapdownState {
latitude: s.latitude_deg.to_radians(),
longitude: s.longitude_deg.to_radians(),
altitude: s.altitude_m,
velocity_north: s.velocity_north_mps,
velocity_east: s.velocity_east_mps,
velocity_vertical: s.velocity_down_mps,
attitude,
is_enu: s.is_enu,
};
let angular_velocity_body_rps = Vector3::new(
s.angular_velocity_x_dps.to_radians(),
s.angular_velocity_y_dps.to_radians(),
s.angular_velocity_z_dps.to_radians(),
);
let dt = 1.0 / config.sample_rate_hz;
let n_steps = (config.duration_s * config.sample_rate_hz).round() as usize;
let initial_alt = state.altitude;
let accel_bias = {
let sigma = config.imu_quality.accel_bias_instability_mps2();
let dist = Normal::new(0.0_f64, sigma).unwrap_or(Normal::new(0.0, 1e-6).unwrap());
Vector3::new(rng.sample(dist), rng.sample(dist), rng.sample(dist))
};
let gyro_bias = {
let sigma = config.imu_quality.gyro_bias_instability_dph();
let dist = Normal::new(0.0_f64, sigma).unwrap_or(Normal::new(0.0, 1e-9).unwrap());
Vector3::new(rng.sample(dist), rng.sample(dist), rng.sample(dist))
};
let accel_noise_sigma = config.imu_quality.accel_velocity_random_walk()
* (config.sample_rate_hz / 3600.0_f64).sqrt();
let gyro_noise_sigma =
config.imu_quality.gyro_angle_random_walk() * (config.sample_rate_hz / 3600.0_f64).sqrt();
let accel_noise_dist =
Normal::new(0.0_f64, accel_noise_sigma).unwrap_or(Normal::new(0.0, 1e-6).unwrap());
let gyro_noise_dist =
Normal::new(0.0_f64, gyro_noise_sigma).unwrap_or(Normal::new(0.0, 1e-9).unwrap());
let gnss_h_dist = Normal::new(0.0_f64, config.gnss_horizontal_noise_m)
.unwrap_or(Normal::new(0.0, 1.0).unwrap());
let gnss_v_dist = Normal::new(0.0_f64, config.gnss_vertical_noise_m)
.unwrap_or(Normal::new(0.0, 1.0).unwrap());
let baro_dist =
Normal::new(0.0_f64, config.baro_noise_std_pa).unwrap_or(Normal::new(0.0, 1.0).unwrap());
let start_time: chrono::DateTime<Utc> = "2025-01-01T00:00:00Z"
.parse()
.unwrap_or_else(|_| Utc::now());
let mut truth_records: Vec<NavigationResult> = Vec::with_capacity(n_steps);
let mut sensor_records: Vec<TestDataRecord> = Vec::with_capacity(n_steps);
for i in 0..n_steps {
let timestamp = start_time + Duration::milliseconds((i as f64 * dt * 1000.0) as i64);
let perfect_imu = compute_perfect_imu(&state, angular_velocity_body_rps);
let (roll, pitch, yaw) = state.attitude.euler_angles();
let truth = NavigationResult {
timestamp,
latitude: state.latitude.to_degrees(),
longitude: state.longitude.to_degrees(),
altitude: state.altitude,
velocity_north: state.velocity_north,
velocity_east: state.velocity_east,
velocity_vertical: state.velocity_vertical,
roll,
pitch,
yaw,
acc_bias_x: 0.0,
acc_bias_y: 0.0,
acc_bias_z: 0.0,
gyro_bias_x: 0.0,
gyro_bias_y: 0.0,
gyro_bias_z: 0.0,
latitude_cov: 0.0,
longitude_cov: 0.0,
altitude_cov: 0.0,
velocity_n_cov: 0.0,
velocity_e_cov: 0.0,
velocity_v_cov: 0.0,
roll_cov: 0.0,
pitch_cov: 0.0,
yaw_cov: 0.0,
acc_bias_x_cov: 0.0,
acc_bias_y_cov: 0.0,
acc_bias_z_cov: 0.0,
gyro_bias_x_cov: 0.0,
gyro_bias_y_cov: 0.0,
gyro_bias_z_cov: 0.0,
};
truth_records.push(truth);
let (out_acc, out_gyro, out_lat, out_lon, out_alt) = if config.no_noise {
(
perfect_imu.accel,
perfect_imu.gyro,
state.latitude.to_degrees(),
state.longitude.to_degrees(),
state.altitude,
)
} else {
let noisy_accel = perfect_imu.accel
+ accel_bias
+ Vector3::new(
rng.sample(accel_noise_dist),
rng.sample(accel_noise_dist),
rng.sample(accel_noise_dist),
);
let noisy_gyro = perfect_imu.gyro
+ gyro_bias
+ Vector3::new(
rng.sample(gyro_noise_dist),
rng.sample(gyro_noise_dist),
rng.sample(gyro_noise_dist),
);
let r_e = earth::EQUATORIAL_RADIUS;
let lat_noise_rad = rng.sample(gnss_h_dist) / r_e;
let lon_noise_rad =
rng.sample(gnss_h_dist) / ((r_e + state.altitude) * state.latitude.cos().max(1e-6));
(
noisy_accel,
noisy_gyro,
(state.latitude + lat_noise_rad).to_degrees(),
(state.longitude + lon_noise_rad).to_degrees(),
state.altitude + rng.sample(gnss_v_dist),
)
};
let true_pressure =
earth::expected_barometric_pressure(state.altitude, earth::SEA_LEVEL_PRESSURE);
let out_pressure = if config.no_noise {
true_pressure
} else {
true_pressure + rng.sample(baro_dist)
};
let speed = (state.velocity_north.powi(2) + state.velocity_east.powi(2)).sqrt();
let bearing = state.velocity_east.atan2(state.velocity_north).to_degrees();
let g = earth::gravity(&state.latitude.to_degrees(), &state.altitude);
let g_nav = if state.is_enu {
Vector3::new(0.0, 0.0, -g)
} else {
Vector3::new(0.0, 0.0, g)
};
let grav_body = state.attitude.matrix().transpose() * g_nav;
sensor_records.push(TestDataRecord {
time: timestamp,
latitude: out_lat,
longitude: out_lon,
altitude: out_alt,
speed,
bearing,
bearing_accuracy: config.gnss_horizontal_noise_m,
speed_accuracy: config.gnss_horizontal_noise_m,
vertical_accuracy: config.gnss_vertical_noise_m,
horizontal_accuracy: config.gnss_horizontal_noise_m,
roll: roll.to_degrees(),
pitch: pitch.to_degrees(),
yaw: yaw.to_degrees(),
qw: state.attitude.euler_angles().2.cos(),
qx: 0.0,
qy: 0.0,
qz: 0.0,
acc_x: out_acc[0],
acc_y: out_acc[1],
acc_z: out_acc[2],
gyro_x: out_gyro[0],
gyro_y: out_gyro[1],
gyro_z: out_gyro[2],
mag_x: 0.0,
mag_y: 0.0,
mag_z: 0.0,
relative_altitude: out_alt - initial_alt,
pressure: out_pressure,
grav_x: grav_body[0],
grav_y: grav_body[1],
grav_z: grav_body[2],
});
crate::forward(&mut state, perfect_imu, dt);
}
(truth_records, sensor_records)
}
#[cfg(test)]
mod tests {
use super::*;
use chrono::Utc;
use std::fs::File;
use std::path::Path;
use std::vec;
fn generate_northward_motion_records() -> Vec<TestDataRecord> {
let mut records: Vec<TestDataRecord> = Vec::with_capacity(3601);
let start_lat: f64 = 0.0;
let start_lon: f64 = 0.0;
let start_alt: f64 = 0.0;
let velocity_mps: f64 = 1852.0 / 3600.0; let earth_radius: f64 = 6371000.0_f64;
for t in 0..3600 {
let dlat: f64 =
(velocity_mps * t as f64) / earth_radius * (180.0 / std::f64::consts::PI);
let time_str: String = format!("2023-01-01 00:{:02}:{:02}+00:00", t / 60, t % 60);
records.push(TestDataRecord {
time: DateTime::parse_from_str(&time_str, "%Y-%m-%d %H:%M:%S%z")
.map(|dt| dt.with_timezone(&Utc))
.unwrap(),
bearing_accuracy: 0.0,
speed_accuracy: 0.0,
vertical_accuracy: 0.0,
horizontal_accuracy: 0.0,
speed: velocity_mps,
bearing: 0.0,
altitude: start_alt,
longitude: start_lon,
latitude: start_lat + dlat,
qz: 0.0,
qy: 0.0,
qx: 0.0,
qw: 1.0,
roll: 0.0,
pitch: 0.0,
yaw: 0.0,
acc_z: 0.0,
acc_y: 0.0,
acc_x: 0.0,
gyro_z: 0.0,
gyro_y: 0.0,
gyro_x: 0.0,
mag_z: 0.0,
mag_y: 0.0,
mag_x: 0.0,
relative_altitude: 0.0,
pressure: 1000.0,
grav_z: 9.81,
grav_y: 0.0,
grav_x: 0.0,
});
}
records
}
#[test]
fn test_generate_northward_motion_records_end_latitude() {
let records = generate_northward_motion_records();
let last = records.last().unwrap();
let expected_lat = 0.016667;
let tolerance = 1e-3;
assert!(
(last.latitude - expected_lat).abs() < tolerance,
"Ending latitude {} not within {} of expected {}",
last.latitude,
tolerance,
expected_lat
);
let northward = File::create("northward_motion.csv").unwrap();
let mut writer = csv::Writer::from_writer(northward);
for record in &records {
writer.serialize(record).unwrap();
}
writer.flush().unwrap();
let _ = std::fs::remove_file("northward_motion.csv");
}
#[test]
fn test_test_data_record_from_csv_invalid_path() {
let path = Path::new("nonexistent.csv");
let result = TestDataRecord::from_csv(path);
assert!(result.is_err(), "Should error on missing file");
}
#[test]
fn test_data_record_to_and_from_csv() {
let path = Path::new("test_file.csv");
let records: Vec<TestDataRecord> = vec![
TestDataRecord {
time: DateTime::parse_from_str("2023-01-01 00:00:00+00:00", "%Y-%m-%d %H:%M:%S%z")
.unwrap()
.with_timezone(&Utc),
bearing_accuracy: 0.1,
speed_accuracy: 0.1,
vertical_accuracy: 0.1,
horizontal_accuracy: 0.1,
speed: 1.0,
bearing: 90.0,
altitude: 100.0,
longitude: -122.0,
latitude: 37.0,
qz: 0.0,
qy: 0.0,
qx: 0.0,
qw: 1.0,
roll: 0.0,
pitch: 0.0,
yaw: 0.0,
acc_z: 9.81,
acc_y: 0.0,
acc_x: 0.0,
gyro_z: 0.01,
gyro_y: 0.01,
gyro_x: 0.01,
mag_z: 50.0,
mag_y: -30.0,
mag_x: -20.0,
relative_altitude: 5.0,
pressure: 1013.25,
grav_z: 9.81,
grav_y: 0.0,
grav_x: 0.0,
},
TestDataRecord {
time: DateTime::parse_from_str("2023-01-01 00:01:00+00:00", "%Y-%m-%d %H:%M:%S%z")
.unwrap()
.with_timezone(&Utc),
bearing_accuracy: 0.1,
speed_accuracy: 0.1,
vertical_accuracy: 0.1,
horizontal_accuracy: 0.1,
speed: 2.0,
bearing: 180.0,
altitude: 200.0,
longitude: -121.0,
latitude: 38.0,
qz: 0.0,
qy: 0.0,
qx: 0.0,
qw: 1.0,
roll: 0.1,
pitch: 0.1,
yaw: 0.1,
acc_z: 9.81,
acc_y: 0.01,
acc_x: -0.01,
gyro_z: 0.02,
gyro_y: -0.02,
gyro_x: 0.02,
mag_z: 55.0,
mag_y: -25.0,
mag_x: -15.0,
relative_altitude: 10.0,
pressure: 1012.25,
grav_z: 9.81,
grav_y: 0.01,
grav_x: -0.01,
},
];
TestDataRecord::to_csv(&records, path).expect("Failed to write test data to CSV");
assert!(path.exists(), "Test data CSV file should exist");
let read_records =
TestDataRecord::from_csv(path).expect("Failed to read test data from CSV");
assert_eq!(
read_records.len(),
records.len(),
"Record count should match"
);
for (i, record) in read_records.iter().enumerate() {
assert_eq!(record.time, records[i].time, "Timestamps should match");
assert!(
(record.latitude - records[i].latitude).abs() < 1e-6,
"Latitudes should match"
);
assert!(
(record.longitude - records[i].longitude).abs() < 1e-6,
"Longitudes should match"
);
assert!(
(record.altitude - records[i].altitude).abs() < 1e-6,
"Altitudes should match"
);
}
let _ = std::fs::remove_file(path);
}
#[test]
fn test_navigation_result_new() {
let nav = NavigationResult::default();
assert_eq!(nav.latitude, 0.0);
assert_eq!(nav.longitude, 0.0);
assert_eq!(nav.altitude, 0.0);
assert_eq!(nav.velocity_north, 0.0);
assert_eq!(nav.velocity_east, 0.0);
assert_eq!(nav.velocity_vertical, 0.0);
}
#[test]
fn test_navigation_result_from_strapdown_state() {
let state = StrapdownState {
latitude: 1.0,
longitude: 2.0,
altitude: 3.0,
velocity_north: 4.0,
velocity_east: 5.0,
velocity_vertical: 6.0,
attitude: nalgebra::Rotation3::from_euler_angles(7.0, 8.0, 9.0),
..Default::default()
};
let state_vector: DVector<f64> = DVector::from_vec(vec![
state.latitude,
state.longitude,
state.altitude,
state.velocity_north,
state.velocity_east,
state.velocity_vertical,
state.attitude.euler_angles().0, state.attitude.euler_angles().1, state.attitude.euler_angles().2, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, ]);
let timestamp = chrono::Utc::now();
let nav = NavigationResult::from((
×tamp,
&state_vector,
&DMatrix::from_diagonal(&DVector::from_element(15, 0.0)), ));
assert_eq!(nav.latitude, (1.0_f64).to_degrees());
assert_eq!(nav.longitude, (2.0_f64).to_degrees());
assert_eq!(nav.altitude, 3.0);
assert_eq!(nav.velocity_north, 4.0);
assert_eq!(nav.velocity_east, 5.0);
assert_eq!(nav.velocity_vertical, 6.0);
}
#[test]
fn test_navigation_result_to_csv_and_from_csv() {
let mut nav = NavigationResult::new();
nav.latitude = 1.0;
nav.longitude = 2.0;
nav.altitude = 3.0;
nav.velocity_north = 4.0;
nav.velocity_east = 5.0;
nav.velocity_vertical = 6.0;
let temp_file = std::env::temp_dir().join("test_nav_result.csv");
NavigationResult::to_csv(&[nav.clone()], &temp_file).unwrap();
let read = NavigationResult::from_csv(&temp_file).unwrap();
assert_eq!(read.len(), 1);
assert_eq!(read[0].latitude, 1.0);
assert_eq!(read[0].longitude, 2.0);
assert_eq!(read[0].altitude, 3.0);
assert_eq!(read[0].velocity_north, 4.0);
assert_eq!(read[0].velocity_east, 5.0);
assert_eq!(read[0].velocity_vertical, 6.0);
let _ = std::fs::remove_file(&temp_file);
}
#[test]
fn test_closed_loop_minimal() {
let rec = TestDataRecord::from_csv("./data/test_data.csv")
.ok()
.and_then(|v| v.into_iter().next())
.unwrap_or_else(|| TestDataRecord {
time: chrono::Utc::now(),
bearing_accuracy: 0.0,
speed_accuracy: 0.0,
vertical_accuracy: 0.0,
horizontal_accuracy: 0.0,
speed: 0.0,
bearing: 0.0,
altitude: 0.0,
longitude: 0.0,
latitude: 0.0,
qz: 0.0,
qy: 0.0,
qx: 0.0,
qw: 1.0,
roll: 0.0,
pitch: 0.0,
yaw: 0.0,
acc_z: 0.0,
acc_y: 0.0,
acc_x: 0.0,
gyro_z: 0.0,
gyro_y: 0.0,
gyro_x: 0.0,
mag_z: 0.0,
mag_y: 0.0,
mag_x: 0.0,
relative_altitude: 0.0,
pressure: 0.0,
grav_z: 0.0,
grav_y: 0.0,
grav_x: 0.0,
});
let mut ukf = initialize_ukf(rec.clone(), UkfConfig::default());
let imu_data = IMUData {
accel: nalgebra::Vector3::new(rec.acc_x, rec.acc_y, rec.acc_z),
gyro: nalgebra::Vector3::new(rec.gyro_x, rec.gyro_y, rec.gyro_z),
};
let event = Event::Imu {
dt_s: 1.0,
imu: imu_data,
elapsed_s: 0.0,
};
let stream = EventStream {
start_time: rec.time,
events: vec![event],
};
let res = run_closed_loop(&mut ukf, stream, None, None);
assert!(!res.unwrap().is_empty());
}
#[test]
fn test_initialize_ukf_default_and_custom() {
let rec = TestDataRecord {
time: chrono::Utc::now(),
bearing_accuracy: 0.0,
speed_accuracy: 0.0,
vertical_accuracy: 1.0,
horizontal_accuracy: 4.0,
speed: 1.0,
bearing: 0.0,
altitude: 10.0,
longitude: 20.0,
latitude: 30.0,
qz: 0.0,
qy: 0.0,
qx: 0.0,
qw: 1.0,
roll: 0.0,
pitch: 0.0,
yaw: 0.0,
acc_z: 0.0,
acc_y: 0.0,
acc_x: 0.0,
gyro_z: 0.0,
gyro_y: 0.0,
gyro_x: 0.0,
mag_z: 0.0,
mag_y: 0.0,
mag_x: 0.0,
relative_altitude: 0.0,
pressure: 0.0,
grav_z: 0.0,
grav_y: 0.0,
grav_x: 0.0,
};
let ukf = initialize_ukf(rec.clone(), UkfConfig::default());
assert!(!ukf.get_estimate().is_empty());
let ukf2 = initialize_ukf(
rec,
UkfConfig {
attitude_covariance: Some(vec![0.1, 0.2, 0.3]),
imu_biases: Some(vec![0.4, 0.5, 0.6, 0.7, 0.8, 0.9]),
..Default::default()
},
);
assert!(!ukf2.get_estimate().is_empty());
}
fn test_header() -> Vec<&'static str> {
vec![
"time",
"bearingAccuracy",
"speedAccuracy",
"verticalAccuracy",
"horizontalAccuracy",
"speed",
"bearing",
"altitude",
"longitude",
"latitude",
"qz",
"qy",
"qx",
"qw",
"roll",
"pitch",
"yaw",
"acc_z",
"acc_y",
"acc_x",
"gyro_z",
"gyro_y",
"gyro_x",
"mag_z",
"mag_y",
"mag_x",
"relativeAltitude",
"pressure",
"grav_z",
"grav_y",
"grav_x",
]
}
#[test]
fn deserialize_with_empty_fields_maps_to_nan() {
let headers = test_header();
let time = "2023-08-04T21:47:58Z";
let mut row: Vec<String> = Vec::with_capacity(headers.len());
row.push(time.to_string());
for _ in 1..headers.len() {
row.push(String::new());
}
let mut csv_data = String::new();
csv_data.push_str(&headers.join(","));
csv_data.push('\n');
csv_data.push_str(&row.join(","));
let temp_file = std::env::temp_dir().join("test_empty_fields_nan.csv");
std::fs::write(&temp_file, csv_data).unwrap();
let recs = TestDataRecord::from_csv(&temp_file).expect("from_csv should succeed");
assert_eq!(recs.len(), 1);
let r = &recs[0];
assert_eq!(
r.time,
chrono::DateTime::parse_from_rfc3339(time)
.unwrap()
.with_timezone(&Utc)
);
assert!(r.speed.is_nan());
assert!(r.latitude.is_nan());
assert!(r.longitude.is_nan());
assert!(r.acc_x.is_nan());
let _ = std::fs::remove_file(&temp_file);
}
#[test]
fn deserialize_with_missing_trailing_columns_returns_error() {
let headers = test_header();
let time = "2023-08-04T21:47:58Z";
let row: Vec<String> = vec![
time.to_string(),
String::from("1.0"),
String::from("2.0"),
];
let mut csv_data = String::new();
csv_data.push_str(&headers.join(","));
csv_data.push('\n');
csv_data.push_str(&row.join(","));
let temp_file = std::env::temp_dir().join("test_missing_trailing.csv");
std::fs::write(&temp_file, csv_data).unwrap();
let recs = TestDataRecord::from_csv(&temp_file).expect("from_csv should succeed");
assert_eq!(recs.len(), 1);
let rec = &recs[0];
assert_eq!(
rec.time,
chrono::DateTime::parse_from_rfc3339(time)
.unwrap()
.with_timezone(&Utc)
);
assert!(rec.speed.is_nan());
assert!(rec.latitude.is_nan());
assert!(rec.longitude.is_nan());
let _ = std::fs::remove_file(&temp_file);
}
#[test]
fn manual_padding_then_deserialize_succeeds() {
let headers = test_header();
let time = "2023-08-04T21:47:58Z";
let row: Vec<String> = vec![
time.to_string(),
String::new(), String::new(), String::new(), String::new(), String::new(), String::new(), String::new(), String::from("-122.0"), String::from("37.0"), ];
let mut csv_data = String::new();
csv_data.push_str(&headers.join(","));
csv_data.push('\n');
csv_data.push_str(&row.join(","));
let temp_file = std::env::temp_dir().join("test_manual_padding.csv");
std::fs::write(&temp_file, csv_data).unwrap();
let got = TestDataRecord::from_csv(&temp_file).expect("from_csv should succeed");
assert_eq!(got.len(), 1);
let r = &got[0];
assert_eq!(
r.time,
chrono::DateTime::parse_from_rfc3339(time)
.unwrap()
.with_timezone(&Utc)
);
assert_eq!(r.longitude, -122.0);
assert_eq!(r.latitude, 37.0);
let _ = std::fs::remove_file(&temp_file);
}
#[test]
fn test_de_f64_nan_with_various_inputs() {
let headers = test_header();
let mut csv_data = String::new();
csv_data.push_str(&headers.join(","));
csv_data.push('\n');
csv_data.push_str("2023-08-04T21:47:58Z,NaN,null,,,1.5,90.0,100.0,-122.0,37.0,");
csv_data.push_str("0,0,0,1,0.1,0.2,0.3,9.8,0,0,0,0,0,0,0,0,0,1013.25,9.81,0,0\n");
let temp_file = std::env::temp_dir().join("test_nan_variants.csv");
std::fs::write(&temp_file, csv_data).unwrap();
let recs = TestDataRecord::from_csv(&temp_file).expect("Should parse");
assert_eq!(recs.len(), 1);
assert!(recs[0].bearing_accuracy.is_nan());
assert!(recs[0].speed_accuracy.is_nan());
assert!(recs[0].vertical_accuracy.is_nan());
assert!(recs[0].horizontal_accuracy.is_nan());
assert_eq!(recs[0].speed, 1.5);
let _ = std::fs::remove_file(&temp_file);
}
#[test]
fn test_test_data_record_display() {
let rec = TestDataRecord {
time: DateTime::parse_from_str("2023-01-01 00:00:00+00:00", "%Y-%m-%d %H:%M:%S%z")
.unwrap()
.with_timezone(&Utc),
latitude: 37.0,
longitude: -122.0,
altitude: 100.0,
speed: 5.0,
bearing: 90.0,
..Default::default()
};
let display_str = format!("{}", rec);
assert!(display_str.contains("37"));
assert!(display_str.contains("-122"));
assert!(display_str.contains("100"));
}
#[test]
fn test_navigation_result_from_ukf() {
let rec = TestDataRecord {
time: Utc::now(),
horizontal_accuracy: 5.0,
vertical_accuracy: 2.0,
speed_accuracy: 1.0,
latitude: 37.0,
longitude: -122.0,
altitude: 100.0,
speed: 10.0,
bearing: 45.0,
roll: 0.1,
pitch: 0.2,
yaw: 0.3,
..Default::default()
};
let ukf = initialize_ukf(rec.clone(), UkfConfig::default());
let timestamp = Utc::now();
let nav_result = NavigationResult::from((×tamp, &ukf));
assert_eq!(nav_result.timestamp, timestamp);
assert!(nav_result.latitude.is_finite());
assert!(nav_result.longitude.is_finite());
assert!(nav_result.altitude.is_finite());
}
#[test]
fn test_dead_reckoning_empty_records() {
let results = dead_reckoning(&[]);
assert!(results.is_empty());
}
#[test]
fn test_dead_reckoning_single_record() {
let rec = TestDataRecord {
time: Utc::now(),
latitude: 37.0,
longitude: -122.0,
altitude: 100.0,
speed: 1.0,
bearing: 0.0,
roll: 0.0,
pitch: 0.0,
yaw: 0.0,
acc_x: 0.0,
acc_y: 0.0,
acc_z: 9.81,
gyro_x: 0.0,
gyro_y: 0.0,
gyro_z: 0.0,
..Default::default()
};
let results = dead_reckoning(&[rec]);
assert_eq!(results.len(), 1);
}
#[test]
fn test_print_ukf() {
let rec = TestDataRecord {
time: Utc::now(),
horizontal_accuracy: 5.0,
vertical_accuracy: 2.0,
speed_accuracy: 1.0,
latitude: 37.0,
longitude: -122.0,
altitude: 100.0,
speed: 10.0,
bearing: 45.0,
roll: 0.1,
pitch: 0.2,
yaw: 0.3,
..Default::default()
};
let ukf = initialize_ukf(rec.clone(), UkfConfig::default());
print_ukf(&ukf, &rec);
}
#[test]
fn test_initialize_ukf_with_nan_angles() {
let rec = TestDataRecord {
time: Utc::now(),
horizontal_accuracy: 5.0,
vertical_accuracy: 2.0,
speed_accuracy: 1.0,
latitude: 37.0,
longitude: -122.0,
altitude: 100.0,
speed: 10.0,
bearing: 45.0,
roll: f64::NAN,
pitch: f64::NAN,
yaw: f64::NAN,
..Default::default()
};
let ukf = initialize_ukf(rec, UkfConfig::default());
let estimate = ukf.get_estimate();
assert!(estimate[6].abs() < 1e-6); assert!(estimate[7].abs() < 1e-6); assert!(estimate[8].abs() < 1e-6); }
#[test]
fn test_initialize_ukf_with_custom_biases() {
let rec = TestDataRecord {
time: Utc::now(),
horizontal_accuracy: 5.0,
vertical_accuracy: 2.0,
speed_accuracy: 1.0,
latitude: 37.0,
longitude: -122.0,
altitude: 100.0,
speed: 10.0,
bearing: 45.0,
roll: 0.0,
pitch: 0.0,
yaw: 0.0,
..Default::default()
};
let ukf = initialize_ukf(
rec,
UkfConfig {
attitude_covariance: Some(vec![1e-4, 2e-4, 3e-4]),
imu_biases: Some(vec![0.01, 0.02, 0.03, 0.001, 0.002, 0.003]),
imu_biases_covariance: Some(vec![1e-5; 6]),
..Default::default()
},
);
let estimate = ukf.get_estimate();
assert_eq!(estimate.len(), 15);
}
#[test]
fn test_initialize_ukf_with_custom_process_noise() {
let rec = TestDataRecord {
time: Utc::now(),
horizontal_accuracy: 5.0,
vertical_accuracy: 2.0,
speed_accuracy: 1.0,
latitude: 37.0,
longitude: -122.0,
altitude: 100.0,
speed: 10.0,
bearing: 45.0,
roll: 0.0,
pitch: 0.0,
yaw: 0.0,
..Default::default()
};
let custom_noise = vec![1e-5; 15];
let ukf = initialize_ukf(
rec,
UkfConfig {
process_noise_diagonal: Some(custom_noise),
..Default::default()
},
);
assert!(!ukf.get_estimate().is_empty());
}
#[test]
fn test_health_limits_default() {
let limits = HealthLimits::default();
assert!(limits.lat_rad.0 < 0.0);
assert!(limits.lat_rad.1 > 0.0);
assert!(limits.speed_mps_max > 0.0);
assert!(limits.cov_diag_max > 0.0);
}
#[test]
fn test_execution_monitor_no_progress_timeout() {
let limits = ExecutionLimits {
max_wall_clock_ratio: 0.0,
max_wall_clock_s: 0.0,
max_no_progress_s: 0.01,
};
let mut monitor = ExecutionMonitor::new(limits, 1.0);
std::thread::sleep(std::time::Duration::from_millis(20));
let result = monitor.check("test");
assert!(result.is_err());
}
#[test]
fn test_execution_monitor_wall_clock_timeout() {
let limits = ExecutionLimits {
max_wall_clock_ratio: 0.0,
max_wall_clock_s: 0.01,
max_no_progress_s: 0.0,
};
let mut monitor = ExecutionMonitor::new(limits, 1.0);
std::thread::sleep(std::time::Duration::from_millis(20));
let result = monitor.check("test");
assert!(result.is_err());
assert!(result.unwrap_err().to_string().contains("wall-clock limit"));
}
#[test]
fn test_execution_monitor_successful_execution_with_progress() {
let limits = ExecutionLimits {
max_wall_clock_ratio: 0.0,
max_wall_clock_s: 1.0,
max_no_progress_s: 0.05,
};
let mut monitor = ExecutionMonitor::new(limits, 1.0);
for _ in 0..5 {
std::thread::sleep(std::time::Duration::from_millis(10));
let result = monitor.check("test");
assert!(result.is_ok());
monitor.mark_progress();
}
}
#[test]
fn test_execution_monitor_zero_timeout_disabled() {
let limits = ExecutionLimits {
max_wall_clock_ratio: 0.0,
max_wall_clock_s: 0.0,
max_no_progress_s: 0.0,
};
let mut monitor = ExecutionMonitor::new(limits, 1.0);
std::thread::sleep(std::time::Duration::from_millis(50));
let result = monitor.check("test");
assert!(result.is_ok());
}
#[test]
fn test_execution_monitor_negative_timeout_disabled() {
let limits = ExecutionLimits {
max_wall_clock_ratio: -1.0,
max_wall_clock_s: -1.0,
max_no_progress_s: -1.0,
};
let mut monitor = ExecutionMonitor::new(limits, 1.0);
std::thread::sleep(std::time::Duration::from_millis(50));
let result = monitor.check("test");
assert!(result.is_ok());
}
#[test]
fn test_health_monitor_check_valid_state() {
let limits = HealthLimits::default();
let mut monitor = HealthMonitor::new(limits);
let state = vec![
0.5, 0.5, 100.0, 10.0, 5.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, ];
let cov = DMatrix::from_diagonal(&DVector::from_vec(vec![1e-6; 15]));
let result = monitor.check(&state, &cov, None);
assert!(result.is_ok());
}
#[test]
fn test_health_monitor_check_non_finite_state() {
let limits = HealthLimits::default();
let mut monitor = HealthMonitor::new(limits);
let state = vec![
f64::NAN,
0.5,
100.0,
10.0,
5.0,
0.0,
0.0,
0.0,
0.0,
0.0,
0.0,
0.0,
0.0,
0.0,
0.0,
];
let cov = DMatrix::from_diagonal(&DVector::from_vec(vec![1e-6; 15]));
let result = monitor.check(&state, &cov, None);
assert!(result.is_err());
}
#[test]
fn test_health_monitor_check_non_finite_covariance() {
let limits = HealthLimits::default();
let mut monitor = HealthMonitor::new(limits);
let state = vec![
0.5, 0.5, 100.0, 10.0, 5.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
];
let mut cov = DMatrix::from_diagonal(&DVector::from_vec(vec![1e-6; 15]));
cov[(0, 0)] = f64::NAN;
let result = monitor.check(&state, &cov, None);
assert!(result.is_err());
}
#[test]
fn test_health_monitor_check_latitude_out_of_range() {
let limits = HealthLimits::default();
let mut monitor = HealthMonitor::new(limits);
let state = vec![
5.0, 0.5, 100.0, 10.0, 5.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
]; let cov = DMatrix::from_diagonal(&DVector::from_vec(vec![1e-6; 15]));
let result = monitor.check(&state, &cov, None);
assert!(result.is_err());
}
#[test]
fn test_health_monitor_check_longitude_out_of_range() {
let limits = HealthLimits::default();
let mut monitor = HealthMonitor::new(limits);
let state = vec![
0.5, 5.0, 100.0, 10.0, 5.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
]; let cov = DMatrix::from_diagonal(&DVector::from_vec(vec![1e-6; 15]));
let result = monitor.check(&state, &cov, None);
assert!(result.is_err());
}
#[test]
fn test_health_monitor_check_altitude_out_of_range() {
let limits = HealthLimits { alt_m: (-100.0, 10000.0), ..Default::default() };
let mut monitor = HealthMonitor::new(limits);
let state = vec![
0.5, 0.5, 20000.0, 10.0, 5.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
];
let cov = DMatrix::from_diagonal(&DVector::from_vec(vec![1e-6; 15]));
let result = monitor.check(&state, &cov, None);
assert!(result.is_err());
}
#[test]
fn test_health_monitor_check_negative_variance() {
let limits = HealthLimits::default();
let mut monitor = HealthMonitor::new(limits);
let state = vec![
0.5, 0.5, 100.0, 10.0, 5.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
];
let mut cov = DMatrix::from_diagonal(&DVector::from_vec(vec![1e-6; 15]));
cov[(2, 2)] = -1.0;
let result = monitor.check(&state, &cov, None);
assert!(result.is_err());
}
#[test]
fn test_health_monitor_check_variance_too_large() {
let limits = HealthLimits::default();
let mut monitor = HealthMonitor::new(limits);
let state = vec![
0.5, 0.5, 100.0, 10.0, 5.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
];
let mut cov = DMatrix::from_diagonal(&DVector::from_vec(vec![1e-6; 15]));
cov[(3, 3)] = 1e20;
let result = monitor.check(&state, &cov, None);
assert!(result.is_err());
}
#[test]
fn test_health_monitor_check_nis_invalid() {
let limits = HealthLimits::default();
let mut monitor = HealthMonitor::new(limits);
let state = vec![
0.5, 0.5, 100.0, 10.0, 5.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
];
let cov = DMatrix::from_diagonal(&DVector::from_vec(vec![1e-6; 15]));
let result = monitor.check(&state, &cov, Some(f64::NAN));
assert!(result.is_err());
}
#[test]
fn test_health_monitor_check_nis_exceeds_threshold() {
let limits = HealthLimits { nis_pos_max: 10.0, nis_pos_consec_fail: 3, ..Default::default() };
let mut monitor = HealthMonitor::new(limits);
let state = vec![
0.5, 0.5, 100.0, 10.0, 5.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
];
let cov = DMatrix::from_diagonal(&DVector::from_vec(vec![1e-6; 15]));
assert!(monitor.check(&state, &cov, Some(15.0)).is_ok());
assert!(monitor.check(&state, &cov, Some(15.0)).is_ok());
let result = monitor.check(&state, &cov, Some(15.0));
assert!(result.is_err());
}
#[test]
fn test_health_monitor_check_nis_reset_on_pass() {
let limits = HealthLimits { nis_pos_max: 10.0, nis_pos_consec_fail: 3, ..Default::default() };
let mut monitor = HealthMonitor::new(limits);
let state = vec![
0.5, 0.5, 100.0, 10.0, 5.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
];
let cov = DMatrix::from_diagonal(&DVector::from_vec(vec![1e-6; 15]));
assert!(monitor.check(&state, &cov, Some(15.0)).is_ok());
assert!(monitor.check(&state, &cov, Some(5.0)).is_ok());
assert!(monitor.check(&state, &cov, Some(15.0)).is_ok());
assert!(monitor.check(&state, &cov, Some(15.0)).is_ok());
}
#[test]
fn test_build_scheduler_passthrough() {
let args = SchedulerArgs {
sched: SchedKind::Passthrough,
interval_s: 1.0,
phase_s: 0.0,
on_s: 10.0,
off_s: 10.0,
duty_phase_s: 0.0,
};
let scheduler = build_scheduler(&args);
matches!(scheduler, GnssScheduler::PassThrough);
}
#[test]
fn test_build_scheduler_fixed() {
let args = SchedulerArgs {
sched: SchedKind::Fixed,
interval_s: 2.5,
phase_s: 0.5,
on_s: 10.0,
off_s: 10.0,
duty_phase_s: 0.0,
};
let scheduler = build_scheduler(&args);
if let GnssScheduler::FixedInterval {
interval_s,
phase_s,
} = scheduler
{
assert_eq!(interval_s, 2.5);
assert_eq!(phase_s, 0.5);
} else {
panic!("Expected FixedInterval scheduler");
}
}
#[test]
fn test_build_scheduler_duty() {
let args = SchedulerArgs {
sched: SchedKind::Duty,
interval_s: 1.0,
phase_s: 0.0,
on_s: 15.0,
off_s: 5.0,
duty_phase_s: 2.0,
};
let scheduler = build_scheduler(&args);
if let GnssScheduler::DutyCycle {
on_s,
off_s,
start_phase_s,
} = scheduler
{
assert_eq!(on_s, 15.0);
assert_eq!(off_s, 5.0);
assert_eq!(start_phase_s, 2.0);
} else {
panic!("Expected DutyCycle scheduler");
}
}
#[test]
fn test_build_fault_none() {
let args = FaultArgs {
fault: FaultKind::None,
rho_pos: 0.99,
sigma_pos_m: 3.0,
rho_vel: 0.95,
sigma_vel_mps: 0.3,
r_scale: 5.0,
drift_n_mps: 0.02,
drift_e_mps: 0.0,
q_bias: 1e-6,
rotate_omega_rps: 0.0,
hijack_offset_n_m: 50.0,
hijack_offset_e_m: 0.0,
hijack_start_s: 120.0,
hijack_duration_s: 60.0,
};
let fault = build_fault(&args);
matches!(fault, GnssFaultModel::None);
}
#[test]
fn test_build_fault_degraded() {
let args = FaultArgs {
fault: FaultKind::Degraded,
rho_pos: 0.98,
sigma_pos_m: 5.0,
rho_vel: 0.93,
sigma_vel_mps: 0.5,
r_scale: 10.0,
drift_n_mps: 0.02,
drift_e_mps: 0.0,
q_bias: 1e-6,
rotate_omega_rps: 0.0,
hijack_offset_n_m: 50.0,
hijack_offset_e_m: 0.0,
hijack_start_s: 120.0,
hijack_duration_s: 60.0,
};
let fault = build_fault(&args);
if let GnssFaultModel::Degraded {
rho_pos,
sigma_pos_m,
rho_vel,
sigma_vel_mps,
r_scale,
} = fault
{
assert_eq!(rho_pos, 0.98);
assert_eq!(sigma_pos_m, 5.0);
assert_eq!(rho_vel, 0.93);
assert_eq!(sigma_vel_mps, 0.5);
assert_eq!(r_scale, 10.0);
} else {
panic!("Expected Degraded fault model");
}
}
#[test]
fn test_build_fault_slowbias() {
let args = FaultArgs {
fault: FaultKind::Slowbias,
rho_pos: 0.99,
sigma_pos_m: 3.0,
rho_vel: 0.95,
sigma_vel_mps: 0.3,
r_scale: 5.0,
drift_n_mps: 0.05,
drift_e_mps: 0.02,
q_bias: 1e-5,
rotate_omega_rps: 0.01,
hijack_offset_n_m: 50.0,
hijack_offset_e_m: 0.0,
hijack_start_s: 120.0,
hijack_duration_s: 60.0,
};
let fault = build_fault(&args);
if let GnssFaultModel::SlowBias {
drift_n_mps,
drift_e_mps,
q_bias,
rotate_omega_rps,
} = fault
{
assert_eq!(drift_n_mps, 0.05);
assert_eq!(drift_e_mps, 0.02);
assert_eq!(q_bias, 1e-5);
assert_eq!(rotate_omega_rps, 0.01);
} else {
panic!("Expected SlowBias fault model");
}
}
#[test]
fn test_build_fault_hijack() {
let args = FaultArgs {
fault: FaultKind::Hijack,
rho_pos: 0.99,
sigma_pos_m: 3.0,
rho_vel: 0.95,
sigma_vel_mps: 0.3,
r_scale: 5.0,
drift_n_mps: 0.02,
drift_e_mps: 0.0,
q_bias: 1e-6,
rotate_omega_rps: 0.0,
hijack_offset_n_m: 100.0,
hijack_offset_e_m: 50.0,
hijack_start_s: 180.0,
hijack_duration_s: 90.0,
};
let fault = build_fault(&args);
if let GnssFaultModel::Hijack {
offset_n_m,
offset_e_m,
start_s,
duration_s,
} = fault
{
assert_eq!(offset_n_m, 100.0);
assert_eq!(offset_e_m, 50.0);
assert_eq!(start_s, 180.0);
assert_eq!(duration_s, 90.0);
} else {
panic!("Expected Hijack fault model");
}
}
#[test]
fn test_ned_covariance() {
let cov = NEDCovariance {
latitude_cov: 1e-6,
longitude_cov: 1e-6,
altitude_cov: 1e-4,
velocity_n_cov: 1e-3,
velocity_e_cov: 1e-3,
velocity_v_cov: 1e-3,
roll_cov: 1e-5,
pitch_cov: 1e-5,
yaw_cov: 1e-5,
acc_bias_x_cov: 1e-6,
acc_bias_y_cov: 1e-6,
acc_bias_z_cov: 1e-6,
gyro_bias_x_cov: 1e-8,
gyro_bias_y_cov: 1e-8,
gyro_bias_z_cov: 1e-8,
};
assert_eq!(cov.latitude_cov, 1e-6);
assert_eq!(cov.gyro_bias_z_cov, 1e-8);
}
#[test]
fn test_navigation_result_csv_roundtrip_with_nan() {
let nav = NavigationResult {
latitude: 37.0,
longitude: -122.0,
altitude: 100.0,
latitude_cov: f64::NAN,
longitude_cov: f64::NAN,
..Default::default()
};
let temp_file = std::env::temp_dir().join("test_nav_nan.csv");
NavigationResult::to_csv(&[nav.clone()], &temp_file).unwrap();
let read = NavigationResult::from_csv(&temp_file).unwrap();
assert_eq!(read.len(), 1);
assert_eq!(read[0].latitude, 37.0);
assert!(read[0].latitude_cov.is_nan());
let _ = std::fs::remove_file(&temp_file);
}
#[test]
fn test_navigation_result_from_strapdown_state_with_rotation() {
let timestamp = Utc::now();
let state = StrapdownState {
latitude: 0.5, longitude: 1.0, altitude: 500.0,
velocity_north: 10.0,
velocity_east: 5.0,
velocity_vertical: -1.0,
attitude: nalgebra::Rotation3::from_euler_angles(0.1, 0.2, 0.3),
..Default::default()
};
let nav = NavigationResult::from((×tamp, &state));
assert_eq!(nav.timestamp, timestamp);
assert!((nav.latitude - 0.5_f64.to_degrees()).abs() < 1e-6);
assert!((nav.longitude - 1.0_f64.to_degrees()).abs() < 1e-6);
assert_eq!(nav.altitude, 500.0);
assert!(nav.latitude_cov.is_nan());
assert_eq!(nav.acc_bias_x, 0.0);
}
#[test]
fn test_default_process_noise_values() {
assert_eq!(DEFAULT_PROCESS_NOISE.len(), 15);
assert_eq!(DEFAULT_PROCESS_NOISE[0], 1e-6); assert_eq!(DEFAULT_PROCESS_NOISE[2], 1e-4); assert_eq!(DEFAULT_PROCESS_NOISE[3], 1e-3); }
#[test]
fn test_run_closed_loop_with_health_limits() {
let rec = TestDataRecord {
time: Utc::now(),
horizontal_accuracy: 5.0,
vertical_accuracy: 2.0,
speed_accuracy: 1.0,
latitude: 37.0,
longitude: -122.0,
altitude: 100.0,
speed: 10.0,
bearing: 45.0,
roll: 0.0,
pitch: 0.0,
yaw: 0.0,
acc_x: 0.0,
acc_y: 0.0,
acc_z: 9.81,
gyro_x: 0.0,
gyro_y: 0.0,
gyro_z: 0.0,
..Default::default()
};
let mut ukf = initialize_ukf(rec.clone(), UkfConfig::default());
let stream = EventStream {
start_time: rec.time,
events: vec![Event::Imu {
dt_s: 0.1,
imu: IMUData {
accel: Vector3::new(0.0, 0.0, 9.81),
gyro: Vector3::new(0.0, 0.0, 0.0),
},
elapsed_s: 0.0,
}],
};
let health_limits = HealthLimits::default();
let result = run_closed_loop(&mut ukf, stream, Some(health_limits), None);
assert!(result.is_ok());
}
#[test]
fn test_initialize_ekf_default_9state() {
let rec = TestDataRecord {
time: Utc::now(),
horizontal_accuracy: 5.0,
vertical_accuracy: 2.0,
speed_accuracy: 1.0,
latitude: 37.0,
longitude: -122.0,
altitude: 100.0,
speed: 10.0,
bearing: 45.0, roll: 0.0,
pitch: 0.0,
yaw: 0.0,
..Default::default()
};
let ekf = initialize_ekf(rec, None, None, None, None, false);
let estimate = ekf.get_estimate();
assert_eq!(estimate.len(), 9, "9-state EKF should have 9 states");
assert!((estimate[3] - estimate[4]).abs() < 1.0); }
#[test]
fn test_initialize_ekf_default_15state() {
let rec = TestDataRecord {
time: Utc::now(),
horizontal_accuracy: 5.0,
vertical_accuracy: 2.0,
speed_accuracy: 1.0,
latitude: 37.0,
longitude: -122.0,
altitude: 100.0,
speed: 10.0,
bearing: 45.0,
roll: 0.0,
pitch: 0.0,
yaw: 0.0,
..Default::default()
};
let ekf = initialize_ekf(rec, None, None, None, None, true);
let estimate = ekf.get_estimate();
assert_eq!(estimate.len(), 15, "15-state EKF should have 15 states");
for i in 9..15 {
assert!(
estimate[i].abs() < 1e-6,
"Default biases should be near zero"
);
}
}
#[test]
fn test_initialize_ekf_with_nan_angles() {
let rec = TestDataRecord {
time: Utc::now(),
horizontal_accuracy: 5.0,
vertical_accuracy: 2.0,
speed_accuracy: 1.0,
latitude: 37.0,
longitude: -122.0,
altitude: 100.0,
speed: 10.0,
bearing: 45.0,
roll: f64::NAN,
pitch: f64::NAN,
yaw: f64::NAN,
..Default::default()
};
let ekf = initialize_ekf(rec, None, None, None, None, true);
let estimate = ekf.get_estimate();
assert!(estimate[6].abs() < 1e-6, "NaN roll should default to 0"); assert!(estimate[7].abs() < 1e-6, "NaN pitch should default to 0"); assert!(estimate[8].abs() < 1e-6, "NaN yaw should default to 0"); }
#[test]
fn test_initialize_ekf_with_custom_biases() {
let rec = TestDataRecord {
time: Utc::now(),
horizontal_accuracy: 5.0,
vertical_accuracy: 2.0,
speed_accuracy: 1.0,
latitude: 37.0,
longitude: -122.0,
altitude: 100.0,
speed: 10.0,
bearing: 45.0,
roll: 0.0,
pitch: 0.0,
yaw: 0.0,
..Default::default()
};
let ekf = initialize_ekf(
rec,
Some(vec![1e-4, 2e-4, 3e-4]),
Some(vec![0.01, 0.02, 0.03, 0.001, 0.002, 0.003]),
Some(vec![1e-5; 6]),
None,
true,
);
let estimate = ekf.get_estimate();
assert_eq!(estimate.len(), 15);
assert!((estimate[9] - 0.01).abs() < 1e-9);
assert!((estimate[10] - 0.02).abs() < 1e-9);
assert!((estimate[11] - 0.03).abs() < 1e-9);
}
#[test]
fn test_initialize_ekf_with_custom_process_noise() {
let rec = TestDataRecord {
time: Utc::now(),
horizontal_accuracy: 5.0,
vertical_accuracy: 2.0,
speed_accuracy: 1.0,
latitude: 37.0,
longitude: -122.0,
altitude: 100.0,
speed: 10.0,
bearing: 45.0,
roll: 0.0,
pitch: 0.0,
yaw: 0.0,
..Default::default()
};
let custom_noise = vec![1e-7; 15];
let ekf = initialize_ekf(rec, None, None, None, Some(custom_noise.clone()), true);
assert_eq!(ekf.get_estimate().len(), 15);
}
#[test]
fn test_test_data_record_hdf5_roundtrip() {
use tempfile::tempdir;
let dir = tempdir().unwrap();
let file_path = dir.path().join("test_data.h5");
let records = vec![
TestDataRecord {
time: DateTime::parse_from_str("2023-01-01 00:00:00+00:00", "%Y-%m-%d %H:%M:%S%z")
.unwrap()
.with_timezone(&Utc),
bearing_accuracy: 0.1,
speed_accuracy: 0.1,
vertical_accuracy: 0.1,
horizontal_accuracy: 0.1,
speed: 1.0,
bearing: 90.0,
altitude: 100.0,
longitude: -122.0,
latitude: 37.0,
qz: 0.0,
qy: 0.0,
qx: 0.0,
qw: 1.0,
roll: 0.0,
pitch: 0.0,
yaw: 0.0,
acc_z: 9.81,
acc_y: 0.0,
acc_x: 0.0,
gyro_z: 0.01,
gyro_y: 0.01,
gyro_x: 0.01,
mag_z: 50.0,
mag_y: -30.0,
mag_x: -20.0,
relative_altitude: 5.0,
pressure: 1013.25,
grav_z: 9.81,
grav_y: 0.0,
grav_x: 0.0,
},
TestDataRecord {
time: DateTime::parse_from_str("2023-01-01 00:01:00+00:00", "%Y-%m-%d %H:%M:%S%z")
.unwrap()
.with_timezone(&Utc),
bearing_accuracy: 0.2,
speed_accuracy: 0.2,
vertical_accuracy: 0.2,
horizontal_accuracy: 0.2,
speed: 2.0,
bearing: 180.0,
altitude: 200.0,
longitude: -121.0,
latitude: 38.0,
qz: 0.0,
qy: 0.0,
qx: 0.0,
qw: 1.0,
roll: 0.1,
pitch: 0.1,
yaw: 0.1,
acc_z: 9.81,
acc_y: 0.01,
acc_x: -0.01,
gyro_z: 0.02,
gyro_y: -0.02,
gyro_x: 0.02,
mag_z: 55.0,
mag_y: -25.0,
mag_x: -15.0,
relative_altitude: 10.0,
pressure: 1012.25,
grav_z: 9.81,
grav_y: 0.01,
grav_x: -0.01,
},
];
TestDataRecord::to_hdf5(&records, &file_path).expect("Failed to write HDF5");
let read_records = TestDataRecord::from_hdf5(&file_path).expect("Failed to read HDF5");
assert_eq!(read_records.len(), records.len());
for (i, (original, read)) in records.iter().zip(read_records.iter()).enumerate() {
assert_eq!(
original.time, read.time,
"Timestamp mismatch at index {}",
i
);
assert!(
(original.latitude - read.latitude).abs() < 1e-10,
"Latitude mismatch at index {}",
i
);
assert!(
(original.longitude - read.longitude).abs() < 1e-10,
"Longitude mismatch at index {}",
i
);
assert!(
(original.altitude - read.altitude).abs() < 1e-10,
"Altitude mismatch at index {}",
i
);
assert!(
(original.speed - read.speed).abs() < 1e-10,
"Speed mismatch at index {}",
i
);
assert!(
(original.bearing - read.bearing).abs() < 1e-10,
"Bearing mismatch at index {}",
i
);
}
}
#[test]
fn test_navigation_result_hdf5_roundtrip() {
use tempfile::tempdir;
let dir = tempdir().unwrap();
let file_path = dir.path().join("nav_results.h5");
let mut results = Vec::new();
let mut nav1 = NavigationResult::new();
nav1.timestamp =
DateTime::parse_from_str("2023-01-01 00:00:00+00:00", "%Y-%m-%d %H:%M:%S%z")
.unwrap()
.with_timezone(&Utc);
nav1.latitude = 37.0;
nav1.longitude = -122.0;
nav1.altitude = 100.0;
nav1.velocity_north = 1.0;
nav1.velocity_east = 2.0;
nav1.velocity_vertical = 0.1;
nav1.roll = 0.01;
nav1.pitch = 0.02;
nav1.yaw = 0.03;
results.push(nav1);
let mut nav2 = NavigationResult::new();
nav2.timestamp =
DateTime::parse_from_str("2023-01-01 00:00:01+00:00", "%Y-%m-%d %H:%M:%S%z")
.unwrap()
.with_timezone(&Utc);
nav2.latitude = 37.0001;
nav2.longitude = -122.0001;
nav2.altitude = 101.0;
nav2.velocity_north = 1.1;
nav2.velocity_east = 2.1;
nav2.velocity_vertical = 0.2;
nav2.roll = 0.02;
nav2.pitch = 0.03;
nav2.yaw = 0.04;
results.push(nav2);
NavigationResult::to_hdf5(&results, &file_path).expect("Failed to write HDF5");
let read_results = NavigationResult::from_hdf5(&file_path).expect("Failed to read HDF5");
assert_eq!(read_results.len(), results.len());
for (i, (original, read)) in results.iter().zip(read_results.iter()).enumerate() {
assert_eq!(
original.timestamp, read.timestamp,
"Timestamp mismatch at index {}",
i
);
assert!(
(original.latitude - read.latitude).abs() < 1e-10,
"Latitude mismatch at index {}",
i
);
assert!(
(original.longitude - read.longitude).abs() < 1e-10,
"Longitude mismatch at index {}",
i
);
assert!(
(original.altitude - read.altitude).abs() < 1e-10,
"Altitude mismatch at index {}",
i
);
assert!(
(original.velocity_north - read.velocity_north).abs() < 1e-10,
"Velocity north mismatch at index {}",
i
);
assert!(
(original.velocity_east - read.velocity_east).abs() < 1e-10,
"Velocity east mismatch at index {}",
i
);
assert!(
(original.roll - read.roll).abs() < 1e-10,
"Roll mismatch at index {}",
i
);
assert!(
(original.pitch - read.pitch).abs() < 1e-10,
"Pitch mismatch at index {}",
i
);
assert!(
(original.yaw - read.yaw).abs() < 1e-10,
"Yaw mismatch at index {}",
i
);
}
}
#[test]
fn test_test_data_record_hdf5_with_nan_values() {
use tempfile::tempdir;
let dir = tempdir().unwrap();
let file_path = dir.path().join("test_data_nan.h5");
let record = TestDataRecord {
time: Utc::now(),
latitude: 37.0,
longitude: -122.0,
altitude: f64::NAN,
speed: f64::NAN,
bearing: 90.0,
..Default::default()
};
let records = vec![record.clone()];
TestDataRecord::to_hdf5(&records, &file_path).expect("Failed to write HDF5");
let read_records = TestDataRecord::from_hdf5(&file_path).expect("Failed to read HDF5");
assert_eq!(read_records.len(), 1);
assert!(
read_records[0].altitude.is_nan(),
"NaN altitude should be preserved"
);
assert!(
read_records[0].speed.is_nan(),
"NaN speed should be preserved"
);
assert!((read_records[0].latitude - record.latitude).abs() < 1e-10);
assert!((read_records[0].longitude - record.longitude).abs() < 1e-10);
}
#[test]
fn test_navigation_result_hdf5_empty() {
use tempfile::tempdir;
let dir = tempdir().unwrap();
let file_path = dir.path().join("nav_results_empty.h5");
let results: Vec<NavigationResult> = Vec::new();
NavigationResult::to_hdf5(&results, &file_path).expect("Failed to write empty HDF5");
let read_results =
NavigationResult::from_hdf5(&file_path).expect("Failed to read empty HDF5");
assert_eq!(read_results.len(), 0);
}
#[test]
fn test_navigation_result_mcap_roundtrip() {
let temp_file = std::env::temp_dir().join("nav_results_mcap.mcap");
let result1 = NavigationResult {
timestamp: Utc::now(),
latitude: 37.0,
longitude: -122.0,
altitude: 100.0,
velocity_north: 10.0,
velocity_east: 5.0,
velocity_vertical: -1.0,
roll: 0.1,
pitch: 0.2,
yaw: 0.3,
..Default::default()
};
let result2 = NavigationResult {
timestamp: Utc::now() + chrono::Duration::seconds(1),
latitude: 37.01,
longitude: -122.01,
altitude: 110.0,
velocity_north: 12.0,
velocity_east: 6.0,
velocity_vertical: 0.5,
roll: 0.15,
pitch: 0.25,
yaw: 0.35,
..Default::default()
};
let results = vec![result1.clone(), result2.clone()];
NavigationResult::to_mcap(&results, &temp_file)
.expect("Failed to write navigation results to MCAP");
assert!(temp_file.exists(), "MCAP file should exist");
let read_results = NavigationResult::from_mcap(&temp_file)
.expect("Failed to read navigation results from MCAP");
assert_eq!(
read_results.len(),
results.len(),
"Result count should match"
);
for (i, (original, read)) in results.iter().zip(read_results.iter()).enumerate() {
assert_eq!(
original.timestamp, read.timestamp,
"Result {} timestamp should match",
i
);
assert!(
(original.latitude - read.latitude).abs() < 1e-6,
"Result {} latitude should match",
i
);
assert!(
(original.longitude - read.longitude).abs() < 1e-6,
"Result {} longitude should match",
i
);
assert!(
(original.altitude - read.altitude).abs() < 1e-6,
"Result {} altitude should match",
i
);
assert!(
(original.velocity_north - read.velocity_north).abs() < 1e-6,
"Result {} velocity_north should match",
i
);
assert!(
(original.roll - read.roll).abs() < 1e-6,
"Result {} roll should match",
i
);
assert!(
(original.pitch - read.pitch).abs() < 1e-6,
"Result {} pitch should match",
i
);
assert!(
(original.yaw - read.yaw).abs() < 1e-6,
"Result {} yaw should match",
i
);
}
let _ = std::fs::remove_file(&temp_file);
}
}