AP_AHRS_NavEKF: override set_correct_centrifugal

This commit is contained in:
Randy Mackay 2014-01-06 12:19:43 +09:00 committed by Andrew Tridgell
parent 8f6fd86f69
commit 9f130b40a0
2 changed files with 4 additions and 3 deletions

View File

@ -91,9 +91,8 @@ void AP_AHRS_NavEKF::reset(bool recover_eulers)
void AP_AHRS_NavEKF::set_correct_centrifugal(bool setting)
{
if (ekf_started) {
EKF.SetStaticMode(setting);
}
AP_AHRS_DCM::set_correct_centrifugal(setting);
EKF.SetStaticMode(!setting);
}
// reset the current attitude, used on new IMU calibration

View File

@ -51,6 +51,8 @@ public:
void update(void);
void reset(bool recover_eulers = false);
void set_correct_centrifugal(bool setting);
// reset the current attitude, used on new IMU calibration
void reset_attitude(const float &roll, const float &pitch, const float &yaw);