|
|
|
@ -85,9 +85,11 @@ void Copter::auto_disarm_check()
@@ -85,9 +85,11 @@ void Copter::auto_disarm_check()
|
|
|
|
|
// always allow auto disarm if using interlock switch or motors are Emergency Stopped
|
|
|
|
|
if ((ap.using_interlock && !motors.get_interlock()) || ap.motor_emergency_stop) { |
|
|
|
|
auto_disarming_counter++; |
|
|
|
|
#if FRAME_CONFIG != HELI_FRAME |
|
|
|
|
// use a shorter delay if using throttle interlock switch or Emergency Stop, because it is less
|
|
|
|
|
// obvious the copter is armed as the motors will not be spinning
|
|
|
|
|
disarm_delay /= 2; |
|
|
|
|
#endif |
|
|
|
|
} else { |
|
|
|
|
bool sprung_throttle_stick = (g.throttle_behavior & THR_BEHAVE_FEEDBACK_FROM_MID_STICK) != 0; |
|
|
|
|
bool thr_low; |
|
|
|
@ -184,8 +186,13 @@ bool Copter::init_arm_motors(bool arming_from_gcs)
@@ -184,8 +186,13 @@ bool Copter::init_arm_motors(bool arming_from_gcs)
|
|
|
|
|
did_ground_start = true; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
#if FRAME_CONFIG == HELI_FRAME |
|
|
|
|
// helicopters are always using motor interlock
|
|
|
|
|
set_using_interlock(true); |
|
|
|
|
#else |
|
|
|
|
// check if we are using motor interlock control on an aux switch
|
|
|
|
|
set_using_interlock(check_if_auxsw_mode_used(AUXSW_MOTOR_INTERLOCK)); |
|
|
|
|
#endif |
|
|
|
|
|
|
|
|
|
// if we are using motor interlock switch and it's enabled, fail to arm
|
|
|
|
|
if (ap.using_interlock && motors.get_interlock()){ |
|
|
|
@ -739,13 +746,12 @@ bool Copter::arm_checks(bool display_failure, bool arming_from_gcs)
@@ -739,13 +746,12 @@ bool Copter::arm_checks(bool display_failure, bool arming_from_gcs)
|
|
|
|
|
return false; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
// always check if rotor is spinning on heli
|
|
|
|
|
#if FRAME_CONFIG == HELI_FRAME |
|
|
|
|
// heli specific arming check
|
|
|
|
|
if ((rsc_control_deglitched > 0) || !motors.allow_arming()){ |
|
|
|
|
#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 Control Engaged")); |
|
|
|
|
} |
|
|
|
|
gcs_send_text_P(MAV_SEVERITY_CRITICAL,PSTR("Arm: Rotor is Spinning")); } |
|
|
|
|
return false; |
|
|
|
|
} |
|
|
|
|
#endif // HELI_FRAME
|
|
|
|
|