From 55dca5cda98129dacd92d0922b205adfef3c7771 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Fri, 22 Feb 2019 07:05:35 +1100 Subject: [PATCH] Copter: added in sink rate for parachute check --- ArduCopter/crash_check.cpp | 3 +++ 1 file changed, 3 insertions(+) diff --git a/ArduCopter/crash_check.cpp b/ArduCopter/crash_check.cpp index c9dcdd1f4d..22578320f2 100644 --- a/ArduCopter/crash_check.cpp +++ b/ArduCopter/crash_check.cpp @@ -201,6 +201,9 @@ void Copter::parachute_check() // release parachute parachute_release(); } + + // pass sink rate to parachute library + parachute.set_sink_rate(-inertial_nav.get_velocity_z() * 0.01); } // parachute_release - trigger the release of the parachute, disarm the motors and notify the user