Skip to content

Commit

Permalink
AP_HAL_ChibiOS: reset DMA after exiting soft serial
Browse files Browse the repository at this point in the history
only configure DMA on groups that are actually being used for soft serial
  • Loading branch information
andyp1per authored and tridge committed Feb 13, 2025
1 parent af95ed5 commit 78d13fb
Show file tree
Hide file tree
Showing 2 changed files with 20 additions and 7 deletions.
25 changes: 18 additions & 7 deletions libraries/AP_HAL_ChibiOS/RCOutput.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1788,6 +1788,7 @@ void RCOutput::send_pulses_DMAR(pwm_group &group, uint32_t buffer_length)
#ifdef HAL_GPIO_LINE_GPIO54
TOGGLE_PIN_DEBUG(54);
#endif

#if STM32_DMA_SUPPORTS_DMAMUX
dmaSetRequestSource(group.dma, group.dma_up_channel);
#endif
Expand Down Expand Up @@ -1914,6 +1915,11 @@ void RCOutput::dma_cancel(pwm_group& group)
While serial output is active normal output to the channel group is
suspended.
chanmask could refer to more than one group so it is assumed that
this function is always called before outputting to the group
implied by chan, but that DMA channels are setup only once
until serial_end() has been called
*/
#if HAL_SERIAL_ESC_COMM_ENABLED
bool RCOutput::serial_setup_output(uint8_t chan, uint32_t baudrate, uint32_t chanmask)
Expand All @@ -1923,7 +1929,7 @@ bool RCOutput::serial_setup_output(uint8_t chan, uint32_t baudrate, uint32_t cha
chanmask >>= chan_offset;
pwm_group *new_serial_group = nullptr;

// find the channel group
// find the channel group for the next output
for (auto &group : pwm_group_list) {
if (group.current_mode == MODE_PWM_BRUSHED) {
// can't do serial output with brushed motors
Expand All @@ -1940,6 +1946,7 @@ bool RCOutput::serial_setup_output(uint8_t chan, uint32_t baudrate, uint32_t cha
}
}

// couldn't find a group, shutdown everything
if (!new_serial_group) {
if (in_soft_serial()) {
// shutdown old group
Expand All @@ -1951,22 +1958,23 @@ bool RCOutput::serial_setup_output(uint8_t chan, uint32_t baudrate, uint32_t cha
// stop further dshot output before we reconfigure the DMA
serial_group = new_serial_group;

// setup the groups for serial output. We ask for a bit width of 1, which gets modified by the
// setup the unconfigured groups for serial output. We ask for a bit width of 1, which gets modified by the
// we setup all groups so they all are setup with the right polarity, and to make switching between
// channels in blheli pass-thru fast
for (auto &group : pwm_group_list) {
if (group.ch_mask & chanmask) {
if ((group.ch_mask & chanmask) && !(group.ch_mask & serial_chanmask)) {
if (!setup_group_DMA(group, baudrate, 10, false, DSHOT_BUFFER_LENGTH, 10, false)) {
serial_end();
return false;
}
}
}

// run the thread doing serial IO at highest priority. This is needed to ensure we don't
// lose bytes when we switch between output and input
serial_thread = chThdGetSelfX();
serial_priority = chThdGetSelfX()->realprio;
// mask of channels currently configured
serial_chanmask |= chanmask;
chThdSetPriority(HIGHPRIO);

// remember the bit period for serial_read_byte()
Expand Down Expand Up @@ -2002,7 +2010,6 @@ void RCOutput::fill_DMA_buffer_byte(dmar_uint_t *buffer, uint8_t stride, uint8_t
}
}


/*
send one serial byte, blocking call, should be called with the DMA lock held
*/
Expand Down Expand Up @@ -2229,11 +2236,15 @@ void RCOutput::serial_end(void)
irq.waiter = nullptr;
for (uint8_t i = 0; i < NUM_GROUPS; i++ ) {
pwm_group &group = pwm_group_list[i];
set_group_mode(group);
set_freq_group(group);
// re-configure groups that were previous configured
if (group.ch_mask & serial_chanmask) {
dma_cancel(group); // this ensures the DMA is in a sane state
set_group_mode(group);
}
}
}
serial_group = nullptr;
serial_chanmask = 0;
}
#endif // HAL_SERIAL_ESC_COMM_ENABLED

Expand Down
2 changes: 2 additions & 0 deletions libraries/AP_HAL_ChibiOS/RCOutput.h
Original file line number Diff line number Diff line change
Expand Up @@ -512,6 +512,8 @@ class ChibiOS::RCOutput : public AP_HAL::RCOutput
struct pwm_group *serial_group;
thread_t *serial_thread;
tprio_t serial_priority;
// mask of channels configured for serial output
uint32_t serial_chanmask;
#endif // HAL_SERIAL_ESC_COMM_ENABLED

static bool soft_serial_waiting() {
Expand Down

0 comments on commit 78d13fb

Please sign in to comment.