From e2d41a3e04ad7df10a79312c1324d1fa9d1f89dd Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Wed, 16 Sep 2020 15:22:17 +0900 Subject: [PATCH] Copter: integrate parachute check_sink_rate also move set_is_flying into check parachute to increase it's update rate --- ArduCopter/Copter.cpp | 4 ---- ArduCopter/crash_check.cpp | 12 +++++++++--- 2 files changed, 9 insertions(+), 7 deletions(-) diff --git a/ArduCopter/Copter.cpp b/ArduCopter/Copter.cpp index a3748b80f8..f64042b9b8 100644 --- a/ArduCopter/Copter.cpp +++ b/ArduCopter/Copter.cpp @@ -517,10 +517,6 @@ void Copter::one_hz_loop() adsb.set_is_flying(!ap.land_complete); #endif -#if PARACHUTE == ENABLED - parachute.set_is_flying(!ap.land_complete); -#endif - AP_Notify::flags.flying = !ap.land_complete; } diff --git a/ArduCopter/crash_check.cpp b/ArduCopter/crash_check.cpp index 96b64c929e..dbef41a7eb 100644 --- a/ArduCopter/crash_check.cpp +++ b/ArduCopter/crash_check.cpp @@ -178,6 +178,12 @@ void Copter::parachute_check() return; } + // pass is_flying to parachute library + parachute.set_is_flying(!ap.land_complete); + + // pass sink rate to parachute library + parachute.set_sink_rate(-inertial_nav.get_velocity_z() * 0.01f); + // exit immediately if in standby if (standby_active) { return; @@ -214,9 +220,9 @@ void Copter::parachute_check() return; } - // pass sink rate to parachute library - parachute.set_sink_rate(-inertial_nav.get_velocity_z() * 0.01); - + // trigger parachute release based on sink rate + parachute.check_sink_rate(); + // check for angle error over 30 degrees const float angle_error = attitude_control->get_att_error_angle_deg(); if (angle_error <= CRASH_CHECK_ANGLE_DEVIATION_DEG) {