AP_NavEKF3_GyroBias.cpp 835 B

12345678910111213141516171819202122232425262728293031
  1. #include <AP_HAL/AP_HAL.h>
  2. #include "AP_NavEKF3.h"
  3. #include "AP_NavEKF3_core.h"
  4. #include <AP_AHRS/AP_AHRS.h>
  5. #include <AP_Vehicle/AP_Vehicle.h>
  6. extern const AP_HAL::HAL& hal;
  7. // reset the body axis gyro bias states to zero and re-initialise the corresponding covariances
  8. // Assume that the calibration is performed to an accuracy of 0.5 deg/sec which will require averaging under static conditions
  9. // WARNING - a non-blocking calibration method must be used
  10. void NavEKF3_core::resetGyroBias(void)
  11. {
  12. stateStruct.gyro_bias.zero();
  13. zeroRows(P,10,12);
  14. zeroCols(P,10,12);
  15. P[10][10] = sq(radians(0.5f * dtIMUavg));
  16. P[11][11] = P[10][10];
  17. P[12][12] = P[10][10];
  18. }
  19. /*
  20. vehicle specific initial gyro bias uncertainty in deg/sec
  21. */
  22. float NavEKF3_core::InitialGyroBiasUncertainty(void) const
  23. {
  24. return 2.5f;
  25. }