From 048a3af785e7589fb4e2ffef52326e54d90b2e3d Mon Sep 17 00:00:00 2001 From: Andy Piper Date: Fri, 7 Jun 2024 16:36:08 +0100 Subject: [PATCH] AP_HAL_ChibiOS: allow forcing of trigger_groups() --- libraries/AP_HAL_ChibiOS/RCOutput.cpp | 3 ++- libraries/AP_HAL_ChibiOS/RCOutput.h | 7 +++++++ 2 files changed, 9 insertions(+), 1 deletion(-) diff --git a/libraries/AP_HAL_ChibiOS/RCOutput.cpp b/libraries/AP_HAL_ChibiOS/RCOutput.cpp index 3d3245444f..1e0fbae0a3 100644 --- a/libraries/AP_HAL_ChibiOS/RCOutput.cpp +++ b/libraries/AP_HAL_ChibiOS/RCOutput.cpp @@ -1398,7 +1398,8 @@ void RCOutput::trigger_groups() osalSysUnlock(); #if !defined(HAL_NO_RCOUT_THREAD) || HAL_DSHOT_ENABLED // trigger a PWM send - if (!in_soft_serial() && hal.scheduler->in_main_thread() && rcout_thread_ctx) { + if (!in_soft_serial() && + (hal.scheduler->in_main_thread() || force_trigger) && rcout_thread_ctx) { chEvtSignal(rcout_thread_ctx, EVT_PWM_SEND); } #endif diff --git a/libraries/AP_HAL_ChibiOS/RCOutput.h b/libraries/AP_HAL_ChibiOS/RCOutput.h index 87aa9948db..a935de7f45 100644 --- a/libraries/AP_HAL_ChibiOS/RCOutput.h +++ b/libraries/AP_HAL_ChibiOS/RCOutput.h @@ -285,6 +285,11 @@ public: */ void rcout_thread(); + /* + Force group trigger from all callers rather than just from the main thread + */ + void force_trigger_groups(bool onoff) override { force_trigger = onoff; } + /* timer information */ @@ -579,6 +584,8 @@ private: uint8_t _dshot_cycle; // virtual timer for post-push() pulses virtual_timer_t _dshot_rate_timer; + // force triggering of groups + bool force_trigger; #if HAL_DSHOT_ENABLED // dshot commands