AP_NavEKF : useAirspeed set automatically

This commit is contained in:
Paul Riseborough 2014-02-18 07:46:42 +11:00 committed by Andrew Tridgell
parent 6fbada26d3
commit 8daca145d0
2 changed files with 2 additions and 2 deletions

View File

@ -204,7 +204,6 @@ NavEKF::NavEKF(const AP_AHRS *ahrs, AP_Baro &baro) :
_ahrs(ahrs),
_baro(baro),
staticModeDemanded(true), // staticMode demanded from outside
useAirspeed(true), // activates fusion of compass data
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
@ -242,6 +241,7 @@ NavEKF::NavEKF(const AP_AHRS *ahrs, AP_Baro &baro) :
hgtRate = 0.0f;
mag_state.q0 = 1;
mag_state.DCM.identity();
useAirspeed = _ahrs->get_airspeed();
}
bool NavEKF::healthy(void) const

View File

@ -327,7 +327,7 @@ private:
ftype dt; // time lapsed since the last covariance prediction (sec)
ftype hgtRate; // state for rate of change of height filter
bool onGround; // boolean true when the flight vehicle is on the ground (not flying)
const bool useAirspeed; // boolean true if airspeed data is being used
bool useAirspeed; // boolean true if airspeed data is being used
const bool useCompass; // boolean true if magnetometer data is being used
Vector6 innovVelPos; // innovation output for a group of measurements
Vector6 varInnovVelPos; // innovation variance output for a group of measurements