From 623f94f85a49f1b720a025c680769ba2ba028ba0 Mon Sep 17 00:00:00 2001 From: Martin Miller Date: Tue, 4 Apr 2017 13:59:03 -0500 Subject: Update Body to use STATESIZE --- src/body.cpp | 141 +++++++++++++++++++++++++--------------------------------- src/body.h | 38 +++++++--------- src/state.cpp | 7 +-- 3 files changed, 81 insertions(+), 105 deletions(-) (limited to 'src') diff --git a/src/body.cpp b/src/body.cpp index f7440b5..819bd01 100644 --- a/src/body.cpp +++ b/src/body.cpp @@ -38,11 +38,7 @@ Body::clamp() *-------------------------------------------------------------------------------------- */ void -#ifdef FULLSTATE -Body::dx ( const Matrix &del ) -#else -Body::dx ( const Matrix &del ) -#endif +Body::dx ( const Matrix &del ) { X += del; clamp(); @@ -65,11 +61,7 @@ Body::vel ( const Matrix &v ) *-------------------------------------------------------------------------------------- */ Matrix -#ifdef FULLSTATE -Body::S ( const Matrix &Pxx ) -#else -Body::S ( const Matrix &Pxx ) -#endif +Body::S ( const Matrix &Pxx ) { Matrix S; S << Pxx(2,2); @@ -117,26 +109,17 @@ Body::R() * Description: Returns Q matrix of process noise for the body. *-------------------------------------------------------------------------------------- */ -#ifdef FULLSTATE -Matrix -#else -Matrix -#endif +Matrix Body::Q (double dt) { -#ifdef FULLSTATE - Matrix Q; - Q = Matrix::Zero(); -#else - Matrix Q; - Q = Matrix::Zero(); -#endif + Matrix Q; + Q = Matrix::Zero(); Q.block<3,3>(0,0) = 0.25*dt*dt*dt*dt*Matrix::Identity(); Q.block<3,3>(3,0) = 0.5*dt*dt*dt*Matrix::Identity(); Q.block<3,3>(0,3) = 0.5*dt*dt*dt*Matrix::Identity(); Q.block<3,3>(3,3) = dt*dt*Matrix::Identity(); Q *= IMU_NOISE; -#ifdef FULLSTATE +#if STATESIZE==13 Q.block<4,4>(6,6) = dt*dt*IMU_NOISE*Matrix::Identity(); Q.block<3,3>(10,10) = dt*dt*IMU_RANDOMWALK*Matrix::Identity(); #else @@ -152,20 +135,11 @@ Body::Q (double dt) * Description: Returns the Jacobian of the measurement model, H. *-------------------------------------------------------------------------------------- */ -#ifdef FULLSTATE -Matrix -#else -Matrix -#endif +Matrix Body::H ( ) { -#ifdef FULLSTATE - Matrix H; - H = Matrix::Zero(); -#else - Matrix H; - H = Matrix::Zero(); -#endif + Matrix H; + H = Matrix::Zero(); H(2) = 1.; return H ; } /* ----- end of method Body::H ----- */ @@ -193,32 +167,29 @@ Body::h ( ) * Description: Returns the Jacobian of the motion model of the body. *-------------------------------------------------------------------------------------- */ -#ifdef FULLSTATE -Matrix +Matrix +#if STATESIZE==13 +Body::F ( const Vector3d &ang, double dt ) #else -Matrix -#endif Body::F ( const Vector3d &ang, const Quaterniond &q, double dt ) +#endif { -#ifdef FULLSTATE - Matrix F = Matrix::Zero(); - double qbw1,qbw2,qbw3,qbw4; - Quaterniond qbw = qhat(); - qbw1 = qbw.x(); - qbw2 = qbw.y(); - qbw3 = qbw.z(); - qbw4 = qbw.w(); - Matrix Rbw(qbw.toRotationMatrix()); -#else - Matrix F = Matrix::Zero(); - Matrix Rbw(q.toRotationMatrix()); + Matrix F = Matrix::Zero(); +#if STATESIZE==13 + Quaterniond q = qhat(); #endif + Matrix Rbw(q.toRotationMatrix()); + Matrix W; W = skewSymmetric(ang); F.block<3,3>(0,3) = Rbw; F.block<3,3>(3,3) = -W; - F.block<3,3>(3,6) = -Matrix::Identity(); -#ifdef FULLSTATE +#if STATESIZE==13 + double qbw1,qbw2,qbw3,qbw4; + qbw1 = q.x(); + qbw2 = q.y(); + qbw3 = q.z(); + qbw4 = q.w(); /* Jacobian generated using symbolic matlab */ double v1,v2,v3; v1 = X(3); @@ -240,12 +211,12 @@ Body::F ( const Vector3d &ang, const Quaterniond &q, double dt ) -2*gravity_world*qbw4, -2*gravity_world*qbw3, -2*gravity_world*qbw2, -2*gravity_world*qbw1, 2*gravity_world*qbw1, 2*gravity_world*qbw2, -2*gravity_world*qbw3, -2*gravity_world*qbw4; F.block<4,4>(6,6) = omega(ang); - F *= dt; - F += Matrix::Identity(); + F.block<3,3>(3,10) = -Matrix::Identity(); #else - F *= dt; - F += Matrix::Identity(); + F.block<3,3>(3,6) = -Matrix::Identity(); #endif + F *= dt; + F += Matrix::Identity(); return F; } /* ----- end of method Body::F ----- */ @@ -276,26 +247,23 @@ Body::omega ( const Vector3d &x ) *-------------------------------------------------------------------------------------- */ void -Body::motionModel ( const Vector3d &acc, const Vector3d &ang, const Quaterniond &q, const double dt) -{ -#ifdef FULLSTATE - Vector3d bias(X.segment<3>(10)); +#if STATESIZE==13 +Body::motionModel ( const Vector3d &acc, const Vector3d &ang, const double dt) #else - Vector3d bias(X.segment<3>(6)); +Body::motionModel ( const Vector3d &acc, const Vector3d &ang, const Quaterniond &q, const double dt) #endif - Vector3d gravity_world(0.,0.,9.80655); +{ + Vector3d bias = accelerometer_bias(); Matrix A; Matrix b; A = Matrix::Zero(); b = Matrix::Zero(); -#ifdef FULLSTATE - Quaterniond qbw qhat(); - Matrix Rbw(qbw.toRotationMatrix()); -#else - Matrix Rbw(q.toRotationMatrix()); +#if STATESIZE==13 + Quaterniond q = qhat(); #endif + Matrix Rbw(q.toRotationMatrix()); A.block<3,3>(0,0) = Rbw; Matrix W; W = skewSymmetric(ang); @@ -303,7 +271,7 @@ Body::motionModel ( const Vector3d &acc, const Vector3d &ang, const Quaterniond b.segment<3>(3) = acc-bias+Rbw.transpose()*gravity_world; X.segment<6>(0) += (A*X.segment<3>(3)+b)*dt; -#ifdef FULLSTATE +#if STATESIZE==13 X.segment<4>(6) += 0.5*omega(ang)*X.segment<4>(6); #endif clamp(); @@ -335,13 +303,29 @@ Body::unicsv ( ) return ; } /* ----- end of method Body::unicsv ----- */ - void +void Body::accelerometer_bias ( const Vector3d &b ) { +#if STATESIZE==13 + X.segment<3>(10) = b; +#else X.segment<3>(6) = b; +#endif return ; } /* ----- end of method State::accelerometer_bias ----- */ +Vector3d +Body::accelerometer_bias ( ) +{ + Vector3d bs; +#if STATESIZE==13 + bs = X.segment<3>(10); +#else + bs = X.segment<3>(6); +#endif + return bs ; +} /* ----- end of method State::accelerometer_bias ----- */ + /* *-------------------------------------------------------------------------------------- * Class: Body @@ -361,22 +345,14 @@ Body::vel ( ) return X.segment<3>(3); } /* ----- end of method Body::vel ----- */ -#ifdef FULLSTATE -Matrix -#else -Matrix -#endif +Matrix Body::asVector ( ) { return X; } /* ----- end of method Body::asVector ----- */ void -#ifdef FULLSTATE -Body::asVector ( const Matrix &m ) -#else -Body::asVector ( const Matrix &m ) -#endif +Body::asVector ( const Matrix &m ) { X = m; return ; @@ -393,7 +369,12 @@ Body::asVector ( const Matrix &m ) Quaterniond Body::qhat ( ) { +#if STATESIZE==13 Quaterniond qbw(X(9),X(6),X(7),X(8)); +#else + fprintf(stderr, "Quaternion is not being estimated, quitting.\n"); + exit(1); +#endif return qbw; } /* ----- end of method Body::qhat ----- */ diff --git a/src/body.h b/src/body.h index 5544bba..97df1e9 100644 --- a/src/body.h +++ b/src/body.h @@ -9,7 +9,7 @@ //#define DOCLAMP #define MAXHEIGHT -1.5 /* Notion of max and min is reversed due to z pointing down */ #define MINHEIGHT -0.3 /* */ -#define FULLSTATE /* Uncomment to estimate quaternion */ +#define STATESIZE 13 using Eigen::Matrix; @@ -29,27 +29,21 @@ class Body Body (){ gravity_world << 0.,0.,9.80655; }; /* constructor */ /* ==================== ACCESSORS ======================================= */ -#ifdef FULLSTATE - Matrix asVector(); - void asVector(const Matrix &m); - void dx( const Matrix &del); - Matrix F(const Vector3d &ang, const Quaterniond &q, double dt); - Matrix H(); - Matrix Q(double dt); - Matrix S(const Matrix &Pxx); +#if STATESIZE==13 + Matrix F(const Vector3d &ang, double dt); Quaterniond qhat(); #else - Matrix F(const Vector3d &ang, const Quaterniond &q, double dt); - Matrix asVector(); - void asVector(const Matrix &m); - void dx( const Matrix &del); - Matrix H(); - Matrix Q(double dt); - Matrix S(const Matrix &Pxx); + Matrix F(const Vector3d &ang, const Quaterniond &q, double dt); #endif + Matrix asVector(); + void asVector(const Matrix &m); + void dx( const Matrix &del); + Matrix H(); + Matrix Q(double dt); + Matrix S(const Matrix &Pxx); Vector3d ned(); Vector3d vel(); - + Vector3d accelerometer_bias( ); /* ==================== MUTATORS ======================================= */ void accelerometer_bias( const Vector3d &b); void clamp(); @@ -58,8 +52,12 @@ class Body /* ==================== OPERATORS ======================================= */ Matrix h(); +#if STATESIZE==13 + void motionModel ( const Vector3d &acc, const Vector3d &ang, const double dt); +#else void motionModel ( const Vector3d &acc, const Vector3d &ang, const Quaterniond &q, const double dt); +#endif Matrix R(); Matrix skewSymmetric(const Vector3d &x); Matrix omega(const Vector3d &x); @@ -74,11 +72,7 @@ class Body /* ==================== METHODS ======================================= */ /* ==================== DATA MEMBERS ======================================= */ -#ifdef FULLSTATE - Matrix X; -#else - Matrix X; -#endif + Matrix X; char utm_c; int utm_i; Vector3d gravity_world; diff --git a/src/state.cpp b/src/state.cpp index 5253425..dfe41fa 100644 --- a/src/state.cpp +++ b/src/state.cpp @@ -553,9 +553,6 @@ State::F ( const Vector3d &w, double dt ) State::F ( const Quaterniond &q, const Vector3d &w, double dt ) #endif { -#if STATESIZE==13 - Quaterniond q = body->qhat(); -#endif Vector3d v; v = body->vel(); // Allocate matrix F @@ -564,7 +561,11 @@ State::F ( const Quaterniond &q, const Vector3d &w, double dt ) f = MatrixXd::Zero(rows,rows); // Set body F +#if STATESIZE==13 + f.topLeftCorner() = body->F(w,dt); +#else f.topLeftCorner() = body->F(w,q,dt); +#endif // Set Fxi Fyi { // limit i's scope auto i = features.begin(); -- cgit v1.1