Copter: fixed build with no EKF

This commit is contained in:
Andrew Tridgell 2014-12-06 18:43:38 +11:00
parent 0599f1dcb1
commit fba02479b7

View File

@ -120,8 +120,10 @@ static bool set_mode(uint8_t mode)
// called at 100hz or more // called at 100hz or more
static void update_flight_mode() static void update_flight_mode()
{ {
#if AP_AHRS_NAVEKF_AVAILABLE
// Update EKF speed limit - used to limit speed when we are using optical flow // Update EKF speed limit - used to limit speed when we are using optical flow
ahrs.getEkfControlLimits(ekfGndSpdLimit, ekfNavVelGainScaler); ahrs.getEkfControlLimits(ekfGndSpdLimit, ekfNavVelGainScaler);
#endif
switch (control_mode) { switch (control_mode) {
case ACRO: case ACRO:
#if FRAME_CONFIG == HELI_FRAME #if FRAME_CONFIG == HELI_FRAME