29 void ekf_range_init(
struct EKFRange *ekf_range,
float P0_pos,
float P0_speed,
float Q_sigma2,
float R_dist,
float R_speed,
float dt)
32 const float dt2 = dt * dt;
33 const float dt3 = dt2 * dt / 2.f;
34 const float dt4 = dt2 * dt2 / 4.f;
36 ekf_range->
state[i] = 0.f;
38 ekf_range->
P[i][j] = 0.f;
39 ekf_range->
Q[i][j] = 0.f;
43 ekf_range->
P[i][i] = P0_pos;
44 ekf_range->
P[i+1][i+1] = P0_speed;
45 ekf_range->
Q[i][i] = Q_sigma2 * dt4;
46 ekf_range->
Q[i+1][i] = Q_sigma2 * dt3;
47 ekf_range->
Q[i][i+1] = Q_sigma2 * dt3;
48 ekf_range->
Q[i+1][i+1] = Q_sigma2 * dt2;
50 ekf_range->
R_dist = R_dist;
57 ekf_range->
state[0] = pos.
x;
58 ekf_range->
state[1] = speed.
x;
59 ekf_range->
state[2] = pos.
y;
60 ekf_range->
state[3] = speed.
y;
61 ekf_range->
state[4] = pos.
z;
62 ekf_range->
state[5] = speed.
z;
67 pos->
x = ekf_range->
state[0];
68 pos->
y = ekf_range->
state[2];
69 pos->
z = ekf_range->
state[4];
70 speed->
x = ekf_range->
state[1];
71 speed->
y = ekf_range->
state[3];
72 speed->
z = ekf_range->
state[5];
78 pos.
x = ekf_range->state[0];
79 pos.y = ekf_range->state[2];
80 pos.z = ekf_range->state[4];
87 speed.
x = ekf_range->state[1];
88 speed.y = ekf_range->state[3];
89 speed.z = ekf_range->state[5];
96 const float dt = ekf_range->
dt;
97 const float dt2 = dt * dt;
98 const float dt3 = dt2 * dt / 2.f;
99 const float dt4 = dt2 * dt2 / 4.f;
101 ekf_range->
Q[i][i] = Q_sigma2 * dt4;
102 ekf_range->
Q[i+1][i] = Q_sigma2 * dt3;
103 ekf_range->
Q[i][i+1] = Q_sigma2 * dt3;
104 ekf_range->
Q[i+1][i+1] = Q_sigma2 * dt2;
106 ekf_range->
R_dist = R_dist;
124 ekf_range->
state[i] += ekf_range->
state[i+1] * ekf_range->
dt;
128 const float d_dt = ekf_range->
P[i+1][i+1] * ekf_range->
dt;
129 ekf_range->
P[i][i] += ekf_range->
P[i+1][i] * ekf_range->
dt
130 + ekf_range->
dt * (ekf_range->
P[i][i+1] + d_dt) + ekf_range->
Q[i][i];
131 ekf_range->
P[i][i+1] += d_dt + ekf_range->
Q[i][i+1];
132 ekf_range->
P[i+1][i] += d_dt + ekf_range->
Q[i+1][i];
133 ekf_range->
P[i+1][i+1] += ekf_range->
Q[i+1][i+1];
145 const float dx = ekf_range->
state[0] - anchor.
x;
146 const float dy = ekf_range->
state[2] - anchor.
y;
147 const float dz = ekf_range->
state[4] - anchor.
z;
148 const float norm = sqrtf(dx * dx + dy * dy + dz * dz);
150 const float res = dist - norm;
152 float Hi[] = { dx / norm, 0.f, dy / norm, 0.f, dz / norm, 0.f };
156 Hi[0] * Hi[0] * ekf_range->
P[0][0] +
157 Hi[2] * Hi[2] * ekf_range->
P[2][2] +
158 Hi[4] * Hi[4] * ekf_range->
P[4][4] +
159 Hi[0] * Hi[2] * (ekf_range->
P[0][2] + ekf_range->
P[2][0]) +
160 Hi[0] * Hi[4] * (ekf_range->
P[0][4] + ekf_range->
P[4][0]) +
161 Hi[2] * Hi[4] * (ekf_range->
P[2][4] + ekf_range->
P[4][2]) +
163 if (fabsf(S) < 1e-5) {
168 for (
int i = 0; i < 6; i++) {
169 K[i] = (Hi[0] * ekf_range->
P[i][0] + Hi[2] * ekf_range->
P[i][2] + Hi[4] * ekf_range->
P[i][4]) / S;
170 ekf_range->
state[i] +=
K[i] * res;
175 for (
int i = 0; i < 6; i++) {
176 for (
int j = 0; j < 6; j++) {
177 KH_tmp[i][j] =
K[i] * Hi[j];
178 P_tmp[i][j] = ekf_range->
P[i][j];
182 for (
int i = 0; i < 6; i++) {
183 for (
int j = 0; j < 6; j++) {
184 for (
int k = 0; k < 6; k++) {
185 ekf_range->
P[i][j] -= KH_tmp[i][k] * P_tmp[k][j];
if(GpsFixValid() &&e_identification_started)
void ekf_range_update_noise(struct EKFRange *ekf_range, float Q_sigma2, float R_dist, float R_speed)
Update process and measurement noises.
void ekf_range_set_state(struct EKFRange *ekf_range, struct EnuCoor_f pos, struct EnuCoor_f speed)
Set initial state vector.
struct EnuCoor_f ekf_range_get_speed(struct EKFRange *ekf_range)
Get current speed.
void ekf_range_update_dist(struct EKFRange *ekf_range, float dist, struct EnuCoor_f anchor)
correction step
void ekf_range_update_speed(struct EKFRange *ekf_range, float speed, uint8_t type)
Update step based on speed measure.
void ekf_range_get_state(struct EKFRange *ekf_range, struct EnuCoor_f *pos, struct EnuCoor_f *speed)
Get current state.
struct EnuCoor_f ekf_range_get_pos(struct EKFRange *ekf_range)
Get current pos.
void ekf_range_init(struct EKFRange *ekf_range, float P0_pos, float P0_speed, float Q_sigma2, float R_dist, float R_speed, float dt)
Init EKF_range internal struct.
void ekf_range_predict(struct EKFRange *ekf_range)
propagate dynamic model
float state[EKF_RANGE_DIM]
state vector
float R_dist
measurement noise on distances (assumed the same for all anchors)
float P[EKF_RANGE_DIM][EKF_RANGE_DIM]
covariance matrix
float R_speed
measurement noise on speed (assumed the same for all axis)
float Q[EKF_RANGE_DIM][EKF_RANGE_DIM]
process noise matrix
float dt
prediction step (in seconds)
vector in East North Up coordinates Units: meters
unsigned char uint8_t
Typedef defining 8 bit unsigned char type.