Estimation processes measurements to refine a spacecraft's state -- position, velocity, and optionally additional parameters -- beyond what the dynamics model alone can predict. Brahe provides an Extended Kalman Filter (EKF) with built-in and custom measurement models. The primary workflow is: create a filter with an initial state estimate, feed it observations, and read the refined state.
Set up an EKF with a propagator, measurement model, and initial covariance, then process observations sequentially. The filter propagates state and covariance to each observation epoch and incorporates the measurement to produce an updated estimate.
importnumpyasnpimportbraheasbh# Initialize EOP data for frame transformationsbh.initialize_eop()# Define a LEO circular orbitepoch=bh.Epoch(2024,1,1,0,0,0.0)r=bh.R_EARTH+500e3v=(bh.GM_EARTH/r)**0.5true_state=np.array([r,0.0,0.0,0.0,v,0.0])# Create a truth propagator for generating observationstruth_prop=bh.NumericalOrbitPropagator(epoch,true_state,bh.NumericalPropagationConfig.default(),bh.ForceModelConfig.two_body(),)# Perturbed initial state: 1 km position error, 1 m/s velocity errorinitial_state=true_state.copy()initial_state[0]+=1000.0initial_state[4]+=1.0# Initial covariance reflecting our uncertaintyp0=np.diag([1e6,1e6,1e6,1e2,1e2,1e2])# Create the EKF with inertial position measurements (10 m noise)ekf=bh.ExtendedKalmanFilter(epoch,initial_state,p0,measurement_models=[bh.InertialPositionMeasurementModel(10.0)],propagation_config=bh.NumericalPropagationConfig.default(),force_config=bh.ForceModelConfig.two_body(),)# Process 30 observations at 60-second intervalsdt=60.0foriinrange(1,31):obs_epoch=epoch+dt*itruth_prop.propagate_to(obs_epoch)truth_pos=truth_prop.current_state()[:3]obs=bh.Observation(obs_epoch,truth_pos,model_index=0)ekf.process_observation(obs)# Compare final state to truthtruth_prop.propagate_to(ekf.current_epoch())truth_final=truth_prop.current_state()final_state=ekf.current_state()pos_error=np.linalg.norm(final_state[:3]-truth_final[:3])vel_error=np.linalg.norm(final_state[3:6]-truth_final[3:6])print("Initial position error: 1000.0 m")print(f"Final position error: {pos_error:.2f} m")print(f"Final velocity error: {vel_error:.4f} m/s")print(f"Observations processed: {len(ekf.records())}")# Show final covariance diagonal (1-sigma uncertainties)cov=ekf.current_covariance()sigma=np.sqrt(np.diag(cov))print("\n1-sigma uncertainties:")print(f" Position: [{sigma[0]:.1f}, {sigma[1]:.1f}, {sigma[2]:.1f}] m")print(f" Velocity: [{sigma[3]:.4f}, {sigma[4]:.4f}, {sigma[5]:.4f}] m/s")
usebraheasbh;usenalgebra::{DMatrix,DVector};fnmain(){bh::initialize_eop().unwrap();// Define a LEO circular orbitletepoch=bh::time::Epoch::from_datetime(2024,1,1,0,0,0.0,0.0,bh::time::TimeSystem::UTC);letr=bh::constants::physical::R_EARTH+500e3;letv=(bh::constants::physical::GM_EARTH/r).sqrt();lettrue_state=DVector::from_vec(vec![r,0.0,0.0,0.0,v,0.0]);// Create a truth propagator for generating observationsletmuttruth_prop=bh::propagators::DNumericalOrbitPropagator::new(epoch,true_state.clone(),bh::propagators::NumericalPropagationConfig::default(),bh::propagators::force_model_config::ForceModelConfig::two_body_gravity(),None,None,None,None,).unwrap();// Perturbed initial state: 1 km position error, 1 m/s velocity errorletmutinitial_state=true_state.clone();initial_state[0]+=1000.0;initial_state[4]+=1.0;// Initial covariance reflecting uncertaintyletp0=DMatrix::from_diagonal(&DVector::from_vec(vec![1e6,1e6,1e6,1e2,1e2,1e2,]));// Create the EKF with flat constructorletmodels:Vec<Box<dynbh::estimation::MeasurementModel>>=vec![Box::new(bh::estimation::InertialPositionMeasurementModel::new(10.0)),];letmutekf=bh::estimation::ExtendedKalmanFilter::new(epoch,initial_state,p0,bh::propagators::NumericalPropagationConfig::default(),bh::propagators::force_model_config::ForceModelConfig::two_body_gravity(),None,None,None,models,bh::estimation::EKFConfig::default(),).unwrap();// Process 30 observations at 60-second intervalsletdt=60.0;foriin1..=30{letobs_epoch=epoch+dt*iasf64;truth_prop.propagate_to(obs_epoch);lettruth_pos=truth_prop.current_state().rows(0,3).into_owned();letobs=bh::estimation::Observation::new(obs_epoch,truth_pos,0);ekf.process_observation(&obs).unwrap();}// Compare final state to truthusebh::propagators::traits::DStatePropagator;truth_prop.propagate_to(ekf.current_epoch());lettruth_final=truth_prop.current_state();letfinal_state=ekf.current_state();letpos_error=(final_state.rows(0,3)-truth_final.rows(0,3)).norm();letvel_error=(final_state.rows(3,3)-truth_final.rows(3,3)).norm();println!("Initial position error: 1000.0 m");println!("Final position error: {:.2} m",pos_error);println!("Final velocity error: {:.4} m/s",vel_error);println!("Observations processed: {}",ekf.records().len());// Show final covariance diagonal (1-sigma uncertainties)ifletSome(cov)=ekf.current_covariance(){println!("\n1-sigma uncertainties:");println!(" Position: [{:.1}, {:.1}, {:.1}] m",cov[(0,0)].sqrt(),cov[(1,1)].sqrt(),cov[(2,2)].sqrt());println!(" Velocity: [{:.4}, {:.4}, {:.4}] m/s",cov[(3,3)].sqrt(),cov[(4,4)].sqrt(),cov[(5,5)].sqrt());}}
Initial position error: 1000.0 m
Final position error: 0.01 m
Final velocity error: 0.0000 m/s
Observations processed: 30
1-sigma uncertainties:
Position: [3.2, 4.2, 3.1] m
Velocity: [0.0027, 0.0068, 0.0029] m/s
Initial position error: 1000.0 m
Final position error: 0.01 m
Final velocity error: 0.0000 m/s
Observations processed: 30
1-sigma uncertainties:
Position: [3.2, 4.2, 3.1] m
Velocity: [0.0027, 0.0068, 0.0029] m/s
The EKF constructor accepts an initial epoch, state, covariance, one or more measurement models, and propagation configuration. Internally it builds a numerical orbit propagator with STM (State Transition Matrix) propagation enabled -- the STM drives covariance prediction between observations. Each call to process_observation() performs a predict step (propagate to observation time) followed by an update step (incorporate the measurement via Kalman gain).
Measurement models define the observation function \(h(\mathbf{x}, t)\) that maps a state vector to a predicted measurement. Built-in models handle GPS-like position and velocity observations in both inertial and ECEF frames. Custom models can be defined in Python by subclassing MeasurementModel.
The Extended Kalman Filter orchestrates the estimation loop. It owns a numerical propagator for state and covariance prediction and a list of measurement models for incorporating observations. Different measurement types can arrive at different times -- each Observation carries a model_index indicating which model to use.
Filter records capture the full diagnostic state at each update: pre-fit state, post-fit state, pre-fit and post-fit residuals, covariance, and Kalman gain. These enable analysis of filter performance, consistency checks, and residual monitoring.
The current release includes two sequential filters:
Extended Kalman Filter (EKF) -- linearizes dynamics and measurements using STM and Jacobians. Efficient (one propagation per step) and well-suited for mildly nonlinear problems.
Unscented Kalman Filter (UKF) -- propagates sigma points through true nonlinear functions without linearization. More robust for strongly nonlinear problems, at the cost of 2n+1 propagations per step.
Batch Least Squares (BLS) -- processes all observations simultaneously, iterating to minimize the weighted sum of squared residuals. Best for offline orbit determination with complete observation arcs. Supports two solver formulations and consider parameters.
All estimators share the same measurement models, observation types, and Python API.