diff --git a/ArduCopter/AP_Arming.cpp b/ArduCopter/AP_Arming.cpp index e6677921d0..e14909ee15 100644 --- a/ArduCopter/AP_Arming.cpp +++ b/ArduCopter/AP_Arming.cpp @@ -172,14 +172,6 @@ bool AP_Arming_Copter::parameter_checks(bool display_failure) } #endif - #if RANGEFINDER_ENABLED == ENABLED && OPTFLOW == ENABLED - // check range finder if optflow enabled - if (copter.optflow.enabled() && !copter.rangefinder.pre_arm_check()) { - check_failed(ARMING_CHECK_PARAMETERS, display_failure, "check range finder"); - return false; - } - #endif - #if FRAME_CONFIG == HELI_FRAME // check helicopter parameters if (!copter.motors->parameter_check(display_failure)) {