public class JKalman extends Object
The structure JKalman
is used to keep
Kalman filter state. It is created by constructor function, updated by
Predict
and Correct
functions.
Normally, the structure is used for standard JKalman filter (notation and the formulae below are borrowed from the JKalman tutorial [Welch95]):
xk=A*xk-1+B*uk+wk zk=Hxk+vk,
where:
xk (xk-1) - state of the system at the moment k (k-1) zk - measurement of the system state at the moment k uk - external control applied at the moment k wk and vk are normally-distributed process and measurement noise, respectively: p(w) ~ N(0,Q) p(v) ~ N(0,R), that is, Q - process noise covariance matrix, constant or variable, R - measurement noise covariance matrix, constant or variable
In case of standard JKalman filter, all the matrices: A, B, H, Q and R are initialized once after JKalman structure is allocated via constructor. However, the same structure and the same functions may be used to simulate extended JKalman filter by linearizing extended JKalman filter equation in the current system state neighborhood, in this case A, B, H (and, probably, Q and R) should be updated on every step.
Constructor and Description |
---|
JKalman(int dynam_params,
int measure_params)
Constructor in case of no control.
|
JKalman(int dynam_params,
int measure_params,
int control_params)
The construstor allocates JKalman filter and all its matrices and
initializes them somehow.
|
Modifier and Type | Method and Description |
---|---|
Matrix |
Correct(Matrix measurement)
Adjusts model state.
|
Matrix |
getControl_matrix()
Getter
|
Matrix |
getError_cov_post()
Getter
|
Matrix |
getError_cov_pre()
Getter
|
Matrix |
getGain()
Getter
|
Matrix |
getMeasurement_matrix()
Getter
|
Matrix |
getMeasurement_noise_cov()
Getter
|
Matrix |
getProcess_noise_cov()
Getter
|
Matrix |
getState_post() |
Matrix |
getState_pre()
Getter
|
Matrix |
getTransition_matrix() |
Matrix |
Predict()
Alias for prediction with no control.
|
Matrix |
Predict(Matrix control)
Estimates subsequent model state.
|
void |
setControl_matrix(Matrix control_matrix)
Setter
|
void |
setError_cov_post(Matrix error_cov_post)
Setter
|
void |
setError_cov_pre(Matrix error_cov_pre)
Setter
|
void |
setGain(Matrix gain)
Setter
|
void |
setMeasurement_matrix(Matrix measurement_matrix)
Setter
|
void |
setMeasurement_noise_cov(Matrix measurement_noise_cov)
Setter
|
void |
setProcess_noise_cov(Matrix process_noise_cov)
Setter
|
void |
setState_post(Matrix state_post)
Setter
|
void |
setState_pre(Matrix state_pre)
Setter
|
void |
setTransition_matrix(Matrix transition_matrix)
Getter
|
public JKalman(int dynam_params, int measure_params, int control_params) throws Exception
dynam_params
- measure_params
- control_params
- IllegalArgumentException
- Kalman filter dimensions exception.Exception
public Matrix Predict()
public Matrix Predict(Matrix control)
The function estimates the subsequent
stochastic model state by its current state and stores it at
state_pre
:
x'k=A*xk+B*uk
P'k=A*Pk-1*AT + Q,
where
x'k is predicted state (state_pre),
xk-1 is corrected state on the previous step (state_post)
(should be initialized somehow in the beginning, zero vector by default),
uk is external control (control
parameter),
P'k is prior error covariance matrix (error_cov_pre)
Pk-1 is posteriori error covariance matrix on the previous step (error_cov_post)
(should be initialized somehow in the beginning, identity matrix by default),
control
- Control vector (uk), should be NULL if there
is no external control (control_params
=0).public Matrix Correct(Matrix measurement)
KalmanCorrect
adjusts stochastic model state
on the basis of the given measurement of the model state:
Kk=P'k*HT*(H*P'k*HT+R)-1
xk=x'k+Kk*(zk-H*x'k)
Pk=(I-Kk*H)*P'k
where
zk - given measurement (mesurement
parameter)
Kk - JKalman "gain" matrix.
The function stores adjusted state at state_post
and
returns it on output.
measurement
- Matrix containing the measurement vector.public void setState_pre(Matrix state_pre)
state_pre
- public Matrix getState_pre()
public void setState_post(Matrix state_post)
state_post
- public Matrix getState_post()
public void setTransition_matrix(Matrix transition_matrix)
transition_matrix
- public Matrix getTransition_matrix()
public void setControl_matrix(Matrix control_matrix)
control_matrix
- public Matrix getControl_matrix()
public void setMeasurement_matrix(Matrix measurement_matrix)
measurement_matrix
- public Matrix getMeasurement_matrix()
public void setProcess_noise_cov(Matrix process_noise_cov)
process_noise_cov
- public Matrix getProcess_noise_cov()
public void setMeasurement_noise_cov(Matrix measurement_noise_cov)
measurement_noise_cov
- public Matrix getMeasurement_noise_cov()
public void setError_cov_pre(Matrix error_cov_pre)
error_cov_pre
- public Matrix getError_cov_pre()
public void setGain(Matrix gain)
gain
- public Matrix getGain()
public void setError_cov_post(Matrix error_cov_post)
error_cov_post
- public Matrix getError_cov_post()
Jas4pp 1.5 © Java Analysis Studio for Particle Physics