AP_NavEKF: use AHRS get_correct_centrifugal()

This commit is contained in:
Andrew Tridgell 2014-02-19 10:28:45 +11:00
parent fad0b2b233
commit 536160a3fb
2 changed files with 3 additions and 13 deletions

View File

@ -203,7 +203,6 @@ const AP_Param::GroupInfo NavEKF::var_info[] PROGMEM = {
NavEKF::NavEKF(const AP_AHRS *ahrs, AP_Baro &baro) :
_ahrs(ahrs),
_baro(baro),
staticModeDemanded(true), // staticMode demanded from outside
useCompass(true), // activates fusion of airspeed data
covTimeStepMax(0.07f), // maximum time (sec) between covariance prediction updates
covDelAngMax(0.05f), // maximum delta angle between covariance prediction updates
@ -278,10 +277,6 @@ bool NavEKF::PositionDrifting(void) const
return !posHealth;
}
void NavEKF::SetStaticMode(bool setting) {
staticModeDemanded = setting;
}
void NavEKF::ResetPosition(void)
{
if (staticMode) {
@ -504,7 +499,7 @@ void NavEKF::UpdateFilter()
OnGroundCheck();
// Define rules used to set staticMode
if (onGround && staticModeDemanded) {
if (onGround && !_ahrs->get_correct_centrifugal()) {
staticMode = true;
} else {
staticMode = false;
@ -2235,8 +2230,8 @@ void NavEKF::getGyroBias(Vector3f &gyroBias) const
void NavEKF::getAccelBias(Vector3f &accelBias) const
{
accelBias.x = float(staticMode);
accelBias.y = float(staticModeDemanded);
accelBias.x = staticMode? 1.0f : 0.0f;
accelBias.y = _ahrs->get_correct_centrifugal()? 0.0f : 1.0f;
accelBias.z = states[13] / dtIMU;
}

View File

@ -82,10 +82,6 @@ public:
// This method can only be used when the vehicle is static
void InitialiseFilterBootstrap(void);
// inhibits position and velocity attitude corrections when set to true
// setting to true has same effect as ahrs.set_correct_centrifugal(false)
void SetStaticMode(bool setting);
// Update Filter States - this should be called whenever new IMU data is available
void UpdateFilter(void);
@ -304,7 +300,6 @@ private:
// Variables
uint8_t skipCounter; // counter used to skip position and height corrections to achieve _skipRatio
bool statesInitialised; // boolean true when filter states have been initialised
bool staticModeDemanded; // boolean true when staticMode has been demanded externally.
bool velHealth; // boolean true if velocity measurements have failed innovation consistency check
bool posHealth; // boolean true if position measurements have failed innovation consistency check
bool hgtHealth; // boolean true if height measurements have failed innovation consistency check