mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 09:58:28 -04:00
AP_AHRS: added get_correct_centrifugal()
used by NavEKF to force static mode
This commit is contained in:
parent
599c3a8abf
commit
fad0b2b233
@ -234,10 +234,15 @@ public:
|
||||
|
||||
// set the correct centrifugal flag
|
||||
// allows arducopter to disable corrections when disarmed
|
||||
virtual void set_correct_centrifugal(bool setting) {
|
||||
void set_correct_centrifugal(bool setting) {
|
||||
_flags.correct_centrifugal = setting;
|
||||
}
|
||||
|
||||
// get the correct centrifugal flag
|
||||
bool get_correct_centrifugal(void) const {
|
||||
return _flags.correct_centrifugal;
|
||||
}
|
||||
|
||||
// get trim
|
||||
const Vector3f &get_trim() const { return _trim.get(); }
|
||||
|
||||
|
@ -90,12 +90,6 @@ void AP_AHRS_NavEKF::reset(bool recover_eulers)
|
||||
}
|
||||
}
|
||||
|
||||
void AP_AHRS_NavEKF::set_correct_centrifugal(bool setting)
|
||||
{
|
||||
AP_AHRS_DCM::set_correct_centrifugal(setting);
|
||||
EKF.SetStaticMode(!setting);
|
||||
}
|
||||
|
||||
// reset the current attitude, used on new IMU calibration
|
||||
void AP_AHRS_NavEKF::reset_attitude(const float &_roll, const float &_pitch, const float &_yaw)
|
||||
{
|
||||
|
@ -52,8 +52,6 @@ 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