Class KalmanFilter<States extends Num,​Inputs extends Num,​Outputs extends Num>

java.lang.Object
edu.wpi.first.math.estimator.KalmanFilter<States,​Inputs,​Outputs>
Type Parameters:
States - Number of states.
Inputs - Number of inputs.
Outputs - Number of outputs.
All Implemented Interfaces:
KalmanTypeFilter<States,​Inputs,​Outputs>

public class KalmanFilter<States extends Num,​Inputs extends Num,​Outputs extends Num>
extends Object
implements KalmanTypeFilter<States,​Inputs,​Outputs>
A Kalman filter combines predictions from a model and measurements to give an estimate of the true system state. This is useful because many states cannot be measured directly as a result of sensor noise, or because the state is "hidden".

Kalman filters use a K gain matrix to determine whether to trust the model or measurements more. Kalman filter theory uses statistics to compute an optimal K gain which minimizes the sum of squares error in the state estimate. This K gain is used to correct the state estimate by some amount of the difference between the actual measurements and the measurements predicted by the model.

For more on the underlying math, read https://file.tavsys.net/control/controls-engineering-in-frc.pdf chapter 9 "Stochastic control theory".