Skip to content

Commit d6ce676

Browse files
committed
AP_HAL_ChibiOS: reset DMA after exiting soft serial
only configure DMA on groups that are actually being used for soft serial
1 parent 528daee commit d6ce676

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
@@ -1790,6 +1790,7 @@ void RCOutput::send_pulses_DMAR(pwm_group &group, uint32_t buffer_length)
17901790
#ifdef HAL_GPIO_LINE_GPIO54
17911791
TOGGLE_PIN_DEBUG(54);
17921792
#endif
1793+
17931794
#if STM32_DMA_SUPPORTS_DMAMUX
17941795
dmaSetRequestSource(group.dma, group.dma_up_channel);
17951796
#endif
@@ -1916,6 +1917,11 @@ void RCOutput::dma_cancel(pwm_group& group)
19161917
19171918
While serial output is active normal output to the channel group is
19181919
suspended.
1920+
1921+
chanmask could refer to more than one group so it is assumed that
1922+
this function is always called before outputting to the group
1923+
implied by chan, but that DMA channels are setup only once
1924+
until serial_end() has been called
19191925
*/
19201926
#if HAL_SERIAL_ESC_COMM_ENABLED
19211927
bool RCOutput::serial_setup_output(uint8_t chan, uint32_t baudrate, uint32_t chanmask)
@@ -1925,7 +1931,7 @@ bool RCOutput::serial_setup_output(uint8_t chan, uint32_t baudrate, uint32_t cha
19251931
chanmask >>= chan_offset;
19261932
pwm_group *new_serial_group = nullptr;
19271933

1928-
// find the channel group
1934+
// find the channel group for the next output
19291935
for (auto &group : pwm_group_list) {
19301936
if (group.current_mode == MODE_PWM_BRUSHED) {
19311937
// can't do serial output with brushed motors
@@ -1942,6 +1948,7 @@ bool RCOutput::serial_setup_output(uint8_t chan, uint32_t baudrate, uint32_t cha
19421948
}
19431949
}
19441950

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

1956-
// setup the groups for serial output. We ask for a bit width of 1, which gets modified by the
1963+
// setup the unconfigured groups for serial output. We ask for a bit width of 1, which gets modified by the
19571964
// we setup all groups so they all are setup with the right polarity, and to make switching between
19581965
// channels in blheli pass-thru fast
19591966
for (auto &group : pwm_group_list) {
1960-
if (group.ch_mask & chanmask) {
1967+
if ((group.ch_mask & chanmask) && !(group.ch_mask & serial_chanmask)) {
19611968
if (!setup_group_DMA(group, baudrate, 10, false, DSHOT_BUFFER_LENGTH, 10, false)) {
19621969
serial_end();
19631970
return false;
19641971
}
19651972
}
19661973
}
1967-
19681974
// run the thread doing serial IO at highest priority. This is needed to ensure we don't
19691975
// lose bytes when we switch between output and input
19701976
serial_thread = chThdGetSelfX();
19711977
serial_priority = chThdGetSelfX()->realprio;
1978+
// mask of channels currently configured
1979+
serial_chanmask |= chanmask;
19721980
chThdSetPriority(HIGHPRIO);
19731981

19741982
// remember the bit period for serial_read_byte()
@@ -2004,7 +2012,6 @@ void RCOutput::fill_DMA_buffer_byte(dmar_uint_t *buffer, uint8_t stride, uint8_t
20042012
}
20052013
}
20062014

2007-
20082015
/*
20092016
send one serial byte, blocking call, should be called with the DMA lock held
20102017
*/
@@ -2231,11 +2238,15 @@ void RCOutput::serial_end(void)
22312238
irq.waiter = nullptr;
22322239
for (uint8_t i = 0; i < NUM_GROUPS; i++ ) {
22332240
pwm_group &group = pwm_group_list[i];
2234-
set_group_mode(group);
2235-
set_freq_group(group);
2241+
// re-configure groups that were previous configured
2242+
if (group.ch_mask & serial_chanmask) {
2243+
dma_cancel(group); // this ensures the DMA is in a sane state
2244+
set_group_mode(group);
2245+
}
22362246
}
22372247
}
22382248
serial_group = nullptr;
2249+
serial_chanmask = 0;
22392250
}
22402251
#endif // HAL_SERIAL_ESC_COMM_ENABLED
22412252

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)