diff --git a/ArduCopter/motors.cpp b/ArduCopter/motors.cpp index a3ebab5497..264ae69a4e 100644 --- a/ArduCopter/motors.cpp +++ b/ArduCopter/motors.cpp @@ -536,6 +536,15 @@ bool Copter::pre_arm_checks(bool display_failure) return false; } #endif +#if FRAME_CONFIG == HELI_FRAME + // check helicopter parameters + if (!motors.parameter_check()) { + if (display_failure) { + gcs_send_text_P(SEVERITY_HIGH,PSTR("PreArm: Check Heli Parameters")); + } + return false; + } +#endif // HELI_FRAME } // check throttle is above failsafe throttle