exti_io from Peter Ledvina

This commit is contained in:
Petr Ledvina 2016-05-31 21:19:00 +10:00 committed by borisbstyle
parent a74acccb84
commit 9e30e69cee
34 changed files with 2020 additions and 19 deletions

View File

@ -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

View File

@ -18,6 +18,7 @@
#pragma once
#include <stddef.h>
#include <stdint.h>
#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) \

176
src/main/drivers/exti.c Normal file
View File

@ -0,0 +1,176 @@
#include <string.h>
#include <stdbool.h>
#include <stdint.h>
#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

View File

@ -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);

View File

@ -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

271
src/main/drivers/io.c Normal file
View File

@ -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;
}

95
src/main/drivers/io.h Normal file
View File

@ -0,0 +1,95 @@
#pragma once
#include <stdbool.h>
#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);

35
src/main/drivers/io_def.h Normal file
View File

@ -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"

File diff suppressed because it is too large Load Diff

View File

@ -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);

20
src/main/drivers/rcc.c Normal file
View File

@ -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;
}
}

21
src/main/drivers/rcc.h Normal file
View File

@ -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);

View File

@ -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;

View File

@ -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);

View File

@ -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))

View File

@ -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))

View File

@ -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))

View File

@ -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))

View File

@ -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))

View File

@ -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))

View File

@ -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))

View File

@ -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))

View File

@ -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))

View File

@ -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))

View File

@ -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))

View File

@ -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))

View File

@ -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))

View File

@ -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))

View File

@ -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))

View File

@ -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))

View File

@ -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))

View File

@ -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))

View File

@ -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))

View File

@ -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