| 
									
										
										
										
											2013-05-21 07:16:44 +08:00
										 |  |  | /*
 | 
					
						
							|  |  |  |  * @file AHRS.cpp | 
					
						
							|  |  |  |  * @brief Attitude and Heading Reference System implementation | 
					
						
							|  |  |  |  *  Created on: Jan 26, 2012 | 
					
						
							|  |  |  |  *      Author: cbeall3 | 
					
						
							|  |  |  |  */ | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | #include "AHRS.h"
 | 
					
						
							|  |  |  | #include <cmath>
 | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | using namespace std; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | namespace gtsam { | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2014-12-04 19:30:41 +08:00
										 |  |  | /* ************************************************************************* */ | 
					
						
							|  |  |  | Matrix3 AHRS::Cov(const Vector3s& m) { | 
					
						
							| 
									
										
										
										
											2013-05-21 07:16:44 +08:00
										 |  |  |   const double num_observations = m.cols(); | 
					
						
							| 
									
										
										
										
											2014-12-04 19:30:41 +08:00
										 |  |  |   const Vector3 mean = m.rowwise().sum() / num_observations; | 
					
						
							|  |  |  |   Vector3s D = m.colwise() - mean; | 
					
						
							|  |  |  |   return D * trans(D) / (num_observations - 1); | 
					
						
							| 
									
										
										
										
											2013-05-21 07:16:44 +08:00
										 |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | /* ************************************************************************* */ | 
					
						
							| 
									
										
										
										
											2013-06-15 05:18:22 +08:00
										 |  |  | AHRS::AHRS(const Matrix& stationaryU, const Matrix& stationaryF, double g_e, | 
					
						
							| 
									
										
										
										
											2013-10-11 01:52:57 +08:00
										 |  |  |     bool flat) : | 
					
						
							| 
									
										
										
										
											2013-05-21 07:16:44 +08:00
										 |  |  |     KF_(9) { | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   // Initial state
 | 
					
						
							| 
									
										
										
										
											2013-06-15 05:18:22 +08:00
										 |  |  |   mech0_ = Mechanization_bRn2::initialize(stationaryU, stationaryF, g_e, flat); | 
					
						
							| 
									
										
										
										
											2013-05-21 07:16:44 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   size_t T = stationaryU.cols(); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   // estimate standard deviation on gyroscope readings
 | 
					
						
							| 
									
										
										
										
											2014-12-04 19:30:41 +08:00
										 |  |  |   Pg_ = Cov(stationaryU); | 
					
						
							| 
									
										
										
										
											2016-03-12 03:34:19 +08:00
										 |  |  |   Vector3 sigmas_v_g = (Pg_.diagonal() * T).cwiseSqrt(); | 
					
						
							| 
									
										
										
										
											2013-05-21 07:16:44 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   // estimate standard deviation on accelerometer readings
 | 
					
						
							| 
									
										
										
										
											2014-12-04 19:30:41 +08:00
										 |  |  |   Pa_ = Cov(stationaryF); | 
					
						
							| 
									
										
										
										
											2013-05-21 07:16:44 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   // Quantities needed for integration
 | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   // dynamics, Chris' email September 23, 2011 3:38:05 PM EDT
 | 
					
						
							|  |  |  |   double tau_g = 730; // correlation time for gyroscope
 | 
					
						
							|  |  |  |   double tau_a = 730; // correlation time for accelerometer
 | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2014-12-04 19:30:41 +08:00
										 |  |  |   F_g_ = -I_3x3 / tau_g; | 
					
						
							|  |  |  |   F_a_ = -I_3x3 / tau_a; | 
					
						
							| 
									
										
										
										
											2016-04-16 05:30:54 +08:00
										 |  |  |   Vector3 var_omega_w = 0 * Vector::Ones(3); // TODO
 | 
					
						
							|  |  |  |   Vector3 var_omega_g = (0.0034 * 0.0034) * Vector::Ones(3); | 
					
						
							|  |  |  |   Vector3 var_omega_a = (0.034 * 0.034) * Vector::Ones(3); | 
					
						
							| 
									
										
										
										
											2016-03-06 10:20:32 +08:00
										 |  |  |   Vector3 sigmas_v_g_sq = sigmas_v_g.array().square(); | 
					
						
							| 
									
										
										
										
											2014-12-04 19:30:41 +08:00
										 |  |  |   var_w_ << var_omega_w, var_omega_g, sigmas_v_g_sq, var_omega_a; | 
					
						
							| 
									
										
										
										
											2013-05-21 07:16:44 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   // Quantities needed for aiding
 | 
					
						
							| 
									
										
										
										
											2016-03-12 03:34:19 +08:00
										 |  |  |   sigmas_v_a_ = (T * Pa_.diagonal()).cwiseSqrt(); | 
					
						
							| 
									
										
										
										
											2013-05-21 07:16:44 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   // gravity in nav frame
 | 
					
						
							| 
									
										
										
										
											2014-11-23 08:35:27 +08:00
										 |  |  |   n_g_ = (Vector(3) << 0.0, 0.0, g_e).finished(); | 
					
						
							| 
									
										
										
										
											2013-05-21 07:16:44 +08:00
										 |  |  |   n_g_cross_ = skewSymmetric(n_g_);  // nav frame has Z down !!!
 | 
					
						
							|  |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | /* ************************************************************************* */ | 
					
						
							|  |  |  | std::pair<Mechanization_bRn2, KalmanFilter::State> AHRS::initialize(double g_e) { | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   // Calculate Omega_T, formula 2.80 in Farrell08book
 | 
					
						
							|  |  |  |   double cp = cos(mech0_.bRn().inverse().pitch()); | 
					
						
							|  |  |  |   double sp = sin(mech0_.bRn().inverse().pitch()); | 
					
						
							| 
									
										
										
										
											2013-11-06 00:06:10 +08:00
										 |  |  |   double cy = cos(0.0); | 
					
						
							|  |  |  |   double sy = sin(0.0); | 
					
						
							| 
									
										
										
										
											2014-11-23 08:35:27 +08:00
										 |  |  |   Matrix Omega_T = (Matrix(3, 3) << cy * cp, -sy, 0.0, sy * cp, cy, 0.0, -sp, 0.0, 1.0).finished(); | 
					
						
							| 
									
										
										
										
											2013-05-21 07:16:44 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   // Calculate Jacobian of roll/pitch/yaw wrpt (g1,g2,g3), see doc/ypr.nb
 | 
					
						
							|  |  |  |   Vector b_g = mech0_.b_g(g_e); | 
					
						
							|  |  |  |   double g1 = b_g(0); | 
					
						
							|  |  |  |   double g2 = b_g(1); | 
					
						
							|  |  |  |   double g3 = b_g(2); | 
					
						
							|  |  |  |   double g23 = g2 * g2 + g3 * g3; | 
					
						
							|  |  |  |   double g123 = g1 * g1 + g23; | 
					
						
							| 
									
										
										
										
											2013-05-22 01:24:49 +08:00
										 |  |  |   double f = 1 / (std::sqrt(g23) * g123); | 
					
						
							| 
									
										
										
										
											2013-12-17 05:33:12 +08:00
										 |  |  |   Matrix H_g = (Matrix(3, 3) << | 
					
						
							| 
									
										
										
										
											2014-11-23 08:35:27 +08:00
										 |  |  |       0.0, g3 / g23, -(g2 / g23),                            // roll
 | 
					
						
							| 
									
										
										
										
											2013-05-22 01:24:49 +08:00
										 |  |  |       std::sqrt(g23) / g123, -f * (g1 * g2), -f * (g1 * g3), // pitch
 | 
					
						
							| 
									
										
										
										
											2014-11-23 08:35:27 +08:00
										 |  |  |       0.0, 0.0, 0.0).finished();                             // we don't know anything on yaw
 | 
					
						
							| 
									
										
										
										
											2013-05-21 07:16:44 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   // Calculate the initial covariance matrix for the error state dx, Farrell08book eq. 10.66
 | 
					
						
							| 
									
										
										
										
											2016-04-12 03:11:29 +08:00
										 |  |  |   Matrix Pa = 0.025 * 0.025 * I_3x3; | 
					
						
							| 
									
										
										
										
											2013-05-21 07:16:44 +08:00
										 |  |  |   Matrix P11 = Omega_T * (H_g * (Pa + Pa_) * trans(H_g)) * trans(Omega_T); | 
					
						
							|  |  |  |   P11(2, 2) = 0.0001; | 
					
						
							|  |  |  |   Matrix P12 = -Omega_T * H_g * Pa; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   Matrix P_plus_k2 = Matrix(9, 9); | 
					
						
							| 
									
										
										
										
											2014-03-07 10:05:11 +08:00
										 |  |  |   P_plus_k2.block<3,3>(0, 0) = P11; | 
					
						
							| 
									
										
										
										
											2014-12-04 19:30:41 +08:00
										 |  |  |   P_plus_k2.block<3,3>(0, 3) = Z_3x3; | 
					
						
							| 
									
										
										
										
											2014-03-07 10:05:11 +08:00
										 |  |  |   P_plus_k2.block<3,3>(0, 6) = P12; | 
					
						
							| 
									
										
										
										
											2013-05-21 07:16:44 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2014-12-04 19:30:41 +08:00
										 |  |  |   P_plus_k2.block<3,3>(3, 0) = Z_3x3; | 
					
						
							| 
									
										
										
										
											2014-03-07 10:05:11 +08:00
										 |  |  |   P_plus_k2.block<3,3>(3, 3) = Pg_; | 
					
						
							| 
									
										
										
										
											2014-12-04 19:30:41 +08:00
										 |  |  |   P_plus_k2.block<3,3>(3, 6) = Z_3x3; | 
					
						
							| 
									
										
										
										
											2013-05-21 07:16:44 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2014-03-07 10:05:11 +08:00
										 |  |  |   P_plus_k2.block<3,3>(6, 0) = trans(P12); | 
					
						
							| 
									
										
										
										
											2014-12-04 19:30:41 +08:00
										 |  |  |   P_plus_k2.block<3,3>(6, 3) = Z_3x3; | 
					
						
							| 
									
										
										
										
											2014-03-07 10:05:11 +08:00
										 |  |  |   P_plus_k2.block<3,3>(6, 6) = Pa; | 
					
						
							| 
									
										
										
										
											2013-05-21 07:16:44 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2016-04-16 04:54:46 +08:00
										 |  |  |   Vector dx = Z_9x1; | 
					
						
							| 
									
										
										
										
											2013-05-21 07:16:44 +08:00
										 |  |  |   KalmanFilter::State state = KF_.init(dx, P_plus_k2); | 
					
						
							|  |  |  |   return std::make_pair(mech0_, state); | 
					
						
							|  |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | /* ************************************************************************* */ | 
					
						
							|  |  |  | std::pair<Mechanization_bRn2, KalmanFilter::State> AHRS::integrate( | 
					
						
							|  |  |  |     const Mechanization_bRn2& mech, KalmanFilter::State state, | 
					
						
							|  |  |  |     const Vector& u, double dt) { | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   // Integrate full state
 | 
					
						
							|  |  |  |   Mechanization_bRn2 newMech = mech.integrate(u, dt); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   // Integrate error state Kalman filter
 | 
					
						
							|  |  |  |   // FIXME:
 | 
					
						
							|  |  |  |   //if nargout>1
 | 
					
						
							|  |  |  |   Matrix bRn = mech.bRn().matrix(); | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2014-12-04 19:30:41 +08:00
										 |  |  |   Matrix9 F_k; F_k.setZero(); | 
					
						
							| 
									
										
										
										
											2014-03-07 10:05:11 +08:00
										 |  |  |   F_k.block<3,3>(0, 3) = -bRn; | 
					
						
							|  |  |  |   F_k.block<3,3>(3, 3) = F_g_; | 
					
						
							|  |  |  |   F_k.block<3,3>(6, 6) = F_a_; | 
					
						
							| 
									
										
										
										
											2013-05-21 07:16:44 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2014-12-04 19:30:41 +08:00
										 |  |  |   typedef Eigen::Matrix<double,9,12> Matrix9_12; | 
					
						
							|  |  |  |   Matrix9_12 G_k; G_k.setZero(); | 
					
						
							| 
									
										
										
										
											2014-03-07 10:05:11 +08:00
										 |  |  |   G_k.block<3,3>(0, 0) = -bRn; | 
					
						
							|  |  |  |   G_k.block<3,3>(0, 6) = -bRn; | 
					
						
							| 
									
										
										
										
											2014-12-04 19:30:41 +08:00
										 |  |  |   G_k.block<3,3>(3, 3) = I_3x3; | 
					
						
							|  |  |  |   G_k.block<3,3>(6, 9) = I_3x3; | 
					
						
							| 
									
										
										
										
											2013-05-21 07:16:44 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2014-12-04 19:30:41 +08:00
										 |  |  |   Matrix9 Q_k = G_k * var_w_.asDiagonal() * G_k.transpose(); | 
					
						
							|  |  |  |   Matrix9 Psi_k = I_9x9 + dt * F_k; // +dt*dt*F_k*F_k/2; // transition matrix
 | 
					
						
							| 
									
										
										
										
											2013-05-21 07:16:44 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2014-03-07 10:05:11 +08:00
										 |  |  |   // This implements update in section 10.6
 | 
					
						
							| 
									
										
										
										
											2014-12-04 19:30:41 +08:00
										 |  |  |   Matrix9 B; B.setZero(); | 
					
						
							|  |  |  |   Vector9 u2; u2.setZero(); | 
					
						
							|  |  |  |   // TODO predictQ should be templated to also take fixed size matrices.
 | 
					
						
							| 
									
										
										
										
											2013-05-21 07:16:44 +08:00
										 |  |  |   KalmanFilter::State newState = KF_.predictQ(state, Psi_k,B,u2,dt*Q_k); | 
					
						
							|  |  |  |   return make_pair(newMech, newState); | 
					
						
							|  |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2013-06-15 05:18:22 +08:00
										 |  |  | /* ************************************************************************* */ | 
					
						
							|  |  |  | bool AHRS::isAidingAvailable(const Mechanization_bRn2& mech, | 
					
						
							| 
									
										
										
										
											2014-03-07 10:05:11 +08:00
										 |  |  |     const gtsam::Vector& f, const gtsam::Vector& u, double ge) const { | 
					
						
							| 
									
										
										
										
											2013-06-15 05:18:22 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   // Subtract the biases
 | 
					
						
							|  |  |  |   Vector f_ = f - mech.x_a(); | 
					
						
							|  |  |  |   Vector u_ = u - mech.x_g(); | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2014-03-07 10:05:11 +08:00
										 |  |  |   double mu_f = f_.norm() - ge; // accelerometer same magnitude as local gravity ?
 | 
					
						
							|  |  |  |   double mu_u = u_.norm(); // gyro says we are not maneuvering ?
 | 
					
						
							| 
									
										
										
										
											2019-09-19 03:24:09 +08:00
										 |  |  |   return (std::abs(mu_f)<0.5 && mu_u < 5.0 / 180.0 * M_PI); | 
					
						
							| 
									
										
										
										
											2013-06-15 05:18:22 +08:00
										 |  |  | } | 
					
						
							| 
									
										
										
										
											2013-05-21 07:16:44 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | /* ************************************************************************* */ | 
					
						
							|  |  |  | std::pair<Mechanization_bRn2, KalmanFilter::State> AHRS::aid( | 
					
						
							|  |  |  |     const Mechanization_bRn2& mech, KalmanFilter::State state, | 
					
						
							| 
									
										
										
										
											2014-03-07 10:05:11 +08:00
										 |  |  |     const Vector& f, bool Farrell) const { | 
					
						
							| 
									
										
										
										
											2013-05-21 07:16:44 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   Matrix bRn = mech.bRn().matrix(); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   // get gravity in body from accelerometer
 | 
					
						
							|  |  |  |   Vector measured_b_g = mech.x_a() - f; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   Matrix R, H; | 
					
						
							|  |  |  |   Vector z; | 
					
						
							|  |  |  |   if (Farrell) { | 
					
						
							|  |  |  |     // calculate residual gravity measurement
 | 
					
						
							|  |  |  |     z = n_g_ - trans(bRn) * measured_b_g; | 
					
						
							| 
									
										
										
										
											2014-12-04 19:30:41 +08:00
										 |  |  |     H = collect(3, &n_g_cross_, &Z_3x3, &bRn); | 
					
						
							| 
									
										
										
										
											2016-04-12 03:11:29 +08:00
										 |  |  |     R = trans(bRn) * ((Vector3) sigmas_v_a_.array().square()).asDiagonal() * bRn; | 
					
						
							| 
									
										
										
										
											2013-05-21 07:16:44 +08:00
										 |  |  |   } else { | 
					
						
							|  |  |  |     // my measurement prediction (in body frame):
 | 
					
						
							|  |  |  |     // F(:,k) = bias - b_g
 | 
					
						
							|  |  |  |     // F(:,k) = mech.x_a + dx_a - bRn*n_g;
 | 
					
						
							|  |  |  |     // F(:,k) = mech.x_a + dx_a - bRn*(I+P)*n_g;
 | 
					
						
							|  |  |  |     // F(:,k) = mech.x_a + dx_a - b_g - bRn*(rho x n_g); // P = [rho]_x
 | 
					
						
							| 
									
										
										
										
											2013-10-11 01:52:57 +08:00
										 |  |  |   // Hence, the measurement z = b_g - (mech.x_a - F(:,k)) is predicted
 | 
					
						
							|  |  |  |   // from the filter state (dx_a, rho) as  dx_a + bRn*(n_g x rho)
 | 
					
						
							| 
									
										
										
										
											2013-06-15 05:18:22 +08:00
										 |  |  |     // z = b_g - (mech.x_a - F(:,k)) = dx_a + bRn*(n_g x rho)
 | 
					
						
							| 
									
										
										
										
											2013-05-21 07:16:44 +08:00
										 |  |  |     z = bRn * n_g_ - measured_b_g; | 
					
						
							| 
									
										
										
										
											2013-06-15 05:18:22 +08:00
										 |  |  |     // Now the Jacobian H
 | 
					
						
							| 
									
										
										
										
											2013-05-21 07:16:44 +08:00
										 |  |  |     Matrix b_g = bRn * n_g_cross_; | 
					
						
							| 
									
										
										
										
											2014-12-04 19:30:41 +08:00
										 |  |  |     H = collect(3, &b_g, &Z_3x3, &I_3x3); | 
					
						
							| 
									
										
										
										
											2013-06-15 05:18:22 +08:00
										 |  |  |     // And the measurement noise, TODO: should be created once where sigmas_v_a is given
 | 
					
						
							| 
									
										
										
										
											2016-04-12 03:11:29 +08:00
										 |  |  |     R = ((Vector3) sigmas_v_a_.array().square()).asDiagonal(); | 
					
						
							| 
									
										
										
										
											2013-05-21 07:16:44 +08:00
										 |  |  |   } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | // update the Kalman filter
 | 
					
						
							|  |  |  |   KalmanFilter::State updatedState = KF_.updateQ(state, H, z, R); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | // update full state (rotation and accelerometer bias)
 | 
					
						
							|  |  |  |   Mechanization_bRn2 newMech = mech.correct(updatedState->mean()); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | // reset KF state
 | 
					
						
							| 
									
										
										
										
											2016-04-12 03:11:29 +08:00
										 |  |  |   Vector dx = Z_9x1; | 
					
						
							| 
									
										
										
										
											2013-05-21 07:16:44 +08:00
										 |  |  |   updatedState = KF_.init(dx, updatedState->covariance()); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   return make_pair(newMech, updatedState); | 
					
						
							|  |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | /* ************************************************************************* */ | 
					
						
							|  |  |  | std::pair<Mechanization_bRn2, KalmanFilter::State> AHRS::aidGeneral( | 
					
						
							|  |  |  |     const Mechanization_bRn2& mech, KalmanFilter::State state, | 
					
						
							|  |  |  |     const Vector& f, const Vector& f_previous, | 
					
						
							| 
									
										
										
										
											2014-03-07 10:05:11 +08:00
										 |  |  |     const Rot3& R_previous) const { | 
					
						
							| 
									
										
										
										
											2013-05-21 07:16:44 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   Matrix increment = R_previous.between(mech.bRn()).matrix(); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   // expected - measured
 | 
					
						
							|  |  |  |   Vector z = f - increment * f_previous; | 
					
						
							|  |  |  |   //Vector z = increment * f_previous - f;
 | 
					
						
							|  |  |  |   Matrix b_g = skewSymmetric(increment* f_previous); | 
					
						
							| 
									
										
										
										
											2014-12-04 19:30:41 +08:00
										 |  |  |   Matrix H = collect(3, &b_g, &I_3x3, &Z_3x3); | 
					
						
							| 
									
										
										
										
											2013-05-21 07:16:44 +08:00
										 |  |  | //  Matrix R = diag(emul(sigmas_v_a_, sigmas_v_a_));
 | 
					
						
							| 
									
										
										
										
											2014-11-24 02:22:25 +08:00
										 |  |  | //  Matrix R = diag(Vector3(1.0, 0.2, 1.0)); // good for L_twice
 | 
					
						
							| 
									
										
										
										
											2016-04-12 03:11:29 +08:00
										 |  |  |   Matrix R = Vector3(0.01, 0.0001, 0.01).asDiagonal(); | 
					
						
							| 
									
										
										
										
											2013-05-21 07:16:44 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | // update the Kalman filter
 | 
					
						
							|  |  |  |   KalmanFilter::State updatedState = KF_.updateQ(state, H, z, R); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | // update full state (rotation and gyro bias)
 | 
					
						
							|  |  |  |   Mechanization_bRn2 newMech = mech.correct(updatedState->mean()); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | // reset KF state
 | 
					
						
							| 
									
										
										
										
											2016-04-12 03:11:29 +08:00
										 |  |  |   Vector dx = Z_9x1; | 
					
						
							| 
									
										
										
										
											2013-05-21 07:16:44 +08:00
										 |  |  |   updatedState = KF_.init(dx, updatedState->covariance()); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   return make_pair(newMech, updatedState); | 
					
						
							|  |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | /* ************************************************************************* */ | 
					
						
							|  |  |  | void AHRS::print(const std::string& s) const { | 
					
						
							|  |  |  |   mech0_.print(s + ".mech0_"); | 
					
						
							| 
									
										
										
										
											2014-12-04 19:30:41 +08:00
										 |  |  |   gtsam::print((Matrix)F_g_, s + ".F_g"); | 
					
						
							|  |  |  |   gtsam::print((Matrix)F_a_, s + ".F_a"); | 
					
						
							|  |  |  |   gtsam::print((Vector)var_w_, s + ".var_w"); | 
					
						
							| 
									
										
										
										
											2013-05-21 07:16:44 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2014-12-04 19:30:41 +08:00
										 |  |  |   gtsam::print((Vector)sigmas_v_a_, s + ".sigmas_v_a"); | 
					
						
							|  |  |  |   gtsam::print((Vector)n_g_, s + ".n_g"); | 
					
						
							|  |  |  |   gtsam::print((Matrix)n_g_cross_, s + ".n_g_cross"); | 
					
						
							| 
									
										
										
										
											2013-05-21 07:16:44 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2014-12-04 19:30:41 +08:00
										 |  |  |   gtsam::print((Matrix)Pg_, s + ".P_g"); | 
					
						
							|  |  |  |   gtsam::print((Matrix)Pa_, s + ".P_a"); | 
					
						
							| 
									
										
										
										
											2013-05-21 07:16:44 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | /* ************************************************************************* */ | 
					
						
							|  |  |  | AHRS::~AHRS() { | 
					
						
							|  |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | /* ************************************************************************* */ | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | } /* namespace gtsam */ |