From 9f130b40a03be080dbf784e6be4f80afb1da0d96 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Mon, 6 Jan 2014 12:19:43 +0900 Subject: [PATCH] AP_AHRS_NavEKF: override set_correct_centrifugal --- libraries/AP_AHRS/AP_AHRS_NavEKF.cpp | 5 ++--- libraries/AP_AHRS/AP_AHRS_NavEKF.h | 2 ++ 2 files changed, 4 insertions(+), 3 deletions(-) diff --git a/libraries/AP_AHRS/AP_AHRS_NavEKF.cpp b/libraries/AP_AHRS/AP_AHRS_NavEKF.cpp index 2ba4e01d36..fdb0c52c18 100644 --- a/libraries/AP_AHRS/AP_AHRS_NavEKF.cpp +++ b/libraries/AP_AHRS/AP_AHRS_NavEKF.cpp @@ -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 diff --git a/libraries/AP_AHRS/AP_AHRS_NavEKF.h b/libraries/AP_AHRS/AP_AHRS_NavEKF.h index cf388bdc3f..55953f5f02 100644 --- a/libraries/AP_AHRS/AP_AHRS_NavEKF.h +++ b/libraries/AP_AHRS/AP_AHRS_NavEKF.h @@ -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);