@@ -1788,6 +1788,7 @@ void RCOutput::send_pulses_DMAR(pwm_group &group, uint32_t buffer_length)
1788
1788
#ifdef HAL_GPIO_LINE_GPIO54
1789
1789
TOGGLE_PIN_DEBUG (54 );
1790
1790
#endif
1791
+
1791
1792
#if STM32_DMA_SUPPORTS_DMAMUX
1792
1793
dmaSetRequestSource (group.dma , group.dma_up_channel );
1793
1794
#endif
@@ -1914,6 +1915,11 @@ void RCOutput::dma_cancel(pwm_group& group)
1914
1915
1915
1916
While serial output is active normal output to the channel group is
1916
1917
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
1917
1923
*/
1918
1924
#if HAL_SERIAL_ESC_COMM_ENABLED
1919
1925
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
1923
1929
chanmask >>= chan_offset;
1924
1930
pwm_group *new_serial_group = nullptr ;
1925
1931
1926
- // find the channel group
1932
+ // find the channel group for the next output
1927
1933
for (auto &group : pwm_group_list) {
1928
1934
if (group.current_mode == MODE_PWM_BRUSHED) {
1929
1935
// 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
1940
1946
}
1941
1947
}
1942
1948
1949
+ // couldn't find a group, shutdown everything
1943
1950
if (!new_serial_group) {
1944
1951
if (in_soft_serial ()) {
1945
1952
// shutdown old group
@@ -1951,22 +1958,23 @@ bool RCOutput::serial_setup_output(uint8_t chan, uint32_t baudrate, uint32_t cha
1951
1958
// stop further dshot output before we reconfigure the DMA
1952
1959
serial_group = new_serial_group;
1953
1960
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
1955
1962
// we setup all groups so they all are setup with the right polarity, and to make switching between
1956
1963
// channels in blheli pass-thru fast
1957
1964
for (auto &group : pwm_group_list) {
1958
- if (group.ch_mask & chanmask) {
1965
+ if (( group.ch_mask & chanmask) && !(group. ch_mask & serial_chanmask) ) {
1959
1966
if (!setup_group_DMA (group, baudrate, 10 , false , DSHOT_BUFFER_LENGTH, 10 , false )) {
1960
1967
serial_end ();
1961
1968
return false ;
1962
1969
}
1963
1970
}
1964
1971
}
1965
-
1966
1972
// run the thread doing serial IO at highest priority. This is needed to ensure we don't
1967
1973
// lose bytes when we switch between output and input
1968
1974
serial_thread = chThdGetSelfX ();
1969
1975
serial_priority = chThdGetSelfX ()->realprio ;
1976
+ // mask of channels currently configured
1977
+ serial_chanmask |= chanmask;
1970
1978
chThdSetPriority (HIGHPRIO);
1971
1979
1972
1980
// 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
2002
2010
}
2003
2011
}
2004
2012
2005
-
2006
2013
/*
2007
2014
send one serial byte, blocking call, should be called with the DMA lock held
2008
2015
*/
@@ -2229,11 +2236,15 @@ void RCOutput::serial_end(void)
2229
2236
irq.waiter = nullptr ;
2230
2237
for (uint8_t i = 0 ; i < NUM_GROUPS; i++ ) {
2231
2238
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
+ }
2234
2244
}
2235
2245
}
2236
2246
serial_group = nullptr ;
2247
+ serial_chanmask = 0 ;
2237
2248
}
2238
2249
#endif // HAL_SERIAL_ESC_COMM_ENABLED
2239
2250
0 commit comments