Browse Source

AP_NavEKF: use ahrs->get_armed() for static mode demanded

master
Andrew Tridgell 11 years ago
parent
commit
c9d0c1face
  1. 12
      libraries/AP_NavEKF/AP_NavEKF.cpp
  2. 3
      libraries/AP_NavEKF/AP_NavEKF.h

12
libraries/AP_NavEKF/AP_NavEKF.cpp

@ -499,7 +499,7 @@ void NavEKF::UpdateFilter() @@ -499,7 +499,7 @@ void NavEKF::UpdateFilter()
OnGroundCheck();
// Define rules used to set staticMode
if (onGround && !_ahrs->get_correct_centrifugal()) {
if (onGround && static_mode_demanded()) {
staticMode = true;
} else {
staticMode = false;
@ -2231,7 +2231,7 @@ void NavEKF::getGyroBias(Vector3f &gyroBias) const @@ -2231,7 +2231,7 @@ void NavEKF::getGyroBias(Vector3f &gyroBias) const
void NavEKF::getAccelBias(Vector3f &accelBias) const
{
accelBias.x = staticMode? 1.0f : 0.0f;
accelBias.y = _ahrs->get_correct_centrifugal()? 0.0f : 1.0f;
accelBias.y = static_mode_demanded()? 1.0f : 0.0f;
accelBias.z = states[13] / dtIMU;
}
@ -2659,4 +2659,12 @@ bool NavEKF::useAirspeed(void) const @@ -2659,4 +2659,12 @@ bool NavEKF::useAirspeed(void) const
return _ahrs->get_airspeed()->use();
}
/*
see if the vehicle code has demanded static mode
*/
bool NavEKF::static_mode_demanded(void) const
{
return !_ahrs->get_armed() || !_ahrs->get_correct_centrifugal();
}
#endif // HAL_CPU_CLASS

3
libraries/AP_NavEKF/AP_NavEKF.h

@ -255,6 +255,9 @@ private: @@ -255,6 +255,9 @@ private:
// return true if we should use the airspeed sensor
bool useAirspeed(void) const;
// check if static mode has been demanded by vehicle code
bool static_mode_demanded(void) const;
private:
// EKF Mavlink Tuneable Parameters
AP_Float _gpsHorizVelNoise; // GPS horizontal velocity measurement noise : m/s

Loading…
Cancel
Save