Spacecraft Control Framework 1.0
Spacecraft Control Library
Public Member Functions | List of all members
UKF Class Reference

Unscented Kalman Filter class. More...

#include <sc_ukf.h>

Public Member Functions

 UKF ()
 Constructor.
 
 ~UKF ()
 Destructor.
 
void set_filter_mode (UKF_mode mode)
 Sets the filter mode. More...
 
void set_filter_parameters (const double alpha, const double kappa, const double beta)
 Sets the filter parameters. More...
 
void set_integrator_time_info (double t, double dt)
 Sets the integrator time and time step. More...
 
void set_initial_values (const ml_matrix &state0, const ml_matrix &covariance0, const ml_matrix &parameter0=ml_matrix())
 Sets the initial state and covariance. More...
 
void set_noise_covariances (const ml_matrix &Rp, const ml_matrix &Rm)
 Sets the noise covariance matrices. More...
 
void set_state_function (state_func state_fun)
 Sets the state function. More...
 
void set_integrator (integ_func integ_fun)
 Sets the integrator function. More...
 
void set_measurement_function (meas_func meas_fun)
 Sets the measurement function. More...
 
void set_context (void *context)
 Sets the context pointer for data needed by the state or measurement functions. More...
 
void set_state (const ml_matrix &state0)
 Sets the current state. More...
 
ml_matrix current_state (void) const
 Returns the current estimated state.
 
ml_matrix current_residual (void) const
 Returns the current residual.
 
ml_matrix current_parameter (void) const
 Returns the current estimated parameter.
 
ml_matrix current_covariance (void) const
 Returns the current estimated covariance.
 
ml_matrix current_residual_covariance (void) const
 Returns the current residual covariance.
 
ml_matrix current_rhs_params (void) const
 Returns the current RHS parameters (only used in parameter mode).
 
void update_estimate (const ml_matrix &measurement)
 Updates the current estimate. More...
 

Detailed Description

Unscented Kalman Filter class.

Implements an unscented Kalman filter (UKF). Operates in two modes: state and parameter.

To create and use a filter, do the following:

  1. Construct a UKF object.
  2. Set the filter mode (state or parameter).
  3. Set the filter parameters.
  4. Set the integrator time information (time and time step).
  5. Set the initial state, covariance, and (only in parameter mode) parameters.
  6. Set the noise covariance matrices (process and measurement).
  7. Set the update functions (state, integrator (for state), and measurement).
  8. Set the context data if needed by the state or measurement functions
  9. Use the filter:
    1. get the current state/parameter/covariance,
    2. set the integrator current time, and
    3. update the filter based on new measurements, as appropriate.
  10. When finished with it, destroy the UKF object.

Member Function Documentation

◆ set_filter_mode()

void UKF::set_filter_mode ( UKF_mode  mode)

Sets the filter mode.

Parameters
modedesired mode (from enum UKF_mode).

◆ set_filter_parameters()

void UKF::set_filter_parameters ( const double  alpha,
const double  kappa,
const double  beta 
)

Sets the filter parameters.

Parameters
alphausually in [.0001,1]
kappa0 for state estimation
beta2 for normally distributed data

◆ set_integrator_time_info()

void UKF::set_integrator_time_info ( double  t,
double  dt 
)

Sets the integrator time and time step.

Parameters
ttime (s)
dttimestep (s)

◆ set_initial_values()

void UKF::set_initial_values ( const ml_matrix &  state0,
const ml_matrix &  covariance0,
const ml_matrix &  parameter0 = ml_matrix() 
)

Sets the initial state and covariance.

Sets the initial state, parameter and covariance.

Parameters
state0state (nx1)
covariance0covariance (nxn)
parameter0parameter (nx1) (not used in state mode)

◆ set_noise_covariances()

void UKF::set_noise_covariances ( const ml_matrix &  Rp,
const ml_matrix &  Rm 
)

Sets the noise covariance matrices.

Parameters
Rpnoise covariance matrix (nxn)
Rmmeasurement covariance matrix (mxm)

◆ set_state_function()

void UKF::set_state_function ( state_func  state_fun)

Sets the state function.

Sets the state function, which is the right hand side of the state update.

Parameters
state_funa function pointer to a state_func function

◆ set_integrator()

void UKF::set_integrator ( integ_func  integ_fun)

Sets the integrator function.

Sets the integrator function used to propagate the state.

Parameters
integ_funa function pointer to a integ_func function

◆ set_measurement_function()

void UKF::set_measurement_function ( meas_func  meas_fun)

Sets the measurement function.

Parameters
meas_funa function pointer to a meas_func function

◆ set_context()

void UKF::set_context ( void *  context)

Sets the context pointer for data needed by the state or measurement functions.

Sets the context pointer that will be passed in to the other functions.

Parameters
*contexta function pointer to a meas_func function

◆ set_state()

void UKF::set_state ( const ml_matrix &  state0)

Sets the current state.

Sets the state.

Parameters
state0state (nx1)

◆ update_estimate()

void UKF::update_estimate ( const ml_matrix &  measurement)

Updates the current estimate.

Parameters
measurementupdated measurement vector (mx1)