mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
AP_HAL_ChibiOS: fix sending of dshot commands to all channels
This commit is contained in:
parent
e6e0543b8a
commit
837c81af5e
@ -385,7 +385,6 @@ private:
|
||||
struct {
|
||||
uint16_t erpm[4];
|
||||
volatile bool enabled;
|
||||
#ifdef HAL_WITH_BIDIR_DSHOT
|
||||
const stm32_dma_stream_t *ic_dma[4];
|
||||
uint16_t dma_tx_size; // save tx value from last read
|
||||
Shared_DMA *ic_dma_handle[4];
|
||||
@ -398,11 +397,9 @@ private:
|
||||
uint16_t telem_rate[4];
|
||||
uint16_t telem_err_rate[4];
|
||||
uint64_t last_print; // debug
|
||||
#endif
|
||||
#endif
|
||||
} bdshot;
|
||||
#endif
|
||||
#ifdef HAL_WITH_BIDIR_DSHOT
|
||||
|
||||
// do we have an input capture dma channel
|
||||
bool has_ic_dma() const {
|
||||
return bdshot.ic_dma_handle[bdshot.curr_telem_chan] != nullptr;
|
||||
@ -425,7 +422,7 @@ private:
|
||||
bool ic_enabled() const {
|
||||
return bdshot.enabled && has_ic();
|
||||
}
|
||||
#endif
|
||||
#endif // HAL_WITH_BIDIR_DSHOT
|
||||
// are we safe to send another pulse?
|
||||
bool can_send_dshot_pulse() const {
|
||||
return is_dshot_protocol(current_mode) && AP_HAL::micros() - last_dmar_send_us > (dshot_pulse_time_us + 50);
|
||||
@ -492,7 +489,7 @@ private:
|
||||
struct pwm_group *serial_group;
|
||||
thread_t *serial_thread;
|
||||
tprio_t serial_priority;
|
||||
#endif
|
||||
#endif // HAL_SERIAL_ESC_COMM_ENABLED
|
||||
|
||||
static bool soft_serial_waiting() {
|
||||
#if HAL_SERIAL_ESC_COMM_ENABLED
|
||||
@ -579,7 +576,7 @@ private:
|
||||
return (_dshot_current_command.chan == RCOutput::ALL_CHANNELS || (group.ch_mask & (1UL << _dshot_current_command.chan)))
|
||||
&& _dshot_current_command.cycle > 0;
|
||||
}
|
||||
#endif
|
||||
#endif // HAL_DSHOT_ENABLED
|
||||
bool corked;
|
||||
// mask of channels that are running in high speed
|
||||
uint32_t fast_channel_mask;
|
||||
|
@ -108,13 +108,15 @@ void RCOutput::send_dshot_command(uint8_t command, uint8_t chan, uint32_t comman
|
||||
return;
|
||||
}
|
||||
// not an FMU channel
|
||||
if (chan < chan_offset) {
|
||||
if (chan < chan_offset || chan == ALL_CHANNELS) {
|
||||
#if HAL_WITH_IO_MCU
|
||||
if (AP_BoardConfig::io_dshot()) {
|
||||
iomcu.send_dshot_command(command, chan, command_timeout_ms, repeat_count, priority);
|
||||
}
|
||||
#endif
|
||||
return;
|
||||
if (chan != ALL_CHANNELS) {
|
||||
return;
|
||||
}
|
||||
}
|
||||
|
||||
DshotCommandPacket pkt;
|
||||
|
Loading…
Reference in New Issue
Block a user