AP_NavEKF_GyroBias.cpp 848 B

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