numeris 0.5.1

Pure-Rust numerical algorithms library — high performance with SIMD support while also supporting no-std for embedded and WASM targets.
Documentation
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
400
401
402
403
404
405
406
407
408
409
410
411
412
413
414
415
416
417
418
419
420
extern crate alloc;
use alloc::vec::Vec;

use crate::matrix::vector::Vector;
use crate::traits::FloatScalar;
use crate::Matrix;

use super::{apply_var_floor, cholesky_with_jitter, EstimateError};

/// Unscented Kalman Filter with Merwe-scaled sigma points.
///
/// `N` is the state dimension, `M` is the measurement dimension.
/// Uses `2N+1` sigma points to capture mean and covariance through
/// nonlinear transformations without requiring Jacobians.
///
/// Requires the `alloc` feature for temporary sigma point storage
/// in `predict` and `update`.
///
/// # Default parameters
///
/// `alpha=1.0`, `beta=2.0`, `kappa=0.0` — all sigma-point weights are non-negative,
/// sigma points are placed at distance `√N · L[:,i]` from the mean.
/// For tight sigma point clustering, reduce `alpha` toward 0.1.
///
/// # Example
///
/// ```
/// use numeris::estimate::Ukf;
/// use numeris::{Vector, Matrix};
///
/// let x0 = Vector::from_array([0.0_f64, 1.0]);
/// let p0 = Matrix::new([[1.0, 0.0], [0.0, 1.0]]);
/// let mut ukf = Ukf::<f64, 2, 1>::new(x0, p0);
///
/// let dt = 0.1;
/// let q = Matrix::new([[0.01, 0.0], [0.0, 0.01]]);
/// let r = Matrix::new([[0.5]]);
///
/// // Predict
/// ukf.predict(
///     |x| Vector::from_array([x[0] + dt * x[1], x[1]]),
///     Some(&q),
/// ).unwrap();
///
/// // Update
/// ukf.update(
///     &Vector::from_array([0.12]),
///     |x| Vector::from_array([x[0]]),
///     &r,
/// ).unwrap();
/// ```
pub struct Ukf<T: FloatScalar, const N: usize, const M: usize> {
    /// State estimate.
    pub x: Vector<T, N>,
    /// State covariance.
    pub p: Matrix<T, N, N>,
    alpha: T,
    beta: T,
    kappa: T,
    /// Minimum allowed diagonal variance (0 = disabled).
    min_variance: T,
    /// Fading-memory factor γ≥1 applied to predicted covariance (1 = standard).
    gamma: T,
}

impl<T: FloatScalar, const N: usize, const M: usize> Ukf<T, N, M> {
    /// Create a new UKF with default Merwe parameters: `alpha=1.0`, `beta=2.0`, `kappa=0.0`.
    ///
    /// These defaults yield non-negative sigma-point weights for all state dimensions.
    /// For tighter sigma point spread, use `with_params` to reduce `alpha`.
    pub fn new(x0: Vector<T, N>, p0: Matrix<T, N, N>) -> Self {
        Self::with_params(
            x0,
            p0,
            T::one(),
            T::from(2.0).unwrap(),
            T::zero(),
        )
    }

    /// Create a new UKF with custom scaling parameters.
    ///
    /// - `alpha` — spread of sigma points around mean (1.0 gives non-negative weights;
    ///   values < ~0.52 give negative central weight `wc_0`)
    /// - `beta` — prior distribution knowledge (2.0 optimal for Gaussian)
    /// - `kappa` — secondary scaling (0 or 3-N)
    pub fn with_params(
        x0: Vector<T, N>,
        p0: Matrix<T, N, N>,
        alpha: T,
        beta: T,
        kappa: T,
    ) -> Self {
        Self {
            x: x0,
            p: p0,
            alpha,
            beta,
            kappa,
            min_variance: T::zero(),
            gamma: T::one(),
        }
    }

    /// Set a minimum diagonal variance floor applied after every predict/update.
    pub fn with_min_variance(mut self, min_variance: T) -> Self {
        self.min_variance = min_variance;
        self
    }

    /// Set a fading-memory factor `γ ≥ 1` applied to the propagated covariance.
    ///
    /// The predicted covariance becomes `γ · P_sigma + Q` where `P_sigma` is
    /// the sigma-point weighted covariance (without Q). Default is `1.0`.
    pub fn with_fading_memory(mut self, gamma: T) -> Self {
        self.gamma = gamma;
        self
    }

    /// Reference to the current state estimate.
    #[inline]
    pub fn state(&self) -> &Vector<T, N> {
        &self.x
    }

    /// Reference to the current state covariance.
    #[inline]
    pub fn covariance(&self) -> &Matrix<T, N, N> {
        &self.p
    }

    /// Compute Merwe weights: `(wm_0, wc_0, w_i)` where `w_i = wm_i = wc_i` for i > 0.
    fn weights(&self) -> (T, T, T) {
        let n = T::from(N).unwrap();
        let lambda = self.alpha * self.alpha * (n + self.kappa) - n;
        let denom = n + lambda;
        let wm_0 = lambda / denom;
        let wc_0 = wm_0 + (T::one() - self.alpha * self.alpha + self.beta);
        let w_i = T::one() / (T::from(2.0).unwrap() * denom);
        (wm_0, wc_0, w_i)
    }

    /// Compute lambda = alpha^2 * (N + kappa) - N.
    fn lambda(&self) -> T {
        let n = T::from(N).unwrap();
        self.alpha * self.alpha * (n + self.kappa) - n
    }

    /// Generate scaled Cholesky factor for sigma point generation.
    ///
    /// Returns `scaled_L = sqrt(N + lambda) · L` where `L = chol(P)`.
    fn sigma_cholesky(&self) -> Result<Matrix<T, N, N>, EstimateError> {
        let n = T::from(N).unwrap();
        let lambda = self.lambda();
        let scale = (n + lambda).sqrt();
        let chol = cholesky_with_jitter(&self.p)?;
        Ok(chol.l_full() * scale)
    }

    /// Predict step.
    ///
    /// - `f` — state transition: `x_{k+1} = f(x_k)`
    /// - `q` — process noise covariance (pass `None` for zero process noise)
    ///
    /// Generates `2N+1` sigma points, propagates through `f`, and
    /// reconstructs the predicted mean and covariance as `γ · P_sigma + Q`.
    pub fn predict(
        &mut self,
        f: impl Fn(&Vector<T, N>) -> Vector<T, N>,
        q: Option<&Matrix<T, N, N>>,
    ) -> Result<(), EstimateError> {
        let scaled_l = self.sigma_cholesky()?;
        let (wm_0, wc_0, w_i) = self.weights();

        // Propagate sigma points and store
        let mut sigmas: Vec<Vector<T, N>> = Vec::with_capacity(2 * N + 1);

        // Central point
        sigmas.push(f(&self.x));

        // Positive and negative perturbations
        for i in 0..N {
            let mut col = Vector::<T, N>::zeros();
            for r in 0..N {
                col[r] = scaled_l[(r, i)];
            }
            sigmas.push(f(&(self.x + col)));
            sigmas.push(f(&(self.x - col)));
        }

        // Weighted mean
        let mut x_mean = Vector::<T, N>::zeros();
        for r in 0..N {
            x_mean[r] = wm_0 * sigmas[0][r];
        }
        for i in 0..N {
            for r in 0..N {
                x_mean[r] =
                    x_mean[r] + w_i * (sigmas[2 * i + 1][r] + sigmas[2 * i + 2][r]);
            }
        }

        // Weighted covariance (sigma-point part, without Q)
        let mut p_new = Matrix::<T, N, N>::zeros();
        let d0 = sigmas[0] - x_mean;
        for r in 0..N {
            for c in 0..N {
                p_new[(r, c)] = p_new[(r, c)] + wc_0 * d0[r] * d0[c];
            }
        }
        for i in 0..N {
            let dp = sigmas[2 * i + 1] - x_mean;
            let dm = sigmas[2 * i + 2] - x_mean;
            for r in 0..N {
                for c in 0..N {
                    p_new[(r, c)] = p_new[(r, c)]
                        + w_i * (dp[r] * dp[c] + dm[r] * dm[c]);
                }
            }
        }

        // Fading memory: scale sigma-point covariance by γ before adding Q.
        p_new = p_new * self.gamma;
        self.x = x_mean;
        self.p = if let Some(q) = q { p_new + *q } else { p_new };
        let half = T::from(0.5).unwrap();
        self.p = (self.p + self.p.transpose()) * half;
        apply_var_floor(&mut self.p, self.min_variance);

        Ok(())
    }

    /// Update step.
    ///
    /// - `z` — measurement vector
    /// - `h` — measurement model: `z = h(x)`
    /// - `r` — measurement noise covariance
    ///
    /// Generates sigma points from the predicted state, transforms through `h`,
    /// and computes the Kalman gain via the cross-covariance and innovation covariance.
    ///
    /// Covariance update uses the symmetric `P - K S Kᵀ` form (equivalent to
    /// `P - K Pxzᵀ` but manifestly PSD-subtracted).
    ///
    /// Returns the Normalized Innovation Squared (NIS): `yᵀ S⁻¹ y`.
    pub fn update(
        &mut self,
        z: &Vector<T, M>,
        h: impl Fn(&Vector<T, N>) -> Vector<T, M>,
        r: &Matrix<T, M, M>,
    ) -> Result<T, EstimateError> {
        let scaled_l = self.sigma_cholesky()?;
        let (wm_0, wc_0, w_i) = self.weights();

        // Generate state sigma points
        let mut sigmas_x: Vec<Vector<T, N>> = Vec::with_capacity(2 * N + 1);
        sigmas_x.push(self.x);
        for i in 0..N {
            let mut col = Vector::<T, N>::zeros();
            for r in 0..N {
                col[r] = scaled_l[(r, i)];
            }
            sigmas_x.push(self.x + col);
            sigmas_x.push(self.x - col);
        }

        // Transform through measurement model
        let mut sigmas_z: Vec<Vector<T, M>> = Vec::with_capacity(2 * N + 1);
        for sx in &sigmas_x {
            sigmas_z.push(h(sx));
        }

        // Measurement mean
        let mut z_mean = Vector::<T, M>::zeros();
        for r in 0..M {
            z_mean[r] = wm_0 * sigmas_z[0][r];
        }
        for i in 0..N {
            for r in 0..M {
                z_mean[r] = z_mean[r]
                    + w_i * (sigmas_z[2 * i + 1][r] + sigmas_z[2 * i + 2][r]);
            }
        }

        // Innovation covariance S = Σ wc_i (z_i - z̄)(z_i - z̄)ᵀ + R
        let mut s = Matrix::<T, M, M>::zeros();
        let dz0 = sigmas_z[0] - z_mean;
        for r in 0..M {
            for c in 0..M {
                s[(r, c)] = s[(r, c)] + wc_0 * dz0[r] * dz0[c];
            }
        }
        for i in 0..N {
            let dzp = sigmas_z[2 * i + 1] - z_mean;
            let dzm = sigmas_z[2 * i + 2] - z_mean;
            for r in 0..M {
                for c in 0..M {
                    s[(r, c)] = s[(r, c)]
                        + w_i * (dzp[r] * dzp[c] + dzm[r] * dzm[c]);
                }
            }
        }
        let s_mat = s + *r; // full innovation covariance

        // Cross-covariance Pxz = Σ wc_i (x_i - x̄)(z_i - z̄)ᵀ
        let mut pxz = Matrix::<T, N, M>::zeros();
        let dx0 = sigmas_x[0] - self.x;
        for ri in 0..N {
            for ci in 0..M {
                pxz[(ri, ci)] = pxz[(ri, ci)] + wc_0 * dx0[ri] * dz0[ci];
            }
        }
        for i in 0..N {
            let dxp = sigmas_x[2 * i + 1] - self.x;
            let dxm = sigmas_x[2 * i + 2] - self.x;
            let dzp = sigmas_z[2 * i + 1] - z_mean;
            let dzm = sigmas_z[2 * i + 2] - z_mean;
            for ri in 0..N {
                for ci in 0..M {
                    pxz[(ri, ci)] = pxz[(ri, ci)]
                        + w_i * (dxp[ri] * dzp[ci] + dxm[ri] * dzm[ci]);
                }
            }
        }

        // Kalman gain K = Pxz S⁻¹
        let s_inv = cholesky_with_jitter(&s_mat)
            .map_err(|_| EstimateError::SingularInnovation)?
            .inverse();
        let k = pxz * s_inv;

        // Innovation and NIS = yᵀ S⁻¹ y
        let innovation = *z - z_mean;
        let nis = (innovation.transpose() * s_inv * innovation)[(0, 0)];

        // Update state and covariance: P = P - K·S·Kᵀ (symmetric, manifestly PSD-subtracted)
        self.x = self.x + k * innovation;
        self.p = self.p - k * s_mat * k.transpose();
        let half = T::from(0.5).unwrap();
        self.p = (self.p + self.p.transpose()) * half;
        apply_var_floor(&mut self.p, self.min_variance);

        Ok(nis)
    }

    /// Update with innovation gating — skips state update if NIS exceeds `gate`.
    ///
    /// Returns `Ok(None)` when rejected, `Ok(Some(nis))` when accepted.
    ///
    /// Chi-squared thresholds: M=1 → 99%: 6.63 | M=2 → 9.21 | M=3 → 11.34
    pub fn update_gated(
        &mut self,
        z: &Vector<T, M>,
        h: impl Fn(&Vector<T, N>) -> Vector<T, M>,
        r: &Matrix<T, M, M>,
        gate: T,
    ) -> Result<Option<T>, EstimateError> {
        // Compute NIS without modifying state by running the full sigma-point transform.
        let scaled_l = self.sigma_cholesky()?;
        let (wm_0, wc_0, w_i) = self.weights();

        let mut sigmas_x: Vec<Vector<T, N>> = Vec::with_capacity(2 * N + 1);
        sigmas_x.push(self.x);
        for i in 0..N {
            let mut col = Vector::<T, N>::zeros();
            for r_i in 0..N {
                col[r_i] = scaled_l[(r_i, i)];
            }
            sigmas_x.push(self.x + col);
            sigmas_x.push(self.x - col);
        }

        let mut sigmas_z: Vec<Vector<T, M>> = Vec::with_capacity(2 * N + 1);
        for sx in &sigmas_x {
            sigmas_z.push(h(sx));
        }

        let mut z_mean = Vector::<T, M>::zeros();
        for r_i in 0..M {
            z_mean[r_i] = wm_0 * sigmas_z[0][r_i];
        }
        for i in 0..N {
            for r_i in 0..M {
                z_mean[r_i] = z_mean[r_i]
                    + w_i * (sigmas_z[2 * i + 1][r_i] + sigmas_z[2 * i + 2][r_i]);
            }
        }

        let mut s_mat = Matrix::<T, M, M>::zeros();
        let dz0 = sigmas_z[0] - z_mean;
        for r_i in 0..M {
            for ci in 0..M {
                s_mat[(r_i, ci)] = s_mat[(r_i, ci)] + wc_0 * dz0[r_i] * dz0[ci];
            }
        }
        for i in 0..N {
            let dzp = sigmas_z[2 * i + 1] - z_mean;
            let dzm = sigmas_z[2 * i + 2] - z_mean;
            for r_i in 0..M {
                for ci in 0..M {
                    s_mat[(r_i, ci)] = s_mat[(r_i, ci)]
                        + w_i * (dzp[r_i] * dzp[ci] + dzm[r_i] * dzm[ci]);
                }
            }
        }
        s_mat = s_mat + *r;

        let s_inv = cholesky_with_jitter(&s_mat)
            .map_err(|_| EstimateError::SingularInnovation)?
            .inverse();
        let innovation = *z - z_mean;
        let nis = (innovation.transpose() * s_inv * innovation)[(0, 0)];

        if nis > gate {
            return Ok(None);
        }
        let nis = self.update(z, h, r)?;
        Ok(Some(nis))
    }
}