17 const double num_observations =
m.cols();
18 const Vector3 mean =
m.rowwise().sum() / num_observations;
20 return D *
trans(
D) / (num_observations - 1);
46 F_g_ = -I_3x3 / tau_g;
47 F_a_ = -I_3x3 / tau_a;
48 Vector3 var_omega_w = 0 * Vector::Ones(3);
49 Vector3 var_omega_g = (0.0034 * 0.0034) * Vector::Ones(3);
50 Vector3 var_omega_a = (0.034 * 0.034) * Vector::Ones(3);
51 Vector3 sigmas_v_g_sq = sigmas_v_g.array().square();
52 var_w_ << var_omega_w, var_omega_g, sigmas_v_g_sq, var_omega_a;
70 Matrix Omega_T = (
Matrix(3, 3) <<
cy * cp, -sy, 0.0, sy * cp,
cy, 0.0, -sp, 0.0, 1.0).finished();
77 double g23 =
g2 *
g2 + g3 * g3;
78 double g123 =
g1 *
g1 + g23;
81 0.0, g3 / g23, -(
g2 / g23),
83 0.0, 0.0, 0.0).finished();
86 Matrix Pa = 0.025 * 0.025 * I_3x3;
89 Matrix P12 = -Omega_T * H_g * Pa;
92 P_plus_k2.block<3,3>(0, 0) = P11;
93 P_plus_k2.block<3,3>(0, 3) = Z_3x3;
94 P_plus_k2.block<3,3>(0, 6) = P12;
96 P_plus_k2.block<3,3>(3, 0) = Z_3x3;
97 P_plus_k2.block<3,3>(3, 3) =
Pg_;
98 P_plus_k2.block<3,3>(3, 6) = Z_3x3;
100 P_plus_k2.block<3,3>(6, 0) =
trans(P12);
101 P_plus_k2.block<3,3>(6, 3) = Z_3x3;
102 P_plus_k2.block<3,3>(6, 6) = Pa;
123 F_k.block<3,3>(0, 3) = -bRn;
124 F_k.block<3,3>(3, 3) =
F_g_;
125 F_k.block<3,3>(6, 6) =
F_a_;
129 G_k.block<3,3>(0, 0) = -bRn;
130 G_k.block<3,3>(0, 6) = -bRn;
131 G_k.block<3,3>(3, 3) = I_3x3;
132 G_k.block<3,3>(6, 9) = I_3x3;
139 Vector9
u2;
u2.setZero();
142 return make_pair(newMech, newState);
153 double mu_f = f_.norm() - ge;
154 double mu_u = u_.norm();
155 return (
std::abs(mu_f)<0.5 && mu_u < 5.0 / 180.0 *
M_PI);
159 std::pair<Mechanization_bRn2, KalmanFilter::State>
AHRS::aid(
161 const Vector&
f,
bool Farrell)
const {
184 z = bRn *
n_g_ - measured_b_g;
187 H =
collect(3, &b_g, &Z_3x3, &I_3x3);
200 updatedState =
KF_.
init(dx, updatedState->covariance());
202 return make_pair(newMech, updatedState);
209 const Rot3& R_previous)
const {
214 Vector z =
f - increment * f_previous;
230 updatedState =
KF_.
init(dx, updatedState->covariance());
232 return make_pair(newMech, updatedState);