Skip to article frontmatterSkip to article content

ScenarioRunner

Open In Colab

Overview

The ScenarioRunner class is a utility designed for testing IMU preintegration and factors. It takes a ground truth trajectory defined by a Scenario object, along with IMU parameters (PreintegrationParams or PreintegrationCombinedParams) and a specified IMU bias, and simulates the measurements an IMU would produce while following that trajectory.

Key capabilities include:

  • Calculating the ideal specific force and angular velocity at any time t based on the scenario’s motion.
  • Generating noisy IMU measurements by adding the specified bias and sampling from the noise models defined in the parameters.
  • Integrating these simulated measurements over a time interval T to produce a PreintegratedImuMeasurements or PreintegratedCombinedMeasurements object.
  • Predicting the final state based on an initial state and a preintegrated measurement object.
  • Estimating the covariance of the preintegrated measurements or the prediction error via Monte Carlo simulation (useful for verifying the analytical covariance propagation).

Measurement Simulation

  • actualAngularVelocity(t): Returns the true angular velocity ωb(t)\omega_b(t) from the Scenario.
  • actualSpecificForce(t): Calculates the true specific force (what an ideal accelerometer measures) in the body frame. This is the body-frame acceleration ab(t)a_b(t) minus the body-frame representation of gravity gb(t)g_b(t):
    fb(t)=ab(t)Rbn(t)gn=Rbn(t)(an(t)gn)f_b(t) = a_b(t) - R_{bn}(t) g_n = R_{bn}(t) (a_n(t) - g_n)
    where gng_n is the gravity vector defined in PreintegrationParams.
  • measuredAngularVelocity(t): Adds bias and sampled noise to actualAngularVelocity(t).
    ωmeasured=ωb(t)+bg+ηgd\omega_{measured} = \omega_b(t) + b_g + \eta_{gd}
    where bgb_g is the gyro bias and ηgd\eta_{gd} is sampled discrete gyro noise.
  • measuredSpecificForce(t): Adds bias and sampled noise to actualSpecificForce(t).
    ameasured=fb(t)+ba+ηada_{measured} = f_b(t) + b_a + \eta_{ad}
    where bab_a is the accelerometer bias and ηad\eta_{ad} is sampled discrete accelerometer noise.

Key Functionality / API

  • Constructor: ScenarioRunner(scenario, params, imuSampleTime=0.01, bias=ConstantBias()): Takes the scenario, IMU parameters, sample rate, and the true bias to apply to measurements.
  • Measurement Methods: actual...(), measured...() as described above.
  • integrate(T, estimatedBias, corrupted=True): Simulates measurements at imuSampleTime intervals for a duration T, optionally adding noise (corrupted=True), and integrates them into a PIM object using estimatedBias as the biasHat for the PIM.
  • predict(pim, estimatedBias): Uses the provided PIM (which contains ΔR,Δp,Δv\Delta R, \Delta p, \Delta v) and an estimatedBias to predict the final NavState starting from the scenario’s initial state at t=0t=0.
  • estimateCovariance(T, N, estimatedBias): Performs Monte Carlo simulation: runs integrate N times with different noise samples, calculates the predicted state for each, and computes the sample covariance of the 9D tangent space difference between the Monte Carlo predictions and the mean prediction. Used to verify pim.preintMeasCov().
  • estimateNoiseCovariance(N): Samples noise N times and computes the sample covariance, to verify the noise samplers themselves.

There is also a CombinedScenarioRunner inheriting from ScenarioRunner that works with PreintegrationCombinedParams and PreintegratedCombinedMeasurements.

Usage Example

Using the AcceleratingScenario from the Scenario example to generate measurements and verify prediction.

import gtsam
import numpy as np

# --- 1. Define Scenario --- 
initial_pose_accel = gtsam.Pose3() 
initial_vel_n = np.array([0.0, 0.0, 0.0])
const_accel_n = np.array([0.5, 0.0, 0.0]) # Accelerate along nav X (ENU)
const_omega_b = np.array([0.0, 0.0, 0.0]) # No rotation
scenario = gtsam.AcceleratingScenario(
    initial_pose_accel.rotation(), initial_pose_accel.translation(),
    initial_vel_n, const_accel_n, const_omega_b
)

# --- 2. Define IMU Params and Runner --- 
# Use default ENU parameters (Z-up, g=-9.81)
params = gtsam.PreintegrationParams.MakeSharedU(9.81)
# Add some noise (variances)
params.setAccelerometerCovariance(np.eye(3) * 0.01)
params.setGyroscopeCovariance(np.eye(3) * 0.0001)
params.setIntegrationCovariance(np.eye(3) * 1e-9)

imu_sample_dt = 0.01 # 100 Hz
# Define the *true* bias applied to the measurements
true_bias = gtsam.imuBias.ConstantBias(np.array([0.05, -0.05, 0.1]), 
                                       np.array([0.01, -0.01, 0.02]))

runner = gtsam.ScenarioRunner(scenario, params, imu_sample_dt, true_bias)

# --- 3. Integrate Measurements --- 
integration_time = 2.0 # seconds

# Define the bias *estimate* to be used during preintegration
# Let's assume we have a slightly wrong estimate
estimated_bias = gtsam.imuBias.ConstantBias(np.array([0.04, -0.04, 0.09]), 
                                            np.array([0.005, -0.005, 0.015]))

# Integrate noisy measurements using the 'estimated_bias' as biasHat for the PIM
pim = runner.integrate(integration_time, estimatedBias=estimated_bias, corrupted=True)

print(f"--- Integration Results (T={integration_time}s) ---")
print("Bias Hat used in PIM:")
pim.biasHat().print()
print("PIM Delta R:")
pim.deltaRij().print()
print("PIM Delta P:", pim.deltaPij())
print("PIM Delta V:", pim.deltaVij())

# --- 4. Predict State --- 
# Predict the state at integration_time using the PIM and the *same* estimated_bias
initial_state_actual = scenario.navState(0.0)
predicted_state = runner.predict(pim, estimated_bias)

# Get the ground truth state at the end time
ground_truth_state = scenario.navState(integration_time)

print(f"\n--- Prediction vs Ground Truth (T={integration_time}s) ---")
print("Predicted State:")
predicted_state.print()
print("\nGround Truth State:")
ground_truth_state.print()

# Calculate the error (difference in tangent space)
prediction_error = predicted_state.localCoordinates(ground_truth_state)
print("\nPrediction Error (Logmap(predicted^-1 * ground_truth)):\n", prediction_error)
# Note: Error is non-zero due to noise and bias estimation error used in PIM.
--- Integration Results (T=2.0s) ---
Bias Hat used in PIM:
acc =  0.04 -0.04  0.09 gyro =  0.005 -0.005  0.015
PIM Delta R:
R: [
	0.9998, -0.00700878, -0.0187374;
	0.00661627, 0.999759, -0.0209287;
	0.0188796, 0.0208006, 0.999605
]
PIM Delta P: [ 0.70090612 -0.06192379 19.6232812 ]
PIM Delta V: [ 0.62536677 -0.17585342 19.47976488]

--- Prediction vs Ground Truth (T=2.0s) ---
Predicted State:
R: [
	0.9998, -0.00700878, -0.0187374;
	0.00661627, 0.999759, -0.0209287;
	0.0188796, 0.0208006, 0.999605
]
p:   0.700906 -0.0619238  0.0032812
v:  0.625367 -0.175853 -0.140235

Ground Truth State:
R: [
	1, 0, 0;
	0, 1, 0;
	0, 0, 1
]
p: 1 0 0
v: 1 0 0

Prediction Error (Logmap(predicted^-1 * ground_truth)):
 [-0.02086757  0.01881111 -0.00681348  0.29938178  0.05974434 -0.01018013
  0.37836933  0.1761023   0.12947973]