mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-26 17:55:30 +03:00
Re-arranging VCP/IO/EXTI files in preparation for AT32 (#12289)
* Re-arranging VCP files in preparation for AT32 * Tab size 4 * Adding ADC driver for AT32F43x * RCC code here is STM32 specific. * Adding rcc.c for AT32 * pwm_output.c has very specific MCU coupling - to be re factored. * Separating exti.c * Split up io.c int stm32/io_stm32.c and at32/io_at32.c * Adding in VCP files for AT32 and move timer - note will require more cleanup * Solving for sanity checks * Inadvertent inclusion of timer.c for HAL * rcc.c, timer.c and moving other spevific files out of the driver directory * Adding I2C drivers * Formatting * ws2811 driver and usb_msc driver skeleton
This commit is contained in:
parent
dac1512b30
commit
72ab5b1275
95 changed files with 10624 additions and 1333 deletions
|
@ -31,62 +31,8 @@ struct ioPortDef_s {
|
|||
rccPeriphTag_t rcc;
|
||||
};
|
||||
|
||||
#if defined(STM32F4)
|
||||
const struct ioPortDef_s ioPortDefs[] = {
|
||||
{ RCC_AHB1(GPIOA) },
|
||||
{ RCC_AHB1(GPIOB) },
|
||||
{ RCC_AHB1(GPIOC) },
|
||||
{ RCC_AHB1(GPIOD) },
|
||||
{ RCC_AHB1(GPIOE) },
|
||||
{ RCC_AHB1(GPIOF) },
|
||||
};
|
||||
#elif defined(STM32F7)
|
||||
const struct ioPortDef_s ioPortDefs[] = {
|
||||
{ RCC_AHB1(GPIOA) },
|
||||
{ RCC_AHB1(GPIOB) },
|
||||
{ RCC_AHB1(GPIOC) },
|
||||
{ RCC_AHB1(GPIOD) },
|
||||
{ RCC_AHB1(GPIOE) },
|
||||
{ RCC_AHB1(GPIOF) },
|
||||
};
|
||||
#elif defined(STM32H7)
|
||||
const struct ioPortDef_s ioPortDefs[] = {
|
||||
{ RCC_AHB4(GPIOA) },
|
||||
{ RCC_AHB4(GPIOB) },
|
||||
{ RCC_AHB4(GPIOC) },
|
||||
{ RCC_AHB4(GPIOD) },
|
||||
{ RCC_AHB4(GPIOE) },
|
||||
{ RCC_AHB4(GPIOF) },
|
||||
{ RCC_AHB4(GPIOG) },
|
||||
{ RCC_AHB4(GPIOH) },
|
||||
#if !(defined(STM32H723xx) || defined(STM32H725xx) || defined(STM32H730xx))
|
||||
{ RCC_AHB4(GPIOI) },
|
||||
#endif
|
||||
};
|
||||
#elif defined(STM32G4)
|
||||
const struct ioPortDef_s ioPortDefs[] = {
|
||||
{ RCC_AHB2(GPIOA) },
|
||||
{ RCC_AHB2(GPIOB) },
|
||||
{ RCC_AHB2(GPIOC) },
|
||||
{ RCC_AHB2(GPIOD) },
|
||||
{ RCC_AHB2(GPIOE) },
|
||||
{ RCC_AHB2(GPIOF) },
|
||||
};
|
||||
#elif defined(AT32F4)
|
||||
const struct ioPortDef_s ioPortDefs[] = {
|
||||
{ RCC_AHB1(GPIOA) },
|
||||
{ RCC_AHB1(GPIOB) },
|
||||
{ RCC_AHB1(GPIOC) },
|
||||
{ RCC_AHB1(GPIOD) },
|
||||
{ RCC_AHB1(GPIOE) },
|
||||
{ RCC_AHB1(GPIOF) },
|
||||
{ RCC_AHB1(GPIOG) },
|
||||
{ RCC_AHB1(GPIOH) }
|
||||
};
|
||||
#elif defined(SITL)
|
||||
#if defined(SITL)
|
||||
const struct ioPortDef_s ioPortDefs[] = { 0 };
|
||||
#else
|
||||
# error "IO PortDefs not defined for MCU"
|
||||
#endif
|
||||
|
||||
ioRec_t* IO_Rec(IO_t io)
|
||||
|
@ -106,13 +52,12 @@ uint16_t IO_Pin(IO_t io)
|
|||
return ioRec->pin;
|
||||
}
|
||||
|
||||
// port index, GPIOA == 0
|
||||
int IO_GPIOPortIdx(IO_t io)
|
||||
{
|
||||
if (!io) {
|
||||
return -1;
|
||||
}
|
||||
return (((size_t)IO_GPIO(io) - GPIOA_BASE) >> 10); // ports are 0x400 apart
|
||||
return (((size_t)IO_GPIO(io) - GPIOA_BASE) >> 10);
|
||||
}
|
||||
|
||||
int IO_EXTI_PortSourceGPIO(IO_t io)
|
||||
|
@ -131,7 +76,7 @@ int IO_GPIOPinIdx(IO_t io)
|
|||
if (!io) {
|
||||
return -1;
|
||||
}
|
||||
return 31 - __builtin_clz(IO_Pin(io)); // CLZ is a bit faster than FFS
|
||||
return 31 - __builtin_clz(IO_Pin(io));
|
||||
}
|
||||
|
||||
int IO_EXTI_PinSource(IO_t io)
|
||||
|
@ -144,132 +89,6 @@ int IO_GPIO_PinSource(IO_t io)
|
|||
return IO_GPIOPinIdx(io);
|
||||
}
|
||||
|
||||
// mask on stm32f103, bit index on stm32f303
|
||||
uint32_t IO_EXTI_Line(IO_t io)
|
||||
{
|
||||
if (!io) {
|
||||
return 0;
|
||||
}
|
||||
#if defined(STM32F4) || defined(STM32F7) || defined(STM32H7) || defined(STM32G4) || defined(AT32F4)
|
||||
return 1 << IO_GPIOPinIdx(io);
|
||||
#elif defined(SIMULATOR_BUILD)
|
||||
return 0;
|
||||
#else
|
||||
# error "Unknown target type"
|
||||
#endif
|
||||
}
|
||||
|
||||
bool IORead(IO_t io)
|
||||
{
|
||||
if (!io) {
|
||||
return false;
|
||||
}
|
||||
#if defined(USE_FULL_LL_DRIVER)
|
||||
return (LL_GPIO_ReadInputPort(IO_GPIO(io)) & IO_Pin(io));
|
||||
#elif defined(USE_HAL_DRIVER)
|
||||
return !! HAL_GPIO_ReadPin(IO_GPIO(io), IO_Pin(io));
|
||||
#elif defined(USE_ATBSP_DRIVER)
|
||||
return (IO_GPIO(io)->idt & IO_Pin(io));
|
||||
#else
|
||||
return (IO_GPIO(io)->IDR & IO_Pin(io));
|
||||
#endif
|
||||
}
|
||||
|
||||
void IOWrite(IO_t io, bool hi)
|
||||
{
|
||||
if (!io) {
|
||||
return;
|
||||
}
|
||||
#if defined(USE_FULL_LL_DRIVER)
|
||||
LL_GPIO_SetOutputPin(IO_GPIO(io), IO_Pin(io) << (hi ? 0 : 16));
|
||||
#elif defined(USE_HAL_DRIVER)
|
||||
HAL_GPIO_WritePin(IO_GPIO(io), IO_Pin(io), hi ? GPIO_PIN_SET : GPIO_PIN_RESET);
|
||||
#elif defined(STM32F4)
|
||||
if (hi) {
|
||||
IO_GPIO(io)->BSRRL = IO_Pin(io);
|
||||
} else {
|
||||
IO_GPIO(io)->BSRRH = IO_Pin(io);
|
||||
}
|
||||
#elif defined(USE_ATBSP_DRIVER)
|
||||
IO_GPIO(io)->scr = IO_Pin(io) << (hi ? 0 : 16);
|
||||
#else
|
||||
IO_GPIO(io)->BSRR = IO_Pin(io) << (hi ? 0 : 16);
|
||||
#endif
|
||||
}
|
||||
|
||||
void IOHi(IO_t io)
|
||||
{
|
||||
if (!io) {
|
||||
return;
|
||||
}
|
||||
#if defined(USE_FULL_LL_DRIVER)
|
||||
LL_GPIO_SetOutputPin(IO_GPIO(io), IO_Pin(io));
|
||||
#elif defined(USE_HAL_DRIVER)
|
||||
HAL_GPIO_WritePin(IO_GPIO(io), IO_Pin(io), GPIO_PIN_SET);
|
||||
#elif defined(STM32F4)
|
||||
IO_GPIO(io)->BSRRL = IO_Pin(io);
|
||||
#elif defined(USE_ATBSP_DRIVER)
|
||||
IO_GPIO(io)->scr = IO_Pin(io);
|
||||
#else
|
||||
IO_GPIO(io)->BSRR = IO_Pin(io);
|
||||
#endif
|
||||
}
|
||||
|
||||
void IOLo(IO_t io)
|
||||
{
|
||||
if (!io) {
|
||||
return;
|
||||
}
|
||||
#if defined(USE_FULL_LL_DRIVER)
|
||||
LL_GPIO_ResetOutputPin(IO_GPIO(io), IO_Pin(io));
|
||||
#elif defined(USE_HAL_DRIVER)
|
||||
HAL_GPIO_WritePin(IO_GPIO(io), IO_Pin(io), GPIO_PIN_RESET);
|
||||
#elif defined(STM32F4)
|
||||
IO_GPIO(io)->BSRRH = IO_Pin(io);
|
||||
#elif defined(USE_ATBSP_DRIVER)
|
||||
IO_GPIO(io)->clr = IO_Pin(io);
|
||||
#else
|
||||
IO_GPIO(io)->BRR = IO_Pin(io);
|
||||
#endif
|
||||
}
|
||||
|
||||
void IOToggle(IO_t io)
|
||||
{
|
||||
if (!io) {
|
||||
return;
|
||||
}
|
||||
|
||||
uint32_t mask = IO_Pin(io);
|
||||
// Read pin state from ODR but write to BSRR because it only changes the pins
|
||||
// high in the mask value rather than all pins. XORing ODR directly risks
|
||||
// setting other pins incorrectly because it change all pins' state.
|
||||
#if defined(USE_FULL_LL_DRIVER)
|
||||
if (LL_GPIO_ReadOutputPort(IO_GPIO(io)) & mask) {
|
||||
mask <<= 16; // bit is set, shift mask to reset half
|
||||
}
|
||||
LL_GPIO_SetOutputPin(IO_GPIO(io), mask);
|
||||
#elif defined(USE_HAL_DRIVER)
|
||||
UNUSED(mask);
|
||||
HAL_GPIO_TogglePin(IO_GPIO(io), IO_Pin(io));
|
||||
#elif defined(STM32F4)
|
||||
if (IO_GPIO(io)->ODR & mask) {
|
||||
IO_GPIO(io)->BSRRH = mask;
|
||||
} else {
|
||||
IO_GPIO(io)->BSRRL = mask;
|
||||
}
|
||||
#elif defined(USE_ATBSP_DRIVER)
|
||||
if (IO_GPIO(io)->odt & mask) {
|
||||
mask <<= 16; // bit is set, shift mask to reset half
|
||||
}
|
||||
IO_GPIO(io)->scr = mask;
|
||||
#else
|
||||
if (IO_GPIO(io)->ODR & mask) {
|
||||
mask <<= 16; // bit is set, shift mask to reset half
|
||||
}
|
||||
IO_GPIO(io)->BSRR = mask;
|
||||
#endif
|
||||
}
|
||||
|
||||
// claim IO pin, set owner and resources
|
||||
void IOInit(IO_t io, resourceOwner_e owner, uint8_t index)
|
||||
{
|
||||
|
@ -310,146 +129,6 @@ bool IOIsFreeOrPreinit(IO_t io)
|
|||
return false;
|
||||
}
|
||||
|
||||
#if defined(STM32H7) || defined(STM32G4)
|
||||
|
||||
void IOConfigGPIO(IO_t io, ioConfig_t cfg)
|
||||
{
|
||||
IOConfigGPIOAF(io, cfg, 0);
|
||||
}
|
||||
|
||||
void IOConfigGPIOAF(IO_t io, ioConfig_t cfg, uint8_t af)
|
||||
{
|
||||
if (!io) {
|
||||
return;
|
||||
}
|
||||
|
||||
rccPeriphTag_t rcc = ioPortDefs[IO_GPIOPortIdx(io)].rcc;
|
||||
RCC_ClockCmd(rcc, ENABLE);
|
||||
|
||||
GPIO_InitTypeDef init = {
|
||||
.Pin = IO_Pin(io),
|
||||
.Mode = (cfg >> 0) & 0x13,
|
||||
.Speed = (cfg >> 2) & 0x03,
|
||||
.Pull = (cfg >> 5) & 0x03,
|
||||
.Alternate = af
|
||||
};
|
||||
|
||||
HAL_GPIO_Init(IO_GPIO(io), &init);
|
||||
}
|
||||
|
||||
#elif defined(STM32F7)
|
||||
|
||||
void IOConfigGPIO(IO_t io, ioConfig_t cfg)
|
||||
{
|
||||
IOConfigGPIOAF(io, cfg, 0);
|
||||
}
|
||||
|
||||
void IOConfigGPIOAF(IO_t io, ioConfig_t cfg, uint8_t af)
|
||||
{
|
||||
if (!io) {
|
||||
return;
|
||||
}
|
||||
|
||||
const rccPeriphTag_t rcc = ioPortDefs[IO_GPIOPortIdx(io)].rcc;
|
||||
RCC_ClockCmd(rcc, ENABLE);
|
||||
|
||||
LL_GPIO_InitTypeDef init = {
|
||||
.Pin = IO_Pin(io),
|
||||
.Mode = (cfg >> 0) & 0x03,
|
||||
.Speed = (cfg >> 2) & 0x03,
|
||||
.OutputType = (cfg >> 4) & 0x01,
|
||||
.Pull = (cfg >> 5) & 0x03,
|
||||
.Alternate = af
|
||||
};
|
||||
|
||||
LL_GPIO_Init(IO_GPIO(io), &init);
|
||||
}
|
||||
|
||||
#elif defined(STM32F4)
|
||||
|
||||
void IOConfigGPIO(IO_t io, ioConfig_t cfg)
|
||||
{
|
||||
if (!io) {
|
||||
return;
|
||||
}
|
||||
|
||||
const rccPeriphTag_t rcc = ioPortDefs[IO_GPIOPortIdx(io)].rcc;
|
||||
RCC_ClockCmd(rcc, ENABLE);
|
||||
|
||||
GPIO_InitTypeDef init = {
|
||||
.GPIO_Pin = IO_Pin(io),
|
||||
.GPIO_Mode = (cfg >> 0) & 0x03,
|
||||
.GPIO_Speed = (cfg >> 2) & 0x03,
|
||||
.GPIO_OType = (cfg >> 4) & 0x01,
|
||||
.GPIO_PuPd = (cfg >> 5) & 0x03,
|
||||
};
|
||||
GPIO_Init(IO_GPIO(io), &init);
|
||||
}
|
||||
|
||||
void IOConfigGPIOAF(IO_t io, ioConfig_t cfg, uint8_t af)
|
||||
{
|
||||
if (!io) {
|
||||
return;
|
||||
}
|
||||
|
||||
const rccPeriphTag_t rcc = ioPortDefs[IO_GPIOPortIdx(io)].rcc;
|
||||
RCC_ClockCmd(rcc, ENABLE);
|
||||
GPIO_PinAFConfig(IO_GPIO(io), IO_GPIO_PinSource(io), af);
|
||||
|
||||
GPIO_InitTypeDef init = {
|
||||
.GPIO_Pin = IO_Pin(io),
|
||||
.GPIO_Mode = (cfg >> 0) & 0x03,
|
||||
.GPIO_Speed = (cfg >> 2) & 0x03,
|
||||
.GPIO_OType = (cfg >> 4) & 0x01,
|
||||
.GPIO_PuPd = (cfg >> 5) & 0x03,
|
||||
};
|
||||
GPIO_Init(IO_GPIO(io), &init);
|
||||
}
|
||||
|
||||
#elif defined(AT32F4)
|
||||
|
||||
//TODO: move to specific files (applies to STM32 also)
|
||||
void IOConfigGPIO(IO_t io, ioConfig_t cfg)
|
||||
{
|
||||
if (!io) {
|
||||
return;
|
||||
}
|
||||
|
||||
const rccPeriphTag_t rcc = ioPortDefs[IO_GPIOPortIdx(io)].rcc;
|
||||
RCC_ClockCmd(rcc, ENABLE);
|
||||
|
||||
gpio_init_type init = {
|
||||
.gpio_pins = IO_Pin(io),
|
||||
.gpio_mode = (cfg >> 0) & 0x03,
|
||||
.gpio_drive_strength = (cfg >> 2) & 0x03,
|
||||
.gpio_out_type = (cfg >> 4) & 0x01,
|
||||
.gpio_pull = (cfg >> 5) & 0x03,
|
||||
};
|
||||
gpio_init(IO_GPIO(io), &init);
|
||||
}
|
||||
|
||||
void IOConfigGPIOAF(IO_t io, ioConfig_t cfg, uint8_t af)
|
||||
{
|
||||
if (!io) {
|
||||
return;
|
||||
}
|
||||
|
||||
const rccPeriphTag_t rcc = ioPortDefs[IO_GPIOPortIdx(io)].rcc;
|
||||
RCC_ClockCmd(rcc, ENABLE);
|
||||
|
||||
gpio_init_type init = {
|
||||
.gpio_pins = IO_Pin(io),
|
||||
.gpio_mode = (cfg >> 0) & 0x03,
|
||||
.gpio_drive_strength = (cfg >> 2) & 0x03,
|
||||
.gpio_out_type = (cfg >> 4) & 0x01,
|
||||
.gpio_pull = (cfg >> 5) & 0x03,
|
||||
};
|
||||
gpio_init(IO_GPIO(io), &init);
|
||||
gpio_pin_mux_config(IO_GPIO(io), IO_GPIO_PinSource(io), af);
|
||||
}
|
||||
|
||||
#endif
|
||||
|
||||
#if DEFIO_PORT_USED_COUNT > 0
|
||||
static const uint16_t ioDefUsedMask[DEFIO_PORT_USED_COUNT] = { DEFIO_PORT_USED_LIST };
|
||||
static const uint8_t ioDefUsedOffset[DEFIO_PORT_USED_COUNT] = { DEFIO_PORT_OFFSET_LIST };
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue