diff --git a/ArduCopter/ArduCopter.pde b/ArduCopter/ArduCopter.pde index ef8f4d85b09ea91eb439927258098936331c3376..02b4f96a3b8f9a680695073674ea2c6d9f13119c 100644 --- a/ArduCopter/ArduCopter.pde +++ b/ArduCopter/ArduCopter.pde @@ -314,8 +314,8 @@ AP_Mission mission(ahrs, &start_command, &verify_command, &exit_mission); //////////////////////////////////////////////////////////////////////////////// // Optical flow sensor //////////////////////////////////////////////////////////////////////////////// -#if OPTFLOW == ENABLED && CONFIG_HAL_BOARD == HAL_BOARD_PX4 -static AP_OpticalFlow_PX4 optflow(ahrs); +#if OPTFLOW == ENABLED +static OpticalFlow optflow; #endif // gnd speed limit required to observe optical flow sensor limits diff --git a/ArduCopter/config.h b/ArduCopter/config.h index bac32fc720a23128f03ff79104590d820326d9ba..dfc51baf4960e801b884a1150c4dee8bd0f64d34 100644 --- a/ArduCopter/config.h +++ b/ArduCopter/config.h @@ -388,7 +388,7 @@ ////////////////////////////////////////////////////////////////////////////// // OPTICAL_FLOW #ifndef OPTFLOW - #if CONFIG_HAL_BOARD == HAL_BOARD_PX4 + #if HAL_CPU_CLASS >= HAL_CPU_CLASS_75 # define OPTFLOW ENABLED #else # define OPTFLOW DISABLED