-
Notifications
You must be signed in to change notification settings - Fork 2
/
MEKF.cc
176 lines (138 loc) · 6.05 KB
/
MEKF.cc
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
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
/* Copyright (c) 2019 Siddarth Kaki
* This Source Code Form is subject to the terms of the Mozilla Public
* License, v. 2.0. If a copy of the MPL was not distributed with this
* file, You can obtain one at https://mozilla.org/MPL/2.0/. */
#include "MEKF.h"
namespace MEKF {
MEKF::MEKF(const double &dt)
{
dt_ = dt;
processed_measurement_ = false;
}
void MEKF::Init(const double &process_noise_std, const double &measurement_noise_std, const double &dt)
{
num_states_ = 9; // delta_gibbs(3), omega(3), alpha(3)
num_measurements_ = 3; // delta_gibbs (3)
dt_ = dt;
tau_ = 1.0; // TODO PASS AS ARGUMENT
Q_ = MatrixXd::Identity(num_states_, num_states_)*pow(process_noise_std,2); // process_noise_covariance
double qpsd = 1e5;
double pss = qpsd*tau_/2.0;
Q_(6,6) *= ( 1.0 - exp(-2.0*dt_/tau_) )*pss;
Q_(7,7) *= ( 1.0 - exp(-2.0*dt_/tau_) )*pss;
Q_(8,8) *= ( 1.0 - exp(-2.0*dt_/tau_) )*pss;
R_ = MatrixXd::Identity(num_measurements_, num_measurements_)*pow(measurement_noise_std,2); // measurement_noise_covariance
A_ = MatrixXd::Identity(4, 4); // quaternion_propagation
F_ = MatrixXd::Identity(num_states_, num_states_); // covariance_propagation
H_ = MatrixXd::Zero(num_measurements_, num_states_); // measurement_model
H_.block(0,0,num_measurements_,num_measurements_) = Matrix3d::Identity();
quat_est_ = Quaterniond::Identity();
omega_est_ = Vector3d::Zero();
alpha_est_ = Vector3d::Zero();
delta_gibbs_est_ = Vector3d::Zero();
covar_est_ = MatrixXd::Zero(num_states_, num_states_);
processed_measurement_ = false;
}
void MEKF::SetInitialStateAndCovar(const Quaterniond &quat0, const Vector3d &omega0, const Vector3d &alpha0, const MatrixXd &covar0)
{
quat_est_ = quat0;
omega_est_ = omega0;
alpha_est_ = alpha0;
covar_est_ = covar0;
}
// Prediction step
void MEKF::Predict()
{
double omega_norm = omega_est_.norm();
Vector3d omega_hat = omega_est_ / omega_norm;
Matrix3d I33 = Matrix3d::Identity();
MatrixXd I44 = MatrixXd::Identity(4, 4);
MatrixXd omega_hat_44_equivalent = MatrixXd::Zero(4, 4);
omega_hat_44_equivalent.block(0, 1, 1, 3) = -omega_hat.transpose();
omega_hat_44_equivalent.block(1, 0, 3, 1) = omega_hat;
omega_hat_44_equivalent.block(1, 1, 3, 3) = -CppRot::CrossProductEquivalent(omega_hat);
double phi = 0.5 * omega_norm * dt_;
A_ = cos(phi) * I44 + sin(phi) * omega_hat_44_equivalent;
F_.block(0, 0, 3, 3) = (-CppRot::CrossProductEquivalent(omega_est_) * dt_).exp();
F_.block(3, 3, 3, 3) = I33;
F_.block(3, 6, 3, 3) = I33 * dt_;
F_.block(6, 6, 3, 3) = I33 * exp(-dt_ / tau_);
// propagate quaternion
quat_est_ = Utilities::Vec4ToQuat( A_ * Utilities::QuatToVec4(quat_est_) );
// propagate omega vector
omega_est_ = F_.block(3, 3, 3, 3)*omega_est_ + F_.block(3, 6, 3, 3)*alpha_est_;
// propagate alpha vector
alpha_est_ = F_.block(6, 6, 3, 3)*alpha_est_;
// propagate covariance
covar_est_ = F_ * covar_est_ * F_.transpose() + Q_;
}
// Update step
void MEKF::Update(const VectorXd &measurement)
{
// Kalman gain
MatrixXd K = covar_est_ * H_.transpose() * ((H_ * covar_est_ * H_.transpose() + R_).inverse());
// delta Gibbs update
Quaterniond quat_meas = Utilities::Vec4ToQuat(measurement.head(4));
Quaterniond delta_quat = CppRot::QuatMult_S(quat_meas, quat_est_.inverse());
Vector3d meas_innovation = 2.0 * delta_quat.vec() / delta_quat.w();
delta_gibbs_est_ = K.block(0, 0, 3, 3)*meas_innovation;
// Joseph update (general)
MatrixXd I = MatrixXd::Identity(num_states_, num_states_);
covar_est_ = (I - K * H_) * covar_est_ * ((I - K * H_).transpose()) + K * R_ * (K.transpose());
}
// Reset step
void MEKF::Reset()
{
Quaterniond delta_quat = Quaterniond::Identity();
delta_quat.w() = 1.0;
delta_quat.vec() = 0.5*delta_gibbs_est_;
Quaterniond quat_star = CppRot::QuatMult_S(delta_quat, quat_est_).normalized();
// NOTE: heuristic method to ignore 180 deg pose ambiguities
Quaterniond dq = CppRot::QuatMult_S(quat_est_, quat_star.inverse());
double dangle = 2.0*acos( abs( dq.w() ) );
if (dangle < 30.0*Utilities::DEG2RAD)
{
quat_est_ = quat_star;
}
quat_est_ = quat_star;
processed_measurement_ = true;
}
void MEKF::StoreAndClean()
{
/*
if(processed_measurement_)
{
last_state_estimate = statek1k1_;
last_covar_estimate = covark1k1_;
//states.push_back(err_statek1k1_);
//covars.push_back(covark1k1_);
statekk_ = statek1k1_;
covarkk_ = covark1k1_;
}
else
{
last_state_estimate = statek1k_;
last_covar_estimate = covark1k_;
//states.push_back(err_statek1k_);
//covars.push_back(covark1k_);
statekk_ = statek1k_;
covarkk_ = covark1k_;
}
*/
processed_measurement_ = false;
/*
statek1k_ = VectorXd::Zero(num_states_);
statek1k1_ = VectorXd::Zero(num_states_);
covark1k_ = MatrixXd::Zero(num_states_covar_, num_states_covar_);
covark1k1_ = MatrixXd::Zero(num_states_covar_, num_states_covar_);
*/
}
void MEKF::PrintModelMatrices()
{
std::cout << "A:\t" << std::endl << A_ << std::endl << std::endl;
std::cout << "F:\t" << std::endl << F_ << std::endl << std::endl;
std::cout << "Q:\t" << std::endl << Q_ << std::endl << std::endl;
std::cout << "H:\t" << std::endl << H_ << std::endl << std::endl;
std::cout << "R:\t" << std::endl << R_ << std::endl << std::endl;
}
} // end namespace