diff --git a/Makefile b/Makefile index e5a491659..9792f0122 100644 --- a/Makefile +++ b/Makefile @@ -17,16 +17,16 @@ # # The target to build, see VALID_TARGETS below -TARGET ?= NAZE +TARGET ?= NAZE # Compile-time options -OPTIONS ?= +OPTIONS ?= # compile for OpenPilot BootLoader support -OPBL ?=no +OPBL ?= no # Debugger optons, must be empty or GDB -DEBUG ?= +DEBUG ?= # Insert the debugging hardfault debugger # releases should not be built with this flag as it does not disable pwm output @@ -42,11 +42,11 @@ FLASH_SIZE ?= # Things that need to be maintained as the source changes # -FORKNAME = betaflight +FORKNAME = betaflight -CC3D_TARGETS = CC3D CC3D_OPBL +CC3D_TARGETS = CC3D CC3D_OPBL -VALID_TARGETS = NAZE NAZE32PRO OLIMEXINO STM32F3DISCOVERY CHEBUZZF3 $(CC3D_TARGETS) CJMCU EUSTM32F103RC SPRACINGF3 PORT103R SPARKY ALIENFLIGHTF1 ALIENFLIGHTF3 COLIBRI_RACE LUX_RACE MOTOLAB RMDO IRCFUSIONF3 AFROMINI SPRACINGF3MINI SPRACINGF3EVO DOGE SINGULARITY +VALID_TARGETS = NAZE NAZE32PRO OLIMEXINO STM32F3DISCOVERY CHEBUZZF3 $(CC3D_TARGETS) CJMCU EUSTM32F103RC SPRACINGF3 PORT103R SPARKY ALIENFLIGHTF1 ALIENFLIGHTF3 COLIBRI_RACE LUX_RACE MOTOLAB RMDO IRCFUSIONF3 AFROMINI SPRACINGF3MINI SPRACINGF3EVO DOGE SINGULARITY # Valid targets for OP VCP support VCP_VALID_TARGETS = $(CC3D_TARGETS) @@ -313,6 +313,9 @@ COMMON_SRC = build_config.c \ drivers/gyro_sync.c \ drivers/dma.c \ drivers/buf_writer.c \ + drivers/exti.c \ + drivers/io.c \ + drivers/rcc.c \ io/beeper.c \ io/rc_controls.c \ io/rc_curves.c \ @@ -913,7 +916,8 @@ $(TARGET_BIN): $(TARGET_ELF) $(OBJCOPY) -O binary $< $@ $(TARGET_ELF): $(TARGET_OBJS) - $(CC) -o $@ $^ $(LDFLAGS) + @echo LD $(notdir $@) + @$(CC) -o $@ $^ $(LDFLAGS) $(SIZE) $(TARGET_ELF) # Compile diff --git a/src/main/common/utils.h b/src/main/common/utils.h index ca1ec1042..db9e8c0c5 100644 --- a/src/main/common/utils.h +++ b/src/main/common/utils.h @@ -18,6 +18,7 @@ #pragma once #include +#include #define ARRAYLEN(x) (sizeof(x) / sizeof((x)[0])) @@ -27,6 +28,14 @@ #define STR_HELPER(x) #x #define STR(x) STR_HELPER(x) +#define EXPAND_I(x) x +#define EXPAND(x) EXPAND_I(x) + +#define UNUSED(x) (void)(x) +#define BUILD_BUG_ON(condition) ((void)sizeof(char[1 - 2*!!(condition)])) + +#define BIT(x) (1 << (x)) + /* http://resnet.uoregon.edu/~gurney_j/jmpc/bitwise.html */ @@ -35,6 +44,19 @@ http://resnet.uoregon.edu/~gurney_j/jmpc/bitwise.html #define UNUSED(x) (void)(x) +/* + * https://groups.google.com/forum/?hl=en#!msg/comp.lang.c/attFnqwhvGk/sGBKXvIkY3AJ + * Return (v ? floor(log2(v)) : 0) when 0 <= v < 1<<[8, 16, 32, 64]. + * Inefficient algorithm, intended for compile-time constants. + */ +#define LOG2_8BIT(v) (8 - 90/(((v)/4+14)|1) - 2/((v)/2+1)) +#define LOG2_16BIT(v) (8*((v)>255) + LOG2_8BIT((v) >>8*((v)>255))) +#define LOG2_32BIT(v) (16*((v)>65535L) + LOG2_16BIT((v)*1L >>16*((v)>65535L))) +#define LOG2_64BIT(v) \ + (32*((v)/2L>>31 > 0) \ + + LOG2_32BIT((v)*1L >>16*((v)/2L>>31 > 0) \ + >>16*((v)/2L>>31 > 0))) + #if 0 // ISO C version, but no type checking #define container_of(ptr, type, member) \ diff --git a/src/main/drivers/exti.c b/src/main/drivers/exti.c new file mode 100644 index 000000000..400cdf489 --- /dev/null +++ b/src/main/drivers/exti.c @@ -0,0 +1,176 @@ +#include +#include +#include + +#include "platform.h" + +#include "drivers/nvic.h" +#include "drivers/io_impl.h" + +#include "exti.h" + +#ifdef USE_EXTI + +typedef struct { + extiCallbackRec_t* handler; +} extiChannelRec_t; + +extiChannelRec_t extiChannelRecs[16]; + +// IRQ gouping, same on 103 and 303 +#define EXTI_IRQ_GROUPS 7 +// 0 1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 +static const uint8_t extiGroups[16] = { 0, 1, 2, 3, 4, 5, 5, 5, 5, 5, 6, 6, 6, 6, 6, 6 }; +static uint8_t extiGroupPriority[EXTI_IRQ_GROUPS]; + +#if defined(STM32F10X) +static const uint8_t extiGroupIRQn[EXTI_IRQ_GROUPS] = { + EXTI0_IRQn, EXTI1_IRQn, EXTI2_IRQn, EXTI3_IRQn, EXTI4_IRQn, + EXTI9_5_IRQn, EXTI15_10_IRQn +}; +#elif defined(STM32F303xC) +static const uint8_t extiGroupIRQn[EXTI_IRQ_GROUPS] = { + EXTI0_IRQn, EXTI1_IRQn, EXTI2_TS_IRQn, EXTI3_IRQn, EXTI4_IRQn, + EXTI9_5_IRQn, EXTI15_10_IRQn +}; +#else +# warning "Unknown CPU" +#endif + + + + +void EXTIInit(void) +{ + // TODO - stm32F303 + +#ifdef STM32F10X + // enable AFIO for EXTI support + RCC_APB2PeriphClockCmd(RCC_APB2Periph_AFIO, ENABLE); +#endif +#ifdef STM32F303xC + /* Enable SYSCFG clock otherwise the EXTI irq handlers are not called */ + RCC_APB2PeriphClockCmd(RCC_APB2Periph_SYSCFG, ENABLE); +#endif + memset(extiChannelRecs, 0, sizeof(extiChannelRecs)); + memset(extiGroupPriority, 0xff, sizeof(extiGroupPriority)); +} + +void EXTIHandlerInit(extiCallbackRec_t *self, extiHandlerCallback *fn) +{ + self->fn = fn; +} + +void EXTIConfig(IO_t io, extiCallbackRec_t *cb, int irqPriority, EXTITrigger_TypeDef trigger) +{ + int chIdx; + chIdx = IO_GPIOPinIdx(io); + if(chIdx < 0) + return; + extiChannelRec_t *rec = &extiChannelRecs[chIdx]; + int group = extiGroups[chIdx]; + + rec->handler = cb; +#if defined(STM32F10X) + GPIO_EXTILineConfig(IO_GPIO_PortSource(io), IO_GPIO_PinSource(io)); +#elif defined(STM32F303xC) + SYSCFG_EXTILineConfig(IO_EXTI_PortSourceGPIO(io), IO_EXTI_PinSource(io)); +#else +# warning "Unknown CPU" +#endif + uint32_t extiLine = IO_EXTI_Line(io); + + EXTI_ClearITPendingBit(extiLine); + + EXTI_InitTypeDef EXTIInit; + EXTIInit.EXTI_Line = extiLine; + EXTIInit.EXTI_Mode = EXTI_Mode_Interrupt; + EXTIInit.EXTI_Trigger = trigger; + EXTIInit.EXTI_LineCmd = ENABLE; + EXTI_Init(&EXTIInit); + + if(extiGroupPriority[group] > irqPriority) { + extiGroupPriority[group] = irqPriority; + + NVIC_InitTypeDef NVIC_InitStructure; + NVIC_InitStructure.NVIC_IRQChannel = extiGroupIRQn[group]; + NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = NVIC_PRIORITY_BASE(irqPriority); + NVIC_InitStructure.NVIC_IRQChannelSubPriority = NVIC_PRIORITY_SUB(irqPriority); + NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE; + NVIC_Init(&NVIC_InitStructure); + } +} + +void EXTIRelease(IO_t io) +{ + // don't forget to match cleanup with config + EXTIEnable(io, false); + + int chIdx; + chIdx = IO_GPIOPinIdx(io); + if(chIdx < 0) + return; + extiChannelRec_t *rec = &extiChannelRecs[chIdx]; + rec->handler = NULL; +} + +void EXTIEnable(IO_t io, bool enable) +{ +#if defined(STM32F10X) + uint32_t extiLine = IO_EXTI_Line(io); + if(!extiLine) + return; + if(enable) + EXTI->IMR |= extiLine; + else + EXTI->IMR &= ~extiLine; +#elif defined(STM32F303xC) + int extiLine = IO_EXTI_Line(io); + if(extiLine < 0) + return; + // assume extiLine < 32 (valid for all EXTI pins) + if(enable) + EXTI->IMR |= 1 << extiLine; + else + EXTI->IMR &= ~(1 << extiLine); +#else +# error "Unsupported target" +#endif +} + +void EXTI_IRQHandler(void) +{ + uint32_t exti_active = EXTI->IMR & EXTI->PR; + + while(exti_active) { + unsigned idx = 31 - __builtin_clz(exti_active); + uint32_t mask = 1 << idx; + extiChannelRecs[idx].handler->fn(extiChannelRecs[idx].handler); + EXTI->PR = mask; // clear pending mask (by writing 1) + exti_active &= ~mask; + } +} + +#define _EXTI_IRQ_HANDLER(name) \ + void name(void) { \ + EXTI_IRQHandler(); \ + } \ + struct dummy \ + /**/ + + +_EXTI_IRQ_HANDLER(EXTI0_IRQHandler); +_EXTI_IRQ_HANDLER(EXTI1_IRQHandler); +#if defined(STM32F10X) +_EXTI_IRQ_HANDLER(EXTI2_IRQHandler); +#elif defined(STM32F303xC) +_EXTI_IRQ_HANDLER(EXTI2_TS_IRQHandler); +#else +# warning "Unknown CPU" +#endif +_EXTI_IRQ_HANDLER(EXTI3_IRQHandler); +_EXTI_IRQ_HANDLER(EXTI4_IRQHandler); +_EXTI_IRQ_HANDLER(EXTI9_5_IRQHandler); +_EXTI_IRQ_HANDLER(EXTI15_10_IRQHandler); + +#endif diff --git a/src/main/drivers/exti.h b/src/main/drivers/exti.h index 4e48d9052..c3293f97a 100644 --- a/src/main/drivers/exti.h +++ b/src/main/drivers/exti.h @@ -18,18 +18,35 @@ #pragma once +// old EXTI interface, to be replaced typedef struct extiConfig_s { #ifdef STM32F303 - uint32_t gpioAHBPeripherals; + uint32_t gpioAHBPeripherals; #endif #ifdef STM32F10X - uint32_t gpioAPB2Peripherals; + uint32_t gpioAPB2Peripherals; #endif - uint16_t gpioPin; - GPIO_TypeDef *gpioPort; + uint16_t gpioPin; + GPIO_TypeDef *gpioPort; - uint8_t exti_port_source; - uint32_t exti_line; - uint8_t exti_pin_source; - IRQn_Type exti_irqn; + uint8_t exti_port_source; + uint32_t exti_line; + uint8_t exti_pin_source; + IRQn_Type exti_irqn; } extiConfig_t; + +// new io EXTI interface +#include "drivers/io.h" +typedef struct extiCallbackRec_s extiCallbackRec_t; +typedef void extiHandlerCallback(extiCallbackRec_t *self); + +struct extiCallbackRec_s { + extiHandlerCallback *fn; +}; + +void EXTIInit(void); + +void EXTIHandlerInit(extiCallbackRec_t *cb, extiHandlerCallback *fn); +void EXTIConfig(IO_t io, extiCallbackRec_t *cb, int irqPriority, EXTITrigger_TypeDef trigger); +void EXTIRelease(IO_t io); +void EXTIEnable(IO_t io, bool enable); diff --git a/src/main/drivers/gpio.h b/src/main/drivers/gpio.h index dd08eb4ac..b734de647 100644 --- a/src/main/drivers/gpio.h +++ b/src/main/drivers/gpio.h @@ -17,6 +17,8 @@ #pragma once +#include "platform.h" + #if defined(STM32F10X) typedef enum { @@ -40,20 +42,20 @@ typedef enum GPIO_Mode_OUT = 0x01, // GPIO Output Mode GPIO_Mode_AF = 0x02, // GPIO Alternate function Mode GPIO_Mode_AN = 0x03 // GPIO Analog In/Out Mode -}GPIOMode_TypeDef; +} GPIOMode_TypeDef; typedef enum { GPIO_OType_PP = 0x00, GPIO_OType_OD = 0x01 -}GPIOOType_TypeDef; +} GPIOOType_TypeDef; typedef enum { GPIO_PuPd_NOPULL = 0x00, GPIO_PuPd_UP = 0x01, GPIO_PuPd_DOWN = 0x02 -}GPIOPuPd_TypeDef; +} GPIOPuPd_TypeDef; */ typedef enum diff --git a/src/main/drivers/io.c b/src/main/drivers/io.c new file mode 100644 index 000000000..31cf8ada7 --- /dev/null +++ b/src/main/drivers/io.c @@ -0,0 +1,271 @@ + +#include "common/utils.h" + +#include "drivers/io.h" +#include "drivers/io_impl.h" +#include "drivers/rcc.h" + +#include "target.h" + +// io ports defs are stored in array by index now +struct ioPortDef_s { + rccPeriphTag_t rcc; +}; + +#if defined(STM32F10X) +const struct ioPortDef_s ioPortDefs[] = { + {RCC_APB2(IOPA)}, + {RCC_APB2(IOPB)}, + {RCC_APB2(IOPC)}, + {RCC_APB2(IOPD)}, + {RCC_APB2(IOPE)}, + { +#if defined (STM32F10X_HD) || defined (STM32F10X_XL) || defined (STM32F10X_HD_VL) + RCC_APB2(IOPF), +#else + 0, +#endif + }, + { +#if defined (STM32F10X_HD) || defined (STM32F10X_XL) || defined (STM32F10X_HD_VL) + RCC_APB2(IOPG), +#else + 0, +#endif + }, +}; +#elif defined(STM32F303xC) +const struct ioPortDef_s ioPortDefs[] = { + {RCC_AHB(GPIOA)}, + {RCC_AHB(GPIOB)}, + {RCC_AHB(GPIOC)}, + {RCC_AHB(GPIOD)}, + {RCC_AHB(GPIOE)}, + {RCC_AHB(GPIOF)}, +}; +#endif + +ioRec_t* IO_Rec(IO_t io) +{ + return io; +} + +GPIO_TypeDef* IO_GPIO(IO_t io) +{ + ioRec_t *ioRec = IO_Rec(io); + return ioRec->gpio; +} + +uint16_t IO_Pin(IO_t io) +{ + ioRec_t *ioRec = IO_Rec(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 +} + +int IO_EXTI_PortSourceGPIO(IO_t io) +{ + return IO_GPIOPortIdx(io); +} + +int IO_GPIO_PortSource(IO_t io) +{ + return IO_GPIOPortIdx(io); +} + +// zero based pin index +int IO_GPIOPinIdx(IO_t io) +{ + if(!io) + return -1; + return 31 - __builtin_clz(IO_Pin(io)); // CLZ is a bit faster than FFS +} + +int IO_EXTI_PinSource(IO_t io) +{ + return IO_GPIOPinIdx(io); +} + +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(STM32F10X) + return 1 << IO_GPIOPinIdx(io); +#elif defined(STM32F303xC) + return IO_GPIOPinIdx(io); +#else +# error "Unknown target type" +#endif +} + +bool IORead(IO_t io) +{ + if(!io) + return false; + return !!(IO_GPIO(io)->IDR & IO_Pin(io)); +} + +void IOWrite(IO_t io, bool hi) +{ + if(!io) + return; + IO_GPIO(io)->BSRR = IO_Pin(io) << (hi ? 0 : 16); +} + +void IOHi(IO_t io) +{ + if(!io) + return; + IO_GPIO(io)->BSRR = IO_Pin(io); +} + +void IOLo(IO_t io) +{ + if(!io) + return; + IO_GPIO(io)->BRR = IO_Pin(io); +} + +void IOToggle(IO_t io) +{ + if(!io) + return; + // check pin state and use BSRR accordinly to avoid race condition + uint16_t mask = IO_Pin(io); + if(IO_GPIO(io)->ODR & mask) + mask <<= 16; // bit is set, shift mask to reset half + IO_GPIO(io)->BSRR = mask; +} + +// claim IO pin, set owner and resources +void IOInit(IO_t io, resourceOwner_t owner, resourceType_t resources) +{ + ioRec_t *ioRec = IO_Rec(io); + if(owner != OWNER_FREE) // pass OWNER_FREE to keep old owner + ioRec->owner = owner; + ioRec->resourcesUsed |= resources; +} + +void IORelease(IO_t io) +{ + ioRec_t *ioRec = IO_Rec(io); + ioRec->owner = OWNER_FREE; +} + +resourceOwner_t IOGetOwner(IO_t io) +{ + ioRec_t *ioRec = IO_Rec(io); + return ioRec->owner; +} + +resourceType_t IOGetResources(IO_t io) +{ + ioRec_t *ioRec = IO_Rec(io); + return ioRec->resourcesUsed; +} + +#if defined(STM32F10X) + +void IOConfigGPIO(IO_t io, ioConfig_t cfg) +{ + if(!io) + return; + rccPeriphTag_t rcc = ioPortDefs[IO_GPIOPortIdx(io)].rcc; + RCC_ClockCmd(rcc, ENABLE); + + GPIO_InitTypeDef init = { + .GPIO_Pin = IO_Pin(io), + .GPIO_Speed = cfg & 0x03, + .GPIO_Mode = cfg & 0x7c, + }; + GPIO_Init(IO_GPIO(io), &init); +} + + +#elif defined(STM32F303xC) + +void IOConfigGPIO(IO_t io, ioConfig_t cfg) +{ + if(!io) + return; + 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; + + 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); +} +#endif + +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}; +ioRec_t ioRecs[DEFIO_IO_USED_COUNT]; + +// initialize all ioRec_t structures from ROM +// currently only bitmask is used, this may change in future +void IOInitGlobal(void) { + ioRec_t *ioRec = ioRecs; + + for(unsigned port = 0; port < ARRAYLEN(ioDefUsedMask); port++) + for(unsigned pin = 0; pin < sizeof(ioDefUsedMask[0]) * 8; pin++) + if(ioDefUsedMask[port] & (1 << pin)) { + ioRec->gpio = (GPIO_TypeDef *)(GPIOA_BASE + (port << 10)); // ports are 0x400 apart + ioRec->pin = 1 << pin; + ioRec++; + } +} + +IO_t IOGetByTag(ioTag_t tag) +{ + int portIdx = DEFIO_TAG_GPIOID(tag); + int pinIdx = DEFIO_TAG_PIN(tag); + + if(portIdx >= DEFIO_PORT_USED_COUNT) + return NULL; + // check if pin exists + if(!(ioDefUsedMask[portIdx] & (1 << pinIdx))) + return NULL; + // count bits before this pin on single port + int offset = __builtin_popcount(((1 << pinIdx)-1) & ioDefUsedMask[portIdx]); + // and add port offset + offset += ioDefUsedOffset[portIdx]; + return ioRecs + offset; +} diff --git a/src/main/drivers/io.h b/src/main/drivers/io.h new file mode 100644 index 000000000..5b3c49583 --- /dev/null +++ b/src/main/drivers/io.h @@ -0,0 +1,95 @@ +#pragma once + +#include + +#include "drivers/gpio.h" +#include "drivers/resource.h" + +// IO pin identification +// make sure that ioTag_t can't be assigned into IO_t without warning +typedef uint8_t ioTag_t; // packet tag to specify IO pin +typedef void* IO_t; // type specifying IO pin. Currently ioRec_t pointer, but this may change + +// preprocessor is used to convert pinid to requested C data value +// compile-time error is generated if requested pin is not available (not set in TARGET_IO_PORTx) +// ioTag_t and IO_t is supported, but ioTag_t is preferred + +// expand pinid to ioTag_t, generate compilation error if pin is not supported +#define IO_TAG(pinid) DEFIO_TAG(pinid) +// expand pinid to ioTag_t, expand to NONE if pin is not supported +#define IO_TAG_E(pinid) DEFIO_TAG_E(pinid) + +// both ioTag_t and IO_t are guarantied to be zero if pinid is NONE (no pin) +// this simplifies initialization (globals are zeroed on start) and allows +// omitting unused fields in structure initializers. +// it is also possible to use IO_t and ioTag_t as boolean value +// TODO - this may conflict with requirement to generate warning/error on IO_t - ioTag_t assignment +// IO_t being pointer is only possibility I know of .. + +// pin config handling +// pin config is packed into ioConfig_t to decrease memory requirements +// IOCFG_x macros are defined for common combinations for all CPUs; this +// helps masking CPU differences + +typedef uint8_t ioConfig_t; // packed IO configuration +#if defined(STM32F10X) + +// mode is using only bits 6-2 +# define IO_CONFIG(mode, speed) ((mode) | (speed)) + +# define IOCFG_OUT_PP IO_CONFIG(GPIO_Mode_Out_PP, GPIO_Speed_2MHz) +# define IOCFG_OUT_OD IO_CONFIG(GPIO_Mode_Out_OD, GPIO_Speed_2MHz) +# define IOCFG_AF_PP IO_CONFIG(GPIO_Mode_AF_PP, GPIO_Speed_2MHz) +# define IOCFG_AF_OD IO_CONFIG(GPIO_Mode_AF_OD, GPIO_Speed_2MHz) +# define IOCFG_IPD IO_CONFIG(GPIO_Mode_IPD, GPIO_Speed_2MHz) +# define IOCFG_IPU IO_CONFIG(GPIO_Mode_IPU, GPIO_Speed_2MHz) +# define IOCFG_IN_FLOATING IO_CONFIG(GPIO_Mode_IN_FLOATING, GPIO_Speed_2MHz) +# define IOCFG_ANALOG IO_CONFIG(GPIO_Mode_AIN, GPIO_Speed_2MHz) +#elif defined(STM32F303xC) + +# define IO_CONFIG(mode, speed, otype, pupd) ((mode) | ((speed) << 2) | ((otype) << 4) | ((pupd) << 5)) + +# define IOCFG_OUT_PP IO_CONFIG(GPIO_Mode_OUT, 0, GPIO_OType_PP, GPIO_PuPd_NOPULL) // TODO +# define IOCFG_OUT_OD IO_CONFIG(GPIO_Mode_OUT, 0, GPIO_OType_OD, GPIO_PuPd_NOPULL) +# define IOCFG_AF_PP IO_CONFIG(GPIO_Mode_AF, 0, GPIO_OType_PP, GPIO_PuPd_NOPULL) +# define IOCFG_AF_OD IO_CONFIG(GPIO_Mode_AF, 0, GPIO_OType_OD, GPIO_PuPd_NOPULL) +# define IOCFG_IPD IO_CONFIG(GPIO_Mode_IN, 0, 0, GPIO_PuPd_DOWN) +# define IOCFG_IPU IO_CONFIG(GPIO_Mode_IN, 0, 0, GPIO_PuPd_UP) +# define IOCFG_IN_FLOATING IO_CONFIG(GPIO_Mode_IN, 0, 0, GPIO_PuPd_NOPULL) +# define IOCFG_ANALOG IO_CONFIG(GPIO_Mode_AN, 0, 0, GPIO_PuPd_NOPULL) + +#elif defined(UNIT_TEST) + +# define IOCFG_OUT_PP 0 +# define IOCFG_OUT_OD 0 +# define IOCFG_AF_PP 0 +# define IOCFG_AF_OD 0 +# define IOCFG_IPD 0 +# define IOCFG_IPU 0 +# define IOCFG_IN_FLOATING 0 + +#else +# warning "Unknown TARGET" +#endif + +// declare available IO pins. Available pins are specified per target +#include "io_def.h" + +bool IORead(IO_t io); +void IOWrite(IO_t io, bool value); +void IOHi(IO_t io); +void IOLo(IO_t io); +void IOToggle(IO_t io); + +void IOInit(IO_t io, resourceOwner_t owner, resourceType_t resources); +void IORelease(IO_t io); // unimplemented +resourceOwner_t IOGetOwner(IO_t io); +resourceType_t IOGetResources(IO_t io); +IO_t IOGetByTag(ioTag_t tag); + +void IOConfigGPIO(IO_t io, ioConfig_t cfg); +#if defined(STM32F303xC) +void IOConfigGPIOAF(IO_t io, ioConfig_t cfg, uint8_t af); +#endif + +void IOInitGlobal(void); diff --git a/src/main/drivers/io_def.h b/src/main/drivers/io_def.h new file mode 100644 index 000000000..7600054ec --- /dev/null +++ b/src/main/drivers/io_def.h @@ -0,0 +1,35 @@ +#pragma once + +#include "common/utils.h" + +// return ioTag_t for given pinid +// tag for NONE must be false +#define DEFIO_TAG(pinid) CONCAT(DEFIO_TAG__, pinid) +#define DEFIO_TAG__NONE 0 +#define DEFIO_TAG_E(pinid) CONCAT(DEFIO_TAG_E__, pinid) +#define DEFIO_TAG_E__NONE 0 + + +// return ioRec_t or NULL for given pinid +// tags should be preferred, possibly removing it in future +// io_impl.h must be included when this macro is used +#define DEFIO_REC(pinid) CONCAT(DEFIO_REC__, pinid) +#define DEFIO_REC__NONE NULL + +#define DEFIO_IO(pinid) (IO_t)DEFIO_REC(pinid) +// TODO - macro to check for pinid NONE (fully in preprocessor) + +// get ioRec by index +#define DEFIO_REC_INDEXED(idx) (ioRecs + (idx)) + +// ioTag_t accessor macros +#define DEFIO_TAG_MAKE(gpioid, pin) ((((gpioid) + 1) << 4) | (pin)) +#define DEFIO_TAG_ISEMPTY(tag) (!(tag)) +#define DEFIO_TAG_GPIOID(tag) (((tag) >> 4) - 1) +#define DEFIO_TAG_PIN(tag) ((tag) & 0x0f) + +// TARGET must define used pins +#include "target.h" +// include template-generated macros for IO pins +#include "io_def_generated.h" + diff --git a/src/main/drivers/io_def_generated.h b/src/main/drivers/io_def_generated.h new file mode 100644 index 000000000..a1f0fc311 --- /dev/null +++ b/src/main/drivers/io_def_generated.h @@ -0,0 +1,1142 @@ +#pragma once +// this file is automatically generated by def_generated.pl script +// do not modify this file directly, your changes will be lost + +// DEFIO_PORT__USED_MASK is bitmask of used pins on target +// DEFIO_PORT__USED_COUNT is count of used pins on target + +#if defined(TARGET_IO_PORTA) +# define DEFIO_PORT_A_USED_MASK TARGET_IO_PORTA +# define DEFIO_PORT_A_USED_COUNT BITCOUNT(DEFIO_PORT_A_USED_MASK) +#else +# define DEFIO_PORT_A_USED_MASK 0 +# define DEFIO_PORT_A_USED_COUNT 0 +#endif +#define DEFIO_PORT_A_OFFSET (0) + +#if defined(TARGET_IO_PORTB) +# define DEFIO_PORT_B_USED_MASK TARGET_IO_PORTB +# define DEFIO_PORT_B_USED_COUNT BITCOUNT(DEFIO_PORT_B_USED_MASK) +#else +# define DEFIO_PORT_B_USED_MASK 0 +# define DEFIO_PORT_B_USED_COUNT 0 +#endif +#define DEFIO_PORT_B_OFFSET (DEFIO_PORT_A_USED_COUNT) + +#if defined(TARGET_IO_PORTC) +# define DEFIO_PORT_C_USED_MASK TARGET_IO_PORTC +# define DEFIO_PORT_C_USED_COUNT BITCOUNT(DEFIO_PORT_C_USED_MASK) +#else +# define DEFIO_PORT_C_USED_MASK 0 +# define DEFIO_PORT_C_USED_COUNT 0 +#endif +#define DEFIO_PORT_C_OFFSET (DEFIO_PORT_A_USED_COUNT+DEFIO_PORT_B_USED_COUNT) + +#if defined(TARGET_IO_PORTD) +# define DEFIO_PORT_D_USED_MASK TARGET_IO_PORTD +# define DEFIO_PORT_D_USED_COUNT BITCOUNT(DEFIO_PORT_D_USED_MASK) +#else +# define DEFIO_PORT_D_USED_MASK 0 +# define DEFIO_PORT_D_USED_COUNT 0 +#endif +#define DEFIO_PORT_D_OFFSET (DEFIO_PORT_A_USED_COUNT+DEFIO_PORT_B_USED_COUNT+DEFIO_PORT_C_USED_COUNT) + +#if defined(TARGET_IO_PORTE) +# define DEFIO_PORT_E_USED_MASK TARGET_IO_PORTE +# define DEFIO_PORT_E_USED_COUNT BITCOUNT(DEFIO_PORT_E_USED_MASK) +#else +# define DEFIO_PORT_E_USED_MASK 0 +# define DEFIO_PORT_E_USED_COUNT 0 +#endif +#define DEFIO_PORT_E_OFFSET (DEFIO_PORT_A_USED_COUNT+DEFIO_PORT_B_USED_COUNT+DEFIO_PORT_C_USED_COUNT+DEFIO_PORT_D_USED_COUNT) + +#if defined(TARGET_IO_PORTF) +# define DEFIO_PORT_F_USED_MASK TARGET_IO_PORTF +# define DEFIO_PORT_F_USED_COUNT BITCOUNT(DEFIO_PORT_F_USED_MASK) +#else +# define DEFIO_PORT_F_USED_MASK 0 +# define DEFIO_PORT_F_USED_COUNT 0 +#endif +#define DEFIO_PORT_F_OFFSET (DEFIO_PORT_A_USED_COUNT+DEFIO_PORT_B_USED_COUNT+DEFIO_PORT_C_USED_COUNT+DEFIO_PORT_D_USED_COUNT+DEFIO_PORT_E_USED_COUNT) + +#if defined(TARGET_IO_PORTG) +# define DEFIO_PORT_G_USED_MASK TARGET_IO_PORTG +# define DEFIO_PORT_G_USED_COUNT BITCOUNT(DEFIO_PORT_G_USED_MASK) +#else +# define DEFIO_PORT_G_USED_MASK 0 +# define DEFIO_PORT_G_USED_COUNT 0 +#endif +#define DEFIO_PORT_G_OFFSET (DEFIO_PORT_A_USED_COUNT+DEFIO_PORT_B_USED_COUNT+DEFIO_PORT_C_USED_COUNT+DEFIO_PORT_D_USED_COUNT+DEFIO_PORT_E_USED_COUNT+DEFIO_PORT_F_USED_COUNT) + + + +// DEFIO_GPIOID__ maps to port index +#define DEFIO_GPIOID__A 0 +#define DEFIO_GPIOID__B 1 +#define DEFIO_GPIOID__C 2 +#define DEFIO_GPIOID__D 3 +#define DEFIO_GPIOID__E 4 +#define DEFIO_GPIOID__F 5 +#define DEFIO_GPIOID__G 6 + +// DEFIO_TAG__P will expand to TAG if defined for target +// DEFIO_REC__P will expand to ioRec* (using DEFIO_REC_INDEX(idx)) + +#if DEFIO_PORT_A_USED_MASK & BIT(0) +# define DEFIO_TAG__PA0 DEFIO_TAG_MAKE(DEFIO_GPIOID__A, 0) +# define DEFIO_TAG_E__PA0 DEFIO_TAG_MAKE(DEFIO_GPIOID__A, 0) +# define DEFIO_REC__PA0 DEFIO_REC_INDEXED(BITCOUNT(DEFIO_PORT_A_USED_MASK & (BIT(0) - 1)) + 0) +#else +# define DEFIO_TAG__PA0 defio_error_PA0_is_not_supported_on_TARGET +# define DEFIO_TAG_E__PA0 DEFIO_TAG_E__NONE +# define DEFIO_REC__PA0 defio_error_PA0_is_not_supported_on_TARGET +#endif +#if DEFIO_PORT_A_USED_MASK & BIT(1) +# define DEFIO_TAG__PA1 DEFIO_TAG_MAKE(DEFIO_GPIOID__A, 1) +# define DEFIO_TAG_E__PA1 DEFIO_TAG_MAKE(DEFIO_GPIOID__A, 1) +# define DEFIO_REC__PA1 DEFIO_REC_INDEXED(BITCOUNT(DEFIO_PORT_A_USED_MASK & (BIT(1) - 1)) + 0) +#else +# define DEFIO_TAG__PA1 defio_error_PA1_is_not_supported_on_TARGET +# define DEFIO_TAG_E__PA1 DEFIO_TAG_E__NONE +# define DEFIO_REC__PA1 defio_error_PA1_is_not_supported_on_TARGET +#endif +#if DEFIO_PORT_A_USED_MASK & BIT(2) +# define DEFIO_TAG__PA2 DEFIO_TAG_MAKE(DEFIO_GPIOID__A, 2) +# define DEFIO_TAG_E__PA2 DEFIO_TAG_MAKE(DEFIO_GPIOID__A, 2) +# define DEFIO_REC__PA2 DEFIO_REC_INDEXED(BITCOUNT(DEFIO_PORT_A_USED_MASK & (BIT(2) - 1)) + 0) +#else +# define DEFIO_TAG__PA2 defio_error_PA2_is_not_supported_on_TARGET +# define DEFIO_TAG_E__PA2 DEFIO_TAG_E__NONE +# define DEFIO_REC__PA2 defio_error_PA2_is_not_supported_on_TARGET +#endif +#if DEFIO_PORT_A_USED_MASK & BIT(3) +# define DEFIO_TAG__PA3 DEFIO_TAG_MAKE(DEFIO_GPIOID__A, 3) +# define DEFIO_TAG_E__PA3 DEFIO_TAG_MAKE(DEFIO_GPIOID__A, 3) +# define DEFIO_REC__PA3 DEFIO_REC_INDEXED(BITCOUNT(DEFIO_PORT_A_USED_MASK & (BIT(3) - 1)) + 0) +#else +# define DEFIO_TAG__PA3 defio_error_PA3_is_not_supported_on_TARGET +# define DEFIO_TAG_E__PA3 DEFIO_TAG_E__NONE +# define DEFIO_REC__PA3 defio_error_PA3_is_not_supported_on_TARGET +#endif +#if DEFIO_PORT_A_USED_MASK & BIT(4) +# define DEFIO_TAG__PA4 DEFIO_TAG_MAKE(DEFIO_GPIOID__A, 4) +# define DEFIO_TAG_E__PA4 DEFIO_TAG_MAKE(DEFIO_GPIOID__A, 4) +# define DEFIO_REC__PA4 DEFIO_REC_INDEXED(BITCOUNT(DEFIO_PORT_A_USED_MASK & (BIT(4) - 1)) + 0) +#else +# define DEFIO_TAG__PA4 defio_error_PA4_is_not_supported_on_TARGET +# define DEFIO_TAG_E__PA4 DEFIO_TAG_E__NONE +# define DEFIO_REC__PA4 defio_error_PA4_is_not_supported_on_TARGET +#endif +#if DEFIO_PORT_A_USED_MASK & BIT(5) +# define DEFIO_TAG__PA5 DEFIO_TAG_MAKE(DEFIO_GPIOID__A, 5) +# define DEFIO_TAG_E__PA5 DEFIO_TAG_MAKE(DEFIO_GPIOID__A, 5) +# define DEFIO_REC__PA5 DEFIO_REC_INDEXED(BITCOUNT(DEFIO_PORT_A_USED_MASK & (BIT(5) - 1)) + 0) +#else +# define DEFIO_TAG__PA5 defio_error_PA5_is_not_supported_on_TARGET +# define DEFIO_TAG_E__PA5 DEFIO_TAG_E__NONE +# define DEFIO_REC__PA5 defio_error_PA5_is_not_supported_on_TARGET +#endif +#if DEFIO_PORT_A_USED_MASK & BIT(6) +# define DEFIO_TAG__PA6 DEFIO_TAG_MAKE(DEFIO_GPIOID__A, 6) +# define DEFIO_TAG_E__PA6 DEFIO_TAG_MAKE(DEFIO_GPIOID__A, 6) +# define DEFIO_REC__PA6 DEFIO_REC_INDEXED(BITCOUNT(DEFIO_PORT_A_USED_MASK & (BIT(6) - 1)) + 0) +#else +# define DEFIO_TAG__PA6 defio_error_PA6_is_not_supported_on_TARGET +# define DEFIO_TAG_E__PA6 DEFIO_TAG_E__NONE +# define DEFIO_REC__PA6 defio_error_PA6_is_not_supported_on_TARGET +#endif +#if DEFIO_PORT_A_USED_MASK & BIT(7) +# define DEFIO_TAG__PA7 DEFIO_TAG_MAKE(DEFIO_GPIOID__A, 7) +# define DEFIO_TAG_E__PA7 DEFIO_TAG_MAKE(DEFIO_GPIOID__A, 7) +# define DEFIO_REC__PA7 DEFIO_REC_INDEXED(BITCOUNT(DEFIO_PORT_A_USED_MASK & (BIT(7) - 1)) + 0) +#else +# define DEFIO_TAG__PA7 defio_error_PA7_is_not_supported_on_TARGET +# define DEFIO_TAG_E__PA7 DEFIO_TAG_E__NONE +# define DEFIO_REC__PA7 defio_error_PA7_is_not_supported_on_TARGET +#endif +#if DEFIO_PORT_A_USED_MASK & BIT(8) +# define DEFIO_TAG__PA8 DEFIO_TAG_MAKE(DEFIO_GPIOID__A, 8) +# define DEFIO_TAG_E__PA8 DEFIO_TAG_MAKE(DEFIO_GPIOID__A, 8) +# define DEFIO_REC__PA8 DEFIO_REC_INDEXED(BITCOUNT(DEFIO_PORT_A_USED_MASK & (BIT(8) - 1)) + 0) +#else +# define DEFIO_TAG__PA8 defio_error_PA8_is_not_supported_on_TARGET +# define DEFIO_TAG_E__PA8 DEFIO_TAG_E__NONE +# define DEFIO_REC__PA8 defio_error_PA8_is_not_supported_on_TARGET +#endif +#if DEFIO_PORT_A_USED_MASK & BIT(9) +# define DEFIO_TAG__PA9 DEFIO_TAG_MAKE(DEFIO_GPIOID__A, 9) +# define DEFIO_TAG_E__PA9 DEFIO_TAG_MAKE(DEFIO_GPIOID__A, 9) +# define DEFIO_REC__PA9 DEFIO_REC_INDEXED(BITCOUNT(DEFIO_PORT_A_USED_MASK & (BIT(9) - 1)) + 0) +#else +# define DEFIO_TAG__PA9 defio_error_PA9_is_not_supported_on_TARGET +# define DEFIO_TAG_E__PA9 DEFIO_TAG_E__NONE +# define DEFIO_REC__PA9 defio_error_PA9_is_not_supported_on_TARGET +#endif +#if DEFIO_PORT_A_USED_MASK & BIT(10) +# define DEFIO_TAG__PA10 DEFIO_TAG_MAKE(DEFIO_GPIOID__A, 10) +# define DEFIO_TAG_E__PA10 DEFIO_TAG_MAKE(DEFIO_GPIOID__A, 10) +# define DEFIO_REC__PA10 DEFIO_REC_INDEXED(BITCOUNT(DEFIO_PORT_A_USED_MASK & (BIT(10) - 1)) + 0) +#else +# define DEFIO_TAG__PA10 defio_error_PA10_is_not_supported_on_TARGET +# define DEFIO_TAG_E__PA10 DEFIO_TAG_E__NONE +# define DEFIO_REC__PA10 defio_error_PA10_is_not_supported_on_TARGET +#endif +#if DEFIO_PORT_A_USED_MASK & BIT(11) +# define DEFIO_TAG__PA11 DEFIO_TAG_MAKE(DEFIO_GPIOID__A, 11) +# define DEFIO_TAG_E__PA11 DEFIO_TAG_MAKE(DEFIO_GPIOID__A, 11) +# define DEFIO_REC__PA11 DEFIO_REC_INDEXED(BITCOUNT(DEFIO_PORT_A_USED_MASK & (BIT(11) - 1)) + 0) +#else +# define DEFIO_TAG__PA11 defio_error_PA11_is_not_supported_on_TARGET +# define DEFIO_TAG_E__PA11 DEFIO_TAG_E__NONE +# define DEFIO_REC__PA11 defio_error_PA11_is_not_supported_on_TARGET +#endif +#if DEFIO_PORT_A_USED_MASK & BIT(12) +# define DEFIO_TAG__PA12 DEFIO_TAG_MAKE(DEFIO_GPIOID__A, 12) +# define DEFIO_TAG_E__PA12 DEFIO_TAG_MAKE(DEFIO_GPIOID__A, 12) +# define DEFIO_REC__PA12 DEFIO_REC_INDEXED(BITCOUNT(DEFIO_PORT_A_USED_MASK & (BIT(12) - 1)) + 0) +#else +# define DEFIO_TAG__PA12 defio_error_PA12_is_not_supported_on_TARGET +# define DEFIO_TAG_E__PA12 DEFIO_TAG_E__NONE +# define DEFIO_REC__PA12 defio_error_PA12_is_not_supported_on_TARGET +#endif +#if DEFIO_PORT_A_USED_MASK & BIT(13) +# define DEFIO_TAG__PA13 DEFIO_TAG_MAKE(DEFIO_GPIOID__A, 13) +# define DEFIO_TAG_E__PA13 DEFIO_TAG_MAKE(DEFIO_GPIOID__A, 13) +# define DEFIO_REC__PA13 DEFIO_REC_INDEXED(BITCOUNT(DEFIO_PORT_A_USED_MASK & (BIT(13) - 1)) + 0) +#else +# define DEFIO_TAG__PA13 defio_error_PA13_is_not_supported_on_TARGET +# define DEFIO_TAG_E__PA13 DEFIO_TAG_E__NONE +# define DEFIO_REC__PA13 defio_error_PA13_is_not_supported_on_TARGET +#endif +#if DEFIO_PORT_A_USED_MASK & BIT(14) +# define DEFIO_TAG__PA14 DEFIO_TAG_MAKE(DEFIO_GPIOID__A, 14) +# define DEFIO_TAG_E__PA14 DEFIO_TAG_MAKE(DEFIO_GPIOID__A, 14) +# define DEFIO_REC__PA14 DEFIO_REC_INDEXED(BITCOUNT(DEFIO_PORT_A_USED_MASK & (BIT(14) - 1)) + 0) +#else +# define DEFIO_TAG__PA14 defio_error_PA14_is_not_supported_on_TARGET +# define DEFIO_TAG_E__PA14 DEFIO_TAG_E__NONE +# define DEFIO_REC__PA14 defio_error_PA14_is_not_supported_on_TARGET +#endif +#if DEFIO_PORT_A_USED_MASK & BIT(15) +# define DEFIO_TAG__PA15 DEFIO_TAG_MAKE(DEFIO_GPIOID__A, 15) +# define DEFIO_TAG_E__PA15 DEFIO_TAG_MAKE(DEFIO_GPIOID__A, 15) +# define DEFIO_REC__PA15 DEFIO_REC_INDEXED(BITCOUNT(DEFIO_PORT_A_USED_MASK & (BIT(15) - 1)) + 0) +#else +# define DEFIO_TAG__PA15 defio_error_PA15_is_not_supported_on_TARGET +# define DEFIO_TAG_E__PA15 DEFIO_TAG_E__NONE +# define DEFIO_REC__PA15 defio_error_PA15_is_not_supported_on_TARGET +#endif +#if DEFIO_PORT_B_USED_MASK & BIT(0) +# define DEFIO_TAG__PB0 DEFIO_TAG_MAKE(DEFIO_GPIOID__B, 0) +# define DEFIO_TAG_E__PB0 DEFIO_TAG_MAKE(DEFIO_GPIOID__B, 0) +# define DEFIO_REC__PB0 DEFIO_REC_INDEXED(BITCOUNT(DEFIO_PORT_B_USED_MASK & (BIT(0) - 1)) + DEFIO_PORT_A_USED_COUNT) +#else +# define DEFIO_TAG__PB0 defio_error_PB0_is_not_supported_on_TARGET +# define DEFIO_TAG_E__PB0 DEFIO_TAG_E__NONE +# define DEFIO_REC__PB0 defio_error_PB0_is_not_supported_on_TARGET +#endif +#if DEFIO_PORT_B_USED_MASK & BIT(1) +# define DEFIO_TAG__PB1 DEFIO_TAG_MAKE(DEFIO_GPIOID__B, 1) +# define DEFIO_TAG_E__PB1 DEFIO_TAG_MAKE(DEFIO_GPIOID__B, 1) +# define DEFIO_REC__PB1 DEFIO_REC_INDEXED(BITCOUNT(DEFIO_PORT_B_USED_MASK & (BIT(1) - 1)) + DEFIO_PORT_A_USED_COUNT) +#else +# define DEFIO_TAG__PB1 defio_error_PB1_is_not_supported_on_TARGET +# define DEFIO_TAG_E__PB1 DEFIO_TAG_E__NONE +# define DEFIO_REC__PB1 defio_error_PB1_is_not_supported_on_TARGET +#endif +#if DEFIO_PORT_B_USED_MASK & BIT(2) +# define DEFIO_TAG__PB2 DEFIO_TAG_MAKE(DEFIO_GPIOID__B, 2) +# define DEFIO_TAG_E__PB2 DEFIO_TAG_MAKE(DEFIO_GPIOID__B, 2) +# define DEFIO_REC__PB2 DEFIO_REC_INDEXED(BITCOUNT(DEFIO_PORT_B_USED_MASK & (BIT(2) - 1)) + DEFIO_PORT_A_USED_COUNT) +#else +# define DEFIO_TAG__PB2 defio_error_PB2_is_not_supported_on_TARGET +# define DEFIO_TAG_E__PB2 DEFIO_TAG_E__NONE +# define DEFIO_REC__PB2 defio_error_PB2_is_not_supported_on_TARGET +#endif +#if DEFIO_PORT_B_USED_MASK & BIT(3) +# define DEFIO_TAG__PB3 DEFIO_TAG_MAKE(DEFIO_GPIOID__B, 3) +# define DEFIO_TAG_E__PB3 DEFIO_TAG_MAKE(DEFIO_GPIOID__B, 3) +# define DEFIO_REC__PB3 DEFIO_REC_INDEXED(BITCOUNT(DEFIO_PORT_B_USED_MASK & (BIT(3) - 1)) + DEFIO_PORT_A_USED_COUNT) +#else +# define DEFIO_TAG__PB3 defio_error_PB3_is_not_supported_on_TARGET +# define DEFIO_TAG_E__PB3 DEFIO_TAG_E__NONE +# define DEFIO_REC__PB3 defio_error_PB3_is_not_supported_on_TARGET +#endif +#if DEFIO_PORT_B_USED_MASK & BIT(4) +# define DEFIO_TAG__PB4 DEFIO_TAG_MAKE(DEFIO_GPIOID__B, 4) +# define DEFIO_TAG_E__PB4 DEFIO_TAG_MAKE(DEFIO_GPIOID__B, 4) +# define DEFIO_REC__PB4 DEFIO_REC_INDEXED(BITCOUNT(DEFIO_PORT_B_USED_MASK & (BIT(4) - 1)) + DEFIO_PORT_A_USED_COUNT) +#else +# define DEFIO_TAG__PB4 defio_error_PB4_is_not_supported_on_TARGET +# define DEFIO_TAG_E__PB4 DEFIO_TAG_E__NONE +# define DEFIO_REC__PB4 defio_error_PB4_is_not_supported_on_TARGET +#endif +#if DEFIO_PORT_B_USED_MASK & BIT(5) +# define DEFIO_TAG__PB5 DEFIO_TAG_MAKE(DEFIO_GPIOID__B, 5) +# define DEFIO_TAG_E__PB5 DEFIO_TAG_MAKE(DEFIO_GPIOID__B, 5) +# define DEFIO_REC__PB5 DEFIO_REC_INDEXED(BITCOUNT(DEFIO_PORT_B_USED_MASK & (BIT(5) - 1)) + DEFIO_PORT_A_USED_COUNT) +#else +# define DEFIO_TAG__PB5 defio_error_PB5_is_not_supported_on_TARGET +# define DEFIO_TAG_E__PB5 DEFIO_TAG_E__NONE +# define DEFIO_REC__PB5 defio_error_PB5_is_not_supported_on_TARGET +#endif +#if DEFIO_PORT_B_USED_MASK & BIT(6) +# define DEFIO_TAG__PB6 DEFIO_TAG_MAKE(DEFIO_GPIOID__B, 6) +# define DEFIO_TAG_E__PB6 DEFIO_TAG_MAKE(DEFIO_GPIOID__B, 6) +# define DEFIO_REC__PB6 DEFIO_REC_INDEXED(BITCOUNT(DEFIO_PORT_B_USED_MASK & (BIT(6) - 1)) + DEFIO_PORT_A_USED_COUNT) +#else +# define DEFIO_TAG__PB6 defio_error_PB6_is_not_supported_on_TARGET +# define DEFIO_TAG_E__PB6 DEFIO_TAG_E__NONE +# define DEFIO_REC__PB6 defio_error_PB6_is_not_supported_on_TARGET +#endif +#if DEFIO_PORT_B_USED_MASK & BIT(7) +# define DEFIO_TAG__PB7 DEFIO_TAG_MAKE(DEFIO_GPIOID__B, 7) +# define DEFIO_TAG_E__PB7 DEFIO_TAG_MAKE(DEFIO_GPIOID__B, 7) +# define DEFIO_REC__PB7 DEFIO_REC_INDEXED(BITCOUNT(DEFIO_PORT_B_USED_MASK & (BIT(7) - 1)) + DEFIO_PORT_A_USED_COUNT) +#else +# define DEFIO_TAG__PB7 defio_error_PB7_is_not_supported_on_TARGET +# define DEFIO_TAG_E__PB7 DEFIO_TAG_E__NONE +# define DEFIO_REC__PB7 defio_error_PB7_is_not_supported_on_TARGET +#endif +#if DEFIO_PORT_B_USED_MASK & BIT(8) +# define DEFIO_TAG__PB8 DEFIO_TAG_MAKE(DEFIO_GPIOID__B, 8) +# define DEFIO_TAG_E__PB8 DEFIO_TAG_MAKE(DEFIO_GPIOID__B, 8) +# define DEFIO_REC__PB8 DEFIO_REC_INDEXED(BITCOUNT(DEFIO_PORT_B_USED_MASK & (BIT(8) - 1)) + DEFIO_PORT_A_USED_COUNT) +#else +# define DEFIO_TAG__PB8 defio_error_PB8_is_not_supported_on_TARGET +# define DEFIO_TAG_E__PB8 DEFIO_TAG_E__NONE +# define DEFIO_REC__PB8 defio_error_PB8_is_not_supported_on_TARGET +#endif +#if DEFIO_PORT_B_USED_MASK & BIT(9) +# define DEFIO_TAG__PB9 DEFIO_TAG_MAKE(DEFIO_GPIOID__B, 9) +# define DEFIO_TAG_E__PB9 DEFIO_TAG_MAKE(DEFIO_GPIOID__B, 9) +# define DEFIO_REC__PB9 DEFIO_REC_INDEXED(BITCOUNT(DEFIO_PORT_B_USED_MASK & (BIT(9) - 1)) + DEFIO_PORT_A_USED_COUNT) +#else +# define DEFIO_TAG__PB9 defio_error_PB9_is_not_supported_on_TARGET +# define DEFIO_TAG_E__PB9 DEFIO_TAG_E__NONE +# define DEFIO_REC__PB9 defio_error_PB9_is_not_supported_on_TARGET +#endif +#if DEFIO_PORT_B_USED_MASK & BIT(10) +# define DEFIO_TAG__PB10 DEFIO_TAG_MAKE(DEFIO_GPIOID__B, 10) +# define DEFIO_TAG_E__PB10 DEFIO_TAG_MAKE(DEFIO_GPIOID__B, 10) +# define DEFIO_REC__PB10 DEFIO_REC_INDEXED(BITCOUNT(DEFIO_PORT_B_USED_MASK & (BIT(10) - 1)) + DEFIO_PORT_A_USED_COUNT) +#else +# define DEFIO_TAG__PB10 defio_error_PB10_is_not_supported_on_TARGET +# define DEFIO_TAG_E__PB10 DEFIO_TAG_E__NONE +# define DEFIO_REC__PB10 defio_error_PB10_is_not_supported_on_TARGET +#endif +#if DEFIO_PORT_B_USED_MASK & BIT(11) +# define DEFIO_TAG__PB11 DEFIO_TAG_MAKE(DEFIO_GPIOID__B, 11) +# define DEFIO_TAG_E__PB11 DEFIO_TAG_MAKE(DEFIO_GPIOID__B, 11) +# define DEFIO_REC__PB11 DEFIO_REC_INDEXED(BITCOUNT(DEFIO_PORT_B_USED_MASK & (BIT(11) - 1)) + DEFIO_PORT_A_USED_COUNT) +#else +# define DEFIO_TAG__PB11 defio_error_PB11_is_not_supported_on_TARGET +# define DEFIO_TAG_E__PB11 DEFIO_TAG_E__NONE +# define DEFIO_REC__PB11 defio_error_PB11_is_not_supported_on_TARGET +#endif +#if DEFIO_PORT_B_USED_MASK & BIT(12) +# define DEFIO_TAG__PB12 DEFIO_TAG_MAKE(DEFIO_GPIOID__B, 12) +# define DEFIO_TAG_E__PB12 DEFIO_TAG_MAKE(DEFIO_GPIOID__B, 12) +# define DEFIO_REC__PB12 DEFIO_REC_INDEXED(BITCOUNT(DEFIO_PORT_B_USED_MASK & (BIT(12) - 1)) + DEFIO_PORT_A_USED_COUNT) +#else +# define DEFIO_TAG__PB12 defio_error_PB12_is_not_supported_on_TARGET +# define DEFIO_TAG_E__PB12 DEFIO_TAG_E__NONE +# define DEFIO_REC__PB12 defio_error_PB12_is_not_supported_on_TARGET +#endif +#if DEFIO_PORT_B_USED_MASK & BIT(13) +# define DEFIO_TAG__PB13 DEFIO_TAG_MAKE(DEFIO_GPIOID__B, 13) +# define DEFIO_TAG_E__PB13 DEFIO_TAG_MAKE(DEFIO_GPIOID__B, 13) +# define DEFIO_REC__PB13 DEFIO_REC_INDEXED(BITCOUNT(DEFIO_PORT_B_USED_MASK & (BIT(13) - 1)) + DEFIO_PORT_A_USED_COUNT) +#else +# define DEFIO_TAG__PB13 defio_error_PB13_is_not_supported_on_TARGET +# define DEFIO_TAG_E__PB13 DEFIO_TAG_E__NONE +# define DEFIO_REC__PB13 defio_error_PB13_is_not_supported_on_TARGET +#endif +#if DEFIO_PORT_B_USED_MASK & BIT(14) +# define DEFIO_TAG__PB14 DEFIO_TAG_MAKE(DEFIO_GPIOID__B, 14) +# define DEFIO_TAG_E__PB14 DEFIO_TAG_MAKE(DEFIO_GPIOID__B, 14) +# define DEFIO_REC__PB14 DEFIO_REC_INDEXED(BITCOUNT(DEFIO_PORT_B_USED_MASK & (BIT(14) - 1)) + DEFIO_PORT_A_USED_COUNT) +#else +# define DEFIO_TAG__PB14 defio_error_PB14_is_not_supported_on_TARGET +# define DEFIO_TAG_E__PB14 DEFIO_TAG_E__NONE +# define DEFIO_REC__PB14 defio_error_PB14_is_not_supported_on_TARGET +#endif +#if DEFIO_PORT_B_USED_MASK & BIT(15) +# define DEFIO_TAG__PB15 DEFIO_TAG_MAKE(DEFIO_GPIOID__B, 15) +# define DEFIO_TAG_E__PB15 DEFIO_TAG_MAKE(DEFIO_GPIOID__B, 15) +# define DEFIO_REC__PB15 DEFIO_REC_INDEXED(BITCOUNT(DEFIO_PORT_B_USED_MASK & (BIT(15) - 1)) + DEFIO_PORT_A_USED_COUNT) +#else +# define DEFIO_TAG__PB15 defio_error_PB15_is_not_supported_on_TARGET +# define DEFIO_TAG_E__PB15 DEFIO_TAG_E__NONE +# define DEFIO_REC__PB15 defio_error_PB15_is_not_supported_on_TARGET +#endif +#if DEFIO_PORT_C_USED_MASK & BIT(0) +# define DEFIO_TAG__PC0 DEFIO_TAG_MAKE(DEFIO_GPIOID__C, 0) +# define DEFIO_TAG_E__PC0 DEFIO_TAG_MAKE(DEFIO_GPIOID__C, 0) +# define DEFIO_REC__PC0 DEFIO_REC_INDEXED(BITCOUNT(DEFIO_PORT_C_USED_MASK & (BIT(0) - 1)) + DEFIO_PORT_A_USED_COUNT+DEFIO_PORT_B_USED_COUNT) +#else +# define DEFIO_TAG__PC0 defio_error_PC0_is_not_supported_on_TARGET +# define DEFIO_TAG_E__PC0 DEFIO_TAG_E__NONE +# define DEFIO_REC__PC0 defio_error_PC0_is_not_supported_on_TARGET +#endif +#if DEFIO_PORT_C_USED_MASK & BIT(1) +# define DEFIO_TAG__PC1 DEFIO_TAG_MAKE(DEFIO_GPIOID__C, 1) +# define DEFIO_TAG_E__PC1 DEFIO_TAG_MAKE(DEFIO_GPIOID__C, 1) +# define DEFIO_REC__PC1 DEFIO_REC_INDEXED(BITCOUNT(DEFIO_PORT_C_USED_MASK & (BIT(1) - 1)) + DEFIO_PORT_A_USED_COUNT+DEFIO_PORT_B_USED_COUNT) +#else +# define DEFIO_TAG__PC1 defio_error_PC1_is_not_supported_on_TARGET +# define DEFIO_TAG_E__PC1 DEFIO_TAG_E__NONE +# define DEFIO_REC__PC1 defio_error_PC1_is_not_supported_on_TARGET +#endif +#if DEFIO_PORT_C_USED_MASK & BIT(2) +# define DEFIO_TAG__PC2 DEFIO_TAG_MAKE(DEFIO_GPIOID__C, 2) +# define DEFIO_TAG_E__PC2 DEFIO_TAG_MAKE(DEFIO_GPIOID__C, 2) +# define DEFIO_REC__PC2 DEFIO_REC_INDEXED(BITCOUNT(DEFIO_PORT_C_USED_MASK & (BIT(2) - 1)) + DEFIO_PORT_A_USED_COUNT+DEFIO_PORT_B_USED_COUNT) +#else +# define DEFIO_TAG__PC2 defio_error_PC2_is_not_supported_on_TARGET +# define DEFIO_TAG_E__PC2 DEFIO_TAG_E__NONE +# define DEFIO_REC__PC2 defio_error_PC2_is_not_supported_on_TARGET +#endif +#if DEFIO_PORT_C_USED_MASK & BIT(3) +# define DEFIO_TAG__PC3 DEFIO_TAG_MAKE(DEFIO_GPIOID__C, 3) +# define DEFIO_TAG_E__PC3 DEFIO_TAG_MAKE(DEFIO_GPIOID__C, 3) +# define DEFIO_REC__PC3 DEFIO_REC_INDEXED(BITCOUNT(DEFIO_PORT_C_USED_MASK & (BIT(3) - 1)) + DEFIO_PORT_A_USED_COUNT+DEFIO_PORT_B_USED_COUNT) +#else +# define DEFIO_TAG__PC3 defio_error_PC3_is_not_supported_on_TARGET +# define DEFIO_TAG_E__PC3 DEFIO_TAG_E__NONE +# define DEFIO_REC__PC3 defio_error_PC3_is_not_supported_on_TARGET +#endif +#if DEFIO_PORT_C_USED_MASK & BIT(4) +# define DEFIO_TAG__PC4 DEFIO_TAG_MAKE(DEFIO_GPIOID__C, 4) +# define DEFIO_TAG_E__PC4 DEFIO_TAG_MAKE(DEFIO_GPIOID__C, 4) +# define DEFIO_REC__PC4 DEFIO_REC_INDEXED(BITCOUNT(DEFIO_PORT_C_USED_MASK & (BIT(4) - 1)) + DEFIO_PORT_A_USED_COUNT+DEFIO_PORT_B_USED_COUNT) +#else +# define DEFIO_TAG__PC4 defio_error_PC4_is_not_supported_on_TARGET +# define DEFIO_TAG_E__PC4 DEFIO_TAG_E__NONE +# define DEFIO_REC__PC4 defio_error_PC4_is_not_supported_on_TARGET +#endif +#if DEFIO_PORT_C_USED_MASK & BIT(5) +# define DEFIO_TAG__PC5 DEFIO_TAG_MAKE(DEFIO_GPIOID__C, 5) +# define DEFIO_TAG_E__PC5 DEFIO_TAG_MAKE(DEFIO_GPIOID__C, 5) +# define DEFIO_REC__PC5 DEFIO_REC_INDEXED(BITCOUNT(DEFIO_PORT_C_USED_MASK & (BIT(5) - 1)) + DEFIO_PORT_A_USED_COUNT+DEFIO_PORT_B_USED_COUNT) +#else +# define DEFIO_TAG__PC5 defio_error_PC5_is_not_supported_on_TARGET +# define DEFIO_TAG_E__PC5 DEFIO_TAG_E__NONE +# define DEFIO_REC__PC5 defio_error_PC5_is_not_supported_on_TARGET +#endif +#if DEFIO_PORT_C_USED_MASK & BIT(6) +# define DEFIO_TAG__PC6 DEFIO_TAG_MAKE(DEFIO_GPIOID__C, 6) +# define DEFIO_TAG_E__PC6 DEFIO_TAG_MAKE(DEFIO_GPIOID__C, 6) +# define DEFIO_REC__PC6 DEFIO_REC_INDEXED(BITCOUNT(DEFIO_PORT_C_USED_MASK & (BIT(6) - 1)) + DEFIO_PORT_A_USED_COUNT+DEFIO_PORT_B_USED_COUNT) +#else +# define DEFIO_TAG__PC6 defio_error_PC6_is_not_supported_on_TARGET +# define DEFIO_TAG_E__PC6 DEFIO_TAG_E__NONE +# define DEFIO_REC__PC6 defio_error_PC6_is_not_supported_on_TARGET +#endif +#if DEFIO_PORT_C_USED_MASK & BIT(7) +# define DEFIO_TAG__PC7 DEFIO_TAG_MAKE(DEFIO_GPIOID__C, 7) +# define DEFIO_TAG_E__PC7 DEFIO_TAG_MAKE(DEFIO_GPIOID__C, 7) +# define DEFIO_REC__PC7 DEFIO_REC_INDEXED(BITCOUNT(DEFIO_PORT_C_USED_MASK & (BIT(7) - 1)) + DEFIO_PORT_A_USED_COUNT+DEFIO_PORT_B_USED_COUNT) +#else +# define DEFIO_TAG__PC7 defio_error_PC7_is_not_supported_on_TARGET +# define DEFIO_TAG_E__PC7 DEFIO_TAG_E__NONE +# define DEFIO_REC__PC7 defio_error_PC7_is_not_supported_on_TARGET +#endif +#if DEFIO_PORT_C_USED_MASK & BIT(8) +# define DEFIO_TAG__PC8 DEFIO_TAG_MAKE(DEFIO_GPIOID__C, 8) +# define DEFIO_TAG_E__PC8 DEFIO_TAG_MAKE(DEFIO_GPIOID__C, 8) +# define DEFIO_REC__PC8 DEFIO_REC_INDEXED(BITCOUNT(DEFIO_PORT_C_USED_MASK & (BIT(8) - 1)) + DEFIO_PORT_A_USED_COUNT+DEFIO_PORT_B_USED_COUNT) +#else +# define DEFIO_TAG__PC8 defio_error_PC8_is_not_supported_on_TARGET +# define DEFIO_TAG_E__PC8 DEFIO_TAG_E__NONE +# define DEFIO_REC__PC8 defio_error_PC8_is_not_supported_on_TARGET +#endif +#if DEFIO_PORT_C_USED_MASK & BIT(9) +# define DEFIO_TAG__PC9 DEFIO_TAG_MAKE(DEFIO_GPIOID__C, 9) +# define DEFIO_TAG_E__PC9 DEFIO_TAG_MAKE(DEFIO_GPIOID__C, 9) +# define DEFIO_REC__PC9 DEFIO_REC_INDEXED(BITCOUNT(DEFIO_PORT_C_USED_MASK & (BIT(9) - 1)) + DEFIO_PORT_A_USED_COUNT+DEFIO_PORT_B_USED_COUNT) +#else +# define DEFIO_TAG__PC9 defio_error_PC9_is_not_supported_on_TARGET +# define DEFIO_TAG_E__PC9 DEFIO_TAG_E__NONE +# define DEFIO_REC__PC9 defio_error_PC9_is_not_supported_on_TARGET +#endif +#if DEFIO_PORT_C_USED_MASK & BIT(10) +# define DEFIO_TAG__PC10 DEFIO_TAG_MAKE(DEFIO_GPIOID__C, 10) +# define DEFIO_TAG_E__PC10 DEFIO_TAG_MAKE(DEFIO_GPIOID__C, 10) +# define DEFIO_REC__PC10 DEFIO_REC_INDEXED(BITCOUNT(DEFIO_PORT_C_USED_MASK & (BIT(10) - 1)) + DEFIO_PORT_A_USED_COUNT+DEFIO_PORT_B_USED_COUNT) +#else +# define DEFIO_TAG__PC10 defio_error_PC10_is_not_supported_on_TARGET +# define DEFIO_TAG_E__PC10 DEFIO_TAG_E__NONE +# define DEFIO_REC__PC10 defio_error_PC10_is_not_supported_on_TARGET +#endif +#if DEFIO_PORT_C_USED_MASK & BIT(11) +# define DEFIO_TAG__PC11 DEFIO_TAG_MAKE(DEFIO_GPIOID__C, 11) +# define DEFIO_TAG_E__PC11 DEFIO_TAG_MAKE(DEFIO_GPIOID__C, 11) +# define DEFIO_REC__PC11 DEFIO_REC_INDEXED(BITCOUNT(DEFIO_PORT_C_USED_MASK & (BIT(11) - 1)) + DEFIO_PORT_A_USED_COUNT+DEFIO_PORT_B_USED_COUNT) +#else +# define DEFIO_TAG__PC11 defio_error_PC11_is_not_supported_on_TARGET +# define DEFIO_TAG_E__PC11 DEFIO_TAG_E__NONE +# define DEFIO_REC__PC11 defio_error_PC11_is_not_supported_on_TARGET +#endif +#if DEFIO_PORT_C_USED_MASK & BIT(12) +# define DEFIO_TAG__PC12 DEFIO_TAG_MAKE(DEFIO_GPIOID__C, 12) +# define DEFIO_TAG_E__PC12 DEFIO_TAG_MAKE(DEFIO_GPIOID__C, 12) +# define DEFIO_REC__PC12 DEFIO_REC_INDEXED(BITCOUNT(DEFIO_PORT_C_USED_MASK & (BIT(12) - 1)) + DEFIO_PORT_A_USED_COUNT+DEFIO_PORT_B_USED_COUNT) +#else +# define DEFIO_TAG__PC12 defio_error_PC12_is_not_supported_on_TARGET +# define DEFIO_TAG_E__PC12 DEFIO_TAG_E__NONE +# define DEFIO_REC__PC12 defio_error_PC12_is_not_supported_on_TARGET +#endif +#if DEFIO_PORT_C_USED_MASK & BIT(13) +# define DEFIO_TAG__PC13 DEFIO_TAG_MAKE(DEFIO_GPIOID__C, 13) +# define DEFIO_TAG_E__PC13 DEFIO_TAG_MAKE(DEFIO_GPIOID__C, 13) +# define DEFIO_REC__PC13 DEFIO_REC_INDEXED(BITCOUNT(DEFIO_PORT_C_USED_MASK & (BIT(13) - 1)) + DEFIO_PORT_A_USED_COUNT+DEFIO_PORT_B_USED_COUNT) +#else +# define DEFIO_TAG__PC13 defio_error_PC13_is_not_supported_on_TARGET +# define DEFIO_TAG_E__PC13 DEFIO_TAG_E__NONE +# define DEFIO_REC__PC13 defio_error_PC13_is_not_supported_on_TARGET +#endif +#if DEFIO_PORT_C_USED_MASK & BIT(14) +# define DEFIO_TAG__PC14 DEFIO_TAG_MAKE(DEFIO_GPIOID__C, 14) +# define DEFIO_TAG_E__PC14 DEFIO_TAG_MAKE(DEFIO_GPIOID__C, 14) +# define DEFIO_REC__PC14 DEFIO_REC_INDEXED(BITCOUNT(DEFIO_PORT_C_USED_MASK & (BIT(14) - 1)) + DEFIO_PORT_A_USED_COUNT+DEFIO_PORT_B_USED_COUNT) +#else +# define DEFIO_TAG__PC14 defio_error_PC14_is_not_supported_on_TARGET +# define DEFIO_TAG_E__PC14 DEFIO_TAG_E__NONE +# define DEFIO_REC__PC14 defio_error_PC14_is_not_supported_on_TARGET +#endif +#if DEFIO_PORT_C_USED_MASK & BIT(15) +# define DEFIO_TAG__PC15 DEFIO_TAG_MAKE(DEFIO_GPIOID__C, 15) +# define DEFIO_TAG_E__PC15 DEFIO_TAG_MAKE(DEFIO_GPIOID__C, 15) +# define DEFIO_REC__PC15 DEFIO_REC_INDEXED(BITCOUNT(DEFIO_PORT_C_USED_MASK & (BIT(15) - 1)) + DEFIO_PORT_A_USED_COUNT+DEFIO_PORT_B_USED_COUNT) +#else +# define DEFIO_TAG__PC15 defio_error_PC15_is_not_supported_on_TARGET +# define DEFIO_TAG_E__PC15 DEFIO_TAG_E__NONE +# define DEFIO_REC__PC15 defio_error_PC15_is_not_supported_on_TARGET +#endif +#if DEFIO_PORT_D_USED_MASK & BIT(0) +# define DEFIO_TAG__PD0 DEFIO_TAG_MAKE(DEFIO_GPIOID__D, 0) +# define DEFIO_TAG_E__PD0 DEFIO_TAG_MAKE(DEFIO_GPIOID__D, 0) +# define DEFIO_REC__PD0 DEFIO_REC_INDEXED(BITCOUNT(DEFIO_PORT_D_USED_MASK & (BIT(0) - 1)) + DEFIO_PORT_A_USED_COUNT+DEFIO_PORT_B_USED_COUNT+DEFIO_PORT_C_USED_COUNT) +#else +# define DEFIO_TAG__PD0 defio_error_PD0_is_not_supported_on_TARGET +# define DEFIO_TAG_E__PD0 DEFIO_TAG_E__NONE +# define DEFIO_REC__PD0 defio_error_PD0_is_not_supported_on_TARGET +#endif +#if DEFIO_PORT_D_USED_MASK & BIT(1) +# define DEFIO_TAG__PD1 DEFIO_TAG_MAKE(DEFIO_GPIOID__D, 1) +# define DEFIO_TAG_E__PD1 DEFIO_TAG_MAKE(DEFIO_GPIOID__D, 1) +# define DEFIO_REC__PD1 DEFIO_REC_INDEXED(BITCOUNT(DEFIO_PORT_D_USED_MASK & (BIT(1) - 1)) + DEFIO_PORT_A_USED_COUNT+DEFIO_PORT_B_USED_COUNT+DEFIO_PORT_C_USED_COUNT) +#else +# define DEFIO_TAG__PD1 defio_error_PD1_is_not_supported_on_TARGET +# define DEFIO_TAG_E__PD1 DEFIO_TAG_E__NONE +# define DEFIO_REC__PD1 defio_error_PD1_is_not_supported_on_TARGET +#endif +#if DEFIO_PORT_D_USED_MASK & BIT(2) +# define DEFIO_TAG__PD2 DEFIO_TAG_MAKE(DEFIO_GPIOID__D, 2) +# define DEFIO_TAG_E__PD2 DEFIO_TAG_MAKE(DEFIO_GPIOID__D, 2) +# define DEFIO_REC__PD2 DEFIO_REC_INDEXED(BITCOUNT(DEFIO_PORT_D_USED_MASK & (BIT(2) - 1)) + DEFIO_PORT_A_USED_COUNT+DEFIO_PORT_B_USED_COUNT+DEFIO_PORT_C_USED_COUNT) +#else +# define DEFIO_TAG__PD2 defio_error_PD2_is_not_supported_on_TARGET +# define DEFIO_TAG_E__PD2 DEFIO_TAG_E__NONE +# define DEFIO_REC__PD2 defio_error_PD2_is_not_supported_on_TARGET +#endif +#if DEFIO_PORT_D_USED_MASK & BIT(3) +# define DEFIO_TAG__PD3 DEFIO_TAG_MAKE(DEFIO_GPIOID__D, 3) +# define DEFIO_TAG_E__PD3 DEFIO_TAG_MAKE(DEFIO_GPIOID__D, 3) +# define DEFIO_REC__PD3 DEFIO_REC_INDEXED(BITCOUNT(DEFIO_PORT_D_USED_MASK & (BIT(3) - 1)) + DEFIO_PORT_A_USED_COUNT+DEFIO_PORT_B_USED_COUNT+DEFIO_PORT_C_USED_COUNT) +#else +# define DEFIO_TAG__PD3 defio_error_PD3_is_not_supported_on_TARGET +# define DEFIO_TAG_E__PD3 DEFIO_TAG_E__NONE +# define DEFIO_REC__PD3 defio_error_PD3_is_not_supported_on_TARGET +#endif +#if DEFIO_PORT_D_USED_MASK & BIT(4) +# define DEFIO_TAG__PD4 DEFIO_TAG_MAKE(DEFIO_GPIOID__D, 4) +# define DEFIO_TAG_E__PD4 DEFIO_TAG_MAKE(DEFIO_GPIOID__D, 4) +# define DEFIO_REC__PD4 DEFIO_REC_INDEXED(BITCOUNT(DEFIO_PORT_D_USED_MASK & (BIT(4) - 1)) + DEFIO_PORT_A_USED_COUNT+DEFIO_PORT_B_USED_COUNT+DEFIO_PORT_C_USED_COUNT) +#else +# define DEFIO_TAG__PD4 defio_error_PD4_is_not_supported_on_TARGET +# define DEFIO_TAG_E__PD4 DEFIO_TAG_E__NONE +# define DEFIO_REC__PD4 defio_error_PD4_is_not_supported_on_TARGET +#endif +#if DEFIO_PORT_D_USED_MASK & BIT(5) +# define DEFIO_TAG__PD5 DEFIO_TAG_MAKE(DEFIO_GPIOID__D, 5) +# define DEFIO_TAG_E__PD5 DEFIO_TAG_MAKE(DEFIO_GPIOID__D, 5) +# define DEFIO_REC__PD5 DEFIO_REC_INDEXED(BITCOUNT(DEFIO_PORT_D_USED_MASK & (BIT(5) - 1)) + DEFIO_PORT_A_USED_COUNT+DEFIO_PORT_B_USED_COUNT+DEFIO_PORT_C_USED_COUNT) +#else +# define DEFIO_TAG__PD5 defio_error_PD5_is_not_supported_on_TARGET +# define DEFIO_TAG_E__PD5 DEFIO_TAG_E__NONE +# define DEFIO_REC__PD5 defio_error_PD5_is_not_supported_on_TARGET +#endif +#if DEFIO_PORT_D_USED_MASK & BIT(6) +# define DEFIO_TAG__PD6 DEFIO_TAG_MAKE(DEFIO_GPIOID__D, 6) +# define DEFIO_TAG_E__PD6 DEFIO_TAG_MAKE(DEFIO_GPIOID__D, 6) +# define DEFIO_REC__PD6 DEFIO_REC_INDEXED(BITCOUNT(DEFIO_PORT_D_USED_MASK & (BIT(6) - 1)) + DEFIO_PORT_A_USED_COUNT+DEFIO_PORT_B_USED_COUNT+DEFIO_PORT_C_USED_COUNT) +#else +# define DEFIO_TAG__PD6 defio_error_PD6_is_not_supported_on_TARGET +# define DEFIO_TAG_E__PD6 DEFIO_TAG_E__NONE +# define DEFIO_REC__PD6 defio_error_PD6_is_not_supported_on_TARGET +#endif +#if DEFIO_PORT_D_USED_MASK & BIT(7) +# define DEFIO_TAG__PD7 DEFIO_TAG_MAKE(DEFIO_GPIOID__D, 7) +# define DEFIO_TAG_E__PD7 DEFIO_TAG_MAKE(DEFIO_GPIOID__D, 7) +# define DEFIO_REC__PD7 DEFIO_REC_INDEXED(BITCOUNT(DEFIO_PORT_D_USED_MASK & (BIT(7) - 1)) + DEFIO_PORT_A_USED_COUNT+DEFIO_PORT_B_USED_COUNT+DEFIO_PORT_C_USED_COUNT) +#else +# define DEFIO_TAG__PD7 defio_error_PD7_is_not_supported_on_TARGET +# define DEFIO_TAG_E__PD7 DEFIO_TAG_E__NONE +# define DEFIO_REC__PD7 defio_error_PD7_is_not_supported_on_TARGET +#endif +#if DEFIO_PORT_D_USED_MASK & BIT(8) +# define DEFIO_TAG__PD8 DEFIO_TAG_MAKE(DEFIO_GPIOID__D, 8) +# define DEFIO_TAG_E__PD8 DEFIO_TAG_MAKE(DEFIO_GPIOID__D, 8) +# define DEFIO_REC__PD8 DEFIO_REC_INDEXED(BITCOUNT(DEFIO_PORT_D_USED_MASK & (BIT(8) - 1)) + DEFIO_PORT_A_USED_COUNT+DEFIO_PORT_B_USED_COUNT+DEFIO_PORT_C_USED_COUNT) +#else +# define DEFIO_TAG__PD8 defio_error_PD8_is_not_supported_on_TARGET +# define DEFIO_TAG_E__PD8 DEFIO_TAG_E__NONE +# define DEFIO_REC__PD8 defio_error_PD8_is_not_supported_on_TARGET +#endif +#if DEFIO_PORT_D_USED_MASK & BIT(9) +# define DEFIO_TAG__PD9 DEFIO_TAG_MAKE(DEFIO_GPIOID__D, 9) +# define DEFIO_TAG_E__PD9 DEFIO_TAG_MAKE(DEFIO_GPIOID__D, 9) +# define DEFIO_REC__PD9 DEFIO_REC_INDEXED(BITCOUNT(DEFIO_PORT_D_USED_MASK & (BIT(9) - 1)) + DEFIO_PORT_A_USED_COUNT+DEFIO_PORT_B_USED_COUNT+DEFIO_PORT_C_USED_COUNT) +#else +# define DEFIO_TAG__PD9 defio_error_PD9_is_not_supported_on_TARGET +# define DEFIO_TAG_E__PD9 DEFIO_TAG_E__NONE +# define DEFIO_REC__PD9 defio_error_PD9_is_not_supported_on_TARGET +#endif +#if DEFIO_PORT_D_USED_MASK & BIT(10) +# define DEFIO_TAG__PD10 DEFIO_TAG_MAKE(DEFIO_GPIOID__D, 10) +# define DEFIO_TAG_E__PD10 DEFIO_TAG_MAKE(DEFIO_GPIOID__D, 10) +# define DEFIO_REC__PD10 DEFIO_REC_INDEXED(BITCOUNT(DEFIO_PORT_D_USED_MASK & (BIT(10) - 1)) + DEFIO_PORT_A_USED_COUNT+DEFIO_PORT_B_USED_COUNT+DEFIO_PORT_C_USED_COUNT) +#else +# define DEFIO_TAG__PD10 defio_error_PD10_is_not_supported_on_TARGET +# define DEFIO_TAG_E__PD10 DEFIO_TAG_E__NONE +# define DEFIO_REC__PD10 defio_error_PD10_is_not_supported_on_TARGET +#endif +#if DEFIO_PORT_D_USED_MASK & BIT(11) +# define DEFIO_TAG__PD11 DEFIO_TAG_MAKE(DEFIO_GPIOID__D, 11) +# define DEFIO_TAG_E__PD11 DEFIO_TAG_MAKE(DEFIO_GPIOID__D, 11) +# define DEFIO_REC__PD11 DEFIO_REC_INDEXED(BITCOUNT(DEFIO_PORT_D_USED_MASK & (BIT(11) - 1)) + DEFIO_PORT_A_USED_COUNT+DEFIO_PORT_B_USED_COUNT+DEFIO_PORT_C_USED_COUNT) +#else +# define DEFIO_TAG__PD11 defio_error_PD11_is_not_supported_on_TARGET +# define DEFIO_TAG_E__PD11 DEFIO_TAG_E__NONE +# define DEFIO_REC__PD11 defio_error_PD11_is_not_supported_on_TARGET +#endif +#if DEFIO_PORT_D_USED_MASK & BIT(12) +# define DEFIO_TAG__PD12 DEFIO_TAG_MAKE(DEFIO_GPIOID__D, 12) +# define DEFIO_TAG_E__PD12 DEFIO_TAG_MAKE(DEFIO_GPIOID__D, 12) +# define DEFIO_REC__PD12 DEFIO_REC_INDEXED(BITCOUNT(DEFIO_PORT_D_USED_MASK & (BIT(12) - 1)) + DEFIO_PORT_A_USED_COUNT+DEFIO_PORT_B_USED_COUNT+DEFIO_PORT_C_USED_COUNT) +#else +# define DEFIO_TAG__PD12 defio_error_PD12_is_not_supported_on_TARGET +# define DEFIO_TAG_E__PD12 DEFIO_TAG_E__NONE +# define DEFIO_REC__PD12 defio_error_PD12_is_not_supported_on_TARGET +#endif +#if DEFIO_PORT_D_USED_MASK & BIT(13) +# define DEFIO_TAG__PD13 DEFIO_TAG_MAKE(DEFIO_GPIOID__D, 13) +# define DEFIO_TAG_E__PD13 DEFIO_TAG_MAKE(DEFIO_GPIOID__D, 13) +# define DEFIO_REC__PD13 DEFIO_REC_INDEXED(BITCOUNT(DEFIO_PORT_D_USED_MASK & (BIT(13) - 1)) + DEFIO_PORT_A_USED_COUNT+DEFIO_PORT_B_USED_COUNT+DEFIO_PORT_C_USED_COUNT) +#else +# define DEFIO_TAG__PD13 defio_error_PD13_is_not_supported_on_TARGET +# define DEFIO_TAG_E__PD13 DEFIO_TAG_E__NONE +# define DEFIO_REC__PD13 defio_error_PD13_is_not_supported_on_TARGET +#endif +#if DEFIO_PORT_D_USED_MASK & BIT(14) +# define DEFIO_TAG__PD14 DEFIO_TAG_MAKE(DEFIO_GPIOID__D, 14) +# define DEFIO_TAG_E__PD14 DEFIO_TAG_MAKE(DEFIO_GPIOID__D, 14) +# define DEFIO_REC__PD14 DEFIO_REC_INDEXED(BITCOUNT(DEFIO_PORT_D_USED_MASK & (BIT(14) - 1)) + DEFIO_PORT_A_USED_COUNT+DEFIO_PORT_B_USED_COUNT+DEFIO_PORT_C_USED_COUNT) +#else +# define DEFIO_TAG__PD14 defio_error_PD14_is_not_supported_on_TARGET +# define DEFIO_TAG_E__PD14 DEFIO_TAG_E__NONE +# define DEFIO_REC__PD14 defio_error_PD14_is_not_supported_on_TARGET +#endif +#if DEFIO_PORT_D_USED_MASK & BIT(15) +# define DEFIO_TAG__PD15 DEFIO_TAG_MAKE(DEFIO_GPIOID__D, 15) +# define DEFIO_TAG_E__PD15 DEFIO_TAG_MAKE(DEFIO_GPIOID__D, 15) +# define DEFIO_REC__PD15 DEFIO_REC_INDEXED(BITCOUNT(DEFIO_PORT_D_USED_MASK & (BIT(15) - 1)) + DEFIO_PORT_A_USED_COUNT+DEFIO_PORT_B_USED_COUNT+DEFIO_PORT_C_USED_COUNT) +#else +# define DEFIO_TAG__PD15 defio_error_PD15_is_not_supported_on_TARGET +# define DEFIO_TAG_E__PD15 DEFIO_TAG_E__NONE +# define DEFIO_REC__PD15 defio_error_PD15_is_not_supported_on_TARGET +#endif +#if DEFIO_PORT_E_USED_MASK & BIT(0) +# define DEFIO_TAG__PE0 DEFIO_TAG_MAKE(DEFIO_GPIOID__E, 0) +# define DEFIO_TAG_E__PE0 DEFIO_TAG_MAKE(DEFIO_GPIOID__E, 0) +# define DEFIO_REC__PE0 DEFIO_REC_INDEXED(BITCOUNT(DEFIO_PORT_E_USED_MASK & (BIT(0) - 1)) + DEFIO_PORT_A_USED_COUNT+DEFIO_PORT_B_USED_COUNT+DEFIO_PORT_C_USED_COUNT+DEFIO_PORT_D_USED_COUNT) +#else +# define DEFIO_TAG__PE0 defio_error_PE0_is_not_supported_on_TARGET +# define DEFIO_TAG_E__PE0 DEFIO_TAG_E__NONE +# define DEFIO_REC__PE0 defio_error_PE0_is_not_supported_on_TARGET +#endif +#if DEFIO_PORT_E_USED_MASK & BIT(1) +# define DEFIO_TAG__PE1 DEFIO_TAG_MAKE(DEFIO_GPIOID__E, 1) +# define DEFIO_TAG_E__PE1 DEFIO_TAG_MAKE(DEFIO_GPIOID__E, 1) +# define DEFIO_REC__PE1 DEFIO_REC_INDEXED(BITCOUNT(DEFIO_PORT_E_USED_MASK & (BIT(1) - 1)) + DEFIO_PORT_A_USED_COUNT+DEFIO_PORT_B_USED_COUNT+DEFIO_PORT_C_USED_COUNT+DEFIO_PORT_D_USED_COUNT) +#else +# define DEFIO_TAG__PE1 defio_error_PE1_is_not_supported_on_TARGET +# define DEFIO_TAG_E__PE1 DEFIO_TAG_E__NONE +# define DEFIO_REC__PE1 defio_error_PE1_is_not_supported_on_TARGET +#endif +#if DEFIO_PORT_E_USED_MASK & BIT(2) +# define DEFIO_TAG__PE2 DEFIO_TAG_MAKE(DEFIO_GPIOID__E, 2) +# define DEFIO_TAG_E__PE2 DEFIO_TAG_MAKE(DEFIO_GPIOID__E, 2) +# define DEFIO_REC__PE2 DEFIO_REC_INDEXED(BITCOUNT(DEFIO_PORT_E_USED_MASK & (BIT(2) - 1)) + DEFIO_PORT_A_USED_COUNT+DEFIO_PORT_B_USED_COUNT+DEFIO_PORT_C_USED_COUNT+DEFIO_PORT_D_USED_COUNT) +#else +# define DEFIO_TAG__PE2 defio_error_PE2_is_not_supported_on_TARGET +# define DEFIO_TAG_E__PE2 DEFIO_TAG_E__NONE +# define DEFIO_REC__PE2 defio_error_PE2_is_not_supported_on_TARGET +#endif +#if DEFIO_PORT_E_USED_MASK & BIT(3) +# define DEFIO_TAG__PE3 DEFIO_TAG_MAKE(DEFIO_GPIOID__E, 3) +# define DEFIO_TAG_E__PE3 DEFIO_TAG_MAKE(DEFIO_GPIOID__E, 3) +# define DEFIO_REC__PE3 DEFIO_REC_INDEXED(BITCOUNT(DEFIO_PORT_E_USED_MASK & (BIT(3) - 1)) + DEFIO_PORT_A_USED_COUNT+DEFIO_PORT_B_USED_COUNT+DEFIO_PORT_C_USED_COUNT+DEFIO_PORT_D_USED_COUNT) +#else +# define DEFIO_TAG__PE3 defio_error_PE3_is_not_supported_on_TARGET +# define DEFIO_TAG_E__PE3 DEFIO_TAG_E__NONE +# define DEFIO_REC__PE3 defio_error_PE3_is_not_supported_on_TARGET +#endif +#if DEFIO_PORT_E_USED_MASK & BIT(4) +# define DEFIO_TAG__PE4 DEFIO_TAG_MAKE(DEFIO_GPIOID__E, 4) +# define DEFIO_TAG_E__PE4 DEFIO_TAG_MAKE(DEFIO_GPIOID__E, 4) +# define DEFIO_REC__PE4 DEFIO_REC_INDEXED(BITCOUNT(DEFIO_PORT_E_USED_MASK & (BIT(4) - 1)) + DEFIO_PORT_A_USED_COUNT+DEFIO_PORT_B_USED_COUNT+DEFIO_PORT_C_USED_COUNT+DEFIO_PORT_D_USED_COUNT) +#else +# define DEFIO_TAG__PE4 defio_error_PE4_is_not_supported_on_TARGET +# define DEFIO_TAG_E__PE4 DEFIO_TAG_E__NONE +# define DEFIO_REC__PE4 defio_error_PE4_is_not_supported_on_TARGET +#endif +#if DEFIO_PORT_E_USED_MASK & BIT(5) +# define DEFIO_TAG__PE5 DEFIO_TAG_MAKE(DEFIO_GPIOID__E, 5) +# define DEFIO_TAG_E__PE5 DEFIO_TAG_MAKE(DEFIO_GPIOID__E, 5) +# define DEFIO_REC__PE5 DEFIO_REC_INDEXED(BITCOUNT(DEFIO_PORT_E_USED_MASK & (BIT(5) - 1)) + DEFIO_PORT_A_USED_COUNT+DEFIO_PORT_B_USED_COUNT+DEFIO_PORT_C_USED_COUNT+DEFIO_PORT_D_USED_COUNT) +#else +# define DEFIO_TAG__PE5 defio_error_PE5_is_not_supported_on_TARGET +# define DEFIO_TAG_E__PE5 DEFIO_TAG_E__NONE +# define DEFIO_REC__PE5 defio_error_PE5_is_not_supported_on_TARGET +#endif +#if DEFIO_PORT_E_USED_MASK & BIT(6) +# define DEFIO_TAG__PE6 DEFIO_TAG_MAKE(DEFIO_GPIOID__E, 6) +# define DEFIO_TAG_E__PE6 DEFIO_TAG_MAKE(DEFIO_GPIOID__E, 6) +# define DEFIO_REC__PE6 DEFIO_REC_INDEXED(BITCOUNT(DEFIO_PORT_E_USED_MASK & (BIT(6) - 1)) + DEFIO_PORT_A_USED_COUNT+DEFIO_PORT_B_USED_COUNT+DEFIO_PORT_C_USED_COUNT+DEFIO_PORT_D_USED_COUNT) +#else +# define DEFIO_TAG__PE6 defio_error_PE6_is_not_supported_on_TARGET +# define DEFIO_TAG_E__PE6 DEFIO_TAG_E__NONE +# define DEFIO_REC__PE6 defio_error_PE6_is_not_supported_on_TARGET +#endif +#if DEFIO_PORT_E_USED_MASK & BIT(7) +# define DEFIO_TAG__PE7 DEFIO_TAG_MAKE(DEFIO_GPIOID__E, 7) +# define DEFIO_TAG_E__PE7 DEFIO_TAG_MAKE(DEFIO_GPIOID__E, 7) +# define DEFIO_REC__PE7 DEFIO_REC_INDEXED(BITCOUNT(DEFIO_PORT_E_USED_MASK & (BIT(7) - 1)) + DEFIO_PORT_A_USED_COUNT+DEFIO_PORT_B_USED_COUNT+DEFIO_PORT_C_USED_COUNT+DEFIO_PORT_D_USED_COUNT) +#else +# define DEFIO_TAG__PE7 defio_error_PE7_is_not_supported_on_TARGET +# define DEFIO_TAG_E__PE7 DEFIO_TAG_E__NONE +# define DEFIO_REC__PE7 defio_error_PE7_is_not_supported_on_TARGET +#endif +#if DEFIO_PORT_E_USED_MASK & BIT(8) +# define DEFIO_TAG__PE8 DEFIO_TAG_MAKE(DEFIO_GPIOID__E, 8) +# define DEFIO_TAG_E__PE8 DEFIO_TAG_MAKE(DEFIO_GPIOID__E, 8) +# define DEFIO_REC__PE8 DEFIO_REC_INDEXED(BITCOUNT(DEFIO_PORT_E_USED_MASK & (BIT(8) - 1)) + DEFIO_PORT_A_USED_COUNT+DEFIO_PORT_B_USED_COUNT+DEFIO_PORT_C_USED_COUNT+DEFIO_PORT_D_USED_COUNT) +#else +# define DEFIO_TAG__PE8 defio_error_PE8_is_not_supported_on_TARGET +# define DEFIO_TAG_E__PE8 DEFIO_TAG_E__NONE +# define DEFIO_REC__PE8 defio_error_PE8_is_not_supported_on_TARGET +#endif +#if DEFIO_PORT_E_USED_MASK & BIT(9) +# define DEFIO_TAG__PE9 DEFIO_TAG_MAKE(DEFIO_GPIOID__E, 9) +# define DEFIO_TAG_E__PE9 DEFIO_TAG_MAKE(DEFIO_GPIOID__E, 9) +# define DEFIO_REC__PE9 DEFIO_REC_INDEXED(BITCOUNT(DEFIO_PORT_E_USED_MASK & (BIT(9) - 1)) + DEFIO_PORT_A_USED_COUNT+DEFIO_PORT_B_USED_COUNT+DEFIO_PORT_C_USED_COUNT+DEFIO_PORT_D_USED_COUNT) +#else +# define DEFIO_TAG__PE9 defio_error_PE9_is_not_supported_on_TARGET +# define DEFIO_TAG_E__PE9 DEFIO_TAG_E__NONE +# define DEFIO_REC__PE9 defio_error_PE9_is_not_supported_on_TARGET +#endif +#if DEFIO_PORT_E_USED_MASK & BIT(10) +# define DEFIO_TAG__PE10 DEFIO_TAG_MAKE(DEFIO_GPIOID__E, 10) +# define DEFIO_TAG_E__PE10 DEFIO_TAG_MAKE(DEFIO_GPIOID__E, 10) +# define DEFIO_REC__PE10 DEFIO_REC_INDEXED(BITCOUNT(DEFIO_PORT_E_USED_MASK & (BIT(10) - 1)) + DEFIO_PORT_A_USED_COUNT+DEFIO_PORT_B_USED_COUNT+DEFIO_PORT_C_USED_COUNT+DEFIO_PORT_D_USED_COUNT) +#else +# define DEFIO_TAG__PE10 defio_error_PE10_is_not_supported_on_TARGET +# define DEFIO_TAG_E__PE10 DEFIO_TAG_E__NONE +# define DEFIO_REC__PE10 defio_error_PE10_is_not_supported_on_TARGET +#endif +#if DEFIO_PORT_E_USED_MASK & BIT(11) +# define DEFIO_TAG__PE11 DEFIO_TAG_MAKE(DEFIO_GPIOID__E, 11) +# define DEFIO_TAG_E__PE11 DEFIO_TAG_MAKE(DEFIO_GPIOID__E, 11) +# define DEFIO_REC__PE11 DEFIO_REC_INDEXED(BITCOUNT(DEFIO_PORT_E_USED_MASK & (BIT(11) - 1)) + DEFIO_PORT_A_USED_COUNT+DEFIO_PORT_B_USED_COUNT+DEFIO_PORT_C_USED_COUNT+DEFIO_PORT_D_USED_COUNT) +#else +# define DEFIO_TAG__PE11 defio_error_PE11_is_not_supported_on_TARGET +# define DEFIO_TAG_E__PE11 DEFIO_TAG_E__NONE +# define DEFIO_REC__PE11 defio_error_PE11_is_not_supported_on_TARGET +#endif +#if DEFIO_PORT_E_USED_MASK & BIT(12) +# define DEFIO_TAG__PE12 DEFIO_TAG_MAKE(DEFIO_GPIOID__E, 12) +# define DEFIO_TAG_E__PE12 DEFIO_TAG_MAKE(DEFIO_GPIOID__E, 12) +# define DEFIO_REC__PE12 DEFIO_REC_INDEXED(BITCOUNT(DEFIO_PORT_E_USED_MASK & (BIT(12) - 1)) + DEFIO_PORT_A_USED_COUNT+DEFIO_PORT_B_USED_COUNT+DEFIO_PORT_C_USED_COUNT+DEFIO_PORT_D_USED_COUNT) +#else +# define DEFIO_TAG__PE12 defio_error_PE12_is_not_supported_on_TARGET +# define DEFIO_TAG_E__PE12 DEFIO_TAG_E__NONE +# define DEFIO_REC__PE12 defio_error_PE12_is_not_supported_on_TARGET +#endif +#if DEFIO_PORT_E_USED_MASK & BIT(13) +# define DEFIO_TAG__PE13 DEFIO_TAG_MAKE(DEFIO_GPIOID__E, 13) +# define DEFIO_TAG_E__PE13 DEFIO_TAG_MAKE(DEFIO_GPIOID__E, 13) +# define DEFIO_REC__PE13 DEFIO_REC_INDEXED(BITCOUNT(DEFIO_PORT_E_USED_MASK & (BIT(13) - 1)) + DEFIO_PORT_A_USED_COUNT+DEFIO_PORT_B_USED_COUNT+DEFIO_PORT_C_USED_COUNT+DEFIO_PORT_D_USED_COUNT) +#else +# define DEFIO_TAG__PE13 defio_error_PE13_is_not_supported_on_TARGET +# define DEFIO_TAG_E__PE13 DEFIO_TAG_E__NONE +# define DEFIO_REC__PE13 defio_error_PE13_is_not_supported_on_TARGET +#endif +#if DEFIO_PORT_E_USED_MASK & BIT(14) +# define DEFIO_TAG__PE14 DEFIO_TAG_MAKE(DEFIO_GPIOID__E, 14) +# define DEFIO_TAG_E__PE14 DEFIO_TAG_MAKE(DEFIO_GPIOID__E, 14) +# define DEFIO_REC__PE14 DEFIO_REC_INDEXED(BITCOUNT(DEFIO_PORT_E_USED_MASK & (BIT(14) - 1)) + DEFIO_PORT_A_USED_COUNT+DEFIO_PORT_B_USED_COUNT+DEFIO_PORT_C_USED_COUNT+DEFIO_PORT_D_USED_COUNT) +#else +# define DEFIO_TAG__PE14 defio_error_PE14_is_not_supported_on_TARGET +# define DEFIO_TAG_E__PE14 DEFIO_TAG_E__NONE +# define DEFIO_REC__PE14 defio_error_PE14_is_not_supported_on_TARGET +#endif +#if DEFIO_PORT_E_USED_MASK & BIT(15) +# define DEFIO_TAG__PE15 DEFIO_TAG_MAKE(DEFIO_GPIOID__E, 15) +# define DEFIO_TAG_E__PE15 DEFIO_TAG_MAKE(DEFIO_GPIOID__E, 15) +# define DEFIO_REC__PE15 DEFIO_REC_INDEXED(BITCOUNT(DEFIO_PORT_E_USED_MASK & (BIT(15) - 1)) + DEFIO_PORT_A_USED_COUNT+DEFIO_PORT_B_USED_COUNT+DEFIO_PORT_C_USED_COUNT+DEFIO_PORT_D_USED_COUNT) +#else +# define DEFIO_TAG__PE15 defio_error_PE15_is_not_supported_on_TARGET +# define DEFIO_TAG_E__PE15 DEFIO_TAG_E__NONE +# define DEFIO_REC__PE15 defio_error_PE15_is_not_supported_on_TARGET +#endif +#if DEFIO_PORT_F_USED_MASK & BIT(0) +# define DEFIO_TAG__PF0 DEFIO_TAG_MAKE(DEFIO_GPIOID__F, 0) +# define DEFIO_TAG_E__PF0 DEFIO_TAG_MAKE(DEFIO_GPIOID__F, 0) +# define DEFIO_REC__PF0 DEFIO_REC_INDEXED(BITCOUNT(DEFIO_PORT_F_USED_MASK & (BIT(0) - 1)) + DEFIO_PORT_A_USED_COUNT+DEFIO_PORT_B_USED_COUNT+DEFIO_PORT_C_USED_COUNT+DEFIO_PORT_D_USED_COUNT+DEFIO_PORT_E_USED_COUNT) +#else +# define DEFIO_TAG__PF0 defio_error_PF0_is_not_supported_on_TARGET +# define DEFIO_TAG_E__PF0 DEFIO_TAG_E__NONE +# define DEFIO_REC__PF0 defio_error_PF0_is_not_supported_on_TARGET +#endif +#if DEFIO_PORT_F_USED_MASK & BIT(1) +# define DEFIO_TAG__PF1 DEFIO_TAG_MAKE(DEFIO_GPIOID__F, 1) +# define DEFIO_TAG_E__PF1 DEFIO_TAG_MAKE(DEFIO_GPIOID__F, 1) +# define DEFIO_REC__PF1 DEFIO_REC_INDEXED(BITCOUNT(DEFIO_PORT_F_USED_MASK & (BIT(1) - 1)) + DEFIO_PORT_A_USED_COUNT+DEFIO_PORT_B_USED_COUNT+DEFIO_PORT_C_USED_COUNT+DEFIO_PORT_D_USED_COUNT+DEFIO_PORT_E_USED_COUNT) +#else +# define DEFIO_TAG__PF1 defio_error_PF1_is_not_supported_on_TARGET +# define DEFIO_TAG_E__PF1 DEFIO_TAG_E__NONE +# define DEFIO_REC__PF1 defio_error_PF1_is_not_supported_on_TARGET +#endif +#if DEFIO_PORT_F_USED_MASK & BIT(2) +# define DEFIO_TAG__PF2 DEFIO_TAG_MAKE(DEFIO_GPIOID__F, 2) +# define DEFIO_TAG_E__PF2 DEFIO_TAG_MAKE(DEFIO_GPIOID__F, 2) +# define DEFIO_REC__PF2 DEFIO_REC_INDEXED(BITCOUNT(DEFIO_PORT_F_USED_MASK & (BIT(2) - 1)) + DEFIO_PORT_A_USED_COUNT+DEFIO_PORT_B_USED_COUNT+DEFIO_PORT_C_USED_COUNT+DEFIO_PORT_D_USED_COUNT+DEFIO_PORT_E_USED_COUNT) +#else +# define DEFIO_TAG__PF2 defio_error_PF2_is_not_supported_on_TARGET +# define DEFIO_TAG_E__PF2 DEFIO_TAG_E__NONE +# define DEFIO_REC__PF2 defio_error_PF2_is_not_supported_on_TARGET +#endif +#if DEFIO_PORT_F_USED_MASK & BIT(3) +# define DEFIO_TAG__PF3 DEFIO_TAG_MAKE(DEFIO_GPIOID__F, 3) +# define DEFIO_TAG_E__PF3 DEFIO_TAG_MAKE(DEFIO_GPIOID__F, 3) +# define DEFIO_REC__PF3 DEFIO_REC_INDEXED(BITCOUNT(DEFIO_PORT_F_USED_MASK & (BIT(3) - 1)) + DEFIO_PORT_A_USED_COUNT+DEFIO_PORT_B_USED_COUNT+DEFIO_PORT_C_USED_COUNT+DEFIO_PORT_D_USED_COUNT+DEFIO_PORT_E_USED_COUNT) +#else +# define DEFIO_TAG__PF3 defio_error_PF3_is_not_supported_on_TARGET +# define DEFIO_TAG_E__PF3 DEFIO_TAG_E__NONE +# define DEFIO_REC__PF3 defio_error_PF3_is_not_supported_on_TARGET +#endif +#if DEFIO_PORT_F_USED_MASK & BIT(4) +# define DEFIO_TAG__PF4 DEFIO_TAG_MAKE(DEFIO_GPIOID__F, 4) +# define DEFIO_TAG_E__PF4 DEFIO_TAG_MAKE(DEFIO_GPIOID__F, 4) +# define DEFIO_REC__PF4 DEFIO_REC_INDEXED(BITCOUNT(DEFIO_PORT_F_USED_MASK & (BIT(4) - 1)) + DEFIO_PORT_A_USED_COUNT+DEFIO_PORT_B_USED_COUNT+DEFIO_PORT_C_USED_COUNT+DEFIO_PORT_D_USED_COUNT+DEFIO_PORT_E_USED_COUNT) +#else +# define DEFIO_TAG__PF4 defio_error_PF4_is_not_supported_on_TARGET +# define DEFIO_TAG_E__PF4 DEFIO_TAG_E__NONE +# define DEFIO_REC__PF4 defio_error_PF4_is_not_supported_on_TARGET +#endif +#if DEFIO_PORT_F_USED_MASK & BIT(5) +# define DEFIO_TAG__PF5 DEFIO_TAG_MAKE(DEFIO_GPIOID__F, 5) +# define DEFIO_TAG_E__PF5 DEFIO_TAG_MAKE(DEFIO_GPIOID__F, 5) +# define DEFIO_REC__PF5 DEFIO_REC_INDEXED(BITCOUNT(DEFIO_PORT_F_USED_MASK & (BIT(5) - 1)) + DEFIO_PORT_A_USED_COUNT+DEFIO_PORT_B_USED_COUNT+DEFIO_PORT_C_USED_COUNT+DEFIO_PORT_D_USED_COUNT+DEFIO_PORT_E_USED_COUNT) +#else +# define DEFIO_TAG__PF5 defio_error_PF5_is_not_supported_on_TARGET +# define DEFIO_TAG_E__PF5 DEFIO_TAG_E__NONE +# define DEFIO_REC__PF5 defio_error_PF5_is_not_supported_on_TARGET +#endif +#if DEFIO_PORT_F_USED_MASK & BIT(6) +# define DEFIO_TAG__PF6 DEFIO_TAG_MAKE(DEFIO_GPIOID__F, 6) +# define DEFIO_TAG_E__PF6 DEFIO_TAG_MAKE(DEFIO_GPIOID__F, 6) +# define DEFIO_REC__PF6 DEFIO_REC_INDEXED(BITCOUNT(DEFIO_PORT_F_USED_MASK & (BIT(6) - 1)) + DEFIO_PORT_A_USED_COUNT+DEFIO_PORT_B_USED_COUNT+DEFIO_PORT_C_USED_COUNT+DEFIO_PORT_D_USED_COUNT+DEFIO_PORT_E_USED_COUNT) +#else +# define DEFIO_TAG__PF6 defio_error_PF6_is_not_supported_on_TARGET +# define DEFIO_TAG_E__PF6 DEFIO_TAG_E__NONE +# define DEFIO_REC__PF6 defio_error_PF6_is_not_supported_on_TARGET +#endif +#if DEFIO_PORT_F_USED_MASK & BIT(7) +# define DEFIO_TAG__PF7 DEFIO_TAG_MAKE(DEFIO_GPIOID__F, 7) +# define DEFIO_TAG_E__PF7 DEFIO_TAG_MAKE(DEFIO_GPIOID__F, 7) +# define DEFIO_REC__PF7 DEFIO_REC_INDEXED(BITCOUNT(DEFIO_PORT_F_USED_MASK & (BIT(7) - 1)) + DEFIO_PORT_A_USED_COUNT+DEFIO_PORT_B_USED_COUNT+DEFIO_PORT_C_USED_COUNT+DEFIO_PORT_D_USED_COUNT+DEFIO_PORT_E_USED_COUNT) +#else +# define DEFIO_TAG__PF7 defio_error_PF7_is_not_supported_on_TARGET +# define DEFIO_TAG_E__PF7 DEFIO_TAG_E__NONE +# define DEFIO_REC__PF7 defio_error_PF7_is_not_supported_on_TARGET +#endif +#if DEFIO_PORT_F_USED_MASK & BIT(8) +# define DEFIO_TAG__PF8 DEFIO_TAG_MAKE(DEFIO_GPIOID__F, 8) +# define DEFIO_TAG_E__PF8 DEFIO_TAG_MAKE(DEFIO_GPIOID__F, 8) +# define DEFIO_REC__PF8 DEFIO_REC_INDEXED(BITCOUNT(DEFIO_PORT_F_USED_MASK & (BIT(8) - 1)) + DEFIO_PORT_A_USED_COUNT+DEFIO_PORT_B_USED_COUNT+DEFIO_PORT_C_USED_COUNT+DEFIO_PORT_D_USED_COUNT+DEFIO_PORT_E_USED_COUNT) +#else +# define DEFIO_TAG__PF8 defio_error_PF8_is_not_supported_on_TARGET +# define DEFIO_TAG_E__PF8 DEFIO_TAG_E__NONE +# define DEFIO_REC__PF8 defio_error_PF8_is_not_supported_on_TARGET +#endif +#if DEFIO_PORT_F_USED_MASK & BIT(9) +# define DEFIO_TAG__PF9 DEFIO_TAG_MAKE(DEFIO_GPIOID__F, 9) +# define DEFIO_TAG_E__PF9 DEFIO_TAG_MAKE(DEFIO_GPIOID__F, 9) +# define DEFIO_REC__PF9 DEFIO_REC_INDEXED(BITCOUNT(DEFIO_PORT_F_USED_MASK & (BIT(9) - 1)) + DEFIO_PORT_A_USED_COUNT+DEFIO_PORT_B_USED_COUNT+DEFIO_PORT_C_USED_COUNT+DEFIO_PORT_D_USED_COUNT+DEFIO_PORT_E_USED_COUNT) +#else +# define DEFIO_TAG__PF9 defio_error_PF9_is_not_supported_on_TARGET +# define DEFIO_TAG_E__PF9 DEFIO_TAG_E__NONE +# define DEFIO_REC__PF9 defio_error_PF9_is_not_supported_on_TARGET +#endif +#if DEFIO_PORT_F_USED_MASK & BIT(10) +# define DEFIO_TAG__PF10 DEFIO_TAG_MAKE(DEFIO_GPIOID__F, 10) +# define DEFIO_TAG_E__PF10 DEFIO_TAG_MAKE(DEFIO_GPIOID__F, 10) +# define DEFIO_REC__PF10 DEFIO_REC_INDEXED(BITCOUNT(DEFIO_PORT_F_USED_MASK & (BIT(10) - 1)) + DEFIO_PORT_A_USED_COUNT+DEFIO_PORT_B_USED_COUNT+DEFIO_PORT_C_USED_COUNT+DEFIO_PORT_D_USED_COUNT+DEFIO_PORT_E_USED_COUNT) +#else +# define DEFIO_TAG__PF10 defio_error_PF10_is_not_supported_on_TARGET +# define DEFIO_TAG_E__PF10 DEFIO_TAG_E__NONE +# define DEFIO_REC__PF10 defio_error_PF10_is_not_supported_on_TARGET +#endif +#if DEFIO_PORT_F_USED_MASK & BIT(11) +# define DEFIO_TAG__PF11 DEFIO_TAG_MAKE(DEFIO_GPIOID__F, 11) +# define DEFIO_TAG_E__PF11 DEFIO_TAG_MAKE(DEFIO_GPIOID__F, 11) +# define DEFIO_REC__PF11 DEFIO_REC_INDEXED(BITCOUNT(DEFIO_PORT_F_USED_MASK & (BIT(11) - 1)) + DEFIO_PORT_A_USED_COUNT+DEFIO_PORT_B_USED_COUNT+DEFIO_PORT_C_USED_COUNT+DEFIO_PORT_D_USED_COUNT+DEFIO_PORT_E_USED_COUNT) +#else +# define DEFIO_TAG__PF11 defio_error_PF11_is_not_supported_on_TARGET +# define DEFIO_TAG_E__PF11 DEFIO_TAG_E__NONE +# define DEFIO_REC__PF11 defio_error_PF11_is_not_supported_on_TARGET +#endif +#if DEFIO_PORT_F_USED_MASK & BIT(12) +# define DEFIO_TAG__PF12 DEFIO_TAG_MAKE(DEFIO_GPIOID__F, 12) +# define DEFIO_TAG_E__PF12 DEFIO_TAG_MAKE(DEFIO_GPIOID__F, 12) +# define DEFIO_REC__PF12 DEFIO_REC_INDEXED(BITCOUNT(DEFIO_PORT_F_USED_MASK & (BIT(12) - 1)) + DEFIO_PORT_A_USED_COUNT+DEFIO_PORT_B_USED_COUNT+DEFIO_PORT_C_USED_COUNT+DEFIO_PORT_D_USED_COUNT+DEFIO_PORT_E_USED_COUNT) +#else +# define DEFIO_TAG__PF12 defio_error_PF12_is_not_supported_on_TARGET +# define DEFIO_TAG_E__PF12 DEFIO_TAG_E__NONE +# define DEFIO_REC__PF12 defio_error_PF12_is_not_supported_on_TARGET +#endif +#if DEFIO_PORT_F_USED_MASK & BIT(13) +# define DEFIO_TAG__PF13 DEFIO_TAG_MAKE(DEFIO_GPIOID__F, 13) +# define DEFIO_TAG_E__PF13 DEFIO_TAG_MAKE(DEFIO_GPIOID__F, 13) +# define DEFIO_REC__PF13 DEFIO_REC_INDEXED(BITCOUNT(DEFIO_PORT_F_USED_MASK & (BIT(13) - 1)) + DEFIO_PORT_A_USED_COUNT+DEFIO_PORT_B_USED_COUNT+DEFIO_PORT_C_USED_COUNT+DEFIO_PORT_D_USED_COUNT+DEFIO_PORT_E_USED_COUNT) +#else +# define DEFIO_TAG__PF13 defio_error_PF13_is_not_supported_on_TARGET +# define DEFIO_TAG_E__PF13 DEFIO_TAG_E__NONE +# define DEFIO_REC__PF13 defio_error_PF13_is_not_supported_on_TARGET +#endif +#if DEFIO_PORT_F_USED_MASK & BIT(14) +# define DEFIO_TAG__PF14 DEFIO_TAG_MAKE(DEFIO_GPIOID__F, 14) +# define DEFIO_TAG_E__PF14 DEFIO_TAG_MAKE(DEFIO_GPIOID__F, 14) +# define DEFIO_REC__PF14 DEFIO_REC_INDEXED(BITCOUNT(DEFIO_PORT_F_USED_MASK & (BIT(14) - 1)) + DEFIO_PORT_A_USED_COUNT+DEFIO_PORT_B_USED_COUNT+DEFIO_PORT_C_USED_COUNT+DEFIO_PORT_D_USED_COUNT+DEFIO_PORT_E_USED_COUNT) +#else +# define DEFIO_TAG__PF14 defio_error_PF14_is_not_supported_on_TARGET +# define DEFIO_TAG_E__PF14 DEFIO_TAG_E__NONE +# define DEFIO_REC__PF14 defio_error_PF14_is_not_supported_on_TARGET +#endif +#if DEFIO_PORT_F_USED_MASK & BIT(15) +# define DEFIO_TAG__PF15 DEFIO_TAG_MAKE(DEFIO_GPIOID__F, 15) +# define DEFIO_TAG_E__PF15 DEFIO_TAG_MAKE(DEFIO_GPIOID__F, 15) +# define DEFIO_REC__PF15 DEFIO_REC_INDEXED(BITCOUNT(DEFIO_PORT_F_USED_MASK & (BIT(15) - 1)) + DEFIO_PORT_A_USED_COUNT+DEFIO_PORT_B_USED_COUNT+DEFIO_PORT_C_USED_COUNT+DEFIO_PORT_D_USED_COUNT+DEFIO_PORT_E_USED_COUNT) +#else +# define DEFIO_TAG__PF15 defio_error_PF15_is_not_supported_on_TARGET +# define DEFIO_TAG_E__PF15 DEFIO_TAG_E__NONE +# define DEFIO_REC__PF15 defio_error_PF15_is_not_supported_on_TARGET +#endif +#if DEFIO_PORT_G_USED_MASK & BIT(0) +# define DEFIO_TAG__PG0 DEFIO_TAG_MAKE(DEFIO_GPIOID__G, 0) +# define DEFIO_TAG_E__PG0 DEFIO_TAG_MAKE(DEFIO_GPIOID__G, 0) +# define DEFIO_REC__PG0 DEFIO_REC_INDEXED(BITCOUNT(DEFIO_PORT_G_USED_MASK & (BIT(0) - 1)) + DEFIO_PORT_A_USED_COUNT+DEFIO_PORT_B_USED_COUNT+DEFIO_PORT_C_USED_COUNT+DEFIO_PORT_D_USED_COUNT+DEFIO_PORT_E_USED_COUNT+DEFIO_PORT_F_USED_COUNT) +#else +# define DEFIO_TAG__PG0 defio_error_PG0_is_not_supported_on_TARGET +# define DEFIO_TAG_E__PG0 DEFIO_TAG_E__NONE +# define DEFIO_REC__PG0 defio_error_PG0_is_not_supported_on_TARGET +#endif +#if DEFIO_PORT_G_USED_MASK & BIT(1) +# define DEFIO_TAG__PG1 DEFIO_TAG_MAKE(DEFIO_GPIOID__G, 1) +# define DEFIO_TAG_E__PG1 DEFIO_TAG_MAKE(DEFIO_GPIOID__G, 1) +# define DEFIO_REC__PG1 DEFIO_REC_INDEXED(BITCOUNT(DEFIO_PORT_G_USED_MASK & (BIT(1) - 1)) + DEFIO_PORT_A_USED_COUNT+DEFIO_PORT_B_USED_COUNT+DEFIO_PORT_C_USED_COUNT+DEFIO_PORT_D_USED_COUNT+DEFIO_PORT_E_USED_COUNT+DEFIO_PORT_F_USED_COUNT) +#else +# define DEFIO_TAG__PG1 defio_error_PG1_is_not_supported_on_TARGET +# define DEFIO_TAG_E__PG1 DEFIO_TAG_E__NONE +# define DEFIO_REC__PG1 defio_error_PG1_is_not_supported_on_TARGET +#endif +#if DEFIO_PORT_G_USED_MASK & BIT(2) +# define DEFIO_TAG__PG2 DEFIO_TAG_MAKE(DEFIO_GPIOID__G, 2) +# define DEFIO_TAG_E__PG2 DEFIO_TAG_MAKE(DEFIO_GPIOID__G, 2) +# define DEFIO_REC__PG2 DEFIO_REC_INDEXED(BITCOUNT(DEFIO_PORT_G_USED_MASK & (BIT(2) - 1)) + DEFIO_PORT_A_USED_COUNT+DEFIO_PORT_B_USED_COUNT+DEFIO_PORT_C_USED_COUNT+DEFIO_PORT_D_USED_COUNT+DEFIO_PORT_E_USED_COUNT+DEFIO_PORT_F_USED_COUNT) +#else +# define DEFIO_TAG__PG2 defio_error_PG2_is_not_supported_on_TARGET +# define DEFIO_TAG_E__PG2 DEFIO_TAG_E__NONE +# define DEFIO_REC__PG2 defio_error_PG2_is_not_supported_on_TARGET +#endif +#if DEFIO_PORT_G_USED_MASK & BIT(3) +# define DEFIO_TAG__PG3 DEFIO_TAG_MAKE(DEFIO_GPIOID__G, 3) +# define DEFIO_TAG_E__PG3 DEFIO_TAG_MAKE(DEFIO_GPIOID__G, 3) +# define DEFIO_REC__PG3 DEFIO_REC_INDEXED(BITCOUNT(DEFIO_PORT_G_USED_MASK & (BIT(3) - 1)) + DEFIO_PORT_A_USED_COUNT+DEFIO_PORT_B_USED_COUNT+DEFIO_PORT_C_USED_COUNT+DEFIO_PORT_D_USED_COUNT+DEFIO_PORT_E_USED_COUNT+DEFIO_PORT_F_USED_COUNT) +#else +# define DEFIO_TAG__PG3 defio_error_PG3_is_not_supported_on_TARGET +# define DEFIO_TAG_E__PG3 DEFIO_TAG_E__NONE +# define DEFIO_REC__PG3 defio_error_PG3_is_not_supported_on_TARGET +#endif +#if DEFIO_PORT_G_USED_MASK & BIT(4) +# define DEFIO_TAG__PG4 DEFIO_TAG_MAKE(DEFIO_GPIOID__G, 4) +# define DEFIO_TAG_E__PG4 DEFIO_TAG_MAKE(DEFIO_GPIOID__G, 4) +# define DEFIO_REC__PG4 DEFIO_REC_INDEXED(BITCOUNT(DEFIO_PORT_G_USED_MASK & (BIT(4) - 1)) + DEFIO_PORT_A_USED_COUNT+DEFIO_PORT_B_USED_COUNT+DEFIO_PORT_C_USED_COUNT+DEFIO_PORT_D_USED_COUNT+DEFIO_PORT_E_USED_COUNT+DEFIO_PORT_F_USED_COUNT) +#else +# define DEFIO_TAG__PG4 defio_error_PG4_is_not_supported_on_TARGET +# define DEFIO_TAG_E__PG4 DEFIO_TAG_E__NONE +# define DEFIO_REC__PG4 defio_error_PG4_is_not_supported_on_TARGET +#endif +#if DEFIO_PORT_G_USED_MASK & BIT(5) +# define DEFIO_TAG__PG5 DEFIO_TAG_MAKE(DEFIO_GPIOID__G, 5) +# define DEFIO_TAG_E__PG5 DEFIO_TAG_MAKE(DEFIO_GPIOID__G, 5) +# define DEFIO_REC__PG5 DEFIO_REC_INDEXED(BITCOUNT(DEFIO_PORT_G_USED_MASK & (BIT(5) - 1)) + DEFIO_PORT_A_USED_COUNT+DEFIO_PORT_B_USED_COUNT+DEFIO_PORT_C_USED_COUNT+DEFIO_PORT_D_USED_COUNT+DEFIO_PORT_E_USED_COUNT+DEFIO_PORT_F_USED_COUNT) +#else +# define DEFIO_TAG__PG5 defio_error_PG5_is_not_supported_on_TARGET +# define DEFIO_TAG_E__PG5 DEFIO_TAG_E__NONE +# define DEFIO_REC__PG5 defio_error_PG5_is_not_supported_on_TARGET +#endif +#if DEFIO_PORT_G_USED_MASK & BIT(6) +# define DEFIO_TAG__PG6 DEFIO_TAG_MAKE(DEFIO_GPIOID__G, 6) +# define DEFIO_TAG_E__PG6 DEFIO_TAG_MAKE(DEFIO_GPIOID__G, 6) +# define DEFIO_REC__PG6 DEFIO_REC_INDEXED(BITCOUNT(DEFIO_PORT_G_USED_MASK & (BIT(6) - 1)) + DEFIO_PORT_A_USED_COUNT+DEFIO_PORT_B_USED_COUNT+DEFIO_PORT_C_USED_COUNT+DEFIO_PORT_D_USED_COUNT+DEFIO_PORT_E_USED_COUNT+DEFIO_PORT_F_USED_COUNT) +#else +# define DEFIO_TAG__PG6 defio_error_PG6_is_not_supported_on_TARGET +# define DEFIO_TAG_E__PG6 DEFIO_TAG_E__NONE +# define DEFIO_REC__PG6 defio_error_PG6_is_not_supported_on_TARGET +#endif +#if DEFIO_PORT_G_USED_MASK & BIT(7) +# define DEFIO_TAG__PG7 DEFIO_TAG_MAKE(DEFIO_GPIOID__G, 7) +# define DEFIO_TAG_E__PG7 DEFIO_TAG_MAKE(DEFIO_GPIOID__G, 7) +# define DEFIO_REC__PG7 DEFIO_REC_INDEXED(BITCOUNT(DEFIO_PORT_G_USED_MASK & (BIT(7) - 1)) + DEFIO_PORT_A_USED_COUNT+DEFIO_PORT_B_USED_COUNT+DEFIO_PORT_C_USED_COUNT+DEFIO_PORT_D_USED_COUNT+DEFIO_PORT_E_USED_COUNT+DEFIO_PORT_F_USED_COUNT) +#else +# define DEFIO_TAG__PG7 defio_error_PG7_is_not_supported_on_TARGET +# define DEFIO_TAG_E__PG7 DEFIO_TAG_E__NONE +# define DEFIO_REC__PG7 defio_error_PG7_is_not_supported_on_TARGET +#endif +#if DEFIO_PORT_G_USED_MASK & BIT(8) +# define DEFIO_TAG__PG8 DEFIO_TAG_MAKE(DEFIO_GPIOID__G, 8) +# define DEFIO_TAG_E__PG8 DEFIO_TAG_MAKE(DEFIO_GPIOID__G, 8) +# define DEFIO_REC__PG8 DEFIO_REC_INDEXED(BITCOUNT(DEFIO_PORT_G_USED_MASK & (BIT(8) - 1)) + DEFIO_PORT_A_USED_COUNT+DEFIO_PORT_B_USED_COUNT+DEFIO_PORT_C_USED_COUNT+DEFIO_PORT_D_USED_COUNT+DEFIO_PORT_E_USED_COUNT+DEFIO_PORT_F_USED_COUNT) +#else +# define DEFIO_TAG__PG8 defio_error_PG8_is_not_supported_on_TARGET +# define DEFIO_TAG_E__PG8 DEFIO_TAG_E__NONE +# define DEFIO_REC__PG8 defio_error_PG8_is_not_supported_on_TARGET +#endif +#if DEFIO_PORT_G_USED_MASK & BIT(9) +# define DEFIO_TAG__PG9 DEFIO_TAG_MAKE(DEFIO_GPIOID__G, 9) +# define DEFIO_TAG_E__PG9 DEFIO_TAG_MAKE(DEFIO_GPIOID__G, 9) +# define DEFIO_REC__PG9 DEFIO_REC_INDEXED(BITCOUNT(DEFIO_PORT_G_USED_MASK & (BIT(9) - 1)) + DEFIO_PORT_A_USED_COUNT+DEFIO_PORT_B_USED_COUNT+DEFIO_PORT_C_USED_COUNT+DEFIO_PORT_D_USED_COUNT+DEFIO_PORT_E_USED_COUNT+DEFIO_PORT_F_USED_COUNT) +#else +# define DEFIO_TAG__PG9 defio_error_PG9_is_not_supported_on_TARGET +# define DEFIO_TAG_E__PG9 DEFIO_TAG_E__NONE +# define DEFIO_REC__PG9 defio_error_PG9_is_not_supported_on_TARGET +#endif +#if DEFIO_PORT_G_USED_MASK & BIT(10) +# define DEFIO_TAG__PG10 DEFIO_TAG_MAKE(DEFIO_GPIOID__G, 10) +# define DEFIO_TAG_E__PG10 DEFIO_TAG_MAKE(DEFIO_GPIOID__G, 10) +# define DEFIO_REC__PG10 DEFIO_REC_INDEXED(BITCOUNT(DEFIO_PORT_G_USED_MASK & (BIT(10) - 1)) + DEFIO_PORT_A_USED_COUNT+DEFIO_PORT_B_USED_COUNT+DEFIO_PORT_C_USED_COUNT+DEFIO_PORT_D_USED_COUNT+DEFIO_PORT_E_USED_COUNT+DEFIO_PORT_F_USED_COUNT) +#else +# define DEFIO_TAG__PG10 defio_error_PG10_is_not_supported_on_TARGET +# define DEFIO_TAG_E__PG10 DEFIO_TAG_E__NONE +# define DEFIO_REC__PG10 defio_error_PG10_is_not_supported_on_TARGET +#endif +#if DEFIO_PORT_G_USED_MASK & BIT(11) +# define DEFIO_TAG__PG11 DEFIO_TAG_MAKE(DEFIO_GPIOID__G, 11) +# define DEFIO_TAG_E__PG11 DEFIO_TAG_MAKE(DEFIO_GPIOID__G, 11) +# define DEFIO_REC__PG11 DEFIO_REC_INDEXED(BITCOUNT(DEFIO_PORT_G_USED_MASK & (BIT(11) - 1)) + DEFIO_PORT_A_USED_COUNT+DEFIO_PORT_B_USED_COUNT+DEFIO_PORT_C_USED_COUNT+DEFIO_PORT_D_USED_COUNT+DEFIO_PORT_E_USED_COUNT+DEFIO_PORT_F_USED_COUNT) +#else +# define DEFIO_TAG__PG11 defio_error_PG11_is_not_supported_on_TARGET +# define DEFIO_TAG_E__PG11 DEFIO_TAG_E__NONE +# define DEFIO_REC__PG11 defio_error_PG11_is_not_supported_on_TARGET +#endif +#if DEFIO_PORT_G_USED_MASK & BIT(12) +# define DEFIO_TAG__PG12 DEFIO_TAG_MAKE(DEFIO_GPIOID__G, 12) +# define DEFIO_TAG_E__PG12 DEFIO_TAG_MAKE(DEFIO_GPIOID__G, 12) +# define DEFIO_REC__PG12 DEFIO_REC_INDEXED(BITCOUNT(DEFIO_PORT_G_USED_MASK & (BIT(12) - 1)) + DEFIO_PORT_A_USED_COUNT+DEFIO_PORT_B_USED_COUNT+DEFIO_PORT_C_USED_COUNT+DEFIO_PORT_D_USED_COUNT+DEFIO_PORT_E_USED_COUNT+DEFIO_PORT_F_USED_COUNT) +#else +# define DEFIO_TAG__PG12 defio_error_PG12_is_not_supported_on_TARGET +# define DEFIO_TAG_E__PG12 DEFIO_TAG_E__NONE +# define DEFIO_REC__PG12 defio_error_PG12_is_not_supported_on_TARGET +#endif +#if DEFIO_PORT_G_USED_MASK & BIT(13) +# define DEFIO_TAG__PG13 DEFIO_TAG_MAKE(DEFIO_GPIOID__G, 13) +# define DEFIO_TAG_E__PG13 DEFIO_TAG_MAKE(DEFIO_GPIOID__G, 13) +# define DEFIO_REC__PG13 DEFIO_REC_INDEXED(BITCOUNT(DEFIO_PORT_G_USED_MASK & (BIT(13) - 1)) + DEFIO_PORT_A_USED_COUNT+DEFIO_PORT_B_USED_COUNT+DEFIO_PORT_C_USED_COUNT+DEFIO_PORT_D_USED_COUNT+DEFIO_PORT_E_USED_COUNT+DEFIO_PORT_F_USED_COUNT) +#else +# define DEFIO_TAG__PG13 defio_error_PG13_is_not_supported_on_TARGET +# define DEFIO_TAG_E__PG13 DEFIO_TAG_E__NONE +# define DEFIO_REC__PG13 defio_error_PG13_is_not_supported_on_TARGET +#endif +#if DEFIO_PORT_G_USED_MASK & BIT(14) +# define DEFIO_TAG__PG14 DEFIO_TAG_MAKE(DEFIO_GPIOID__G, 14) +# define DEFIO_TAG_E__PG14 DEFIO_TAG_MAKE(DEFIO_GPIOID__G, 14) +# define DEFIO_REC__PG14 DEFIO_REC_INDEXED(BITCOUNT(DEFIO_PORT_G_USED_MASK & (BIT(14) - 1)) + DEFIO_PORT_A_USED_COUNT+DEFIO_PORT_B_USED_COUNT+DEFIO_PORT_C_USED_COUNT+DEFIO_PORT_D_USED_COUNT+DEFIO_PORT_E_USED_COUNT+DEFIO_PORT_F_USED_COUNT) +#else +# define DEFIO_TAG__PG14 defio_error_PG14_is_not_supported_on_TARGET +# define DEFIO_TAG_E__PG14 DEFIO_TAG_E__NONE +# define DEFIO_REC__PG14 defio_error_PG14_is_not_supported_on_TARGET +#endif +#if DEFIO_PORT_G_USED_MASK & BIT(15) +# define DEFIO_TAG__PG15 DEFIO_TAG_MAKE(DEFIO_GPIOID__G, 15) +# define DEFIO_TAG_E__PG15 DEFIO_TAG_MAKE(DEFIO_GPIOID__G, 15) +# define DEFIO_REC__PG15 DEFIO_REC_INDEXED(BITCOUNT(DEFIO_PORT_G_USED_MASK & (BIT(15) - 1)) + DEFIO_PORT_A_USED_COUNT+DEFIO_PORT_B_USED_COUNT+DEFIO_PORT_C_USED_COUNT+DEFIO_PORT_D_USED_COUNT+DEFIO_PORT_E_USED_COUNT+DEFIO_PORT_F_USED_COUNT) +#else +# define DEFIO_TAG__PG15 defio_error_PG15_is_not_supported_on_TARGET +# define DEFIO_TAG_E__PG15 DEFIO_TAG_E__NONE +# define DEFIO_REC__PG15 defio_error_PG15_is_not_supported_on_TARGET +#endif + +// DEFIO_IO_USED_COUNT is number of io pins supported on target +#define DEFIO_IO_USED_COUNT (DEFIO_PORT_A_USED_COUNT+DEFIO_PORT_B_USED_COUNT+DEFIO_PORT_C_USED_COUNT+DEFIO_PORT_D_USED_COUNT+DEFIO_PORT_E_USED_COUNT+DEFIO_PORT_F_USED_COUNT+DEFIO_PORT_G_USED_COUNT) + +// DEFIO_PORT_USED_LIST - comma separated list of bitmask for all used ports. +// DEFIO_PORT_OFFSET_LIST - comma separated list of port offsets (count of pins before this port) +// unused ports on end of list are skipped +#if !defined DEFIO_PORT_USED_LIST && DEFIO_PORT_G_USED_COUNT > 0 +# define DEFIO_PORT_USED_COUNT 7 +# define DEFIO_PORT_USED_LIST DEFIO_PORT_A_USED_MASK,DEFIO_PORT_B_USED_MASK,DEFIO_PORT_C_USED_MASK,DEFIO_PORT_D_USED_MASK,DEFIO_PORT_E_USED_MASK,DEFIO_PORT_F_USED_MASK,DEFIO_PORT_G_USED_MASK +# define DEFIO_PORT_OFFSET_LIST DEFIO_PORT_A_OFFSET,DEFIO_PORT_B_OFFSET,DEFIO_PORT_C_OFFSET,DEFIO_PORT_D_OFFSET,DEFIO_PORT_E_OFFSET,DEFIO_PORT_F_OFFSET,DEFIO_PORT_G_OFFSET +#endif +#if !defined DEFIO_PORT_USED_LIST && DEFIO_PORT_F_USED_COUNT > 0 +# define DEFIO_PORT_USED_COUNT 6 +# define DEFIO_PORT_USED_LIST DEFIO_PORT_A_USED_MASK,DEFIO_PORT_B_USED_MASK,DEFIO_PORT_C_USED_MASK,DEFIO_PORT_D_USED_MASK,DEFIO_PORT_E_USED_MASK,DEFIO_PORT_F_USED_MASK +# define DEFIO_PORT_OFFSET_LIST DEFIO_PORT_A_OFFSET,DEFIO_PORT_B_OFFSET,DEFIO_PORT_C_OFFSET,DEFIO_PORT_D_OFFSET,DEFIO_PORT_E_OFFSET,DEFIO_PORT_F_OFFSET +#endif +#if !defined DEFIO_PORT_USED_LIST && DEFIO_PORT_E_USED_COUNT > 0 +# define DEFIO_PORT_USED_COUNT 5 +# define DEFIO_PORT_USED_LIST DEFIO_PORT_A_USED_MASK,DEFIO_PORT_B_USED_MASK,DEFIO_PORT_C_USED_MASK,DEFIO_PORT_D_USED_MASK,DEFIO_PORT_E_USED_MASK +# define DEFIO_PORT_OFFSET_LIST DEFIO_PORT_A_OFFSET,DEFIO_PORT_B_OFFSET,DEFIO_PORT_C_OFFSET,DEFIO_PORT_D_OFFSET,DEFIO_PORT_E_OFFSET +#endif +#if !defined DEFIO_PORT_USED_LIST && DEFIO_PORT_D_USED_COUNT > 0 +# define DEFIO_PORT_USED_COUNT 4 +# define DEFIO_PORT_USED_LIST DEFIO_PORT_A_USED_MASK,DEFIO_PORT_B_USED_MASK,DEFIO_PORT_C_USED_MASK,DEFIO_PORT_D_USED_MASK +# define DEFIO_PORT_OFFSET_LIST DEFIO_PORT_A_OFFSET,DEFIO_PORT_B_OFFSET,DEFIO_PORT_C_OFFSET,DEFIO_PORT_D_OFFSET +#endif +#if !defined DEFIO_PORT_USED_LIST && DEFIO_PORT_C_USED_COUNT > 0 +# define DEFIO_PORT_USED_COUNT 3 +# define DEFIO_PORT_USED_LIST DEFIO_PORT_A_USED_MASK,DEFIO_PORT_B_USED_MASK,DEFIO_PORT_C_USED_MASK +# define DEFIO_PORT_OFFSET_LIST DEFIO_PORT_A_OFFSET,DEFIO_PORT_B_OFFSET,DEFIO_PORT_C_OFFSET +#endif +#if !defined DEFIO_PORT_USED_LIST && DEFIO_PORT_B_USED_COUNT > 0 +# define DEFIO_PORT_USED_COUNT 2 +# define DEFIO_PORT_USED_LIST DEFIO_PORT_A_USED_MASK,DEFIO_PORT_B_USED_MASK +# define DEFIO_PORT_OFFSET_LIST DEFIO_PORT_A_OFFSET,DEFIO_PORT_B_OFFSET +#endif +#if !defined DEFIO_PORT_USED_LIST && DEFIO_PORT_A_USED_COUNT > 0 +# define DEFIO_PORT_USED_COUNT 1 +# define DEFIO_PORT_USED_LIST DEFIO_PORT_A_USED_MASK +# define DEFIO_PORT_OFFSET_LIST DEFIO_PORT_A_OFFSET +#endif + +#if !defined DEFIO_PORT_USED_LIST +# warning "No pins are defined. Maybe you forgot to define TARGET_IO_PORTx in target_io.h" +# define DEFIO_PORT_USED_COUNT 0 +# define DEFIO_PORT_USED_LIST /* empty */ +# define DEFIO_PORT_OFFSET_LIST /* empty */ +#endif + diff --git a/src/main/drivers/io_impl.h b/src/main/drivers/io_impl.h new file mode 100644 index 000000000..580829655 --- /dev/null +++ b/src/main/drivers/io_impl.h @@ -0,0 +1,30 @@ +#pragma once + +// TODO - GPIO_TypeDef include +#include "io.h" +#include "platform.h" + +typedef struct ioDef_s { + ioTag_t tag; +} ioDef_t; + +typedef struct ioRec_s { + GPIO_TypeDef *gpio; + uint16_t pin; + resourceOwner_t owner; + resourceType_t resourcesUsed; // TODO! +} ioRec_t; + +extern ioRec_t ioRecs[DEFIO_IO_USED_COUNT]; + +int IO_GPIOPortIdx(IO_t io); +int IO_GPIOPinIdx(IO_t io); +#if defined(STM32F10X) +int IO_GPIO_PinSource(IO_t io); +int IO_GPIO_PortSource(IO_t io); +#elif defined(STM32F303xC) +int IO_EXTI_PortSourceGPIO(IO_t io); +int IO_EXTI_PinSource(IO_t io); +#endif +uint32_t IO_EXTI_Line(IO_t io); +ioRec_t *IO_Rec(IO_t io); diff --git a/src/main/drivers/rcc.c b/src/main/drivers/rcc.c new file mode 100644 index 000000000..30df1d888 --- /dev/null +++ b/src/main/drivers/rcc.c @@ -0,0 +1,20 @@ + +#include "platform.h" +#include "rcc.h" + +void RCC_ClockCmd(rccPeriphTag_t periphTag, FunctionalState NewState) +{ + int tag = periphTag >> 5; + uint32_t mask = 1 << (periphTag & 0x1f); + switch(tag) { + case RCC_AHB: + RCC_AHBPeriphClockCmd(mask, NewState); + break; + case RCC_APB2: + RCC_APB2PeriphClockCmd(mask, NewState); + break; + case RCC_APB1: + RCC_APB1PeriphClockCmd(mask, NewState); + break; + } +} diff --git a/src/main/drivers/rcc.h b/src/main/drivers/rcc.h new file mode 100644 index 000000000..14ce122c9 --- /dev/null +++ b/src/main/drivers/rcc.h @@ -0,0 +1,21 @@ +#pragma once + +#include "common/utils.h" + +enum rcc_reg { + RCC_EMPTY = 0, // make sure that default value (0) does not enable anything + RCC_AHB, + RCC_APB2, + RCC_APB1, +}; + +#define RCC_ENCODE(reg, mask) (((reg) << 5) | LOG2_32BIT(mask)) +#define RCC_AHB(periph) RCC_ENCODE(RCC_AHB, RCC_AHBENR_ ## periph ## EN) +#define RCC_APB2(periph) RCC_ENCODE(RCC_APB2, RCC_APB2ENR_ ## periph ## EN) +#define RCC_APB1(periph) RCC_ENCODE(RCC_APB1, RCC_APB1ENR_ ## periph ## EN) + +typedef uint8_t rccPeriphTag_t; + +void RCC_ClockCmd(rccPeriphTag_t periphTag, FunctionalState NewState); + + diff --git a/src/main/drivers/resource.h b/src/main/drivers/resource.h new file mode 100644 index 000000000..754c08a6d --- /dev/null +++ b/src/main/drivers/resource.h @@ -0,0 +1,38 @@ + +#pragma once + +typedef enum { + OWNER_FREE = 0, + OWNER_PWMINPUT, + OWNER_PPMINPUT, + OWNER_PWMOUTPUT_MOTOR, + OWNER_PWMOUTPUT_FAST, + OWNER_PWMOUTPUT_ONESHOT, + OWNER_PWMOUTPUT_SERVO, + OWNER_SOFTSERIAL_RX, + OWNER_SOFTSERIAL_TX, + OWNER_SOFTSERIAL_RXTX, // bidirectional pin for softserial + OWNER_SOFTSERIAL_AUXTIMER, // timer channel is used for softserial. No IO function on pin + OWNER_ADC, + OWNER_SERIAL_RX, + OWNER_SERIAL_TX, + OWNER_SERIAL_RXTX, + OWNER_PINDEBUG, + OWNER_TIMER, + OWNER_SONAR, + OWNER_SYSTEM, +} resourceOwner_t; + + +// Currently TIMER should be shared resource (softserial dualtimer and timerqueue needs to allocate timer channel, but pin can be used for other function) +// with mode switching (shared serial ports, ...) this will need some improvement +typedef enum { + RESOURCE_INPUT = 1 << 0, + RESOURCE_OUTPUT = 1<< 1, + RESOURCE_IO = RESOURCE_INPUT | RESOURCE_OUTPUT, + RESOURCE_TIMER = 1 << 2, + RESOURCE_TIMER_DUAL = 1 << 3, // channel used in dual-capture, other channel will be allocated too + RESOURCE_USART = 1 << 4, + RESOURCE_ADC = 1 << 5, + RESOURCE_EXTI = 1 << 6, +} resourceType_t; diff --git a/src/main/main.c b/src/main/main.c index d89bb4492..48200f902 100644 --- a/src/main/main.c +++ b/src/main/main.c @@ -56,6 +56,8 @@ #include "drivers/sdcard.h" #include "drivers/usb_io.h" #include "drivers/transponder_ir.h" +#include "drivers/io.h" +#include "drivers/exti.h" #include "rx/rx.h" @@ -193,6 +195,13 @@ void init(void) // Latch active features to be used for feature() in the remainder of init(). latchActiveFeatures(); + // initialize IO (needed for all IO operations) + IOInitGlobal(); + +#ifdef USE_EXTI + EXTIInit(); +#endif + #ifdef ALIENFLIGHTF3 if (hardwareRevision == AFF3_REV_1) { ledInit(false); diff --git a/src/main/target/ALIENFLIGHTF3/target.h b/src/main/target/ALIENFLIGHTF3/target.h index 79365c62e..da9879336 100644 --- a/src/main/target/ALIENFLIGHTF3/target.h +++ b/src/main/target/ALIENFLIGHTF3/target.h @@ -171,3 +171,9 @@ #define BINDPLUG_PORT GPIOB #define BINDPLUG_PIN Pin_12 +// IO - assuming 303 in 64pin package, TODO +#define TARGET_IO_PORTA 0xffff +#define TARGET_IO_PORTB 0xffff +#define TARGET_IO_PORTC 0xffff +#define TARGET_IO_PORTD (BIT(2)) +#define TARGET_IO_PORTF (BIT(0)|BIT(1)|BIT(4)) \ No newline at end of file diff --git a/src/main/target/CC3D/target.h b/src/main/target/CC3D/target.h index ca94199b8..cb8235124 100644 --- a/src/main/target/CC3D/target.h +++ b/src/main/target/CC3D/target.h @@ -141,3 +141,7 @@ #undef GPS #endif +// IO - from schematics +#define TARGET_IO_PORTA 0xffff +#define TARGET_IO_PORTB 0xffff +#define TARGET_IO_PORTC (BIT(14)) \ No newline at end of file diff --git a/src/main/target/CHEBUZZF3/target.h b/src/main/target/CHEBUZZF3/target.h index 15b54d015..48a2d87b0 100644 --- a/src/main/target/CHEBUZZF3/target.h +++ b/src/main/target/CHEBUZZF3/target.h @@ -167,3 +167,11 @@ #define SERIAL_RX #define USE_SERVOS #define USE_CLI + + +// IO - assuming 303 in 64pin package, TODO +#define TARGET_IO_PORTA 0xffff +#define TARGET_IO_PORTB 0xffff +#define TARGET_IO_PORTC 0xffff +#define TARGET_IO_PORTD (BIT(2)) +#define TARGET_IO_PORTF (BIT(0)|BIT(1)|BIT(4)) diff --git a/src/main/target/CJMCU/target.h b/src/main/target/CJMCU/target.h index cf32393b4..d97b71032 100644 --- a/src/main/target/CJMCU/target.h +++ b/src/main/target/CJMCU/target.h @@ -80,3 +80,8 @@ //#undef USE_CLI #define GTUNE //#define BLACKBOX + +// IO - assuming all IOs on 48pin package TODO +#define TARGET_IO_PORTA 0xffff +#define TARGET_IO_PORTB 0xffff +#define TARGET_IO_PORTC (BIT(13)|BIT(14)|BIT(15)) \ No newline at end of file diff --git a/src/main/target/COLIBRI_RACE/target.h b/src/main/target/COLIBRI_RACE/target.h index 92edd4fea..708aad000 100755 --- a/src/main/target/COLIBRI_RACE/target.h +++ b/src/main/target/COLIBRI_RACE/target.h @@ -194,3 +194,10 @@ #define USE_CLI #define USE_SERIAL_4WAY_BLHELI_INTERFACE + +// IO - assuming 303 in 64pin package, TODO +#define TARGET_IO_PORTA 0xffff +#define TARGET_IO_PORTB 0xffff +#define TARGET_IO_PORTC 0xffff +#define TARGET_IO_PORTD (BIT(2)) +#define TARGET_IO_PORTF (BIT(0)|BIT(1)|BIT(4)) \ No newline at end of file diff --git a/src/main/target/EUSTM32F103RC/target.h b/src/main/target/EUSTM32F103RC/target.h index 389acbbb0..99b16f53e 100644 --- a/src/main/target/EUSTM32F103RC/target.h +++ b/src/main/target/EUSTM32F103RC/target.h @@ -133,3 +133,9 @@ // USART2, PA3 #define BIND_PORT GPIOA #define BIND_PIN Pin_3 + +// IO - stm32f103RCT6 in 64pin package (TODO) +#define TARGET_IO_PORTA 0xffff +#define TARGET_IO_PORTB 0xffff +#define TARGET_IO_PORTC 0xffff +#define TARGET_IO_PORTD (BIT(0)|BIT(1)|BIT(2)) \ No newline at end of file diff --git a/src/main/target/IRCFUSIONF3/target.h b/src/main/target/IRCFUSIONF3/target.h index c3b99b5c7..afcbca7b0 100644 --- a/src/main/target/IRCFUSIONF3/target.h +++ b/src/main/target/IRCFUSIONF3/target.h @@ -136,3 +136,8 @@ #define S1W_RX_PIN GPIO_Pin_10 #endif +// IO - stm32f303cc in 48pin package +#define TARGET_IO_PORTA 0xffff +#define TARGET_IO_PORTB 0xffff +#define TARGET_IO_PORTC (BIT(13)|BIT(14)|BIT(15)) +#define TARGET_IO_PORTF (BIT(0)|BIT(1)) \ No newline at end of file diff --git a/src/main/target/LUX_RACE/target.h b/src/main/target/LUX_RACE/target.h index a3b370df7..c7eef4bba 100644 --- a/src/main/target/LUX_RACE/target.h +++ b/src/main/target/LUX_RACE/target.h @@ -163,3 +163,10 @@ #define BIND_PIN Pin_5 #define USE_SERIAL_4WAY_BLHELI_INTERFACE + +// IO - assuming 303 in 64pin package, TODO +#define TARGET_IO_PORTA 0xffff +#define TARGET_IO_PORTB 0xffff +#define TARGET_IO_PORTC 0xffff +#define TARGET_IO_PORTD (BIT(2)) +#define TARGET_IO_PORTF (BIT(0)|BIT(1)|BIT(4)) \ No newline at end of file diff --git a/src/main/target/MOTOLAB/target.h b/src/main/target/MOTOLAB/target.h index 9f168587f..500ca5168 100644 --- a/src/main/target/MOTOLAB/target.h +++ b/src/main/target/MOTOLAB/target.h @@ -189,3 +189,9 @@ #define BIND_PIN Pin_4 #define USE_SERIAL_4WAY_BLHELI_INTERFACE + +// IO - stm32f303cc in 48pin package +#define TARGET_IO_PORTA 0xffff +#define TARGET_IO_PORTB 0xffff +#define TARGET_IO_PORTC (BIT(13)|BIT(14)|BIT(15)) +#define TARGET_IO_PORTF (BIT(0)|BIT(1)) \ No newline at end of file diff --git a/src/main/target/NAZE/target.h b/src/main/target/NAZE/target.h index 944206a98..faf986dba 100644 --- a/src/main/target/NAZE/target.h +++ b/src/main/target/NAZE/target.h @@ -201,3 +201,8 @@ #define BINDPLUG_PORT GPIOB #define BINDPLUG_PIN Pin_5 #endif + +// IO - assuming all IOs on 48pin package +#define TARGET_IO_PORTA 0xffff +#define TARGET_IO_PORTB 0xffff +#define TARGET_IO_PORTC (BIT(13)|BIT(14)|BIT(15)) \ No newline at end of file diff --git a/src/main/target/NAZE32PRO/target.h b/src/main/target/NAZE32PRO/target.h index 7cb85713d..dd3e99648 100644 --- a/src/main/target/NAZE32PRO/target.h +++ b/src/main/target/NAZE32PRO/target.h @@ -52,3 +52,10 @@ // USART2, PA3 #define BIND_PORT GPIOA #define BIND_PIN Pin_3 + +// IO - assuming 303 in 64pin package, TODO +#define TARGET_IO_PORTA 0xffff +#define TARGET_IO_PORTB 0xffff +#define TARGET_IO_PORTC 0xffff +#define TARGET_IO_PORTD (BIT(2)) +#define TARGET_IO_PORTF (BIT(0)|BIT(1)|BIT(4)) \ No newline at end of file diff --git a/src/main/target/OLIMEXINO/target.h b/src/main/target/OLIMEXINO/target.h index 9185fa281..2fca08014 100644 --- a/src/main/target/OLIMEXINO/target.h +++ b/src/main/target/OLIMEXINO/target.h @@ -113,3 +113,9 @@ #define BLACKBOX #define USE_SERVOS #define USE_CLI + +// IO - assuming all IOs on smt32f103rb LQFP64 package +#define TARGET_IO_PORTA 0xffff +#define TARGET_IO_PORTB 0xffff +#define TARGET_IO_PORTC 0xffff +#define TARGET_IO_PORTD (BIT(2)) \ No newline at end of file diff --git a/src/main/target/PORT103R/target.h b/src/main/target/PORT103R/target.h index 4f58065da..201ec7e60 100644 --- a/src/main/target/PORT103R/target.h +++ b/src/main/target/PORT103R/target.h @@ -158,3 +158,9 @@ #define USE_CLI #define USE_SERIAL_4WAY_BLHELI_INTERFACE + +// IO - stm32f103RCT6 in 64pin package +#define TARGET_IO_PORTA 0xffff +#define TARGET_IO_PORTB 0xffff +#define TARGET_IO_PORTC 0xffff +#define TARGET_IO_PORTD (BIT(0)|BIT(1)|BIT(2)) \ No newline at end of file diff --git a/src/main/target/RMDO/target.h b/src/main/target/RMDO/target.h index b9f201ab1..b537c4a5b 100644 --- a/src/main/target/RMDO/target.h +++ b/src/main/target/RMDO/target.h @@ -155,3 +155,9 @@ #define BIND_PIN Pin_11 #define USE_SERIAL_4WAY_BLHELI_INTERFACE + +// IO - stm32f303cc in 48pin package +#define TARGET_IO_PORTA 0xffff +#define TARGET_IO_PORTB 0xffff +#define TARGET_IO_PORTC (BIT(13)|BIT(14)|BIT(15)) +#define TARGET_IO_PORTF (BIT(0)|BIT(1)) diff --git a/src/main/target/SINGULARITY/target.h b/src/main/target/SINGULARITY/target.h index 54d182444..79b6cea1b 100644 --- a/src/main/target/SINGULARITY/target.h +++ b/src/main/target/SINGULARITY/target.h @@ -135,3 +135,8 @@ #define USE_SERIAL_4WAY_BLHELI_INTERFACE +// IO - stm32f303cc in 48pin package +#define TARGET_IO_PORTA 0xffff +#define TARGET_IO_PORTB 0xffff +#define TARGET_IO_PORTC (BIT(13)|BIT(14)|BIT(15)) +#define TARGET_IO_PORTF (BIT(0)|BIT(1)) diff --git a/src/main/target/SPARKY/target.h b/src/main/target/SPARKY/target.h index 8ff56c86c..267a573bf 100644 --- a/src/main/target/SPARKY/target.h +++ b/src/main/target/SPARKY/target.h @@ -169,3 +169,8 @@ // USART2, PA3 #define BIND_PORT GPIOA #define BIND_PIN Pin_3 + + +// available IO pins (from schematics) +#define TARGET_IO_PORTA (BIT(1)|BIT(2)|BIT(3)|BIT(4)|BIT(6)|BIT(7)|BIT(8)|BIT(9)|BIT(10)|BIT(11)|BIT(12)|BIT(13)|BIT(14)|BIT(15)) +#define TARGET_IO_PORTB (BIT(0)|BIT(1)|BIT(10)|BIT(11)|BIT(14)|BIT(15)|BIT(3)|BIT(4)|BIT(5)|BIT(6)|BIT(7)|BIT(8)|BIT(9)) diff --git a/src/main/target/SPRACINGF3/target.h b/src/main/target/SPRACINGF3/target.h index c5a0e5265..b8eae3c64 100644 --- a/src/main/target/SPRACINGF3/target.h +++ b/src/main/target/SPRACINGF3/target.h @@ -164,3 +164,9 @@ #define BIND_PIN Pin_11 #define USE_SERIAL_4WAY_BLHELI_INTERFACE + +// IO - stm32f303cc in 48pin package +#define TARGET_IO_PORTA 0xffff +#define TARGET_IO_PORTB 0xffff +#define TARGET_IO_PORTC (BIT(13)|BIT(14)|BIT(15)) +#define TARGET_IO_PORTF (BIT(0)|BIT(1)) diff --git a/src/main/target/SPRACINGF3EVO/target.h b/src/main/target/SPRACINGF3EVO/target.h index 4586dbc2d..804bb2a41 100755 --- a/src/main/target/SPRACINGF3EVO/target.h +++ b/src/main/target/SPRACINGF3EVO/target.h @@ -223,3 +223,9 @@ #define BIND_PIN Pin_11 #define USE_SERIAL_4WAY_BLHELI_INTERFACE + +// IO - stm32f303cc in 48pin package +#define TARGET_IO_PORTA 0xffff +#define TARGET_IO_PORTB 0xffff +#define TARGET_IO_PORTC (BIT(13)|BIT(14)|BIT(15)) +#define TARGET_IO_PORTF (BIT(0)|BIT(1)) diff --git a/src/main/target/SPRACINGF3MINI/target.h b/src/main/target/SPRACINGF3MINI/target.h index 5459d4f9a..bbef3341f 100644 --- a/src/main/target/SPRACINGF3MINI/target.h +++ b/src/main/target/SPRACINGF3MINI/target.h @@ -233,3 +233,8 @@ #define BINDPLUG_PIN BUTTON_B_PIN #define USE_SERIAL_4WAY_BLHELI_INTERFACE + +#define TARGET_IO_PORTA 0xffff +#define TARGET_IO_PORTB 0xffff +#define TARGET_IO_PORTC (BIT(13)|BIT(14)|BIT(15)) +#define TARGET_IO_PORTF (BIT(0)|BIT(1)) \ No newline at end of file diff --git a/src/main/target/STM32F3DISCOVERY/target.h b/src/main/target/STM32F3DISCOVERY/target.h index 190676ef3..cde9d7bdd 100644 --- a/src/main/target/STM32F3DISCOVERY/target.h +++ b/src/main/target/STM32F3DISCOVERY/target.h @@ -177,3 +177,11 @@ #define USE_CLI #define USE_SERIAL_4WAY_BLHELI_INTERFACE + +// IO - 303 in 100pin package +#define TARGET_IO_PORTA 0xffff +#define TARGET_IO_PORTB 0xffff +#define TARGET_IO_PORTC 0xffff +#define TARGET_IO_PORTD 0xffff +#define TARGET_IO_PORTE 0xffff +#define TARGET_IO_PORTF 0x00ff \ No newline at end of file