mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-05 07:28:29 -04:00
HAL_ChibiOS: port SPI, I2C and UART drivers to H7
This commit is contained in:
parent
ae448a6932
commit
d9c888ab45
@ -118,7 +118,7 @@ I2CDeviceManager::I2CDeviceManager(void)
|
||||
drop the speed to be the minimum speed requested
|
||||
*/
|
||||
businfo[i].busclock = HAL_I2C_MAX_CLOCK;
|
||||
#if defined(STM32F7)
|
||||
#if defined(STM32F7) || defined(STM32H7)
|
||||
if (businfo[i].busclock <= 100000) {
|
||||
businfo[i].i2ccfg.timingr = HAL_I2C_F7_100_TIMINGR;
|
||||
businfo[i].busclock = 100000;
|
||||
@ -150,7 +150,7 @@ I2CDevice::I2CDevice(uint8_t busnum, uint8_t address, uint32_t bus_clock, bool u
|
||||
asprintf(&pname, "I2C:%u:%02x",
|
||||
(unsigned)busnum, (unsigned)address);
|
||||
if (bus_clock < bus.busclock) {
|
||||
#if defined(STM32F7)
|
||||
#if defined(STM32F7) || defined(STM32H7)
|
||||
if (bus_clock <= 100000) {
|
||||
bus.i2ccfg.timingr = HAL_I2C_F7_100_TIMINGR;
|
||||
bus.busclock = 100000;
|
||||
@ -197,7 +197,7 @@ bool I2CDevice::transfer(const uint8_t *send, uint32_t send_len,
|
||||
return false;
|
||||
}
|
||||
|
||||
#if defined(STM32F7)
|
||||
#if defined(STM32F7) || defined(STM32H7)
|
||||
if (_use_smbus) {
|
||||
bus.i2ccfg.cr1 |= I2C_CR1_SMBHEN;
|
||||
} else {
|
||||
|
@ -29,10 +29,17 @@ using namespace ChibiOS;
|
||||
extern const AP_HAL::HAL& hal;
|
||||
|
||||
// SPI mode numbers
|
||||
#if defined(STM32H7)
|
||||
#define SPIDEV_MODE0 0
|
||||
#define SPIDEV_MODE1 SPI_CFG2_CPHA
|
||||
#define SPIDEV_MODE2 SPI_CFG2_CPOL
|
||||
#define SPIDEV_MODE3 SPI_CFG2_CPOL | SPI_CFG2_CPHA
|
||||
#else
|
||||
#define SPIDEV_MODE0 0
|
||||
#define SPIDEV_MODE1 SPI_CR1_CPHA
|
||||
#define SPIDEV_MODE2 SPI_CR1_CPOL
|
||||
#define SPIDEV_MODE3 SPI_CR1_CPOL | SPI_CR1_CPHA
|
||||
#endif
|
||||
|
||||
#define SPI1_CLOCK STM32_PCLK2
|
||||
#define SPI2_CLOCK STM32_PCLK1
|
||||
@ -190,7 +197,7 @@ bool SPIDevice::clock_pulse(uint32_t n)
|
||||
return true;
|
||||
}
|
||||
|
||||
uint16_t SPIDevice::derive_freq_flag_bus(uint8_t busid, uint32_t _frequency)
|
||||
uint32_t SPIDevice::derive_freq_flag_bus(uint8_t busid, uint32_t _frequency)
|
||||
{
|
||||
uint32_t spi_clock_freq = SPI1_CLOCK;
|
||||
if (busid > 0 && uint8_t(busid-1) < ARRAY_SIZE(bus_clocks)) {
|
||||
@ -207,10 +214,14 @@ uint16_t SPIDevice::derive_freq_flag_bus(uint8_t busid, uint32_t _frequency)
|
||||
// assuming the bitrate bits are consecutive in the CR1 register,
|
||||
// we can just multiply by BR_0 to get the right bits for the desired
|
||||
// scaling
|
||||
#if defined(STM32H7)
|
||||
return (i * SPI_CFG1_MBR_0) | SPI_CFG1_DSIZE_VALUE(7); // 8 bit transfers
|
||||
#else
|
||||
return i * SPI_CR1_BR_0;
|
||||
#endif
|
||||
}
|
||||
|
||||
uint16_t SPIDevice::derive_freq_flag(uint32_t _frequency)
|
||||
uint32_t SPIDevice::derive_freq_flag(uint32_t _frequency)
|
||||
{
|
||||
uint8_t busid = spi_devices[device_desc.bus].busid;
|
||||
return derive_freq_flag_bus(busid, _frequency);
|
||||
@ -293,8 +304,13 @@ bool SPIDevice::acquire_bus(bool set, bool skip_cs)
|
||||
bus.spicfg.end_cb = nullptr;
|
||||
bus.spicfg.ssport = PAL_PORT(device_desc.pal_line);
|
||||
bus.spicfg.sspad = PAL_PAD(device_desc.pal_line);
|
||||
#if defined(STM32H7)
|
||||
bus.spicfg.cfg1 = freq_flag;
|
||||
bus.spicfg.cfg2 = device_desc.mode;
|
||||
#else
|
||||
bus.spicfg.cr1 = (uint16_t)(freq_flag | device_desc.mode);
|
||||
bus.spicfg.cr2 = 0;
|
||||
#endif
|
||||
if (bus.spi_started) {
|
||||
spiStop(spi_devices[device_desc.bus].driver);
|
||||
bus.spi_started = false;
|
||||
@ -379,7 +395,11 @@ void SPIDevice::test_clock_freq(void)
|
||||
SPIConfig spicfg {};
|
||||
const uint32_t target_freq = 2000000UL;
|
||||
// use a clock divisor of 256 for maximum resolution
|
||||
#if defined(STM32H7)
|
||||
spicfg.cfg1 = derive_freq_flag_bus(spi_devices[i].busid, target_freq);
|
||||
#else
|
||||
spicfg.cr1 = derive_freq_flag_bus(spi_devices[i].busid, target_freq);
|
||||
#endif
|
||||
spiAcquireBus(spi_devices[i].driver);
|
||||
spiStart(spi_devices[i].driver, &spicfg);
|
||||
uint32_t t0 = AP_HAL::micros();
|
||||
|
@ -48,7 +48,7 @@ public:
|
||||
struct SPIDesc {
|
||||
SPIDesc(const char *_name, uint8_t _bus,
|
||||
uint8_t _device, ioline_t _pal_line,
|
||||
uint16_t _mode, uint32_t _lowspeed, uint32_t _highspeed)
|
||||
uint32_t _mode, uint32_t _lowspeed, uint32_t _highspeed)
|
||||
: name(_name), bus(_bus), device(_device),
|
||||
pal_line(_pal_line), mode(_mode),
|
||||
lowspeed(_lowspeed), highspeed(_highspeed)
|
||||
@ -59,7 +59,7 @@ struct SPIDesc {
|
||||
uint8_t bus;
|
||||
uint8_t device;
|
||||
ioline_t pal_line;
|
||||
uint16_t mode;
|
||||
uint32_t mode;
|
||||
uint32_t lowspeed;
|
||||
uint32_t highspeed;
|
||||
};
|
||||
@ -119,14 +119,14 @@ private:
|
||||
SPIBus &bus;
|
||||
SPIDesc &device_desc;
|
||||
uint32_t frequency;
|
||||
uint16_t freq_flag;
|
||||
uint16_t freq_flag_low;
|
||||
uint16_t freq_flag_high;
|
||||
uint32_t freq_flag;
|
||||
uint32_t freq_flag_low;
|
||||
uint32_t freq_flag_high;
|
||||
char *pname;
|
||||
bool cs_forced;
|
||||
static void *spi_thread(void *arg);
|
||||
static uint16_t derive_freq_flag_bus(uint8_t busid, uint32_t _frequency);
|
||||
uint16_t derive_freq_flag(uint32_t _frequency);
|
||||
static uint32_t derive_freq_flag_bus(uint8_t busid, uint32_t _frequency);
|
||||
uint32_t derive_freq_flag(uint32_t _frequency);
|
||||
};
|
||||
|
||||
class SPIDeviceManager : public AP_HAL::SPIDeviceManager {
|
||||
|
@ -234,7 +234,7 @@ void UARTDriver::begin(uint32_t b, uint16_t rxS, uint16_t txS)
|
||||
(void *)this);
|
||||
osalDbgAssert(rxdma, "stream alloc failed");
|
||||
chSysUnlock();
|
||||
#if defined(STM32F7)
|
||||
#if defined(STM32F7) || defined(STM32H7)
|
||||
dmaStreamSetPeripheral(rxdma, &((SerialDriver*)sdef.serial)->usart->RDR);
|
||||
#else
|
||||
dmaStreamSetPeripheral(rxdma, &((SerialDriver*)sdef.serial)->usart->DR);
|
||||
@ -322,7 +322,7 @@ void UARTDriver::dma_tx_allocate(Shared_DMA *ctx)
|
||||
(void *)this);
|
||||
osalDbgAssert(txdma, "stream alloc failed");
|
||||
chSysUnlock();
|
||||
#if defined(STM32F7)
|
||||
#if defined(STM32F7) || defined(STM32H7)
|
||||
dmaStreamSetPeripheral(txdma, &((SerialDriver*)sdef.serial)->usart->TDR);
|
||||
#else
|
||||
dmaStreamSetPeripheral(txdma, &((SerialDriver*)sdef.serial)->usart->DR);
|
||||
@ -368,7 +368,7 @@ void UARTDriver::rx_irq_cb(void* self)
|
||||
if (!uart_drv->sdef.dma_rx) {
|
||||
return;
|
||||
}
|
||||
#if defined(STM32F7)
|
||||
#if defined(STM32F7) || defined(STM32H7)
|
||||
//disable dma, triggering DMA transfer complete interrupt
|
||||
uart_drv->rxdma->stream->CR &= ~STM32_DMA_CR_EN;
|
||||
#else
|
||||
|
Loading…
Reference in New Issue
Block a user