2015-10-05 23:30:07 -03:00
|
|
|
#include <AP_HAL/AP_HAL.h>
|
|
|
|
|
|
|
|
|
|
|
|
#include "AP_NavEKF2.h"
|
|
|
|
#include "AP_NavEKF2_core.h"
|
|
|
|
|
|
|
|
extern const AP_HAL::HAL& hal;
|
|
|
|
|
|
|
|
// reset the body axis gyro bias states to zero and re-initialise the corresponding covariances
|
2015-10-14 20:20:55 -03:00
|
|
|
// Assume that the calibration is performed to an accuracy of 0.5 deg/sec which will require averaging under static conditions
|
|
|
|
// WARNING - a non-blocking calibration method must be used
|
2015-10-05 23:30:07 -03:00
|
|
|
void NavEKF2_core::resetGyroBias(void)
|
|
|
|
{
|
|
|
|
stateStruct.gyro_bias.zero();
|
|
|
|
zeroRows(P,9,11);
|
|
|
|
zeroCols(P,9,11);
|
2015-10-14 20:20:55 -03:00
|
|
|
|
2021-05-04 08:12:23 -03:00
|
|
|
P[9][9] = sq(radians(0.5 * dtIMUavg));
|
2015-10-05 23:30:07 -03:00
|
|
|
P[10][10] = P[9][9];
|
|
|
|
P[11][11] = P[9][9];
|
|
|
|
}
|
|
|
|
|
|
|
|
/*
|
|
|
|
vehicle specific initial gyro bias uncertainty in deg/sec
|
|
|
|
*/
|
2021-05-04 08:12:23 -03:00
|
|
|
ftype NavEKF2_core::InitialGyroBiasUncertainty(void) const
|
2015-10-05 23:30:07 -03:00
|
|
|
{
|
2021-05-04 08:12:23 -03:00
|
|
|
return 2.5;
|
2015-10-05 23:30:07 -03:00
|
|
|
}
|
|
|
|
|