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