KalmanFilter
ddekf.m
Go to the documentation of this file.
1 function [estimates, covariances ] = ddekf(f_func,jacobian_func,dt_between_measurements,start_time,state_count,sensor_count,measurement_count,C,Q_root,R_root,P_0_root,x_0, measurements)
2 %Runs discrete-discrete Extended Kalman filter on data. The initial
3 %estimate and covariances are at the time step before all the
4 %measurements - be wary of the off-by-one error. If f_func is a
5 %linear function the code is equivalent to discrete-discrete Kalman
6 %filter.
7 %[estimates, covariances] = ddekf(f_func,jacobian_func,state_count,sensor_count,measurement_count,C,Q_root,R_root,P_0_root,x_0, measurements)
8 %INPUT:
9 % f_func: x_{k+1} = f_func(x_k,t) where x_k is the state. The
10 % function's second argument is time t for cases when the function
11 % changes with time. The argument can be also used an internal
12 % counter variable for f_func when start_time is set to zero and
13 % dt_between_measurements is set to 1.
14 %
15 % jacobian_func(x,t): jacobian of f_func with state x at time t
16 %
17 % dt_between_measurements: time distance between incoming
18 % measurements. Used for incrementing time counter for each
19 % successive measurement with the time counter initialized with
20 % start_time. The time counter is fed into f_func(x,t) as t.
21 %
22 % start_time: the time of first measurement
23 %
24 % state_count: dimension of the state
25 %
26 % sensor_count: dimension of observation vector
27 %
28 % C: observation matrix of size 'sensor_count by state_count'
29 %
30 % R_root: The root of sensor error covariance matrix R where
31 % R = R_root*(R_root'). R_root is of size 'sensor_count by
32 % sensor_count'. R_root = chol(R)' is one way to derive it.
33 %
34 % Q_root: The root of process error covariance matrix Q where
35 % Q = Q_root*(Q_root'). Q_root is of size 'state_count by
36 % state_count'. Q_root = chol(Q)' is one way to derive it.
37 %
38 % P_0_root: The root of initial covariance matrix P_0 where
39 % P_0 = P_0_root*(P_root'); P_0_root is of size 'state_count by
40 % state_count'. % P_0_root = chol(P_0)' is one way to derive it.
41 %
42 % x_0:Initial state estimate of size 'state_count by 1'
43 %
44 % measurements: ith column is ith measurement. Matrix of size
45 % 'sensor_count by measurement_count'
46 %
47 %OUTPUT:
48 % estimates: 'state_count by measurement_count+1'
49 % ith column is ith estimate. first column is x_0
50 %
51 % covariances: cell of size 'measurement_count+1' by 1
52 % where each entry is the P covariance matrix at that time
53 % Time is computed based on dt_between_measurements
54 
55  %make sure input is valid
56  assert(size(P_0_root,1)==state_count &&...
57  size(P_0_root,2)==state_count);
58  assert(size(C,1)==sensor_count && size(C,2)==state_count);
59  assert(size(Q_root,1)==state_count &&...
60  size(Q_root,2)==state_count);
61  assert(size(x_0,1)==state_count && size(x_0,2)==1);
62  assert(size(R_root,1)==sensor_count &&...
63  size(R_root,2)==sensor_count);
64  test = f_func(x_0,start_time);
65  assert(size(test,1)==state_count && size(test,2)==1);
66  test = jacobian_func(x_0,start_time);
67  assert(size(test,1)==state_count && size(test,2)==state_count);
68  assert(size(measurements,1)==sensor_count &&...
69  size(measurements,2)==measurement_count);
70 
71  x_km1_p = x_0;
72  P_root_km1_p = P_0_root;
73 
74  estimates = zeros(state_count,measurement_count + 1);
75  covariances = cell(measurement_count + 1, 1);
76 
77  estimates(1:state_count,1) = x_0;
78  covariances{1,1} = P_0_root*P_0_root';
79 
80  current_time = start_time;
81 
82  for k=1:measurement_count
83  %loop through all measurements and follow through predict
84  %and update phase
85  [x_k_m,P_root_km] = ddekf_predict_phase(f_func,...
86  jacobian_func,current_time,P_root_km1_p,x_km1_p,...
87  Q_root);
88  [x_k_p,P_root_kp] = ddekf_update_phase(R_root,...
89  P_root_km,C,x_k_m,measurements(:,k));
90 
91  x_km1_p = x_k_p;
92  P_root_km1_p = P_root_kp;
93 
94  %store results
95  estimates(:,k+1) = x_k_p;
96  covariances{k+1,1} = P_root_kp*(P_root_kp');
97 
98  current_time = current_time + dt_between_measurements;
99  end
100 end
function ddekf(in f_func, in jacobian_func, in dt_between_measurements, in start_time, in state_count, in sensor_count, in measurement_count, in C, in Q_root, in R_root, in P_0_root, in x_0, in measurements)
function ddekf_predict_phase(in f_func, in jacobian_func, in t, in P_0_sqrt, in x_0, in Q_root)
function ddekf_update_phase(in R_root, in P_root, in C, in estimate, in measurement)