AHRS mechanization small efficiency change (in progress)
							parent
							
								
									169eb4af3e
								
							
						
					
					
						commit
						5f5e481394
					
				| 
						 | 
				
			
			@ -83,14 +83,21 @@ Mechanization_bRn2 Mechanization_bRn2::integrate(const Vector& u,
 | 
			
		|||
    const double dt) const {
 | 
			
		||||
  // integrate rotation nRb based on gyro measurement u and bias x_g
 | 
			
		||||
 | 
			
		||||
#ifndef MODEL_NAV_FRAME_ROTATION
 | 
			
		||||
  // get body to inertial (measured in b) from gyro, subtract bias
 | 
			
		||||
  Vector b_omega_ib = u - x_g_;
 | 
			
		||||
 | 
			
		||||
  // assume nav to inertial through movement is unknown
 | 
			
		||||
  // nav to inertial due to Earth's rotation and our movement on Earth surface
 | 
			
		||||
  // TODO: figure out how to do this if we need it
 | 
			
		||||
  Vector b_omega_in = zero(3);
 | 
			
		||||
 | 
			
		||||
  // get angular velocity on bRn measured in body frame
 | 
			
		||||
  // calculate angular velocity on bRn measured in body frame
 | 
			
		||||
  Vector b_omega_bn = b_omega_in - b_omega_ib;
 | 
			
		||||
#else
 | 
			
		||||
  // Assume a non-rotating nav frame (probably an approximation)
 | 
			
		||||
  // calculate angular velocity on bRn measured in body frame
 | 
			
		||||
  Vector b_omega_bn = x_g_ - u;
 | 
			
		||||
#endif
 | 
			
		||||
 | 
			
		||||
  // convert to navigation frame
 | 
			
		||||
  Rot3 nRb = bRn_.inverse();
 | 
			
		||||
| 
						 | 
				
			
			
 | 
			
		|||
| 
						 | 
				
			
			@ -5,11 +5,12 @@
 | 
			
		|||
 * @author Chris Beall
 | 
			
		||||
 */
 | 
			
		||||
 | 
			
		||||
#include <list>
 | 
			
		||||
#include "../AHRS.h"
 | 
			
		||||
#include <gtsam/geometry/Rot3.h>
 | 
			
		||||
#include <gtsam/base/Vector.h>
 | 
			
		||||
#include "../AHRS.h"
 | 
			
		||||
#include <gtsam/base/Testable.h>
 | 
			
		||||
#include <CppUnitLite/TestHarness.h>
 | 
			
		||||
#include <list>
 | 
			
		||||
 | 
			
		||||
using namespace std;
 | 
			
		||||
using namespace gtsam;
 | 
			
		||||
| 
						 | 
				
			
			@ -67,6 +68,21 @@ TEST (AHRS, constructor) {
 | 
			
		|||
  AHRS ahrs = AHRS(stationaryU,stationaryF,g_e);
 | 
			
		||||
}
 | 
			
		||||
 | 
			
		||||
/* ************************************************************************* */
 | 
			
		||||
// TODO make a testMechanization_bRn2
 | 
			
		||||
TEST (AHRS, Mechanization_integrate) {
 | 
			
		||||
  AHRS ahrs = AHRS(stationaryU,stationaryF,g_e);
 | 
			
		||||
  Mechanization_bRn2 mech;
 | 
			
		||||
  KalmanFilter::State state;
 | 
			
		||||
//  boost::tie(mech,state) = ahrs.initialize(g_e);
 | 
			
		||||
//  Vector u = Vector_(3,0.05,0.0,0.0);
 | 
			
		||||
//  double dt = 2;
 | 
			
		||||
//  Rot3 expected;
 | 
			
		||||
//  Mechanization_bRn2 mech2 = mech.integrate(u,dt);
 | 
			
		||||
//  Rot3 actual = mech2.bRn();
 | 
			
		||||
//  EXPECT(assert_equal(expected, actual));
 | 
			
		||||
}
 | 
			
		||||
 | 
			
		||||
/* ************************************************************************* */
 | 
			
		||||
/* TODO: currently fails because of problem with ill-conditioned system
 | 
			
		||||
TEST (AHRS, init) {
 | 
			
		||||
| 
						 | 
				
			
			
 | 
			
		|||
		Loading…
	
		Reference in New Issue