APM:Libraries
AP_NavEKF_GyroBias.cpp
Go to the documentation of this file.
1 #include <AP_HAL/AP_HAL.h>
2 
3 #if HAL_CPU_CLASS >= HAL_CPU_CLASS_150
4 
5 #include "AP_NavEKF2.h"
6 #include "AP_NavEKF2_core.h"
7 #include <AP_AHRS/AP_AHRS.h>
9 
10 #include <stdio.h>
11 
12 extern const AP_HAL::HAL& hal;
13 
14 // reset the body axis gyro bias states to zero and re-initialise the corresponding covariances
15 // Assume that the calibration is performed to an accuracy of 0.5 deg/sec which will require averaging under static conditions
16 // WARNING - a non-blocking calibration method must be used
18 {
20  zeroRows(P,9,11);
21  zeroCols(P,9,11);
22 
23  P[9][9] = sq(radians(0.5f * dtIMUavg));
24  P[10][10] = P[9][9];
25  P[11][11] = P[9][9];
26 }
27 
28 /*
29  vehicle specific initial gyro bias uncertainty in deg/sec
30  */
32 {
33  return 2.5f;
34 }
35 
36 
37 #endif // HAL_CPU_CLASS
void zeroCols(Matrix24 &covMat, uint8_t first, uint8_t last)
void zeroRows(Matrix24 &covMat, uint8_t first, uint8_t last)
struct NavEKF2_core::state_elements & stateStruct
#define f(i)
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
Definition: AC_PID_test.cpp:14
static constexpr float radians(float deg)
Definition: AP_Math.h:158
float sq(const T val)
Definition: AP_Math.h:170
void resetGyroBias(void)
float InitialGyroBiasUncertainty(void) const
void zero()
Definition: vector3.h:182