diff --git a/ArduCopter/crash_check.cpp b/ArduCopter/crash_check.cpp index 07e3ba69a3..560aefcd36 100644 --- a/ArduCopter/crash_check.cpp +++ b/ArduCopter/crash_check.cpp @@ -269,7 +269,6 @@ void Copter::parachute_check() } if (parachute.release_initiated()) { - copter.arming.disarm(AP_Arming::Method::PARACHUTE_RELEASE); return; } @@ -331,9 +330,6 @@ void Copter::parachute_check() // parachute_release - trigger the release of the parachute, disarm the motors and notify the user void Copter::parachute_release() { - // disarm motors - arming.disarm(AP_Arming::Method::PARACHUTE_RELEASE); - // release parachute parachute.release();