Copter: remove rotor spinning arming check from TradHeli

This commit is contained in:
Randy Mackay 2015-10-26 16:49:21 +09:00
parent 724f5511aa
commit b49fda4a94

View File

@ -747,16 +747,6 @@ bool Copter::arm_checks(bool display_failure, bool arming_from_gcs)
return false;
}
// heli specific arming check
#if FRAME_CONFIG == HELI_FRAME
// check if rotor is spinning on heli because this could disrupt gyro calibration
if (!motors.allow_arming()){
if (display_failure) {
gcs_send_text_P(MAV_SEVERITY_CRITICAL,PSTR("Arm: Rotor is Spinning")); }
return false;
}
#endif // HELI_FRAME
// succeed if arming checks are disabled
if (g.arming_check == ARMING_CHECK_NONE) {
return true;