mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-27 10:13:57 -04:00
AP_AHRS : Publish EKF learned compass offsets
This commit is contained in:
parent
10f050c53b
commit
d44cf14178
@ -344,5 +344,13 @@ void AP_AHRS_NavEKF::getEkfControlLimits(float &ekfGndSpdLimit, float &ekfNavVel
|
|||||||
EKF.getEkfControlLimits(ekfGndSpdLimit,ekfNavVelGainScaler);
|
EKF.getEkfControlLimits(ekfGndSpdLimit,ekfNavVelGainScaler);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// get compass offset estimates
|
||||||
|
// true if offsets are valid
|
||||||
|
bool AP_AHRS_NavEKF::getMagOffsets(Vector3f &magOffsets)
|
||||||
|
{
|
||||||
|
bool status = EKF.getMagOffsets(magOffsets);
|
||||||
|
return status;
|
||||||
|
}
|
||||||
|
|
||||||
#endif // AP_AHRS_NAVEKF_AVAILABLE
|
#endif // AP_AHRS_NAVEKF_AVAILABLE
|
||||||
|
|
||||||
|
@ -120,6 +120,10 @@ public:
|
|||||||
// true if the AHRS has completed initialisation
|
// true if the AHRS has completed initialisation
|
||||||
bool initialised(void) const;
|
bool initialised(void) const;
|
||||||
|
|
||||||
|
// get compass offset estimates
|
||||||
|
// true if offsets are valid
|
||||||
|
bool getMagOffsets(Vector3f &magOffsets);
|
||||||
|
|
||||||
private:
|
private:
|
||||||
bool using_EKF(void) const;
|
bool using_EKF(void) const;
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user