| 
									
										
										
										
											2013-05-21 07:16:44 +08:00
										 |  |  | /**
 | 
					
						
							|  |  |  |  * @file Mechanization_bRn.cpp | 
					
						
							|  |  |  |  * @date Jan 25, 2012 | 
					
						
							|  |  |  |  * @author Chris Beall | 
					
						
							|  |  |  |  * @author Frank Dellaert | 
					
						
							|  |  |  |  */ | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | #include "Mechanization_bRn2.h"
 | 
					
						
							|  |  |  | #include <boost/foreach.hpp>
 | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | namespace gtsam { | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | /* ************************************************************************* */ | 
					
						
							|  |  |  | Mechanization_bRn2 Mechanization_bRn2::initializeVector(const std::list<Vector>& U, | 
					
						
							| 
									
										
										
										
											2013-06-15 05:18:22 +08:00
										 |  |  |     const std::list<Vector>& F, const double g_e, bool flat) { | 
					
						
							| 
									
										
										
										
											2014-11-23 08:35:27 +08:00
										 |  |  |   Matrix Umat = (Matrix(3, U.size()) << concatVectors(U)).finished(); | 
					
						
							|  |  |  |   Matrix Fmat = (Matrix(3, F.size()) << concatVectors(F)).finished(); | 
					
						
							| 
									
										
										
										
											2013-05-21 07:16:44 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2013-06-15 05:18:22 +08:00
										 |  |  |   return initialize(Umat, Fmat, g_e, flat); | 
					
						
							| 
									
										
										
										
											2013-05-21 07:16:44 +08:00
										 |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | /* ************************************************************************* */ | 
					
						
							|  |  |  | Mechanization_bRn2 Mechanization_bRn2::initialize(const Matrix& U, | 
					
						
							| 
									
										
										
										
											2013-06-15 05:18:22 +08:00
										 |  |  |     const Matrix& F, const double g_e, bool flat) { | 
					
						
							| 
									
										
										
										
											2013-05-21 07:16:44 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   // estimate gyro bias by averaging gyroscope readings (10.62)
 | 
					
						
							| 
									
										
										
										
											2014-12-22 09:52:31 +08:00
										 |  |  |   Vector3 x_g = U.rowwise().mean(); | 
					
						
							|  |  |  |   Vector3 meanF = F.rowwise().mean(); | 
					
						
							| 
									
										
										
										
											2013-05-21 07:16:44 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2013-06-15 05:18:22 +08:00
										 |  |  |   // estimate gravity
 | 
					
						
							| 
									
										
										
										
											2014-12-22 09:52:31 +08:00
										 |  |  |   Vector3 b_g; | 
					
						
							| 
									
										
										
										
											2013-05-21 07:16:44 +08:00
										 |  |  |   if(g_e == 0) { | 
					
						
							| 
									
										
										
										
											2013-06-15 05:18:22 +08:00
										 |  |  |     if (flat) | 
					
						
							|  |  |  |       // acceleration measured is  along the z-axis.
 | 
					
						
							| 
									
										
										
										
											2014-12-22 09:52:31 +08:00
										 |  |  |       b_g = (Vector3(3) << 0.0, 0.0, norm_2(meanF)).finished(); | 
					
						
							| 
									
										
										
										
											2013-06-15 05:18:22 +08:00
										 |  |  |     else | 
					
						
							|  |  |  |       // acceleration measured is the opposite of gravity (10.13)
 | 
					
						
							|  |  |  |       b_g = -meanF; | 
					
						
							| 
									
										
										
										
											2013-05-21 07:16:44 +08:00
										 |  |  |   } else { | 
					
						
							| 
									
										
										
										
											2013-06-15 05:18:22 +08:00
										 |  |  |     if (flat) | 
					
						
							|  |  |  |       // gravity is downward along the z-axis since we are flat on the ground
 | 
					
						
							| 
									
										
										
										
											2014-12-22 09:52:31 +08:00
										 |  |  |       b_g = (Vector3(3) << 0.0,0.0,g_e).finished(); | 
					
						
							| 
									
										
										
										
											2013-06-15 05:18:22 +08:00
										 |  |  |     else | 
					
						
							|  |  |  |       // normalize b_g and attribute remainder to biases
 | 
					
						
							|  |  |  |       b_g = - g_e * meanF/meanF.norm(); | 
					
						
							| 
									
										
										
										
											2013-05-21 07:16:44 +08:00
										 |  |  |   } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2013-06-15 05:18:22 +08:00
										 |  |  |   // estimate accelerometer bias
 | 
					
						
							| 
									
										
										
										
											2014-12-22 09:52:31 +08:00
										 |  |  |   Vector3 x_a = meanF + b_g; | 
					
						
							| 
									
										
										
										
											2013-06-15 05:18:22 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2013-05-21 07:16:44 +08:00
										 |  |  |   // initialize roll, pitch (eqns. 10.14, 10.15)
 | 
					
						
							|  |  |  |   double g1=b_g(0); | 
					
						
							|  |  |  |   double g2=b_g(1); | 
					
						
							|  |  |  |   double g3=b_g(2); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   // Farrell08book eqn. 10.14
 | 
					
						
							|  |  |  |   double roll = atan2(g2, g3); | 
					
						
							|  |  |  |   // Farrell08book eqn. 10.15
 | 
					
						
							|  |  |  |   double pitch = atan2(-g1, sqrt(g2 * g2 + g3 * g3)); | 
					
						
							|  |  |  |   double yaw = 0; | 
					
						
							|  |  |  |   // This returns body-to-nav nRb
 | 
					
						
							|  |  |  |   Rot3 bRn = Rot3::ypr(yaw, pitch, roll).inverse(); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   return Mechanization_bRn2(bRn, x_g, x_a); | 
					
						
							|  |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | /* ************************************************************************* */ | 
					
						
							| 
									
										
										
										
											2014-12-22 09:52:31 +08:00
										 |  |  | Mechanization_bRn2 Mechanization_bRn2::correct(const Vector3& dx) const { | 
					
						
							|  |  |  |   Vector3 rho = sub(dx, 0, 3); | 
					
						
							| 
									
										
										
										
											2013-05-21 07:16:44 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2015-07-06 07:11:04 +08:00
										 |  |  |   Rot3 delta_nRn = Rot3::Rodrigues(rho); | 
					
						
							| 
									
										
										
										
											2013-05-21 07:16:44 +08:00
										 |  |  |   Rot3 bRn = bRn_ * delta_nRn; | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2014-12-22 09:52:31 +08:00
										 |  |  |   Vector3 x_g = x_g_ + sub(dx, 3, 6); | 
					
						
							|  |  |  |   Vector3 x_a = x_a_ + sub(dx, 6, 9); | 
					
						
							| 
									
										
										
										
											2013-05-21 07:16:44 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   return Mechanization_bRn2(bRn, x_g, x_a); | 
					
						
							|  |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | /* ************************************************************************* */ | 
					
						
							| 
									
										
										
										
											2014-12-22 09:52:31 +08:00
										 |  |  | Mechanization_bRn2 Mechanization_bRn2::integrate(const Vector3& u, | 
					
						
							| 
									
										
										
										
											2013-05-21 07:16:44 +08:00
										 |  |  |     const double dt) const { | 
					
						
							|  |  |  |   // integrate rotation nRb based on gyro measurement u and bias x_g
 | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2013-06-21 08:21:18 +08:00
										 |  |  | #ifndef MODEL_NAV_FRAME_ROTATION
 | 
					
						
							| 
									
										
										
										
											2013-05-21 07:16:44 +08:00
										 |  |  |   // get body to inertial (measured in b) from gyro, subtract bias
 | 
					
						
							| 
									
										
										
										
											2014-12-22 09:52:31 +08:00
										 |  |  |   Vector3 b_omega_ib = u - x_g_; | 
					
						
							| 
									
										
										
										
											2013-05-21 07:16:44 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2013-06-21 08:21:18 +08:00
										 |  |  |   // 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
 | 
					
						
							| 
									
										
										
										
											2014-12-22 09:52:31 +08:00
										 |  |  |   Vector3 b_omega_in; b_omega_in.setZero(); | 
					
						
							| 
									
										
										
										
											2013-05-21 07:16:44 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2013-06-21 08:21:18 +08:00
										 |  |  |   // calculate angular velocity on bRn measured in body frame
 | 
					
						
							| 
									
										
										
										
											2014-12-22 09:52:31 +08:00
										 |  |  |   Vector3 b_omega_bn = b_omega_in - b_omega_ib; | 
					
						
							| 
									
										
										
										
											2013-06-21 08:21:18 +08:00
										 |  |  | #else
 | 
					
						
							|  |  |  |   // Assume a non-rotating nav frame (probably an approximation)
 | 
					
						
							|  |  |  |   // calculate angular velocity on bRn measured in body frame
 | 
					
						
							| 
									
										
										
										
											2014-12-22 09:52:31 +08:00
										 |  |  |   Vector3 b_omega_bn = x_g_ - u; | 
					
						
							| 
									
										
										
										
											2013-06-21 08:21:18 +08:00
										 |  |  | #endif
 | 
					
						
							| 
									
										
										
										
											2013-05-21 07:16:44 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   // convert to navigation frame
 | 
					
						
							|  |  |  |   Rot3 nRb = bRn_.inverse(); | 
					
						
							| 
									
										
										
										
											2015-07-22 02:23:42 +08:00
										 |  |  |   Vector3 n_omega_bn = nRb * b_omega_bn; | 
					
						
							| 
									
										
										
										
											2013-05-21 07:16:44 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   // integrate bRn using exponential map, assuming constant over dt
 | 
					
						
							| 
									
										
										
										
											2015-07-06 07:11:04 +08:00
										 |  |  |   Rot3 delta_nRn = Rot3::Rodrigues(n_omega_bn*dt); | 
					
						
							| 
									
										
										
										
											2013-05-21 07:16:44 +08:00
										 |  |  |   Rot3 bRn = bRn_.compose(delta_nRn); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   // implicit updating of biases (variables just do not change)
 | 
					
						
							|  |  |  |   // x_g = x_g;
 | 
					
						
							|  |  |  |   // x_a = x_a;
 | 
					
						
							|  |  |  |   return Mechanization_bRn2(bRn, x_g_, x_a_); | 
					
						
							|  |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | } /* namespace gtsam */ |