Skip to content

Commit

Permalink
Merge pull request #10909 from SteveCEvans/g4_spi
Browse files Browse the repository at this point in the history
  • Loading branch information
mikeller committed Aug 31, 2021
2 parents bdccfc3 + ab66795 commit 4c9eb21
Show file tree
Hide file tree
Showing 10 changed files with 75 additions and 289 deletions.
Empty file.
4 changes: 2 additions & 2 deletions make/mcu/STM32G4.mk
Expand Up @@ -40,6 +40,7 @@ EXCLUDES = \
stm32g4xx_hal_smartcard.c \
stm32g4xx_hal_smartcard_ex.c \
stm32g4xx_hal_smbus.c \
stm32g4xx_hal_spi.c \
stm32g4xx_hal_spi_ex.c \
stm32g4xx_hal_sram.c \
stm32g4xx_hal_timebase_tim_template.c \
Expand All @@ -65,7 +66,6 @@ EXCLUDES = \
stm32g4xx_ll_rcc.c \
stm32g4xx_ll_rng.c \
stm32g4xx_ll_rtc.c \
stm32g4xx_ll_spi.c \
stm32g4xx_ll_ucpd.c \
stm32g4xx_ll_usart.c \
stm32g4xx_ll_utils.c
Expand Down Expand Up @@ -161,7 +161,7 @@ MCU_COMMON_SRC = \
drivers/bus_i2c_hal.c \
drivers/bus_i2c_hal_init.c \
drivers/bus_i2c_timing.c \
drivers/bus_spi_hal.c \
drivers/bus_spi_ll.c \
drivers/dma_stm32g4xx.c \
drivers/dshot_bitbang.c \
drivers/dshot_bitbang_decode.c \
Expand Down
12 changes: 6 additions & 6 deletions src/main/drivers/accgyro/accgyro_spi_bmi270.c
Expand Up @@ -282,8 +282,8 @@ static bool bmi270AccRead(accDev_t *acc)
BUFFER_SIZE,
};

uint8_t bmi270_rx_buf[BUFFER_SIZE];
static const uint8_t bmi270_tx_buf[BUFFER_SIZE] = {BMI270_REG_ACC_DATA_X_LSB | 0x80, 0, 0, 0, 0, 0, 0, 0};
STATIC_DMA_DATA_AUTO uint8_t bmi270_rx_buf[BUFFER_SIZE];
STATIC_DMA_DATA_AUTO uint8_t bmi270_tx_buf[BUFFER_SIZE] = {BMI270_REG_ACC_DATA_X_LSB | 0x80, 0, 0, 0, 0, 0, 0, 0};

spiReadWriteBuf(&acc->gyro->dev, (uint8_t *)bmi270_tx_buf, bmi270_rx_buf, BUFFER_SIZE); // receive response

Expand All @@ -308,8 +308,8 @@ static bool bmi270GyroReadRegister(gyroDev_t *gyro)
BUFFER_SIZE,
};

uint8_t bmi270_rx_buf[BUFFER_SIZE];
static const uint8_t bmi270_tx_buf[BUFFER_SIZE] = {BMI270_REG_GYR_DATA_X_LSB | 0x80, 0, 0, 0, 0, 0, 0, 0};
STATIC_DMA_DATA_AUTO uint8_t bmi270_rx_buf[BUFFER_SIZE];
STATIC_DMA_DATA_AUTO uint8_t bmi270_tx_buf[BUFFER_SIZE] = {BMI270_REG_GYR_DATA_X_LSB | 0x80, 0, 0, 0, 0, 0, 0, 0};

spiReadWriteBuf(&gyro->dev, (uint8_t *)bmi270_tx_buf, bmi270_rx_buf, BUFFER_SIZE); // receive response

Expand Down Expand Up @@ -338,8 +338,8 @@ static bool bmi270GyroReadFifo(gyroDev_t *gyro)
};

bool dataRead = false;
static const uint8_t bmi270_tx_buf[BUFFER_SIZE] = {BMI270_REG_FIFO_LENGTH_LSB | 0x80, 0, 0, 0, 0, 0, 0, 0, 0, 0};
uint8_t bmi270_rx_buf[BUFFER_SIZE];
STATIC_DMA_DATA_AUTO uint8_t bmi270_tx_buf[BUFFER_SIZE] = {BMI270_REG_FIFO_LENGTH_LSB | 0x80, 0, 0, 0, 0, 0, 0, 0, 0, 0};
STATIC_DMA_DATA_AUTO uint8_t bmi270_rx_buf[BUFFER_SIZE];

// Burst read the FIFO length followed by the next 6 bytes containing the gyro axis data for
// the first sample in the queue. It's possible for the FIFO to be empty so we need to check the
Expand Down
4 changes: 1 addition & 3 deletions src/main/drivers/bus.h
Expand Up @@ -64,8 +64,6 @@ typedef struct busDevice_s {
uint8_t deviceCount;
dmaChannelDescriptor_t *dmaTx;
dmaChannelDescriptor_t *dmaRx;
uint32_t dmaTxChannel;
uint32_t dmaRxChannel;
#ifndef UNIT_TEST
// Use a reference here as this saves RAM for unused descriptors
#if defined(USE_FULL_LL_DRIVER)
Expand Down Expand Up @@ -109,7 +107,7 @@ typedef struct extDevice_s {
} busType_u;
#ifndef UNIT_TEST
// Cache the init structure for the next DMA transfer to reduce inter-segment delay
#if defined(USE_HAL_DRIVER)
#if defined(USE_FULL_LL_DRIVER)
LL_DMA_InitTypeDef initTx;
LL_DMA_InitTypeDef initRx;
#else
Expand Down
15 changes: 10 additions & 5 deletions src/main/drivers/bus_spi.c
Expand Up @@ -543,7 +543,9 @@ void spiInitBusDMA()
break;
}
#endif
bus->dmaTxChannel = dmaTxChannelSpec->channel;
bus->dmaTx = dmaGetDescriptorByIdentifier(dmaTxIdentifier);
bus->dmaTx->stream = DMA_DEVICE_INDEX(dmaTxIdentifier);
bus->dmaTx->channel = dmaTxChannelSpec->channel;
dmaInit(dmaTxIdentifier, OWNER_SPI_MOSI, device + 1);
break;
}
Expand All @@ -564,16 +566,15 @@ void spiInitBusDMA()
break;
}
#endif
bus->dmaRxChannel = dmaRxChannelSpec->channel;
bus->dmaRx = dmaGetDescriptorByIdentifier(dmaRxIdentifier);
bus->dmaRx->stream = DMA_DEVICE_INDEX(dmaRxIdentifier);
bus->dmaRx->channel = dmaRxChannelSpec->channel;
dmaInit(dmaRxIdentifier, OWNER_SPI_MISO, device + 1);
break;
}
}

if (dmaTxIdentifier && dmaRxIdentifier) {
bus->dmaTx = dmaGetDescriptorByIdentifier(dmaTxIdentifier);
bus->dmaRx = dmaGetDescriptorByIdentifier(dmaRxIdentifier);

// Ensure streams are disabled
spiInternalResetStream(bus->dmaRx);
spiInternalResetStream(bus->dmaTx);
Expand All @@ -586,6 +587,10 @@ void spiInitBusDMA()
dmaSetHandler(dmaRxIdentifier, spiRxIrqHandler, NVIC_PRIO_SPI_DMA, 0);

bus->useDMA = true;
} else {
// Disassociate channels from bus
bus->dmaRx = (dmaChannelDescriptor_t *)NULL;
bus->dmaTx = (dmaChannelDescriptor_t *)NULL;
}
}
}
Expand Down
249 changes: 0 additions & 249 deletions src/main/drivers/bus_spi_hal.c

This file was deleted.

0 comments on commit 4c9eb21

Please sign in to comment.