17 const double num_observations = m.
cols();
18 const Vector3 mean = m.rowwise().sum() / num_observations;
20 return D *
trans(D) / (num_observations - 1);
31 size_t T = stationaryU.cols();
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),
82 std::sqrt(g23) / g123, -f * (g1 *
g2), -f * (g1 * g3),
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;
106 return std::make_pair(
mech0_, state);
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;
135 Matrix9 Psi_k = I_9x9 + dt * F_k;
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);
void print(const Matrix &A, const string &s, ostream &stream)
Matrix< SCALARB, Dynamic, Dynamic, opt_B > B
Mechanization_bRn2 mech0_
Initial mechanization state.
const Vector3 & x_a() const
EIGEN_DEVICE_FUNC Derived & setZero(Index size)
Jet< T, N > cos(const Jet< T, N > &f)
static Mechanization_bRn2 initialize(const Matrix &U, const Matrix &F, const double g_e=0, bool flat=false)
Matrix version of initialize.
State predictQ(const State &p, const Matrix &F, const Matrix &B, const Vector &u, const Matrix &Q) const
Vector3 sigmas_v_a_
measurement sigma
GaussianDensity::shared_ptr State
double pitch(OptionalJacobian< 1, 3 > H={}) const
Matrix3 F_g_
gyro bias dynamics
Rot2 R(Rot2::fromAngle(0.1))
Jet< T, N > sin(const Jet< T, N > &f)
Vector3 b_g(double g_e) const
gravity in the body frame
std::pair< Mechanization_bRn2, KalmanFilter::State > initialize(double g_e)
std::pair< Mechanization_bRn2, KalmanFilter::State > integrate(const Mechanization_bRn2 &mech, KalmanFilter::State state, const Vector &u, double dt)
set noclip points set clip one set noclip two set bar set border lt lw set xdata set ydata set zdata set x2data set y2data set boxwidth set dummy y set format x g set format y g set format x2 g set format y2 g set format z g set angles radians set nogrid set key title set key left top Right noreverse box linetype linewidth samplen spacing width set nolabel set noarrow set nologscale set logscale x set set pointsize set encoding default set nopolar set noparametric set set set set surface set nocontour set clabel set mapping cartesian set nohidden3d set cntrparam order set cntrparam linear set cntrparam levels auto set cntrparam points set size set set xzeroaxis lt lw set x2zeroaxis lt lw set yzeroaxis lt lw set y2zeroaxis lt lw set tics in set ticslevel set tics set mxtics default set mytics default set mx2tics default set my2tics default set xtics border mirror norotate autofreq set ytics border mirror norotate autofreq set ztics border nomirror norotate autofreq set nox2tics set noy2tics set timestamp bottom norotate set rrange [*:*] noreverse nowriteback set trange [*:*] noreverse nowriteback set urange [*:*] noreverse nowriteback set vrange [*:*] noreverse nowriteback set xlabel matrix size set x2label set timefmt d m y n H
Mechanization_bRn2 integrate(const Vector3 &u, const double dt) const
void print(const std::string &s="") const
print
EIGEN_DEVICE_FUNC const CwiseSqrtReturnType cwiseSqrt() const
Rot3 is a 3D rotation represented as a rotation matrix if the preprocessor symbol GTSAM_USE_QUATERNIO...
Matrix trans(const Matrix &A)
static const Vector2 mean(20, 40)
Rot3 inverse() const
inverse of a rotation
std::pair< Mechanization_bRn2, KalmanFilter::State > aid(const Mechanization_bRn2 &mech, KalmanFilter::State state, const Vector &f, bool Farrell=0) const
Matrix collect(const std::vector< const Matrix *> &matrices, size_t m, size_t n)
Eigen::Triplet< double > T
Point2(* f)(const Point3 &, OptionalJacobian< 2, 3 >)
Vector3 n_g_
gravity in nav frame
KalmanFilter KF_
initial Kalman filter
Variances var_w_
dynamic noise variances
const Vector3 & x_g() const
Matrix3 skewSymmetric(double wx, double wy, double wz)
void print(const std::string &s="") const
print
State init(const Vector &x0, const SharedDiagonal &P0) const
std::pair< Mechanization_bRn2, KalmanFilter::State > aidGeneral(const Mechanization_bRn2 &mech, KalmanFilter::State state, const Vector &f, const Vector &f_expected, const Rot3 &R_previous) const
Matrix3 F_a_
acc bias dynamics
Class between(const Class &g) const
Pose3 g1(Rot3(), Point3(100.0, 0.0, 300.0))
Jet< T, N > sqrt(const Jet< T, N > &f)
bool isAidingAvailable(const Mechanization_bRn2 &mech, const Vector &f, const Vector &u, double ge) const
Matrix3 n_g_cross_
and its skew-symmetric matrix
Map< Matrix< T, Dynamic, Dynamic, ColMajor >, 0, OuterStride<> > matrix(T *data, int rows, int cols, int stride)
The matrix class, also used for vectors and row-vectors.
Pose3 g2(g1.expmap(h *V1_g1))
EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE EIGEN_CONSTEXPR Index cols() const EIGEN_NOEXCEPT
Mechanization_bRn2 correct(const Vector9 &dx) const
State updateQ(const State &p, const Matrix &H, const Vector &z, const Matrix &Q) const
static Matrix3 Cov(const Vector3s &m)