forked from simondlevy/TinyEKF
-
Notifications
You must be signed in to change notification settings - Fork 0
/
TinyEKF.h
139 lines (121 loc) · 4.04 KB
/
TinyEKF.h
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
/*
* TinyEKF: Extended Kalman Filter for Arduino and TeensyBoard.
*
* Copyright (C) 2015 Simon D. Levy
*
* This code is free software: you can redistribute it and/or modify
* it under the terms of the GNU Lesser General Public License as
* published by the Free Software Foundation, either version 3 of the
* License, or (at your option) any later version.
*
* This code is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU Lesser General Public License
* along with this code. If not, see <http:#www.gnu.org/licenses/>.
*/
#include <stdio.h>
#include <stdlib.h>
#include "tiny_ekf_struct.h"
// Support both Arduino and command-line versions
#ifndef MAIN
extern "C" {
#endif
void ekf_init(void *, int, int);
int ekf_step(void *, double *);
#ifndef MAIN
}
#endif
/**
* A header-only class for the Extended Kalman Filter. Your implementing class should #define the constant N and
* and then #include <TinyEKF.h> You will also need to implement a model() method for your application.
*/
class TinyEKF {
private:
ekf_t ekf;
protected:
/**
* The current state.
*/
double * x;
/**
* Initializes a TinyEKF object.
*/
TinyEKF() {
ekf_init(&this->ekf, N, M);
this->x = this->ekf.x;
}
/**
* Deallocates memory for a TinyEKF object.
*/
~TinyEKF() { }
/**
* Implement this function for your EKF model.
* @param fx gets output of state-transition function <i>f(x<sub>0 .. n-1</sub>)</i>
* @param F gets <i>n × n</i> Jacobian of <i>f(x)</i>
* @param hx gets output of observation function <i>h(x<sub>0 .. n-1</sub>)</i>
* @param H gets <i>m × n</i> Jacobian of <i>h(x)</i>
*/
virtual void model(double fx[N], double F[N][N], double hx[M], double H[M][N]) = 0;
/**
* Sets the specified value of the prediction error covariance. <i>P<sub>i,j</sub> = value</i>
* @param i row index
* @param j column index
* @param value value to set
*/
void setP(int i, int j, double value)
{
this->ekf.P[i][j] = value;
}
/**
* Sets the specified value of the process noise covariance. <i>Q<sub>i,j</sub> = value</i>
* @param i row index
* @param j column index
* @param value value to set
*/
void setQ(int i, int j, double value)
{
this->ekf.Q[i][j] = value;
}
/**
* Sets the specified value of the observation noise covariance. <i>R<sub>i,j</sub> = value</i>
* @param i row index
* @param j column index
* @param value value to set
*/
void setR(int i, int j, double value)
{
this->ekf.R[i][j] = value;
}
public:
/**
* Returns the state element at a given index.
* @param i the index (at least 0 and less than <i>n</i>
* @return state value at index
*/
double getX(int i)
{
return this->ekf.x[i];
}
/**
* Sets the state element at a given index.
* @param i the index (at least 0 and less than <i>n</i>
* @param value value to set
*/
void setX(int i, double value)
{
this->ekf.x[i] = value;
}
/**
Performs one step of the prediction and update.
* @param z observation vector, length <i>m</i>
* @return true on success, false on failure caused by non-positive-definite matrix.
*/
bool step(double * z)
{
this->model(this->ekf.fx, this->ekf.F, this->ekf.hx, this->ekf.H);
return ekf_step(&this->ekf, z) ? false : true;
}
};