1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-24 00:35:39 +03:00

Merge pull request #7017 from jflyper/bfdev-exti-for-f7hal

EXTI: Unified EXTIConfig for all MCU types
This commit is contained in:
Michael Keller 2018-11-01 22:06:20 +13:00 committed by GitHub
commit 965de2133f
No known key found for this signature in database
GPG key ID: 4AEE18F83AFDEB23
10 changed files with 62 additions and 64 deletions

View file

@ -134,17 +134,9 @@ static void mpuIntExtiInit(gyroDev_t *gyro)
} }
#endif #endif
#if defined (STM32F7)
IOInit(mpuIntIO, OWNER_GYRO_EXTI, 0); IOInit(mpuIntIO, OWNER_GYRO_EXTI, 0);
EXTIHandlerInit(&gyro->exti, mpuIntExtiHandler); EXTIHandlerInit(&gyro->exti, mpuIntExtiHandler);
EXTIConfig(mpuIntIO, &gyro->exti, NVIC_PRIO_MPU_INT_EXTI, IO_CONFIG(GPIO_MODE_INPUT,0,GPIO_NOPULL)); // TODO - maybe pullup / pulldown ? EXTIConfig(mpuIntIO, &gyro->exti, NVIC_PRIO_MPU_INT_EXTI, IOCFG_IN_FLOATING, EXTI_TRIGGER_RISING);
#else
IOInit(mpuIntIO, OWNER_GYRO_EXTI, 0);
IOConfigGPIO(mpuIntIO, IOCFG_IN_FLOATING); // TODO - maybe pullup / pulldown ?
EXTIHandlerInit(&gyro->exti, mpuIntExtiHandler);
EXTIConfig(mpuIntIO, &gyro->exti, NVIC_PRIO_MPU_INT_EXTI, EXTI_Trigger_Rising);
#endif
EXTIEnable(mpuIntIO, true); EXTIEnable(mpuIntIO, true);
} }
#endif // MPU_INT_EXTI #endif // MPU_INT_EXTI

View file

@ -252,10 +252,8 @@ static void bmi160IntExtiInit(gyroDev_t *gyro)
IO_t mpuIntIO = IOGetByTag(gyro->mpuIntExtiTag); IO_t mpuIntIO = IOGetByTag(gyro->mpuIntExtiTag);
IOInit(mpuIntIO, OWNER_GYRO_EXTI, 0); IOInit(mpuIntIO, OWNER_GYRO_EXTI, 0);
IOConfigGPIO(mpuIntIO, IOCFG_IN_FLOATING); // TODO - maybe pullup / pulldown ?
EXTIHandlerInit(&gyro->exti, bmi160ExtiHandler); EXTIHandlerInit(&gyro->exti, bmi160ExtiHandler);
EXTIConfig(mpuIntIO, &gyro->exti, NVIC_PRIO_MPU_INT_EXTI, EXTI_Trigger_Rising); EXTIConfig(mpuIntIO, &gyro->exti, NVIC_PRIO_MPU_INT_EXTI, IOCFG_IN_FLOATING, EXTI_TRIGGER_RISING); // TODO - maybe pullup / pulldown ?
EXTIEnable(mpuIntIO, true); EXTIEnable(mpuIntIO, true);
} }

View file

@ -181,7 +181,7 @@ bool bmp085Detect(const bmp085Config_t *config, baroDev_t *baro)
IOInit(eocIO, OWNER_BARO_EXTI, 0); IOInit(eocIO, OWNER_BARO_EXTI, 0);
IOConfigGPIO(eocIO, Mode_IN_FLOATING); IOConfigGPIO(eocIO, Mode_IN_FLOATING);
EXTIHandlerInit(&bmp085_extiCallbackRec, bmp085_extiHandler); EXTIHandlerInit(&bmp085_extiCallbackRec, bmp085_extiHandler);
EXTIConfig(eocIO, &bmp085_extiCallbackRec, NVIC_PRIO_BARO_EXTI, EXTI_Trigger_Rising); EXTIConfig(eocIO, &bmp085_extiCallbackRec, NVIC_PRIO_BARO_EXTI, IOCFG_IN_FLOATING, EXTI_TRIGGER_RISING);
EXTIEnable(eocIO, true); EXTIEnable(eocIO, true);
} }
#else #else

View file

@ -172,18 +172,11 @@ static void hmc5883lConfigureDataReadyInterruptHandling(magDev_t* mag)
} }
#endif #endif
#if defined (STM32F7)
IOInit(magIntIO, OWNER_COMPASS_EXTI, 0); IOInit(magIntIO, OWNER_COMPASS_EXTI, 0);
EXTIHandlerInit(&mag->exti, hmc5883_extiHandler); EXTIHandlerInit(&mag->exti, hmc5883_extiHandler);
EXTIConfig(magIntIO, &mag->exti, NVIC_PRIO_MPU_INT_EXTI, IO_CONFIG(GPIO_MODE_INPUT,0,GPIO_NOPULL)); EXTIConfig(magIntIO, &mag->exti, NVIC_PRIO_MPU_INT_EXTI, IOCFG_IN_FLOATING, EXTI_TRIGGER_RISING);
EXTIEnable(magIntIO, true); EXTIEnable(magIntIO, true);
#else
IOInit(magIntIO, OWNER_COMPASS_EXTI, 0);
IOConfigGPIO(magIntIO, IOCFG_IN_FLOATING);
EXTIHandlerInit(&mag->exti, hmc5883_extiHandler);
EXTIConfig(magIntIO, &mag->exti, NVIC_PRIO_MAG_INT_EXTI, EXTI_Trigger_Rising);
EXTIEnable(magIntIO, true); EXTIEnable(magIntIO, true);
#endif
#else #else
UNUSED(mag); UNUSED(mag);
#endif #endif

View file

@ -36,7 +36,7 @@ typedef struct {
extiChannelRec_t extiChannelRecs[16]; extiChannelRec_t extiChannelRecs[16];
// IRQ gouping, same on 103 and 303 // IRQ gouping, same on 103, 303, 40x and 7xx.
#define EXTI_IRQ_GROUPS 7 #define EXTI_IRQ_GROUPS 7
// 0 1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 // 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 const uint8_t extiGroups[16] = { 0, 1, 2, 3, 4, 5, 5, 5, 5, 5, 6, 6, 6, 6, 6, 6 };
@ -66,6 +66,20 @@ static const uint8_t extiGroupIRQn[EXTI_IRQ_GROUPS] = {
# warning "Unknown CPU" # warning "Unknown CPU"
#endif #endif
static uint32_t triggerLookupTable[] = {
#if defined(STM32F7)
[EXTI_TRIGGER_RISING] = GPIO_MODE_IT_RISING,
[EXTI_TRIGGER_FALLING] = GPIO_MODE_IT_FALLING,
[EXTI_TRIGGER_BOTH] = GPIO_MODE_IT_RISING_FALLING
#elif defined(STM32F1) || defined(STM32F3) || defined(STM32F4)
[EXTI_TRIGGER_RISING] = EXTI_Trigger_Rising,
[EXTI_TRIGGER_FALLING] = EXTI_Trigger_Falling,
[EXTI_TRIGGER_BOTH] = EXTI_Trigger_Rising_Falling
#else
# warning "Unknown CPU"
#endif
};
void EXTIInit(void) void EXTIInit(void)
{ {
@ -92,48 +106,37 @@ void EXTIHandlerInit(extiCallbackRec_t *self, extiHandlerCallback *fn)
self->fn = fn; self->fn = fn;
} }
#if defined(STM32F7) void EXTIConfig(IO_t io, extiCallbackRec_t *cb, int irqPriority, ioConfig_t config, extiTrigger_t trigger)
void EXTIConfig(IO_t io, extiCallbackRec_t *cb, int irqPriority, ioConfig_t config)
{ {
(void)config; int chIdx = IO_GPIOPinIdx(io);
int chIdx;
chIdx = IO_GPIOPinIdx(io); if (chIdx < 0) {
if (chIdx < 0)
return; return;
extiChannelRec_t *rec = &extiChannelRecs[chIdx]; }
int group = extiGroups[chIdx]; int group = extiGroups[chIdx];
extiChannelRec_t *rec = &extiChannelRecs[chIdx];
rec->handler = cb;
#if defined(STM32F7)
GPIO_InitTypeDef init = { GPIO_InitTypeDef init = {
.Pin = IO_Pin(io), .Pin = IO_Pin(io),
.Mode = GPIO_MODE_IT_RISING, .Mode = GPIO_MODE_INPUT | IO_CONFIG_GET_MODE(config) | triggerLookupTable[trigger],
.Speed = GPIO_SPEED_FREQ_LOW, .Speed = IO_CONFIG_GET_SPEED(config),
.Pull = GPIO_NOPULL, .Pull = IO_CONFIG_GET_PULL(config),
}; };
HAL_GPIO_Init(IO_GPIO(io), &init); HAL_GPIO_Init(IO_GPIO(io), &init);
rec->handler = cb;
//uint32_t extiLine = IO_EXTI_Line(io);
//EXTI_ClearITPendingBit(extiLine);
if (extiGroupPriority[group] > irqPriority) { if (extiGroupPriority[group] > irqPriority) {
extiGroupPriority[group] = irqPriority; extiGroupPriority[group] = irqPriority;
HAL_NVIC_SetPriority(extiGroupIRQn[group], NVIC_PRIORITY_BASE(irqPriority), NVIC_PRIORITY_SUB(irqPriority)); HAL_NVIC_SetPriority(extiGroupIRQn[group], NVIC_PRIORITY_BASE(irqPriority), NVIC_PRIORITY_SUB(irqPriority));
HAL_NVIC_EnableIRQ(extiGroupIRQn[group]); HAL_NVIC_EnableIRQ(extiGroupIRQn[group]);
} }
}
#else #else
IOConfigGPIO(io, config);
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) #if defined(STM32F10X)
GPIO_EXTILineConfig(IO_GPIO_PortSource(io), IO_GPIO_PinSource(io)); GPIO_EXTILineConfig(IO_GPIO_PortSource(io), IO_GPIO_PinSource(io));
#elif defined(STM32F303xC) #elif defined(STM32F303xC)
@ -143,6 +146,7 @@ void EXTIConfig(IO_t io, extiCallbackRec_t *cb, int irqPriority, EXTITrigger_Typ
#else #else
# warning "Unknown CPU" # warning "Unknown CPU"
#endif #endif
uint32_t extiLine = IO_EXTI_Line(io); uint32_t extiLine = IO_EXTI_Line(io);
EXTI_ClearITPendingBit(extiLine); EXTI_ClearITPendingBit(extiLine);
@ -150,7 +154,7 @@ void EXTIConfig(IO_t io, extiCallbackRec_t *cb, int irqPriority, EXTITrigger_Typ
EXTI_InitTypeDef EXTIInit; EXTI_InitTypeDef EXTIInit;
EXTIInit.EXTI_Line = extiLine; EXTIInit.EXTI_Line = extiLine;
EXTIInit.EXTI_Mode = EXTI_Mode_Interrupt; EXTIInit.EXTI_Mode = EXTI_Mode_Interrupt;
EXTIInit.EXTI_Trigger = trigger; EXTIInit.EXTI_Trigger = triggerLookupTable[trigger];
EXTIInit.EXTI_LineCmd = ENABLE; EXTIInit.EXTI_LineCmd = ENABLE;
EXTI_Init(&EXTIInit); EXTI_Init(&EXTIInit);
@ -164,8 +168,8 @@ void EXTIConfig(IO_t io, extiCallbackRec_t *cb, int irqPriority, EXTITrigger_Typ
NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE; NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
NVIC_Init(&NVIC_InitStructure); NVIC_Init(&NVIC_InitStructure);
} }
}
#endif #endif
}
void EXTIRelease(IO_t io) void EXTIRelease(IO_t io)
{ {
@ -200,7 +204,7 @@ void EXTIEnable(IO_t io, bool enable)
else else
EXTI->IMR &= ~(1 << extiLine); EXTI->IMR &= ~(1 << extiLine);
#else #else
# error "Unsupported target" # error "Unknown CPU"
#endif #endif
} }

View file

@ -24,6 +24,12 @@
#include "drivers/io_types.h" #include "drivers/io_types.h"
typedef enum {
EXTI_TRIGGER_RISING = 0,
EXTI_TRIGGER_FALLING = 1,
EXTI_TRIGGER_BOTH = 2
} extiTrigger_t;
typedef struct extiCallbackRec_s extiCallbackRec_t; typedef struct extiCallbackRec_s extiCallbackRec_t;
typedef void extiHandlerCallback(extiCallbackRec_t *self); typedef void extiHandlerCallback(extiCallbackRec_t *self);
@ -34,10 +40,6 @@ struct extiCallbackRec_s {
void EXTIInit(void); void EXTIInit(void);
void EXTIHandlerInit(extiCallbackRec_t *cb, extiHandlerCallback *fn); void EXTIHandlerInit(extiCallbackRec_t *cb, extiHandlerCallback *fn);
#if defined(STM32F7) void EXTIConfig(IO_t io, extiCallbackRec_t *cb, int irqPriority, ioConfig_t config, extiTrigger_t trigger);
void EXTIConfig(IO_t io, extiCallbackRec_t *cb, int irqPriority, ioConfig_t config);
#else
void EXTIConfig(IO_t io, extiCallbackRec_t *cb, int irqPriority, EXTITrigger_TypeDef trigger);
#endif
void EXTIRelease(IO_t io); void EXTIRelease(IO_t io);
void EXTIEnable(IO_t io, bool enable); void EXTIEnable(IO_t io, bool enable);

View file

@ -98,6 +98,14 @@
# warning "Unknown TARGET" # warning "Unknown TARGET"
#endif #endif
#if defined(STM32F7)
// Expose these for EXTIConfig
#define IO_CONFIG_GET_MODE(cfg) (((cfg) >> 0) & 0x03)
#define IO_CONFIG_GET_SPEED(cfg) (((cfg) >> 2) & 0x03)
#define IO_CONFIG_GET_OTYPE(cfg) (((cfg) >> 4) & 0x01)
#define IO_CONFIG_GET_PULL(cfg) (((cfg) >> 5) & 0x03)
#endif
// declare available IO pins. Available pins are specified per target // declare available IO pins. Available pins are specified per target
#include "io_def.h" #include "io_def.h"

View file

@ -203,7 +203,7 @@ bool hcsr04Detect(rangefinderDev_t *dev, const sonarConfig_t * rangefinderHardwa
// Hardware detected - configure the driver // Hardware detected - configure the driver
#ifdef USE_EXTI #ifdef USE_EXTI
EXTIHandlerInit(&hcsr04_extiCallbackRec, hcsr04_extiHandler); EXTIHandlerInit(&hcsr04_extiCallbackRec, hcsr04_extiHandler);
EXTIConfig(echoIO, &hcsr04_extiCallbackRec, NVIC_PRIO_SONAR_EXTI, EXTI_Trigger_Rising_Falling); // TODO - priority! EXTIConfig(echoIO, &hcsr04_extiCallbackRec, NVIC_PRIO_SONAR_EXTI, IOCFG_IN_FLOATING, EXTI_TRIGGER_BOTH); // TODO - priority!
EXTIEnable(echoIO, true); EXTIEnable(echoIO, true);
#endif #endif

View file

@ -54,18 +54,13 @@ void a7105extiHandler(extiCallbackRec_t* cb)
} }
} }
void A7105Init (uint32_t id) { void A7105Init (uint32_t id)
{
spiDeviceByInstance(RX_SPI_INSTANCE); spiDeviceByInstance(RX_SPI_INSTANCE);
rxIntIO = IOGetByTag(IO_TAG(RX_IRQ_PIN)); /* config receiver IRQ pin */ rxIntIO = IOGetByTag(IO_TAG(RX_IRQ_PIN)); /* config receiver IRQ pin */
IOInit(rxIntIO, OWNER_RX_SPI_CS, 0); IOInit(rxIntIO, OWNER_RX_SPI_CS, 0);
#ifdef STM32F7
EXTIHandlerInit(&a7105extiCallbackRec, a7105extiHandler); EXTIHandlerInit(&a7105extiCallbackRec, a7105extiHandler);
EXTIConfig(rxIntIO, &a7105extiCallbackRec, NVIC_PRIO_MPU_INT_EXTI, IO_CONFIG(GPIO_MODE_INPUT,0,GPIO_PULLDOWN)); EXTIConfig(rxIntIO, &a7105extiCallbackRec, NVIC_PRIO_MPU_INT_EXTI, IOCFG_IPD, EXTI_TRIGGER_RISING);
#else
IOConfigGPIO(rxIntIO, IOCFG_IPD);
EXTIHandlerInit(&a7105extiCallbackRec, a7105extiHandler);
EXTIConfig(rxIntIO, &a7105extiCallbackRec, NVIC_PRIO_MPU_INT_EXTI, EXTI_Trigger_Rising);
#endif
EXTIEnable(rxIntIO, false); EXTIEnable(rxIntIO, false);
#ifdef RX_PA_TXEN_PIN #ifdef RX_PA_TXEN_PIN

View file

@ -223,6 +223,12 @@
#define VBAT_ADC_PIN PC3 #define VBAT_ADC_PIN PC3
#define RSSI_ADC_PIN PC5 #define RSSI_ADC_PIN PC5
// Additional sensors ----------------------
#define USE_RANGEFINDER
#define USE_RANGEFINDER_HCSR04
#define RANGEFINDER_HCSR04_TRIGGER_PIN PB10 // TX3 for testing
#define RANGEFINDER_HCSR04_ECHO_PIN PB11 // RX3 for testing
//DEFAULTS---------------------------------- //DEFAULTS----------------------------------
#define DEFAULT_FEATURES (FEATURE_OSD) #define DEFAULT_FEATURES (FEATURE_OSD)