Skip to content
Snippets Groups Projects
Commit fba02479 authored by Andrew Tridgell's avatar Andrew Tridgell
Browse files

Copter: fixed build with no EKF

parent 0599f1dc
No related branches found
No related tags found
No related merge requests found
...@@ -120,8 +120,10 @@ static bool set_mode(uint8_t mode) ...@@ -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
......
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment