mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 09:58:28 -04:00
AP_AHRS_NavEKF: override set_correct_centrifugal
This commit is contained in:
parent
8f6fd86f69
commit
9f130b40a0
@ -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
|
||||
|
@ -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…
Reference in New Issue
Block a user