diff --git a/libraries/AP_HAL_ChibiOS/RCOutput.cpp b/libraries/AP_HAL_ChibiOS/RCOutput.cpp index 33fbe4ac69..5da86d9558 100644 --- a/libraries/AP_HAL_ChibiOS/RCOutput.cpp +++ b/libraries/AP_HAL_ChibiOS/RCOutput.cpp @@ -1399,6 +1399,9 @@ void RCOutput::trigger_groups() #if !defined(HAL_NO_RCOUT_THREAD) || HAL_DSHOT_ENABLED // trigger a PWM send if (!in_soft_serial() && + // we always trigger an output if we are in the main thread + // we also always trigger an output if we are in the rate thread and thus + // force_trigger has been set (hal.scheduler->in_main_thread() || force_trigger) && rcout_thread_ctx) { chEvtSignal(rcout_thread_ctx, EVT_PWM_SEND); } diff --git a/libraries/AP_HAL_ChibiOS/RCOutput.h b/libraries/AP_HAL_ChibiOS/RCOutput.h index a935de7f45..c1ace28939 100644 --- a/libraries/AP_HAL_ChibiOS/RCOutput.h +++ b/libraries/AP_HAL_ChibiOS/RCOutput.h @@ -584,7 +584,7 @@ private: uint8_t _dshot_cycle; // virtual timer for post-push() pulses virtual_timer_t _dshot_rate_timer; - // force triggering of groups + // force triggering of groups, this is used by the rate thread to ensure output occurs bool force_trigger; #if HAL_DSHOT_ENABLED