Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Binary file modified Tools/IO_Firmware/iofirmware_dshot_highpolh.bin
Binary file not shown.
Binary file modified Tools/IO_Firmware/iofirmware_dshot_lowpolh.bin
Binary file not shown.
Binary file modified Tools/IO_Firmware/iofirmware_f103_8MHz_dshot_highpolh.bin
Binary file not shown.
Binary file modified Tools/IO_Firmware/iofirmware_f103_8MHz_dshot_lowpolh.bin
Binary file not shown.
Binary file modified Tools/IO_Firmware/iofirmware_f103_8MHz_highpolh.bin
Binary file not shown.
Binary file modified Tools/IO_Firmware/iofirmware_f103_8MHz_lowpolh.bin
Binary file not shown.
Binary file modified Tools/IO_Firmware/iofirmware_f103_dshot_highpolh.bin
Binary file not shown.
Binary file modified Tools/IO_Firmware/iofirmware_f103_dshot_lowpolh.bin
Binary file not shown.
Binary file modified Tools/IO_Firmware/iofirmware_f103_highpolh.bin
Binary file not shown.
Binary file modified Tools/IO_Firmware/iofirmware_f103_lowpolh.bin
Binary file not shown.
Binary file modified Tools/IO_Firmware/iofirmware_highpolh.bin
Binary file not shown.
Binary file modified Tools/IO_Firmware/iofirmware_lowpolh.bin
Binary file not shown.
5 changes: 2 additions & 3 deletions libraries/AP_HAL_ChibiOS/RCOutput.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1531,16 +1531,15 @@ void RCOutput::dma_deallocate(Shared_DMA *ctx)
for (auto &group : pwm_group_list) {
if (group.dma_handle == ctx && group.dma != nullptr) {
chSysLock();
dmaStreamFreeI(group.dma);
#if defined(STM32F1)
// leaving the peripheral running on IOMCU plays havoc with the UART that is
// also sharing this channel, we only turn it off rather than resetting so
// that we don't have to worry about line modes etc
if (group.pwm_started && group.dma_handle->is_shared()) {
group.pwm_drv->tim->CR1 = 0;
group.pwm_drv->tim->DIER = 0;
bdshot_disable_pwm_f1(group);
}
#endif
dmaStreamFreeI(group.dma);
group.dma = nullptr;
chSysUnlock();
}
Expand Down
1 change: 1 addition & 0 deletions libraries/AP_HAL_ChibiOS/RCOutput.h
Original file line number Diff line number Diff line change
Expand Up @@ -733,6 +733,7 @@ class ChibiOS::RCOutput : public AP_HAL::RCOutput
static void bdshot_receive_pulses_DMAR_f1(pwm_group* group);
static void bdshot_reset_pwm(pwm_group& group, uint8_t telem_channel);
static void bdshot_reset_pwm_f1(pwm_group& group, uint8_t telem_channel);
static void bdshot_disable_pwm_f1(pwm_group& group);
static void bdshot_config_icu_dshot(stm32_tim_t* TIMx, uint8_t chan, uint8_t ccr_ch);
static void bdshot_config_icu_dshot_f1(stm32_tim_t* TIMx, uint8_t chan, uint8_t ccr_ch);
static uint32_t bdshot_get_output_rate_hz(const enum output_mode mode);
Expand Down
5 changes: 5 additions & 0 deletions libraries/AP_HAL_ChibiOS/RCOutput_bdshot.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -230,6 +230,11 @@ void RCOutput::bdshot_ic_dma_deallocate(Shared_DMA *ctx)
chSysLock();
if (group.bdshot.ic_dma_handle[icuch] == ctx && group.bdshot.ic_dma[icuch] != nullptr) {
dmaStreamFreeI(group.bdshot.ic_dma[icuch]);
#if defined(STM32F1)
if (group.bdshot.ic_dma_handle[icuch]->is_shared()) {
bdshot_disable_pwm_f1(group);
}
#endif
group.bdshot.ic_dma[icuch] = nullptr;
}
chSysUnlock();
Expand Down
23 changes: 16 additions & 7 deletions libraries/AP_HAL_ChibiOS/RCOutput_iofirmware.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -135,23 +135,32 @@ void RCOutput::rcout_thread() {
}
}

#if defined(HAL_WITH_BIDIR_DSHOT) && defined(STM32F1)
// reset pwm driver to output mode without resetting the clock or the peripheral
// the code here is the equivalent of pwmStart()/pwmStop()
void RCOutput::bdshot_reset_pwm_f1(pwm_group& group, uint8_t telem_channel)
#if defined(STM32F1)
void RCOutput::bdshot_disable_pwm_f1(pwm_group& group)
{
osalSysLock();

stm32_tim_t* TIMx = group.pwm_drv->tim;
// pwmStop sets these
TIMx->CR1 = 0; /* Timer disabled. */
TIMx->DIER = 0; /* All IRQs disabled. */
TIMx->SR = 0; /* Clear eventual pending IRQs. */
TIMx->CNT = 0;
TIMx->CNT = 0;
TIMx->CCR[0] = 0; /* Comparator 1 disabled. */
TIMx->CCR[1] = 0; /* Comparator 2 disabled. */
TIMx->CCR[2] = 0; /* Comparator 3 disabled. */
TIMx->CCR[3] = 0; /* Comparator 4 disabled. */
}
#endif

#if defined(HAL_WITH_BIDIR_DSHOT) && defined(STM32F1)
// reset pwm driver to output mode without resetting the clock or the peripheral
// the code here is the equivalent of pwmStart()/pwmStop()
void RCOutput::bdshot_reset_pwm_f1(pwm_group& group, uint8_t telem_channel)
{
osalSysLock();

stm32_tim_t* TIMx = group.pwm_drv->tim;
bdshot_disable_pwm_f1(group);

// at the point this is called we will have done input capture on two CC channels
// we need to switch those channels back to output and the default settings
// all other channels will not have been modified
Expand Down
2 changes: 2 additions & 0 deletions libraries/AP_HAL_ChibiOS/hwdef/iomcu-f103-dshot/hwdef.inc
Original file line number Diff line number Diff line change
Expand Up @@ -40,6 +40,8 @@ define STM32_TIM_TIM4_CH3_DMA_CHAN 1
define STM32_TIM_TIM3_CH4_DMA_STREAM STM32_DMA_STREAM_ID(1, 3)
define STM32_TIM_TIM3_CH4_DMA_CHAN 1

# STM32_UART_USART2_TX_DMA_STREAM defined as (1, 7) by ChibiOS

undef SHARED_DMA_MASK
define SHARED_DMA_MASK (1U<<STM32_TIM_TIM4_UP_DMA_STREAM | 1U<<STM32_TIM_TIM2_CH2_DMA_STREAM | 1U<<STM32_UART_USART2_TX_DMA_STREAM)

Expand Down
4 changes: 2 additions & 2 deletions libraries/AP_IOMCU/AP_IOMCU.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -646,8 +646,8 @@ bool AP_IOMCU::read_registers(uint8_t page, uint8_t offset, uint8_t count, uint1

// wait for the expected number of reply bytes or timeout
if (!uart.wait_timeout(count*2+4, 10)) {
debug("t=%lu timeout read page=%u offset=%u count=%u\n",
AP_HAL::millis(), page, offset, count);
debug("t=%lu timeout read page=%u offset=%u count=%u avail=%u\n",
AP_HAL::millis(), page, offset, count, uart.available());
protocol_fail_count++;
return false;
}
Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_IOMCU/iofirmware/iofirmware.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -91,7 +91,7 @@ static void setup_tx_dma(hal_uart_driver* uart)
dmaStreamSetMode(uart->dmatx, uart->dmatxmode | STM32_DMA_CR_DIR_M2P |
STM32_DMA_CR_MINC | STM32_DMA_CR_TCIE);
// enable transmission complete interrupt
uart->usart->SR = ~USART_SR_TC;
uart->usart->SR &= ~USART_SR_TC;
uart->usart->CR1 |= USART_CR1_TCIE;

dmaStreamEnable(uart->dmatx);
Expand Down