Fix SPI DMA issue (#55)

* [dma]icm check delete

* remove timer ,save irqs

移除usb 传输定时器,采用直接发送方式

Co-Authored-By: kikoqiu <5524046+kikoqiu@users.noreply.github.com>

* 取消禁止中断设计

Co-Authored-By: kikoqiu <5524046+kikoqiu@users.noreply.github.com>

* 取消 IS_CCM 检查

at32 无CCM 内存,DMA整体可用
同步bf 的修改回来, 清理代码

Co-Authored-By: Steve Evans <SteveCEvans@users.noreply.github.com>
Co-Authored-By: Gaogao <91398548+vangao-gg@users.noreply.github.com>

* 修正缩进

* add  new line

---------

Co-authored-by: gaofeng <1024355591@qq.com>
Co-authored-by: kikoqiu <5524046+kikoqiu@users.noreply.github.com>
Co-authored-by: Steve Evans <SteveCEvans@users.noreply.github.com>
Co-authored-by: Gaogao <91398548+vangao-gg@users.noreply.github.com>
This commit is contained in:
EMSR 2023-05-11 18:13:23 +08:00 committed by GitHub
parent ae262813c0
commit f8d2aed791
No known key found for this signature in database
GPG Key ID: 4AEE18F83AFDEB23
3 changed files with 124 additions and 301 deletions

View File

@ -26,9 +26,6 @@
#ifdef USE_SPI
// STM32F405 can't DMA to/from FASTRAM (CCM SRAM)
#define IS_CCM(p) (((uint32_t)p & 0xffff0000) == 0x10000000)
#include "common/maths.h"
#include "drivers/bus.h"
#include "drivers/bus_spi.h"
@ -37,37 +34,28 @@
#include "drivers/io.h"
#include "drivers/rcc.h"
static spi_init_type defaultInit = {
// .SPI_Mode = SPI_Mode_Master,
// .SPI_Direction = SPI_Direction_2Lines_FullDuplex,
// .SPI_DataSize = SPI_DataSize_8b,
// .SPI_NSS = SPI_NSS_Soft,
// .SPI_FirstBit = SPI_FirstBit_MSB,
// .SPI_CRCPolynomial = 7,
// .SPI_BaudRatePrescaler = SPI_BaudRatePrescaler_8,
// .SPI_CPOL = SPI_CPOL_High,
// .SPI_CPHA = SPI_CPHA_2Edge
//fixme: at32f43x的spi默认初始化需要自己单独设置crc polynomial using spi_crc_polynomial_set
.master_slave_mode = SPI_MODE_MASTER,
.transmission_mode = SPI_TRANSMIT_FULL_DUPLEX,
.frame_bit_num = SPI_FRAME_8BIT,
.cs_mode_selection = SPI_CS_SOFTWARE_MODE,
.first_bit_transmission = SPI_FIRST_BIT_MSB,
.mclk_freq_division = SPI_MCLK_DIV_8,
.clock_polarity = SPI_CLOCK_POLARITY_HIGH,
.clock_phase = SPI_CLOCK_PHASE_2EDGE };
// Use DMA if possible if this many bytes are to be transferred
#define SPI_DMA_THRESHOLD 8
static spi_init_type defaultInit = {
.master_slave_mode = SPI_MODE_MASTER,
.transmission_mode = SPI_TRANSMIT_FULL_DUPLEX,
.frame_bit_num = SPI_FRAME_8BIT,
.cs_mode_selection = SPI_CS_SOFTWARE_MODE,
.first_bit_transmission = SPI_FIRST_BIT_MSB,
.mclk_freq_division = SPI_MCLK_DIV_8,
.clock_polarity = SPI_CLOCK_POLARITY_HIGH,
.clock_phase = SPI_CLOCK_PHASE_2EDGE
};
//分频数转换为 BR 分频配置bit at32f437 对应ctrl1 寄存器 bit 5:3 mdiv[2:0] ctrl2 bit8 mdiv[3]
//与stm32F4 略增加 512分频和1024分频(mdiv[3]=1)
static uint16_t spiDivisorToBRbits(spi_type *instance, uint16_t divisor)
{
//at32 spi1\2\3 频率一样
UNUSED(instance);
UNUSED(instance);
divisor = constrain(divisor, 2, 256);
return (ffs(divisor) - 2) << 3; // SPI_CR1_BR_Pos
}
//bug: 不支持1000 512 1001 1024分频
static void spiSetDivisorBRreg(spi_type *instance, uint16_t divisor)
{
#define BR_BITS ((BIT(5) | BIT(4) | BIT(3)))
@ -76,7 +64,6 @@ static void spiSetDivisorBRreg(spi_type *instance, uint16_t divisor)
#undef BR_BITS
}
void spiInitDevice(SPIDevice device)
{
spiDevice_t *spi = &(spiDevice[device]);
@ -100,14 +87,13 @@ void spiInitDevice(SPIDevice device)
// Init SPI hardware
spi_i2s_reset(spi->dev);
spi_i2s_dma_transmitter_enable(spi->dev,TRUE);
spi_i2s_dma_receiver_enable(spi->dev,TRUE);
spi_i2s_dma_transmitter_enable(spi->dev, TRUE);
spi_i2s_dma_receiver_enable(spi->dev, TRUE);
spi_init(spi->dev,&defaultInit);
//补充设置crc其实复位值就是7 ,还是设置一下吧
spi_crc_polynomial_set(spi->dev,7);
spi_init(spi->dev, &defaultInit);
spi_crc_polynomial_set(spi->dev, 7);
spi_enable(spi->dev,TRUE);
spi_enable(spi->dev, TRUE);
}
void spiInternalResetDescriptors(busDevice_t *bus)
@ -119,10 +105,10 @@ void spiInternalResetDescriptors(busDevice_t *bus)
initTx->direction=DMA_DIR_MEMORY_TO_PERIPHERAL;
initTx->loop_mode_enable=FALSE;
initTx->peripheral_base_addr=(uint32_t)&bus->busType_u.spi.instance->dt ;
initTx->priority =DMA_PRIORITY_LOW;
initTx->peripheral_inc_enable =FALSE;
initTx->priority =DMA_PRIORITY_LOW;
initTx->peripheral_inc_enable =FALSE;
initTx->peripheral_data_width = DMA_PERIPHERAL_DATA_WIDTH_BYTE;
initTx->memory_data_width =DMA_MEMORY_DATA_WIDTH_BYTE;
initTx->memory_data_width = DMA_MEMORY_DATA_WIDTH_BYTE;
if (bus->dmaRx) {
dma_init_type *initRx = bus->initRx;
@ -141,13 +127,8 @@ void spiInternalResetDescriptors(busDevice_t *bus)
void spiInternalResetStream(dmaChannelDescriptor_t *descriptor)
{
DMA_ARCH_TYPE *streamRegs = (DMA_ARCH_TYPE *)descriptor->ref;
// Disable the stream
// streamRegs->CR = 0U;
// xDMA_DeInit(streamRegs);
xDMA_Cmd(streamRegs,DISABLE);
// Clear any pending interrupt flags
DMA_ARCH_TYPE *streamRegs = (DMA_ARCH_TYPE *)descriptor->ref;
xDMA_Cmd(streamRegs, FALSE);
DMA_CLEAR_FLAG(descriptor, DMA_IT_HTIF | DMA_IT_TEIF | DMA_IT_TCIF);
}
@ -156,19 +137,14 @@ static bool spiInternalReadWriteBufPolled(spi_type *instance, const uint8_t *txD
uint8_t b;
while (len--) {
/*
*
* SPI_I2S_FLAG_TXE Transmit buffer empty flag
* SPI_I2S_FLAG_RXNE Receive buffer not empty flag
*/
b = txData ? *(txData++) : 0xFF;
while(spi_i2s_flag_get(instance,SPI_I2S_TDBE_FLAG)==RESET);
spi_i2s_data_transmit(instance,b);
while (spi_i2s_flag_get(instance, SPI_I2S_TDBE_FLAG) == RESET);
spi_i2s_data_transmit(instance, b);
while(spi_i2s_flag_get(instance,SPI_I2S_RDBF_FLAG)==RESET);
b=spi_i2s_data_receive(instance);
while (spi_i2s_flag_get(instance, SPI_I2S_RDBF_FLAG) == RESET);
b = (uint8_t)spi_i2s_data_receive(instance);
if (rxData) {
*(rxData++) = b;
@ -201,10 +177,10 @@ void spiInternalInitStream(const extDevice_t *dev, bool preInit)
dma_init_type *initTx = bus->initTx;
if (txData) {
initTx->memory_base_addr = (uint32_t)txData;
initTx->memory_inc_enable =TRUE;
initTx->memory_base_addr = (uint32_t)txData;
initTx->memory_inc_enable =TRUE;
} else {
dummyTxByte = 0xff;//默认启动字节
dummyTxByte = 0xff;
initTx->memory_base_addr = (uint32_t)&dummyTxByte;
initTx->memory_inc_enable =FALSE;
}
@ -215,19 +191,13 @@ void spiInternalInitStream(const extDevice_t *dev, bool preInit)
dma_init_type *initRx = bus->initRx;
if (rxData) {
initRx->memory_base_addr= (uint32_t)rxData;
initRx->memory_inc_enable=TRUE;
initRx->memory_base_addr= (uint32_t)rxData;
initRx->memory_inc_enable = TRUE;
} else {
initRx->memory_base_addr = (uint32_t)&dummyRxByte;
initRx->memory_base_addr = (uint32_t)&dummyRxByte;
initRx->memory_inc_enable = FALSE;
}
// If possible use 16 bit memory writes to prevent atomic access issues on gyro data
//cause oom when using w25n01g
// if ((initRx->memory_base_addr & 0x1) || (len & 0x1)) {
// initRx->memory_data_width = DMA_MEMORY_DATA_WIDTH_BYTE;
// } else {
// initRx->memory_data_width = DMA_MEMORY_DATA_WIDTH_HALFWORD;
// }
initRx->buffer_size = len;
}
}
@ -238,7 +208,7 @@ void spiInternalStartDMA(const extDevice_t *dev)
dmaChannelDescriptor_t *dmaRx = dev->bus->dmaRx;
DMA_ARCH_TYPE *streamRegsTx = (DMA_ARCH_TYPE *)dmaTx->ref;
if (dmaRx) {
DMA_ARCH_TYPE *streamRegsRx = (DMA_ARCH_TYPE *)dmaRx->ref;
DMA_ARCH_TYPE *streamRegsRx = (DMA_ARCH_TYPE *)dmaRx->ref;
// Use the correct callback argument
dmaRx->userParam = (uint32_t)dev;
@ -248,30 +218,24 @@ void spiInternalStartDMA(const extDevice_t *dev)
DMA_CLEAR_FLAG(dmaRx, DMA_IT_HTIF | DMA_IT_TEIF | DMA_IT_TCIF);
// Disable streams to enable update
xDMA_Cmd(streamRegsTx, FALSE);
xDMA_Cmd(streamRegsRx, FALSE);
xDMA_Cmd(streamRegsTx, DISABLE);
xDMA_Cmd(streamRegsRx, DISABLE);
/* Use the Rx interrupt as this occurs once the SPI operation is complete whereas the Tx interrupt
* occurs earlier when the Tx FIFO is empty, but the SPI operation is still in progress
*/
xDMA_ITConfig(streamRegsRx, DMA_IT_TCIF, ENABLE);
xDMA_ITConfig(streamRegsRx, DMA_IT_TCIF, TRUE);
// Update streams
xDMA_Init(streamRegsTx, dev->bus->initTx);
xDMA_Init(streamRegsRx, dev->bus->initRx);
// Enable streams
xDMA_Cmd(streamRegsTx, ENABLE);
xDMA_Cmd(streamRegsRx, ENABLE);
//fixme: ENABLE DMAMUX ? should check dmamuxen regs in debug
/* Enable the SPI DMA Tx & Rx requests */
// SPI_I2S_DMACmd(dev->bus->busType_u.spi.instance, SPI_I2S_DMAReq_Tx | SPI_I2S_DMAReq_Rx, ENABLE);
spi_i2s_dma_transmitter_enable(dev->bus->busType_u.spi.instance,TRUE);
spi_i2s_dma_receiver_enable(dev->bus->busType_u.spi.instance,TRUE);
xDMA_Cmd(streamRegsTx, TRUE);
xDMA_Cmd(streamRegsRx, TRUE);
/* Enable the receiver before the transmitter to ensure that not bits are missed on reception. An interrupt between
* the transmitter and receiver being enabled can otherwise cause a hang.
*/
spi_i2s_dma_receiver_enable(dev->bus->busType_u.spi.instance, TRUE);
spi_i2s_dma_transmitter_enable(dev->bus->busType_u.spi.instance, TRUE);
} else {
// Use the correct callback argument
@ -281,24 +245,20 @@ void spiInternalStartDMA(const extDevice_t *dev)
DMA_CLEAR_FLAG(dmaTx, DMA_IT_HTIF | DMA_IT_TEIF | DMA_IT_TCIF);
// Disable stream to enable update
xDMA_Cmd(streamRegsTx, DISABLE);
xDMA_Cmd(streamRegsTx, FALSE);
// Update stream
xDMA_Init(streamRegsTx, dev->bus->initTx);
// Enable stream
xDMA_Cmd(streamRegsTx, ENABLE);
xDMA_ITConfig(streamRegsTx, DMA_IT_TCIF, ENABLE);
xDMA_Cmd(streamRegsTx, TRUE);
xDMA_ITConfig(streamRegsTx, DMA_IT_TCIF, TRUE);
/* Enable the SPI DMA Tx request */
spi_i2s_dma_transmitter_enable(dev->bus->busType_u.spi.instance,TRUE);
spi_i2s_dma_transmitter_enable(dev->bus->busType_u.spi.instance, TRUE);
}
}
void spiInternalStopDMA (const extDevice_t *dev)
{
dmaChannelDescriptor_t *dmaTx = dev->bus->dmaTx;
@ -307,36 +267,31 @@ void spiInternalStopDMA (const extDevice_t *dev)
DMA_ARCH_TYPE *streamRegsTx = (DMA_ARCH_TYPE *)dmaTx->ref;
if (dmaRx) {
DMA_ARCH_TYPE *streamRegsRx = (DMA_ARCH_TYPE *)dmaRx->ref;
DMA_ARCH_TYPE *streamRegsRx = (DMA_ARCH_TYPE *)dmaRx->ref;
// Disable streams
xDMA_Cmd(streamRegsTx,DISABLE);
xDMA_Cmd(streamRegsRx,DISABLE);
xDMA_Cmd(streamRegsTx, FALSE);
xDMA_Cmd(streamRegsRx, FALSE);
DMA_CLEAR_FLAG(dmaTx, DMA_IT_HTIF | DMA_IT_TEIF | DMA_IT_TCIF);
DMA_CLEAR_FLAG(dmaRx, DMA_IT_HTIF | DMA_IT_TEIF | DMA_IT_TCIF);
spi_i2s_dma_transmitter_enable(instance,FALSE);
spi_i2s_dma_receiver_enable(instance,FALSE);
DMA_CLEAR_FLAG(dmaTx, DMA_IT_HTIF | DMA_IT_TEIF | DMA_IT_TCIF);
DMA_CLEAR_FLAG(dmaRx, DMA_IT_HTIF | DMA_IT_TEIF | DMA_IT_TCIF);
spi_i2s_dma_transmitter_enable(instance, FALSE);
spi_i2s_dma_receiver_enable(instance, FALSE);
} else {
// Ensure the current transmission is complete
while(spi_i2s_flag_get(instance,SPI_I2S_BF_FLAG));
while (spi_i2s_flag_get(instance, SPI_I2S_BF_FLAG));
// Drain the RX buffer
while(spi_i2s_flag_get(instance,SPI_I2S_RDBF_FLAG)){
// instance->DR;
while (spi_i2s_flag_get(instance, SPI_I2S_RDBF_FLAG)) {
instance->dt;
}
// Disable stream
xDMA_Cmd(streamRegsTx,DISABLE);
DMA_CLEAR_FLAG(dmaTx, DMA_IT_HTIF | DMA_IT_TEIF | DMA_IT_TCIF);
xDMA_Cmd(streamRegsTx, FALSE);
DMA_CLEAR_FLAG(dmaTx, DMA_IT_HTIF | DMA_IT_TEIF | DMA_IT_TCIF);
spi_i2s_dma_transmitter_enable(instance,FALSE);
spi_i2s_dma_transmitter_enable(instance, FALSE);
}
}
@ -351,8 +306,7 @@ void spiSequenceStart(const extDevice_t *dev)
dev->bus->initSegment = true;
// SPI_Cmd(instance, DISABLE);
spi_enable(instance,FALSE);
spi_enable(instance, FALSE);
// Switch bus speed
if (dev->busType_u.spi.speed != bus->busType_u.spi.speed) {
@ -361,42 +315,30 @@ void spiSequenceStart(const extDevice_t *dev)
}
if (dev->busType_u.spi.leadingEdge != bus->busType_u.spi.leadingEdge) {
// Switch SPI clock polarity/phase
// instance->CR1 &= ~(SPI_CPOL_High | SPI_CPHA_2Edge);
//fixme: 这里是否是漏写了?
// Apply setting
if (dev->busType_u.spi.leadingEdge) {
// instance->CR1 |= SPI_CPOL_Low | SPI_CPHA_1Edge;
instance->ctrl1_bit.clkpol = SPI_CLOCK_POLARITY_LOW;
instance->ctrl1_bit.clkpha = SPI_CLOCK_PHASE_1EDGE;
} else
{
// instance->CR1 |= SPI_CPOL_High | SPI_CPHA_2Edge;
} else {
instance->ctrl1_bit.clkpol = SPI_CLOCK_POLARITY_HIGH;
instance->ctrl1_bit.clkpha = SPI_CLOCK_PHASE_2EDGE;
}
bus->busType_u.spi.leadingEdge = dev->busType_u.spi.leadingEdge;
}
// SPI_Cmd(instance, ENABLE);
spi_enable(instance,TRUE);
spi_enable(instance, TRUE);
// Check that any there are no attempts to DMA to/from CCD SRAM
// Count segments
for (busSegment_t *checkSegment = (busSegment_t *)bus->curSegment; checkSegment->len; checkSegment++) {
// Check there is no receive data as only transmit DMA is available
if (((checkSegment->u.buffers.rxData) && (IS_CCM(checkSegment->u.buffers.rxData) || (bus->dmaRx == (dmaChannelDescriptor_t *)NULL))) ||
((checkSegment->u.buffers.txData) && IS_CCM(checkSegment->u.buffers.txData))) {
dmaSafe = false;
break;
}
// Note that these counts are only valid if dmaSafe is true
segmentCount++;
xferLen += checkSegment->len;
}
// Use DMA if possible
// If there are more than one segments, or a single segment with negateCS negated then force DMA irrespective of length
if (bus->useDMA && dmaSafe && ((segmentCount > 1) || (xferLen >= 8) || !bus->curSegment->negateCS)) {
// If there are more than one segments, or a single segment with negateCS negated in the list terminator then force DMA irrespective of length
if (bus->useDMA && dmaSafe && ((segmentCount > 1) ||
(xferLen >= SPI_DMA_THRESHOLD) ||
!bus->curSegment[segmentCount].negateCS)) {
// Intialise the init structures for the first transfer
spiInternalInitStream(dev, false);
@ -407,6 +349,7 @@ void spiSequenceStart(const extDevice_t *dev)
spiInternalStartDMA(dev);
} else {
busSegment_t *lastSegment = NULL;
bool segmentComplete;
// Manually work through the segment list performing a transfer for each
while (bus->curSegment->len) {
@ -415,26 +358,27 @@ void spiSequenceStart(const extDevice_t *dev)
IOLo(dev->busType_u.spi.csnPin);
}
spiInternalReadWriteBufPolled(
bus->busType_u.spi.instance,
bus->curSegment->u.buffers.txData,
bus->curSegment->u.buffers.rxData,
bus->curSegment->len);
spiInternalReadWriteBufPolled(bus->busType_u.spi.instance,
bus->curSegment->u.buffers.txData,
bus->curSegment->u.buffers.rxData,
bus->curSegment->len);
if (bus->curSegment->negateCS) {
// Negate Chip Select
IOHi(dev->busType_u.spi.csnPin);
}
segmentComplete = true;
if (bus->curSegment->callback) {
switch(bus->curSegment->callback(dev->callbackArg)) {
case BUS_BUSY:
// Repeat the last DMA segment
bus->curSegment--;
segmentComplete = false;
break;
case BUS_ABORT:
bus->curSegment = (busSegment_t *)BUS_SPI_FREE;
segmentComplete = false;
return;
case BUS_READY:
@ -443,13 +387,10 @@ void spiSequenceStart(const extDevice_t *dev)
break;
}
}
lastSegment = (busSegment_t *)bus->curSegment;
bus->curSegment++;
}
if (lastSegment && !lastSegment->negateCS) {
// Negate Chip Select if not done so already
IOHi(dev->busType_u.spi.csnPin);
if (segmentComplete) {
lastSegment = (busSegment_t *)bus->curSegment;
bus->curSegment++;
}
}
// If a following transaction has been linked, start it
@ -461,7 +402,6 @@ void spiSequenceStart(const extDevice_t *dev)
endSegment->u.link.dev = NULL;
spiSequenceStart(nextDev);
} else {
// The end of the segment list has been reached, so mark transactions as complete
bus->curSegment = (busSegment_t *)BUS_SPI_FREE;
}
}

View File

@ -234,22 +234,15 @@ void OTG_WKUP_HANDLER(void)
uint32_t CDC_Send_FreeBytes(void)
{
/*
return the bytes free in the circular buffer
functionally equivalent to:
(APP_Rx_ptr_out > APP_Rx_ptr_in ? APP_Rx_ptr_out - APP_Rx_ptr_in : APP_RX_DATA_SIZE - APP_Rx_ptr_in + APP_Rx_ptr_in)
but without the impact of the condition check.
*/
uint32_t freeBytes;
ATOMIC_BLOCK(NVIC_BUILD_PRIORITY(6, 0)) {
freeBytes = ((UserTxBufPtrOut - UserTxBufPtrIn) + (-((int)(UserTxBufPtrOut <= UserTxBufPtrIn)) & APP_TX_DATA_SIZE)) - 1;
}
return freeBytes;
cdc_struct_type *pcdc = (cdc_struct_type *)otg_core_struct.dev.class_handler->pdata;
if(pcdc->g_tx_completed){
return APP_TX_BLOCK_SIZE;
}else{
return 0;
}
}
/**
* @brief CDC_Send_DATA
* CDC received data to be send over USB IN endpoint are managed in
@ -260,106 +253,40 @@ uint32_t CDC_Send_FreeBytes(void)
*/
uint32_t CDC_Send_DATA(const uint8_t *ptrBuffer, uint32_t sendLength)
{
for (uint32_t i = 0; i < sendLength; i++) {
while (CDC_Send_FreeBytes() == 0) {
// block until there is free space in the ring buffer
delay(1);
}
ATOMIC_BLOCK(NVIC_BUILD_PRIORITY(6, 0)) { // Paranoia
UserTxBuffer[UserTxBufPtrIn] = ptrBuffer[i];
UserTxBufPtrIn = (UserTxBufPtrIn + 1) % APP_TX_DATA_SIZE;
}
cdc_struct_type *pcdc = (cdc_struct_type *)otg_core_struct.dev.class_handler->pdata;
uint32_t start = millis();
uint32_t pos=0;
while(pos < sendLength || (pos==sendLength && sendLength%64 == 0) ){//`==` is intended for sending 0 length packet
int tosend=sendLength-pos;
if(tosend>APP_TX_BLOCK_SIZE){
tosend=APP_TX_BLOCK_SIZE;
}
return sendLength;
}
void TxTimerConfig(void){
/* Initialize TIMx peripheral as follow:
+ Period = CDC_POLLING_INTERVAL*1000 - 1 every 5ms
+ Prescaler = ((SystemCoreClock/2)/10000) - 1
+ ClockDivision = 0
+ Counter direction = Up
*/
//timer, period, perscaler
tmr_base_init(usbTxTmr,(CDC_POLLING_INTERVAL - 1),((system_core_clock)/1000 - 1));
//TMR_CLOCK_DIV1 = 0X00 NO DIV
tmr_clock_source_div_set(usbTxTmr,TMR_CLOCK_DIV1);
//COUNT UP
tmr_cnt_dir_set(usbTxTmr,TMR_COUNT_UP);
tmr_period_buffer_enable(usbTxTmr,TRUE);
tmr_interrupt_enable(usbTxTmr, TMR_OVF_INT, TRUE);
nvic_irq_enable(TMR20_OVF_IRQn,NVIC_PRIORITY_BASE(NVIC_PRIO_USB), NVIC_PRIORITY_SUB(NVIC_PRIO_USB));
tmr_counter_enable(usbTxTmr,TRUE);
}
/**
* @brief TIM period elapsed callback
* @param htim: TIM handle
* @retval None
*/
void TMR20_OVF_IRQHandler()
{
uint32_t buffsize;
static uint32_t lastBuffsize = 0;
cdc_struct_type *pcdc = (cdc_struct_type *)otg_core_struct.dev.class_handler->pdata;
if (pcdc->g_tx_completed == 1) {
// endpoint has finished transmitting previous block
if (lastBuffsize) {
bool needZeroLengthPacket = lastBuffsize % 64 == 0;
// move the ring buffer tail based on the previous succesful transmission
UserTxBufPtrOut += lastBuffsize;
if (UserTxBufPtrOut == APP_TX_DATA_SIZE) {
UserTxBufPtrOut = 0;
}
lastBuffsize = 0;
if (needZeroLengthPacket) {
usb_vcp_send_data(&otg_core_struct.dev, (uint8_t*)&UserTxBuffer[UserTxBufPtrOut], 0);
return;
}
}
if (UserTxBufPtrOut != UserTxBufPtrIn) {
if (UserTxBufPtrOut > UserTxBufPtrIn) { /* Roll-back */
buffsize = APP_TX_DATA_SIZE - UserTxBufPtrOut;
} else {
buffsize = UserTxBufPtrIn - UserTxBufPtrOut;
}
if (buffsize > APP_TX_BLOCK_SIZE) {
buffsize = APP_TX_BLOCK_SIZE;
}
uint32_t txed=usb_vcp_send_data(&otg_core_struct.dev,(uint8_t*)&UserTxBuffer[UserTxBufPtrOut], buffsize);
if (txed==SUCCESS) {
lastBuffsize = buffsize;
}
}
while(pcdc->g_tx_completed != 1) {
if (millis() - start > USB_TIMEOUT) {
return pos;
}
}
tmr_flag_clear(usbTxTmr,TMR_OVF_FLAG);
uint32_t txed=usb_vcp_send_data(&otg_core_struct.dev,(uint8_t *)(ptrBuffer+pos), tosend);
if(pos==sendLength){
break;
}
if (txed==SUCCESS) {
pos+=tosend;
}
}
return pos;
}
/************************************************************/
//是否插入
uint8_t usbIsConnected(){
return (USB_CONN_STATE_DEFAULT !=otg_core_struct.dev.conn_state);
return (USB_CONN_STATE_DEFAULT !=otg_core_struct.dev.conn_state);
}
//是否配置
uint8_t usbIsConfigured(){
return (USB_CONN_STATE_CONFIGURED ==otg_core_struct.dev.conn_state);
return (USB_CONN_STATE_CONFIGURED ==otg_core_struct.dev.conn_state);
}
//vcp 状态
@ -427,18 +354,14 @@ static bool isUsbVcpTransmitBufferEmpty(const serialPort_t *instance)
//缓冲区是否有数据,需要实现
static uint32_t usbVcpAvailable(const serialPort_t *instance)
{
UNUSED(instance);
uint32_t available=0;
available=APP_Rx_ptr_in-APP_Rx_ptr_out;
if(available ==0){//是否还有没copy到缓存里的
cdc_struct_type *pcdc = (cdc_struct_type *)otg_core_struct.dev.class_handler->pdata;
if(pcdc->g_rx_completed == 1){
available=pcdc->g_rxlen;
}
}
return available;
UNUSED(instance);
cdc_struct_type *pcdc = (cdc_struct_type *)otg_core_struct.dev.class_handler->pdata;
uint32_t available=APP_Rx_ptr_in-APP_Rx_ptr_out;
if(pcdc->g_rx_completed == 1){
available+=pcdc->g_rxlen;
}
return available;
}
/*
@ -609,9 +532,6 @@ serialPort_t *usbVcpOpen(void)
s->port.vTable = usbVTable;
//CONFIG TX TIMER
TxTimerConfig();
return (serialPort_t *)s;
}
//查询波特率 完成修改
@ -623,8 +543,5 @@ uint32_t usbVcpGetBaudRate(serialPort_t *instance)
cdc_struct_type *pcdc = (cdc_struct_type *)otg_core_struct.dev.class_handler->pdata;
return pcdc->linecoding.bitrate;
}
#endif

View File

@ -156,28 +156,7 @@ static uint8_t BL_ReadBuf(uint8_t *pstring, uint8_t len)
CRC_16.word = 0;
LastCRC_16.word = 0;
uint8_t LastACK = brNONE;
//disable exint
uint32_t ExIntReg=0;
/* 因为收发过程采用GPIO模拟且收发时长最大可达70ms在期间可能会出现被其他中断打断的情况
*
* atomic_block(nvic_prio_max)
*/
#if defined(AT32F43x)
//disable exint
ExIntReg=EXINT->inten;
EXINT->inten=0;//DISABLE ALL EXINT
//disable 5-15 EXINT
NVIC_DisableIRQ(EXINT9_5_IRQn);
NVIC_DisableIRQ(EXINT15_10_IRQn);
//disable USB
NVIC_DisableIRQ(TMR20_OVF_IRQn);
NVIC_DisableIRQ(OTGFS1_IRQn);
//disable uart 1\2\3
NVIC_DisableIRQ(USART1_IRQn);
NVIC_DisableIRQ(USART2_IRQn);
NVIC_DisableIRQ(USART3_IRQn);
#endif
do {
if (!suart_getc_(pstring)) goto timeout;
ByteCrc(pstring);
@ -197,19 +176,6 @@ static uint8_t BL_ReadBuf(uint8_t *pstring, uint8_t len)
if (!suart_getc_(&LastACK)) goto timeout;
}
timeout:
#if defined(AT32F43x)
//re-enable exint
EXINT->inten=ExIntReg;
NVIC_EnableIRQ(EXINT9_5_IRQn);
NVIC_EnableIRQ(EXINT15_10_IRQn);
//re-enable USB
NVIC_EnableIRQ(TMR20_OVF_IRQn);//TODO:tmr20 should be removed after
NVIC_EnableIRQ(OTGFS1_IRQn);
//re-enable uart 1\2\3
NVIC_EnableIRQ(USART1_IRQn);
NVIC_EnableIRQ(USART2_IRQn);
NVIC_EnableIRQ(USART3_IRQn);
#endif
return (LastACK == brSUCCESS);
}