Mechanization_bRn2.h 2.4 KB

12345678910111213141516171819202122232425262728293031323334353637383940414243444546474849505152535455565758596061626364656667686970717273747576777879808182838485868788899091
  1. /**
  2. * @file Mechanization_bRn.h
  3. * @date Jan 25, 2012
  4. * @author Chris Beall
  5. * @author Frank Dellaert
  6. */
  7. #pragma once
  8. #include <gtsam/geometry/Rot3.h>
  9. #include <gtsam/base/Vector.h>
  10. #include <gtsam_unstable/dllexport.h>
  11. #include <list>
  12. namespace gtsam {
  13. class GTSAM_UNSTABLE_EXPORT Mechanization_bRn2 {
  14. private:
  15. Rot3 bRn_; ///< rotation from nav to body
  16. Vector3 x_g_; ///< gyroscope bias
  17. Vector3 x_a_; ///< accelerometer bias
  18. public:
  19. /**
  20. * Constructor
  21. * @param initial_bRn initial rotation from nav to body frame
  22. * @param initial_x_g initial gyro bias
  23. * @param r3 Z-axis of rotated frame
  24. */
  25. Mechanization_bRn2(const Rot3& initial_bRn = Rot3(),
  26. const Vector3& initial_x_g = Z_3x1, const Vector3& initial_x_a = Z_3x1) :
  27. bRn_(initial_bRn), x_g_(initial_x_g), x_a_(initial_x_a) {
  28. }
  29. /// Copy constructor
  30. Mechanization_bRn2(const Mechanization_bRn2& other) :
  31. bRn_(other.bRn_), x_g_(other.x_g_), x_a_(other.x_a_) {
  32. }
  33. /// gravity in the body frame
  34. Vector3 b_g(double g_e) const {
  35. Vector3 n_g(0, 0, g_e);
  36. return bRn_ * n_g;
  37. }
  38. const Rot3& bRn() const {return bRn_; }
  39. const Vector3& x_g() const { return x_g_; }
  40. const Vector3& x_a() const { return x_a_; }
  41. /**
  42. * Initialize the first Mechanization state
  43. * @param U a list of gyro measurement vectors
  44. * @param F a list of accelerometer measurement vectors
  45. * @param g_e gravity magnitude
  46. * @param flat flag saying whether this is a flat trim init
  47. */
  48. static Mechanization_bRn2 initializeVector(const std::list<Vector>& U,
  49. const std::list<Vector>& F, const double g_e = 0, bool flat=false);
  50. /// Matrix version of initialize
  51. static Mechanization_bRn2 initialize(const Matrix& U,
  52. const Matrix& F, const double g_e = 0, bool flat=false);
  53. /**
  54. * Correct AHRS full state given error state dx
  55. * @param obj The current state
  56. * @param dx The error used to correct and return a new state
  57. */
  58. Mechanization_bRn2 correct(const Vector9& dx) const;
  59. /**
  60. * Integrate to get new state
  61. * @param obj The current state
  62. * @param u gyro measurement to integrate
  63. * @param dt time elapsed since previous state in seconds
  64. */
  65. Mechanization_bRn2 integrate(const Vector3& u, const double dt) const;
  66. /// print
  67. void print(const std::string& s = "") const {
  68. bRn_.print(s + ".R");
  69. std::cout << s + ".x_g" << x_g_ << std::endl;
  70. std::cout << s + ".x_a" << x_a_ << std::endl;
  71. }
  72. };
  73. } // namespace gtsam