This guide covers sensor noise modeling utilities for simulating realistic IMU (Inertial Measurement Unit) errors in flight simulation and navigation filter development.
Quick Start
#include <random>
std::mt19937 rng(42);
std::normal_distribution<double> dist(0.0, 1.0);
for (int j = 0; j < 3; ++j) {
}
IMUNoiseState< Scalar > init_state()
Initialize IMU noise state.
Definition AllanVarianceNoise.hpp:139
sensors::IMUNoiseSample< Scalar > step(IMUNoiseState< Scalar > &state, const IMUNoiseCoeffs &coeffs, const IMUNoiseInput< Scalar > &input)
Step the complete IMU noise model.
Definition AllanVarianceNoise.hpp:213
IMUNoiseCoeffs consumer_grade_coeffs(double dt)
Compute coefficients for consumer-grade IMU.
Definition AllanVarianceNoise.hpp:277
Noise Model Overview
Vulcan implements five fundamental sensor noise processes:
| Noise Type | Allan Slope | Parameter | Physical Source |
| White Noise (ARW/VRW) | -1/2 | N | Quantization, thermal noise |
| Bias Instability | 0 | B | Electronics drift |
| Rate Random Walk | +1/2 | K | Slow environmental effects |
| First-Order Markov | varies | σ, τ | Correlated disturbances |
Gaussian White Noise
Simple scaling of unit-variance noise:
double noise_sample = dist(rng);
double sigma = 0.01;
double N = 8.7e-5;
double dt = 0.01;
double sigma_from_arw(double N, double dt)
Compute white noise gain from Allan variance N parameter.
Definition GaussianNoise.hpp:96
Scalar apply(const Scalar &noise_input, double sigma)
Apply Gaussian white noise scaling.
Definition GaussianNoise.hpp:27
Random Walk (Drift)
Integrated white noise modeling sensor drift:
double K = 1e-6;
double dt = 0.01;
double t = 100.0;
double expected_variance(double K, double t)
Compute expected variance at given time.
Definition RandomWalk.hpp:120
Scalar step(State< Scalar > &state, const Coeffs &coeffs, const Scalar &noise_input)
Step the random walk process.
Definition RandomWalk.hpp:80
State< Scalar > init_state()
Initialize random walk state to zero.
Definition RandomWalk.hpp:32
Coeffs compute_coeffs(double K, double dt)
Compute random walk coefficients.
Definition RandomWalk.hpp:60
Bias Instability
Long-correlation-time Markov process for slow bias wandering:
double sigma_b = 4.8e-6;
double tau = 300.0;
double dt = 0.01;
State< Scalar > init_state()
Initialize state to zero bias.
Definition BiasInstability.hpp:34
Scalar step(State< Scalar > &state, const Coeffs &coeffs, const Scalar &noise_input)
Step the bias instability process.
Definition BiasInstability.hpp:96
Coeffs compute_coeffs(double sigma_b, double tau, double dt)
Compute bias instability coefficients.
Definition BiasInstability.hpp:73
First-Order Markov Process
General exponentially correlated noise:
double tau = 10.0;
double sigma = 0.1;
double dt = 0.01;
double autocorrelation(double tau, double sigma, double tau_lag)
Compute autocorrelation at lag τ_lag.
Definition MarkovProcess.hpp:180
double psd_at_frequency(double tau, double sigma, double f)
Compute power spectral density at frequency f.
Definition MarkovProcess.hpp:197
Coeffs discretize(double tau, double sigma, double dt)
Discretize first-order Markov process.
Definition MarkovProcess.hpp:84
Scalar step(State< Scalar > &state, const Coeffs &coeffs, const Scalar &noise_input)
Step the first-order Markov process.
Definition MarkovProcess.hpp:139
State< Scalar > init_state()
Initialize state to zero.
Definition MarkovProcess.hpp:35
Allan Variance Composite Model
Complete IMU noise model combining all processes:
.N = 2.9e-5,
.B = 4.8e-6,
.K = 1.0e-8,
.tau_bias = 300.0,
};
.N = 1.0e-3,
.B = 1.0e-4,
.K = 3.0e-6,
.tau_bias = 300.0,
};
IMUNoiseCoeffs compute_coeffs(const sensors::AllanParams< double > &gyro_params, const sensors::AllanParams< double > &accel_params, double dt)
Compute IMU coefficients from Allan parameters.
Definition AllanVarianceNoise.hpp:172
Allan variance noise parameters for IMU sensors.
Definition NoiseTypes.hpp:25
IMU Grade Presets
| Grade | Gyro ARW | Gyro Bias | Typical Application |
| Consumer | 0.3°/√hr | 10°/hr | Smartphones, drones |
| Industrial | 0.1°/√hr | 1°/hr | Robotics, vehicles |
| Tactical | 0.01°/√hr | 0.1°/hr | Military, aerospace |
| Navigation | 0.001°/√hr | 0.01°/hr | Aircraft, submarines |
Symbolic Computation
All noise models work with janus::SymbolicScalar:
using Scalar = janus::SymbolicScalar;
auto w1 = janus::sym("w_arw");
auto w2 = janus::sym("w_bias");
auto w3 = janus::sym("w_rrw");
janus::Function f("imu_noise", {w1, w2, w3}, {output});
AxisCoeffs compute_axis_coeffs(const sensors::AllanParams< double > ¶ms, double dt)
Compute per-axis coefficients from Allan parameters.
Definition AllanVarianceNoise.hpp:70
AxisState< Scalar > init_axis_state()
Initialize per-axis state to zero.
Definition AllanVarianceNoise.hpp:39
Scalar step_axis(AxisState< Scalar > &state, const AxisCoeffs &coeffs, const Scalar &noise_arw, const Scalar &noise_bias, const Scalar &noise_rrw)
Step single-axis noise model.
Definition AllanVarianceNoise.hpp:102
AllanParams< double > industrial_gyro()
Industrial-grade MEMS gyroscope.
Definition NoiseTypes.hpp:109
Graph Visualization
janus::export_graph_html(output, "graph_imu_noise", "IMU_Noise");
API Reference
NoiseTypes.hpp
| Type | Description |
| AllanParams<Scalar> | N, B, K, τ_bias parameters |
| IMUNoiseSample<Scalar> | 3-axis gyro + accel noise vectors |
| imu_grades::consumer_gyro() | Preset Allan parameters |
| imu_grades::industrial_gyro() | ... |
| imu_grades::tactical_gyro() | ... |
| imu_grades::navigation_gyro() | ... |
GaussianNoise.hpp
| Function | Description |
| apply(noise, σ) | Scale noise by σ |
| apply_psd(noise, psd, dt) | Scale from PSD |
| sigma_from_arw(N, dt) | Convert Allan N to discrete σ |
RandomWalk.hpp
| Function | Description |
| init_state<Scalar>() | Initialize to zero |
| compute_coeffs(K, dt) | Discretize coefficients |
| step(state, coeffs, noise) | Integrate one step |
| expected_variance(K, t) | K²·t |
BiasInstability.hpp
| Function | Description |
| init_state<Scalar>() | Initialize to zero |
| compute_coeffs(σ_b, τ, dt) | Discretize Markov process |
| step(state, coeffs, noise) | Update bias |
MarkovProcess.hpp
| Function | Description |
| init_state<Scalar>() | Initialize to zero |
| discretize(τ, σ, dt) | Exact discretization |
| step(state, coeffs, noise) | Update state |
| autocorrelation(τ, σ, lag) | R(lag) = σ²·exp(-|lag|/τ) |
| psd_at_frequency(τ, σ, f) | Lorentzian PSD |
AllanVarianceNoise.hpp
| Function | Description |
| init_state<Scalar>() | Initialize 6-axis IMU state |
| compute_coeffs(gyro, accel, dt) | From Allan params |
| step(state, coeffs, input) | Full 6-axis step |
| consumer_grade_coeffs(dt) | Preset coefficients |
Example: Sensor Noise Demo
See examples/sensors/sensor_noise_demo.cpp:
./scripts/build.sh
./build/examples/sensor_noise_demo
Output shows:
- IMU grade parameter comparison
- Gyroscope noise time series
- Bias instability accumulation
- Random walk drift growth
- Symbolic graph generation