use crate::earth::METERS_TO_DEGREES;
use crate::linalg::{matrix_square_root, robust_spd_solve, symmetrize};
use crate::{IMUData, StrapdownState, forward, wrap_to_2pi};
use std::fmt::Debug;
use nalgebra::{DMatrix, DVector, Rotation3};
use rand;
pub trait MeasurementModel {
fn get_dimension(&self) -> usize;
fn get_vector(&self) -> DVector<f64>;
fn get_noise(&self) -> DMatrix<f64>;
fn get_sigma_points(&self, state_sigma_points: &DMatrix<f64>) -> DMatrix<f64>;
}
#[derive(Clone, Debug, Default)]
pub struct GPSPositionMeasurement {
pub latitude: f64,
pub longitude: f64,
pub altitude: f64,
pub horizontal_noise_std: f64,
pub vertical_noise_std: f64,
}
impl MeasurementModel for GPSPositionMeasurement {
fn get_dimension(&self) -> usize {
3 }
fn get_vector(&self) -> DVector<f64> {
DVector::from_vec(vec![
self.latitude.to_radians(),
self.longitude.to_radians(),
self.altitude,
])
}
fn get_noise(&self) -> DMatrix<f64> {
DMatrix::from_diagonal(&DVector::from_vec(vec![
(self.horizontal_noise_std * METERS_TO_DEGREES).powi(2),
(self.horizontal_noise_std * METERS_TO_DEGREES).powi(2),
self.vertical_noise_std.powi(2),
]))
}
fn get_sigma_points(&self, state_sigma_points: &DMatrix<f64>) -> DMatrix<f64> {
let mut measurement_sigma_points = DMatrix::<f64>::zeros(3, state_sigma_points.ncols());
for (i, sigma_point) in state_sigma_points.column_iter().enumerate() {
measurement_sigma_points[(0, i)] = sigma_point[0];
measurement_sigma_points[(1, i)] = sigma_point[1];
measurement_sigma_points[(2, i)] = sigma_point[2];
}
measurement_sigma_points
}
}
#[derive(Clone, Debug, Default)]
pub struct GPSVelocityMeasurement {
pub northward_velocity: f64,
pub eastward_velocity: f64,
pub downward_velocity: f64,
pub horizontal_noise_std: f64,
pub vertical_noise_std: f64,
}
impl MeasurementModel for GPSVelocityMeasurement {
fn get_dimension(&self) -> usize {
3 }
fn get_vector(&self) -> DVector<f64> {
DVector::from_vec(vec![
self.northward_velocity,
self.eastward_velocity,
self.downward_velocity,
])
}
fn get_noise(&self) -> DMatrix<f64> {
DMatrix::from_diagonal(&DVector::from_vec(vec![
self.horizontal_noise_std.powi(2),
self.horizontal_noise_std.powi(2),
self.vertical_noise_std.powi(2),
]))
}
fn get_sigma_points(&self, state_sigma_points: &DMatrix<f64>) -> DMatrix<f64> {
let mut measurement_sigma_points = DMatrix::<f64>::zeros(3, state_sigma_points.ncols());
for (i, sigma_point) in state_sigma_points.column_iter().enumerate() {
measurement_sigma_points[(0, i)] = sigma_point[3];
measurement_sigma_points[(1, i)] = sigma_point[4];
measurement_sigma_points[(2, i)] = sigma_point[5];
}
measurement_sigma_points
}
}
#[derive(Clone, Debug, Default)]
pub struct GPSPositionAndVelocityMeasurement {
pub latitude: f64,
pub longitude: f64,
pub altitude: f64,
pub northward_velocity: f64,
pub eastward_velocity: f64,
pub horizontal_noise_std: f64,
pub vertical_noise_std: f64,
pub velocity_noise_std: f64,
}
impl MeasurementModel for GPSPositionAndVelocityMeasurement {
fn get_dimension(&self) -> usize {
5 }
fn get_vector(&self) -> DVector<f64> {
DVector::from_vec(vec![
self.latitude.to_radians(),
self.longitude.to_radians(),
self.altitude,
self.northward_velocity,
self.eastward_velocity,
])
}
fn get_noise(&self) -> DMatrix<f64> {
DMatrix::from_diagonal(&DVector::from_vec(vec![
(self.horizontal_noise_std * METERS_TO_DEGREES).powi(2),
(self.horizontal_noise_std * METERS_TO_DEGREES).powi(2),
self.vertical_noise_std.powi(2),
self.velocity_noise_std.powi(2),
self.velocity_noise_std.powi(2),
]))
}
fn get_sigma_points(&self, state_sigma_points: &DMatrix<f64>) -> DMatrix<f64> {
let mut measurement_sigma_points = DMatrix::<f64>::zeros(5, state_sigma_points.ncols());
for (i, sigma_point) in state_sigma_points.column_iter().enumerate() {
measurement_sigma_points[(0, i)] = sigma_point[0];
measurement_sigma_points[(1, i)] = sigma_point[1];
measurement_sigma_points[(2, i)] = sigma_point[2];
measurement_sigma_points[(3, i)] = sigma_point[3];
measurement_sigma_points[(4, i)] = sigma_point[4];
}
measurement_sigma_points
}
}
#[derive(Clone, Debug, Default)]
pub struct RelativeAltitudeMeasurement {
pub relative_altitude: f64,
pub reference_altitude: f64,
}
impl MeasurementModel for RelativeAltitudeMeasurement {
fn get_dimension(&self) -> usize {
1 }
fn get_vector(&self) -> DVector<f64> {
DVector::from_vec(vec![self.relative_altitude + self.reference_altitude])
}
fn get_noise(&self) -> DMatrix<f64> {
DMatrix::from_diagonal(&DVector::from_vec(vec![5.0])) }
fn get_sigma_points(&self, state_sigma_points: &DMatrix<f64>) -> DMatrix<f64> {
let mut measurement_sigma_points =
DMatrix::<f64>::zeros(self.get_dimension(), state_sigma_points.ncols());
for (i, sigma_point) in state_sigma_points.column_iter().enumerate() {
measurement_sigma_points[(0, i)] = sigma_point[2];
}
measurement_sigma_points
}
}
#[derive(Clone, Debug, Default)]
pub struct GravityAnomalyMeasurement {
}
#[derive(Clone, Debug, Default)]
pub struct MagneticAnomalyMeasurement {}
#[derive(Clone, Debug, Default)]
pub struct StrapdownParams {
pub latitude: f64,
pub longitude: f64,
pub altitude: f64,
pub northward_velocity: f64,
pub eastward_velocity: f64,
pub downward_velocity: f64,
pub roll: f64,
pub pitch: f64,
pub yaw: f64,
pub in_degrees: bool,
}
pub struct UKF {
mean_state: DVector<f64>,
covariance: DMatrix<f64>,
process_noise: DMatrix<f64>,
lambda: f64,
state_size: usize,
weights_mean: DVector<f64>,
weights_cov: DVector<f64>,
}
impl Debug for UKF {
fn fmt(&self, f: &mut std::fmt::Formatter<'_>) -> std::fmt::Result {
f.debug_struct("UKF")
.field("mean_state", &self.mean_state)
.field("covariance", &self.covariance)
.field("process_noise", &self.process_noise)
.field("lambda", &self.lambda)
.field("state_size", &self.state_size)
.finish()
}
}
impl UKF {
pub fn new(
strapdown_state: StrapdownParams,
imu_biases: Vec<f64>,
other_states: Option<Vec<f64>>,
covariance_diagonal: Vec<f64>,
process_noise: DMatrix<f64>,
alpha: f64,
beta: f64,
kappa: f64,
) -> UKF {
assert!(
process_noise.nrows() == process_noise.ncols(),
"Process noise matrix must be square"
);
let mut mean = if strapdown_state.in_degrees {
vec![
strapdown_state.latitude.to_radians(),
strapdown_state.longitude.to_radians(),
strapdown_state.altitude,
strapdown_state.northward_velocity,
strapdown_state.eastward_velocity,
strapdown_state.downward_velocity,
strapdown_state.roll,
strapdown_state.pitch,
strapdown_state.yaw,
]
} else {
vec![
strapdown_state.latitude,
strapdown_state.longitude,
strapdown_state.altitude,
strapdown_state.northward_velocity,
strapdown_state.eastward_velocity,
strapdown_state.downward_velocity,
strapdown_state.roll,
strapdown_state.pitch,
strapdown_state.yaw,
]
};
mean.extend(imu_biases);
if let Some(ref other_states) = other_states {
mean.extend(other_states.iter().cloned());
}
assert!(
mean.len() >= 15,
"Expected a canonical state vector of at least 15 states (position, velocity, attitude, imu biases)"
);
assert!(
mean.len() == covariance_diagonal.len(),
"{}",
&format!(
"Mean vector and covariance diagonal must be of the same size (mean: {}, covariance_diagonal: {})",
mean.len(),
covariance_diagonal.len()
)
);
let state_size = mean.len();
let mean_state = DVector::from_vec(mean);
let covariance = DMatrix::<f64>::from_diagonal(&DVector::from_vec(covariance_diagonal));
assert!(
covariance.shape() == (state_size, state_size),
"Covariance matrix must be square"
);
assert!(
covariance.shape() == process_noise.shape(),
"Covariance and process noise must be of the same size"
);
let lambda = alpha * alpha * (state_size as f64 + kappa) - state_size as f64;
let mut weights_mean = DVector::zeros(2 * state_size + 1);
let mut weights_cov = DVector::zeros(2 * state_size + 1);
weights_mean[0] = lambda / (state_size as f64 + lambda);
weights_cov[0] = lambda / (state_size as f64 + lambda) + (1.0 - alpha * alpha + beta);
for i in 1..(2 * state_size + 1) {
let w = 1.0 / (2.0 * (state_size as f64 + lambda));
weights_mean[i] = w;
weights_cov[i] = w;
}
UKF {
mean_state,
covariance,
process_noise,
lambda,
state_size,
weights_mean,
weights_cov,
}
}
pub fn predict(&mut self, imu_data: IMUData, dt: f64) {
let mut sigma_points = self.get_sigma_points();
for i in 0..sigma_points.ncols() {
let mut sigma_point_vec = sigma_points.column(i).clone_owned();
let mut state = StrapdownState {
latitude: sigma_point_vec[0],
longitude: sigma_point_vec[1],
altitude: sigma_point_vec[2],
velocity_north: sigma_point_vec[3],
velocity_east: sigma_point_vec[4],
velocity_down: sigma_point_vec[5],
attitude: Rotation3::from_euler_angles(
sigma_point_vec[6],
sigma_point_vec[7],
sigma_point_vec[8],
),
coordinate_convention: true,
};
forward(&mut state, imu_data, dt);
sigma_point_vec[0] = state.latitude;
sigma_point_vec[1] = state.longitude;
sigma_point_vec[2] = state.altitude;
sigma_point_vec[3] = state.velocity_north;
sigma_point_vec[4] = state.velocity_east;
sigma_point_vec[5] = state.velocity_down;
sigma_point_vec[6] = state.attitude.euler_angles().0; sigma_point_vec[7] = state.attitude.euler_angles().1; sigma_point_vec[8] = state.attitude.euler_angles().2; sigma_points.set_column(i, &sigma_point_vec);
}
let mut mu_bar = DVector::<f64>::zeros(self.state_size);
for (i, sigma_point) in sigma_points.column_iter().enumerate() {
mu_bar += self.weights_mean[i] * sigma_point;
}
let mut p_bar = DMatrix::<f64>::zeros(self.state_size, self.state_size);
for (i, sigma_point) in sigma_points.column_iter().enumerate() {
let diff = sigma_point - &mu_bar;
p_bar += self.weights_cov[i] * &diff * &diff.transpose();
}
p_bar += &self.process_noise;
self.mean_state = mu_bar;
self.covariance = symmetrize(&p_bar);
}
pub fn get_mean(&self) -> DVector<f64> {
self.mean_state.clone()
}
pub fn get_covariance(&self) -> DMatrix<f64> {
self.covariance.clone()
}
pub fn get_sigma_points(&self) -> DMatrix<f64> {
let p = (self.state_size as f64 + self.lambda) * self.covariance.clone();
let sqrt_p = matrix_square_root(&p);
let mu = self.mean_state.clone();
let mut pts = DMatrix::<f64>::zeros(self.state_size, 2 * self.state_size + 1);
pts.column_mut(0).copy_from(&mu);
for i in 0..sqrt_p.ncols() {
pts.column_mut(i + 1).copy_from(&(&mu + sqrt_p.column(i)));
pts.column_mut(i + 1 + self.state_size)
.copy_from(&(&mu - sqrt_p.column(i)));
}
pts
}
pub fn update<M: MeasurementModel>(&mut self, measurement: M) {
let measurement_sigma_points = measurement.get_sigma_points(&self.get_sigma_points());
let mut z_hat = DVector::<f64>::zeros(measurement.get_dimension());
for (i, sigma_point) in measurement_sigma_points.column_iter().enumerate() {
z_hat += self.weights_mean[i] * sigma_point;
}
let mut s = DMatrix::<f64>::zeros(measurement.get_dimension(), measurement.get_dimension());
for (i, sigma_point) in measurement_sigma_points.column_iter().enumerate() {
let diff = sigma_point - &z_hat;
s += self.weights_cov[i] * &diff * &diff.transpose();
}
s += measurement.get_noise();
let sigma_points = self.get_sigma_points();
let mut cross_covariance =
DMatrix::<f64>::zeros(self.state_size, measurement.get_dimension());
for (i, measurement_sigma_point) in measurement_sigma_points.column_iter().enumerate() {
let measurement_diff = measurement_sigma_point - &z_hat;
let state_diff = sigma_points.column(i) - &self.mean_state;
cross_covariance += self.weights_cov[i] * state_diff * measurement_diff.transpose();
}
let k = self.robust_kalman_gain(&cross_covariance, &s);
self.mean_state += &k * (measurement.get_vector() - &z_hat);
self.mean_state[6] = wrap_to_2pi(self.mean_state[6]);
self.mean_state[7] = wrap_to_2pi(self.mean_state[7]);
self.mean_state[8] = wrap_to_2pi(self.mean_state[8]);
self.covariance -= &k * &s * &k.transpose();
self.covariance = 0.5 * (&self.covariance + self.covariance.transpose());
}
fn robust_kalman_gain(
&mut self,
cross_covariance: &DMatrix<f64>,
s: &DMatrix<f64>,
) -> DMatrix<f64> {
let kt = robust_spd_solve(&symmetrize(s), &cross_covariance.transpose());
kt.transpose()
}
}
#[derive(Clone, Debug, Default)]
pub struct Particle {
pub nav_state: StrapdownState,
pub weight: f64,
}
pub struct ParticleFilter {
pub particles: Vec<Particle>,
}
impl ParticleFilter {
pub fn new(particles: Vec<Particle>) -> Self {
ParticleFilter { particles }
}
pub fn propagate(&mut self, imu_data: &IMUData, dt: f64) {
for particle in &mut self.particles {
forward(&mut particle.nav_state, *imu_data, dt);
}
}
pub fn update(&mut self, measurement: &DVector<f64>, expected_measurements: &[DVector<f64>]) {
assert_eq!(self.particles.len(), expected_measurements.len());
let mut weights = Vec::with_capacity(self.particles.len());
for expected in expected_measurements.iter() {
let diff = measurement - expected;
let weight = (-0.5 * diff.transpose() * diff).exp().sum(); weights.push(weight);
}
self.normalize_weights();
}
pub fn set_weights(&mut self, weights: &[f64]) {
assert_eq!(weights.len(), self.particles.len());
for (particle, &w) in self.particles.iter_mut().zip(weights.iter()) {
particle.weight = w;
}
}
pub fn normalize_weights(&mut self) {
let sum: f64 = self.particles.iter().map(|p| p.weight).sum();
if sum > 0.0 {
for particle in &mut self.particles {
particle.weight /= sum;
}
}
}
pub fn residual_resample(&mut self) {
let n = self.particles.len();
let mut new_particles = Vec::with_capacity(n);
let weights: Vec<f64> = self.particles.iter().map(|p| p.weight).collect();
let mut num_copies = vec![0usize; n];
let mut residual: Vec<f64> = vec![0.0; n];
for (i, &w) in weights.iter().enumerate() {
let copies = (w * n as f64).floor() as usize;
num_copies[i] = copies;
residual[i] = w * n as f64 - copies as f64;
}
for (i, &copies) in num_copies.iter().enumerate() {
for _ in 0..copies {
new_particles.push(self.particles[i].clone());
}
}
let residual_particles = n - new_particles.len();
if residual_particles > 0 {
let sum_residual: f64 = residual.iter().sum();
let mut positions = Vec::with_capacity(residual_particles);
let step = sum_residual / residual_particles as f64;
let mut u = rand::random::<f64>() * step;
for _ in 0..residual_particles {
positions.push(u);
u += step;
}
let mut i = 0;
let mut j = 0;
let mut cumsum = residual[0];
while j < residual_particles {
while positions[j] > cumsum {
i += 1;
cumsum += residual[i];
}
new_particles.push(self.particles[i].clone());
j += 1;
}
}
let uniform_weight = 1.0 / n as f64;
for particle in &mut new_particles {
particle.weight = uniform_weight;
}
self.particles = new_particles;
}
}
#[cfg(test)]
mod tests {
use super::*;
use crate::earth;
use assert_approx_eq::assert_approx_eq;
use nalgebra::Vector3;
const IMU_BIASES: [f64; 6] = [0.0; 6];
const N: usize = 15;
const COVARIANCE_DIAGONAL: [f64; N] = [1e-9; N];
const PROCESS_NOISE_DIAGONAL: [f64; N] = [1e-9; N];
const ALPHA: f64 = 1e-3;
const BETA: f64 = 2.0;
const KAPPA: f64 = 0.0;
const UKF_PARAMS: StrapdownParams = StrapdownParams {
latitude: 0.0,
longitude: 0.0,
altitude: 0.0,
northward_velocity: 0.0,
eastward_velocity: 0.0,
downward_velocity: 0.0,
roll: 0.0,
pitch: 0.0,
yaw: 0.0,
in_degrees: false,
};
#[test]
fn ukf_construction() {
let measurement_bias = vec![0.0; 3]; let ukf = UKF::new(
UKF_PARAMS,
IMU_BIASES.to_vec(),
Some(measurement_bias.clone()),
vec![1e-3; 18],
DMatrix::from_diagonal(&DVector::from_vec(vec![1e-3; 18])),
ALPHA,
BETA,
KAPPA,
);
assert_eq!(ukf.mean_state.len(), 18);
let wms = ukf.weights_mean;
let wcs = ukf.weights_cov;
assert_eq!(wms.len(), (2 * ukf.state_size) + 1);
assert_eq!(wcs.len(), (2 * ukf.state_size) + 1);
let lambda = ALPHA.powi(2) * (18.0 + KAPPA) - 18.0;
assert_eq!(lambda, ukf.lambda);
let wm_0 = lambda / (18.0 + lambda);
let wc_0 = wm_0 + (1.0 - ALPHA.powi(2)) + BETA;
let w_i = 1.0 / (2.0 * (18.0 + lambda));
assert_approx_eq!(wms[0], wm_0, 1e-6);
assert_approx_eq!(wcs[0], wc_0, 1e-6);
for i in 1..wms.len() {
assert_approx_eq!(wms[i], w_i, 1e-6);
assert_approx_eq!(wcs[i], w_i, 1e-6);
}
}
#[test]
fn ukf_get_sigma_points() {
let ukf = UKF::new(
UKF_PARAMS,
IMU_BIASES.to_vec(),
None,
COVARIANCE_DIAGONAL.to_vec(),
DMatrix::from_diagonal(&DVector::from_vec(PROCESS_NOISE_DIAGONAL.to_vec())),
ALPHA,
BETA,
KAPPA,
);
let sigma_points = ukf.get_sigma_points();
assert_eq!(sigma_points.ncols(), (2 * ukf.state_size) + 1);
let mu = ukf.get_sigma_points() * ukf.weights_mean;
assert_eq!(mu.nrows(), ukf.state_size);
assert_eq!(mu.ncols(), 1);
assert_approx_eq!(mu[0], 0.0, 1e-6);
assert_approx_eq!(mu[1], 0.0, 1e-6);
assert_approx_eq!(mu[2], 0.0, 1e-6);
assert_approx_eq!(mu[3], 0.0, 1e-6);
assert_approx_eq!(mu[4], 0.0, 1e-6);
assert_approx_eq!(mu[5], 0.0, 1e-6);
assert_approx_eq!(mu[6], 0.0, 1e-6);
assert_approx_eq!(mu[7], 0.0, 1e-6);
assert_approx_eq!(mu[8], 0.0, 1e-6);
}
#[test]
fn ukf_propagate() {
let mut ukf = UKF::new(
UKF_PARAMS,
vec![0.0; 6],
None, vec![0.0; N], DMatrix::from_diagonal(&DVector::from_vec(PROCESS_NOISE_DIAGONAL.to_vec())),
1e-3,
2.0,
0.0,
);
let dt = 1.0;
let imu_data = IMUData {
accel: Vector3::new(0.0, 0.0, earth::gravity(&0.0, &0.0)),
gyro: Vector3::new(0.0, 0.0, 0.0), };
ukf.predict(imu_data, dt);
assert!(
ukf.mean_state.len() == 15 );
let measurement = GPSPositionMeasurement {
latitude: 0.0,
longitude: 0.0,
altitude: 0.0,
horizontal_noise_std: 1e-3,
vertical_noise_std: 1e-3,
};
ukf.update(measurement);
assert_approx_eq!(ukf.mean_state[0], 0.0, 1e-3);
assert_approx_eq!(ukf.mean_state[1], 0.0, 1e-3);
assert_approx_eq!(ukf.mean_state[2], 0.0, 0.1);
assert_approx_eq!(ukf.mean_state[3], 0.0, 0.1);
assert_approx_eq!(ukf.mean_state[4], 0.0, 0.1);
assert_approx_eq!(ukf.mean_state[5], 0.0, 0.1);
}
}