diff --git a/ArduCopter/system.pde b/ArduCopter/system.pde index dde3e35de2..46fe29c6a8 100644 --- a/ArduCopter/system.pde +++ b/ArduCopter/system.pde @@ -216,8 +216,10 @@ static void init_ardupilot() if(g.compass_enabled) init_compass(); +#if OPTFLOW == ENABLED // make optflow available to AHRS ahrs.set_optflow(&optflow); +#endif // initialise attitude and position controllers attitude_control.set_dt(MAIN_LOOP_SECONDS);