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