mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-25 17:25:20 +03:00
AT32 development, introduction of AT32F435 target (#12247)
* AT32F435: new target (#12159) * AT32F435: New target (WIP) * IO and Timer Updates * Adding pseudonyms for the STM TypeDef items. - implementation to follow * Adding config_streamer support for AT32 * Implementation for IO * Adding in Peripheral mapping from emsr. * Warnings cleanup for AT drivers * Getting things to the linking stage * Add AT-START-F435 LEDs as default in AT32F435 as a temporary measure to aid bringup * Remove tabs * Enable selection of serial port to use for MSP * Setup defaults for AT-START-F435 to use MSP on UART1 * Fix for most recent 4.5.0 Makefile changes * Solve for sanity check. * Add AT32F435 MCU type * Fix compilation issue with SITL * Merge conflict resolution * Minor cleanup * Adding line feed. --------- Co-authored-by: Steve Evans <Steve@SCEvans.com>
This commit is contained in:
parent
8900a831e5
commit
74be33dfbc
58 changed files with 6256 additions and 84 deletions
|
@ -72,6 +72,21 @@ const struct ioPortDef_s ioPortDefs[] = {
|
|||
{ 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)
|
||||
const struct ioPortDef_s ioPortDefs[] = { 0 };
|
||||
#else
|
||||
# error "IO PortDefs not defined for MCU"
|
||||
#endif
|
||||
|
||||
ioRec_t* IO_Rec(IO_t io)
|
||||
|
@ -135,7 +150,7 @@ uint32_t IO_EXTI_Line(IO_t io)
|
|||
if (!io) {
|
||||
return 0;
|
||||
}
|
||||
#if defined(STM32F4) || defined(STM32F7) || defined(STM32H7) || defined(STM32G4)
|
||||
#if defined(STM32F4) || defined(STM32F7) || defined(STM32H7) || defined(STM32G4) || defined(AT32F4)
|
||||
return 1 << IO_GPIOPinIdx(io);
|
||||
#elif defined(SIMULATOR_BUILD)
|
||||
return 0;
|
||||
|
@ -153,6 +168,8 @@ bool IORead(IO_t io)
|
|||
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
|
||||
|
@ -173,6 +190,8 @@ void IOWrite(IO_t io, bool hi)
|
|||
} 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
|
||||
|
@ -189,6 +208,8 @@ void IOHi(IO_t io)
|
|||
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
|
||||
|
@ -205,6 +226,8 @@ void IOLo(IO_t io)
|
|||
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
|
||||
|
@ -234,10 +257,15 @@ void IOToggle(IO_t io)
|
|||
} 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
|
||||
|
||||
if (IO_GPIO(io)->ODR & mask) {
|
||||
mask <<= 16; // bit is set, shift mask to reset half
|
||||
}
|
||||
IO_GPIO(io)->BSRR = mask;
|
||||
#endif
|
||||
}
|
||||
|
@ -377,6 +405,49 @@ void IOConfigGPIOAF(IO_t io, ioConfig_t cfg, uint8_t af)
|
|||
};
|
||||
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
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue