From 89cd17d153f2ebb5429717d662bef265cda68978 Mon Sep 17 00:00:00 2001 From: Leonard Hall Date: Thu, 20 Jun 2024 10:41:29 +0930 Subject: [PATCH 1/2] Copter: Remove Payload release on thrust loss detection --- ArduCopter/crash_check.cpp | 6 ------ 1 file changed, 6 deletions(-) diff --git a/ArduCopter/crash_check.cpp b/ArduCopter/crash_check.cpp index 5fcd4a41ade1c..ddc0d3e31df63 100644 --- a/ArduCopter/crash_check.cpp +++ b/ArduCopter/crash_check.cpp @@ -169,12 +169,6 @@ void Copter::thrust_loss_check() // enable thrust loss handling motors->set_thrust_boost(true); // the motors library disables this when it is no longer needed to achieve the commanded output - -#if AP_GRIPPER_ENABLED - if (copter.option_is_enabled(FlightOption::RELEASE_GRIPPER_ON_THRUST_LOSS)) { - gripper.release(); - } -#endif } } From 16c7a4c2a887e78d9c91fb586c7a5ae1497947e2 Mon Sep 17 00:00:00 2001 From: Leonard Hall Date: Thu, 20 Jun 2024 11:52:51 +0930 Subject: [PATCH 2/2] Copter: Improve comments on thrust_loss_check() --- ArduCopter/crash_check.cpp | 7 ++++++- 1 file changed, 6 insertions(+), 1 deletion(-) diff --git a/ArduCopter/crash_check.cpp b/ArduCopter/crash_check.cpp index ddc0d3e31df63..39cf462906628 100644 --- a/ArduCopter/crash_check.cpp +++ b/ArduCopter/crash_check.cpp @@ -96,7 +96,12 @@ void Copter::crash_check() } } -// check for loss of thrust and trigger thrust boost in motors library +// thrust_loss_check - returns true when the aircraft detects for 1 second that it is: +// above 90% thrust, +// less than 15 degrees lean angle target, +// less than 30 degrees of attitude error, +// is descending. +// This check provides a warning that the aircraft is near it's maximum thrust limits and is used trigger thrust boost algorithm in the motors library void Copter::thrust_loss_check() { static uint16_t thrust_loss_counter; // number of iterations vehicle may have been crashed