EXTI - Remove boolean argument from EXTIEnable.

It's confusing to have a method called EXTIEnable that takes an argument
that can DISABLE the line.

There are usually 3 options for this:
1. Use two methods, one for enable, one for disable.
2. Use enum constants instead of the boolean argument.
3. Rename to '*Set', e.g. EXTISet(...)

This commit applies option 1 above, as it's cleaner and the most common
use case in the codebase.
This commit is contained in:
Dominic Clifton 2022-03-05 17:14:29 +01:00
parent 0cfd462d85
commit d0de9ac1f8
14 changed files with 52 additions and 29 deletions

View File

@ -173,7 +173,7 @@ static void mpuIntExtiInit(gyroDev_t *gyro)
IOInit(mpuIntIO, OWNER_GYRO_EXTI, 0);
EXTIHandlerInit(&gyro->exti, mpuIntExtiHandler);
EXTIConfig(mpuIntIO, &gyro->exti, NVIC_PRIO_MPU_INT_EXTI, IOCFG_IN_FLOATING, BETAFLIGHT_EXTI_TRIGGER_RISING);
EXTIEnable(mpuIntIO, true);
EXTIEnable(mpuIntIO);
}
#endif // USE_GYRO_EXTI

View File

@ -255,7 +255,7 @@ static void bmi160IntExtiInit(gyroDev_t *gyro)
IOInit(mpuIntIO, OWNER_GYRO_EXTI, 0);
EXTIHandlerInit(&gyro->exti, bmi160ExtiHandler);
EXTIConfig(mpuIntIO, &gyro->exti, NVIC_PRIO_MPU_INT_EXTI, IOCFG_IN_FLOATING, BETAFLIGHT_EXTI_TRIGGER_RISING); // TODO - maybe pullup / pulldown ?
EXTIEnable(mpuIntIO, true);
EXTIEnable(mpuIntIO);
}
#endif

View File

@ -300,7 +300,7 @@ static void bmi270IntExtiInit(gyroDev_t *gyro)
IOInit(mpuIntIO, OWNER_GYRO_EXTI, 0);
EXTIHandlerInit(&gyro->exti, bmi270ExtiHandler);
EXTIConfig(mpuIntIO, &gyro->exti, NVIC_PRIO_MPU_INT_EXTI, IOCFG_IN_FLOATING, BETAFLIGHT_EXTI_TRIGGER_RISING);
EXTIEnable(mpuIntIO, true);
EXTIEnable(mpuIntIO);
}
#else
void bmi270ExtiHandler(extiCallbackRec_t *cb)

View File

@ -95,7 +95,7 @@ static void l3gd20IntExtiInit(gyroDev_t *gyro)
IOInit(mpuIntIO, OWNER_GYRO_EXTI, 0);
EXTIHandlerInit(&gyro->exti, l3gd20ExtiHandler);
EXTIConfig(mpuIntIO, &gyro->exti, NVIC_PRIO_MPU_INT_EXTI, IOCFG_IN_FLOATING, BETAFLIGHT_EXTI_TRIGGER_RISING);
EXTIEnable(mpuIntIO, true);
EXTIEnable(mpuIntIO);
}
#endif

View File

@ -160,7 +160,7 @@ static void lsm6dsoIntExtiInit(gyroDev_t *gyro)
IOInit(mpuIntIO, OWNER_GYRO_EXTI, 0);
EXTIHandlerInit(&gyro->exti, lsm6dsoExtiHandler);
EXTIConfig(mpuIntIO, &gyro->exti, NVIC_PRIO_MPU_INT_EXTI, IOCFG_IN_FLOATING, BETAFLIGHT_EXTI_TRIGGER_RISING);
EXTIEnable(mpuIntIO, true);
EXTIEnable(mpuIntIO);
}
#endif

View File

@ -168,7 +168,7 @@ bool bmp085Detect(const bmp085Config_t *config, baroDev_t *baro)
IOInit(eocIO, OWNER_BARO_EOC, 0);
EXTIHandlerInit(&exti, bmp085ExtiHandler);
EXTIConfig(eocIO, &exti, NVIC_PRIO_BARO_EXTI, IOCFG_IN_FLOATING, BETAFLIGHT_EXTI_TRIGGER_RISING);
EXTIEnable(eocIO, true);
EXTIEnable(eocIO);
#else
UNUSED(config);
#endif

View File

@ -236,7 +236,7 @@ bool bmp388Detect(const bmp388Config_t *config, baroDev_t *baro)
IOInit(baroIntIO, OWNER_BARO_EOC, 0);
EXTIHandlerInit(&baro->exti, bmp388_extiHandler);
EXTIConfig(baroIntIO, &baro->exti, NVIC_PRIO_BARO_EXTI, IOCFG_IN_FLOATING, BETAFLIGHT_EXTI_TRIGGER_RISING);
EXTIEnable(baroIntIO, true);
EXTIEnable(baroIntIO);
}
#else
UNUSED(config);

View File

@ -178,8 +178,8 @@ static void hmc5883lConfigureDataReadyInterruptHandling(magDev_t* mag)
IOInit(magIntIO, OWNER_COMPASS_EXTI, 0);
EXTIHandlerInit(&mag->exti, hmc5883_extiHandler);
EXTIConfig(magIntIO, &mag->exti, NVIC_PRIO_MPU_INT_EXTI, IOCFG_IN_FLOATING, BETAFLIGHT_EXTI_TRIGGER_RISING);
EXTIEnable(magIntIO, true);
EXTIEnable(magIntIO, true);
EXTIEnable(magIntIO);
EXTIEnable(magIntIO);
#else
UNUSED(mag);
#endif

View File

@ -186,7 +186,7 @@ void EXTIConfig(IO_t io, extiCallbackRec_t *cb, int irqPriority, ioConfig_t conf
void EXTIRelease(IO_t io)
{
// don't forget to match cleanup with config
EXTIEnable(io, false);
EXTIDisable(io);
const int chIdx = IO_GPIOPinIdx(io);
@ -198,7 +198,7 @@ void EXTIRelease(IO_t io)
rec->handler = NULL;
}
void EXTIEnable(IO_t io, bool enable)
void EXTIEnable(IO_t io)
{
#if defined(STM32F1) || defined(STM32F4) || defined(STM32F7) || defined(STM32H7) || defined(STM32G4)
uint32_t extiLine = IO_EXTI_Line(io);
@ -207,11 +207,7 @@ void EXTIEnable(IO_t io, bool enable)
return;
}
if (enable) {
EXTI_REG_IMR |= extiLine;
} else {
EXTI_REG_IMR &= ~extiLine;
}
#elif defined(STM32F303xC)
int extiLine = IO_EXTI_Line(io);
@ -222,17 +218,41 @@ void EXTIEnable(IO_t io, bool enable)
// assume extiLine < 32 (valid for all EXTI pins)
if (enable) {
EXTI_REG_IMR |= 1 << extiLine;
} else {
EXTI_REG_IMR &= ~(1 << extiLine);
EXTI_REG_PR = extiLine;
}
#else
# error "Unknown CPU"
#endif
}
void EXTIDisable(IO_t io)
{
#if defined(STM32F1) || defined(STM32F4) || defined(STM32F7) || defined(STM32H7) || defined(STM32G4)
uint32_t extiLine = IO_EXTI_Line(io);
if (!extiLine) {
return;
}
EXTI_REG_IMR &= ~extiLine;
EXTI_REG_PR = extiLine;
#elif defined(STM32F303xC)
int extiLine = IO_EXTI_Line(io);
if (extiLine < 0) {
return;
}
// assume extiLine < 32 (valid for all EXTI pins)
EXTI_REG_IMR &= ~(1 << extiLine);
#else
# error "Unknown CPU"
#endif
}
#define EXTI_EVENT_MASK 0xFFFF // first 16 bits only, see also definition of extiChannelRecs.
void EXTI_IRQHandler(uint32_t mask)

View File

@ -42,4 +42,5 @@ void EXTIInit(void);
void EXTIHandlerInit(extiCallbackRec_t *cb, extiHandlerCallback *fn);
void EXTIConfig(IO_t io, extiCallbackRec_t *cb, int irqPriority, ioConfig_t config, extiTrigger_t trigger);
void EXTIRelease(IO_t io);
void EXTIEnable(IO_t io, bool enable);
void EXTIEnable(IO_t io);
void EXTIDisable(IO_t io);

View File

@ -188,7 +188,7 @@ bool hcsr04Detect(rangefinderDev_t *dev, const sonarConfig_t * rangefinderHardwa
// Hardware detected - configure the driver
EXTIHandlerInit(&hcsr04_extiCallbackRec, hcsr04_extiHandler);
EXTIConfig(echoIO, &hcsr04_extiCallbackRec, NVIC_PRIO_SONAR_EXTI, IOCFG_IN_FLOATING, BETAFLIGHT_EXTI_TRIGGER_BOTH); // TODO - priority!
EXTIEnable(echoIO, true);
EXTIEnable(echoIO);
dev->delayMs = 100;
dev->maxRangeCm = HCSR04_MAX_RANGE_CM;

View File

@ -138,7 +138,7 @@ void rxSpiExtiInit(ioConfig_t rxSpiExtiPinConfig, extiTrigger_t rxSpiExtiPinTrig
EXTIHandlerInit(&rxSpiExtiCallbackRec, rxSpiExtiHandler);
EXTIConfig(extiPin, &rxSpiExtiCallbackRec, NVIC_PRIO_RX_INT_EXTI, rxSpiExtiPinConfig, rxSpiExtiPinTrigger);
EXTIEnable(extiPin, true);
EXTIEnable(extiPin);
// Check that we've not missed the rising edge on the interrupt line
if (rxSpiGetExtiState()) {

View File

@ -106,7 +106,7 @@ static bool sx1280MarkBusy(void)
static void sx1280ClearBusyFn(void)
{
EXTIEnable(busy, false);
EXTIDisable(busy);
}
// Switch to waiting for busy interrupt
@ -143,9 +143,9 @@ static void sx1280SetBusyFn(extiHandlerCallback *waitingFn)
sx1280Busy = IORead(busy);
if (sx1280Busy) {
EXTIHandlerInit(&busyIntContext.exti, waitingFn);
EXTIEnable(busy, true);
EXTIEnable(busy);
} else {
EXTIEnable(busy, false);
EXTIDisable(busy);
}
}

View File

@ -180,7 +180,9 @@ void EXTIHandlerInit(extiCallbackRec_t *, extiHandlerCallback *) {
void EXTIConfig(IO_t, extiCallbackRec_t *, int, ioConfig_t, extiTrigger_t) {
}
void EXTIEnable(IO_t, bool) {
void EXTIEnable(IO_t) {
}
void EXTIDisable(IO_t) {
}