mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-23 00:04:02 -04:00
Copter: remove rotor spinning arming check from TradHeli
This commit is contained in:
parent
724f5511aa
commit
b49fda4a94
@ -747,16 +747,6 @@ bool Copter::arm_checks(bool display_failure, bool arming_from_gcs)
|
|||||||
return false;
|
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
|
// succeed if arming checks are disabled
|
||||||
if (g.arming_check == ARMING_CHECK_NONE) {
|
if (g.arming_check == ARMING_CHECK_NONE) {
|
||||||
return true;
|
return true;
|
||||||
|
Loading…
Reference in New Issue
Block a user