Skip to content

Commit 8ea0003

Browse files
andyp1pertridge
authored andcommitted
AP_HAL_ChibiOS: reset DMA after exiting soft serial
only configure DMA on groups that are actually being used for soft serial
1 parent 9f31795 commit 8ea0003

File tree

2 files changed

+20
-7
lines changed

2 files changed

+20
-7
lines changed

libraries/AP_HAL_ChibiOS/RCOutput.cpp

Lines changed: 18 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -1788,6 +1788,7 @@ void RCOutput::send_pulses_DMAR(pwm_group &group, uint32_t buffer_length)
17881788
#ifdef HAL_GPIO_LINE_GPIO54
17891789
TOGGLE_PIN_DEBUG(54);
17901790
#endif
1791+
17911792
#if STM32_DMA_SUPPORTS_DMAMUX
17921793
dmaSetRequestSource(group.dma, group.dma_up_channel);
17931794
#endif
@@ -1914,6 +1915,11 @@ void RCOutput::dma_cancel(pwm_group& group)
19141915
19151916
While serial output is active normal output to the channel group is
19161917
suspended.
1918+
1919+
chanmask could refer to more than one group so it is assumed that
1920+
this function is always called before outputting to the group
1921+
implied by chan, but that DMA channels are setup only once
1922+
until serial_end() has been called
19171923
*/
19181924
#if HAL_SERIAL_ESC_COMM_ENABLED
19191925
bool RCOutput::serial_setup_output(uint8_t chan, uint32_t baudrate, uint32_t chanmask)
@@ -1923,7 +1929,7 @@ bool RCOutput::serial_setup_output(uint8_t chan, uint32_t baudrate, uint32_t cha
19231929
chanmask >>= chan_offset;
19241930
pwm_group *new_serial_group = nullptr;
19251931

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

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

1954-
// setup the groups for serial output. We ask for a bit width of 1, which gets modified by the
1961+
// setup the unconfigured groups for serial output. We ask for a bit width of 1, which gets modified by the
19551962
// we setup all groups so they all are setup with the right polarity, and to make switching between
19561963
// channels in blheli pass-thru fast
19571964
for (auto &group : pwm_group_list) {
1958-
if (group.ch_mask & chanmask) {
1965+
if ((group.ch_mask & chanmask) && !(group.ch_mask & serial_chanmask)) {
19591966
if (!setup_group_DMA(group, baudrate, 10, false, DSHOT_BUFFER_LENGTH, 10, false)) {
19601967
serial_end();
19611968
return false;
19621969
}
19631970
}
19641971
}
1965-
19661972
// run the thread doing serial IO at highest priority. This is needed to ensure we don't
19671973
// lose bytes when we switch between output and input
19681974
serial_thread = chThdGetSelfX();
19691975
serial_priority = chThdGetSelfX()->realprio;
1976+
// mask of channels currently configured
1977+
serial_chanmask |= chanmask;
19701978
chThdSetPriority(HIGHPRIO);
19711979

19721980
// remember the bit period for serial_read_byte()
@@ -2002,7 +2010,6 @@ void RCOutput::fill_DMA_buffer_byte(dmar_uint_t *buffer, uint8_t stride, uint8_t
20022010
}
20032011
}
20042012

2005-
20062013
/*
20072014
send one serial byte, blocking call, should be called with the DMA lock held
20082015
*/
@@ -2229,11 +2236,15 @@ void RCOutput::serial_end(void)
22292236
irq.waiter = nullptr;
22302237
for (uint8_t i = 0; i < NUM_GROUPS; i++ ) {
22312238
pwm_group &group = pwm_group_list[i];
2232-
set_group_mode(group);
2233-
set_freq_group(group);
2239+
// re-configure groups that were previous configured
2240+
if (group.ch_mask & serial_chanmask) {
2241+
dma_cancel(group); // this ensures the DMA is in a sane state
2242+
set_group_mode(group);
2243+
}
22342244
}
22352245
}
22362246
serial_group = nullptr;
2247+
serial_chanmask = 0;
22372248
}
22382249
#endif // HAL_SERIAL_ESC_COMM_ENABLED
22392250

libraries/AP_HAL_ChibiOS/RCOutput.h

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -512,6 +512,8 @@ class ChibiOS::RCOutput : public AP_HAL::RCOutput
512512
struct pwm_group *serial_group;
513513
thread_t *serial_thread;
514514
tprio_t serial_priority;
515+
// mask of channels configured for serial output
516+
uint32_t serial_chanmask;
515517
#endif // HAL_SERIAL_ESC_COMM_ENABLED
516518

517519
static bool soft_serial_waiting() {

0 commit comments

Comments
 (0)