measurement_model (MeasurementModel, optional) – The measurement model used to generate the measurement prediction.
Should be used in cases where the measurement model is dependent
on the received measurement. The default is None, in which case
the updater will use the measurement model specified on
initialisation
measurement_noise (bool) – Whether to include measurement noise predicted measurement. Default True
A class which embodies Kalman-type updaters; also a class which
performs measurement update step as in the standard Kalman filter.
The Kalman updaters assume \(h(\mathbf{x}) = H \mathbf{x}\) with
additive noise \(\sigma = \mathcal{N}(0,R)\). Daughter classes can
overwrite to specify a more general measurement model
\(h(\mathbf{x})\).
update() first calls predict_measurement() function which
proceeds by calculating the predicted measurement, innovation covariance
and measurement cross-covariance,
measurement_model (LinearGaussian, optional) – A linear Gaussian measurement model. This need not be defined if a measurement model is provided in the measurement. If no model specified on construction, or in the measurement, then error will be thrown.
force_symmetric_covariance (bool, optional) – A flag to force the output covariance matrix to be symmetric by way of a simple geometric combination of the matrix and transpose. Default is False.
use_joseph_cov (bool, optional) – Bool dictating the method of covariance calculation. If use_joseph_cov is True then the Joseph form of the covariance equation is used.
A linear Gaussian measurement model. This need not be defined if a measurement model is provided in the measurement. If no model specified on construction, or in the measurement, then error will be thrown.
The Kalman update method. Given a hypothesised association between
a predicted state or predicted measurement and an actual measurement,
calculate the posterior state.
Parameters:
hypothesis (SingleHypothesis) – the prediction-measurement association hypothesis. This hypothesis
may carry a predicted measurement, or a predicted state. In the
latter case a predicted measurement will be calculated.
The Extended Kalman Filter version of the Kalman Updater. Inherits most
of the functionality from KalmanUpdater.
The difference is that the measurement model may now be non-linear, though
must be differentiable to return the linearisation of \(h(\mathbf{x})\)
via the matrix \(H\) accessible via jacobian().
Parameters:
measurement_model (MeasurementModel, optional) – A measurement model. This need not be defined if a measurement model is provided in the measurement. If no model specified on construction, or in the measurement, then error will be thrown. Must be linear or capable or implement the jacobian().
force_symmetric_covariance (bool, optional) – A flag to force the output covariance matrix to be symmetric by way of a simple geometric combination of the matrix and transpose. Default is False.
use_joseph_cov (bool, optional) – Bool dictating the method of covariance calculation. If use_joseph_cov is True then the Joseph form of the covariance equation is used.
A measurement model. This need not be defined if a measurement model is provided in the measurement. If no model specified on construction, or in the measurement, then error will be thrown. Must be linear or capable or implement the jacobian().
The Unscented Kalman Filter version of the Kalman Updater. Inherits most
of the functionality from KalmanUpdater.
In this case the predict_measurement() function uses the
unscented_transform() function to estimate a (Gaussian) predicted
measurement. This is then updated via the standard Kalman update equations.
Parameters:
measurement_model (MeasurementModel, optional) – The measurement model to be used. This need not be defined if a measurement model is provided in the measurement. If no model specified on construction, or in the measurement, then error will be thrown.
force_symmetric_covariance (bool, optional) – A flag to force the output covariance matrix to be symmetric by way of a simple geometric combination of the matrix and transpose. Default is False.
use_joseph_cov (bool, optional) – Bool dictating the method of covariance calculation. If use_joseph_cov is True then the Joseph form of the covariance equation is used.
alpha (float, optional) – Primary sigma point spread scaling parameter. Default is 0.5.
beta (float, optional) – Used to incorporate prior knowledge of the distribution. If the true distribution is Gaussian, the value of 2 is optimal. Default is 2
kappa (float, optional) – Secondary spread scaling parameter. Default is calculated as 3-Ns
The measurement model to be used. This need not be defined if a measurement model is provided in the measurement. If no model specified on construction, or in the measurement, then error will be thrown.
measurement_model (MeasurementModel, optional) – The measurement model used to generate the measurement prediction.
This should be used in cases where the measurement model is
dependent on the received measurement (the default is None, in
which case the updater will use the measurement model specified on
initialisation)
measurement_noise (bool) – Whether to include measurement noise \(R\) with innovation covariance
The input State is a SqrtGaussianState which means
that the covariance of the predicted state is stored in square root form.
This can be achieved by keeping covar attribute as \(L\) where
the ‘full’ covariance matrix \(P_{k|k-1} = L_{k|k-1} L^T_{k|k-1}\)
[Eq1].
In its basic form \(L\) is the lower triangular matrix returned via
Cholesky factorisation. There’s no reason why other forms that satisfy Eq 1
above can’t be used.
References
Schmidt, S.F. 1970, Computational techniques in Kalman filtering, NATO advisory group for
aerospace research and development, London 1970
Andrews, A. 1968, A square root formulation of the Kalman covariance equations, AIAA
Journal, 6:6, 1165-1166
Parameters:
measurement_model (MeasurementModel, optional) – A measurement model. This need not be defined if a measurement model is provided in the measurement. If no model specified on construction, or in the measurement, then error will be thrown. Must be linear or capable or implement the jacobian().
force_symmetric_covariance (bool, optional) – A flag to force the output covariance matrix to be symmetric by way of a simple geometric combination of the matrix and transpose. Default is False.
use_joseph_cov (bool, optional) – Bool dictating the method of covariance calculation. If use_joseph_cov is True then the Joseph form of the covariance equation is used.
qr_method (bool, optional) – A switch to do the update via a QR decomposition, rather than using the (vector form of) the Potter method.
This version of the Kalman updater runs an iteration over the linearisation of the
sensor function in order to refine the posterior state estimate. Specifically,
It inherits from the ExtendedKalmanUpdater as it uses the same linearisation of the sensor
function via the _measurement_matrix() function.
Parameters:
measurement_model (MeasurementModel, optional) – A measurement model. This need not be defined if a measurement model is provided in the measurement. If no model specified on construction, or in the measurement, then error will be thrown. Must be linear or capable or implement the jacobian().
force_symmetric_covariance (bool, optional) – A flag to force the output covariance matrix to be symmetric by way of a simple geometric combination of the matrix and transpose. Default is False.
use_joseph_cov (bool, optional) – Bool dictating the method of covariance calculation. If use_joseph_cov is True then the Joseph form of the covariance equation is used.
tolerance (float, optional) – The value of the difference in the measure used as a stopping criterion.
measure (Measure, optional) – The measure to use to test the iteration stopping criterion. Defaults to the Euclidean distance between current and prior posterior state estimate.
max_iterations (int, optional) – Number of iterations before while loop is exited and a non-convergence warning is returned
The iterated Kalman update method. Given a hypothesised association between a predicted
state or predicted measurement and an actual measurement,
calculate the posterior state.
Parameters:
hypothesis (SingleHypothesis) – the prediction-measurement association hypothesis. This hypothesis
may carry a predicted measurement, or a predicted state. In the
latter case a predicted measurement will be calculated.
**kwargs (various) – These are passed to the measurement model function
Returns:
The posterior state Gaussian with mean \(\mathbf{x}_{k|k}\) and
covariance \(P_{k|k}\)
A class which extends the standard Kalman filter to employ the Schmidt-Kalman version of
the update. The key thing here is that the state vector is split into parameters to be
estimated, and those which are merely ‘considered’. The consider parameters are not updated,
though their relative covariances are maintained through the process. The state vector,
covariance and measurement matrix are defined as,
where the consider parameters are denoted \(p\) and those to be estimated \(s\). Note
that though they are separated in the definition above, they may be interleaved in practice.
The update proceeds as:
Due to the excellent efficiency of NumPy’s matrix algebra tools, the savings gained by
extracting a sub-matrix over performing the calculation on full matrices, are relatively
minor. This class therefore functions most effectively as a tutorial example of the
Schmidt-Kalman updater. Efficiencies could be made by enforcing view operations rather than
copies, using the square-root form or, most promisingly, by employing Cython.
References
[1] S. F. Schmidt, “Application of State-Space Methods to Navigation Problems,” Advances in
Control Systems, Vol. 3, 1966, pp. 293–340
[2] Zanetti, R. & D’Souza, C. (2013). Recursive Implementations of the Schmidt-Kalman
‘Consider’ Filter. The Journal of the Astronautical Sciences. 60. 672-685.
10.1007/s40295-015-0068-7.
Parameters:
measurement_model (MeasurementModel, optional) – A measurement model. This need not be defined if a measurement model is provided in the measurement. If no model specified on construction, or in the measurement, then error will be thrown. Must be linear or capable or implement the jacobian().
force_symmetric_covariance (bool, optional) – A flag to force the output covariance matrix to be symmetric by way of a simple geometric combination of the matrix and transpose. Default is False.
use_joseph_cov (bool, optional) – Bool dictating the method of covariance calculation. If use_joseph_cov is True then the Joseph form of the covariance equation is used.
consider (numpy.ndarray, optional) – The boolean vector of ‘consider’ parameters. True indicates considered, False are state parameters to be estimated. If undefined these default to all False, i.e.the standard Kalman filter.
The boolean vector of ‘consider’ parameters. True indicates considered, False are state parameters to be estimated. If undefined these default to all False, i.e.the standard Kalman filter.
The cubature Kalman filter version of the Kalman updater. Inherits most of its functionality
from KalmanUpdater.
The predict_measurement() function uses the cubature_transform() function to
estimate a (Gaussian) predicted measurement. This is then updated via the standard Kalman
update equations.
Parameters:
measurement_model (MeasurementModel, optional) – The measurement model to be used. This need not be defined if a measurement model is provided in the measurement. If no model specified on construction, or in the measurement, then error will be thrown.
force_symmetric_covariance (bool, optional) – A flag to force the output covariance matrix to be symmetric by way of a simple geometric combination of the matrix and transpose. Default is False.
use_joseph_cov (bool, optional) – Bool dictating the method of covariance calculation. If use_joseph_cov is True then the Joseph form of the covariance equation is used.
alpha (float, optional) – Scaling parameter. Default is 1.0. Lower values select points closer to the mean and vice versa.
The measurement model to be used. This need not be defined if a measurement model is provided in the measurement. If no model specified on construction, or in the measurement, then error will be thrown.
measurement_model (MeasurementModel, optional) – The measurement model used to generate the measurement prediction.
This should be used in cases where the measurement model is
dependent on the received measurement (the default is None, in
which case the updater will use the measurement model specified on
initialisation)
measurement_noise (bool) – Whether to include measurement noise \(R\) with innovation covariance.
Default True
Perform an update by multiplying particle weights by PDF of measurement
model (either measurement_model or
measurement_model), and normalising the weights. If provided, a
resampler will be used to take a new sample of particles (this is
called every time, and it’s up to the resampler to decide if resampling is
required).
resampler (Resampler, optional) – Resampler to prevent particle degeneracy
regulariser (Regulariser, optional) – Regulariser to prevent particle impoverishment. The regulariser is normally used after resampling. If a Resampler is defined, then regularisation will only take place if the particles have been resampled. If the Resampler is not defined but a Regulariser is, then regularisation will be conducted under the assumption that the user intends for this to occur.
constraint_func (Callable, optional) – Callable, user defined function for applying constraints to the states. This is done by setting the weights of particles to 0 for particles that are not correctly constrained. This function provides indices of the unconstrained particles and should accept a ParticleState object and return an array-like object of logical indices.
Regulariser to prevent particle impoverishment. The regulariser is normally used after resampling. If a Resampler is defined, then regularisation will only take place if the particles have been resampled. If the Resampler is not defined but a Regulariser is, then regularisation will be conducted under the assumption that the user intends for this to occur.
Callable, user defined function for applying constraints to the states. This is done by setting the weights of particles to 0 for particles that are not correctly constrained. This function provides indices of the unconstrained particles and should accept a ParticleState object and return an array-like object of logical indices.
measurement_model (MeasurementModel, optional) – The measurement model used to generate the measurement prediction.
Should be used in cases where the measurement model is dependent
on the received measurement. The default is None, in which case
the updater will use the measurement model specified on
initialisation
measurement_noise (bool) – Whether to include measurement noise predicted measurement. Default True
This is implementation of Gromov method for stochastic particle flow
filters [2]. The Euler Maruyama method is used for integration, over 20
steps using an exponentially increase step size.
measurement_model (MeasurementModel, optional) – The measurement model used to generate the measurement prediction.
Should be used in cases where the measurement model is dependent
on the received measurement. The default is None, in which case
the updater will use the measurement model specified on
initialisation
measurement_noise (bool) – Whether to include measurement noise predicted measurement. Default True
kalman_updater (KalmanUpdater, optional) – Kalman updater to use. Default None where a new instance of:class:~.ExtendedKalmanUpdater will be created utilising thesame measurement model.
measurement_model (MeasurementModel, optional) – The measurement model used to generate the measurement prediction.
Should be used in cases where the measurement model is dependent
on the received measurement. The default is None, in which case
the updater will use the measurement model specified on
initialisation
measurement_noise (bool) – Whether to include measurement noise predicted measurement. Default True
predictor (MultiModelPredictor) – Predictor which hold holds transition matrix
resampler (Resampler, optional) – Resampler to prevent particle degeneracy
regulariser (Regulariser, optional) – Regulariser to prevent particle impoverishment. The regulariser is normally used after resampling. If a Resampler is defined, then regularisation will only take place if the particles have been resampled. If the Resampler is not defined but a Regulariser is, then regularisation will be conducted under the assumption that the user intends for this to occur.
constraint_func (Callable, optional) – Callable, user defined function for applying constraints to the states. This is done by setting the weights of particles to 0 for particles that are not correctly constrained. This function provides indices of the unconstrained particles and should accept a ParticleState object and return an array-like object of logical indices.
resampler (Resampler, optional) – Resampler to prevent particle degeneracy
regulariser (Regulariser, optional) – Regulariser to prevent particle impoverishment. The regulariser is normally used after resampling. If a Resampler is defined, then regularisation will only take place if the particles have been resampled. If the Resampler is not defined but a Regulariser is, then regularisation will be conducted under the assumption that the user intends for this to occur.
constraint_func (Callable, optional) – Callable, user defined function for applying constraints to the states. This is done by setting the weights of particles to 0 for particles that are not correctly constrained. This function provides indices of the unconstrained particles and should accept a ParticleState object and return an array-like object of logical indices.
An implementation of a particle filter updater utilising the
Bernoulli filter formulation that estimates the spatial distribution
of a single target and estimates its existence, as described in [1].
Due to the nature of the Bernoulli particle
filter prediction process, resampling is required at every
time step to reduce the number of particles back down to the
desired size.
resampler (Resampler, optional) – Resampler to prevent particle degeneracy
regulariser (Regulariser, optional) – Regulariser to prevent particle impoverishment. The regulariser is normally used after resampling. If a Resampler is defined, then regularisation will only take place if the particles have been resampled. If the Resampler is not defined but a Regulariser is, then regularisation will be conducted under the assumption that the user intends for this to occur.
constraint_func (Callable, optional) – Callable, user defined function for applying constraints to the states. This is done by setting the weights of particles to 0 for particles that are not correctly constrained. This function provides indices of the unconstrained particles and should accept a ParticleState object and return an array-like object of logical indices.
birth_probability (float, optional) – Probability of target birth.
survival_probability (float, optional) – Probability of target survival
clutter_rate (int, optional) – Average number of clutter measurements per time step. Implementation assumes number of clutter measurements follows a Poisson distribution
clutter_distribution (float, optional) – Distribution used to describe clutter measurements. This is usually assumed uniform in the measurement space.
detection_probability (float, optional) – Probability of detection assigned to the generated samples of the birth distribution. If None, it will inherit from the input.
nsurv_particles (float, optional) – Number of particles describing the surviving distribution, which will be output from the update algorithm.
Sequential Monte Carlo Probability Hypothesis Density (SMC-PHD) Updater class
An implementation of a particle updater that estimates only the first-order moment (i.e. the
Probability Hypothesis Density) of the multi-target state density based on [4] and
[5].
Note
It is assumed that the proposal distribution is the same as the dynamics
clutter_intensity (float) – Average number of clutter measurements per time step, per unit volume
resampler (Resampler, optional) – Resampler to prevent particle degeneracy
regulariser (Regulariser, optional) – Regulariser to prevent particle impoverishment. The regulariser is normally used after resampling. If a Resampler is defined, then regularisation will only take place if the particles have been resampled. If the Resampler is not defined but a Regulariser is, then regularisation will be conducted under the assumption that the user intends for this to occur.
constraint_func (Callable, optional) – Callable, user defined function for applying constraints to the states. This is done by setting the weights of particles to 0 for particles that are not correctly constrained. This function provides indices of the unconstrained particles and should accept a ParticleState object and return an array-like object of logical indices.
prob_detect (Probability, optional) – Target Detection Probability
num_samples (int, optional) – The number of particles to be output by the updater, after resampling. If the corresponding predictor has been configured in 'expansion' mode, users should setthis to the number of particles they want to output, otherwise the number of particles will continuously grow. Default is None, which will output the same number of particles as the input prediction.
The number of particles to be output by the updater, after resampling. If the corresponding predictor has been configured in 'expansion' mode, users should setthis to the number of particles they want to output, otherwise the number of particles will continuously grow. Default is None, which will output the same number of particles as the input prediction.
hypotheses (MultipleHypothesis) – A container of SingleHypothesis objects. All hypotheses are assumed to have
the same prediction (and hence same timestamp).
hypotheses (MultipleHypothesis) – A container of SingleHypothesis objects. All hypotheses are assumed to have
the same prediction (and hence same timestamp).
Returns:
The log weights per hypothesis, where the first dimension is the number of particles
and the second dimension is the number of hypotheses. The first hypothesis (column) is
always the missed detection hypothesis.
The adaptive kernel Kalman updater uses the predictions from the predictor to generate the
measurement particles and update the posterior kernel weight vector and covariance matrix.
Additionally, the updater generates new proposal particles at every step to refine the state
estimate.
kernel (Kernel, optional) – Default is None. If None, the default QuadraticKernel is used.
lambda_updater (float, optional) – Used to incorporate prior knowledge of the distribution. If the true distribution is Gaussian, the value of 2 is optimal. Default is 1e-3
measurement_model (MeasurementModel, optional) – The measurement model used to generate the measurement prediction.
Should be used in cases where the measurement model is dependent
on the received measurement. The default is None, in which case
the updater will use the measurement model specified on
initialisation
measurement_noise (bool) – Whether to include measurement noise predicted measurement. Default True
The adaptive kernel Kalman update method. Given a hypothesised association between
a predicted state or predicted measurement and an actual measurement,
calculate the posterior state.
Parameters:
hypothesis (SingleHypothesis) – the prediction-measurement association hypothesis. This hypothesis
may carry a predicted measurement, or a predicted state. In the
latter case a predicted measurement will be calculated.
Ensemble Kalman Filter Updater class
The EnKF is a hybrid of the Kalman updating scheme and the
Monte Carlo approach of the particle filter.
Deliberately structured to resemble the Vanilla Kalman Filter,
update() first calls predict_measurement() function which
proceeds by calculating the predicted measurement, innovation covariance
and measurement cross-covariance. Note however, these are not propagated
explicitly, they are derived from the sample covariance of the ensemble
itself.
Note that the EnKF equations are simpler when written in the following
formalism. Note that h is not necessarily a matrix, but could be a
nonlinear measurement function.
1. J. Hiles, S. M. O’Rourke, R. Niu and E. P. Blasch,
“Implementation of Ensemble Kalman Filters in Stone-Soup,”
International Conference on Information Fusion, (2021)
2. Mandel, Jan. “A brief tutorial on the ensemble Kalman filter.”
arXiv preprint arXiv:0901.3725 (2009).
Parameters:
measurement_model (MeasurementModel, optional) – A measurement model. This need not be defined if a measurement model is provided in the measurement. If no model specified on construction, or in the measurement, then error will be thrown.
force_symmetric_covariance (bool, optional) – A flag to force the output covariance matrix to be symmetric by way of a simple geometric combination of the matrix and transpose. Default is False.
use_joseph_cov (bool, optional) – Bool dictating the method of covariance calculation. If use_joseph_cov is True then the Joseph form of the covariance equation is used.
A measurement model. This need not be defined if a measurement model is provided in the measurement. If no model specified on construction, or in the measurement, then error will be thrown.
The Ensemble Kalman update method. The Ensemble Kalman filter
simply uses the Kalman Update scheme
to evolve a set or Ensemble
of state vectors as a group. This ensemble of vectors contains all the
information on the system state.
Parameters:
hypothesis (SingleHypothesis) – the prediction-measurement association hypothesis. This hypothesis
may carry a predicted measurement, or a predicted state. In the
latter case a predicted measurement will be calculated.
Returns:
The posterior state which contains an ensemble of state vectors
and a timestamp.
The Ensemble Square Root filter propagates the mean and square root
covariance through time, and samples a new ensemble.
This has the advantage of not requiring perturbation of the measurement
which reduces sampling error.
The posterior mean is calculated via:
The posterior mean and covariance are used to sample a new ensemble.
The resulting state is returned via a EnsembleStateUpdate object.
References
1. J. Hiles, S. M. O’Rourke, R. Niu and E. P. Blasch,
“Implementation of Ensemble Kalman Filters in Stone-Soup”,
International Conference on Information Fusion, (2021)
2. Livings, Dance, S. L., & Nichols, N. K.
“Unbiased ensemble square root filters.”
Physica. D, 237(8), 1021–1028. (2008)
Parameters:
measurement_model (MeasurementModel, optional) – A measurement model. This need not be defined if a measurement model is provided in the measurement. If no model specified on construction, or in the measurement, then error will be thrown.
force_symmetric_covariance (bool, optional) – A flag to force the output covariance matrix to be symmetric by way of a simple geometric combination of the matrix and transpose. Default is False.
use_joseph_cov (bool, optional) – Bool dictating the method of covariance calculation. If use_joseph_cov is True then the Joseph form of the covariance equation is used.
The Ensemble Square Root Kalman update method. The Ensemble Square
Root filter propagates the mean and square root covariance through time,
and samples a new ensemble. This has the advantage of not peturbing the
measurement with statistical noise, and thus is less prone to sampling
error for small ensembles.
Parameters:
hypothesis (SingleHypothesis) – the prediction-measurement association hypothesis. This hypothesis
may carry a predicted measurement, or a predicted state. In the
latter case a predicted measurement will be calculated.
Returns:
The posterior state which contains an ensemble of state vectors
and a timestamp.
Implementation of ‘The Linearized EnKF Update’ algorithm from “Ensemble Kalman Filter with
Bayesian Recursive Update” by Kristen Michaelson, Andrey A. Popov and Renato Zanetti.
Similar to the EnsembleUpdater, but uses a different form of Kalman gain. This alternative form
of the EnKF calculates a separate kalman gain for each ensemble member. This alternative
Kalman gain calculation involves linearization of the measurement. An additional step is
introduced to perform inflation.
References
1. K. Michaelson, A. A. Popov and R. Zanetti,
“Ensemble Kalman Filter with Bayesian Recursive Update”
Parameters:
measurement_model (MeasurementModel, optional) – A measurement model. This need not be defined if a measurement model is provided in the measurement. If no model specified on construction, or in the measurement, then error will be thrown.
force_symmetric_covariance (bool, optional) – A flag to force the output covariance matrix to be symmetric by way of a simple geometric combination of the matrix and transpose. Default is False.
use_joseph_cov (bool, optional) – Bool dictating the method of covariance calculation. If use_joseph_cov is True then the Joseph form of the covariance equation is used.
inflation_factor (float, optional) – Parameter to control inflation
The LinearisedEnsembleUpdater update method. This method includes an additional step
over the EnsembleUpdater update step to perform inflation.
Parameters:
hypothesis (SingleHypothesis) – the prediction-measurement association hypothesis. This hypothesis
may carry a predicted measurement, or a predicted state. In the
latter case a predicted measurement will be calculated.
Returns:
The posterior state which contains an ensemble of state vectors
and a timestamp.
measurement_model (MeasurementModel, optional) – A measurement model. This need not be defined if a measurement model is provided in the measurement. If no model specified on construction, or in the measurement, then error will be thrown. Must be linear or capable or implement the jacobian().
force_symmetric_covariance (bool, optional) – A flag to force the output covariance matrix to be symmetric by way of a simple geometric combination of the matrix and transpose. Default is False.
use_joseph_cov (bool, optional) – Bool dictating the method of covariance calculation. If use_joseph_cov is True then the Joseph form of the covariance equation is used.
number_steps (int, optional) – Number of recursive steps
The Kalman update method. Given a hypothesised association between
a predicted state or predicted measurement and an actual measurement,
calculate the posterior state.
Parameters:
hypothesis (SingleHypothesis) – the prediction-measurement association hypothesis. This hypothesis
may carry a predicted measurement, or a predicted state. In the
latter case a predicted measurement will be calculated.
**kwargs (various) – These are passed to predict_measurement()
Returns:
The posterior state Gaussian with mean \(\mathbf{x}_{k|k}\) and
covariance \(P_{x|x}\)
Recursive version of EnsembleUpdater. Uses calculated posterior ensemble as prior ensemble to
recursively update number_steps times.
Parameters:
number_steps (int) – Number of recursive steps
measurement_model (MeasurementModel, optional) – A measurement model. This need not be defined if a measurement model is provided in the measurement. If no model specified on construction, or in the measurement, then error will be thrown. Must be linear or capable or implement the jacobian().
force_symmetric_covariance (bool, optional) – A flag to force the output covariance matrix to be symmetric by way of a simple geometric combination of the matrix and transpose. Default is False.
use_joseph_cov (bool, optional) – Bool dictating the method of covariance calculation. If use_joseph_cov is True then the Joseph form of the covariance equation is used.
The BayesianRecursiveEnsembleUpdater update method. The Ensemble Kalman filter
simply uses the Kalman Update scheme
to evolve a set or Ensemble
of state vectors as a group. This ensemble of vectors contains all the
information on the system state.
Uses calculated posterior ensemble as prior ensemble to
recursively update number_steps times.
Parameters:
hypothesis (SingleHypothesis) – the prediction-measurement association hypothesis. This hypothesis
may carry a predicted measurement, or a predicted state. In the
latter case a predicted measurement will be calculated.
Returns:
The posterior state which contains an ensemble of state vectors
and a timestamp.
Implementation of ‘The Bayesian Recursive Update Linearized EnKF’ algorithm from “Ensemble
Kalman Filter with Bayesian Recursive Update” by Kristen Michaelson, Andrey A. Popov and
Renato Zanetti.
Recursive version of the LinearisedEnsembleUpdater that recursively iterates over the update
step for a given number of steps.
References
1. K. Michaelson, A. A. Popov and R. Zanetti,
“Ensemble Kalman Filter with Bayesian Recursive Update”
Parameters:
number_steps (int) – Number of recursive steps
measurement_model (MeasurementModel, optional) – A measurement model. This need not be defined if a measurement model is provided in the measurement. If no model specified on construction, or in the measurement, then error will be thrown. Must be linear or capable or implement the jacobian().
force_symmetric_covariance (bool, optional) – A flag to force the output covariance matrix to be symmetric by way of a simple geometric combination of the matrix and transpose. Default is False.
use_joseph_cov (bool, optional) – Bool dictating the method of covariance calculation. If use_joseph_cov is True then the Joseph form of the covariance equation is used.
inflation_factor (float, optional) – Parameter to control inflation
The RecursiveLinearisedEnsembleUpdater update method. Uses an alternative form of
Kalman gain to calculate a value for each member of the ensemble. Iterates over the update
step recursively to improve upon error caused by linearisation.
Parameters:
hypothesis (SingleHypothesis) – the prediction-measurement association hypothesis. This hypothesis
may carry a predicted measurement, or a predicted state. In the
latter case a predicted measurement will be calculated.
Returns:
The posterior state which contains an ensemble of state vectors
and a timestamp.
Extension of the BayesianRecursiveUpdater. The BayesianRecursiveUpdater uses equal
measurement noise for each recursive step. The VariableStepBayesianUpdater over-inflates
measurement noise in the earlier steps, requiring the use of a smaller number of steps.
References
1. K. Michaelson, A. A. Popov and R. Zanetti,
“Bayesian Recursive Update for Ensemble Kalman Filters”
Parameters:
measurement_model (MeasurementModel, optional) – A measurement model. This need not be defined if a measurement model is provided in the measurement. If no model specified on construction, or in the measurement, then error will be thrown. Must be linear or capable or implement the jacobian().
force_symmetric_covariance (bool, optional) – A flag to force the output covariance matrix to be symmetric by way of a simple geometric combination of the matrix and transpose. Default is False.
use_joseph_cov (bool, optional) – Bool dictating the method of covariance calculation. If use_joseph_cov is True then the Joseph form of the covariance equation is used.
number_steps (int, optional) – Number of recursive steps
Extension of the variable-step Bayesian recursive update method, which introduces
error-controlling parameters. This method allows the step size to adjust according to the
error value from the previous step. Implementation based on algorithm 3 of [1]. Default
values for parameters atol, rtol, f, fmin and fmax are copied from values stated in examples
in [1]
References
1. K. Michaelson, A. A. Popov and R. Zanetti,
“Bayesian Recursive Update for Ensemble Kalman Filters”
Parameters:
f (float) – Nominal value for step size scale factor
fmin (float) – Minimum value for step size scale factor
fmax (float) – Maximum value for step size scale factor
measurement_model (MeasurementModel, optional) – A measurement model. This need not be defined if a measurement model is provided in the measurement. If no model specified on construction, or in the measurement, then error will be thrown. Must be linear or capable or implement the jacobian().
force_symmetric_covariance (bool, optional) – A flag to force the output covariance matrix to be symmetric by way of a simple geometric combination of the matrix and transpose. Default is False.
use_joseph_cov (bool, optional) – Bool dictating the method of covariance calculation. If use_joseph_cov is True then the Joseph form of the covariance equation is used.
number_steps (int, optional) – Number of recursive steps
Update method of the ErrorControllerBayesianRecursiveUpdater. This method allows the
step size to adjust according to the error value from the previous step.
Parameters:
hypothesis (SingleHypothesis) – the prediction-measurement association hypothesis. This hypothesis
may carry a predicted measurement, or a predicted state. In the
latter case a predicted measurement will be calculated.
Returns:
The posterior state Gaussian with mean \(\mathbf{x}_{k|k}\) and
covariance \(P_{x|x}\)
Wrapper around a Predictor, Updater and Smoother. This
updater takes a Prediction, and updates as usual by calling its updater property.
The updated state is then used to smooth the prior state, completing the first iteration.
The second iteration begins from predicting using the smoothed prior. Iterates until
convergence, or a maximum number of iterations is reached.
Implementation of algorithm 2: Dynamically iterated filter, from “Iterated Filters for
Nonlinear Transition Models”
References
1. Anton Kullberg, Isaac Skog, Gustaf Hendeby,
“Iterated Filters for Nonlinear Transition Models”
Parameters:
predictor (Predictor) – Predictor to use for iterating over the predict step. Probably should be the same predictor used for the initial predict step
updater (Updater) – Updater to use for iterating over update step
smoother (Smoother) – Smoother used to smooth the prior
tolerance (float, optional) – The value of the difference in the measure used as a stopping criterion.
measure (Measure, optional) – The measure to use to test the iteration stopping criterion. Defaults to the Euclidean distance between current and prior posterior state estimate.
max_iterations (int, optional) – Number of iterations before while loop is exited and a non-convergence warning is returned
measurement_model (MeasurementModel, optional) – The measurement model used to generate the measurement prediction.
Should be used in cases where the measurement model is dependent
on the received measurement. The default is None, in which case
the updater will use the measurement model specified on
initialisation
measurement_noise (bool) – Whether to include measurement noise predicted measurement. Default True
transition_model (TransitionModel) – The transition model to be used.
tolerance (float, optional) – The value of the difference in the measure used as a stopping criterion.
measure (Measure, optional) – The measure to use to test the iteration stopping criterion. Defaults to the Euclidean distance between current and prior posterior state estimate.
max_iterations (int, optional) – Number of iterations before while loop is exited and a non-convergence warning is returned
where \(\mathbf{y}_{k|k-1}\) is the predicted information state and \(Y_{k|k-1}\) the
predicted information matrix which form the InformationStatePrediction object. The
measurement matrix \(H_k\) and measurement covariance \(R_k\) are those in the Kalman
filter (see tutorial 1). An InformationStateUpdate object is returned.
Note
Analogously with the InformationKalmanPredictor, the measurement model is queried
for the existence of an inverse_covar() property. If absent, the covar() is
inverted.
Parameters:
measurement_model (LinearGaussian, optional) – A linear Gaussian measurement model. This need not be defined if a measurement model is provided in the measurement. If no model specified on construction, or in the measurement, then error will be thrown.
force_symmetric_covariance (bool, optional) – A flag to force the output covariance matrix to be symmetric by way of a simple geometric combination of the matrix and transpose. Default is False.
use_joseph_cov (bool, optional) – Bool dictating the method of covariance calculation. If use_joseph_cov is True then the Joseph form of the covariance equation is used.
A linear Gaussian measurement model. This need not be defined if a measurement model is provided in the measurement. If no model specified on construction, or in the measurement, then error will be thrown.
There’s no direct analogue of a predicted measurement in the information form. This
method is therefore provided to return the predicted measurement as would the standard
Kalman updater. This is mainly for compatibility as it’s not anticipated that it would
be used in the usual operation of the information filter.
Parameters:
predicted_state (State) – The predicted state in information form \(\mathbf{y}_{k|k-1}\)
measurement_model (MeasurementModel) – The measurement model. If omitted, the model in the updater object
is used
measurement_noise (bool) – Whether to include measurement noise \(R\) with innovation covariance.
Default True
**kwargs (various) – These are passed to matrix()
Returns:
The measurement prediction, \(H \mathbf{x}_{k|k-1}\)
The Information filter update (corrector) method. Given a hypothesised association
between a predicted information state and an actual measurement, calculate the posterior
information state.
Parameters:
hypothesis (SingleHypothesis) – the prediction-measurement association hypothesis. This hypothesis
carries a predicted information state.
A linear updater for accumulated state densities, for processing out of
sequence measurements. This requires the state is represented in
ASDGaussianState multi-state.
References
W. Koch and F. Govaers, On Accumulated State Densities with Applications to
Out-of-Sequence Measurement Processing in IEEE Transactions on Aerospace and
Electronic Systems,
vol. 47, no. 4, pp. 2766-2778, OCTOBER 2011, doi: 10.1109/TAES.2011.6034663.
Parameters:
measurement_model (LinearGaussian, optional) – A linear Gaussian measurement model. This need not be defined if a measurement model is provided in the measurement. If no model specified on construction, or in the measurement, then error will be thrown.
force_symmetric_covariance (bool, optional) – A flag to force the output covariance matrix to be symmetric by way of a simple geometric combination of the matrix and transpose. Default is False.
use_joseph_cov (bool, optional) – Bool dictating the method of covariance calculation. If use_joseph_cov is True then the Joseph form of the covariance equation is used.
The Kalman update method. Given a hypothesised association between
a predicted state and an actual measurement,
calculate the posterior state. The Measurement Prediction should be
calculated by this method. It is overwritten in this method
Parameters:
hypothesis (SingleHypothesis) – the prediction-measurement association hypothesis. This hypothesis
may carry a predicted measurement, or a predicted state. In the
latter case a predicted measurement will be calculated.
force_symmetric_covariance (bool, optional) – A flag to force the output covariance matrix to be symmetric by way
of a simple geometric combination of the matrix and transpose.
Default is False
Base updater class for the implementation of any Gaussian Mixture (GM)
point process derived multi target filters such as the
Probability Hypothesis Density (PHD),
Cardinalised Probability Hypothesis Density (CPHD) or
Linear Complexity with Cumulants (LCC) filters
Parameters:
updater (KalmanUpdater) – Underlying updater used to perform the single target Kalman Update.
clutter_spatial_density (float, optional) – Spatial density of the clutter process uniformly distributed across the state space.
normalisation (bool, optional) – Flag for normalisation
prob_detection (Probability, optional) – Probability of a target being detected at the current timestep
prob_survival (Probability, optional) – Probability of a target surviving until the next timestep
A implementation of the Gaussian Mixture
Probability Hypothesis Density (GM-PHD) multi-target filter
References
[1] B.-N. Vo and W.-K. Ma, “The Gaussian Mixture Probability Hypothesis
Density Filter,” Signal Processing,IEEE Transactions on, vol. 54, no. 11,
pp. 4091–4104, 2006. https://ieeexplore.ieee.org/document/1710358.
[2] D. E. Clark, K. Panta and B. Vo, “The GM-PHD Filter Multiple Target Tracker,” 2006 9th
International Conference on Information Fusion, 2006, pp. 1-8, doi: 10.1109/ICIF.2006.301809.
https://ieeexplore.ieee.org/document/4086095.
Parameters:
updater (KalmanUpdater) – Underlying updater used to perform the single target Kalman Update.
clutter_spatial_density (float, optional) – Spatial density of the clutter process uniformly distributed across the state space.
normalisation (bool, optional) – Flag for normalisation
prob_detection (Probability, optional) – Probability of a target being detected at the current timestep
prob_survival (Probability, optional) – Probability of a target surviving until the next timestep
A implementation of the Gaussian Mixture
Linear Complexity with Cumulants (GM-LCC) multi-target filter
References
[1] D. E. Clark and F. De Melo. “A Linear-Complexity Second-Order
Multi-Object Filter via Factorial Cumulants”.
In: 2018 21st International Conference on
Information Fusion (FUSION). 2018. DOI: 10.
23919/ICIF.2018.8455331. https://ieeexplore.ieee.org/document/8455331..
Parameters:
updater (KalmanUpdater) – Underlying updater used to perform the single target Kalman Update.
clutter_spatial_density (float, optional) – Spatial density of the clutter process uniformly distributed across the state space.
normalisation (bool, optional) – Flag for normalisation
prob_detection (Probability, optional) – Probability of a target being detected at the current timestep
prob_survival (Probability, optional) – Probability of a target surviving until the next timestep
mean_number_of_false_alarms (float, optional) – Mean number of false alarms (clutter) expected per timestep
variance_of_false_alarms (float, optional) – Variance on the number of false alarms (clutter) expected per timestep
Conceptually, the \(\alpha-\beta\) filter is similar to its Kalman cousins in that it
operates recursively over predict and update steps. It assumes that a state vector is
decomposable into quantities and the rates of change of those quantities. We refer to these as
position \(p\) and velocity \(v\) respectively, though they aren’t confined to
locations in space. If the interval from \(t_{k-1} \rightarrow t_k\) is \(\Delta T\),
and at \(k\), we can gain a (noisy) measurement of the position, \(p^z_k\).
The \(\alpha\) and \(\beta\) parameters which give the filter its name are small,
\(0 < \alpha < 1\) and \(0 < \beta \leq 2\). Colloquially, the larger the values of the
parameters, the more influence the measurements have over the transition model; \(\beta\)
is usually much smaller than \(\alpha\).
As the prediction is just the application of a constant velocity model, there is no
\(\alpha-\beta\) predictor provided in Stone Soup. It is assumed that the predictions
passed to the hypothesis have been generated by a constant velocity model. Any application of a
control model is also assumed to have taken place during the prediction stage.
This class assumes the velocity is in units of the length per second. If different units are
required, scale the prior appropriately.
The measurement model used should be linear and a measurement model such that it provides a
‘mapping’ to \(p\) via the mapping tuple and a binary measurement matrix which
returns \(p\). This isn’t checked.
alpha (float) – The alpha parameter. Controls the weight given to the measurements over the transition model.
beta (float) – The beta parameter. Controls the amount of variation allowed in the velocity component.
vmap (numpy.ndarray, optional) – Binary map of the velocity elements in the state vector. If left default, the class will assume that the velocity elements interleave the position elements in the state vector.
Binary map of the velocity elements in the state vector. If left default, the class will assume that the velocity elements interleave the position elements in the state vector.
The Sliding Innovation Filter (SIF) is a sub-optimal filter (in comparison to Kalman filter)
which uses a switching gain to provide robustness to estimation problems that may be
ill-conditioned or contain modeling uncertainties or disturbances.
The main difference from Kalman filter is the calculation of the gain:
where \(\mathbf{\delta}\) is the sliding boundary layer width.
References
S. A. Gadsden and M. Al-Shabi, “The Sliding Innovation Filter,” in IEEE Access, vol. 8,
pp. 96129-96138, 2020, doi: 10.1109/ACCESS.2020.2995345.
Parameters:
layer_width (numpy.ndarray) – Sliding boundary layer width \(\mathbf{\delta}\). A tunable parameter in measurement space. An example initial value provided in original paper is \(10 \times \text{diag}(R)\)
measurement_model (LinearGaussian, optional) – A linear Gaussian measurement model. This need not be defined if a measurement model is provided in the measurement. If no model specified on construction, or in the measurement, then error will be thrown.
force_symmetric_covariance (bool, optional) – A flag to force the output covariance matrix to be symmetric by way of a simple geometric combination of the matrix and transpose. Default is False.
use_joseph_cov (bool, optional) – Bool dictating the method of covariance calculation. If use_joseph_cov is True then the Joseph form of the covariance equation is used.
Sliding boundary layer width \(\mathbf{\delta}\). A tunable parameter in measurement space. An example initial value provided in original paper is \(10 \times \text{diag}(R)\)
S. A. Gadsden and M. Al-Shabi, “The Sliding Innovation Filter,” in IEEE Access, vol. 8,
pp. 96129-96138, 2020, doi: 10.1109/ACCESS.2020.2995345.
Parameters:
layer_width (numpy.ndarray) – Sliding boundary layer width \(\mathbf{\delta}\). A tunable parameter in measurement space. An example initial value provided in original paper is \(10 \times \text{diag}(R)\)
measurement_model (LinearGaussian, optional) – A linear Gaussian measurement model. This need not be defined if a measurement model is provided in the measurement. If no model specified on construction, or in the measurement, then error will be thrown.
force_symmetric_covariance (bool, optional) – A flag to force the output covariance matrix to be symmetric by way of a simple geometric combination of the matrix and transpose. Default is False.
use_joseph_cov (bool, optional) – Bool dictating the method of covariance calculation. If use_joseph_cov is True then the Joseph form of the covariance equation is used.
measurement_model (MarkovianMeasurementModel, optional) – The measurement model used to predict measurement vectors. If no model is specified on construction, or in a measurement, then an error will be thrown.
The measurement model used to predict measurement vectors. If no model is specified on construction, or in a measurement, then an error will be thrown.
The update method. Given a hypothesised association between a predicted state or
predicted measurement and an actual measurement, calculate the posterior state.
\[\alpha_t^i = E^{ki}(F\alpha_{t-1})^i\]
Measurements are assumed to be discrete categories from a finite set of measurement
categories \(Z = \{\zeta^n|n\in \mathbf{N}, n\le N\}\) (for some finite \(N\)).
A measurement should be equivalent to a basis vector \(e^k\), (the N-tuple with all
components equal to 0, except the k-th (indices starting at 0), which is 1). This
indicates that the measured category is \(\zeta^k\).
The equation above can be simplified to:
\[\alpha_t = E^Ty_t \circ F\alpha_{t-1}\]
where \(\circ\) denotes element-wise (Hadamard) product.
Parameters:
hypothesis (SingleHypothesis) – the prediction-measurement association hypothesis. This hypothesis may carry a
predicted measurement, or a predicted state. In the latter case a predicted
measurement will be calculated.
To attain measurement predictions, the composite updater will use it’s sub-updaters’
predict_measurement methods and leave combining these to the
CompositeHypothesis type.
Given a hypothesised association between a composite predicted state or composite
predicted measurement and a composite measurement, calculate the composite
posterior state.
Parameters:
hypothesis (CompositeHypothesis) – the prediction-measurement association hypothesis. This hypothesis may carry a
composite predicted measurement, or a composite predicted state. In the latter case
a measurement prediction is calculated for each sub-state of the composite hypothesis,
which will then create its own composite measurement prediction.
**kwargs (various) – These are passed to the predict_measurement() method of each sub-updater
A class which performs state updates using the Chernoff fusion rule. In this context,
measurements come in the form of states with a mean and covariance (compared to traditional
measurements which contain solely a mean). The measurements are expected to come as
GaussianDetection objects.
where \(\omega\) is a weighting parameter in the range \((0,1]\), which can be found
using an optimization algorithm.
In situations where \(p_1(x)\) and \(p_2(x)\) are multivariate Gaussian distributions,
the above formula is equal to the Covariance Intersection Algorithm from Julier et al [7].
Let \((a,A)\) and \((b,B)\) be the means and covariances of the measurement and
prediction respectively. The Covariance Intersection Algorithm was reformulated for use in
Bayesian state estimation by Clark and Campbell [8], yielding formulas for the updated
covariance and mean, \(D\) and \(d\), and the innovation covariance matrix, \(V\),
as follows:
\[\begin{split}D &= \left ( \omega A^{-1} + (1-\omega)B^{-1} \right )\\
d &= D \left ( \omega A^{-1}a + (1-\omega)B^{-1}b \right )\\
V &= \frac{A}{1-\omega} + \frac{B}{\omega}\end{split}\]
In filters where gating is required, the gating region can be written using the innovation
covariance matrix as:
The specifics for implementing the Covariance Intersection Algorithm in several popular
multi-target tracking algorithms was expanded upon by Clark et al [9]. The work includes a
discussion of Stone Soup and can be used to apply this class to a tracking algorithm of
choice.
Note
If you have tracks that you would like to use as measurements for this updater, the
Tracks2GaussianDetectionFeeder class can be used to convert the tracks to the
appropriate format.
This function predicts the measurement of a state in situations where measurements consist
of a covariance and state vector.
Parameters:
predicted_state (GaussianState) – The predicted state \(\mathbf{x}_{k|k-1}\)
measurement_model (MeasurementModel) – The measurement model. If omitted, the updater will use the model that was specified
on initialization.
measurement_noise (bool) – Whether to include measurement noise. Default True. Where False the
predicted state covariance is used directly without omega factor.
Given a hypothesis, calculate the posterior mean and covariance.
Parameters:
hypothesis (Hypothesis) – Hypothesis with the predicted state and the actual/associated measurement which should
be used for updating. If the hypothesis does not contain a measurement prediction, one
will be calculated.
force_symmetric_covariance (bool) – A flag to force the output covariance matrix to be symmetric by way of a simple
geometric combination of the matrix and transpose. Default is False.
Returns:
The state posterior, saved in a generic Update object.
An updater which undertakes probabilistic data association (PDA), as defined in [10]. It
differs slightly from the Kalman updater it inherits from in that instead of a single
hypothesis object, the update() method takes a hypotheses object returned by a
PDA (or similar) data associator. Functionally this is a list of single hypothesis
objects which group tracks together with associated measuments and probabilities.
The ExtendedKalmanUpdater is used in order to inherit the ability to cope with
(slight) non-linearities. Other inheritance structures should be trivial to implement.
where \(K_k\) and \(P_{k|k}\) are the Kalman gain and posterior covariance
respectively returned by the single-target Kalman update, \(\beta_0\) is the probability
of missed detection. In this instance \(\mathbf{y}_k\) is the combined innovation,
over \(m_k\) detections:
The posterior covariance is composed of a term to account for the covariance due to missed
detection, that due to the true detection, and a term (\(\tilde{P}\)) which quantifies the
effect of the measurement origin uncertainty.
A method for updating via a Gaussian mixture reduction is also provided. In this latter case,
each of the hypotheses, including that for a missed detection, is updated and then a weighted
Gaussian reduction is used to resolve the hypotheses to a single Gaussian distribution. The
reason this is equivalent to the innovation-based method is shown in [11].
References
Parameters:
measurement_model (MeasurementModel, optional) – A measurement model. This need not be defined if a measurement model is provided in the measurement. If no model specified on construction, or in the measurement, then error will be thrown. Must be linear or capable or implement the jacobian().
force_symmetric_covariance (bool, optional) – A flag to force the output covariance matrix to be symmetric by way of a simple geometric combination of the matrix and transpose. Default is False.
use_joseph_cov (bool, optional) – Bool dictating the method of covariance calculation. If use_joseph_cov is True then the Joseph form of the covariance equation is used.
The prediction-measurement association hypotheses. This hypotheses object carries
tracks, associated sets of measurements for each track together with a probability
measure which enumerates the likelihood of each track-measurement pair. (This is most
likely output by the PDA associator).
In a single case (the missed detection hypothesis), the hypothesis will not have an
associated measurement or measurement prediction.
gm_method (bool) – Use the innovation-based update method if False (default), or the GM-reduction (True).
**kwargs (various) – These are passed to predict_measurement()