Browse Source

AP_AHRS_NavEKF: override set_correct_centrifugal

mission-4.1.18
Randy Mackay 11 years ago committed by Andrew Tridgell
parent
commit
9f130b40a0
  1. 5
      libraries/AP_AHRS/AP_AHRS_NavEKF.cpp
  2. 2
      libraries/AP_AHRS/AP_AHRS_NavEKF.h

5
libraries/AP_AHRS/AP_AHRS_NavEKF.cpp

@ -91,9 +91,8 @@ void AP_AHRS_NavEKF::reset(bool recover_eulers) @@ -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

2
libraries/AP_AHRS/AP_AHRS_NavEKF.h

@ -51,6 +51,8 @@ public: @@ -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);

Loading…
Cancel
Save