SoloGimbalEKF.h 4.0 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127
  1. /*
  2. smaller EKF for simpler estimation applications
  3. Converted from Matlab to C++ by Paul Riseborough
  4. This program is free software: you can redistribute it and/or modify
  5. it under the terms of the GNU General Public License as published by
  6. the Free Software Foundation, either version 3 of the License, or
  7. (at your option) any later version.
  8. This program is distributed in the hope that it will be useful,
  9. but WITHOUT ANY WARRANTY; without even the implied warranty of
  10. MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
  11. GNU General Public License for more details.
  12. You should have received a copy of the GNU General Public License
  13. along with this program. If not, see <http://www.gnu.org/licenses/>.
  14. */
  15. #pragma once
  16. #include <AP_Math/AP_Math.h>
  17. #include <AP_Param/AP_Param.h>
  18. //#include <AP_NavEKF2/AP_NavEKF2.h>
  19. #include <AP_Math/vectorN.h>
  20. class SoloGimbalEKF
  21. {
  22. public:
  23. typedef float ftype;
  24. #if MATH_CHECK_INDEXES
  25. typedef VectorN<ftype,13> Vector13;
  26. #else
  27. typedef ftype Vector13[13];
  28. #endif
  29. // Constructor
  30. SoloGimbalEKF();
  31. // Run the EKF main loop once every time we receive sensor data
  32. void RunEKF(float delta_time, const Vector3f &delta_angles, const Vector3f &delta_velocity, const Vector3f &joint_angles);
  33. void reset();
  34. // get gyro bias data
  35. void getGyroBias(Vector3f &gyroBias) const;
  36. // set gyro bias
  37. void setGyroBias(const Vector3f &gyroBias);
  38. // get quaternion data
  39. void getQuat(Quaternion &quat) const;
  40. // get filter alignment status - true is aligned
  41. bool getStatus(void) const;
  42. static const struct AP_Param::GroupInfo var_info[];
  43. private:
  44. // the states are available in two forms, either as a Vector13 or
  45. // broken down as individual elements. Both are equivalent (same
  46. // memory)
  47. Vector13 states;
  48. struct state_elements {
  49. Vector3f angErr; // 0..2 rotation vector representing the growth in angle error since the last state correction (rad)
  50. Vector3f velocity; // 3..5 NED velocity (m/s)
  51. Vector3f delAngBias; // 6..8 estimated bias errors in the IMU delta angles
  52. Quaternion quat; // 9..12 these states are used by the INS prediction only and are not used by the EKF state equations.
  53. } &state;
  54. // data from sensors
  55. struct {
  56. Vector3f delAng;
  57. Vector3f delVel;
  58. float gPhi;
  59. float gPsi;
  60. float gTheta;
  61. } gSense;
  62. float Cov[9][9]; // covariance matrix
  63. Matrix3f Tsn; // Sensor to NED rotation matrix
  64. float TiltCorrectionSquared; // Angle correction applied to tilt from last velocity fusion (rad)
  65. bool newDataMag; // true when new magnetometer data is waiting to be used
  66. uint32_t StartTime_ms; // time the EKF was started (msec)
  67. bool FiltInit; // true when EKF is initialised
  68. bool YawAligned; // true when EKF heading is initialised
  69. float cosPhi;// = cosf(gSense.gPhi);
  70. float cosTheta;// = cosf(gSense.gTheta);
  71. float sinPhi;// = sinf(gSense.gPhi);
  72. float sinTheta;// = sinf(gSense.gTheta);
  73. float sinPsi;// = sinf(gSense.gPsi);
  74. float cosPsi;// = cosf(gSense.gPsi);
  75. uint32_t lastMagUpdate;
  76. Vector3f magData;
  77. uint32_t imuSampleTime_ms;
  78. float dtIMU;
  79. // States used for unwrapping of compass yaw error
  80. float innovationIncrement;
  81. float lastInnovation;
  82. // state prediction
  83. void predictStates();
  84. // EKF covariance prediction
  85. void predictCovariance();
  86. // EKF velocity fusion
  87. void fuseVelocity();
  88. // read magnetometer data
  89. void readMagData();
  90. // EKF compass fusion
  91. void fuseCompass();
  92. // Perform an initial heading alignment using the magnetic field and assumed declination
  93. void alignHeading();
  94. // Calculate magnetic heading innovation
  95. float calcMagHeadingInnov();
  96. // Force symmmetry and non-negative diagonals on state covarinace matrix
  97. void fixCovariance();
  98. };