Skip to content

Commit

Permalink
AP_HAL_ChibiOS: allow forcing of trigger_groups()
Browse files Browse the repository at this point in the history
  • Loading branch information
andyp1per committed Jun 7, 2024
1 parent 5b6aa9e commit f9cdf2d
Show file tree
Hide file tree
Showing 2 changed files with 9 additions and 1 deletion.
3 changes: 2 additions & 1 deletion libraries/AP_HAL_ChibiOS/RCOutput.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1389,7 +1389,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
Expand Down
7 changes: 7 additions & 0 deletions libraries/AP_HAL_ChibiOS/RCOutput.h
Original file line number Diff line number Diff line change
Expand Up @@ -285,6 +285,11 @@ class ChibiOS::RCOutput : public AP_HAL::RCOutput
*/
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
*/
Expand Down Expand Up @@ -579,6 +584,8 @@ class ChibiOS::RCOutput : public AP_HAL::RCOutput
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
Expand Down

0 comments on commit f9cdf2d

Please sign in to comment.