From 762f027e8afdf1e85dd6f2a5a6082d878af9a026 Mon Sep 17 00:00:00 2001 From: Martin Budden Date: Tue, 14 Jun 2016 16:48:40 +0100 Subject: [PATCH 01/22] Moved BST (Black Sheep Telemetry) code into COLIBRI_RACE target directory. --- src/main/main.c | 5 ++++- src/main/{drivers => target/COLIBRI_RACE}/bus_bst.h | 0 .../{drivers => target/COLIBRI_RACE}/bus_bst_stm32f30x.c | 2 +- src/main/{io => target/COLIBRI_RACE}/i2c_bst.c | 3 +++ src/main/{io => target/COLIBRI_RACE}/i2c_bst.h | 2 -- src/main/target/COLIBRI_RACE/target.mk | 4 ++-- 6 files changed, 10 insertions(+), 6 deletions(-) rename src/main/{drivers => target/COLIBRI_RACE}/bus_bst.h (100%) rename src/main/{drivers => target/COLIBRI_RACE}/bus_bst_stm32f30x.c (99%) rename src/main/{io => target/COLIBRI_RACE}/i2c_bst.c (99%) rename src/main/{io => target/COLIBRI_RACE}/i2c_bst.h (96%) diff --git a/src/main/main.c b/src/main/main.c index 2a08223606..d836deee07 100644 --- a/src/main/main.c +++ b/src/main/main.c @@ -47,7 +47,6 @@ #include "drivers/pwm_output.h" #include "drivers/adc.h" #include "drivers/bus_i2c.h" -#include "drivers/bus_bst.h" #include "drivers/bus_spi.h" #include "drivers/inverter.h" #include "drivers/flash_m25p16.h" @@ -59,6 +58,10 @@ #include "drivers/io.h" #include "drivers/exti.h" +#ifdef USE_BST +#include "bus_bst.h" +#endif + #include "rx/rx.h" #include "io/beeper.h" diff --git a/src/main/drivers/bus_bst.h b/src/main/target/COLIBRI_RACE/bus_bst.h similarity index 100% rename from src/main/drivers/bus_bst.h rename to src/main/target/COLIBRI_RACE/bus_bst.h diff --git a/src/main/drivers/bus_bst_stm32f30x.c b/src/main/target/COLIBRI_RACE/bus_bst_stm32f30x.c similarity index 99% rename from src/main/drivers/bus_bst_stm32f30x.c rename to src/main/target/COLIBRI_RACE/bus_bst_stm32f30x.c index 201985e9e0..8ab8f6cf51 100644 --- a/src/main/drivers/bus_bst_stm32f30x.c +++ b/src/main/target/COLIBRI_RACE/bus_bst_stm32f30x.c @@ -12,7 +12,7 @@ #include -#include "nvic.h" +#include "drivers/nvic.h" #include "bus_bst.h" diff --git a/src/main/io/i2c_bst.c b/src/main/target/COLIBRI_RACE/i2c_bst.c similarity index 99% rename from src/main/io/i2c_bst.c rename to src/main/target/COLIBRI_RACE/i2c_bst.c index f0891e8e02..c0462d6db9 100644 --- a/src/main/io/i2c_bst.c +++ b/src/main/target/COLIBRI_RACE/i2c_bst.c @@ -11,6 +11,8 @@ #include "platform.h" +#include "i2c_bst.h" + #include "common/axis.h" #include "common/color.h" #include "common/maths.h" @@ -69,6 +71,7 @@ #include "hardware_revision.h" #endif +#include "bus_bst.h" #include "i2c_bst.h" void useRcControlsConfig(modeActivationCondition_t *modeActivationConditions, escAndServoConfig_t *escAndServoConfigToUse, pidProfile_t *pidProfileToUse); diff --git a/src/main/io/i2c_bst.h b/src/main/target/COLIBRI_RACE/i2c_bst.h similarity index 96% rename from src/main/io/i2c_bst.h rename to src/main/target/COLIBRI_RACE/i2c_bst.h index d2678764ec..cf9ee46118 100644 --- a/src/main/io/i2c_bst.h +++ b/src/main/target/COLIBRI_RACE/i2c_bst.h @@ -17,8 +17,6 @@ #pragma once -#include "drivers/bus_bst.h" - void bstProcessInCommand(void); void bstSlaveProcessInCommand(void); void taskBstMasterProcess(void); diff --git a/src/main/target/COLIBRI_RACE/target.mk b/src/main/target/COLIBRI_RACE/target.mk index 3158000738..b59d32d0e1 100644 --- a/src/main/target/COLIBRI_RACE/target.mk +++ b/src/main/target/COLIBRI_RACE/target.mk @@ -2,8 +2,8 @@ F3_TARGETS += $(TARGET) FEATURES = VCP TARGET_SRC = \ - io/i2c_bst.c \ - drivers/bus_bst_stm32f30x.c \ + i2c_bst.c \ + bus_bst_stm32f30x.c \ drivers/accgyro_mpu.c \ drivers/accgyro_mpu6500.c \ drivers/accgyro_spi_mpu6000.c \ From 43e5a1637305ae2fa112933724aaabe26f960274 Mon Sep 17 00:00:00 2001 From: Martin Budden Date: Tue, 14 Jun 2016 16:54:16 +0100 Subject: [PATCH 02/22] Removed repeated #include --- src/main/target/COLIBRI_RACE/i2c_bst.c | 2 -- 1 file changed, 2 deletions(-) diff --git a/src/main/target/COLIBRI_RACE/i2c_bst.c b/src/main/target/COLIBRI_RACE/i2c_bst.c index c0462d6db9..25638fb546 100644 --- a/src/main/target/COLIBRI_RACE/i2c_bst.c +++ b/src/main/target/COLIBRI_RACE/i2c_bst.c @@ -11,8 +11,6 @@ #include "platform.h" -#include "i2c_bst.h" - #include "common/axis.h" #include "common/color.h" #include "common/maths.h" From 8b1cc05e1de92ff1a921df48695f2be18bcec66a Mon Sep 17 00:00:00 2001 From: blckmn Date: Mon, 13 Jun 2016 09:02:33 +1000 Subject: [PATCH 03/22] Updated timerHardware_t to drop pinsource, and use new IO tags. --- src/main/drivers/io.c | 22 ++++++++-------- src/main/drivers/io.h | 26 ++++++++++--------- src/main/drivers/io_impl.h | 21 ++++++++------- src/main/drivers/pwm_mapping.c | 30 ++++++++++++++------- src/main/drivers/pwm_output.c | 14 ++++------ src/main/drivers/pwm_rx.c | 14 ++++------ src/main/drivers/serial_softserial.c | 39 ++++++++++++++-------------- src/main/drivers/timer.c | 24 +++++------------ src/main/drivers/timer.h | 10 +++---- src/main/target/BLUEJAYF4/target.c | 15 ++++++----- src/main/target/NAZE/target.c | 28 ++++++++++---------- 11 files changed, 120 insertions(+), 123 deletions(-) diff --git a/src/main/drivers/io.c b/src/main/drivers/io.c index 7d1d206b09..57bbecdc44 100644 --- a/src/main/drivers/io.c +++ b/src/main/drivers/io.c @@ -11,7 +11,7 @@ struct ioPortDef_s { rccPeriphTag_t rcc; }; -#if defined(STM32F10X) +#if defined(STM32F1) const struct ioPortDef_s ioPortDefs[] = { { RCC_APB2(IOPA) }, { RCC_APB2(IOPB) }, @@ -33,7 +33,7 @@ const struct ioPortDef_s ioPortDefs[] = { #endif }, }; -#elif defined(STM32F303xC) +#elif defined(STM32F3) const struct ioPortDef_s ioPortDefs[] = { { RCC_AHB(GPIOA) }, { RCC_AHB(GPIOB) }, @@ -111,11 +111,11 @@ uint32_t IO_EXTI_Line(IO_t io) { if (!io) return 0; -#if defined(STM32F10X) +#if defined(STM32F1) return 1 << IO_GPIOPinIdx(io); -#elif defined(STM32F303xC) +#elif defined(STM32F3) return IO_GPIOPinIdx(io); -#elif defined(STM32F40_41xxx) || defined(STM32F411xE) +#elif defined(STM32F4) return 1 << IO_GPIOPinIdx(io); #else # error "Unknown target type" @@ -133,7 +133,7 @@ void IOWrite(IO_t io, bool hi) { if (!io) return; -#if defined(STM32F40_41xxx) || defined(STM32F411xE) +#ifdef STM32F4 if (hi) { IO_GPIO(io)->BSRRL = IO_Pin(io); } @@ -149,7 +149,7 @@ void IOHi(IO_t io) { if (!io) return; -#if defined(STM32F40_41xxx) || defined(STM32F411xE) +#ifdef STM32F4 IO_GPIO(io)->BSRRL = IO_Pin(io); #else IO_GPIO(io)->BSRR = IO_Pin(io); @@ -160,7 +160,7 @@ void IOLo(IO_t io) { if (!io) return; -#if defined(STM32F40_41xxx) || defined(STM32F411xE) +#ifdef STM32F4 IO_GPIO(io)->BSRRH = IO_Pin(io); #else IO_GPIO(io)->BRR = IO_Pin(io); @@ -175,7 +175,7 @@ void IOToggle(IO_t io) // Read pin state from ODR but write to BSRR because it only changes the pins // high in the mask value rather than all pins. XORing ODR directly risks // setting other pins incorrectly because it change all pins' state. -#if defined(STM32F40_41xxx) || defined(STM32F411xE) +#ifdef STM32F4 if (IO_GPIO(io)->ODR & mask) { IO_GPIO(io)->BSRRH = mask; } else { @@ -216,7 +216,7 @@ resourceType_t IOGetResources(IO_t io) return ioRec->resourcesUsed; } -#if defined(STM32F10X) +#if defined(STM32F1) void IOConfigGPIO(IO_t io, ioConfig_t cfg) { @@ -233,7 +233,7 @@ void IOConfigGPIO(IO_t io, ioConfig_t cfg) GPIO_Init(IO_GPIO(io), &init); } -#elif defined(STM32F303xC) || defined(STM32F40_41xxx) || defined(STM32F411xE) +#elif defined(STM32F3) || defined(STM32F4) void IOConfigGPIO(IO_t io, ioConfig_t cfg) { diff --git a/src/main/drivers/io.h b/src/main/drivers/io.h index c8e0561aa6..74c4fbbaeb 100644 --- a/src/main/drivers/io.h +++ b/src/main/drivers/io.h @@ -3,6 +3,7 @@ #include #include +#include #include "resource.h" // IO pin identification @@ -33,7 +34,7 @@ typedef void* IO_t; // type specifying IO pin. Currently ioRec_t poin // helps masking CPU differences typedef uint8_t ioConfig_t; // packed IO configuration -#if defined(STM32F10X) +#if defined(STM32F1) // mode is using only bits 6-2 # define IO_CONFIG(mode, speed) ((mode) | (speed)) @@ -46,7 +47,7 @@ typedef uint8_t ioConfig_t; // packed IO configuration # define IOCFG_IPU IO_CONFIG(GPIO_Mode_IPU, GPIO_Speed_2MHz) # define IOCFG_IN_FLOATING IO_CONFIG(GPIO_Mode_IN_FLOATING, GPIO_Speed_2MHz) -#elif defined(STM32F303xC) +#elif defined(STM32F3) # define IO_CONFIG(mode, speed, otype, pupd) ((mode) | ((speed) << 2) | ((otype) << 4) | ((pupd) << 5)) @@ -58,17 +59,18 @@ typedef uint8_t ioConfig_t; // packed IO configuration # 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) -#elif defined(STM32F40_41xxx) || defined(STM32F411xE) +#elif defined(STM32F4) -# define IO_CONFIG(mode, speed, otype, pupd) ((mode) | ((speed) << 2) | ((otype) << 4) | ((pupd) << 5)) +#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_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_PP_UP IO_CONFIG(GPIO_Mode_AF, 0, GPIO_OType_PP, GPIO_PuPd_UP) +#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) #elif defined(UNIT_TEST) @@ -100,7 +102,7 @@ resourceType_t IOGetResources(IO_t io); IO_t IOGetByTag(ioTag_t tag); void IOConfigGPIO(IO_t io, ioConfig_t cfg); -#if defined(STM32F303xC) || defined(STM32F40_41xxx) || defined(STM32F411xE) +#if defined(STM32F3) || defined(STM32F4) void IOConfigGPIOAF(IO_t io, ioConfig_t cfg, uint8_t af); #endif diff --git a/src/main/drivers/io_impl.h b/src/main/drivers/io_impl.h index 1b5cb15e09..b7bbcec7f3 100644 --- a/src/main/drivers/io_impl.h +++ b/src/main/drivers/io_impl.h @@ -19,19 +19,20 @@ extern ioRec_t ioRecs[DEFIO_IO_USED_COUNT]; int IO_GPIOPortIdx(IO_t io); int IO_GPIOPinIdx(IO_t io); -#if defined(STM32F1) -int IO_GPIO_PinSource(IO_t io); -int IO_GPIO_PortSource(IO_t io); -#elif defined(STM32F3) -int IO_GPIO_PinSource(IO_t io); -int IO_GPIO_PortSource(IO_t io); -int IO_EXTI_PortSourceGPIO(IO_t io); -int IO_EXTI_PinSource(IO_t io); -#elif defined(STM32F4) + int IO_GPIO_PinSource(IO_t io); int IO_GPIO_PortSource(IO_t io); + +#if defined(STM32F3) || defined(STM32F4) int IO_EXTI_PortSourceGPIO(IO_t io); int IO_EXTI_PinSource(IO_t io); -# endif +#endif + +GPIO_TypeDef* IO_GPIO(IO_t io); +uint16_t IO_Pin(IO_t io); + +#define IO_GPIOBYTAG(tag) IO_GPIO(IOGetByTag(tag)) +#define IO_PINBYTAG(tag) IO_Pin(IOGetByTag(tag)) + uint32_t IO_EXTI_Line(IO_t io); ioRec_t *IO_Rec(IO_t io); diff --git a/src/main/drivers/pwm_mapping.c b/src/main/drivers/pwm_mapping.c index 99650a91b9..73308581ba 100755 --- a/src/main/drivers/pwm_mapping.c +++ b/src/main/drivers/pwm_mapping.c @@ -23,6 +23,8 @@ #include "platform.h" #include "gpio.h" +#include "io.h" +#include "io_impl.h" #include "timer.h" #include "pwm_output.h" @@ -91,6 +93,16 @@ pwmOutputConfiguration_t *pwmGetOutputConfiguration(void) return &pwmOutputConfiguration; } +bool CheckGPIOPin(ioTag_t tag, GPIO_TypeDef *gpio, uint16_t pin) +{ + return IO_GPIOBYTAG(tag) == gpio && IO_PINBYTAG(tag) == pin; +} + +bool CheckGPIOPinSource(ioTag_t tag, GPIO_TypeDef *gpio, uint16_t pin) +{ + return IO_GPIOBYTAG(tag) == gpio && IO_GPIO_PinSource(IOGetByTag(tag)) == pin; +} + pwmOutputConfiguration_t *pwmInit(drv_pwm_config_t *init) { int i = 0; @@ -99,7 +111,7 @@ pwmOutputConfiguration_t *pwmInit(drv_pwm_config_t *init) int channelIndex = 0; memset(&pwmOutputConfiguration, 0, sizeof(pwmOutputConfiguration)); - + // this is pretty hacky shit, but it will do for now. array of 4 config maps, [ multiPWM multiPPM airPWM airPPM ] if (init->airplane) i = 2; // switch to air hardware config @@ -132,7 +144,7 @@ pwmOutputConfiguration_t *pwmInit(drv_pwm_config_t *init) #if defined(STM32F303xC) && defined(USE_USART3) // skip UART3 ports (PB10/PB11) - if (init->useUART3 && timerHardwarePtr->gpio == UART3_GPIO && (timerHardwarePtr->pin == UART3_TX_PIN || timerHardwarePtr->pin == UART3_RX_PIN)) + if (init->useUART3 && (CheckGPIOPin(timerHardwarePtr->pin, UART3_GPIO, UART3_TX_PIN) || CheckGPIOPin(timerHardwarePtr->pin, UART3_GPIO, UART3_RX_PIN)) continue; #endif @@ -151,7 +163,7 @@ pwmOutputConfiguration_t *pwmInit(drv_pwm_config_t *init) if (timerHardwarePtr->tim == LED_STRIP_TIMER) continue; #if defined(STM32F303xC) && defined(WS2811_GPIO) && defined(WS2811_PIN_SOURCE) - if (timerHardwarePtr->gpio == WS2811_GPIO && timerHardwarePtr->gpioPinSource == WS2811_PIN_SOURCE) + if (CheckGPIOPinSource(timerHardwarePtr->pin, WS2811_GPIO, WS2811_PIN_SOURCE) continue; #endif } @@ -159,28 +171,28 @@ pwmOutputConfiguration_t *pwmInit(drv_pwm_config_t *init) #endif #ifdef VBAT_ADC_GPIO - if (init->useVbat && timerHardwarePtr->gpio == VBAT_ADC_GPIO && timerHardwarePtr->pin == VBAT_ADC_GPIO_PIN) { + if (init->useVbat && CheckGPIOPin(timerHardwarePtr->pin, VBAT_ADC_GPIO, VBAT_ADC_GPIO_PIN)) { continue; } #endif #ifdef RSSI_ADC_GPIO - if (init->useRSSIADC && timerHardwarePtr->gpio == RSSI_ADC_GPIO && timerHardwarePtr->pin == RSSI_ADC_GPIO_PIN) { + if (init->useRSSIADC && CheckGPIOPin(timerHardwarePtr->pin, RSSI_ADC_GPIO, RSSI_ADC_GPIO_PIN)) { continue; } #endif #ifdef CURRENT_METER_ADC_GPIO - if (init->useCurrentMeterADC && timerHardwarePtr->gpio == CURRENT_METER_ADC_GPIO && timerHardwarePtr->pin == CURRENT_METER_ADC_GPIO_PIN) { + if (init->useCurrentMeterADC && CheckGPIOPin(timerHardwarePtr->pin, CURRENT_METER_ADC_GPIO, CURRENT_METER_ADC_GPIO_PIN)) { continue; } #endif #ifdef SONAR - if (init->sonarGPIOConfig && timerHardwarePtr->gpio == init->sonarGPIOConfig->gpio && + if (init->sonarGPIOConfig && ( - timerHardwarePtr->pin == init->sonarGPIOConfig->triggerPin || - timerHardwarePtr->pin == init->sonarGPIOConfig->echoPin + CheckGPIOPin(timerHardwarePtr->pin, init->sonarGPIOConfig->gpio, init->sonarGPIOConfig->triggerPin) || + CheckGPIOPin(timerHardwarePtr->pin, init->sonarGPIOConfig->gpio, init->sonarGPIOConfig->echoPin) ) ) { continue; diff --git a/src/main/drivers/pwm_output.c b/src/main/drivers/pwm_output.c index 5b047875e7..cd703c557a 100644 --- a/src/main/drivers/pwm_output.c +++ b/src/main/drivers/pwm_output.c @@ -22,7 +22,7 @@ #include "platform.h" -#include "gpio.h" +#include "io.h" #include "timer.h" #include "flight/failsafe.h" // FIXME dependency into the main code from a driver @@ -83,14 +83,10 @@ static void pwmOCConfig(TIM_TypeDef *tim, uint8_t channel, uint16_t value, uint8 } } -static void pwmGPIOConfig(GPIO_TypeDef *gpio, uint32_t pin, GPIO_Mode mode) +static void pwmGPIOConfig(ioTag_t pin, ioConfig_t mode) { - gpio_config_t cfg; - - cfg.pin = pin; - cfg.mode = mode; - cfg.speed = Speed_2MHz; - gpioInit(gpio, &cfg); + IOInit(IOGetByTag(pin), OWNER_PWMOUTPUT_MOTOR, RESOURCE_OUTPUT); + IOConfigGPIO(IOGetByTag(pin), mode); } static pwmOutputPort_t *pwmOutConfig(const timerHardware_t *timerHardware, uint8_t mhz, uint16_t period, uint16_t value) @@ -98,7 +94,7 @@ static pwmOutputPort_t *pwmOutConfig(const timerHardware_t *timerHardware, uint8 pwmOutputPort_t *p = &pwmOutputPorts[allocatedOutputPortCount++]; configTimeBase(timerHardware->tim, period, mhz); - pwmGPIOConfig(timerHardware->gpio, timerHardware->pin, Mode_AF_PP); + pwmGPIOConfig(timerHardware->pin, IOCFG_AF_PP); pwmOCConfig(timerHardware->tim, timerHardware->channel, value, timerHardware->outputInverted); diff --git a/src/main/drivers/pwm_rx.c b/src/main/drivers/pwm_rx.c index df91273f2e..50a24e28e7 100644 --- a/src/main/drivers/pwm_rx.c +++ b/src/main/drivers/pwm_rx.c @@ -337,14 +337,10 @@ static void pwmEdgeCallback(timerCCHandlerRec_t *cbRec, captureCompare_t capture } } -static void pwmGPIOConfig(GPIO_TypeDef *gpio, uint32_t pin, GPIO_Mode mode) +static void pwmGPIOConfig(ioTag_t pin, ioConfig_t mode) { - gpio_config_t cfg; - - cfg.pin = pin; - cfg.mode = mode; - cfg.speed = Speed_2MHz; - gpioInit(gpio, &cfg); + IOInit(IOGetByTag(pin), OWNER_PWMINPUT, RESOURCE_INPUT); + IOConfigGPIO(IOGetByTag(pin), mode); } void pwmICConfig(TIM_TypeDef *tim, uint8_t channel, uint16_t polarity) @@ -376,7 +372,7 @@ void pwmInConfig(const timerHardware_t *timerHardwarePtr, uint8_t channel) self->mode = INPUT_MODE_PWM; self->timerHardware = timerHardwarePtr; - pwmGPIOConfig(timerHardwarePtr->gpio, timerHardwarePtr->pin, timerHardwarePtr->gpioInputMode); + pwmGPIOConfig(timerHardwarePtr->pin, timerHardwarePtr->ioMode); pwmICConfig(timerHardwarePtr->tim, timerHardwarePtr->channel, TIM_ICPolarity_Rising); timerConfigure(timerHardwarePtr, (uint16_t)PWM_TIMER_PERIOD, PWM_TIMER_MHZ); @@ -405,7 +401,7 @@ void ppmInConfig(const timerHardware_t *timerHardwarePtr) self->mode = INPUT_MODE_PPM; self->timerHardware = timerHardwarePtr; - pwmGPIOConfig(timerHardwarePtr->gpio, timerHardwarePtr->pin, timerHardwarePtr->gpioInputMode); + pwmGPIOConfig(timerHardwarePtr->pin, timerHardwarePtr->ioMode); pwmICConfig(timerHardwarePtr->tim, timerHardwarePtr->channel, TIM_ICPolarity_Rising); timerConfigure(timerHardwarePtr, (uint16_t)PPM_TIMER_PERIOD, PWM_TIMER_MHZ); diff --git a/src/main/drivers/serial_softserial.c b/src/main/drivers/serial_softserial.c index 446302b551..6ab1f26bad 100644 --- a/src/main/drivers/serial_softserial.c +++ b/src/main/drivers/serial_softserial.c @@ -30,7 +30,7 @@ #include "nvic.h" #include "system.h" -#include "gpio.h" +#include "io.h" #include "timer.h" #include "serial.h" @@ -48,6 +48,8 @@ typedef struct softSerial_s { serialPort_t port; + IO_t rxIO; + IO_t txIO; const timerHardware_t *rxTimerHardware; volatile uint8_t rxBuffer[SOFTSERIAL_BUFFER_SIZE]; @@ -92,30 +94,24 @@ void setTxSignal(softSerial_t *softSerial, uint8_t state) } if (state) { - digitalHi(softSerial->txTimerHardware->gpio, softSerial->txTimerHardware->pin); + IOHi(softSerial->txIO); } else { - digitalLo(softSerial->txTimerHardware->gpio, softSerial->txTimerHardware->pin); + IOLo(softSerial->txIO); } } -static void softSerialGPIOConfig(GPIO_TypeDef *gpio, uint16_t pin, GPIO_Mode mode) +static void softSerialGPIOConfig(ioTag_t pin, ioConfig_t mode) { - gpio_config_t cfg; - - cfg.pin = pin; - cfg.mode = mode; - cfg.speed = Speed_2MHz; - gpioInit(gpio, &cfg); + IOInit(IOGetByTag(pin), OWNER_SOFTSERIAL_RXTX, RESOURCE_USART); + IOConfigGPIO(IOGetByTag(pin), mode); } -void serialInputPortConfig(const timerHardware_t *timerHardwarePtr) +void serialInputPortConfig(ioTag_t pin) { -#ifdef STM32F10X - softSerialGPIOConfig(timerHardwarePtr->gpio, timerHardwarePtr->pin, Mode_IPU); +#ifdef STM32F1 + softSerialGPIOConfig(pin, IOCFG_IPU); #else -#ifdef STM32F303xC - softSerialGPIOConfig(timerHardwarePtr->gpio, timerHardwarePtr->pin, Mode_AF_PP_PU); -#endif + softSerialGPIOConfig(pin, IOCFG_AF_PP_UP); #endif } @@ -168,9 +164,9 @@ static void serialTimerRxConfig(const timerHardware_t *timerHardwarePtr, uint8_t timerChConfigCallbacks(timerHardwarePtr, &softSerialPorts[reference].edgeCb, NULL); } -static void serialOutputPortConfig(const timerHardware_t *timerHardwarePtr) +static void serialOutputPortConfig(ioTag_t pin) { - softSerialGPIOConfig(timerHardwarePtr->gpio, timerHardwarePtr->pin, Mode_Out_PP); + softSerialGPIOConfig(pin, IOCFG_OUT_PP); } static void resetBuffers(softSerial_t *softSerial) @@ -222,8 +218,11 @@ serialPort_t *openSoftSerial(softSerialPortIndex_e portIndex, serialReceiveCallb softSerial->softSerialPortIndex = portIndex; - serialOutputPortConfig(softSerial->txTimerHardware); - serialInputPortConfig(softSerial->rxTimerHardware); + softSerial->txIO = IOGetByTag(softSerial->txTimerHardware->pin); + serialOutputPortConfig(softSerial->txTimerHardware->pin); + + softSerial->rxIO = IOGetByTag(softSerial->rxTimerHardware->pin); + serialInputPortConfig(softSerial->rxTimerHardware->pin); setTxSignal(softSerial, ENABLE); delay(50); diff --git a/src/main/drivers/timer.c b/src/main/drivers/timer.c index ed8b0d587e..8e78241681 100755 --- a/src/main/drivers/timer.c +++ b/src/main/drivers/timer.c @@ -353,14 +353,10 @@ void timerChClearCCFlag(const timerHardware_t *timHw) } // configure timer channel GPIO mode -void timerChConfigGPIO(const timerHardware_t *timHw, GPIO_Mode mode) +void timerChConfigGPIO(const timerHardware_t* timHw, ioConfig_t mode) { - gpio_config_t cfg; - - cfg.pin = timHw->pin; - cfg.mode = mode; - cfg.speed = Speed_2MHz; - gpioInit(timHw->gpio, &cfg); + IOInit(IOGetByTag(timHw->pin), OWNER_TIMER, RESOURCE_TIMER); + IOConfigGPIO(IOGetByTag(timHw->pin), mode); } // calculate input filter constant @@ -656,20 +652,14 @@ void timerInit(void) RCC_AHBPeriphClockCmd(TIMER_AHB_PERIPHERALS, ENABLE); #endif -#ifdef STM32F303xC +#if defined(STM32F3) || defined(STM32F4) for (uint8_t timerIndex = 0; timerIndex < USABLE_TIMER_CHANNEL_COUNT; timerIndex++) { const timerHardware_t *timerHardwarePtr = &timerHardware[timerIndex]; - GPIO_PinAFConfig(timerHardwarePtr->gpio, (uint16_t)timerHardwarePtr->gpioPinSource, timerHardwarePtr->alternateFunction); + IOConfigGPIOAF(IOGetByTag(timerHardwarePtr->pin), timerHardwarePtr->ioMode, timerHardwarePtr->alternateFunction); } #endif - -#if defined(STM32F40_41xxx) || defined (STM32F411xE) - for (uint8_t timerIndex = 0; timerIndex < USABLE_TIMER_CHANNEL_COUNT; timerIndex++) { - const timerHardware_t *timerHardwarePtr = &timerHardware[timerIndex]; - GPIO_PinAFConfig(timerHardwarePtr->gpio, (uint16_t)timerHardwarePtr->gpioPinSource, timerHardwarePtr->alternateFunction); - } -#endif -// initialize timer channel structures + + // initialize timer channel structures for(int i = 0; i < USABLE_TIMER_CHANNEL_COUNT; i++) { timerChannelInfo[i].type = TYPE_FREE; } diff --git a/src/main/drivers/timer.h b/src/main/drivers/timer.h index d8f0b2051c..9ca4c7d957 100644 --- a/src/main/drivers/timer.h +++ b/src/main/drivers/timer.h @@ -17,6 +17,8 @@ #pragma once +#include "io.h" + #if !defined(USABLE_TIMER_CHANNEL_COUNT) #define USABLE_TIMER_CHANNEL_COUNT 14 #endif @@ -64,14 +66,12 @@ typedef struct timerOvrHandlerRec_s { typedef struct { TIM_TypeDef *tim; - GPIO_TypeDef *gpio; - uint16_t pin; + ioTag_t pin; uint8_t channel; uint8_t irq; uint8_t outputEnable; - GPIO_Mode gpioInputMode; + ioConfig_t ioMode; #if defined(STM32F3) || defined(STM32F4) - uint8_t gpioPinSource; // TODO - this can be removed and pinSource calculated from pin uint8_t alternateFunction; #endif uint8_t outputInverted; @@ -106,7 +106,7 @@ volatile timCCR_t* timerChCCR(const timerHardware_t* timHw); volatile timCCR_t* timerChCCRLo(const timerHardware_t* timHw); volatile timCCR_t* timerChCCRHi(const timerHardware_t* timHw); void timerChConfigOC(const timerHardware_t* timHw, bool outEnable, bool stateHigh); -void timerChConfigGPIO(const timerHardware_t* timHw, GPIO_Mode mode); +void timerChConfigGPIO(const timerHardware_t* timHw, ioConfig_t mode); void timerChCCHandlerInit(timerCCHandlerRec_t *self, timerCCHandlerCallback *fn); void timerChOvrHandlerInit(timerOvrHandlerRec_t *self, timerOvrHandlerCallback *fn); diff --git a/src/main/target/BLUEJAYF4/target.c b/src/main/target/BLUEJAYF4/target.c index d7f1f4ef10..512e667f9f 100644 --- a/src/main/target/BLUEJAYF4/target.c +++ b/src/main/target/BLUEJAYF4/target.c @@ -3,6 +3,7 @@ #include #include +#include "drivers/io.h" #include "drivers/pwm_mapping.h" const uint16_t multiPPM[] = { @@ -50,12 +51,12 @@ const uint16_t airPWM[] = { }; const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { - { TIM8, GPIOC, Pin_7, TIM_Channel_2, TIM8_CC_IRQn, 0, Mode_IPD, GPIO_PinSource7, GPIO_AF_TIM8, 0 }, // PPM IN - { TIM5, GPIOA, Pin_0, TIM_Channel_1, TIM5_IRQn, 1, Mode_AF_PP, GPIO_PinSource0, GPIO_AF_TIM5, 0 }, // S1_OUT - { TIM5, GPIOA, Pin_1, TIM_Channel_2, TIM5_IRQn, 1, Mode_AF_PP, GPIO_PinSource1, GPIO_AF_TIM5, 0 }, // S2_OUT - { TIM2, GPIOA, Pin_2, TIM_Channel_3, TIM2_IRQn, 1, Mode_AF_PP, GPIO_PinSource2, GPIO_AF_TIM2, 0 }, // S3_OUT - { TIM9, GPIOA, Pin_3, TIM_Channel_2, TIM1_BRK_TIM9_IRQn, 1, Mode_AF_PP, GPIO_PinSource3, GPIO_AF_TIM9, 0 }, // S4_OUT - { TIM3, GPIOB, Pin_1, TIM_Channel_4, TIM3_IRQn, 1, Mode_AF_PP, GPIO_PinSource1, GPIO_AF_TIM3, 0 }, // S5_OUT - { TIM3, GPIOB, Pin_0, TIM_Channel_3, TIM3_IRQn, 1, Mode_AF_PP, GPIO_PinSource0, GPIO_AF_TIM3, 0 }, // S6_OUT + { TIM8, IO_TAG(PC7), TIM_Channel_2, TIM8_CC_IRQn, 0, Mode_IPD, GPIO_AF_TIM8, 0 }, // PPM IN + { TIM5, IO_TAG(PA0), TIM_Channel_1, TIM5_IRQn, 1, Mode_AF_PP, GPIO_AF_TIM5, 0}, // S1_OUT + { TIM5, IO_TAG(PA1), TIM_Channel_2, TIM5_IRQn, 1, Mode_AF_PP, GPIO_AF_TIM5, 0}, // S2_OUT + { TIM2, IO_TAG(PA2), TIM_Channel_3, TIM2_IRQn, 1, Mode_AF_PP, GPIO_AF_TIM2, 0}, // S3_OUT + { TIM9, IO_TAG(PA3), TIM_Channel_2, TIM1_BRK_TIM9_IRQn, 1, Mode_AF_PP, GPIO_AF_TIM9, 0}, // S4_OUT + { TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, 1, Mode_AF_PP, GPIO_AF_TIM3, 0}, // S5_OUT + { TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, 1, Mode_AF_PP, GPIO_AF_TIM3, 0}, // S6_OUT }; diff --git a/src/main/target/NAZE/target.c b/src/main/target/NAZE/target.c index be1c6ff53d..5cf715ec1b 100644 --- a/src/main/target/NAZE/target.c +++ b/src/main/target/NAZE/target.c @@ -72,19 +72,19 @@ const uint16_t airPWM[] = { }; const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { - { TIM2, GPIOA, Pin_0, TIM_Channel_1, TIM2_IRQn, 0, Mode_IPD, 0}, // PWM1 - RC1 - { TIM2, GPIOA, Pin_1, TIM_Channel_2, TIM2_IRQn, 0, Mode_IPD, 0}, // PWM2 - RC2 - { TIM2, GPIOA, Pin_2, TIM_Channel_3, TIM2_IRQn, 0, Mode_IPD, 0}, // PWM3 - RC3 - { TIM2, GPIOA, Pin_3, TIM_Channel_4, TIM2_IRQn, 0, Mode_IPD, 0}, // PWM4 - RC4 - { TIM3, GPIOA, Pin_6, TIM_Channel_1, TIM3_IRQn, 0, Mode_IPD, 0}, // PWM5 - RC5 - { TIM3, GPIOA, Pin_7, TIM_Channel_2, TIM3_IRQn, 0, Mode_IPD, 0}, // PWM6 - RC6 - { TIM3, GPIOB, Pin_0, TIM_Channel_3, TIM3_IRQn, 0, Mode_IPD, 0}, // PWM7 - RC7 - { TIM3, GPIOB, Pin_1, TIM_Channel_4, TIM3_IRQn, 0, Mode_IPD, 0}, // PWM8 - RC8 - { TIM1, GPIOA, Pin_8, TIM_Channel_1, TIM1_CC_IRQn, 1, Mode_IPD, 0}, // PWM9 - OUT1 - { TIM1, GPIOA, Pin_11,TIM_Channel_4, TIM1_CC_IRQn, 1, Mode_IPD, 0}, // PWM10 - OUT2 - { TIM4, GPIOB, Pin_6, TIM_Channel_1, TIM4_IRQn, 0, Mode_IPD, 0}, // PWM11 - OUT3 - { TIM4, GPIOB, Pin_7, TIM_Channel_2, TIM4_IRQn, 0, Mode_IPD, 0}, // PWM12 - OUT4 - { TIM4, GPIOB, Pin_8, TIM_Channel_3, TIM4_IRQn, 0, Mode_IPD, 0}, // PWM13 - OUT5 - { TIM4, GPIOB, Pin_9, TIM_Channel_4, TIM4_IRQn, 0, Mode_IPD, 0} // PWM14 - OUT6 + { TIM2, IO_TAG(PA0), TIM_Channel_1, TIM2_IRQn, 0, Mode_IPD, 0}, // PWM1 - RC1 + { TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, 0, Mode_IPD, 0}, // PWM2 - RC2 + { TIM2, IO_TAG(PA2), TIM_Channel_3, TIM2_IRQn, 0, Mode_IPD, 0}, // PWM3 - RC3 + { TIM2, IO_TAG(PA3), TIM_Channel_4, TIM2_IRQn, 0, Mode_IPD, 0}, // PWM4 - RC4 + { TIM3, IO_TAG(PA6), TIM_Channel_1, TIM3_IRQn, 0, Mode_IPD, 0}, // PWM5 - RC5 + { TIM3, IO_TAG(PA7), TIM_Channel_2, TIM3_IRQn, 0, Mode_IPD, 0}, // PWM6 - RC6 + { TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, 0, Mode_IPD, 0}, // PWM7 - RC7 + { TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, 0, Mode_IPD, 0}, // PWM8 - RC8 + { TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, 1, Mode_IPD, 0}, // PWM9 - OUT1 + { TIM1, IO_TAG(PA11),TIM_Channel_4, TIM1_CC_IRQn, 1, Mode_IPD, 0}, // PWM10 - OUT2 + { TIM4, IO_TAG(PB6), TIM_Channel_1, TIM4_IRQn, 0, Mode_IPD, 0}, // PWM11 - OUT3 + { TIM4, IO_TAG(PB7), TIM_Channel_2, TIM4_IRQn, 0, Mode_IPD, 0}, // PWM12 - OUT4 + { TIM4, IO_TAG(PB8), TIM_Channel_3, TIM4_IRQn, 0, Mode_IPD, 0}, // PWM13 - OUT5 + { TIM4, IO_TAG(PB9), TIM_Channel_4, TIM4_IRQn, 0, Mode_IPD, 0} // PWM14 - OUT6 }; From cf6ca7293d6fe1ea8c33f7b61bd6697d8709f5d7 Mon Sep 17 00:00:00 2001 From: blckmn Date: Mon, 13 Jun 2016 10:19:25 +1000 Subject: [PATCH 04/22] Adding resource CLI command to see whats in use. --- src/main/drivers/resource.h | 6 ++-- src/main/drivers/serial_usb_vcp.c | 9 +++--- src/main/drivers/sound_beeper.c | 4 +-- src/main/io/serial_cli.c | 50 ++++++++++++++++++++++++++++++ src/main/target/BLUEJAYF4/target.h | 2 +- 5 files changed, 60 insertions(+), 11 deletions(-) diff --git a/src/main/drivers/resource.h b/src/main/drivers/resource.h index 7c10ba7ecb..b6cfed465f 100644 --- a/src/main/drivers/resource.h +++ b/src/main/drivers/resource.h @@ -6,8 +6,6 @@ typedef enum { OWNER_PWMINPUT, OWNER_PPMINPUT, OWNER_PWMOUTPUT_MOTOR, - OWNER_PWMOUTPUT_FAST, - OWNER_PWMOUTPUT_ONESHOT, OWNER_PWMOUTPUT_SERVO, OWNER_SOFTSERIAL_RX, OWNER_SOFTSERIAL_TX, @@ -23,7 +21,8 @@ typedef enum { OWNER_SYSTEM, OWNER_SDCARD, OWNER_FLASH, - OWNER_USB + OWNER_USB, + OWNER_BEEPER } 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) @@ -41,3 +40,4 @@ typedef enum { RESOURCE_I2C = 1 << 7, RESOURCE_SPI = 1 << 8, } resourceType_t; + diff --git a/src/main/drivers/serial_usb_vcp.c b/src/main/drivers/serial_usb_vcp.c index 0954027753..45a3702562 100644 --- a/src/main/drivers/serial_usb_vcp.c +++ b/src/main/drivers/serial_usb_vcp.c @@ -24,6 +24,7 @@ #include "build_config.h" #include "common/utils.h" +#include "drivers/io.h" #include "usb_core.h" #ifdef STM32F4 @@ -178,11 +179,9 @@ serialPort_t *usbVcpOpen(void) vcpPort_t *s; #ifdef STM32F4 - USBD_Init(&USB_OTG_dev, - USB_OTG_FS_CORE_ID, - &USR_desc, - &USBD_CDC_cb, - &USR_cb); + IOInit(IOGetByTag(IO_TAG(PA11)), OWNER_USB, RESOURCE_IO); + IOInit(IOGetByTag(IO_TAG(PA12)), OWNER_USB, RESOURCE_IO); + USBD_Init(&USB_OTG_dev, USB_OTG_FS_CORE_ID, &USR_desc, &USBD_CDC_cb, &USR_cb); #else Set_System(); Set_USBClock(); diff --git a/src/main/drivers/sound_beeper.c b/src/main/drivers/sound_beeper.c index 09294c2609..1e71845d20 100644 --- a/src/main/drivers/sound_beeper.c +++ b/src/main/drivers/sound_beeper.c @@ -24,7 +24,7 @@ #include "common/utils.h" #include "system.h" -#include "gpio.h" +#include "io.h" #include "sound_beeper.h" @@ -61,7 +61,7 @@ void beeperInit(const beeperConfig_t *config) beeperInverted = config->isInverted; if (beeperIO) { - IOInit(beeperIO, OWNER_SYSTEM, RESOURCE_OUTPUT); + IOInit(beeperIO, OWNER_BEEPER, RESOURCE_OUTPUT); IOConfigGPIO(beeperIO, config->isOD ? IOCFG_OUT_OD : IOCFG_OUT_PP); } systemBeep(false); diff --git a/src/main/io/serial_cli.c b/src/main/io/serial_cli.c index 2ea0b022fc..e057e6f926 100644 --- a/src/main/io/serial_cli.c +++ b/src/main/io/serial_cli.c @@ -44,6 +44,8 @@ #include "drivers/serial.h" #include "drivers/bus_i2c.h" #include "drivers/gpio.h" +#include "drivers/io.h" +#include "drivers/io_impl.h" #include "drivers/timer.h" #include "drivers/pwm_rx.h" #include "drivers/sdcard.h" @@ -139,6 +141,7 @@ static void cliTasks(char *cmdline); #endif static void cliVersion(char *cmdline); static void cliRxRange(char *cmdline); +static void cliResource(char *cmdline); #ifdef GPS static void cliGpsPassthrough(char *cmdline); @@ -298,6 +301,7 @@ const clicmd_t cmdTable[] = { CLI_COMMAND_DEF("profile", "change profile", "[]", cliProfile), CLI_COMMAND_DEF("rateprofile", "change rate profile", "[]", cliRateProfile), + CLI_COMMAND_DEF("resource", "view currently used resources", NULL, cliResource), CLI_COMMAND_DEF("rxrange", "configure rx channel ranges", NULL, cliRxRange), CLI_COMMAND_DEF("rxfail", "show/set rx failsafe settings", NULL, cliRxFail), CLI_COMMAND_DEF("save", "save and reboot", NULL, cliSave), @@ -1860,6 +1864,10 @@ static void dumpValues(uint16_t valueSection) cliPrintf("set %s = ", valueTable[i].name); cliPrintVar(value, 0); cliPrint("\r\n"); + +#ifdef STM32F4 + delayMicroseconds(1000); +#endif } } @@ -2993,6 +3001,48 @@ void cliProcess(void) } } +const char * const ownerNames[] = { + "FREE", + "PWM IN", + "PPM IN", + "MOTOR", + "SERVO", + "SOFTSERIAL RX", + "SOFTSERIAL TX", + "SOFTSERIAL RXTX", // bidirectional pin for softserial + "SOFTSERIAL AUXTIMER", // timer channel is used for softserial. No IO function on pin + "ADC", + "SERIAL RX", + "SERIAL TX", + "SERIAL RXTX", + "PINDEBUG", + "TIMER", + "SONAR", + "SYSTEM", + "SDCARD", + "FLASH", + "USB", + "BEEPER", +}; + +static void cliResource(char *cmdline) +{ + UNUSED(cmdline); + cliPrintf("IO:\r\n"); + for (unsigned i = 0; i < DEFIO_IO_USED_COUNT; i++) { + const char* owner; + char buff[15]; + if (ioRecs[i].owner < ARRAYLEN(ownerNames)) { + owner = ownerNames[ioRecs[i].owner]; + } + else { + sprintf(buff, "O=%d", ioRecs[i].owner); + owner = buff; + } + cliPrintf("%c%02d: %19s\r\n", IO_GPIOPortIdx(ioRecs + i) + 'A', IO_GPIOPinIdx(ioRecs + i), owner); + } +} + void cliInit(serialConfig_t *serialConfig) { UNUSED(serialConfig); diff --git a/src/main/target/BLUEJAYF4/target.h b/src/main/target/BLUEJAYF4/target.h index 5cb81ea900..da0b3921c4 100644 --- a/src/main/target/BLUEJAYF4/target.h +++ b/src/main/target/BLUEJAYF4/target.h @@ -146,7 +146,7 @@ #define TARGET_IO_PORTA 0xffff #define TARGET_IO_PORTB 0xffff #define TARGET_IO_PORTC 0xffff -#define TARGET_IO_PORTD 0xffff +#define TARGET_IO_PORTD (BIT(2)) #define USED_TIMERS ( TIM_N(2) | TIM_N(3) | TIM_N(5) | TIM_N(8) | TIM_N(9)) #define TIMER_APB1_PERIPHERALS (RCC_APB1Periph_TIM2 | RCC_APB1Periph_TIM3 | RCC_APB1Periph_TIM5 | RCC_AHB1Periph_GPIOA | RCC_AHB1Periph_GPIOB | RCC_AHB1Periph_GPIOC) From 0e7fd2056960dbc66e4f46279dffff4fbab8ff6d Mon Sep 17 00:00:00 2001 From: blckmn Date: Mon, 13 Jun 2016 10:47:04 +1000 Subject: [PATCH 05/22] ALIENFLIGHT targets NAZE and BLUEJAY correction --- src/main/drivers/io.h | 33 +++++++++++++------------- src/main/drivers/pwm_mapping.c | 4 ++-- src/main/target/ALIENFLIGHTF3/target.c | 29 +++++++++++----------- src/main/target/ALIENFLIGHTF4/target.c | 27 +++++++++++---------- src/main/target/BLUEJAYF4/target.c | 14 +++++------ src/main/target/NAZE/target.c | 28 +++++++++++----------- 6 files changed, 69 insertions(+), 66 deletions(-) diff --git a/src/main/drivers/io.h b/src/main/drivers/io.h index 74c4fbbaeb..e7ee16480b 100644 --- a/src/main/drivers/io.h +++ b/src/main/drivers/io.h @@ -37,27 +37,28 @@ typedef uint8_t ioConfig_t; // packed IO configuration #if defined(STM32F1) // mode is using only bits 6-2 -# define IO_CONFIG(mode, speed) ((mode) | (speed)) +#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_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) #elif defined(STM32F3) -# define IO_CONFIG(mode, speed, otype, pupd) ((mode) | ((speed) << 2) | ((otype) << 4) | ((pupd) << 5)) +#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_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_PP_PD IO_CONFIG(GPIO_Mode_AF, 0, GPIO_OType_PP, GPIO_PuPd_DOWN) +#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) #elif defined(STM32F4) diff --git a/src/main/drivers/pwm_mapping.c b/src/main/drivers/pwm_mapping.c index 73308581ba..e8c6e6b31a 100755 --- a/src/main/drivers/pwm_mapping.c +++ b/src/main/drivers/pwm_mapping.c @@ -144,7 +144,7 @@ pwmOutputConfiguration_t *pwmInit(drv_pwm_config_t *init) #if defined(STM32F303xC) && defined(USE_USART3) // skip UART3 ports (PB10/PB11) - if (init->useUART3 && (CheckGPIOPin(timerHardwarePtr->pin, UART3_GPIO, UART3_TX_PIN) || CheckGPIOPin(timerHardwarePtr->pin, UART3_GPIO, UART3_RX_PIN)) + if (init->useUART3 && (CheckGPIOPin(timerHardwarePtr->pin, UART3_GPIO, UART3_TX_PIN) || CheckGPIOPin(timerHardwarePtr->pin, UART3_GPIO, UART3_RX_PIN))) continue; #endif @@ -163,7 +163,7 @@ pwmOutputConfiguration_t *pwmInit(drv_pwm_config_t *init) if (timerHardwarePtr->tim == LED_STRIP_TIMER) continue; #if defined(STM32F303xC) && defined(WS2811_GPIO) && defined(WS2811_PIN_SOURCE) - if (CheckGPIOPinSource(timerHardwarePtr->pin, WS2811_GPIO, WS2811_PIN_SOURCE) + if (CheckGPIOPinSource(timerHardwarePtr->pin, WS2811_GPIO, WS2811_PIN_SOURCE)) continue; #endif } diff --git a/src/main/target/ALIENFLIGHTF3/target.c b/src/main/target/ALIENFLIGHTF3/target.c index 5af01ce9d8..7b7e6c163d 100644 --- a/src/main/target/ALIENFLIGHTF3/target.c +++ b/src/main/target/ALIENFLIGHTF3/target.c @@ -3,6 +3,7 @@ #include #include +#include "drivers/io.h" #include "drivers/pwm_mapping.h" const uint16_t multiPPM[] = { @@ -51,33 +52,33 @@ const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { // 6 x 3 pin headers // - { TIM15, GPIOB, Pin_15, TIM_Channel_2, TIM1_BRK_TIM15_IRQn, 1, Mode_AF_PP, GPIO_PinSource15, GPIO_AF_1, 0}, // PWM1 - PB15 - TIM1_CH3N, TIM15_CH1N, *TIM15_CH2 - { TIM15, GPIOB, Pin_14, TIM_Channel_1, TIM1_BRK_TIM15_IRQn, 1, Mode_AF_PP, GPIO_PinSource14, GPIO_AF_1, 0}, // PWM2 - PB14 - TIM1_CH2N, *TIM15_CH1 - { TIM1, GPIOA, Pin_8, TIM_Channel_1, TIM1_CC_IRQn, 1, Mode_AF_PP, GPIO_PinSource8, GPIO_AF_6, 0}, // PWM3 - PA8 - *TIM1_CH1, TIM4_ETR - { TIM3, GPIOB, Pin_0, TIM_Channel_3, TIM3_IRQn, 0, Mode_AF_PP, GPIO_PinSource0, GPIO_AF_2, 0}, // PWM4 - PB0 - *TIM3_CH3, TIM1_CH2N, TIM8_CH2N - { TIM3, GPIOA, Pin_6, TIM_Channel_1, TIM3_IRQn, 0, Mode_AF_PP, GPIO_PinSource6, GPIO_AF_2, 0}, // PWM5 - PA6 - *TIM3_CH1, TIM8_BKIN, TIM1_BKIN, TIM16_CH1 - { TIM2, GPIOA, Pin_2, TIM_Channel_3, TIM2_IRQn, 0, Mode_AF_PP, GPIO_PinSource2, GPIO_AF_1, 0}, // PWM6 - PA2 - *TIM2_CH3, !TIM15_CH1 + { TIM15, IO_TAG(PB15), TIM_Channel_2, TIM1_BRK_TIM15_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1, 0}, // PWM1 - PB15 - TIM1_CH3N, TIM15_CH1N, *TIM15_CH2 + { TIM15, IO_TAG(PB14), TIM_Channel_1, TIM1_BRK_TIM15_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1, 0}, // PWM2 - PB14 - TIM1_CH2N, *TIM15_CH1 + { TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, 1, IOCFG_AF_PP, GPIO_AF_6, 0}, // PWM3 - PA8 - *TIM1_CH1, TIM4_ETR + { TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2, 0}, // PWM4 - PB0 - *TIM3_CH3, TIM1_CH2N, TIM8_CH2N + { TIM3, IO_TAG(PA6), TIM_Channel_1, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2, 0}, // PWM5 - PA6 - *TIM3_CH1, TIM8_BKIN, TIM1_BKIN, TIM16_CH1 + { TIM2, IO_TAG(PA2), TIM_Channel_3, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1, 0}, // PWM6 - PA2 - *TIM2_CH3, !TIM15_CH1 // // 6 pin header // // PWM7-10 - { TIM3, GPIOB, Pin_1, TIM_Channel_4, TIM3_IRQn, 0, Mode_AF_PP, GPIO_PinSource1, GPIO_AF_2, 0}, // PWM7 - PB1 - *TIM3_CH4, TIM1_CH3N, TIM8_CH3N - { TIM17, GPIOA, Pin_7, TIM_Channel_1, TIM1_TRG_COM_TIM17_IRQn, 1, Mode_AF_PP, GPIO_PinSource7, GPIO_AF_1, 0}, // PWM8 - PA7 - !TIM3_CH2, *TIM17_CH1, TIM1_CH1N, TIM8_CH1 - { TIM3, GPIOA, Pin_4, TIM_Channel_2, TIM3_IRQn, 0, Mode_AF_PP, GPIO_PinSource4, GPIO_AF_2, 0}, // PWM9 - PA4 - *TIM3_CH2 - { TIM2, GPIOA, Pin_1, TIM_Channel_2, TIM2_IRQn, 0, Mode_AF_PP, GPIO_PinSource1, GPIO_AF_1, 0}, // PWM10 - PA1 - *TIM2_CH2, TIM15_CH1N + { TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2, 0}, // PWM7 - PB1 - *TIM3_CH4, TIM1_CH3N, TIM8_CH3N + { TIM17, IO_TAG(PA7), TIM_Channel_1, TIM1_TRG_COM_TIM17_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1, 0}, // PWM8 - PA7 - !TIM3_CH2, *TIM17_CH1, TIM1_CH1N, TIM8_CH1 + { TIM3, IO_TAG(PA4), TIM_Channel_2, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2, 0}, // PWM9 - PA4 - *TIM3_CH2 + { TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1, 0}, // PWM10 - PA1 - *TIM2_CH2, TIM15_CH1N // // PPM PORT - Also USART2 RX (AF5) // - { TIM2, GPIOA, Pin_3, TIM_Channel_4, TIM2_IRQn, 0, Mode_AF_PP_PD, GPIO_PinSource3, GPIO_AF_1, 0} // PPM - PA3 - TIM2_CH4, TIM15_CH2 - PWM13 - //{ TIM15, GPIOA, Pin_3, TIM_Channel_2, TIM1_BRK_TIM15_IRQn, 0, Mode_AF_PP_PD, GPIO_PinSource3, GPIO_AF_9, 0} // PPM - PA3 - TIM2_CH4, TIM15_CH2 - PWM13 + { TIM2, IO_TAG(PA3), TIM_Channel_4, TIM2_IRQn, 0, IOCFG_IPD, GPIO_AF_1, 0} // PPM - PA3 - TIM2_CH4, TIM15_CH2 - PWM13 + //{ TIM15, GPIOA, Pin_3, TIM_Channel_2, TIM1_BRK_TIM15_IRQn, 0, IOCFG_IPD, GPIO_PinSource3, GPIO_AF_9, 0} // PPM - PA3 - TIM2_CH4, TIM15_CH2 - PWM13 // USART3 RX/TX // RX conflicts with PPM port - //{ TIM2, GPIOB, Pin_11, TIM_Channel_4, TIM3_IRQn, 0, Mode_AF_PP, GPIO_PinSource11, GPIO_AF_1, 0} // RX - PB11 - *TIM2_CH4, USART3_RX (AF7) - PWM11 - //{ TIM2, GPIOB, Pin_10, TIM_Channel_3, TIM3_IRQn, 0, Mode_AF_PP, GPIO_PinSource10, GPIO_AF_1, 0} // TX - PB10 - *TIM2_CH3, USART3_TX (AF7) - PWM12 + //{ TIM2, GPIOB, Pin_11, TIM_Channel_4, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_PinSource11, GPIO_AF_1, 0} // RX - PB11 - *TIM2_CH4, USART3_RX (AF7) - PWM11 + //{ TIM2, GPIOB, Pin_10, TIM_Channel_3, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_PinSource10, GPIO_AF_1, 0} // TX - PB10 - *TIM2_CH3, USART3_TX (AF7) - PWM12 }; diff --git a/src/main/target/ALIENFLIGHTF4/target.c b/src/main/target/ALIENFLIGHTF4/target.c index 2b90d71750..02efa0b5e6 100644 --- a/src/main/target/ALIENFLIGHTF4/target.c +++ b/src/main/target/ALIENFLIGHTF4/target.c @@ -1,6 +1,7 @@ #include #include +#include "drivers/io.h" #include "drivers/pwm_mapping.h" const uint16_t multiPPM[] = { @@ -72,19 +73,19 @@ const uint16_t airPWM[] = { }; const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { - { TIM1, GPIOA, Pin_8, TIM_Channel_1, TIM1_CC_IRQn, 0, GPIO_Mode_AF, GPIO_PinSource8, GPIO_AF_TIM1, 0}, // PWM1 - PA8 RC1 - { TIM1, GPIOB, Pin_0, TIM_Channel_2, TIM1_CC_IRQn, 0, GPIO_Mode_AF, GPIO_PinSource0, GPIO_AF_TIM1, 0}, // PWM2 - PB0 RC2 - { TIM1, GPIOB, Pin_1, TIM_Channel_3, TIM1_CC_IRQn, 0, GPIO_Mode_AF, GPIO_PinSource1, GPIO_AF_TIM1, 0}, // PWM3 - PB1 RC3 - { TIM8, GPIOB, Pin_14,TIM_Channel_2, TIM8_CC_IRQn, 0, GPIO_Mode_AF, GPIO_PinSource14, GPIO_AF_TIM8, 0}, // PWM4 - PA14 RC4 - { TIM8, GPIOB, Pin_15,TIM_Channel_3, TIM8_CC_IRQn, 0, GPIO_Mode_AF, GPIO_PinSource15, GPIO_AF_TIM8, 0}, // PWM5 - PA15 RC5 + { TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM1, 0}, // PWM1 - PA8 RC1 + { TIM1, IO_TAG(PB0), TIM_Channel_2, TIM1_CC_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM1, 0}, // PWM2 - PB0 RC2 + { TIM1, IO_TAG(PB1), TIM_Channel_3, TIM1_CC_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM1, 0}, // PWM3 - PB1 RC3 + { TIM8, IO_TAG(PB14),TIM_Channel_2, TIM8_CC_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM8, 0}, // PWM4 - PA14 RC4 + { TIM8, IO_TAG(PB15),TIM_Channel_3, TIM8_CC_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM8, 0}, // PWM5 - PA15 RC5 - { TIM4, GPIOB, Pin_8, TIM_Channel_3, TIM4_IRQn, 1, GPIO_Mode_AF, GPIO_PinSource8, GPIO_AF_TIM4, 0}, // PWM6 - PB8 OUT1 - { TIM4, GPIOB, Pin_9, TIM_Channel_4, TIM4_IRQn, 1, GPIO_Mode_AF, GPIO_PinSource9, GPIO_AF_TIM4, 0}, // PWM7 - PB9 OUT2 - { TIM5, GPIOA, Pin_0, TIM_Channel_1, TIM5_IRQn, 1, GPIO_Mode_AF, GPIO_PinSource0, GPIO_AF_TIM5, 0}, // PWM8 - PA0 OUT3 - { TIM5, GPIOA, Pin_1, TIM_Channel_2, TIM5_IRQn, 1, GPIO_Mode_AF, GPIO_PinSource1, GPIO_AF_TIM5, 0}, // PWM9 - PA1 OUT4 - { TIM3, GPIOC, Pin_6, TIM_Channel_1, TIM3_IRQn, 1, GPIO_Mode_AF, GPIO_PinSource6, GPIO_AF_TIM3, 0}, // PWM10 - PC6 OUT5 - { TIM3, GPIOC, Pin_7, TIM_Channel_2, TIM3_IRQn, 1, GPIO_Mode_AF, GPIO_PinSource7, GPIO_AF_TIM3, 0}, // PWM11 - PC7 OUT6 - { TIM3, GPIOC, Pin_8, TIM_Channel_3, TIM3_IRQn, 1, GPIO_Mode_AF, GPIO_PinSource8, GPIO_AF_TIM3, 0}, // PWM13 - PC8 OUT7 - { TIM3, GPIOC, Pin_9, TIM_Channel_4, TIM3_IRQn, 1, GPIO_Mode_AF, GPIO_PinSource9, GPIO_AF_TIM3, 0}, // PWM13 - PC9 OUT8 + { TIM4, IO_TAG(PB8), TIM_Channel_3, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM4, 0}, // PWM6 - PB8 OUT1 + { TIM4, IO_TAG(PB9), TIM_Channel_4, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM4, 0}, // PWM7 - PB9 OUT2 + { TIM5, IO_TAG(PA0), TIM_Channel_1, TIM5_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM5, 0}, // PWM8 - PA0 OUT3 + { TIM5, IO_TAG(PA1), TIM_Channel_2, TIM5_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM5, 0}, // PWM9 - PA1 OUT4 + { TIM3, IO_TAG(PC6), TIM_Channel_1, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM3, 0}, // PWM10 - PC6 OUT5 + { TIM3, IO_TAG(PC7), TIM_Channel_2, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM3, 0}, // PWM11 - PC7 OUT6 + { TIM3, IO_TAG(PC8), TIM_Channel_3, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM3, 0}, // PWM13 - PC8 OUT7 + { TIM3, IO_TAG(PC9), TIM_Channel_4, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM3, 0}, // PWM13 - PC9 OUT8 }; diff --git a/src/main/target/BLUEJAYF4/target.c b/src/main/target/BLUEJAYF4/target.c index 512e667f9f..e7e0aaf82d 100644 --- a/src/main/target/BLUEJAYF4/target.c +++ b/src/main/target/BLUEJAYF4/target.c @@ -51,12 +51,12 @@ const uint16_t airPWM[] = { }; const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { - { TIM8, IO_TAG(PC7), TIM_Channel_2, TIM8_CC_IRQn, 0, Mode_IPD, GPIO_AF_TIM8, 0 }, // PPM IN - { TIM5, IO_TAG(PA0), TIM_Channel_1, TIM5_IRQn, 1, Mode_AF_PP, GPIO_AF_TIM5, 0}, // S1_OUT - { TIM5, IO_TAG(PA1), TIM_Channel_2, TIM5_IRQn, 1, Mode_AF_PP, GPIO_AF_TIM5, 0}, // S2_OUT - { TIM2, IO_TAG(PA2), TIM_Channel_3, TIM2_IRQn, 1, Mode_AF_PP, GPIO_AF_TIM2, 0}, // S3_OUT - { TIM9, IO_TAG(PA3), TIM_Channel_2, TIM1_BRK_TIM9_IRQn, 1, Mode_AF_PP, GPIO_AF_TIM9, 0}, // S4_OUT - { TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, 1, Mode_AF_PP, GPIO_AF_TIM3, 0}, // S5_OUT - { TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, 1, Mode_AF_PP, GPIO_AF_TIM3, 0}, // S6_OUT + { TIM8, IO_TAG(PC7), TIM_Channel_2, TIM8_CC_IRQn, 0, IOCFG_IPD, GPIO_AF_TIM8, 0 }, // PPM IN + { TIM5, IO_TAG(PA0), TIM_Channel_1, TIM5_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM5, 0}, // S1_OUT + { TIM5, IO_TAG(PA1), TIM_Channel_2, TIM5_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM5, 0}, // S2_OUT + { TIM2, IO_TAG(PA2), TIM_Channel_3, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM2, 0}, // S3_OUT + { TIM9, IO_TAG(PA3), TIM_Channel_2, TIM1_BRK_TIM9_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM9, 0}, // S4_OUT + { TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM3, 0}, // S5_OUT + { TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM3, 0}, // S6_OUT }; diff --git a/src/main/target/NAZE/target.c b/src/main/target/NAZE/target.c index 5cf715ec1b..41c3c0b4a7 100644 --- a/src/main/target/NAZE/target.c +++ b/src/main/target/NAZE/target.c @@ -72,19 +72,19 @@ const uint16_t airPWM[] = { }; const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { - { TIM2, IO_TAG(PA0), TIM_Channel_1, TIM2_IRQn, 0, Mode_IPD, 0}, // PWM1 - RC1 - { TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, 0, Mode_IPD, 0}, // PWM2 - RC2 - { TIM2, IO_TAG(PA2), TIM_Channel_3, TIM2_IRQn, 0, Mode_IPD, 0}, // PWM3 - RC3 - { TIM2, IO_TAG(PA3), TIM_Channel_4, TIM2_IRQn, 0, Mode_IPD, 0}, // PWM4 - RC4 - { TIM3, IO_TAG(PA6), TIM_Channel_1, TIM3_IRQn, 0, Mode_IPD, 0}, // PWM5 - RC5 - { TIM3, IO_TAG(PA7), TIM_Channel_2, TIM3_IRQn, 0, Mode_IPD, 0}, // PWM6 - RC6 - { TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, 0, Mode_IPD, 0}, // PWM7 - RC7 - { TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, 0, Mode_IPD, 0}, // PWM8 - RC8 - { TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, 1, Mode_IPD, 0}, // PWM9 - OUT1 - { TIM1, IO_TAG(PA11),TIM_Channel_4, TIM1_CC_IRQn, 1, Mode_IPD, 0}, // PWM10 - OUT2 - { TIM4, IO_TAG(PB6), TIM_Channel_1, TIM4_IRQn, 0, Mode_IPD, 0}, // PWM11 - OUT3 - { TIM4, IO_TAG(PB7), TIM_Channel_2, TIM4_IRQn, 0, Mode_IPD, 0}, // PWM12 - OUT4 - { TIM4, IO_TAG(PB8), TIM_Channel_3, TIM4_IRQn, 0, Mode_IPD, 0}, // PWM13 - OUT5 - { TIM4, IO_TAG(PB9), TIM_Channel_4, TIM4_IRQn, 0, Mode_IPD, 0} // PWM14 - OUT6 + { TIM2, IO_TAG(PA0), TIM_Channel_1, TIM2_IRQn, 0, IOCFG_IPD, 0}, // PWM1 - RC1 + { TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, 0, IOCFG_IPD, 0}, // PWM2 - RC2 + { TIM2, IO_TAG(PA2), TIM_Channel_3, TIM2_IRQn, 0, IOCFG_IPD, 0}, // PWM3 - RC3 + { TIM2, IO_TAG(PA3), TIM_Channel_4, TIM2_IRQn, 0, IOCFG_IPD, 0}, // PWM4 - RC4 + { TIM3, IO_TAG(PA6), TIM_Channel_1, TIM3_IRQn, 0, IOCFG_IPD, 0}, // PWM5 - RC5 + { TIM3, IO_TAG(PA7), TIM_Channel_2, TIM3_IRQn, 0, IOCFG_IPD, 0}, // PWM6 - RC6 + { TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, 0, IOCFG_IPD, 0}, // PWM7 - RC7 + { TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, 0, IOCFG_IPD, 0}, // PWM8 - RC8 + { TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, 1, IOCFG_IPD, 0}, // PWM9 - OUT1 + { TIM1, IO_TAG(PA11),TIM_Channel_4, TIM1_CC_IRQn, 1, IOCFG_IPD, 0}, // PWM10 - OUT2 + { TIM4, IO_TAG(PB6), TIM_Channel_1, TIM4_IRQn, 0, IOCFG_IPD, 0}, // PWM11 - OUT3 + { TIM4, IO_TAG(PB7), TIM_Channel_2, TIM4_IRQn, 0, IOCFG_IPD, 0}, // PWM12 - OUT4 + { TIM4, IO_TAG(PB8), TIM_Channel_3, TIM4_IRQn, 0, IOCFG_IPD, 0}, // PWM13 - OUT5 + { TIM4, IO_TAG(PB9), TIM_Channel_4, TIM4_IRQn, 0, IOCFG_IPD, 0} // PWM14 - OUT6 }; From d81d445165d27532c4be937906b3619d45f242e7 Mon Sep 17 00:00:00 2001 From: blckmn Date: Mon, 13 Jun 2016 15:33:29 +1000 Subject: [PATCH 06/22] Adjusted all other targets --- src/main/drivers/adc_stm32f30x.c | 3 +- src/main/drivers/barometer_bmp085.c | 1 - src/main/drivers/io.h | 14 +------- src/main/target/CC3D/target.c | 26 +++++++------- src/main/target/CHEBUZZF3/target.c | 39 ++++++++++---------- src/main/target/CHEBUZZF3/target.h | 4 +-- src/main/target/CJMCU/target.c | 29 +++++++-------- src/main/target/COLIBRI_RACE/target.c | 26 +++++++------- src/main/target/DOGE/target.c | 18 +++++----- src/main/target/EUSTM32F103RC/target.c | 28 +++++++-------- src/main/target/FURYF3/target.c | 16 ++++----- src/main/target/FURYF4/target.c | 10 +++--- src/main/target/IRCFUSIONF3/target.c | 34 +++++++++--------- src/main/target/KISSFC/target.c | 24 ++++++------- src/main/target/LUX_RACE/target.c | 25 ++++++------- src/main/target/MOTOLAB/target.c | 19 +++++----- src/main/target/NAZE/target.c | 28 +++++++-------- src/main/target/NAZE32PRO/target.c | 29 ++++++++------- src/main/target/OLIMEXINO/target.c | 29 +++++++-------- src/main/target/PORT103R/target.c | 28 +++++++-------- src/main/target/REVO/target.c | 26 +++++++------- src/main/target/RMDO/target.c | 34 +++++++++--------- src/main/target/SINGULARITY/target.c | 23 ++++++------ src/main/target/SPARKY/target.c | 44 ++++++----------------- src/main/target/SPRACINGF3/target.c | 35 +++++++++--------- src/main/target/SPRACINGF3EVO/target.c | 30 +++++++--------- src/main/target/SPRACINGF3MINI/target.c | 27 +++++++------- src/main/target/STM32F3DISCOVERY/target.c | 29 +++++++-------- 28 files changed, 317 insertions(+), 361 deletions(-) diff --git a/src/main/drivers/adc_stm32f30x.c b/src/main/drivers/adc_stm32f30x.c index 68f1177b5c..97f6ee525b 100644 --- a/src/main/drivers/adc_stm32f30x.c +++ b/src/main/drivers/adc_stm32f30x.c @@ -21,7 +21,7 @@ #include "platform.h" #include "system.h" - +#include "common/utils.h" #include "gpio.h" #include "sensor.h" @@ -38,6 +38,7 @@ void adcInit(drv_adc_config_t *init) { + UNUSED(init); ADC_InitTypeDef ADC_InitStructure; DMA_InitTypeDef DMA_InitStructure; GPIO_InitTypeDef GPIO_InitStructure; diff --git a/src/main/drivers/barometer_bmp085.c b/src/main/drivers/barometer_bmp085.c index 951bc62ab9..a746500b56 100644 --- a/src/main/drivers/barometer_bmp085.c +++ b/src/main/drivers/barometer_bmp085.c @@ -52,7 +52,6 @@ void bmp085_extiHandler(extiCallbackRec_t* cb) bool bmp085TestEOCConnected(const bmp085Config_t *config); # endif - typedef struct { int16_t ac1; int16_t ac2; diff --git a/src/main/drivers/io.h b/src/main/drivers/io.h index e7ee16480b..dfc13aebbb 100644 --- a/src/main/drivers/io.h +++ b/src/main/drivers/io.h @@ -47,7 +47,7 @@ typedef uint8_t ioConfig_t; // packed IO configuration #define IOCFG_IPU IO_CONFIG(GPIO_Mode_IPU, GPIO_Speed_2MHz) #define IOCFG_IN_FLOATING IO_CONFIG(GPIO_Mode_IN_FLOATING, GPIO_Speed_2MHz) -#elif defined(STM32F3) +#elif defined(STM32F3) || defined(STM32F4) #define IO_CONFIG(mode, speed, otype, pupd) ((mode) | ((speed) << 2) | ((otype) << 4) | ((pupd) << 5)) @@ -55,18 +55,6 @@ typedef uint8_t ioConfig_t; // packed IO configuration #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_PP_PD IO_CONFIG(GPIO_Mode_AF, 0, GPIO_OType_PP, GPIO_PuPd_DOWN) -#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) - -#elif defined(STM32F4) - -#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_PP_UP IO_CONFIG(GPIO_Mode_AF, 0, GPIO_OType_PP, GPIO_PuPd_UP) #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) diff --git a/src/main/target/CC3D/target.c b/src/main/target/CC3D/target.c index db26673d11..b146e6a72b 100644 --- a/src/main/target/CC3D/target.c +++ b/src/main/target/CC3D/target.c @@ -3,6 +3,7 @@ #include #include +#include "drivers/io.h" #include "drivers/pwm_mapping.h" const uint16_t multiPPM[] = { @@ -127,18 +128,17 @@ const uint16_t airPWM_BP6[] = { const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { - { TIM4, GPIOB, Pin_6, TIM_Channel_1, TIM4_IRQn, 0, Mode_IPD, 0}, // S1_IN - { TIM3, GPIOB, Pin_5, TIM_Channel_2, TIM3_IRQn, 0, Mode_IPD, 0}, // S2_IN - SoftSerial TX - GPIO_PartialRemap_TIM3 / Sonar trigger - { TIM3, GPIOB, Pin_0, TIM_Channel_3, TIM3_IRQn, 0, Mode_IPD, 0}, // S3_IN - SoftSerial RX / Sonar echo / RSSI ADC - { TIM3, GPIOB, Pin_1, TIM_Channel_4, TIM3_IRQn, 0, Mode_IPD, 0}, // S4_IN - Current - { TIM2, GPIOA, Pin_0, TIM_Channel_1, TIM2_IRQn, 0, Mode_IPD, 0}, // S5_IN - Vbattery - { TIM2, GPIOA, Pin_1, TIM_Channel_2, TIM2_IRQn, 0, Mode_IPD, 0}, // S6_IN - PPM IN - - { TIM4, GPIOB, Pin_9, TIM_Channel_4, TIM4_IRQn, 1, GPIO_Mode_AF_PP, 0}, // S1_OUT - { TIM4, GPIOB, Pin_8, TIM_Channel_3, TIM4_IRQn, 1, GPIO_Mode_AF_PP, 0}, // S2_OUT - { TIM4, GPIOB, Pin_7, TIM_Channel_2, TIM4_IRQn, 1, GPIO_Mode_AF_PP, 0}, // S3_OUT - { TIM1, GPIOA, Pin_8, TIM_Channel_1, TIM1_CC_IRQn, 1, GPIO_Mode_AF_PP, 0}, // S4_OUT - { TIM3, GPIOB, Pin_4, TIM_Channel_1, TIM3_IRQn, 1, GPIO_Mode_AF_PP, 0}, // S5_OUT - GPIO_PartialRemap_TIM3 - LED Strip - { TIM2, GPIOA, Pin_2, TIM_Channel_3, TIM2_IRQn, 1, GPIO_Mode_AF_PP, 0} // S6_OUT + { TIM4, IO_TAG(PB6), TIM_Channel_1, TIM4_IRQn, 0, IOCFG_IPD, 0}, // S1_IN + { TIM3, IO_TAG(PB5), TIM_Channel_2, TIM3_IRQn, 0, IOCFG_IPD, 0}, // S2_IN - SoftSerial TX - GPIO_PartialRemap_TIM3 / Sonar trigger + { TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, 0, IOCFG_IPD, 0}, // S3_IN - SoftSerial RX / Sonar echo / RSSI ADC + { TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, 0, IOCFG_IPD, 0}, // S4_IN - Current + { TIM2, IO_TAG(PA0), TIM_Channel_1, TIM2_IRQn, 0, IOCFG_IPD, 0}, // S5_IN - Vbattery + { TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, 0, IOCFG_IPD, 0}, // S6_IN - PPM IN + { TIM4, IO_TAG(PB9), TIM_Channel_4, TIM4_IRQn, 1, IOCFG_AF_PP, 0}, // S1_OUT + { TIM4, IO_TAG(PB8), TIM_Channel_3, TIM4_IRQn, 1, IOCFG_AF_PP, 0}, // S2_OUT + { TIM4, IO_TAG(PB7), TIM_Channel_2, TIM4_IRQn, 1, IOCFG_AF_PP, 0}, // S3_OUT + { TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, 1, IOCFG_AF_PP, 0}, // S4_OUT + { TIM3, IO_TAG(PB4), TIM_Channel_1, TIM3_IRQn, 1, IOCFG_AF_PP, 0}, // S5_OUT - GPIO_PartialRemap_TIM3 - LED Strip + { TIM2, IO_TAG(PA2), TIM_Channel_3, TIM2_IRQn, 1, IOCFG_AF_PP, 0} // S6_OUT }; diff --git a/src/main/target/CHEBUZZF3/target.c b/src/main/target/CHEBUZZF3/target.c index 9bfabe7fb3..3099e24e73 100644 --- a/src/main/target/CHEBUZZF3/target.c +++ b/src/main/target/CHEBUZZF3/target.c @@ -3,6 +3,7 @@ #include #include +#include "drivers/io.h" #include "drivers/pwm_mapping.h" const uint16_t multiPPM[] = { @@ -73,25 +74,23 @@ const uint16_t airPWM[] = { const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { // INPUTS CH1-8 - { TIM1, GPIOA, Pin_8, TIM_Channel_1, TIM1_CC_IRQn, 1, Mode_AF_PP_PD, GPIO_PinSource8, GPIO_AF_6, 0}, // PWM1 - PA8 - { TIM16, GPIOB, Pin_8, TIM_Channel_1, TIM1_UP_TIM16_IRQn, 0, Mode_AF_PP_PD, GPIO_PinSource8, GPIO_AF_1, 0}, // PWM2 - PB8 - { TIM17, GPIOB, Pin_9, TIM_Channel_1, TIM1_TRG_COM_TIM17_IRQn, 0, Mode_AF_PP_PD, GPIO_PinSource9, GPIO_AF_1, 0}, // PWM3 - PB9 - { TIM8, GPIOC, Pin_6, TIM_Channel_1, TIM8_CC_IRQn, 1, Mode_AF_PP_PD, GPIO_PinSource6, GPIO_AF_4, 0}, // PWM4 - PC6 - { TIM8, GPIOC, Pin_7, TIM_Channel_2, TIM8_CC_IRQn, 1, Mode_AF_PP_PD, GPIO_PinSource7, GPIO_AF_4, 0}, // PWM5 - PC7 - { TIM8, GPIOC, Pin_8, TIM_Channel_3, TIM8_CC_IRQn, 1, Mode_AF_PP_PD, GPIO_PinSource8, GPIO_AF_4, 0}, // PWM6 - PC8 - { TIM15, GPIOF, Pin_9, TIM_Channel_1, TIM1_BRK_TIM15_IRQn, 0, Mode_AF_PP_PD, GPIO_PinSource9, GPIO_AF_3, 0}, // PWM7 - PF9 - { TIM15, GPIOF, Pin_10, TIM_Channel_2, TIM1_BRK_TIM15_IRQn, 0, Mode_AF_PP_PD, GPIO_PinSource10, GPIO_AF_3, 0}, // PWM8 - PF10 - - // OUTPUTS CH1-10 - { TIM4, GPIOD, Pin_12, TIM_Channel_1, TIM4_IRQn, 0, Mode_AF_PP, GPIO_PinSource12, GPIO_AF_2, 0}, // PWM9 - PD12 - { TIM4, GPIOD, Pin_13, TIM_Channel_2, TIM4_IRQn, 0, Mode_AF_PP, GPIO_PinSource13, GPIO_AF_2, 0}, // PWM10 - PD13 - { TIM4, GPIOD, Pin_14, TIM_Channel_3, TIM4_IRQn, 0, Mode_AF_PP, GPIO_PinSource14, GPIO_AF_2, 0}, // PWM11 - PD14 - { TIM4, GPIOD, Pin_15, TIM_Channel_4, TIM4_IRQn, 0, Mode_AF_PP, GPIO_PinSource15, GPIO_AF_2, 0}, // PWM12 - PD15 - { TIM2, GPIOA, Pin_1, TIM_Channel_2, TIM2_IRQn, 0, Mode_AF_PP, GPIO_PinSource1, GPIO_AF_1, 0}, // PWM13 - PA1 - { TIM2, GPIOA, Pin_2, TIM_Channel_3, TIM2_IRQn, 0, Mode_AF_PP, GPIO_PinSource2, GPIO_AF_1, 0}, // PWM14 - PA2 - { TIM2, GPIOA, Pin_3, TIM_Channel_4, TIM2_IRQn, 0, Mode_AF_PP, GPIO_PinSource3, GPIO_AF_1, 0}, // PWM15 - PA3 - { TIM3, GPIOB, Pin_0, TIM_Channel_3, TIM3_IRQn, 0, Mode_AF_PP, GPIO_PinSource0, GPIO_AF_2, 0}, // PWM16 - PB0 - { TIM3, GPIOB, Pin_1, TIM_Channel_4, TIM3_IRQn, 0, Mode_AF_PP, GPIO_PinSource1, GPIO_AF_2, 0}, // PWM17 - PB1 - { TIM3, GPIOA, Pin_4, TIM_Channel_2, TIM3_IRQn, 0, Mode_AF_PP, GPIO_PinSource4, GPIO_AF_2, 0} // PWM18 - PA4 + { TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, 1, IOCFG_AF_PP_PD, GPIO_AF_6, 0}, // PWM1 - PA8 + { TIM16, IO_TAG(PB8), TIM_Channel_1, TIM1_UP_TIM16_IRQn, 0, IOCFG_AF_PP_PD, GPIO_AF_1, 0}, // PWM2 - PB8 + { TIM17, IO_TAG(PB9), TIM_Channel_1, TIM1_TRG_COM_TIM17_IRQn, 0, IOCFG_AF_PP_PD, GPIO_AF_1, 0}, // PWM3 - PB9 + { TIM8, IO_TAG(PC6), TIM_Channel_1, TIM8_CC_IRQn, 1, IOCFG_AF_PP_PD, GPIO_AF_4, 0}, // PWM4 - PC6 + { TIM8, IO_TAG(PC7), TIM_Channel_2, TIM8_CC_IRQn, 1, IOCFG_AF_PP_PD, GPIO_AF_4, 0}, // PWM5 - PC7 + { TIM8, IO_TAG(PC8), TIM_Channel_3, TIM8_CC_IRQn, 1, IOCFG_AF_PP_PD, GPIO_AF_4, 0}, // PWM6 - PC8 + { TIM15, IO_TAG(PF9), TIM_Channel_1, TIM1_BRK_TIM15_IRQn, 0, IOCFG_AF_PP_PD, GPIO_AF_3, 0}, // PWM7 - PF9 + { TIM15, IO_TAG(PF10), TIM_Channel_2, TIM1_BRK_TIM15_IRQn, 0, IOCFG_AF_PP_PD, GPIO_AF_3, 0}, // PWM8 - PF10 + { TIM4, IO_TAG(PD12), TIM_Channel_1, TIM4_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2, 0}, // PWM9 - PD12 + { TIM4, IO_TAG(PD13), TIM_Channel_2, TIM4_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2, 0}, // PWM10 - PD13 + { TIM4, IO_TAG(PD14), TIM_Channel_3, TIM4_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2, 0}, // PWM11 - PD14 + { TIM4, IO_TAG(PD15), TIM_Channel_4, TIM4_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2, 0}, // PWM12 - PD15 + { TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1, 0}, // PWM13 - PA1 + { TIM2, IO_TAG(PA2), TIM_Channel_3, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1, 0}, // PWM14 - PA2 + { TIM2, IO_TAG(PA3), TIM_Channel_4, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1, 0}, // PWM15 - PA3 + { TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2, 0}, // PWM16 - PB0 + { TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2, 0}, // PWM17 - PB1 + { TIM3, IO_TAG(PA4), TIM_Channel_2, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2, 0} // PWM18 - PA4 }; diff --git a/src/main/target/CHEBUZZF3/target.h b/src/main/target/CHEBUZZF3/target.h index 29d60c5491..b15505cab4 100644 --- a/src/main/target/CHEBUZZF3/target.h +++ b/src/main/target/CHEBUZZF3/target.h @@ -126,9 +126,9 @@ #define TARGET_IO_PORTA 0xffff #define TARGET_IO_PORTB 0xffff #define TARGET_IO_PORTC 0xffff -#define TARGET_IO_PORTD (BIT(2)) +#define TARGET_IO_PORTD (BIT(2)|BIT(10)|BIT(12)|BIT(13)|BIT(14)|BIT(15)) #define TARGET_IO_PORTE 0xffff -#define TARGET_IO_PORTF (BIT(0)|BIT(1)|BIT(4)) +#define TARGET_IO_PORTF (BIT(0)|BIT(1)|BIT(4)|BIT(9)|BIT(10)) #define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(8) | TIM_N(15) | TIM_N(16) | TIM_N(17)) diff --git a/src/main/target/CJMCU/target.c b/src/main/target/CJMCU/target.c index c71aad1e7f..b84a104543 100644 --- a/src/main/target/CJMCU/target.c +++ b/src/main/target/CJMCU/target.c @@ -3,6 +3,7 @@ #include #include +#include "drivers/io.h" #include "drivers/pwm_mapping.h" const uint16_t multiPPM[] = { @@ -37,19 +38,19 @@ const uint16_t airPWM[] = { }; const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { - { TIM2, GPIOA, Pin_0, TIM_Channel_1, TIM2_IRQn, 0, Mode_IPD, 0}, // PWM1 - RC1 - { TIM2, GPIOA, Pin_1, TIM_Channel_2, TIM2_IRQn, 0, Mode_IPD, 0}, // PWM2 - RC2 - { TIM2, GPIOA, Pin_2, TIM_Channel_3, TIM2_IRQn, 0, Mode_IPD, 0}, // PWM3 - RC3 - { TIM2, GPIOA, Pin_3, TIM_Channel_4, TIM2_IRQn, 0, Mode_IPD, 0}, // PWM4 - RC4 - { TIM3, GPIOA, Pin_6, TIM_Channel_1, TIM3_IRQn, 0, Mode_IPD, 0}, // PWM5 - RC5 - { TIM3, GPIOA, Pin_7, TIM_Channel_2, TIM3_IRQn, 0, Mode_IPD, 0}, // PWM6 - RC6 - { TIM3, GPIOB, Pin_0, TIM_Channel_3, TIM3_IRQn, 0, Mode_IPD, 0}, // PWM7 - RC7 - { TIM3, GPIOB, Pin_1, TIM_Channel_4, TIM3_IRQn, 0, Mode_IPD, 0}, // PWM8 - RC8 - { TIM1, GPIOA, Pin_8, TIM_Channel_1, TIM1_CC_IRQn, 1, Mode_IPD, 0}, // PWM9 - OUT1 - { TIM1, GPIOA, Pin_11,TIM_Channel_4, TIM1_CC_IRQn, 1, Mode_IPD, 0}, // PWM10 - OUT2 - { TIM4, GPIOB, Pin_6, TIM_Channel_1, TIM4_IRQn, 0, Mode_IPD, 0}, // PWM11 - OUT3 - { TIM4, GPIOB, Pin_7, TIM_Channel_2, TIM4_IRQn, 0, Mode_IPD, 0}, // PWM12 - OUT4 - { TIM4, GPIOB, Pin_8, TIM_Channel_3, TIM4_IRQn, 0, Mode_IPD, 0}, // PWM13 - OUT5 - { TIM4, GPIOB, Pin_9, TIM_Channel_4, TIM4_IRQn, 0, Mode_IPD, 0} // PWM14 - OUT6 + { TIM2, IO_TAG(PA0), TIM_Channel_1, TIM2_IRQn, 0, IOCFG_IPD, 0}, // PWM1 - RC1 + { TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, 0, IOCFG_IPD, 0}, // PWM2 - RC2 + { TIM2, IO_TAG(PA2), TIM_Channel_3, TIM2_IRQn, 0, IOCFG_IPD, 0}, // PWM3 - RC3 + { TIM2, IO_TAG(PA3), TIM_Channel_4, TIM2_IRQn, 0, IOCFG_IPD, 0}, // PWM4 - RC4 + { TIM3, IO_TAG(PA6), TIM_Channel_1, TIM3_IRQn, 0, IOCFG_IPD, 0}, // PWM5 - RC5 + { TIM3, IO_TAG(PA7), TIM_Channel_2, TIM3_IRQn, 0, IOCFG_IPD, 0}, // PWM6 - RC6 + { TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, 0, IOCFG_IPD, 0}, // PWM7 - RC7 + { TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, 0, IOCFG_IPD, 0}, // PWM8 - RC8 + { TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, 1, IOCFG_IPD, 0}, // PWM9 - OUT1 + { TIM1, IO_TAG(PA11),TIM_Channel_4, TIM1_CC_IRQn, 1, IOCFG_IPD, 0}, // PWM10 - OUT2 + { TIM4, IO_TAG(PB6), TIM_Channel_1, TIM4_IRQn, 0, IOCFG_IPD, 0}, // PWM11 - OUT3 + { TIM4, IO_TAG(PB7), TIM_Channel_2, TIM4_IRQn, 0, IOCFG_IPD, 0}, // PWM12 - OUT4 + { TIM4, IO_TAG(PB8), TIM_Channel_3, TIM4_IRQn, 0, IOCFG_IPD, 0}, // PWM13 - OUT5 + { TIM4, IO_TAG(PB9), TIM_Channel_4, TIM4_IRQn, 0, IOCFG_IPD, 0} // PWM14 - OUT6 }; diff --git a/src/main/target/COLIBRI_RACE/target.c b/src/main/target/COLIBRI_RACE/target.c index b6d3dfc23e..d26176e38e 100644 --- a/src/main/target/COLIBRI_RACE/target.c +++ b/src/main/target/COLIBRI_RACE/target.c @@ -3,6 +3,7 @@ #include #include +#include "drivers/io.h" #include "drivers/pwm_mapping.h" const uint16_t multiPPM[] = { @@ -66,19 +67,16 @@ const uint16_t airPWM[] = { }; const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { - { TIM1, GPIOA, Pin_8, TIM_Channel_1, TIM1_CC_IRQn, 0, Mode_AF_PP_PD, GPIO_PinSource8, GPIO_AF_6, 0}, // PWM1 - PA8 - - { TIM3, GPIOC, Pin_6, TIM_Channel_1, TIM3_IRQn, 1, Mode_AF_PP, GPIO_PinSource6, GPIO_AF_2, 0}, // PWM2 - PC6 - { TIM3, GPIOC, Pin_7, TIM_Channel_2, TIM3_IRQn, 1, Mode_AF_PP, GPIO_PinSource7, GPIO_AF_2, 0}, // PWM3 - PC7 - { TIM3, GPIOC, Pin_8, TIM_Channel_3, TIM3_IRQn, 1, Mode_AF_PP, GPIO_PinSource8, GPIO_AF_2, 0}, // PMW4 - PC8 - { TIM3, GPIOC, Pin_9, TIM_Channel_4, TIM3_IRQn, 1, Mode_AF_PP, GPIO_PinSource9, GPIO_AF_2, 0}, // PWM5 - PC9 - - { TIM2, GPIOA, Pin_0, TIM_Channel_1, TIM2_IRQn, 1, Mode_AF_PP, GPIO_PinSource0, GPIO_AF_1, 0}, // PWM6 - PA0 - { TIM2, GPIOA, Pin_1, TIM_Channel_2, TIM2_IRQn, 1, Mode_AF_PP, GPIO_PinSource1, GPIO_AF_1, 0}, // PWM7 - PA1 - { TIM2, GPIOA, Pin_2, TIM_Channel_3, TIM2_IRQn, 1, Mode_AF_PP, GPIO_PinSource2, GPIO_AF_1, 0}, // PWM8 - PA2 - { TIM2, GPIOA, Pin_3, TIM_Channel_4, TIM2_IRQn, 1, Mode_AF_PP, GPIO_PinSource3, GPIO_AF_1, 0}, // PWM9 - PA3 - - { TIM15, GPIOB, Pin_14, TIM_Channel_1, TIM1_BRK_TIM15_IRQn, 1, Mode_AF_PP_PD, GPIO_PinSource14, GPIO_AF_1, 0}, // PWM10 - PB14 - { TIM15, GPIOB, Pin_15, TIM_Channel_2, TIM1_BRK_TIM15_IRQn, 1, Mode_AF_PP_PD, GPIO_PinSource15, GPIO_AF_1, 0}, // PWM11 - PB15 + { TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, 0, IOCFG_AF_PP_PD, GPIO_AF_6, 0}, // PWM1 - PA8 + { TIM3, IO_TAG(PC6), TIM_Channel_1, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2, 0}, // PWM2 - PC6 + { TIM3, IO_TAG(PC7), TIM_Channel_2, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2, 0}, // PWM3 - PC7 + { TIM3, IO_TAG(PC8), TIM_Channel_3, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2, 0}, // PMW4 - PC8 + { TIM3, IO_TAG(PC9), TIM_Channel_4, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2, 0}, // PWM5 - PC9 + { TIM2, IO_TAG(PA0), TIM_Channel_1, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1, 0}, // PWM6 - PA0 + { TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1, 0}, // PWM7 - PA1 + { TIM2, IO_TAG(PA2), TIM_Channel_3, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1, 0}, // PWM8 - PA2 + { TIM2, IO_TAG(PA3), TIM_Channel_4, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1, 0}, // PWM9 - PA3 + { TIM15, IO_TAG(PB14), TIM_Channel_1, TIM1_BRK_TIM15_IRQn, 1, IOCFG_AF_PP_PD, GPIO_AF_1, 0}, // PWM10 - PB14 + { TIM15, IO_TAG(PB15), TIM_Channel_2, TIM1_BRK_TIM15_IRQn, 1, IOCFG_AF_PP_PD, GPIO_AF_1, 0}, // PWM11 - PB15 }; diff --git a/src/main/target/DOGE/target.c b/src/main/target/DOGE/target.c index 4743d6e432..aa34221f91 100644 --- a/src/main/target/DOGE/target.c +++ b/src/main/target/DOGE/target.c @@ -58,17 +58,17 @@ const uint16_t airPWM[] = { }; const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { - { TIM1, GPIOA, Pin_8, TIM_Channel_1, TIM1_CC_IRQn, 0, Mode_AF_PP_PD, GPIO_PinSource8, GPIO_AF_6, 0}, // PWM1 - PA8 + { TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, 0, IOCFG_AF_PP_PD, GPIO_AF_6, 0}, // PWM1 - PA8 - { TIM4, GPIOB, Pin_8, TIM_Channel_3, TIM4_IRQn, 1, Mode_AF_PP, GPIO_PinSource8, GPIO_AF_2, 0}, // PWM2 - PB8 - { TIM4, GPIOB, Pin_9, TIM_Channel_4, TIM4_IRQn, 1, Mode_AF_PP, GPIO_PinSource9, GPIO_AF_2, 0}, // PWM3 - PB9 + { TIM4, IO_TAG(PB8), TIM_Channel_3, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2, 0}, // PWM2 - PB8 + { TIM4, IO_TAG(PB9), TIM_Channel_4, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2, 0}, // PWM3 - PB9 - { TIM2, GPIOA, Pin_10, TIM_Channel_4, TIM2_IRQn, 1, Mode_AF_PP, GPIO_PinSource10, GPIO_AF_10, 0}, // PMW4 - PA10 - { TIM2, GPIOA, Pin_9, TIM_Channel_3, TIM2_IRQn, 1, Mode_AF_PP, GPIO_PinSource9, GPIO_AF_10, 0}, // PWM5 - PA9 - { TIM2, GPIOA, Pin_0, TIM_Channel_1, TIM2_IRQn, 1, Mode_AF_PP, GPIO_PinSource0, GPIO_AF_1, 0}, // PWM6 - PA0 - { TIM2, GPIOA, Pin_1, TIM_Channel_2, TIM2_IRQn, 1, Mode_AF_PP, GPIO_PinSource1, GPIO_AF_1, 0}, // PWM7 - PA1 + { TIM2, IO_TAG(PA10), TIM_Channel_4, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_10, 0}, // PMW4 - PA10 + { TIM2, IO_TAG(PA9), TIM_Channel_3, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_10, 0}, // PWM5 - PA9 + { TIM2, IO_TAG(PA0), TIM_Channel_1, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1, 0}, // PWM6 - PA0 + { TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1, 0}, // PWM7 - PA1 - { TIM3, GPIOB, Pin_0, TIM_Channel_3, TIM3_IRQn, 1, Mode_AF_PP_PD, GPIO_PinSource0, GPIO_AF_2, 0}, // PWM8 - PB1 - { TIM3, GPIOB, Pin_1, TIM_Channel_4, TIM3_IRQn, 1, Mode_AF_PP_PD, GPIO_PinSource1, GPIO_AF_2, 0}, // PWM9 - PB0 + { TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, 1, IOCFG_AF_PP_PD, GPIO_AF_2, 0}, // PWM8 - PB1 + { TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, 1, IOCFG_AF_PP_PD, GPIO_AF_2, 0}, // PWM9 - PB0 }; diff --git a/src/main/target/EUSTM32F103RC/target.c b/src/main/target/EUSTM32F103RC/target.c index 99b0b1003b..b917526d7e 100644 --- a/src/main/target/EUSTM32F103RC/target.c +++ b/src/main/target/EUSTM32F103RC/target.c @@ -72,19 +72,19 @@ const uint16_t airPWM[] = { }; const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { - { TIM2, GPIOA, Pin_0, TIM_Channel_1, TIM2_IRQn, 0, Mode_IPD, 0 }, // PWM1 - RC1 - { TIM2, GPIOA, Pin_1, TIM_Channel_2, TIM2_IRQn, 0, Mode_IPD, 0 }, // PWM2 - RC2 - { TIM2, GPIOA, Pin_2, TIM_Channel_3, TIM2_IRQn, 0, Mode_IPD, 0 }, // PWM3 - RC3 - { TIM2, GPIOA, Pin_3, TIM_Channel_4, TIM2_IRQn, 0, Mode_IPD, 0 }, // PWM4 - RC4 - { TIM3, GPIOA, Pin_6, TIM_Channel_1, TIM3_IRQn, 0, Mode_IPD, 0 }, // PWM5 - RC5 - { TIM3, GPIOA, Pin_7, TIM_Channel_2, TIM3_IRQn, 0, Mode_IPD, 0 }, // PWM6 - RC6 - { TIM3, GPIOB, Pin_0, TIM_Channel_3, TIM3_IRQn, 0, Mode_IPD, 0 }, // PWM7 - RC7 - { TIM3, GPIOB, Pin_1, TIM_Channel_4, TIM3_IRQn, 0, Mode_IPD, 0 }, // PWM8 - RC8 - { TIM1, GPIOA, Pin_8, TIM_Channel_1, TIM1_CC_IRQn, 1, Mode_IPD, 0 }, // PWM9 - OUT1 - { TIM1, GPIOA, Pin_11, TIM_Channel_4, TIM1_CC_IRQn, 1, Mode_IPD, 0 }, // PWM10 - OUT2 - { TIM4, GPIOB, Pin_6, TIM_Channel_1, TIM4_IRQn, 0, Mode_IPD, 0 }, // PWM11 - OUT3 - { TIM4, GPIOB, Pin_7, TIM_Channel_2, TIM4_IRQn, 0, Mode_IPD, 0 }, // PWM12 - OUT4 - { TIM4, GPIOB, Pin_8, TIM_Channel_3, TIM4_IRQn, 0, Mode_IPD, 0 }, // PWM13 - OUT5 - { TIM4, GPIOB, Pin_9, TIM_Channel_4, TIM4_IRQn, 0, Mode_IPD, 0 } // PWM14 - OUT6 + { TIM2, IO_TAG(PA0), TIM_Channel_1, TIM2_IRQn, 0, IOCFG_IPD, 0 }, // PWM1 - RC1 + { TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, 0, IOCFG_IPD, 0 }, // PWM2 - RC2 + { TIM2, IO_TAG(PA2), TIM_Channel_3, TIM2_IRQn, 0, IOCFG_IPD, 0 }, // PWM3 - RC3 + { TIM2, IO_TAG(PA3), TIM_Channel_4, TIM2_IRQn, 0, IOCFG_IPD, 0 }, // PWM4 - RC4 + { TIM3, IO_TAG(PA6), TIM_Channel_1, TIM3_IRQn, 0, IOCFG_IPD, 0 }, // PWM5 - RC5 + { TIM3, IO_TAG(PA7), TIM_Channel_2, TIM3_IRQn, 0, IOCFG_IPD, 0 }, // PWM6 - RC6 + { TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, 0, IOCFG_IPD, 0 }, // PWM7 - RC7 + { TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, 0, IOCFG_IPD, 0 }, // PWM8 - RC8 + { TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, 1, IOCFG_IPD, 0 }, // PWM9 - OUT1 + { TIM1, IO_TAG(PA11), TIM_Channel_4, TIM1_CC_IRQn, 1, IOCFG_IPD, 0 }, // PWM10 - OUT2 + { TIM4, IO_TAG(PB6), TIM_Channel_1, TIM4_IRQn, 0, IOCFG_IPD, 0 }, // PWM11 - OUT3 + { TIM4, IO_TAG(PB7), TIM_Channel_2, TIM4_IRQn, 0, IOCFG_IPD, 0 }, // PWM12 - OUT4 + { TIM4, IO_TAG(PB8), TIM_Channel_3, TIM4_IRQn, 0, IOCFG_IPD, 0 }, // PWM13 - OUT5 + { TIM4, IO_TAG(PB9), TIM_Channel_4, TIM4_IRQn, 0, IOCFG_IPD, 0 } // PWM14 - OUT6 }; diff --git a/src/main/target/FURYF3/target.c b/src/main/target/FURYF3/target.c index 1a21ff33f8..5a011433c3 100644 --- a/src/main/target/FURYF3/target.c +++ b/src/main/target/FURYF3/target.c @@ -52,15 +52,15 @@ const uint16_t airPWM[] = { }; const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { - { TIM2, GPIOB, Pin_3, TIM_Channel_2, TIM2_IRQn, 0, Mode_AF_PP, GPIO_PinSource3, GPIO_AF_1, 0}, // PPM IN - { TIM3, GPIOB, Pin_0, TIM_Channel_3, TIM3_IRQn, 0, Mode_AF_PP, GPIO_PinSource0, GPIO_AF_2, 0}, // SS1 - PB0 - *TIM3_CH3, TIM1_CH2N, TIM8_CH2N - { TIM3, GPIOB, Pin_1, TIM_Channel_4, TIM3_IRQn, 0, Mode_AF_PP, GPIO_PinSource1, GPIO_AF_2, 0}, // SS1 - PB1 - *TIM3_CH4, TIM1_CH3N, TIM8_CH3N + { TIM2, IO_TAG(PB3), TIM_Channel_2, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1, 0}, // PPM IN + { TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2, 0}, // SS1 - PB0 - *TIM3_CH3, TIM1_CH2N, TIM8_CH2N + { TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2, 0}, // SS1 - PB1 - *TIM3_CH4, TIM1_CH3N, TIM8_CH3N - { TIM4, GPIOB, Pin_7, TIM_Channel_2, TIM4_IRQn, 1, Mode_AF_PP, GPIO_PinSource7, GPIO_AF_2, 0}, // PWM4 - S1 - { TIM4, GPIOB, Pin_6, TIM_Channel_1, TIM4_IRQn, 1, Mode_AF_PP, GPIO_PinSource6, GPIO_AF_2, 0}, // PWM5 - S2 - { TIM17, GPIOB, Pin_5, TIM_Channel_1, TIM1_TRG_COM_TIM17_IRQn, 1, Mode_AF_PP, GPIO_PinSource5, GPIO_AF_10,0}, // PWM6 - S3 - { TIM16, GPIOB, Pin_4, TIM_Channel_1, TIM1_UP_TIM16_IRQn, 1, Mode_AF_PP, GPIO_PinSource4, GPIO_AF_1, 0}, // PWM7 - S4 + { TIM4, IO_TAG(PB7), TIM_Channel_2, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2, 0}, // PWM4 - S1 + { TIM4, IO_TAG(PB6), TIM_Channel_1, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2, 0}, // PWM5 - S2 + { TIM17, IO_TAG(PB5), TIM_Channel_1, TIM1_TRG_COM_TIM17_IRQn, 1, IOCFG_AF_PP, GPIO_AF_10, 0}, // PWM6 - S3 + { TIM16, IO_TAG(PB4), TIM_Channel_1, TIM1_UP_TIM16_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1, 0}, // PWM7 - S4 - { TIM1, GPIOA, Pin_8, TIM_Channel_1, TIM1_CC_IRQn, 1, Mode_AF_PP, GPIO_PinSource8, GPIO_AF_6, 0}, // GPIO TIMER - LED_STRIP + { TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, 1, IOCFG_AF_PP, GPIO_AF_6, 0}, // GPIO TIMER - LED_STRIP }; diff --git a/src/main/target/FURYF4/target.c b/src/main/target/FURYF4/target.c index b1a0e82218..b6dbf5fe7f 100644 --- a/src/main/target/FURYF4/target.c +++ b/src/main/target/FURYF4/target.c @@ -42,12 +42,12 @@ const uint16_t airPWM[] = { }; const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { - { TIM8, GPIOC, Pin_9, TIM_Channel_4, TIM8_CC_IRQn, 0, GPIO_Mode_AF, GPIO_PinSource9, GPIO_AF_TIM8, 0}, // PPM_IN + { TIM8, IO_TAG(PC9), TIM_Channel_4, TIM8_CC_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM8, 0}, // PPM_IN - { TIM9, GPIOA, Pin_3, TIM_Channel_2, TIM1_BRK_TIM9_IRQn, 1, GPIO_Mode_AF, GPIO_PinSource3, GPIO_AF_TIM9, 0}, // S1_OUT - { TIM3, GPIOB, Pin_0, TIM_Channel_3, TIM3_IRQn, 1, GPIO_Mode_AF, GPIO_PinSource0, GPIO_AF_TIM3, 0}, // S2_OUT - { TIM3, GPIOB, Pin_1, TIM_Channel_4, TIM3_IRQn, 1, GPIO_Mode_AF, GPIO_PinSource1, GPIO_AF_TIM3, 0}, // S3_OUT - { TIM2, GPIOA, Pin_2, TIM_Channel_3, TIM2_IRQn, 1, GPIO_Mode_AF, GPIO_PinSource2, GPIO_AF_TIM2, 0}, // S4_OUT + { TIM9, IO_TAG(PA3), TIM_Channel_2, TIM1_BRK_TIM9_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM9, 0}, // S1_OUT + { TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM3, 0}, // S2_OUT + { TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM3, 0}, // S3_OUT + { TIM2, IO_TAG(PA2), TIM_Channel_3, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM2, 0}, // S4_OUT // { TIM5, GPIOA, Pin_0, TIM_Channel_1, TIM5_IRQn, 1, GPIO_Mode_AF, GPIO_PinSource0, GPIO_AF_TIM5, 0}, // LED Strip }; diff --git a/src/main/target/IRCFUSIONF3/target.c b/src/main/target/IRCFUSIONF3/target.c index 828387c1c1..9eaf0c4d9d 100644 --- a/src/main/target/IRCFUSIONF3/target.c +++ b/src/main/target/IRCFUSIONF3/target.c @@ -81,22 +81,22 @@ const uint16_t airPWM[] = { }; const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { - { TIM2, GPIOA, Pin_0, TIM_Channel_1, TIM2_IRQn, 0, Mode_AF_PP, GPIO_PinSource0, GPIO_AF_1, 0}, // RC_CH1 - PA0 - *TIM2_CH1 - { TIM2, GPIOA, Pin_1, TIM_Channel_2, TIM2_IRQn, 0, Mode_AF_PP, GPIO_PinSource1, GPIO_AF_1, 0}, // RC_CH2 - PA1 - *TIM2_CH2, TIM15_CH1N - { TIM2, GPIOB, Pin_11, TIM_Channel_4, TIM2_IRQn, 0, Mode_AF_PP, GPIO_PinSource11, GPIO_AF_1, 0}, // RC_CH3 - PB11 - *TIM2_CH4, USART3_RX (AF7) - { TIM2, GPIOB, Pin_10, TIM_Channel_3, TIM2_IRQn, 0, Mode_AF_PP, GPIO_PinSource10, GPIO_AF_1, 0}, // RC_CH4 - PB10 - *TIM2_CH3, USART3_TX (AF7) - { TIM3, GPIOB, Pin_4, TIM_Channel_1, TIM3_IRQn, 0, Mode_AF_PP, GPIO_PinSource4, GPIO_AF_2, 0}, // RC_CH5 - PB4 - *TIM3_CH1 - { TIM3, GPIOB, Pin_5, TIM_Channel_2, TIM3_IRQn, 0, Mode_AF_PP, GPIO_PinSource5, GPIO_AF_2, 0}, // RC_CH6 - PB5 - *TIM3_CH2 - { TIM3, GPIOB, Pin_0, TIM_Channel_3, TIM3_IRQn, 0, Mode_AF_PP, GPIO_PinSource0, GPIO_AF_2, 0}, // RC_CH7 - PB0 - *TIM3_CH3, TIM1_CH2N, TIM8_CH2N - { TIM3, GPIOB, Pin_1, TIM_Channel_4, TIM3_IRQn, 0, Mode_AF_PP, GPIO_PinSource1, GPIO_AF_2, 0}, // RC_CH8 - PB1 - *TIM3_CH4, TIM1_CH3N, TIM8_CH3N - { TIM16, GPIOA, Pin_6, TIM_Channel_1, TIM1_UP_TIM16_IRQn, 1, Mode_AF_PP, GPIO_PinSource6, GPIO_AF_1, 0}, // PWM1 - PA6 - TIM3_CH1, TIM8_BKIN, TIM1_BKIN, *TIM16_CH1 - { TIM17, GPIOA, Pin_7, TIM_Channel_1, TIM1_TRG_COM_TIM17_IRQn, 1, Mode_AF_PP, GPIO_PinSource7, GPIO_AF_1, 0}, // PWM2 - PA7 - TIM3_CH2, *TIM17_CH1, TIM1_CH1N, TIM8_CH1 - { TIM4, GPIOA, Pin_11, TIM_Channel_1, TIM4_IRQn, 1, Mode_AF_PP, GPIO_PinSource11, GPIO_AF_10, 0}, // PWM3 - PA11 - { TIM4, GPIOA, Pin_12, TIM_Channel_2, TIM4_IRQn, 1, Mode_AF_PP, GPIO_PinSource12, GPIO_AF_10, 0}, // PWM4 - PA12 - { TIM4, GPIOB, Pin_8, TIM_Channel_3, TIM4_IRQn, 1, Mode_AF_PP, GPIO_PinSource8, GPIO_AF_2, 0}, // PWM5 - PB8 - { TIM4, GPIOB, Pin_9, TIM_Channel_4, TIM4_IRQn, 1, Mode_AF_PP, GPIO_PinSource9, GPIO_AF_2, 0}, // PWM6 - PB9 - { TIM15, GPIOA, Pin_2, TIM_Channel_1, TIM1_BRK_TIM15_IRQn, 1, Mode_AF_PP, GPIO_PinSource2, GPIO_AF_9, 0}, // PWM7 - PA2 - { TIM15, GPIOA, Pin_3, TIM_Channel_2, TIM1_BRK_TIM15_IRQn, 1, Mode_AF_PP, GPIO_PinSource3, GPIO_AF_9, 0}, // PWM8 - PA3 - { TIM1, GPIOA, Pin_8, TIM_Channel_1, TIM1_CC_IRQn, 1, Mode_AF_PP, GPIO_PinSource8, GPIO_AF_6, 0}, // GPIO_TIMER / LED_STRIP + { TIM2, IO_TAG(PA0), TIM_Channel_1, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1, 0}, // RC_CH1 - PA0 - *TIM2_CH1 + { TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1, 0}, // RC_CH2 - PA1 - *TIM2_CH2, TIM15_CH1N + { TIM2, IO_TAG(PB11), TIM_Channel_4, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1, 0}, // RC_CH3 - PB11 - *TIM2_CH4, USART3_RX (AF7) + { TIM2, IO_TAG(PB10), TIM_Channel_3, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1, 0}, // RC_CH4 - PB10 - *TIM2_CH3, USART3_TX (AF7) + { TIM3, IO_TAG(PB4), TIM_Channel_1, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2, 0}, // RC_CH5 - PB4 - *TIM3_CH1 + { TIM3, IO_TAG(PB5), TIM_Channel_2, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2, 0}, // RC_CH6 - PB5 - *TIM3_CH2 + { TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2, 0}, // RC_CH7 - PB0 - *TIM3_CH3, TIM1_CH2N, TIM8_CH2N + { TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2, 0}, // RC_CH8 - PB1 - *TIM3_CH4, TIM1_CH3N, TIM8_CH3N + { TIM16, IO_TAG(PA6), TIM_Channel_1, TIM1_UP_TIM16_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1, 0}, // PWM1 - PA6 - TIM3_CH1, TIM8_BKIN, TIM1_BKIN, *TIM16_CH1 + { TIM17, IO_TAG(PA7), TIM_Channel_1, TIM1_TRG_COM_TIM17_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1, 0}, // PWM2 - PA7 - TIM3_CH2, *TIM17_CH1, TIM1_CH1N, TIM8_CH1 + { TIM4, IO_TAG(PA11), TIM_Channel_1, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_10, 0}, // PWM3 - PA11 + { TIM4, IO_TAG(PA12), TIM_Channel_2, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_10, 0}, // PWM4 - PA12 + { TIM4, IO_TAG(PB8), TIM_Channel_3, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2, 0}, // PWM5 - PB8 + { TIM4, IO_TAG(PB9), TIM_Channel_4, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2, 0}, // PWM6 - PB9 + { TIM15, IO_TAG(PA2), TIM_Channel_1, TIM1_BRK_TIM15_IRQn, 1, IOCFG_AF_PP, GPIO_AF_9, 0}, // PWM7 - PA2 + { TIM15, IO_TAG(PA3), TIM_Channel_2, TIM1_BRK_TIM15_IRQn, 1, IOCFG_AF_PP, GPIO_AF_9, 0}, // PWM8 - PA3 + { TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, 1, IOCFG_AF_PP, GPIO_AF_6, 0}, // GPIO_TIMER / LED_STRIP }; diff --git a/src/main/target/KISSFC/target.c b/src/main/target/KISSFC/target.c index 2cac728fcf..30d03b9f69 100644 --- a/src/main/target/KISSFC/target.c +++ b/src/main/target/KISSFC/target.c @@ -48,18 +48,18 @@ const uint16_t airPWM[] = { }; const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { - { TIM1, GPIOA, Pin_8, TIM_Channel_1, TIM1_CC_IRQn, 1, Mode_AF_PP, GPIO_PinSource8, GPIO_AF_6, PWM_INVERTED}, - { TIM3, GPIOB, Pin_0, TIM_Channel_3, TIM3_IRQn, 1, Mode_AF_PP, GPIO_PinSource0, GPIO_AF_2, PWM_INVERTED}, - { TIM15, GPIOB, Pin_14, TIM_Channel_1, TIM1_BRK_TIM15_IRQn, 1, Mode_AF_PP, GPIO_PinSource14, GPIO_AF_1, PWM_INVERTED}, - { TIM15, GPIOB, Pin_15, TIM_Channel_2, TIM1_BRK_TIM15_IRQn, 1, Mode_AF_PP, GPIO_PinSource15, GPIO_AF_1, PWM_INVERTED}, - { TIM16, GPIOA, Pin_6, TIM_Channel_1, TIM1_UP_TIM16_IRQn, 1, Mode_AF_PP, GPIO_PinSource6, GPIO_AF_1, PWM_INVERTED}, - { TIM17, GPIOA, Pin_7, TIM_Channel_1, TIM1_TRG_COM_TIM17_IRQn, 1, Mode_AF_PP, GPIO_PinSource7, GPIO_AF_1, PWM_INVERTED}, + { TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, 1, IOCFG_AF_PP, GPIO_AF_6, PWM_INVERTED}, + { TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2, PWM_INVERTED}, + { TIM15, IO_TAG(PB14), TIM_Channel_1, TIM1_BRK_TIM15_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1, PWM_INVERTED}, + { TIM15, IO_TAG(PB15), TIM_Channel_2, TIM1_BRK_TIM15_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1, PWM_INVERTED}, + { TIM16, IO_TAG(PA6), TIM_Channel_1, TIM1_UP_TIM16_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1, PWM_INVERTED}, + { TIM17, IO_TAG(PA7), TIM_Channel_1, TIM1_TRG_COM_TIM17_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1, PWM_INVERTED}, - { TIM2, GPIOB, Pin_3, TIM_Channel_2, TIM2_IRQn, 0, Mode_AF_PP, GPIO_PinSource3, GPIO_AF_1, 0}, - { TIM2, GPIOA, Pin_15, TIM_Channel_1, TIM2_IRQn, 0, Mode_AF_PP, GPIO_PinSource15, GPIO_AF_1, 0}, - { TIM2, GPIOA, Pin_2, TIM_Channel_3, TIM2_IRQn, 0, Mode_AF_PP, GPIO_PinSource2, GPIO_AF_1, 0}, - { TIM2, GPIOB, Pin_11, TIM_Channel_4, TIM2_IRQn, 0, Mode_AF_PP, GPIO_PinSource11, GPIO_AF_1, 0}, - { TIM4, GPIOA, Pin_13, TIM_Channel_2, TIM4_IRQn, 0, Mode_AF_PP, GPIO_PinSource13, GPIO_AF_10,0}, - { TIM8, GPIOA, Pin_14, TIM_Channel_3, TIM8_CC_IRQn, 0, Mode_AF_PP, GPIO_PinSource14, GPIO_AF_5, 0}, + { TIM2, IO_TAG(PB3), TIM_Channel_2, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1, 0}, + { TIM2, IO_TAG(PA15), TIM_Channel_1, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1, 0}, + { TIM2, IO_TAG(PA2), TIM_Channel_3, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1, 0}, + { TIM2, IO_TAG(PB11), TIM_Channel_4, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1, 0}, + { TIM4, IO_TAG(PA13), TIM_Channel_2, TIM4_IRQn, 0, IOCFG_AF_PP, GPIO_AF_10,0}, + { TIM8, IO_TAG(PA14), TIM_Channel_3, TIM8_CC_IRQn, 0, IOCFG_AF_PP, GPIO_AF_5, 0}, }; diff --git a/src/main/target/LUX_RACE/target.c b/src/main/target/LUX_RACE/target.c index b6d3dfc23e..7f80590d9c 100644 --- a/src/main/target/LUX_RACE/target.c +++ b/src/main/target/LUX_RACE/target.c @@ -66,19 +66,16 @@ const uint16_t airPWM[] = { }; const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { - { TIM1, GPIOA, Pin_8, TIM_Channel_1, TIM1_CC_IRQn, 0, Mode_AF_PP_PD, GPIO_PinSource8, GPIO_AF_6, 0}, // PWM1 - PA8 - - { TIM3, GPIOC, Pin_6, TIM_Channel_1, TIM3_IRQn, 1, Mode_AF_PP, GPIO_PinSource6, GPIO_AF_2, 0}, // PWM2 - PC6 - { TIM3, GPIOC, Pin_7, TIM_Channel_2, TIM3_IRQn, 1, Mode_AF_PP, GPIO_PinSource7, GPIO_AF_2, 0}, // PWM3 - PC7 - { TIM3, GPIOC, Pin_8, TIM_Channel_3, TIM3_IRQn, 1, Mode_AF_PP, GPIO_PinSource8, GPIO_AF_2, 0}, // PMW4 - PC8 - { TIM3, GPIOC, Pin_9, TIM_Channel_4, TIM3_IRQn, 1, Mode_AF_PP, GPIO_PinSource9, GPIO_AF_2, 0}, // PWM5 - PC9 - - { TIM2, GPIOA, Pin_0, TIM_Channel_1, TIM2_IRQn, 1, Mode_AF_PP, GPIO_PinSource0, GPIO_AF_1, 0}, // PWM6 - PA0 - { TIM2, GPIOA, Pin_1, TIM_Channel_2, TIM2_IRQn, 1, Mode_AF_PP, GPIO_PinSource1, GPIO_AF_1, 0}, // PWM7 - PA1 - { TIM2, GPIOA, Pin_2, TIM_Channel_3, TIM2_IRQn, 1, Mode_AF_PP, GPIO_PinSource2, GPIO_AF_1, 0}, // PWM8 - PA2 - { TIM2, GPIOA, Pin_3, TIM_Channel_4, TIM2_IRQn, 1, Mode_AF_PP, GPIO_PinSource3, GPIO_AF_1, 0}, // PWM9 - PA3 - - { TIM15, GPIOB, Pin_14, TIM_Channel_1, TIM1_BRK_TIM15_IRQn, 1, Mode_AF_PP_PD, GPIO_PinSource14, GPIO_AF_1, 0}, // PWM10 - PB14 - { TIM15, GPIOB, Pin_15, TIM_Channel_2, TIM1_BRK_TIM15_IRQn, 1, Mode_AF_PP_PD, GPIO_PinSource15, GPIO_AF_1, 0}, // PWM11 - PB15 + { TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, 0, IOCFG_AF_PP_PD, GPIO_AF_6, 0}, // PWM1 - PA8 + { TIM3, IO_TAG(PC6), TIM_Channel_1, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2, 0}, // PWM2 - PC6 + { TIM3, IO_TAG(PC7), TIM_Channel_2, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2, 0}, // PWM3 - PC7 + { TIM3, IO_TAG(PC8), TIM_Channel_3, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2, 0}, // PMW4 - PC8 + { TIM3, IO_TAG(PC9), TIM_Channel_4, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2, 0}, // PWM5 - PC9 + { TIM2, IO_TAG(PA0), TIM_Channel_1, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1, 0}, // PWM6 - PA0 + { TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1, 0}, // PWM7 - PA1 + { TIM2, IO_TAG(PA2), TIM_Channel_3, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1, 0}, // PWM8 - PA2 + { TIM2, IO_TAG(PA3), TIM_Channel_4, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1, 0}, // PWM9 - PA3 + { TIM15, IO_TAG(PB14), TIM_Channel_1, TIM1_BRK_TIM15_IRQn, 1, IOCFG_AF_PP_PD, GPIO_AF_1, 0}, // PWM10 - PB14 + { TIM15, IO_TAG(PB15), TIM_Channel_2, TIM1_BRK_TIM15_IRQn, 1, IOCFG_AF_PP_PD, GPIO_AF_1, 0}, // PWM11 - PB15 }; diff --git a/src/main/target/MOTOLAB/target.c b/src/main/target/MOTOLAB/target.c index dab944eaca..514839eada 100644 --- a/src/main/target/MOTOLAB/target.c +++ b/src/main/target/MOTOLAB/target.c @@ -42,15 +42,14 @@ const uint16_t airPWM[] = { }; const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { - { TIM3, GPIOA, Pin_4, TIM_Channel_2, TIM3_IRQn, 1, Mode_AF_PP, GPIO_PinSource4, GPIO_AF_2}, // PWM1 - PA4 - *TIM3_CH2 - { TIM3, GPIOA, Pin_6, TIM_Channel_1, TIM3_IRQn, 1, Mode_AF_PP, GPIO_PinSource6, GPIO_AF_2}, // PWM2 - PA6 - *TIM3_CH1, TIM8_BKIN, TIM1_BKIN, TIM16_CH1 - { TIM3, GPIOB, Pin_0, TIM_Channel_3, TIM3_IRQn, 1, Mode_AF_PP, GPIO_PinSource0, GPIO_AF_2}, // PWM3 - PB0 - *TIM3_CH3, TIM1_CH2N, TIM8_CH2N - { TIM3, GPIOB, Pin_1, TIM_Channel_4, TIM3_IRQn, 1, Mode_AF_PP, GPIO_PinSource1, GPIO_AF_2}, // PWM4 - PB1 - *TIM3_CH4, TIM1_CH3N, TIM8_CH3N - { TIM2, GPIOA, Pin_1, TIM_Channel_2, TIM2_IRQn, 1, Mode_AF_PP, GPIO_PinSource1, GPIO_AF_1}, // PWM5 - PA1 - *TIM2_CH2, TIM15_CH1N - { TIM2, GPIOA, Pin_2, TIM_Channel_3, TIM2_IRQn, 1, Mode_AF_PP, GPIO_PinSource2, GPIO_AF_1}, // PWM6 - PA2 - *TIM2_CH3, !TIM15_CH1 - { TIM15, GPIOA, Pin_3, TIM_Channel_2, TIM1_BRK_TIM15_IRQn, 1, Mode_AF_PP, GPIO_PinSource3, GPIO_AF_9}, // PWM7 - PA3 - *TIM15_CH2, TIM2_CH4 - { TIM1, GPIOA, Pin_8, TIM_Channel_1, TIM1_CC_IRQn, 1, Mode_AF_PP, GPIO_PinSource8, GPIO_AF_6}, // PWM8 - PA8 - *TIM1_CH1, TIM4_ETR - - { TIM17, GPIOA, Pin_7, TIM_Channel_1, TIM1_TRG_COM_TIM17_IRQn, 0, Mode_AF_PP_PD, GPIO_PinSource7, GPIO_AF_1}, // PPM - PA7 - *TIM17_CH1, TIM1_CH1N, TIM8_CH1 + { TIM3, IO_TAG(PA4), TIM_Channel_2, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2, 0}, // PWM1 - PA4 - *TIM3_CH2 + { TIM3, IO_TAG(PA6), TIM_Channel_1, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2, 0}, // PWM2 - PA6 - *TIM3_CH1, TIM8_BKIN, TIM1_BKIN, TIM16_CH1 + { TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2, 0}, // PWM3 - PB0 - *TIM3_CH3, TIM1_CH2N, TIM8_CH2N + { TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2, 0}, // PWM4 - PB1 - *TIM3_CH4, TIM1_CH3N, TIM8_CH3N + { TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1, 0}, // PWM5 - PA1 - *TIM2_CH2, TIM15_CH1N + { TIM2, IO_TAG(PA2), TIM_Channel_3, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1, 0}, // PWM6 - PA2 - *TIM2_CH3, !TIM15_CH1 + { TIM15, IO_TAG(PA3), TIM_Channel_2, TIM1_BRK_TIM15_IRQn, 1, IOCFG_AF_PP, GPIO_AF_9, 0}, // PWM7 - PA3 - *TIM15_CH2, TIM2_CH4 + { TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, 1, IOCFG_AF_PP, GPIO_AF_6, 0}, // PWM8 - PA8 - *TIM1_CH1, TIM4_ETR + { TIM17, IO_TAG(PA7), TIM_Channel_1, TIM1_TRG_COM_TIM17_IRQn, 0, IOCFG_AF_PP_PD, GPIO_AF_1, 0}, // PPM - PA7 - *TIM17_CH1, TIM1_CH1N, TIM8_CH1 }; diff --git a/src/main/target/NAZE/target.c b/src/main/target/NAZE/target.c index 41c3c0b4a7..83a8862aa8 100644 --- a/src/main/target/NAZE/target.c +++ b/src/main/target/NAZE/target.c @@ -72,19 +72,19 @@ const uint16_t airPWM[] = { }; const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { - { TIM2, IO_TAG(PA0), TIM_Channel_1, TIM2_IRQn, 0, IOCFG_IPD, 0}, // PWM1 - RC1 - { TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, 0, IOCFG_IPD, 0}, // PWM2 - RC2 - { TIM2, IO_TAG(PA2), TIM_Channel_3, TIM2_IRQn, 0, IOCFG_IPD, 0}, // PWM3 - RC3 - { TIM2, IO_TAG(PA3), TIM_Channel_4, TIM2_IRQn, 0, IOCFG_IPD, 0}, // PWM4 - RC4 - { TIM3, IO_TAG(PA6), TIM_Channel_1, TIM3_IRQn, 0, IOCFG_IPD, 0}, // PWM5 - RC5 - { TIM3, IO_TAG(PA7), TIM_Channel_2, TIM3_IRQn, 0, IOCFG_IPD, 0}, // PWM6 - RC6 - { TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, 0, IOCFG_IPD, 0}, // PWM7 - RC7 - { TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, 0, IOCFG_IPD, 0}, // PWM8 - RC8 - { TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, 1, IOCFG_IPD, 0}, // PWM9 - OUT1 - { TIM1, IO_TAG(PA11),TIM_Channel_4, TIM1_CC_IRQn, 1, IOCFG_IPD, 0}, // PWM10 - OUT2 - { TIM4, IO_TAG(PB6), TIM_Channel_1, TIM4_IRQn, 0, IOCFG_IPD, 0}, // PWM11 - OUT3 - { TIM4, IO_TAG(PB7), TIM_Channel_2, TIM4_IRQn, 0, IOCFG_IPD, 0}, // PWM12 - OUT4 - { TIM4, IO_TAG(PB8), TIM_Channel_3, TIM4_IRQn, 0, IOCFG_IPD, 0}, // PWM13 - OUT5 - { TIM4, IO_TAG(PB9), TIM_Channel_4, TIM4_IRQn, 0, IOCFG_IPD, 0} // PWM14 - OUT6 + { TIM2, IO_TAG(PA0), TIM_Channel_1, TIM2_IRQn, 0, IOCFG_IPD, 0}, // PWM1 - RC1 + { TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, 0, IOCFG_IPD, 0}, // PWM2 - RC2 + { TIM2, IO_TAG(PA2), TIM_Channel_3, TIM2_IRQn, 0, IOCFG_IPD, 0}, // PWM3 - RC3 + { TIM2, IO_TAG(PA3), TIM_Channel_4, TIM2_IRQn, 0, IOCFG_IPD, 0}, // PWM4 - RC4 + { TIM3, IO_TAG(PA6), TIM_Channel_1, TIM3_IRQn, 0, IOCFG_IPD, 0}, // PWM5 - RC5 + { TIM3, IO_TAG(PA7), TIM_Channel_2, TIM3_IRQn, 0, IOCFG_IPD, 0}, // PWM6 - RC6 + { TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, 0, IOCFG_IPD, 0}, // PWM7 - RC7 + { TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, 0, IOCFG_IPD, 0}, // PWM8 - RC8 + { TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, 1, IOCFG_IPD, 0}, // PWM9 - OUT1 + { TIM1, IO_TAG(PA11), TIM_Channel_4, TIM1_CC_IRQn, 1, IOCFG_IPD, 0}, // PWM10 - OUT2 + { TIM4, IO_TAG(PB6), TIM_Channel_1, TIM4_IRQn, 0, IOCFG_IPD, 0}, // PWM11 - OUT3 + { TIM4, IO_TAG(PB7), TIM_Channel_2, TIM4_IRQn, 0, IOCFG_IPD, 0}, // PWM12 - OUT4 + { TIM4, IO_TAG(PB8), TIM_Channel_3, TIM4_IRQn, 0, IOCFG_IPD, 0}, // PWM13 - OUT5 + { TIM4, IO_TAG(PB9), TIM_Channel_4, TIM4_IRQn, 0, IOCFG_IPD, 0} // PWM14 - OUT6 }; diff --git a/src/main/target/NAZE32PRO/target.c b/src/main/target/NAZE32PRO/target.c index 425ca38c41..5c8baef256 100644 --- a/src/main/target/NAZE32PRO/target.c +++ b/src/main/target/NAZE32PRO/target.c @@ -72,20 +72,19 @@ const uint16_t airPWM[] = { }; const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { - { TIM1, GPIOA, Pin_8, TIM_Channel_1, TIM1_CC_IRQn, 0, Mode_AF_PP_PD, GPIO_PinSource8, GPIO_AF_6, 0}, // PA8 - AF6 - { TIM1, GPIOA, Pin_9, TIM_Channel_2, TIM1_CC_IRQn, 0, Mode_AF_PP_PD, GPIO_PinSource9, GPIO_AF_6, 0}, // PA9 - AF6 - { TIM1, GPIOA, Pin_10, TIM_Channel_3, TIM1_CC_IRQn, 0, Mode_AF_PP_PD, GPIO_PinSource10, GPIO_AF_6, 0}, // PA10 - AF6 - { TIM3, GPIOB, Pin_4, TIM_Channel_1, TIM3_IRQn, 0, Mode_AF_PP_PD, GPIO_PinSource4, GPIO_AF_2, 0}, // PB4 - AF2 - { TIM4, GPIOB, Pin_6, TIM_Channel_1, TIM4_IRQn, 0, Mode_AF_PP_PD, GPIO_PinSource6, GPIO_AF_2, 0}, // PB6 - AF2 - not working yet - { TIM4, GPIOB, Pin_7, TIM_Channel_2, TIM4_IRQn, 0, Mode_AF_PP_PD, GPIO_PinSource7, GPIO_AF_2, 0}, // PB7 - AF2 - not working yet - { TIM4, GPIOB, Pin_8, TIM_Channel_3, TIM4_IRQn, 0, Mode_AF_PP_PD, GPIO_PinSource8, GPIO_AF_2, 0}, // PB8 - AF2 - { TIM4, GPIOB, Pin_9, TIM_Channel_4, TIM4_IRQn, 0, Mode_AF_PP_PD, GPIO_PinSource9, GPIO_AF_2, 0}, // PB9 - AF2 - - { TIM2, GPIOA, Pin_0, TIM_Channel_1, TIM2_IRQn, 1, Mode_AF_PP, GPIO_PinSource0, GPIO_AF_2}, // PA0 - untested - { TIM2, GPIOA, Pin_1, TIM_Channel_2, TIM2_IRQn, 1, Mode_AF_PP, GPIO_PinSource1, GPIO_AF_2, 0}, // PA1 - untested - { TIM15, GPIOA, Pin_2, TIM_Channel_1, TIM1_BRK_TIM15_IRQn, 1, Mode_AF_PP, GPIO_PinSource2, GPIO_AF_9, 0}, // PA2 - untested - { TIM15, GPIOA, Pin_3, TIM_Channel_2, TIM1_BRK_TIM15_IRQn, 1, Mode_AF_PP, GPIO_PinSource3, GPIO_AF_9, 0}, // PA3 - untested - { TIM16, GPIOA, Pin_6, TIM_Channel_1, TIM1_UP_TIM16_IRQn, 1, Mode_AF_PP, GPIO_PinSource6, GPIO_AF_1, 0}, // PA6 - untested - { TIM17, GPIOA, Pin_7, TIM_Channel_1, TIM1_TRG_COM_TIM17_IRQn, 1, Mode_AF_PP, GPIO_PinSource7, GPIO_AF_1, 0} // PA7 - untested + { TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, 0, IOCFG_AF_PP_PD, GPIO_AF_6, 0}, // PA8 - AF6 + { TIM1, IO_TAG(PA9), TIM_Channel_2, TIM1_CC_IRQn, 0, IOCFG_AF_PP_PD, GPIO_AF_6, 0}, // PA9 - AF6 + { TIM1, IO_TAG(PA10), TIM_Channel_3, TIM1_CC_IRQn, 0, IOCFG_AF_PP_PD, GPIO_AF_6, 0}, // PA10 - AF6 + { TIM3, IO_TAG(PB4), TIM_Channel_1, TIM3_IRQn, 0, IOCFG_AF_PP_PD, GPIO_AF_2, 0}, // PB4 - AF2 + { TIM4, IO_TAG(PB6), TIM_Channel_1, TIM4_IRQn, 0, IOCFG_AF_PP_PD, GPIO_AF_2, 0}, // PB6 - AF2 - not working yet + { TIM4, IO_TAG(PB7), TIM_Channel_2, TIM4_IRQn, 0, IOCFG_AF_PP_PD, GPIO_AF_2, 0}, // PB7 - AF2 - not working yet + { TIM4, IO_TAG(PB8), TIM_Channel_3, TIM4_IRQn, 0, IOCFG_AF_PP_PD, GPIO_AF_2, 0}, // PB8 - AF2 + { TIM4, IO_TAG(PB9), TIM_Channel_4, TIM4_IRQn, 0, IOCFG_AF_PP_PD, GPIO_AF_2, 0}, // PB9 - AF2 + { TIM2, IO_TAG(PA0), TIM_Channel_1, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2, 0}, // PA0 - untested + { TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2, 0}, // PA1 - untested + { TIM15, IO_TAG(PA2), TIM_Channel_1, TIM1_BRK_TIM15_IRQn, 1, IOCFG_AF_PP, GPIO_AF_9, 0}, // PA2 - untested + { TIM15, IO_TAG(PA3), TIM_Channel_2, TIM1_BRK_TIM15_IRQn, 1, IOCFG_AF_PP, GPIO_AF_9, 0}, // PA3 - untested + { TIM16, IO_TAG(PA6), TIM_Channel_1, TIM1_UP_TIM16_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1, 0}, // PA6 - untested + { TIM17, IO_TAG(PA7), TIM_Channel_1, TIM1_TRG_COM_TIM17_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1, 0} // PA7 - untested }; diff --git a/src/main/target/OLIMEXINO/target.c b/src/main/target/OLIMEXINO/target.c index defeac77ef..72b22c8db1 100644 --- a/src/main/target/OLIMEXINO/target.c +++ b/src/main/target/OLIMEXINO/target.c @@ -70,20 +70,21 @@ const uint16_t airPWM[] = { PWM14 | (MAP_TO_SERVO_OUTPUT << 8), // servo #4 0xFFFF }; + const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { - { TIM2, GPIOA, Pin_0, TIM_Channel_1, TIM2_IRQn, 0, Mode_IPD, 0}, // PWM1 - RC1 - { TIM2, GPIOA, Pin_1, TIM_Channel_2, TIM2_IRQn, 0, Mode_IPD, 0}, // PWM2 - RC2 - { TIM2, GPIOA, Pin_2, TIM_Channel_3, TIM2_IRQn, 0, Mode_IPD, 0}, // PWM3 - RC3 - { TIM2, GPIOA, Pin_3, TIM_Channel_4, TIM2_IRQn, 0, Mode_IPD, 0}, // PWM4 - RC4 - { TIM3, GPIOA, Pin_6, TIM_Channel_1, TIM3_IRQn, 0, Mode_IPD, 0}, // PWM5 - RC5 - { TIM3, GPIOA, Pin_7, TIM_Channel_2, TIM3_IRQn, 0, Mode_IPD, 0}, // PWM6 - RC6 - { TIM3, GPIOB, Pin_0, TIM_Channel_3, TIM3_IRQn, 0, Mode_IPD, 0}, // PWM7 - RC7 - { TIM3, GPIOB, Pin_1, TIM_Channel_4, TIM3_IRQn, 0, Mode_IPD, 0}, // PWM8 - RC8 - { TIM1, GPIOA, Pin_8, TIM_Channel_1, TIM1_CC_IRQn, 1, Mode_IPD, 0}, // PWM9 - OUT1 - { TIM1, GPIOA, Pin_11,TIM_Channel_4, TIM1_CC_IRQn, 1, Mode_IPD, 0}, // PWM10 - OUT2 - { TIM4, GPIOB, Pin_6, TIM_Channel_1, TIM4_IRQn, 0, Mode_IPD, 0}, // PWM11 - OUT3 - { TIM4, GPIOB, Pin_7, TIM_Channel_2, TIM4_IRQn, 0, Mode_IPD, 0}, // PWM12 - OUT4 - { TIM4, GPIOB, Pin_8, TIM_Channel_3, TIM4_IRQn, 0, Mode_IPD, 0}, // PWM13 - OUT5 - { TIM4, GPIOB, Pin_9, TIM_Channel_4, TIM4_IRQn, 0, Mode_IPD, 0} // PWM14 - OUT6 + { TIM2, IO_TAG(PA0), TIM_Channel_1, TIM2_IRQn, 0, IOCFG_IPD, 0}, // PWM1 - RC1 + { TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, 0, IOCFG_IPD, 0}, // PWM2 - RC2 + { TIM2, IO_TAG(PA2), TIM_Channel_3, TIM2_IRQn, 0, IOCFG_IPD, 0}, // PWM3 - RC3 + { TIM2, IO_TAG(PA3), TIM_Channel_4, TIM2_IRQn, 0, IOCFG_IPD, 0}, // PWM4 - RC4 + { TIM3, IO_TAG(PA6), TIM_Channel_1, TIM3_IRQn, 0, IOCFG_IPD, 0}, // PWM5 - RC5 + { TIM3, IO_TAG(PA7), TIM_Channel_2, TIM3_IRQn, 0, IOCFG_IPD, 0}, // PWM6 - RC6 + { TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, 0, IOCFG_IPD, 0}, // PWM7 - RC7 + { TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, 0, IOCFG_IPD, 0}, // PWM8 - RC8 + { TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, 1, IOCFG_IPD, 0}, // PWM9 - OUT1 + { TIM1, IO_TAG(PA11),TIM_Channel_4, TIM1_CC_IRQn, 1, IOCFG_IPD, 0}, // PWM10 - OUT2 + { TIM4, IO_TAG(PB6), TIM_Channel_1, TIM4_IRQn, 0, IOCFG_IPD, 0}, // PWM11 - OUT3 + { TIM4, IO_TAG(PB7), TIM_Channel_2, TIM4_IRQn, 0, IOCFG_IPD, 0}, // PWM12 - OUT4 + { TIM4, IO_TAG(PB8), TIM_Channel_3, TIM4_IRQn, 0, IOCFG_IPD, 0}, // PWM13 - OUT5 + { TIM4, IO_TAG(PB9), TIM_Channel_4, TIM4_IRQn, 0, IOCFG_IPD, 0} // PWM14 - OUT6 }; diff --git a/src/main/target/PORT103R/target.c b/src/main/target/PORT103R/target.c index 36728e8c59..e014e430d1 100644 --- a/src/main/target/PORT103R/target.c +++ b/src/main/target/PORT103R/target.c @@ -72,19 +72,19 @@ const uint16_t airPWM[] = { }; const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { - { TIM2, GPIOA, Pin_0, TIM_Channel_1, TIM2_IRQn, 0, Mode_IPD, 0}, // PWM1 - RC1 - { TIM2, GPIOA, Pin_1, TIM_Channel_2, TIM2_IRQn, 0, Mode_IPD, 0}, // PWM2 - RC2 - { TIM2, GPIOA, Pin_2, TIM_Channel_3, TIM2_IRQn, 0, Mode_IPD, 0}, // PWM3 - RC3 - { TIM2, GPIOA, Pin_3, TIM_Channel_4, TIM2_IRQn, 0, Mode_IPD, 0}, // PWM4 - RC4 - { TIM3, GPIOA, Pin_6, TIM_Channel_1, TIM3_IRQn, 0, Mode_IPD, 0}, // PWM5 - RC5 - { TIM3, GPIOA, Pin_7, TIM_Channel_2, TIM3_IRQn, 0, Mode_IPD, 0}, // PWM6 - RC6 - { TIM3, GPIOB, Pin_0, TIM_Channel_3, TIM3_IRQn, 0, Mode_IPD, 0}, // PWM7 - RC7 - { TIM3, GPIOB, Pin_1, TIM_Channel_4, TIM3_IRQn, 0, Mode_IPD, 0}, // PWM8 - RC8 - { TIM1, GPIOA, Pin_8, TIM_Channel_1, TIM1_CC_IRQn, 1, Mode_IPD, 0}, // PWM9 - OUT1 - { TIM1, GPIOA, Pin_11,TIM_Channel_4, TIM1_CC_IRQn, 1, Mode_IPD, 0}, // PWM10 - OUT2 - { TIM4, GPIOB, Pin_6, TIM_Channel_1, TIM4_IRQn, 0, Mode_IPD, 0}, // PWM11 - OUT3 - { TIM4, GPIOB, Pin_7, TIM_Channel_2, TIM4_IRQn, 0, Mode_IPD, 0}, // PWM12 - OUT4 - { TIM4, GPIOB, Pin_8, TIM_Channel_3, TIM4_IRQn, 0, Mode_IPD, 0}, // PWM13 - OUT5 - { TIM4, GPIOB, Pin_9, TIM_Channel_4, TIM4_IRQn, 0, Mode_IPD, 0} // PWM14 - OUT6 + { TIM2, IO_TAG(PA0), TIM_Channel_1, TIM2_IRQn, 0, IOCFG_IPD, 0}, // PWM1 - RC1 + { TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, 0, IOCFG_IPD, 0}, // PWM2 - RC2 + { TIM2, IO_TAG(PA2), TIM_Channel_3, TIM2_IRQn, 0, IOCFG_IPD, 0}, // PWM3 - RC3 + { TIM2, IO_TAG(PA3), TIM_Channel_4, TIM2_IRQn, 0, IOCFG_IPD, 0}, // PWM4 - RC4 + { TIM3, IO_TAG(PA6), TIM_Channel_1, TIM3_IRQn, 0, IOCFG_IPD, 0}, // PWM5 - RC5 + { TIM3, IO_TAG(PA7), TIM_Channel_2, TIM3_IRQn, 0, IOCFG_IPD, 0}, // PWM6 - RC6 + { TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, 0, IOCFG_IPD, 0}, // PWM7 - RC7 + { TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, 0, IOCFG_IPD, 0}, // PWM8 - RC8 + { TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, 1, IOCFG_IPD, 0}, // PWM9 - OUT1 + { TIM1, IO_TAG(PA11),TIM_Channel_4, TIM1_CC_IRQn, 1, IOCFG_IPD, 0}, // PWM10 - OUT2 + { TIM4, IO_TAG(PB6), TIM_Channel_1, TIM4_IRQn, 0, IOCFG_IPD, 0}, // PWM11 - OUT3 + { TIM4, IO_TAG(PB7), TIM_Channel_2, TIM4_IRQn, 0, IOCFG_IPD, 0}, // PWM12 - OUT4 + { TIM4, IO_TAG(PB8), TIM_Channel_3, TIM4_IRQn, 0, IOCFG_IPD, 0}, // PWM13 - OUT5 + { TIM4, IO_TAG(PB9), TIM_Channel_4, TIM4_IRQn, 0, IOCFG_IPD, 0} // PWM14 - OUT6 }; diff --git a/src/main/target/REVO/target.c b/src/main/target/REVO/target.c index 7e93d4d16f..af6b8eb1e8 100644 --- a/src/main/target/REVO/target.c +++ b/src/main/target/REVO/target.c @@ -71,19 +71,19 @@ const uint16_t airPWM[] = { const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { - { TIM12, GPIOB, Pin_14, TIM_Channel_1, TIM8_BRK_TIM12_IRQn, 0, GPIO_Mode_AF, GPIO_PinSource14, GPIO_AF_TIM12, 0}, // PPM (5th pin on FlexiIO port) - { TIM12, GPIOB, Pin_15, TIM_Channel_2, TIM8_BRK_TIM12_IRQn, 0, GPIO_Mode_AF, GPIO_PinSource15, GPIO_AF_TIM12, 0}, // S2_IN - GPIO_PartialRemap_TIM3 - { TIM8, GPIOC, Pin_6, TIM_Channel_1, TIM8_CC_IRQn, 0, GPIO_Mode_AF, GPIO_PinSource6, GPIO_AF_TIM8, 0}, // S3_IN - { TIM8, GPIOC, Pin_7, TIM_Channel_2, TIM8_CC_IRQn, 0, GPIO_Mode_AF, GPIO_PinSource7, GPIO_AF_TIM8, 0}, // S4_IN - { TIM8, GPIOC, Pin_8, TIM_Channel_3, TIM8_CC_IRQn, 0, GPIO_Mode_AF, GPIO_PinSource8, GPIO_AF_TIM8, 0}, // S5_IN - { TIM8, GPIOC, Pin_9, TIM_Channel_4, TIM8_CC_IRQn, 0, GPIO_Mode_AF, GPIO_PinSource9, GPIO_AF_TIM8, 0}, // S6_IN - - { TIM3, GPIOB, Pin_0, TIM_Channel_3, TIM3_IRQn, 1, GPIO_Mode_AF, GPIO_PinSource0, GPIO_AF_TIM3, 0}, // S1_OUT - { TIM3, GPIOB, Pin_1, TIM_Channel_4, TIM3_IRQn, 1, GPIO_Mode_AF, GPIO_PinSource1, GPIO_AF_TIM3, 0}, // S2_OUT - { TIM9, GPIOA, Pin_3, TIM_Channel_2, TIM1_BRK_TIM9_IRQn, 1, GPIO_Mode_AF, GPIO_PinSource3, GPIO_AF_TIM9, 0}, // S3_OUT - { TIM2, GPIOA, Pin_2, TIM_Channel_3, TIM2_IRQn, 1, GPIO_Mode_AF, GPIO_PinSource2, GPIO_AF_TIM2, 0}, // S4_OUT - { TIM5, GPIOA, Pin_1, TIM_Channel_2, TIM5_IRQn, 1, GPIO_Mode_AF, GPIO_PinSource1, GPIO_AF_TIM5, 0}, // S5_OUT - GPIO_PartialRemap_TIM3 - { TIM5, GPIOA, Pin_0, TIM_Channel_1, TIM5_IRQn, 1, GPIO_Mode_AF, GPIO_PinSource0, GPIO_AF_TIM5, 0}, // S6_OUT + { TIM12, IO_TAG(PB14), TIM_Channel_1, TIM8_BRK_TIM12_IRQn, IOCFG_IPD, GPIO_Mode_AF, GPIO_AF_TIM12, 0}, // PPM (5th pin on FlexiIO port) + { TIM12, IO_TAG(PB15), TIM_Channel_2, TIM8_BRK_TIM12_IRQn, IOCFG_IPD, GPIO_Mode_AF, GPIO_AF_TIM12, 0}, // S2_IN - GPIO_PartialRemap_TIM3 + { TIM8, IO_TAG(PC6), TIM_Channel_1, TIM8_CC_IRQn, IOCFG_IPD, GPIO_Mode_AF, GPIO_AF_TIM8, 0}, // S3_IN + { TIM8, IO_TAG(PC7), TIM_Channel_2, TIM8_CC_IRQn, IOCFG_IPD, GPIO_Mode_AF, GPIO_AF_TIM8, 0}, // S4_IN + { TIM8, IO_TAG(PC8), TIM_Channel_3, TIM8_CC_IRQn, IOCFG_IPD, GPIO_Mode_AF, GPIO_AF_TIM8, 0}, // S5_IN + { TIM8, IO_TAG(PC9), TIM_Channel_4, TIM8_CC_IRQn, IOCFG_IPD, GPIO_Mode_AF, GPIO_AF_TIM8, 0}, // S6_IN + + { TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, IOCFG_AF_PP_PD, GPIO_Mode_AF, GPIO_AF_TIM3, 0}, // S1_OUT + { TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, IOCFG_AF_PP_PD, GPIO_Mode_AF, GPIO_AF_TIM3, 0}, // S2_OUT + { TIM9, IO_TAG(PA3), TIM_Channel_2, TIM1_BRK_TIM9_IRQn, IOCFG_AF_PP_PD, GPIO_Mode_AF, GPIO_AF_TIM9, 0}, // S3_OUT + { TIM2, IO_TAG(PA2), TIM_Channel_3, TIM2_IRQn, IOCFG_AF_PP_PD, GPIO_Mode_AF, GPIO_AF_TIM2, 0}, // S4_OUT + { TIM5, IO_TAG(PA1), TIM_Channel_2, TIM5_IRQn, IOCFG_AF_PP_PD, GPIO_Mode_AF, GPIO_AF_TIM5, 0}, // S5_OUT - GPIO_PartialRemap_TIM3 + { TIM5, IO_TAG(PA0), TIM_Channel_1, TIM5_IRQn, IOCFG_AF_PP_PD, GPIO_Mode_AF, GPIO_AF_TIM5, 0}, // S6_OUT }; diff --git a/src/main/target/RMDO/target.c b/src/main/target/RMDO/target.c index fea9723b25..9eaf0c4d9d 100644 --- a/src/main/target/RMDO/target.c +++ b/src/main/target/RMDO/target.c @@ -81,22 +81,22 @@ const uint16_t airPWM[] = { }; const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { - { TIM2, GPIOA, Pin_0, TIM_Channel_1, TIM2_IRQn, 0, Mode_AF_PP, GPIO_PinSource0, GPIO_AF_1 ,0}, // RC_CH1 - PA0 - *TIM2_CH1 - { TIM2, GPIOA, Pin_1, TIM_Channel_2, TIM2_IRQn, 0, Mode_AF_PP, GPIO_PinSource1, GPIO_AF_1 ,0}, // RC_CH2 - PA1 - *TIM2_CH2, TIM15_CH1N - { TIM2, GPIOB, Pin_11, TIM_Channel_4, TIM2_IRQn, 0, Mode_AF_PP, GPIO_PinSource11, GPIO_AF_1 ,0}, // RC_CH3 - PB11 - *TIM2_CH4, USART3_RX (AF7) - { TIM2, GPIOB, Pin_10, TIM_Channel_3, TIM2_IRQn, 0, Mode_AF_PP, GPIO_PinSource10, GPIO_AF_1 ,0}, // RC_CH4 - PB10 - *TIM2_CH3, USART3_TX (AF7) - { TIM3, GPIOB, Pin_4, TIM_Channel_1, TIM3_IRQn, 0, Mode_AF_PP, GPIO_PinSource4, GPIO_AF_2 ,0}, // RC_CH5 - PB4 - *TIM3_CH1 - { TIM3, GPIOB, Pin_5, TIM_Channel_2, TIM3_IRQn, 0, Mode_AF_PP, GPIO_PinSource5, GPIO_AF_2 ,0}, // RC_CH6 - PB5 - *TIM3_CH2 - { TIM3, GPIOB, Pin_0, TIM_Channel_3, TIM3_IRQn, 0, Mode_AF_PP, GPIO_PinSource0, GPIO_AF_2 ,0}, // RC_CH7 - PB0 - *TIM3_CH3, TIM1_CH2N, TIM8_CH2N - { TIM3, GPIOB, Pin_1, TIM_Channel_4, TIM3_IRQn, 0, Mode_AF_PP, GPIO_PinSource1, GPIO_AF_2 ,0}, // RC_CH8 - PB1 - *TIM3_CH4, TIM1_CH3N, TIM8_CH3N - { TIM16, GPIOA, Pin_6, TIM_Channel_1, TIM1_UP_TIM16_IRQn, 1, Mode_AF_PP, GPIO_PinSource6, GPIO_AF_1 ,0}, // PWM1 - PA6 - TIM3_CH1, TIM8_BKIN, TIM1_BKIN, *TIM16_CH1 - { TIM17, GPIOA, Pin_7, TIM_Channel_1, TIM1_TRG_COM_TIM17_IRQn, 1, Mode_AF_PP, GPIO_PinSource7, GPIO_AF_1 ,0}, // PWM2 - PA7 - TIM3_CH2, *TIM17_CH1, TIM1_CH1N, TIM8_CH1 - { TIM4, GPIOA, Pin_11, TIM_Channel_1, TIM4_IRQn, 1, Mode_AF_PP, GPIO_PinSource11, GPIO_AF_10 ,0}, // PWM3 - PA11 - { TIM4, GPIOA, Pin_12, TIM_Channel_2, TIM4_IRQn, 1, Mode_AF_PP, GPIO_PinSource12, GPIO_AF_10 ,0}, // PWM4 - PA12 - { TIM4, GPIOB, Pin_8, TIM_Channel_3, TIM4_IRQn, 1, Mode_AF_PP, GPIO_PinSource8, GPIO_AF_2 ,0}, // PWM5 - PB8 - { TIM4, GPIOB, Pin_9, TIM_Channel_4, TIM4_IRQn, 1, Mode_AF_PP, GPIO_PinSource9, GPIO_AF_2 ,0}, // PWM6 - PB9 - { TIM15, GPIOA, Pin_2, TIM_Channel_1, TIM1_BRK_TIM15_IRQn, 1, Mode_AF_PP, GPIO_PinSource2, GPIO_AF_9 ,0}, // PWM7 - PA2 - { TIM15, GPIOA, Pin_3, TIM_Channel_2, TIM1_BRK_TIM15_IRQn, 1, Mode_AF_PP, GPIO_PinSource3, GPIO_AF_9 ,0}, // PWM8 - PA3 - { TIM1, GPIOA, Pin_8, TIM_Channel_1, TIM1_CC_IRQn, 1, Mode_AF_PP, GPIO_PinSource8, GPIO_AF_6 ,0}, // GPIO_TIMER / LED_STRIP + { TIM2, IO_TAG(PA0), TIM_Channel_1, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1, 0}, // RC_CH1 - PA0 - *TIM2_CH1 + { TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1, 0}, // RC_CH2 - PA1 - *TIM2_CH2, TIM15_CH1N + { TIM2, IO_TAG(PB11), TIM_Channel_4, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1, 0}, // RC_CH3 - PB11 - *TIM2_CH4, USART3_RX (AF7) + { TIM2, IO_TAG(PB10), TIM_Channel_3, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1, 0}, // RC_CH4 - PB10 - *TIM2_CH3, USART3_TX (AF7) + { TIM3, IO_TAG(PB4), TIM_Channel_1, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2, 0}, // RC_CH5 - PB4 - *TIM3_CH1 + { TIM3, IO_TAG(PB5), TIM_Channel_2, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2, 0}, // RC_CH6 - PB5 - *TIM3_CH2 + { TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2, 0}, // RC_CH7 - PB0 - *TIM3_CH3, TIM1_CH2N, TIM8_CH2N + { TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2, 0}, // RC_CH8 - PB1 - *TIM3_CH4, TIM1_CH3N, TIM8_CH3N + { TIM16, IO_TAG(PA6), TIM_Channel_1, TIM1_UP_TIM16_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1, 0}, // PWM1 - PA6 - TIM3_CH1, TIM8_BKIN, TIM1_BKIN, *TIM16_CH1 + { TIM17, IO_TAG(PA7), TIM_Channel_1, TIM1_TRG_COM_TIM17_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1, 0}, // PWM2 - PA7 - TIM3_CH2, *TIM17_CH1, TIM1_CH1N, TIM8_CH1 + { TIM4, IO_TAG(PA11), TIM_Channel_1, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_10, 0}, // PWM3 - PA11 + { TIM4, IO_TAG(PA12), TIM_Channel_2, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_10, 0}, // PWM4 - PA12 + { TIM4, IO_TAG(PB8), TIM_Channel_3, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2, 0}, // PWM5 - PB8 + { TIM4, IO_TAG(PB9), TIM_Channel_4, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2, 0}, // PWM6 - PB9 + { TIM15, IO_TAG(PA2), TIM_Channel_1, TIM1_BRK_TIM15_IRQn, 1, IOCFG_AF_PP, GPIO_AF_9, 0}, // PWM7 - PA2 + { TIM15, IO_TAG(PA3), TIM_Channel_2, TIM1_BRK_TIM15_IRQn, 1, IOCFG_AF_PP, GPIO_AF_9, 0}, // PWM8 - PA3 + { TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, 1, IOCFG_AF_PP, GPIO_AF_6, 0}, // GPIO_TIMER / LED_STRIP }; diff --git a/src/main/target/SINGULARITY/target.c b/src/main/target/SINGULARITY/target.c index 137e6bdeb6..fe6106ec9e 100644 --- a/src/main/target/SINGULARITY/target.c +++ b/src/main/target/SINGULARITY/target.c @@ -60,18 +60,15 @@ const uint16_t airPWM[] = { }; const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { - { TIM2, GPIOA, Pin_15, TIM_Channel_1, TIM2_IRQn, 0, Mode_AF_PP, GPIO_PinSource15, GPIO_AF_1, 0}, // PPM/SERIAL RX - - { TIM3, GPIOB, Pin_4, TIM_Channel_1, TIM3_IRQn, 0, Mode_AF_PP, GPIO_PinSource4, GPIO_AF_2, 0}, // PWM1 - { TIM3, GPIOB, Pin_5, TIM_Channel_2, TIM3_IRQn, 0, Mode_AF_PP, GPIO_PinSource5, GPIO_AF_2, 0}, // PWM2 - { TIM3, GPIOB, Pin_0, TIM_Channel_3, TIM3_IRQn, 0, Mode_AF_PP, GPIO_PinSource0, GPIO_AF_2, 0}, // PWM3 - { TIM3, GPIOB, Pin_1, TIM_Channel_4, TIM3_IRQn, 0, Mode_AF_PP, GPIO_PinSource1, GPIO_AF_2, 0}, // PWM4 - { TIM16, GPIOB, Pin_8, TIM_Channel_1, TIM1_UP_TIM16_IRQn, 1, Mode_AF_PP, GPIO_PinSource8, GPIO_AF_1, 0}, // PWM5 - { TIM17, GPIOB, Pin_9, TIM_Channel_1, TIM1_TRG_COM_TIM17_IRQn, 1, Mode_AF_PP, GPIO_PinSource9, GPIO_AF_1, 0}, // PWM6 - - { TIM15, GPIOA, Pin_2, TIM_Channel_1, TIM1_BRK_TIM15_IRQn, 1, Mode_AF_PP, GPIO_PinSource2, GPIO_AF_9, 0}, // SOFTSERIAL1 RX (NC) - { TIM15, GPIOA, Pin_3, TIM_Channel_2, TIM1_BRK_TIM15_IRQn, 1, Mode_AF_PP, GPIO_PinSource3, GPIO_AF_9, 0}, // SOFTSERIAL1 TX - - { TIM1, GPIOA, Pin_8, TIM_Channel_1, TIM1_CC_IRQn, 1, Mode_AF_PP, GPIO_PinSource8, GPIO_AF_6, 0}, // LED_STRIP + { TIM2, IO_TAG(PA15), TIM_Channel_1, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1, 0}, // PPM/SERIAL RX + { TIM3, IO_TAG(PB4), TIM_Channel_1, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2, 0}, // PWM1 + { TIM3, IO_TAG(PB5), TIM_Channel_2, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2, 0}, // PWM2 + { TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2, 0}, // PWM3 + { TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2, 0}, // PWM4 + { TIM16, IO_TAG(PB8), TIM_Channel_1, TIM1_UP_TIM16_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1, 0}, // PWM5 + { TIM17, IO_TAG(PB9), TIM_Channel_1, TIM1_TRG_COM_TIM17_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1, 0}, // PWM6 + { TIM15, IO_TAG(PA2), TIM_Channel_1, TIM1_BRK_TIM15_IRQn, 1, IOCFG_AF_PP, GPIO_AF_9, 0}, // SOFTSERIAL1 RX (NC) + { TIM15, IO_TAG(PA3), TIM_Channel_2, TIM1_BRK_TIM15_IRQn, 1, IOCFG_AF_PP, GPIO_AF_9, 0}, // SOFTSERIAL1 TX + { TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, 1, IOCFG_AF_PP, GPIO_AF_6, 0}, // LED_STRIP }; diff --git a/src/main/target/SPARKY/target.c b/src/main/target/SPARKY/target.c index 76d27d777a..2b27f994f6 100644 --- a/src/main/target/SPARKY/target.c +++ b/src/main/target/SPARKY/target.c @@ -47,38 +47,16 @@ const uint16_t airPWM[] = { const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { - // - // 6 x 3 pin headers - // - - { TIM15, GPIOB, Pin_15, TIM_Channel_2, TIM1_BRK_TIM15_IRQn, 1, Mode_AF_PP, GPIO_PinSource15, GPIO_AF_1, 0}, // PWM1 - PB15 - TIM1_CH3N, TIM15_CH1N, *TIM15_CH2 - { TIM15, GPIOB, Pin_14, TIM_Channel_1, TIM1_BRK_TIM15_IRQn, 1, Mode_AF_PP, GPIO_PinSource14, GPIO_AF_1, 0}, // PWM2 - PB14 - TIM1_CH2N, *TIM15_CH1 - { TIM1, GPIOA, Pin_8, TIM_Channel_1, TIM1_CC_IRQn, 1, Mode_AF_PP, GPIO_PinSource8, GPIO_AF_6, 0}, // PWM3 - PA8 - *TIM1_CH1, TIM4_ETR - { TIM3, GPIOB, Pin_0, TIM_Channel_3, TIM3_IRQn, 0, Mode_AF_PP, GPIO_PinSource0, GPIO_AF_2, 0}, // PWM4 - PB0 - *TIM3_CH3, TIM1_CH2N, TIM8_CH2N - { TIM3, GPIOA, Pin_6, TIM_Channel_1, TIM3_IRQn, 0, Mode_AF_PP, GPIO_PinSource6, GPIO_AF_2, 0}, // PWM5 - PA6 - *TIM3_CH1, TIM8_BKIN, TIM1_BKIN, TIM16_CH1 - { TIM2, GPIOA, Pin_2, TIM_Channel_3, TIM2_IRQn, 0, Mode_AF_PP, GPIO_PinSource2, GPIO_AF_1, 0}, // PWM6 - PA2 - *TIM2_CH3, !TIM15_CH1 - - // - // 6 pin header - // - - // PWM7-10 - { TIM3, GPIOB, Pin_1, TIM_Channel_4, TIM3_IRQn, 0, Mode_AF_PP, GPIO_PinSource1, GPIO_AF_2, 0}, // PWM7 - PB1 - *TIM3_CH4, TIM1_CH3N, TIM8_CH3N - { TIM17, GPIOA, Pin_7, TIM_Channel_1, TIM1_TRG_COM_TIM17_IRQn, 1, Mode_AF_PP, GPIO_PinSource7, GPIO_AF_1, 0}, // PWM8 - PA7 - !TIM3_CH2, *TIM17_CH1, TIM1_CH1N, TIM8_CH1 - { TIM3, GPIOA, Pin_4, TIM_Channel_2, TIM3_IRQn, 0, Mode_AF_PP, GPIO_PinSource4, GPIO_AF_2, 0}, // PWM9 - PA4 - *TIM3_CH2 - { TIM2, GPIOA, Pin_1, TIM_Channel_2, TIM2_IRQn, 0, Mode_AF_PP, GPIO_PinSource1, GPIO_AF_1, 0}, // PWM10 - PA1 - *TIM2_CH2, TIM15_CH1N - - // - // PPM PORT - Also USART2 RX (AF5) - // - - { TIM2, GPIOA, Pin_3, TIM_Channel_4, TIM2_IRQn, 0, Mode_AF_PP_PD, GPIO_PinSource3, GPIO_AF_1, 0} // PPM - PA3 - TIM2_CH4, TIM15_CH2 - PWM13 - //{ TIM15, GPIOA, Pin_3, TIM_Channel_2, TIM1_BRK_TIM15_IRQn, 0, Mode_AF_PP_PD, GPIO_PinSource3, GPIO_AF_9, 0} // PPM - PA3 - TIM2_CH4, TIM15_CH2 - PWM13 - - // USART3 RX/TX - // RX conflicts with PPM port - //{ TIM2, GPIOB, Pin_11, TIM_Channel_4, TIM3_IRQn, 0, Mode_AF_PP, GPIO_PinSource11, GPIO_AF_1, 0} // RX - PB11 - *TIM2_CH4, USART3_RX (AF7) - PWM11 - //{ TIM2, GPIOB, Pin_10, TIM_Channel_3, TIM3_IRQn, 0, Mode_AF_PP, GPIO_PinSource10, GPIO_AF_1, 0} // TX - PB10 - *TIM2_CH3, USART3_TX (AF7) - PWM12 - + { TIM15, IO_TAG(PB15), TIM_Channel_2, TIM1_BRK_TIM15_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1, 0}, // PWM1 - PB15 - TIM1_CH3N, TIM15_CH1N, *TIM15_CH2 + { TIM15, IO_TAG(PB14), TIM_Channel_1, TIM1_BRK_TIM15_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1, 0}, // PWM2 - PB14 - TIM1_CH2N, *TIM15_CH1 + { TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, 1, IOCFG_AF_PP, GPIO_AF_6, 0}, // PWM3 - PA8 - *TIM1_CH1, TIM4_ETR + { TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2, 0}, // PWM4 - PB0 - *TIM3_CH3, TIM1_CH2N, TIM8_CH2N + { TIM3, IO_TAG(PA6), TIM_Channel_1, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2, 0}, // PWM5 - PA6 - *TIM3_CH1, TIM8_BKIN, TIM1_BKIN, TIM16_CH1 + { TIM2, IO_TAG(PA2), TIM_Channel_3, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1, 0}, // PWM6 - PA2 - *TIM2_CH3, !TIM15_CH1 + { TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2, 0}, // PWM7 - PB1 - *TIM3_CH4, TIM1_CH3N, TIM8_CH3N + { TIM17, IO_TAG(PA7), TIM_Channel_1, TIM1_TRG_COM_TIM17_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1, 0}, // PWM8 - PA7 - !TIM3_CH2, *TIM17_CH1, TIM1_CH1N, TIM8_CH1 + { TIM3, IO_TAG(PA4), TIM_Channel_2, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2, 0}, // PWM9 - PA4 - *TIM3_CH2 + { TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1, 0}, // PWM10 - PA1 - *TIM2_CH2, TIM15_CH1N + { TIM2, IO_TAG(PA3), TIM_Channel_4, TIM2_IRQn, 0, IOCFG_AF_PP_PD, GPIO_AF_1, 0} // PPM - PA3 - TIM2_CH4, TIM15_CH2 - PWM13 }; diff --git a/src/main/target/SPRACINGF3/target.c b/src/main/target/SPRACINGF3/target.c index 5c68f9a98b..829d7ef003 100644 --- a/src/main/target/SPRACINGF3/target.c +++ b/src/main/target/SPRACINGF3/target.c @@ -3,6 +3,7 @@ #include #include +#include "drivers/io.h" #include "drivers/pwm_mapping.h" const uint16_t multiPPM[] = { @@ -81,25 +82,25 @@ const uint16_t airPWM[] = { }; const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { - { TIM2, GPIOA, Pin_0, TIM_Channel_1, TIM2_IRQn, 0, Mode_AF_PP, GPIO_PinSource0, GPIO_AF_1, 0}, // RC_CH1 - PA0 - *TIM2_CH1 - { TIM2, GPIOA, Pin_1, TIM_Channel_2, TIM2_IRQn, 0, Mode_AF_PP, GPIO_PinSource1, GPIO_AF_1, 0}, // RC_CH2 - PA1 - *TIM2_CH2, TIM15_CH1N + { TIM2, IO_TAG(PA0), TIM_Channel_1, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1, 0}, // RC_CH1 - PA0 - *TIM2_CH1 + { TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1, 0}, // RC_CH2 - PA1 - *TIM2_CH2, TIM15_CH1N // Production boards swapped RC_CH3/4 swapped to make it easier to use SerialRX using supplied cables - compared to first prototype. - { TIM2, GPIOB, Pin_11, TIM_Channel_4, TIM2_IRQn, 0, Mode_AF_PP, GPIO_PinSource11, GPIO_AF_1, 0}, // RC_CH3 - PB11 - *TIM2_CH4, USART3_RX (AF7) - { TIM2, GPIOB, Pin_10, TIM_Channel_3, TIM2_IRQn, 0, Mode_AF_PP, GPIO_PinSource10, GPIO_AF_1, 0}, // RC_CH4 - PB10 - *TIM2_CH3, USART3_TX (AF7) - { TIM3, GPIOB, Pin_4, TIM_Channel_1, TIM3_IRQn, 0, Mode_AF_PP, GPIO_PinSource4, GPIO_AF_2, 0}, // RC_CH5 - PB4 - *TIM3_CH1 - { TIM3, GPIOB, Pin_5, TIM_Channel_2, TIM3_IRQn, 0, Mode_AF_PP, GPIO_PinSource5, GPIO_AF_2, 0}, // RC_CH6 - PB5 - *TIM3_CH2 - { TIM3, GPIOB, Pin_0, TIM_Channel_3, TIM3_IRQn, 0, Mode_AF_PP, GPIO_PinSource0, GPIO_AF_2, 0}, // RC_CH7 - PB0 - *TIM3_CH3, TIM1_CH2N, TIM8_CH2N - { TIM3, GPIOB, Pin_1, TIM_Channel_4, TIM3_IRQn, 0, Mode_AF_PP, GPIO_PinSource1, GPIO_AF_2, 0}, // RC_CH8 - PB1 - *TIM3_CH4, TIM1_CH3N, TIM8_CH3N + { TIM2, IO_TAG(PB11), TIM_Channel_4, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1, 0}, // RC_CH3 - PB11 - *TIM2_CH4, USART3_RX (AF7) + { TIM2, IO_TAG(PB10), TIM_Channel_3, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1, 0}, // RC_CH4 - PB10 - *TIM2_CH3, USART3_TX (AF7) + { TIM3, IO_TAG(PB4), TIM_Channel_1, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2, 0}, // RC_CH5 - PB4 - *TIM3_CH1 + { TIM3, IO_TAG(PB5), TIM_Channel_2, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2, 0}, // RC_CH6 - PB5 - *TIM3_CH2 + { TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2, 0}, // RC_CH7 - PB0 - *TIM3_CH3, TIM1_CH2N, TIM8_CH2N + { TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2, 0}, // RC_CH8 - PB1 - *TIM3_CH4, TIM1_CH3N, TIM8_CH3N - { TIM16, GPIOA, Pin_6, TIM_Channel_1, TIM1_UP_TIM16_IRQn, 1, Mode_AF_PP, GPIO_PinSource6, GPIO_AF_1, 0}, // PWM1 - PA6 - TIM3_CH1, TIM8_BKIN, TIM1_BKIN, *TIM16_CH1 - { TIM17, GPIOA, Pin_7, TIM_Channel_1, TIM1_TRG_COM_TIM17_IRQn, 1, Mode_AF_PP, GPIO_PinSource7, GPIO_AF_1}, // PWM2 - PA7 - TIM3_CH2, *TIM17_CH1, TIM1_CH1N, TIM8_CH1 - { TIM4, GPIOA, Pin_11, TIM_Channel_1, TIM4_IRQn, 1, Mode_AF_PP, GPIO_PinSource11, GPIO_AF_10, 0}, // PWM3 - PA11 - { TIM4, GPIOA, Pin_12, TIM_Channel_2, TIM4_IRQn, 1, Mode_AF_PP, GPIO_PinSource12, GPIO_AF_10, 0}, // PWM4 - PA12 - { TIM4, GPIOB, Pin_8, TIM_Channel_3, TIM4_IRQn, 1, Mode_AF_PP, GPIO_PinSource8, GPIO_AF_2, 0}, // PWM5 - PB8 - { TIM4, GPIOB, Pin_9, TIM_Channel_4, TIM4_IRQn, 1, Mode_AF_PP, GPIO_PinSource9, GPIO_AF_2, 0}, // PWM6 - PB9 - { TIM15, GPIOA, Pin_2, TIM_Channel_1, TIM1_BRK_TIM15_IRQn, 1, Mode_AF_PP, GPIO_PinSource2, GPIO_AF_9, 0}, // PWM7 - PA2 - { TIM15, GPIOA, Pin_3, TIM_Channel_2, TIM1_BRK_TIM15_IRQn, 1, Mode_AF_PP, GPIO_PinSource3, GPIO_AF_9, 0}, // PWM8 - PA3 + { TIM16, IO_TAG(PA6), TIM_Channel_1, TIM1_UP_TIM16_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1, 0}, // PWM1 - PA6 - TIM3_CH1, TIM8_BKIN, TIM1_BKIN, *TIM16_CH1 + { TIM17, IO_TAG(PA7), TIM_Channel_1, TIM1_TRG_COM_TIM17_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1, 0}, // PWM2 - PA7 - TIM3_CH2, *TIM17_CH1, TIM1_CH1N, TIM8_CH1 + { TIM4, IO_TAG(PA11), TIM_Channel_1, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_10, 0}, // PWM3 - PA11 + { TIM4, IO_TAG(PA12), TIM_Channel_2, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_10, 0}, // PWM4 - PA12 + { TIM4, IO_TAG(PB8), TIM_Channel_3, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2, 0}, // PWM5 - PB8 + { TIM4, IO_TAG(PB9), TIM_Channel_4, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2, 0}, // PWM6 - PB9 + { TIM15, IO_TAG(PA2), TIM_Channel_1, TIM1_BRK_TIM15_IRQn, 1, IOCFG_AF_PP, GPIO_AF_9, 0}, // PWM7 - PA2 + { TIM15, IO_TAG(PA3), TIM_Channel_2, TIM1_BRK_TIM15_IRQn, 1, IOCFG_AF_PP, GPIO_AF_9, 0}, // PWM8 - PA3 - { TIM1, GPIOA, Pin_8, TIM_Channel_1, TIM1_CC_IRQn, 1, Mode_AF_PP, GPIO_PinSource8, GPIO_AF_6, 0}, // GPIO_TIMER / LED_STRIP + { TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, 1, IOCFG_AF_PP, GPIO_AF_6, 0}, // GPIO_TIMER / LED_STRIP }; diff --git a/src/main/target/SPRACINGF3EVO/target.c b/src/main/target/SPRACINGF3EVO/target.c index 81cc1ed06a..1b601e8818 100644 --- a/src/main/target/SPRACINGF3EVO/target.c +++ b/src/main/target/SPRACINGF3EVO/target.c @@ -3,6 +3,7 @@ #include #include +#include "drivers/io.h" #include "drivers/pwm_mapping.h" const uint16_t multiPPM[] = { @@ -66,22 +67,17 @@ const uint16_t airPWM[] = { const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { // PPM / UART2 RX - { TIM8, GPIOA, Pin_15, TIM_Channel_1, TIM8_CC_IRQn, 0, Mode_AF_PP_PD, GPIO_PinSource15, GPIO_AF_2, 0}, // PPM - - { TIM2, GPIOA, Pin_0, TIM_Channel_1, TIM2_IRQn, 1, Mode_AF_PP, GPIO_PinSource0, GPIO_AF_1, 0}, // PWM1 - { TIM2, GPIOA, Pin_1, TIM_Channel_2, TIM2_IRQn, 1, Mode_AF_PP, GPIO_PinSource1, GPIO_AF_1, 0}, // PWM2 - { TIM15, GPIOA, Pin_2, TIM_Channel_1, TIM1_BRK_TIM15_IRQn, 1, Mode_AF_PP, GPIO_PinSource2, GPIO_AF_9, 0}, // PWM3 - { TIM15, GPIOA, Pin_3, TIM_Channel_2, TIM1_BRK_TIM15_IRQn, 1, Mode_AF_PP, GPIO_PinSource3, GPIO_AF_9, 0}, // PWM4 - { TIM3, GPIOA, Pin_6, TIM_Channel_1, TIM3_IRQn, 1, Mode_AF_PP, GPIO_PinSource6, GPIO_AF_2, 0}, // PWM5 - { TIM3, GPIOA, Pin_7, TIM_Channel_2, TIM3_IRQn, 1, Mode_AF_PP, GPIO_PinSource7, GPIO_AF_2, 0}, // PWM6 - { TIM3, GPIOB, Pin_0, TIM_Channel_3, TIM3_IRQn, 1, Mode_AF_PP, GPIO_PinSource0, GPIO_AF_2, 0}, // PWM7 - { TIM3, GPIOB, Pin_1, TIM_Channel_4, TIM3_IRQn, 1, Mode_AF_PP, GPIO_PinSource1, GPIO_AF_2, 0}, // PWM8 - - // UART3 RX/TX - { TIM2, GPIOB, Pin_10, TIM_Channel_3, TIM2_IRQn, 1, Mode_AF_PP, GPIO_PinSource10, GPIO_AF_1, 0}, // RC_CH4 - PB10 - *TIM2_CH3, USART3_TX (AF7) - { TIM2, GPIOB, Pin_11, TIM_Channel_4, TIM2_IRQn, 1, Mode_AF_PP, GPIO_PinSource11, GPIO_AF_1, 0}, // RC_CH3 - PB11 - *TIM2_CH4, USART3_RX (AF7) - - // IR / LED Strip Pad - { TIM1, GPIOA, Pin_8, TIM_Channel_1, TIM1_CC_IRQn, 1, Mode_AF_PP, GPIO_PinSource8, GPIO_AF_6, 0}, // GPIO_TIMER / LED_STRIP + { TIM8, IO_TAG(PA15), TIM_Channel_1, TIM8_CC_IRQn, 0, IOCFG_AF_PP_PD, GPIO_AF_2, 0}, // PPM + { TIM2, IO_TAG(PA0), TIM_Channel_1, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1, 0}, // PWM1 + { TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1, 0}, // PWM2 + { TIM15, IO_TAG(PA2), TIM_Channel_1, TIM1_BRK_TIM15_IRQn, 1, IOCFG_AF_PP, GPIO_AF_9, 0}, // PWM3 + { TIM15, IO_TAG(PA3), TIM_Channel_2, TIM1_BRK_TIM15_IRQn, 1, IOCFG_AF_PP, GPIO_AF_9, 0}, // PWM4 + { TIM3, IO_TAG(PA6), TIM_Channel_1, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2, 0}, // PWM5 + { TIM3, IO_TAG(PA7), TIM_Channel_2, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2, 0}, // PWM6 + { TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2, 0}, // PWM7 + { TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2, 0}, // PWM8 + { TIM2, IO_TAG(PB10), TIM_Channel_3, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1, 0}, // RC_CH4 - PB10 - *TIM2_CH3, USART3_TX (AF7) + { TIM2, IO_TAG(PB11), TIM_Channel_4, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1, 0}, // RC_CH3 - PB11 - *TIM2_CH4, USART3_RX (AF7) + { TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, 1, IOCFG_AF_PP, GPIO_AF_6, 0}, // GPIO_TIMER / LED_STRIP }; diff --git a/src/main/target/SPRACINGF3MINI/target.c b/src/main/target/SPRACINGF3MINI/target.c index 5ef0c6abb5..daa8bbe8c8 100644 --- a/src/main/target/SPRACINGF3MINI/target.c +++ b/src/main/target/SPRACINGF3MINI/target.c @@ -3,6 +3,7 @@ #include #include +#include "drivers/io.h" #include "drivers/pwm_mapping.h" const uint16_t multiPPM[] = { @@ -67,27 +68,27 @@ const uint16_t airPWM[] = { const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { // PPM Pad #ifdef SPRACINGF3MINI_MKII_REVA - { TIM3, GPIOB, Pin_5, TIM_Channel_2, TIM3_IRQn, 0, Mode_AF_PP, GPIO_PinSource5, GPIO_AF_2, 0}, // PPM - PB5 + { TIM3, IO_TAG(PB5), TIM_Channel_2, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2, 0}, // PPM - PB5 // PB4 / TIM3 CH1 is connected to USBPresent #else - { TIM3, GPIOB, Pin_4, TIM_Channel_1, TIM3_IRQn, 0, Mode_AF_PP, GPIO_PinSource4, GPIO_AF_2, 0}, // PPM - PB4 + { TIM3, IO_TAG(PB4), TIM_Channel_1, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2, 0}, // PPM - PB4 // PB5 / TIM3 CH2 is connected to USBPresent #endif - { TIM16, GPIOA, Pin_6, TIM_Channel_1, TIM1_UP_TIM16_IRQn, 1, Mode_AF_PP, GPIO_PinSource6, GPIO_AF_1, 0}, // PWM1 - PA6 - { TIM17, GPIOA, Pin_7, TIM_Channel_1, TIM1_TRG_COM_TIM17_IRQn, 1, Mode_AF_PP, GPIO_PinSource7, GPIO_AF_1, 0}, // PWM2 - PA7 - { TIM4, GPIOB, Pin_8, TIM_Channel_3, TIM4_IRQn, 1, Mode_AF_PP, GPIO_PinSource8, GPIO_AF_2, 0}, // PWM3 - PB8 - { TIM4, GPIOB, Pin_9, TIM_Channel_4, TIM4_IRQn, 1, Mode_AF_PP, GPIO_PinSource9, GPIO_AF_2, 0}, // PWM4 - PB9 - { TIM15, GPIOA, Pin_2, TIM_Channel_1, TIM1_BRK_TIM15_IRQn, 1, Mode_AF_PP, GPIO_PinSource2, GPIO_AF_9, 0}, // PWM5 - PA2 - { TIM15, GPIOA, Pin_3, TIM_Channel_2, TIM1_BRK_TIM15_IRQn, 1, Mode_AF_PP, GPIO_PinSource3, GPIO_AF_9, 0}, // PWM6 - PA3 - { TIM2, GPIOA, Pin_0, TIM_Channel_1, TIM2_IRQn, 1, Mode_AF_PP, GPIO_PinSource0, GPIO_AF_1, 0}, // PWM7 - PA0 - { TIM2, GPIOA, Pin_1, TIM_Channel_2, TIM2_IRQn, 1, Mode_AF_PP, GPIO_PinSource1, GPIO_AF_1, 0}, // PWM8 - PA1 + { TIM16, IO_TAG(PA6), TIM_Channel_1, TIM1_UP_TIM16_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1, 0}, // PWM1 - PA6 + { TIM17, IO_TAG(PA7), TIM_Channel_1, TIM1_TRG_COM_TIM17_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1, 0}, // PWM2 - PA7 + { TIM4, IO_TAG(PB8), TIM_Channel_3, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2, 0}, // PWM3 - PB8 + { TIM4, IO_TAG(PB9), TIM_Channel_4, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2, 0}, // PWM4 - PB9 + { TIM15, IO_TAG(PA2), TIM_Channel_1, TIM1_BRK_TIM15_IRQn, 1, IOCFG_AF_PP, GPIO_AF_9, 0}, // PWM5 - PA2 + { TIM15, IO_TAG(PA3), TIM_Channel_2, TIM1_BRK_TIM15_IRQn, 1, IOCFG_AF_PP, GPIO_AF_9, 0}, // PWM6 - PA3 + { TIM2, IO_TAG(PA0), TIM_Channel_1, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1, 0}, // PWM7 - PA0 + { TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1, 0}, // PWM8 - PA1 // UART3 RX/TX - { TIM2, GPIOB, Pin_10, TIM_Channel_3, TIM2_IRQn, 1, Mode_AF_PP, GPIO_PinSource10, GPIO_AF_1, 0}, // PWM9 - PB10 - TIM2_CH3 / USART3_TX (AF7) - { TIM2, GPIOB, Pin_11, TIM_Channel_4, TIM2_IRQn, 1, Mode_AF_PP, GPIO_PinSource11, GPIO_AF_1, 0}, // PWM10 - PB11 - TIM2_CH4 / USART3_RX (AF7) + { TIM2, IO_TAG(PB10), TIM_Channel_3, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1, 0}, // PWM9 - PB10 - TIM2_CH3 / USART3_TX (AF7) + { TIM2, IO_TAG(PB11), TIM_Channel_4, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1, 0}, // PWM10 - PB11 - TIM2_CH4 / USART3_RX (AF7) // LED Strip Pad - { TIM1, GPIOA, Pin_8, TIM_Channel_1, TIM1_CC_IRQn, 1, Mode_AF_PP, GPIO_PinSource8, GPIO_AF_6, 0}, // GPIO_TIMER / LED_STRIP + { TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, 1, IOCFG_AF_PP, GPIO_AF_6, 0}, // GPIO_TIMER / LED_STRIP }; diff --git a/src/main/target/STM32F3DISCOVERY/target.c b/src/main/target/STM32F3DISCOVERY/target.c index 8d7f6173b0..1d2e615ead 100644 --- a/src/main/target/STM32F3DISCOVERY/target.c +++ b/src/main/target/STM32F3DISCOVERY/target.c @@ -3,6 +3,7 @@ #include #include +#include "drivers/io.h" #include "drivers/pwm_mapping.h" const uint16_t multiPPM[] = { @@ -72,19 +73,19 @@ const uint16_t airPWM[] = { }; const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { - { TIM1, GPIOA, Pin_8, TIM_Channel_1, TIM1_CC_IRQn, 1, Mode_AF_PP_PD, GPIO_PinSource8, GPIO_AF_6, 0}, // PWM1 - PA8 - { TIM16, GPIOB, Pin_8, TIM_Channel_1, TIM1_UP_TIM16_IRQn, 0, Mode_AF_PP_PD, GPIO_PinSource8, GPIO_AF_1, 0}, // PWM2 - PB8 - { TIM17, GPIOB, Pin_9, TIM_Channel_1, TIM1_TRG_COM_TIM17_IRQn, 0, Mode_AF_PP_PD, GPIO_PinSource9, GPIO_AF_1, 0}, // PWM3 - PB9 - { TIM8, GPIOC, Pin_6, TIM_Channel_1, TIM8_CC_IRQn, 1, Mode_AF_PP_PD, GPIO_PinSource6, GPIO_AF_4, 0}, // PWM4 - PC6 - { TIM8, GPIOC, Pin_7, TIM_Channel_2, TIM8_CC_IRQn, 1, Mode_AF_PP_PD, GPIO_PinSource7, GPIO_AF_4, 0}, // PWM5 - PC7 - { TIM8, GPIOC, Pin_8, TIM_Channel_3, TIM8_CC_IRQn, 1, Mode_AF_PP_PD, GPIO_PinSource8, GPIO_AF_4, 0}, // PWM6 - PC8 - { TIM3, GPIOB, Pin_1, TIM_Channel_4, TIM3_IRQn, 0, Mode_AF_PP_PD, GPIO_PinSource1, GPIO_AF_2, 0}, // PWM7 - PB1 - { TIM3, GPIOA, Pin_4, TIM_Channel_2, TIM3_IRQn, 0, Mode_AF_PP_PD, GPIO_PinSource4, GPIO_AF_2, 0}, // PWM8 - PA2 - { TIM4, GPIOD, Pin_12, TIM_Channel_1, TIM4_IRQn, 0, Mode_AF_PP, GPIO_PinSource12, GPIO_AF_2, 0}, // PWM9 - PD12 - { TIM4, GPIOD, Pin_13, TIM_Channel_2, TIM4_IRQn, 0, Mode_AF_PP, GPIO_PinSource13, GPIO_AF_2, 0}, // PWM10 - PD13 - { TIM4, GPIOD, Pin_14, TIM_Channel_3, TIM4_IRQn, 0, Mode_AF_PP, GPIO_PinSource14, GPIO_AF_2, 0}, // PWM11 - PD14 - { TIM4, GPIOD, Pin_15, TIM_Channel_4, TIM4_IRQn, 0, Mode_AF_PP, GPIO_PinSource15, GPIO_AF_2, 0}, // PWM12 - PD15 - { TIM2, GPIOA, Pin_1, TIM_Channel_2, TIM2_IRQn, 0, Mode_AF_PP, GPIO_PinSource1, GPIO_AF_1, 0}, // PWM13 - PA1 - { TIM2, GPIOA, Pin_2, TIM_Channel_3, TIM2_IRQn, 0, Mode_AF_PP, GPIO_PinSource2, GPIO_AF_1, 0} // PWM14 - PA2 + { TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, 1, IOCFG_AF_PP_PD, GPIO_AF_6, 0}, // PWM1 - PA8 + { TIM16, IO_TAG(PB8), TIM_Channel_1, TIM1_UP_TIM16_IRQn, 0, IOCFG_AF_PP_PD, GPIO_AF_1, 0}, // PWM2 - PB8 + { TIM17, IO_TAG(PB9), TIM_Channel_1, TIM1_TRG_COM_TIM17_IRQn, 0, IOCFG_AF_PP_PD, GPIO_AF_1, 0}, // PWM3 - PB9 + { TIM8, IO_TAG(PC6), TIM_Channel_1, TIM8_CC_IRQn, 1, IOCFG_AF_PP_PD, GPIO_AF_4, 0}, // PWM4 - PC6 + { TIM8, IO_TAG(PC7), TIM_Channel_2, TIM8_CC_IRQn, 1, IOCFG_AF_PP_PD, GPIO_AF_4, 0}, // PWM5 - PC7 + { TIM8, IO_TAG(PC8), TIM_Channel_3, TIM8_CC_IRQn, 1, IOCFG_AF_PP_PD, GPIO_AF_4, 0}, // PWM6 - PC8 + { TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, 0, IOCFG_AF_PP_PD, GPIO_AF_2, 0}, // PWM7 - PB1 + { TIM3, IO_TAG(PA4), TIM_Channel_2, TIM3_IRQn, 0, IOCFG_AF_PP_PD, GPIO_AF_2, 0}, // PWM8 - PA2 + { TIM4, IO_TAG(PD12), TIM_Channel_1, TIM4_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2, 0}, // PWM9 - PD12 + { TIM4, IO_TAG(PD13), TIM_Channel_2, TIM4_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2, 0}, // PWM10 - PD13 + { TIM4, IO_TAG(PD14), TIM_Channel_3, TIM4_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2, 0}, // PWM11 - PD14 + { TIM4, IO_TAG(PD15), TIM_Channel_4, TIM4_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2, 0}, // PWM12 - PD15 + { TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1, 0}, // PWM13 - PA1 + { TIM2, IO_TAG(PA2), TIM_Channel_3, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1, 0} // PWM14 - PA2 }; From 822f57b7f8cb92df6cc072c49cbce12d9bda103c Mon Sep 17 00:00:00 2001 From: blckmn Date: Tue, 14 Jun 2016 19:07:01 +1000 Subject: [PATCH 07/22] Updated for changes in serial_4way --- src/main/io/serial_4way.c | 6 ++++-- 1 file changed, 4 insertions(+), 2 deletions(-) diff --git a/src/main/io/serial_4way.c b/src/main/io/serial_4way.c index d7710cee42..91ed53db4e 100644 --- a/src/main/io/serial_4way.c +++ b/src/main/io/serial_4way.c @@ -26,6 +26,8 @@ #ifdef USE_SERIAL_4WAY_BLHELI_INTERFACE #include "drivers/serial.h" #include "drivers/gpio.h" +#include "drivers/io.h" +#include "drivers/io_impl.h" #include "drivers/timer.h" #include "drivers/pwm_mapping.h" #include "drivers/pwm_output.h" @@ -149,8 +151,8 @@ int esc4wayInit(void) for (volatile uint8_t i = 0; i < pwmOutputConfiguration->outputCount; i++) { if ((pwmOutputConfiguration->portConfigurations[i].flags & PWM_PF_MOTOR) == PWM_PF_MOTOR) { if(motor[pwmOutputConfiguration->portConfigurations[i].index] > 0) { - escHardware[escIdx].gpio = pwmOutputConfiguration->portConfigurations[i].timerHardware->gpio; - escHardware[escIdx].pin = pwmOutputConfiguration->portConfigurations[i].timerHardware->pin; + escHardware[escIdx].gpio = IO_GPIO(IOGetByTag(pwmOutputConfiguration->portConfigurations[i].timerHardware->pin)); + escHardware[escIdx].pin = IO_Pin(IOGetByTag(pwmOutputConfiguration->portConfigurations[i].timerHardware->pin)); escHardware[escIdx].pinpos = getPinPos(escHardware[escIdx].pin); escHardware[escIdx].gpio_config_INPUT.pin = escHardware[escIdx].pin; escHardware[escIdx].gpio_config_INPUT.speed = Speed_2MHz; // see pwmOutConfig() From 9a92cb85600c52f40dc7bb61da02763fe8a3c4b0 Mon Sep 17 00:00:00 2001 From: NightHawk32 Date: Tue, 14 Jun 2016 17:37:01 -0400 Subject: [PATCH 08/22] added PikoBLX target --- fake_travis_build.sh | 1 + src/main/target/PIKOBLX/target.c | 56 ++++++++++ src/main/target/PIKOBLX/target.h | 169 ++++++++++++++++++++++++++++++ src/main/target/PIKOBLX/target.mk | 13 +++ 4 files changed, 239 insertions(+) create mode 100644 src/main/target/PIKOBLX/target.c create mode 100644 src/main/target/PIKOBLX/target.h create mode 100644 src/main/target/PIKOBLX/target.mk diff --git a/fake_travis_build.sh b/fake_travis_build.sh index 7749d64354..29089c24fb 100755 --- a/fake_travis_build.sh +++ b/fake_travis_build.sh @@ -13,6 +13,7 @@ targets=("PUBLISHMETA=True" \ "TARGET=RMDO" \ "TARGET=SPARKY" \ "TARGET=MOTOLAB" \ + "TARGET=PIKOBLX" \ "TARGET=IRCFUSIONF3" \ "TARGET=ALIENFLIGHTF1" \ "TARGET=ALIENFLIGHTF3" \ diff --git a/src/main/target/PIKOBLX/target.c b/src/main/target/PIKOBLX/target.c new file mode 100644 index 0000000000..dab944eaca --- /dev/null +++ b/src/main/target/PIKOBLX/target.c @@ -0,0 +1,56 @@ + +#include +#include + +#include +#include "drivers/pwm_mapping.h" + +const uint16_t multiPPM[] = { + PWM9 | (MAP_TO_PPM_INPUT << 8), // PPM input + + PWM1 | (MAP_TO_MOTOR_OUTPUT << 8), + PWM2 | (MAP_TO_MOTOR_OUTPUT << 8), + PWM3 | (MAP_TO_MOTOR_OUTPUT << 8), + PWM4 | (MAP_TO_MOTOR_OUTPUT << 8), + PWM5 | (MAP_TO_MOTOR_OUTPUT << 8), + PWM6 | (MAP_TO_MOTOR_OUTPUT << 8), + PWM7 | (MAP_TO_MOTOR_OUTPUT << 8), + PWM8 | (MAP_TO_MOTOR_OUTPUT << 8), + 0xFFFF +}; + +const uint16_t multiPWM[] = { + PWM1 | (MAP_TO_MOTOR_OUTPUT << 8), + PWM2 | (MAP_TO_MOTOR_OUTPUT << 8), + PWM3 | (MAP_TO_MOTOR_OUTPUT << 8), + PWM4 | (MAP_TO_MOTOR_OUTPUT << 8), + PWM5 | (MAP_TO_MOTOR_OUTPUT << 8), + PWM6 | (MAP_TO_MOTOR_OUTPUT << 8), + PWM7 | (MAP_TO_MOTOR_OUTPUT << 8), + PWM8 | (MAP_TO_MOTOR_OUTPUT << 8), + 0xFFFF +}; + +const uint16_t airPPM[] = { + // TODO + 0xFFFF +}; + +const uint16_t airPWM[] = { + // TODO + 0xFFFF +}; + +const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { + { TIM3, GPIOA, Pin_4, TIM_Channel_2, TIM3_IRQn, 1, Mode_AF_PP, GPIO_PinSource4, GPIO_AF_2}, // PWM1 - PA4 - *TIM3_CH2 + { TIM3, GPIOA, Pin_6, TIM_Channel_1, TIM3_IRQn, 1, Mode_AF_PP, GPIO_PinSource6, GPIO_AF_2}, // PWM2 - PA6 - *TIM3_CH1, TIM8_BKIN, TIM1_BKIN, TIM16_CH1 + { TIM3, GPIOB, Pin_0, TIM_Channel_3, TIM3_IRQn, 1, Mode_AF_PP, GPIO_PinSource0, GPIO_AF_2}, // PWM3 - PB0 - *TIM3_CH3, TIM1_CH2N, TIM8_CH2N + { TIM3, GPIOB, Pin_1, TIM_Channel_4, TIM3_IRQn, 1, Mode_AF_PP, GPIO_PinSource1, GPIO_AF_2}, // PWM4 - PB1 - *TIM3_CH4, TIM1_CH3N, TIM8_CH3N + { TIM2, GPIOA, Pin_1, TIM_Channel_2, TIM2_IRQn, 1, Mode_AF_PP, GPIO_PinSource1, GPIO_AF_1}, // PWM5 - PA1 - *TIM2_CH2, TIM15_CH1N + { TIM2, GPIOA, Pin_2, TIM_Channel_3, TIM2_IRQn, 1, Mode_AF_PP, GPIO_PinSource2, GPIO_AF_1}, // PWM6 - PA2 - *TIM2_CH3, !TIM15_CH1 + { TIM15, GPIOA, Pin_3, TIM_Channel_2, TIM1_BRK_TIM15_IRQn, 1, Mode_AF_PP, GPIO_PinSource3, GPIO_AF_9}, // PWM7 - PA3 - *TIM15_CH2, TIM2_CH4 + { TIM1, GPIOA, Pin_8, TIM_Channel_1, TIM1_CC_IRQn, 1, Mode_AF_PP, GPIO_PinSource8, GPIO_AF_6}, // PWM8 - PA8 - *TIM1_CH1, TIM4_ETR + + { TIM17, GPIOA, Pin_7, TIM_Channel_1, TIM1_TRG_COM_TIM17_IRQn, 0, Mode_AF_PP_PD, GPIO_PinSource7, GPIO_AF_1}, // PPM - PA7 - *TIM17_CH1, TIM1_CH1N, TIM8_CH1 +}; + diff --git a/src/main/target/PIKOBLX/target.h b/src/main/target/PIKOBLX/target.h new file mode 100644 index 0000000000..4248a58a73 --- /dev/null +++ b/src/main/target/PIKOBLX/target.h @@ -0,0 +1,169 @@ +/* + * This file is part of Cleanflight. + * + * Cleanflight is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * Cleanflight is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with Cleanflight. If not, see . + */ + +#pragma once + +#define TARGET_BOARD_IDENTIFIER "PIKO" // Furious FPV Piko BLX +#define USE_CLI + +#define CONFIG_FASTLOOP_PREFERRED_ACC ACC_DEFAULT + +#define LED0 PB9 +#define LED1 PB5 + +#define BEEPER PA0 +#define BEEPER_INVERTED + +#define USABLE_TIMER_CHANNEL_COUNT 9 + +// MPU6000 interrupts +#define USE_EXTI +#define MPU_INT_EXTI PA15 +#define EXTI15_10_CALLBACK_HANDLER_COUNT 1 // MPU data ready +#define USE_MPU_DATA_READY_SIGNAL + +#define GYRO +#define ACC + +#define USE_GYRO_SPI_MPU6000 +#define GYRO_MPU6000_ALIGN CW180_DEG +#define USE_ACC_SPI_MPU6000 +#define ACC_MPU6000_ALIGN CW180_DEG + +#define MPU6000_CS_GPIO GPIOB +#define MPU6000_CS_PIN PB12 +#define MPU6000_SPI_INSTANCE SPI2 + +#define USE_VCP +#define USE_USART1 +#define USE_USART2 +#define USE_USART3 +#define SERIAL_PORT_COUNT 4 + +#define UART1_TX_PIN GPIO_Pin_6 // PB6 +#define UART1_RX_PIN GPIO_Pin_7 // PB7 +#define UART1_GPIO GPIOB +#define UART1_GPIO_AF GPIO_AF_7 +#define UART1_TX_PINSOURCE GPIO_PinSource6 +#define UART1_RX_PINSOURCE GPIO_PinSource7 + +#define UART2_TX_PIN GPIO_Pin_3 // PB3 +#define UART2_RX_PIN GPIO_Pin_4 // PB4 +#define UART2_GPIO GPIOB +#define UART2_GPIO_AF GPIO_AF_7 +#define UART2_TX_PINSOURCE GPIO_PinSource3 +#define UART2_RX_PINSOURCE GPIO_PinSource4 + +#define UART3_TX_PIN GPIO_Pin_10 // PB10 (AF7) +#define UART3_RX_PIN GPIO_Pin_11 // PB11 (AF7) +#define UART3_GPIO_AF GPIO_AF_7 +#define UART3_GPIO GPIOB +#define UART3_TX_PINSOURCE GPIO_PinSource10 +#define UART3_RX_PINSOURCE GPIO_PinSource11 + +#define USE_SPI +#define USE_SPI_DEVICE_2 + +#define SENSORS_SET (SENSOR_ACC) + +#define TELEMETRY +#define BLACKBOX +#define SERIAL_RX +#define USE_SERVOS + +#define USE_ADC +#define BOARD_HAS_VOLTAGE_DIVIDER + +#define ADC_INSTANCE ADC2 +#define ADC_DMA_CHANNEL DMA2_Channel1 +#define ADC_AHB_PERIPHERAL RCC_AHBPeriph_DMA2 + +#define VBAT_ADC_GPIO GPIOA +#define VBAT_ADC_GPIO_PIN GPIO_Pin_5 +#define VBAT_ADC_CHANNEL ADC_Channel_2 + +#define RSSI_ADC_GPIO GPIOB +#define RSSI_ADC_GPIO_PIN GPIO_Pin_2 +#define RSSI_ADC_CHANNEL ADC_Channel_12 + +#define LED_STRIP +#if 1 +#define LED_STRIP_TIMER TIM16 + +#define USE_LED_STRIP_ON_DMA1_CHANNEL3 +#define WS2811_GPIO GPIOB +#define WS2811_GPIO_AHB_PERIPHERAL RCC_AHBPeriph_GPIOB +#define WS2811_GPIO_AF GPIO_AF_1 +#define WS2811_PIN GPIO_Pin_8 // TIM16_CH1 +#define WS2811_PIN_SOURCE GPIO_PinSource8 +#define WS2811_TIMER TIM16 +#define WS2811_TIMER_APB2_PERIPHERAL RCC_APB2Periph_TIM16 +#define WS2811_DMA_CHANNEL DMA1_Channel3 +#define WS2811_IRQ DMA1_Channel3_IRQn +#define WS2811_DMA_TC_FLAG DMA1_FLAG_TC3 +#define WS2811_DMA_HANDLER_IDENTIFER DMA1_CH3_HANDLER +#endif + +#if 0 +// Alternate LED strip pin +// FIXME DMA IRQ Transfer Complete is never called because the TIM17_DMA_RMP needs to be set in SYSCFG_CFGR1 +#define LED_STRIP_TIMER TIM17 + +#define USE_LED_STRIP_ON_DMA1_CHANNEL7 +#define WS2811_GPIO GPIOA +#define WS2811_GPIO_AHB_PERIPHERAL RCC_AHBPeriph_GPIOA +#define WS2811_GPIO_AF GPIO_AF_1 +#define WS2811_PIN GPIO_Pin_7 // TIM17_CH1 +#define WS2811_PIN_SOURCE GPIO_PinSource7 +#define WS2811_TIMER TIM17 +#define WS2811_TIMER_APB2_PERIPHERAL RCC_APB2Periph_TIM17 +#define WS2811_DMA_CHANNEL DMA1_Channel7 +#define WS2811_IRQ DMA1_Channel7_IRQn +#endif + +#define TRANSPONDER +#define TRANSPONDER_GPIO GPIOA +#define TRANSPONDER_GPIO_AHB_PERIPHERAL RCC_AHBPeriph_GPIOA +#define TRANSPONDER_GPIO_AF GPIO_AF_6 +#define TRANSPONDER_PIN GPIO_Pin_8 +#define TRANSPONDER_PIN_SOURCE GPIO_PinSource8 +#define TRANSPONDER_TIMER TIM1 +#define TRANSPONDER_TIMER_APB2_PERIPHERAL RCC_APB2Periph_TIM1 +#define TRANSPONDER_DMA_CHANNEL DMA1_Channel2 +#define TRANSPONDER_IRQ DMA1_Channel2_IRQn +#define TRANSPONDER_DMA_TC_FLAG DMA1_FLAG_TC2 +#define TRANSPONDER_DMA_HANDLER_IDENTIFER DMA1_CH2_HANDLER + +#define SPEKTRUM_BIND +// USART3, PB11 +#define BIND_PIN PB11 + +#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)) +// !!TODO - check the following line is correct +#define TARGET_IO_PORTF (BIT(0)|BIT(1)|BIT(3)|BIT(4)) + +#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(15) | TIM_N(17)) + +#define TIMER_APB2_PERIPHERALS (RCC_APB2Periph_TIM1 | RCC_APB2Periph_TIM15 | RCC_APB2Periph_TIM17) +#define TIMER_APB1_PERIPHERALS (RCC_APB1Periph_TIM2 | RCC_APB1Periph_TIM3) +#define TIMER_AHB_PERIPHERALS (RCC_AHBPeriph_GPIOA | RCC_AHBPeriph_GPIOB) diff --git a/src/main/target/PIKOBLX/target.mk b/src/main/target/PIKOBLX/target.mk new file mode 100644 index 0000000000..3662ea997a --- /dev/null +++ b/src/main/target/PIKOBLX/target.mk @@ -0,0 +1,13 @@ +F3_TARGETS += $(TARGET) +FEATURES = VCP + +TARGET_SRC = \ + drivers/accgyro_mpu.c \ + drivers/accgyro_spi_mpu6000.c \ + drivers/light_ws2811strip.c \ + drivers/light_ws2811strip_stm32f30x.c \ + drivers/serial_softserial.c \ + drivers/transponder_ir.c \ + drivers/transponder_ir_stm32f30x.c \ + io/transponder_ir.c + From 251b3d7e3c11adc71fe9bfc6ac30c17e8f4b0ae1 Mon Sep 17 00:00:00 2001 From: blckmn Date: Wed, 15 Jun 2016 06:20:03 +1000 Subject: [PATCH 09/22] Moved target specific code out of initialisation.c --- src/main/drivers/io.h | 2 +- src/main/sensors/initialisation.c | 43 ++----------------- .../target/ALIENFLIGHTF3/hardware_revision.c | 21 ++++++++- .../target/ALIENFLIGHTF3/hardware_revision.h | 5 +++ src/main/target/NAZE/hardware_revision.c | 24 +++++++++++ src/main/target/NAZE/hardware_revision.h | 5 +++ 6 files changed, 59 insertions(+), 41 deletions(-) diff --git a/src/main/drivers/io.h b/src/main/drivers/io.h index dfc13aebbb..debc78d950 100644 --- a/src/main/drivers/io.h +++ b/src/main/drivers/io.h @@ -8,7 +8,7 @@ // 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 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 // NONE initializer for IO_t variable diff --git a/src/main/sensors/initialisation.c b/src/main/sensors/initialisation.c index 637ded62b4..25627eb632 100755 --- a/src/main/sensors/initialisation.c +++ b/src/main/sensors/initialisation.c @@ -90,45 +90,10 @@ const extiConfig_t *selectMPUIntExtiConfig(void) return &mpuIntExtiConfig; #endif -#ifdef NAZE - // MPU_INT output on rev4 PB13 - static const extiConfig_t nazeRev4MPUIntExtiConfig = { - .io = IO_TAG(PB13) - }; - // MPU_INT output on rev5 hardware PC13 - static const extiConfig_t nazeRev5MPUIntExtiConfig = { - .io = IO_TAG(PC13) - }; - -#ifdef AFROMINI - return &nazeRev5MPUIntExtiConfig; -#else - if (hardwareRevision < NAZE32_REV5) { - return &nazeRev4MPUIntExtiConfig; - } - else { - return &nazeRev5MPUIntExtiConfig; - } -#endif -#endif - -#ifdef ALIENFLIGHTF3 - // MPU_INT output on V1 PA15 - static const extiConfig_t alienFlightF3V1MPUIntExtiConfig = { - .io = IO_TAG(PA15) - }; - // MPU_INT output on V2 PB13 - static const extiConfig_t alienFlightF3V2MPUIntExtiConfig = { - .io = IO_TAG(PB13) - }; - if (hardwareRevision == AFF3_REV_1) { - return &alienFlightF3V1MPUIntExtiConfig; - } - else { - return &alienFlightF3V2MPUIntExtiConfig; - } -#endif - return NULL; +#ifdef USE_HARDWARE_REVISION_DETECTION + return selectMPUIntExtiConfigByHardwareRevision(); +#else return NULL; +#endif } #ifdef USE_FAKE_GYRO diff --git a/src/main/target/ALIENFLIGHTF3/hardware_revision.c b/src/main/target/ALIENFLIGHTF3/hardware_revision.c index 16a9de5b28..0905b449c5 100644 --- a/src/main/target/ALIENFLIGHTF3/hardware_revision.c +++ b/src/main/target/ALIENFLIGHTF3/hardware_revision.c @@ -24,7 +24,7 @@ #include "drivers/system.h" #include "drivers/io.h" - +#include "drivers/exti.h" #include "hardware_revision.h" static const char * const hardwareRevisionNames[] = { @@ -56,3 +56,22 @@ void detectHardwareRevision(void) void updateHardwareRevision(void) { } + +const extiConfig_t *selectMPUIntExtiConfigByHardwareRevision(void) +{ + // MPU_INT output on V1 PA15 + static const extiConfig_t alienFlightF3V1MPUIntExtiConfig = { + .io = IO_TAG(PA15) + }; + // MPU_INT output on V2 PB13 + static const extiConfig_t alienFlightF3V2MPUIntExtiConfig = { + .io = IO_TAG(PB13) + }; + + if (hardwareRevision == AFF3_REV_1) { + return &alienFlightF3V1MPUIntExtiConfig; + } + else { + return &alienFlightF3V2MPUIntExtiConfig; + } +} \ No newline at end of file diff --git a/src/main/target/ALIENFLIGHTF3/hardware_revision.h b/src/main/target/ALIENFLIGHTF3/hardware_revision.h index f4c0e90952..7e60ddc55f 100644 --- a/src/main/target/ALIENFLIGHTF3/hardware_revision.h +++ b/src/main/target/ALIENFLIGHTF3/hardware_revision.h @@ -14,6 +14,9 @@ * You should have received a copy of the GNU General Public License * along with Cleanflight. If not, see . */ +#pragma once + +#include "drivers/exti.h" typedef enum awf3HardwareRevision_t { UNKNOWN = 0, @@ -25,3 +28,5 @@ extern uint8_t hardwareRevision; void updateHardwareRevision(void); void detectHardwareRevision(void); + +const extiConfig_t *selectMPUIntExtiConfigByHardwareRevision(void); \ No newline at end of file diff --git a/src/main/target/NAZE/hardware_revision.c b/src/main/target/NAZE/hardware_revision.c index dae3698442..d9f540eb9f 100755 --- a/src/main/target/NAZE/hardware_revision.c +++ b/src/main/target/NAZE/hardware_revision.c @@ -26,6 +26,7 @@ #include "drivers/system.h" #include "drivers/bus_spi.h" #include "drivers/sensor.h" +#include "drivers/io.h" #include "drivers/exti.h" #include "drivers/accgyro.h" #include "drivers/accgyro_mpu.h" @@ -109,3 +110,26 @@ void updateHardwareRevision(void) hardwareRevision = NAZE32_SP; #endif } + +const extiConfig_t *selectMPUIntExtiConfigByHardwareRevision(void) +{ + // MPU_INT output on rev4 PB13 + static const extiConfig_t nazeRev4MPUIntExtiConfig = { + .io = IO_TAG(PB13) + }; + // MPU_INT output on rev5 hardware PC13 + static const extiConfig_t nazeRev5MPUIntExtiConfig = { + .io = IO_TAG(PC13) + }; + +#ifdef AFROMINI + return &nazeRev5MPUIntExtiConfig; +#else + if (hardwareRevision < NAZE32_REV5) { + return &nazeRev4MPUIntExtiConfig; + } + else { + return &nazeRev5MPUIntExtiConfig; + } +#endif +} diff --git a/src/main/target/NAZE/hardware_revision.h b/src/main/target/NAZE/hardware_revision.h index 9f663bb6c2..08895620f0 100755 --- a/src/main/target/NAZE/hardware_revision.h +++ b/src/main/target/NAZE/hardware_revision.h @@ -14,6 +14,9 @@ * You should have received a copy of the GNU General Public License * along with Cleanflight. If not, see . */ +#pragma once + +#include "drivers/exti.h" typedef enum nazeHardwareRevision_t { UNKNOWN = 0, @@ -28,3 +31,5 @@ void updateHardwareRevision(void); void detectHardwareRevision(void); void spiBusInit(void); + +const extiConfig_t *selectMPUIntExtiConfigByHardwareRevision(void); From b55f43d4975681604f7b916fbe0ded0bf99093b8 Mon Sep 17 00:00:00 2001 From: blckmn Date: Wed, 15 Jun 2016 08:30:40 +1000 Subject: [PATCH 10/22] No need to specify c files in target directory, these are automatically included by Makefile --- src/main/target/ALIENFLIGHTF3/target.mk | 1 - src/main/target/NAZE/target.mk | 3 +-- 2 files changed, 1 insertion(+), 3 deletions(-) diff --git a/src/main/target/ALIENFLIGHTF3/target.mk b/src/main/target/ALIENFLIGHTF3/target.mk index fc9d28c289..04ba9c48f6 100644 --- a/src/main/target/ALIENFLIGHTF3/target.mk +++ b/src/main/target/ALIENFLIGHTF3/target.mk @@ -8,6 +8,5 @@ TARGET_SRC = \ drivers/accgyro_mpu6500.c \ drivers/accgyro_spi_mpu6500.c \ drivers/compass_ak8963.c \ - hardware_revision.c \ drivers/sonar_hcsr04.c diff --git a/src/main/target/NAZE/target.mk b/src/main/target/NAZE/target.mk index 45d87e4b78..07d81cf447 100644 --- a/src/main/target/NAZE/target.mk +++ b/src/main/target/NAZE/target.mk @@ -17,5 +17,4 @@ TARGET_SRC = \ drivers/compass_hmc5883l.c \ drivers/light_ws2811strip.c \ drivers/light_ws2811strip_stm32f10x.c \ - drivers/sonar_hcsr04.c \ - hardware_revision.c + drivers/sonar_hcsr04.c From b0dd16b3be1234529a3bca70251bdbf6051d4a82 Mon Sep 17 00:00:00 2001 From: blckmn Date: Wed, 15 Jun 2016 13:29:00 +1000 Subject: [PATCH 11/22] Fixed CJMCU build fail --- src/main/sensors/initialisation.c | 7 +++---- src/main/target/CJMCU/hardware_revision.c | 6 ++++++ src/main/target/CJMCU/hardware_revision.h | 5 +++++ 3 files changed, 14 insertions(+), 4 deletions(-) diff --git a/src/main/sensors/initialisation.c b/src/main/sensors/initialisation.c index 25627eb632..e856112948 100755 --- a/src/main/sensors/initialisation.c +++ b/src/main/sensors/initialisation.c @@ -88,11 +88,10 @@ const extiConfig_t *selectMPUIntExtiConfig(void) #if defined(MPU_INT_EXTI) static const extiConfig_t mpuIntExtiConfig = { .io = IO_TAG(MPU_INT_EXTI) }; return &mpuIntExtiConfig; -#endif - -#ifdef USE_HARDWARE_REVISION_DETECTION +#elif defined(USE_HARDWARE_REVISION_DETECTION) return selectMPUIntExtiConfigByHardwareRevision(); -#else return NULL; +#else + return NULL; #endif } diff --git a/src/main/target/CJMCU/hardware_revision.c b/src/main/target/CJMCU/hardware_revision.c index f424ee2aff..29071314b8 100755 --- a/src/main/target/CJMCU/hardware_revision.c +++ b/src/main/target/CJMCU/hardware_revision.c @@ -28,6 +28,7 @@ #include "drivers/sensor.h" #include "drivers/accgyro.h" #include "drivers/accgyro_spi_mpu6500.h" +#include "drivers/exti.h" #include "hardware_revision.h" @@ -51,3 +52,8 @@ void detectHardwareRevision(void) void updateHardwareRevision(void) { } + +const extiConfig_t *selectMPUIntExtiConfigByHardwareRevision(void) +{ + return NULL; +} \ No newline at end of file diff --git a/src/main/target/CJMCU/hardware_revision.h b/src/main/target/CJMCU/hardware_revision.h index 4eee9078fa..4b3c13d674 100755 --- a/src/main/target/CJMCU/hardware_revision.h +++ b/src/main/target/CJMCU/hardware_revision.h @@ -14,7 +14,10 @@ * You should have received a copy of the GNU General Public License * along with Cleanflight. If not, see . */ +#pragma once + #include "drivers/exti.h" + typedef enum cjmcuHardwareRevision_t { UNKNOWN = 0, REV_1, // Blue LED3 @@ -27,3 +30,5 @@ void updateHardwareRevision(void); void detectHardwareRevision(void); void spiBusInit(void); + +const extiConfig_t *selectMPUIntExtiConfigByHardwareRevision(void); \ No newline at end of file From 24142e930c1df1793384db0a0042cedbfe2747ef Mon Sep 17 00:00:00 2001 From: blckmn Date: Wed, 15 Jun 2016 14:49:40 +1000 Subject: [PATCH 12/22] Removed superfluous hardware_revision.c from .mk file for CJMCU --- src/main/target/CJMCU/target.mk | 1 - 1 file changed, 1 deletion(-) diff --git a/src/main/target/CJMCU/target.mk b/src/main/target/CJMCU/target.mk index 5aa48e4f21..69a1ecc9f4 100644 --- a/src/main/target/CJMCU/target.mk +++ b/src/main/target/CJMCU/target.mk @@ -5,7 +5,6 @@ TARGET_SRC = \ drivers/accgyro_mpu.c \ drivers/accgyro_mpu6050.c \ drivers/compass_hmc5883l.c \ - hardware_revision.c \ flight/gtune.c \ blackbox/blackbox.c \ blackbox/blackbox_io.c From 3f9d67030d181802052a122d957ee4fc75b83999 Mon Sep 17 00:00:00 2001 From: NightHawk32 Date: Wed, 15 Jun 2016 02:25:23 -0400 Subject: [PATCH 13/22] convertet to IO_TAG, added ADC for current sensor --- src/main/target/PIKOBLX/target.c | 19 +++++++++---------- src/main/target/PIKOBLX/target.h | 4 ++++ 2 files changed, 13 insertions(+), 10 deletions(-) diff --git a/src/main/target/PIKOBLX/target.c b/src/main/target/PIKOBLX/target.c index dab944eaca..514839eada 100644 --- a/src/main/target/PIKOBLX/target.c +++ b/src/main/target/PIKOBLX/target.c @@ -42,15 +42,14 @@ const uint16_t airPWM[] = { }; const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { - { TIM3, GPIOA, Pin_4, TIM_Channel_2, TIM3_IRQn, 1, Mode_AF_PP, GPIO_PinSource4, GPIO_AF_2}, // PWM1 - PA4 - *TIM3_CH2 - { TIM3, GPIOA, Pin_6, TIM_Channel_1, TIM3_IRQn, 1, Mode_AF_PP, GPIO_PinSource6, GPIO_AF_2}, // PWM2 - PA6 - *TIM3_CH1, TIM8_BKIN, TIM1_BKIN, TIM16_CH1 - { TIM3, GPIOB, Pin_0, TIM_Channel_3, TIM3_IRQn, 1, Mode_AF_PP, GPIO_PinSource0, GPIO_AF_2}, // PWM3 - PB0 - *TIM3_CH3, TIM1_CH2N, TIM8_CH2N - { TIM3, GPIOB, Pin_1, TIM_Channel_4, TIM3_IRQn, 1, Mode_AF_PP, GPIO_PinSource1, GPIO_AF_2}, // PWM4 - PB1 - *TIM3_CH4, TIM1_CH3N, TIM8_CH3N - { TIM2, GPIOA, Pin_1, TIM_Channel_2, TIM2_IRQn, 1, Mode_AF_PP, GPIO_PinSource1, GPIO_AF_1}, // PWM5 - PA1 - *TIM2_CH2, TIM15_CH1N - { TIM2, GPIOA, Pin_2, TIM_Channel_3, TIM2_IRQn, 1, Mode_AF_PP, GPIO_PinSource2, GPIO_AF_1}, // PWM6 - PA2 - *TIM2_CH3, !TIM15_CH1 - { TIM15, GPIOA, Pin_3, TIM_Channel_2, TIM1_BRK_TIM15_IRQn, 1, Mode_AF_PP, GPIO_PinSource3, GPIO_AF_9}, // PWM7 - PA3 - *TIM15_CH2, TIM2_CH4 - { TIM1, GPIOA, Pin_8, TIM_Channel_1, TIM1_CC_IRQn, 1, Mode_AF_PP, GPIO_PinSource8, GPIO_AF_6}, // PWM8 - PA8 - *TIM1_CH1, TIM4_ETR - - { TIM17, GPIOA, Pin_7, TIM_Channel_1, TIM1_TRG_COM_TIM17_IRQn, 0, Mode_AF_PP_PD, GPIO_PinSource7, GPIO_AF_1}, // PPM - PA7 - *TIM17_CH1, TIM1_CH1N, TIM8_CH1 + { TIM3, IO_TAG(PA4), TIM_Channel_2, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2, 0}, // PWM1 - PA4 - *TIM3_CH2 + { TIM3, IO_TAG(PA6), TIM_Channel_1, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2, 0}, // PWM2 - PA6 - *TIM3_CH1, TIM8_BKIN, TIM1_BKIN, TIM16_CH1 + { TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2, 0}, // PWM3 - PB0 - *TIM3_CH3, TIM1_CH2N, TIM8_CH2N + { TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2, 0}, // PWM4 - PB1 - *TIM3_CH4, TIM1_CH3N, TIM8_CH3N + { TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1, 0}, // PWM5 - PA1 - *TIM2_CH2, TIM15_CH1N + { TIM2, IO_TAG(PA2), TIM_Channel_3, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1, 0}, // PWM6 - PA2 - *TIM2_CH3, !TIM15_CH1 + { TIM15, IO_TAG(PA3), TIM_Channel_2, TIM1_BRK_TIM15_IRQn, 1, IOCFG_AF_PP, GPIO_AF_9, 0}, // PWM7 - PA3 - *TIM15_CH2, TIM2_CH4 + { TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, 1, IOCFG_AF_PP, GPIO_AF_6, 0}, // PWM8 - PA8 - *TIM1_CH1, TIM4_ETR + { TIM17, IO_TAG(PA7), TIM_Channel_1, TIM1_TRG_COM_TIM17_IRQn, 0, IOCFG_AF_PP_PD, GPIO_AF_1, 0}, // PPM - PA7 - *TIM17_CH1, TIM1_CH1N, TIM8_CH1 }; diff --git a/src/main/target/PIKOBLX/target.h b/src/main/target/PIKOBLX/target.h index 4248a58a73..b15f0202ec 100644 --- a/src/main/target/PIKOBLX/target.h +++ b/src/main/target/PIKOBLX/target.h @@ -92,6 +92,10 @@ #define ADC_DMA_CHANNEL DMA2_Channel1 #define ADC_AHB_PERIPHERAL RCC_AHBPeriph_DMA2 +#define CURRENT_METER_ADC_GPIO GPIOA +#define CURRENT_METER_ADC_GPIO_PIN GPIO_Pin_2 +#define CURRENT_METER_ADC_CHANNEL ADC_Channel_3 + #define VBAT_ADC_GPIO GPIOA #define VBAT_ADC_GPIO_PIN GPIO_Pin_5 #define VBAT_ADC_CHANNEL ADC_Channel_2 From f0f2941bb67794d19bc40ba272a2b3e6c8017e37 Mon Sep 17 00:00:00 2001 From: Martin Budden Date: Wed, 15 Jun 2016 07:35:17 +0100 Subject: [PATCH 14/22] Moved scheduler into separate directory. Moved task declarations into header file. --- Makefile | 4 +-- src/main/io/display.c | 4 +-- src/main/io/serial_cli.c | 4 +-- src/main/io/serial_msp.c | 3 +- src/main/main.c | 4 +-- src/main/mw.c | 7 ++-- src/main/{ => scheduler}/scheduler.c | 4 ++- src/main/{ => scheduler}/scheduler.h | 0 src/main/{ => scheduler}/scheduler_tasks.c | 25 ++----------- src/main/scheduler/scheduler_tasks.h | 42 ++++++++++++++++++++++ src/main/sensors/barometer.c | 2 -- src/test/unit/scheduler_unittest.cc | 2 +- 12 files changed, 63 insertions(+), 38 deletions(-) rename src/main/{ => scheduler}/scheduler.c (99%) rename src/main/{ => scheduler}/scheduler.h (100%) rename src/main/{ => scheduler}/scheduler_tasks.c (88%) create mode 100644 src/main/scheduler/scheduler_tasks.h diff --git a/Makefile b/Makefile index 53159fa346..c083a61906 100644 --- a/Makefile +++ b/Makefile @@ -363,8 +363,6 @@ COMMON_SRC = \ $(TARGET_DIR_SRC) \ main.c \ mw.c \ - scheduler.c \ - scheduler_tasks.c \ common/encoding.c \ common/filter.c \ common/maths.c \ @@ -414,6 +412,8 @@ COMMON_SRC = \ rx/sumd.c \ rx/sumh.c \ rx/xbus.c \ + scheduler/scheduler.c \ + scheduler/scheduler_tasks.c \ sensors/acceleration.c \ sensors/battery.c \ sensors/boardalignment.c \ diff --git a/src/main/io/display.c b/src/main/io/display.c index ed394d9c95..a61b64f276 100644 --- a/src/main/io/display.c +++ b/src/main/io/display.c @@ -63,9 +63,9 @@ #include "config/runtime_config.h" #include "config/config_profile.h" -#include "display.h" +#include "io/display.h" -#include "scheduler.h" +#include "scheduler/scheduler.h" extern profile_t *currentProfile; diff --git a/src/main/io/serial_cli.c b/src/main/io/serial_cli.c index e057e6f926..68f16d4c12 100644 --- a/src/main/io/serial_cli.c +++ b/src/main/io/serial_cli.c @@ -24,7 +24,6 @@ #include #include "platform.h" -#include "scheduler.h" #include "version.h" #include "debug.h" @@ -91,7 +90,8 @@ #include "common/printf.h" -#include "serial_cli.h" +#include "io/serial_cli.h" +#include "scheduler/scheduler.h" // FIXME remove this for targets that don't need a CLI. Perhaps use a no-op macro when USE_CLI is not enabled // signal that we're in cli mode diff --git a/src/main/io/serial_msp.c b/src/main/io/serial_msp.c index 31756bbe08..df3988e281 100644 --- a/src/main/io/serial_msp.c +++ b/src/main/io/serial_msp.c @@ -24,7 +24,6 @@ #include "build_config.h" #include "debug.h" #include "platform.h" -#include "scheduler.h" #include "common/axis.h" #include "common/color.h" @@ -61,6 +60,8 @@ #include "telemetry/telemetry.h" +#include "scheduler/scheduler.h" + #include "sensors/boardalignment.h" #include "sensors/sensors.h" #include "sensors/battery.h" diff --git a/src/main/main.c b/src/main/main.c index d836deee07..026bcfa178 100644 --- a/src/main/main.c +++ b/src/main/main.c @@ -22,8 +22,6 @@ #include #include "platform.h" -#include "scheduler.h" - #include "common/axis.h" #include "common/color.h" #include "common/maths.h" @@ -77,6 +75,8 @@ #include "io/transponder_ir.h" #include "io/vtx.h" +#include "scheduler/scheduler.h" + #include "sensors/sensors.h" #include "sensors/sonar.h" #include "sensors/barometer.h" diff --git a/src/main/mw.c b/src/main/mw.c index 717dc10e8b..cf70e2ca16 100644 --- a/src/main/mw.c +++ b/src/main/mw.c @@ -21,7 +21,6 @@ #include #include "platform.h" -#include "scheduler.h" #include "debug.h" #include "common/maths.h" @@ -86,6 +85,9 @@ #include "config/config_profile.h" #include "config/config_master.h" +#include "scheduler/scheduler.h" +#include "scheduler/scheduler_tasks.h" + // June 2013 V2.2-dev enum { @@ -839,8 +841,9 @@ void taskUpdateBattery(void) } } -bool taskUpdateRxCheck(void) +bool taskUpdateRxCheck(uint32_t currentDeltaTime) { + UNUSED(currentDeltaTime); updateRx(currentTime); return shouldProcessRx(currentTime); } diff --git a/src/main/scheduler.c b/src/main/scheduler/scheduler.c similarity index 99% rename from src/main/scheduler.c rename to src/main/scheduler/scheduler.c index 7e7b98469b..7fe3fea8ec 100755 --- a/src/main/scheduler.c +++ b/src/main/scheduler/scheduler.c @@ -23,10 +23,12 @@ #include "platform.h" -#include "scheduler.h" #include "debug.h" #include "build_config.h" +#include "scheduler/scheduler.h" +#include "scheduler/scheduler_tasks.h" + #include "common/maths.h" #include "drivers/system.h" diff --git a/src/main/scheduler.h b/src/main/scheduler/scheduler.h similarity index 100% rename from src/main/scheduler.h rename to src/main/scheduler/scheduler.h diff --git a/src/main/scheduler_tasks.c b/src/main/scheduler/scheduler_tasks.c similarity index 88% rename from src/main/scheduler_tasks.c rename to src/main/scheduler/scheduler_tasks.c index c2b949259a..bc66fb6dab 100644 --- a/src/main/scheduler_tasks.c +++ b/src/main/scheduler/scheduler_tasks.c @@ -20,30 +20,9 @@ #include #include -#include "scheduler.h" -void taskSystem(void); -void taskMainPidLoopCheck(void); -void taskUpdateAccelerometer(void); -void taskUpdateAttitude(void); -bool taskUpdateRxCheck(uint32_t currentDeltaTime); -void taskUpdateRxMain(void); -void taskHandleSerial(void); -void taskUpdateBattery(void); -void taskUpdateBeeper(void); -void taskProcessGPS(void); -void taskUpdateCompass(void); -void taskUpdateBaro(void); -void taskUpdateSonar(void); -void taskCalculateAltitude(void); -void taskUpdateDisplay(void); -void taskTelemetry(void); -void taskLedStrip(void); -void taskTransponder(void); -#ifdef USE_BST -void taskBstReadWrite(void); -void taskBstMasterProcess(void); -#endif +#include "scheduler/scheduler.h" +#include "scheduler/scheduler_tasks.h" cfTask_t cfTasks[TASK_COUNT] = { [TASK_SYSTEM] = { diff --git a/src/main/scheduler/scheduler_tasks.h b/src/main/scheduler/scheduler_tasks.h new file mode 100644 index 0000000000..a570afa967 --- /dev/null +++ b/src/main/scheduler/scheduler_tasks.h @@ -0,0 +1,42 @@ +/* + * This file is part of Cleanflight. + * + * Cleanflight is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * Cleanflight is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with Cleanflight. If not, see . + */ + +#pragma once + +void taskSystem(void); +void taskMainPidLoopCheck(void); +void taskUpdateAccelerometer(void); +void taskUpdateAttitude(void); +bool taskUpdateRxCheck(uint32_t currentDeltaTime); +void taskUpdateRxMain(void); +void taskHandleSerial(void); +void taskUpdateBattery(void); +void taskUpdateBeeper(void); +void taskProcessGPS(void); +void taskUpdateCompass(void); +void taskUpdateBaro(void); +void taskUpdateSonar(void); +void taskCalculateAltitude(void); +void taskUpdateDisplay(void); +void taskTelemetry(void); +void taskLedStrip(void); +void taskTransponder(void); +#ifdef USE_BST +void taskBstReadWrite(void); +void taskBstMasterProcess(void); +#endif + diff --git a/src/main/sensors/barometer.c b/src/main/sensors/barometer.c index e4ad51c3a9..2a011d8e2b 100644 --- a/src/main/sensors/barometer.c +++ b/src/main/sensors/barometer.c @@ -20,8 +20,6 @@ #include #include "platform.h" -#include "scheduler.h" - #include "common/maths.h" #include "drivers/barometer.h" diff --git a/src/test/unit/scheduler_unittest.cc b/src/test/unit/scheduler_unittest.cc index 95c21755c8..d998f2f4ec 100644 --- a/src/test/unit/scheduler_unittest.cc +++ b/src/test/unit/scheduler_unittest.cc @@ -19,7 +19,7 @@ extern "C" { #include "platform.h" - #include "scheduler.h" + #include "scheduler/scheduler.h" } #include "unittest_macros.h" From c16d642d66a8a04233f43632aaee57ce303111cb Mon Sep 17 00:00:00 2001 From: blckmn Date: Wed, 15 Jun 2016 22:28:08 +1000 Subject: [PATCH 15/22] Changes to sonar for new IO --- src/main/drivers/pwm_mapping.c | 9 ++- src/main/drivers/pwm_mapping.h | 13 ++-- src/main/drivers/sonar_hcsr04.c | 33 ++++----- src/main/drivers/sonar_hcsr04.h | 4 -- src/main/main.c | 9 ++- src/main/sensors/sonar.c | 75 ++------------------ src/main/target/CC3D/target.h | 3 + src/main/target/EUSTM32F103RC/sonar_config.c | 30 ++++++++ src/main/target/EUSTM32F103RC/target.h | 2 + src/main/target/FURYF3/target.h | 3 + src/main/target/NAZE/sonar_config.c | 30 ++++++++ src/main/target/NAZE/target.h | 1 + src/main/target/OLIMEXINO/target.h | 2 + src/main/target/PORT103R/sonar_config.c | 30 ++++++++ src/main/target/PORT103R/target.h | 2 + src/main/target/RMDO/target.h | 2 + src/main/target/SPARKY/target.h | 3 + src/main/target/SPRACINGF3/target.h | 2 + src/main/target/SPRACINGF3MINI/target.h | 10 +-- 19 files changed, 150 insertions(+), 113 deletions(-) create mode 100644 src/main/target/EUSTM32F103RC/sonar_config.c create mode 100644 src/main/target/NAZE/sonar_config.c create mode 100644 src/main/target/PORT103R/sonar_config.c diff --git a/src/main/drivers/pwm_mapping.c b/src/main/drivers/pwm_mapping.c index e8c6e6b31a..ffba5063b5 100755 --- a/src/main/drivers/pwm_mapping.c +++ b/src/main/drivers/pwm_mapping.c @@ -189,12 +189,11 @@ pwmOutputConfiguration_t *pwmInit(drv_pwm_config_t *init) #endif #ifdef SONAR - if (init->sonarGPIOConfig && + if (init->sonarConfig && ( - CheckGPIOPin(timerHardwarePtr->pin, init->sonarGPIOConfig->gpio, init->sonarGPIOConfig->triggerPin) || - CheckGPIOPin(timerHardwarePtr->pin, init->sonarGPIOConfig->gpio, init->sonarGPIOConfig->echoPin) - ) - ) { + timerHardwarePtr->pin == init->sonarConfig->triggerPin || + timerHardwarePtr->pin == init->sonarConfig->echoPin + )) { continue; } #endif diff --git a/src/main/drivers/pwm_mapping.h b/src/main/drivers/pwm_mapping.h index 0d70fafc58..4c94681bc3 100644 --- a/src/main/drivers/pwm_mapping.h +++ b/src/main/drivers/pwm_mapping.h @@ -16,7 +16,7 @@ */ #pragma once -#include "gpio.h" + #include "timer.h" #define MAX_PWM_MOTORS 12 @@ -42,11 +42,10 @@ #define ONESHOT42_TIMER_MHZ 24 #define ONESHOT125_TIMER_MHZ 8 -typedef struct sonarGPIOConfig_s { - GPIO_TypeDef *gpio; - uint16_t triggerPin; - uint16_t echoPin; -} sonarGPIOConfig_t; +typedef struct sonarIOConfig_s { + ioTag_t triggerPin; + ioTag_t echoPin; +} sonarIOConfig_t; typedef struct drv_pwm_config_s { bool useParallelPWM; @@ -78,7 +77,7 @@ typedef struct drv_pwm_config_s { uint16_t motorPwmRate; uint16_t idlePulse; // PWM value to use when initializing the driver. set this to either PULSE_1MS (regular pwm), // some higher value (used by 3d mode), or 0, for brushed pwm drivers. - sonarGPIOConfig_t *sonarGPIOConfig; + sonarIOConfig_t *sonarConfig; } drv_pwm_config_t; enum { diff --git a/src/main/drivers/sonar_hcsr04.c b/src/main/drivers/sonar_hcsr04.c index a835bfa05b..dbe72acd3f 100644 --- a/src/main/drivers/sonar_hcsr04.c +++ b/src/main/drivers/sonar_hcsr04.c @@ -22,7 +22,6 @@ #include "build_config.h" #include "system.h" -#include "gpio.h" #include "nvic.h" #include "io.h" #include "exti.h" @@ -43,8 +42,9 @@ static uint32_t lastMeasurementAt; static sonarHardware_t const *sonarHardware; extiCallbackRec_t hcsr04_extiCallbackRec; + static IO_t echoIO; -//static IO_t triggerIO; +static IO_t triggerIO; void hcsr04_extiHandler(extiCallbackRec_t* cb) { @@ -52,7 +52,7 @@ void hcsr04_extiHandler(extiCallbackRec_t* cb) uint32_t timing_stop; UNUSED(cb); - if (digitalIn(sonarHardware->echo_gpio, sonarHardware->echo_pin) != 0) { + if (IORead(echoIO) != 0) { timing_start = micros(); } else { @@ -71,32 +71,27 @@ void hcsr04_init(const sonarHardware_t *initialSonarHardware, sonarRange_t *sona sonarRange->detectionConeExtendedDeciDegrees = HCSR04_DETECTION_CONE_EXTENDED_DECIDEGREES; #if !defined(UNIT_TEST) - gpio_config_t gpio; #ifdef STM32F10X // enable AFIO for EXTI support RCC_APB2PeriphClockCmd(RCC_APB2Periph_AFIO, ENABLE); #endif -#ifdef STM32F303xC - RCC_AHBPeriphClockCmd(RCC_AHBPeriph_GPIOB, ENABLE); - +#if defined(STM32F3) || defined(STM32F4) /* Enable SYSCFG clock otherwise the EXTI irq handlers are not called */ RCC_APB2PeriphClockCmd(RCC_APB2Periph_SYSCFG, ENABLE); #endif // trigger pin - gpio.pin = sonarHardware->trigger_pin; - gpio.mode = Mode_Out_PP; - gpio.speed = Speed_2MHz; - gpioInit(sonarHardware->trigger_gpio, &gpio); - - // echo pin - gpio.pin = sonarHardware->echo_pin; - gpio.mode = Mode_IN_FLOATING; - gpioInit(sonarHardware->echo_gpio, &gpio); + triggerIO = IOGetByTag(sonarHardware->triggerIO); + IOInit(triggerIO, OWNER_SONAR, RESOURCE_INPUT); + IOConfigGPIO(triggerIO, IOCFG_OUT_PP); - echoIO = IOGetByTag(sonarHardware->echoIO); + // echo pin + echoIO = IOGetByTag(sonarHardware->echoIO); + IOInit(echoIO, OWNER_SONAR, RESOURCE_INPUT); + IOConfigGPIO(echoIO, IOCFG_IN_FLOATING); + #ifdef USE_EXTI EXTIHandlerInit(&hcsr04_extiCallbackRec, hcsr04_extiHandler); EXTIConfig(echoIO, &hcsr04_extiCallbackRec, NVIC_PRIO_SONAR_EXTI, EXTI_Trigger_Rising_Falling); // TODO - priority! @@ -123,10 +118,10 @@ void hcsr04_start_reading(void) lastMeasurementAt = now; - digitalHi(sonarHardware->trigger_gpio, sonarHardware->trigger_pin); + IOHi(triggerIO); // The width of trig signal must be greater than 10us delayMicroseconds(11); - digitalLo(sonarHardware->trigger_gpio, sonarHardware->trigger_pin); + IOLo(triggerIO); #endif } diff --git a/src/main/drivers/sonar_hcsr04.h b/src/main/drivers/sonar_hcsr04.h index 99c89a4c8c..311fa233f5 100644 --- a/src/main/drivers/sonar_hcsr04.h +++ b/src/main/drivers/sonar_hcsr04.h @@ -21,10 +21,6 @@ #include "io.h" typedef struct sonarHardware_s { - uint16_t trigger_pin; - GPIO_TypeDef* trigger_gpio; - uint16_t echo_pin; - GPIO_TypeDef* echo_gpio; ioTag_t triggerIO; ioTag_t echoIO; } sonarHardware_t; diff --git a/src/main/main.c b/src/main/main.c index d836deee07..a964b6182f 100644 --- a/src/main/main.c +++ b/src/main/main.c @@ -265,12 +265,11 @@ void init(void) if (feature(FEATURE_SONAR)) { sonarHardware = sonarGetHardwareConfiguration(&masterConfig.batteryConfig); - sonarGPIOConfig_t sonarGPIOConfig = { - .gpio = SONAR_GPIO, - .triggerPin = sonarHardware->echo_pin, - .echoPin = sonarHardware->trigger_pin, + sonarIOConfig_t sonarConfig = { + .triggerPin = sonarHardware->triggerIO, + .echoPin = sonarHardware->echoIO }; - pwm_params.sonarGPIOConfig = &sonarGPIOConfig; + pwm_params.sonarConfig = &sonarConfig; } #endif diff --git a/src/main/sensors/sonar.c b/src/main/sensors/sonar.c index 6a55389b8f..5225747f37 100644 --- a/src/main/sensors/sonar.c +++ b/src/main/sensors/sonar.c @@ -26,7 +26,7 @@ #include "common/axis.h" #include "drivers/sonar_hcsr04.h" -#include "drivers/gpio.h" +#include "drivers/io.h" #include "config/runtime_config.h" #include "config/config.h" @@ -48,77 +48,14 @@ float sonarMaxTiltCos; static int32_t calculatedAltitude; +#ifndef SONAR_CUSTOM_CONFIG const sonarHardware_t *sonarGetHardwareConfiguration(batteryConfig_t *batteryConfig) { -#if defined(NAZE) || defined(EUSTM32F103RC) || defined(PORT103R) - static const sonarHardware_t const sonarPWM56 = { - .trigger_pin = Pin_8, // PWM5 (PB8) - 5v tolerant - .trigger_gpio = GPIOB, - .echo_pin = Pin_9, // PWM6 (PB9) - 5v tolerant - .echo_gpio = GPIOB, - .triggerIO = IO_TAG(PB8), - .echoIO = IO_TAG(PB9), - }; - static const sonarHardware_t sonarRC78 = { - .trigger_pin = Pin_0, // RX7 (PB0) - only 3.3v ( add a 1K Ohms resistor ) - .trigger_gpio = GPIOB, - .echo_pin = Pin_1, // RX8 (PB1) - only 3.3v ( add a 1K Ohms resistor ) - .echo_gpio = GPIOB, - .triggerIO = IO_TAG(PB0), - .echoIO = IO_TAG(PB1), - }; - // If we are using softserial, parallel PWM or ADC current sensor, then use motor pins 5 and 6 for sonar, otherwise use rc pins 7 and 8 - if (feature(FEATURE_SOFTSERIAL) - || feature(FEATURE_RX_PARALLEL_PWM ) - || (feature(FEATURE_CURRENT_METER) && batteryConfig->currentMeterType == CURRENT_SENSOR_ADC)) { - return &sonarPWM56; - } else { - return &sonarRC78; - } -#elif defined(OLIMEXINO) +#if defined(SONAR_TRIGGER_PIN) && defined(SONAR_ECHO_PIN) UNUSED(batteryConfig); static const sonarHardware_t const sonarHardware = { - .trigger_pin = Pin_0, // RX7 (PB0) - only 3.3v ( add a 1K Ohms resistor ) - .trigger_gpio = GPIOB, - .echo_pin = Pin_1, // RX8 (PB1) - only 3.3v ( add a 1K Ohms resistor ) - .echo_gpio = GPIOB, - .triggerIO = IO_TAG(PB0), - .echoIO = IO_TAG(PB1), - }; - return &sonarHardware; -#elif defined(CC3D) - UNUSED(batteryConfig); - static const sonarHardware_t const sonarHardware = { - .trigger_pin = Pin_5, // (PB5) - .trigger_gpio = GPIOB, - .echo_pin = Pin_0, // (PB0) - only 3.3v ( add a 1K Ohms resistor ) - .echo_gpio = GPIOB, - .triggerIO = IO_TAG(PB5), - .echoIO = IO_TAG(PB0), - }; - return &sonarHardware; - -// TODO - move sonar pin selection to CLI -#elif defined(SPRACINGF3) || defined(SPRACINGF3MINI) || defined(FURYF3) || defined(RMDO) - UNUSED(batteryConfig); - static const sonarHardware_t const sonarHardware = { - .trigger_pin = Pin_0, // RC_CH7 (PB0) - only 3.3v ( add a 1K Ohms resistor ) - .trigger_gpio = GPIOB, - .echo_pin = Pin_1, // RC_CH8 (PB1) - only 3.3v ( add a 1K Ohms resistor ) - .echo_gpio = GPIOB, - .triggerIO = IO_TAG(PB0), - .echoIO = IO_TAG(PB1), - }; - return &sonarHardware; -#elif defined(SPARKY) - UNUSED(batteryConfig); - static const sonarHardware_t const sonarHardware = { - .trigger_pin = Pin_2, // PWM6 (PA2) - only 3.3v ( add a 1K Ohms resistor ) - .trigger_gpio = GPIOA, - .echo_pin = Pin_1, // PWM7 (PB1) - only 3.3v ( add a 1K Ohms resistor ) - .echo_gpio = GPIOB, - .triggerIO = IO_TAG(PA2), - .echoIO = IO_TAG(PB1), + .triggerIO = IO_TAG(SONAR_TRIGGER_PIN), + .echoIO = IO_TAG(SONAR_ECHO_PIN), }; return &sonarHardware; #elif defined(UNIT_TEST) @@ -128,7 +65,7 @@ const sonarHardware_t *sonarGetHardwareConfiguration(batteryConfig_t *batteryCon #error Sonar not defined for target #endif } - +#endif void sonarInit(const sonarHardware_t *sonarHardware) { sonarRange_t sonarRange; diff --git a/src/main/target/CC3D/target.h b/src/main/target/CC3D/target.h index 708d4547a0..dc39a80c52 100644 --- a/src/main/target/CC3D/target.h +++ b/src/main/target/CC3D/target.h @@ -118,6 +118,9 @@ #define DISPLAY #define SONAR +#define SONAR_ECHO_PIN PB0 +#define SONAR_TRIGGER_PIN PB5 + #undef GPS #undef BARO diff --git a/src/main/target/EUSTM32F103RC/sonar_config.c b/src/main/target/EUSTM32F103RC/sonar_config.c new file mode 100644 index 0000000000..c563fa9f93 --- /dev/null +++ b/src/main/target/EUSTM32F103RC/sonar_config.c @@ -0,0 +1,30 @@ + +#include "drivers/sonar_hcsr04.h" +#include "drivers/io.h" +#include "config/runtime_config.h" +#include "config/config.h" + +#include "sensors/battery.h" +#include "sensors/sonar.h" + +#ifdef SONAR_CUSTOM_CONFIG +const sonarHardware_t *sonarGetHardwareConfiguration(batteryConfig_t *batteryConfig) +{ + static const sonarHardware_t const sonarPWM56 = { + .triggerIO = IO_TAG(PB8), + .echoIO = IO_TAG(PB9), + }; + static const sonarHardware_t sonarRC78 = { + .triggerIO = IO_TAG(PB0), + .echoIO = IO_TAG(PB1), + }; + // If we are using softserial, parallel PWM or ADC current sensor, then use motor pins 5 and 6 for sonar, otherwise use rc pins 7 and 8 + if (feature(FEATURE_SOFTSERIAL) + || feature(FEATURE_RX_PARALLEL_PWM ) + || (feature(FEATURE_CURRENT_METER) && batteryConfig->currentMeterType == CURRENT_SENSOR_ADC)) { + return &sonarPWM56; + } else { + return &sonarRC78; + } +} +#endif \ No newline at end of file diff --git a/src/main/target/EUSTM32F103RC/target.h b/src/main/target/EUSTM32F103RC/target.h index ef7534c663..83fe60e92d 100644 --- a/src/main/target/EUSTM32F103RC/target.h +++ b/src/main/target/EUSTM32F103RC/target.h @@ -69,6 +69,8 @@ #define MAG_AK8975_ALIGN CW180_DEG_FLIP #define SONAR +#define SONAR_CUSTOM_CONFIG + #define DISPLAY #define USE_USART1 diff --git a/src/main/target/FURYF3/target.h b/src/main/target/FURYF3/target.h index fb4b899ea2..c68ce2c085 100644 --- a/src/main/target/FURYF3/target.h +++ b/src/main/target/FURYF3/target.h @@ -184,6 +184,9 @@ #define WS2811_DMA_HANDLER_IDENTIFER DMA1_CH2_HANDLER #define SONAR +#define SONAR_ECHO_PIN PB1 +#define SONAR_TRIGGER_PIN PB0 + #define DEFAULT_RX_FEATURE FEATURE_RX_PPM #define DEFAULT_FEATURES FEATURE_BLACKBOX diff --git a/src/main/target/NAZE/sonar_config.c b/src/main/target/NAZE/sonar_config.c new file mode 100644 index 0000000000..c563fa9f93 --- /dev/null +++ b/src/main/target/NAZE/sonar_config.c @@ -0,0 +1,30 @@ + +#include "drivers/sonar_hcsr04.h" +#include "drivers/io.h" +#include "config/runtime_config.h" +#include "config/config.h" + +#include "sensors/battery.h" +#include "sensors/sonar.h" + +#ifdef SONAR_CUSTOM_CONFIG +const sonarHardware_t *sonarGetHardwareConfiguration(batteryConfig_t *batteryConfig) +{ + static const sonarHardware_t const sonarPWM56 = { + .triggerIO = IO_TAG(PB8), + .echoIO = IO_TAG(PB9), + }; + static const sonarHardware_t sonarRC78 = { + .triggerIO = IO_TAG(PB0), + .echoIO = IO_TAG(PB1), + }; + // If we are using softserial, parallel PWM or ADC current sensor, then use motor pins 5 and 6 for sonar, otherwise use rc pins 7 and 8 + if (feature(FEATURE_SOFTSERIAL) + || feature(FEATURE_RX_PARALLEL_PWM ) + || (feature(FEATURE_CURRENT_METER) && batteryConfig->currentMeterType == CURRENT_SENSOR_ADC)) { + return &sonarPWM56; + } else { + return &sonarRC78; + } +} +#endif \ No newline at end of file diff --git a/src/main/target/NAZE/target.h b/src/main/target/NAZE/target.h index ffabc5e584..d447ffe1f9 100644 --- a/src/main/target/NAZE/target.h +++ b/src/main/target/NAZE/target.h @@ -108,6 +108,7 @@ #define MAG_HMC5883_ALIGN CW180_DEG #define SONAR +#define SONAR_CUSTOM_CONFIG #define DISPLAY #define USE_USART1 diff --git a/src/main/target/OLIMEXINO/target.h b/src/main/target/OLIMEXINO/target.h index 86a4304723..c50c1d51fc 100644 --- a/src/main/target/OLIMEXINO/target.h +++ b/src/main/target/OLIMEXINO/target.h @@ -59,6 +59,8 @@ #define USE_MAG_HMC5883 #define SONAR +#define SONAR_ECHO_PIN PB1 +#define SONAR_TRIGGER_PIN PB0 #define USE_USART1 #define USE_USART2 diff --git a/src/main/target/PORT103R/sonar_config.c b/src/main/target/PORT103R/sonar_config.c new file mode 100644 index 0000000000..c563fa9f93 --- /dev/null +++ b/src/main/target/PORT103R/sonar_config.c @@ -0,0 +1,30 @@ + +#include "drivers/sonar_hcsr04.h" +#include "drivers/io.h" +#include "config/runtime_config.h" +#include "config/config.h" + +#include "sensors/battery.h" +#include "sensors/sonar.h" + +#ifdef SONAR_CUSTOM_CONFIG +const sonarHardware_t *sonarGetHardwareConfiguration(batteryConfig_t *batteryConfig) +{ + static const sonarHardware_t const sonarPWM56 = { + .triggerIO = IO_TAG(PB8), + .echoIO = IO_TAG(PB9), + }; + static const sonarHardware_t sonarRC78 = { + .triggerIO = IO_TAG(PB0), + .echoIO = IO_TAG(PB1), + }; + // If we are using softserial, parallel PWM or ADC current sensor, then use motor pins 5 and 6 for sonar, otherwise use rc pins 7 and 8 + if (feature(FEATURE_SOFTSERIAL) + || feature(FEATURE_RX_PARALLEL_PWM ) + || (feature(FEATURE_CURRENT_METER) && batteryConfig->currentMeterType == CURRENT_SENSOR_ADC)) { + return &sonarPWM56; + } else { + return &sonarRC78; + } +} +#endif \ No newline at end of file diff --git a/src/main/target/PORT103R/target.h b/src/main/target/PORT103R/target.h index c0dfc4aa33..1cf06398cb 100644 --- a/src/main/target/PORT103R/target.h +++ b/src/main/target/PORT103R/target.h @@ -87,6 +87,8 @@ #define USE_FLASH_M25P16 #define SONAR +#define SONAR_CUSTOM_CONFIG + #define DISPLAY #define USE_USART1 diff --git a/src/main/target/RMDO/target.h b/src/main/target/RMDO/target.h index 09a3497eaa..24234ea27b 100644 --- a/src/main/target/RMDO/target.h +++ b/src/main/target/RMDO/target.h @@ -52,6 +52,8 @@ #define USE_FLASH_M25P16 #define SONAR +#define SONAR_ECHO_PIN PB1 +#define SONAR_TRIGGER_PIN PB0 #define USE_USART1 #define USE_USART2 diff --git a/src/main/target/SPARKY/target.h b/src/main/target/SPARKY/target.h index 7e3e2ed9dd..32b783d64e 100644 --- a/src/main/target/SPARKY/target.h +++ b/src/main/target/SPARKY/target.h @@ -156,6 +156,9 @@ // USART2, PA3 #define BIND_PIN PA3 +//#define SONAR +//#define SONAR_ECHO_PIN PB1 +//#define SONAR_TRIGGER_PIN PA2 // 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)) diff --git a/src/main/target/SPRACINGF3/target.h b/src/main/target/SPRACINGF3/target.h index c041b54d92..52263deb8b 100644 --- a/src/main/target/SPRACINGF3/target.h +++ b/src/main/target/SPRACINGF3/target.h @@ -61,6 +61,8 @@ #define USE_FLASH_M25P16 #define SONAR +#define SONAR_ECHO_PIN PB1 +#define SONAR_TRIGGER_PIN PB0 #define USE_USART1 #define USE_USART2 diff --git a/src/main/target/SPRACINGF3MINI/target.h b/src/main/target/SPRACINGF3MINI/target.h index 5272a49030..6063abd97d 100644 --- a/src/main/target/SPRACINGF3MINI/target.h +++ b/src/main/target/SPRACINGF3MINI/target.h @@ -24,9 +24,9 @@ // early prototype had slightly different pin mappings. //#define SPRACINGF3MINI_MKII_REVA -#define LED0 PB3 +#define LED0 PB3 -#define BEEPER PC15 +#define BEEPER PC15 #define BEEPER_INVERTED #define USABLE_TIMER_CHANNEL_COUNT 12 // 8 Outputs; PPM; LED Strip; 2 additional PWM pins also on UART3 RX/TX pins. @@ -50,7 +50,7 @@ //#define USE_FAKE_ACC #define USE_ACC_MPU6500 -#define ACC_MPU6500_ALIGN CW180_DEG +#define ACC_MPU6500_ALIGN CW180_DEG #define GYRO_MPU6500_ALIGN CW180_DEG #define BARO @@ -64,11 +64,13 @@ #define MAG_AK8975_ALIGN CW90_DEG_FLIP #define SONAR +#define SONAR_ECHO_PIN PB1 +#define SONAR_TRIGGER_PIN PB0 #define USB_IO #define USB_CABLE_DETECTION -#define USB_DETECT_PIN PB5 +#define USB_DETECT_PIN PB5 #define USE_VCP #define USE_USART1 From e18aeb8dc2771ffd121be405e6dd49215a1aa8ae Mon Sep 17 00:00:00 2001 From: blckmn Date: Wed, 15 Jun 2016 22:29:09 +1000 Subject: [PATCH 16/22] Whitespace --- src/main/main.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/main/main.c b/src/main/main.c index a964b6182f..0df3685bac 100644 --- a/src/main/main.c +++ b/src/main/main.c @@ -269,7 +269,7 @@ void init(void) .triggerPin = sonarHardware->triggerIO, .echoPin = sonarHardware->echoIO }; - pwm_params.sonarConfig = &sonarConfig; + pwm_params.sonarConfig = &sonarConfig; } #endif From 7910ae5c7baa79b2702938331d52686f82e02f1c Mon Sep 17 00:00:00 2001 From: Michael Keller Date: Thu, 16 Jun 2016 10:38:35 +1200 Subject: [PATCH 17/22] Re-added support for the AFROMINI target. --- src/main/main.c | 4 ---- src/main/target/NAZE/AFROMINI.mk | 1 + src/main/target/NAZE/target.h | 3 +++ 3 files changed, 4 insertions(+), 4 deletions(-) create mode 100644 src/main/target/NAZE/AFROMINI.mk diff --git a/src/main/main.c b/src/main/main.c index d836deee07..8a7b661d91 100644 --- a/src/main/main.c +++ b/src/main/main.c @@ -352,10 +352,6 @@ void init(void) .isInverted = false #endif }; -#ifdef AFROMINI - beeperConfig.isOD = true; - beeperConfig.isInverted = true; -#endif #ifdef NAZE if (hardwareRevision >= NAZE32_REV5) { // naze rev4 and below used opendrain to PNP for buzzer. Rev5 and above use PP to NPN. diff --git a/src/main/target/NAZE/AFROMINI.mk b/src/main/target/NAZE/AFROMINI.mk new file mode 100644 index 0000000000..0f11de8fe6 --- /dev/null +++ b/src/main/target/NAZE/AFROMINI.mk @@ -0,0 +1 @@ +# AFROMINI is a VARIANT of NAZE being recognized as rev4, but needs to use rev5 diff --git a/src/main/target/NAZE/target.h b/src/main/target/NAZE/target.h index ffabc5e584..765153f4f1 100644 --- a/src/main/target/NAZE/target.h +++ b/src/main/target/NAZE/target.h @@ -26,6 +26,9 @@ #define LED1 PB4 // PB4 (LED) #define BEEPER PA12 // PA12 (Beeper) +#ifdef AFROMINI +#define BEEPER_INVERTED +#endif #define BARO_XCLR_PIN PC13 #define BARO_EOC_PIN PC14 From cd25f0fa968daa4969df7173381cce7308f8ef4b Mon Sep 17 00:00:00 2001 From: blckmn Date: Thu, 16 Jun 2016 16:35:00 +1000 Subject: [PATCH 18/22] Updated as per code review from @martinbudden --- src/main/sensors/sonar.c | 9 +++++++-- src/main/target/EUSTM32F103RC/sonar_config.c | 14 ++++++-------- src/main/target/NAZE/sonar_config.c | 4 +--- src/main/target/PORT103R/sonar_config.c | 14 ++++++-------- 4 files changed, 20 insertions(+), 21 deletions(-) diff --git a/src/main/sensors/sonar.c b/src/main/sensors/sonar.c index 5225747f37..73859f3917 100644 --- a/src/main/sensors/sonar.c +++ b/src/main/sensors/sonar.c @@ -48,7 +48,10 @@ float sonarMaxTiltCos; static int32_t calculatedAltitude; -#ifndef SONAR_CUSTOM_CONFIG +#ifdef SONAR_CUSTOM_CONFIG +const sonarHardware_t *sonarGetTargetHardwareConfiguration(batteryConfig_t *batteryConfig); +#endif + const sonarHardware_t *sonarGetHardwareConfiguration(batteryConfig_t *batteryConfig) { #if defined(SONAR_TRIGGER_PIN) && defined(SONAR_ECHO_PIN) @@ -58,6 +61,8 @@ const sonarHardware_t *sonarGetHardwareConfiguration(batteryConfig_t *batteryCon .echoIO = IO_TAG(SONAR_ECHO_PIN), }; return &sonarHardware; +#elif defined(SONAR_CUSTOM_CONFIG) + return sonarGetTargetHardwareConfiguration(batteryConfig); #elif defined(UNIT_TEST) UNUSED(batteryConfig); return 0; @@ -65,7 +70,7 @@ const sonarHardware_t *sonarGetHardwareConfiguration(batteryConfig_t *batteryCon #error Sonar not defined for target #endif } -#endif + void sonarInit(const sonarHardware_t *sonarHardware) { sonarRange_t sonarRange; diff --git a/src/main/target/EUSTM32F103RC/sonar_config.c b/src/main/target/EUSTM32F103RC/sonar_config.c index c563fa9f93..e2f4fb7b19 100644 --- a/src/main/target/EUSTM32F103RC/sonar_config.c +++ b/src/main/target/EUSTM32F103RC/sonar_config.c @@ -7,16 +7,15 @@ #include "sensors/battery.h" #include "sensors/sonar.h" -#ifdef SONAR_CUSTOM_CONFIG -const sonarHardware_t *sonarGetHardwareConfiguration(batteryConfig_t *batteryConfig) +const sonarHardware_t *sonarGetTargetHardwareConfiguration(batteryConfig_t *batteryConfig) { static const sonarHardware_t const sonarPWM56 = { - .triggerIO = IO_TAG(PB8), - .echoIO = IO_TAG(PB9), + .triggerIO = IO_TAG(PB8), + .echoIO = IO_TAG(PB9), }; static const sonarHardware_t sonarRC78 = { - .triggerIO = IO_TAG(PB0), - .echoIO = IO_TAG(PB1), + .triggerIO = IO_TAG(PB0), + .echoIO = IO_TAG(PB1), }; // If we are using softserial, parallel PWM or ADC current sensor, then use motor pins 5 and 6 for sonar, otherwise use rc pins 7 and 8 if (feature(FEATURE_SOFTSERIAL) @@ -26,5 +25,4 @@ const sonarHardware_t *sonarGetHardwareConfiguration(batteryConfig_t *batteryCon } else { return &sonarRC78; } -} -#endif \ No newline at end of file +} \ No newline at end of file diff --git a/src/main/target/NAZE/sonar_config.c b/src/main/target/NAZE/sonar_config.c index c563fa9f93..3362146c0d 100644 --- a/src/main/target/NAZE/sonar_config.c +++ b/src/main/target/NAZE/sonar_config.c @@ -7,8 +7,7 @@ #include "sensors/battery.h" #include "sensors/sonar.h" -#ifdef SONAR_CUSTOM_CONFIG -const sonarHardware_t *sonarGetHardwareConfiguration(batteryConfig_t *batteryConfig) +const sonarHardware_t *sonarGetTargetHardwareConfiguration(batteryConfig_t *batteryConfig) { static const sonarHardware_t const sonarPWM56 = { .triggerIO = IO_TAG(PB8), @@ -27,4 +26,3 @@ const sonarHardware_t *sonarGetHardwareConfiguration(batteryConfig_t *batteryCon return &sonarRC78; } } -#endif \ No newline at end of file diff --git a/src/main/target/PORT103R/sonar_config.c b/src/main/target/PORT103R/sonar_config.c index c563fa9f93..e2f4fb7b19 100644 --- a/src/main/target/PORT103R/sonar_config.c +++ b/src/main/target/PORT103R/sonar_config.c @@ -7,16 +7,15 @@ #include "sensors/battery.h" #include "sensors/sonar.h" -#ifdef SONAR_CUSTOM_CONFIG -const sonarHardware_t *sonarGetHardwareConfiguration(batteryConfig_t *batteryConfig) +const sonarHardware_t *sonarGetTargetHardwareConfiguration(batteryConfig_t *batteryConfig) { static const sonarHardware_t const sonarPWM56 = { - .triggerIO = IO_TAG(PB8), - .echoIO = IO_TAG(PB9), + .triggerIO = IO_TAG(PB8), + .echoIO = IO_TAG(PB9), }; static const sonarHardware_t sonarRC78 = { - .triggerIO = IO_TAG(PB0), - .echoIO = IO_TAG(PB1), + .triggerIO = IO_TAG(PB0), + .echoIO = IO_TAG(PB1), }; // If we are using softserial, parallel PWM or ADC current sensor, then use motor pins 5 and 6 for sonar, otherwise use rc pins 7 and 8 if (feature(FEATURE_SOFTSERIAL) @@ -26,5 +25,4 @@ const sonarHardware_t *sonarGetHardwareConfiguration(batteryConfig_t *batteryCon } else { return &sonarRC78; } -} -#endif \ No newline at end of file +} \ No newline at end of file From 74ec4a033717ec54faf72030c07d7e01731a5a01 Mon Sep 17 00:00:00 2001 From: Evgeny Sychov Date: Wed, 15 Jun 2016 23:54:31 -0700 Subject: [PATCH 19/22] Fix constatnt names, move vtx_channel config variable out of OSD ifdef --- src/main/config/config_master.h | 5 ++++- src/main/drivers/max7456.c | 10 +++++----- 2 files changed, 9 insertions(+), 6 deletions(-) diff --git a/src/main/config/config_master.h b/src/main/config/config_master.h index 6d1c943179..6adb9d48d7 100644 --- a/src/main/config/config_master.h +++ b/src/main/config/config_master.h @@ -125,8 +125,11 @@ typedef struct master_t { uint8_t transponderData[6]; #endif -#ifdef OSD +#ifdef USE_RTC6705 uint8_t vtx_channel; +#endif + +#ifdef OSD osd_profile osdProfile; #endif diff --git a/src/main/drivers/max7456.c b/src/main/drivers/max7456.c index 57874fbf31..ec161138d8 100644 --- a/src/main/drivers/max7456.c +++ b/src/main/drivers/max7456.c @@ -35,14 +35,14 @@ #define ENABLE_MAX7456 GPIO_ResetBits(MAX7456_CS_GPIO, MAX7456_CS_PIN) /** PAL or NTSC, value is number of chars total */ -#define VIDEO_MODE_PIXELS_NTSC 390 -#define VIDEO_MODE_PIXELS_PAL 480 +#define VIDEO_BUFFER_CHARS_NTSC 390 +#define VIDEO_BUFFER_CHARS_PAL 480 uint16_t max_screen_size; uint8_t video_signal_type = 0; uint8_t max7456_lock = 0; -char screen[VIDEO_MODE_PIXELS_PAL]; +char screen[VIDEO_BUFFER_CHARS_PAL]; uint8_t max7456_send(uint8_t add, uint8_t data) { @@ -85,10 +85,10 @@ void max7456_init(uint8_t system) { } if (video_signal_type) { //PAL - max_screen_size = VIDEO_MODE_PIXELS_PAL; + max_screen_size = VIDEO_BUFFER_CHARS_PAL; max_screen_rows = 16; } else { // NTSC - max_screen_size = VIDEO_MODE_PIXELS_NTSC; + max_screen_size = VIDEO_BUFFER_CHARS_NTSC; max_screen_rows = 13; } From ca2ec58dd4403d4a6247083c6536627a3d04b095 Mon Sep 17 00:00:00 2001 From: J Blackman Date: Thu, 16 Jun 2016 17:30:19 +1000 Subject: [PATCH 20/22] Delete q --- q | 59 ----------------------------------------------------------- 1 file changed, 59 deletions(-) delete mode 100644 q diff --git a/q b/q deleted file mode 100644 index 04586033b6..0000000000 --- a/q +++ /dev/null @@ -1,59 +0,0 @@ -diff --git a/src/main/io/rc_controls.c b/src/main/io/rc_controls.c -index fdde2cf..53464ef 100644 ---- a/src/main/io/rc_controls.c -+++ b/src/main/io/rc_controls.c -@@ -67,6 +67,7 @@ static pidProfile_t *pidProfile; - static bool isUsingSticksToArm = true; -  - int16_t rcCommand[4]; // interval [1000;2000] for THROTTLE and [-500;+500] for ROLL/PITCH/YAW -+int16_t rcCommandSmooth[4]; // Smoothed RcCommand -  - uint32_t rcModeActivationMask; // one bit per mode defined in boxId_e -  -diff --git a/src/main/io/rc_controls.h b/src/main/io/rc_controls.h -index eaec277..dd8afaf 100644 ---- a/src/main/io/rc_controls.h -+++ b/src/main/io/rc_controls.h -@@ -147,6 +147,7 @@ typedef struct controlRateConfig_s { - } controlRateConfig_t; -  - extern int16_t rcCommand[4]; -+extern int16_t rcCommandSmooth[4]; // Smoothed RcCommand -  - typedef struct rcControlsConfig_s { - uint8_t deadband; // introduce a deadband around the stick center for pitch and roll axis. Must be greater than zero. -diff --git a/src/main/mw.c b/src/main/mw.c -index 125674c..5da79cf 100644 ---- a/src/main/mw.c -+++ b/src/main/mw.c -@@ -181,7 +181,7 @@ void filterRc(void) -  - if (isRXDataNew) { - for (int channel=0; channel < 4; channel++) { -- deltaRC[channel] = rcCommand[channel] - (lastCommand[channel] - deltaRC[channel] * factor / rcInterpolationFactor); -+ deltaRC[channel] = rcCommand[channel] - (lastCommand[channel] - deltaRC[channel] * factor / rcInterpolationFactor); - lastCommand[channel] = rcCommand[channel]; - } -  -@@ -194,7 +194,7 @@ void filterRc(void) - // Interpolate steps of rcCommand - if (factor > 0) { - for (int channel=0; channel < 4; channel++) { -- rcCommand[channel] = lastCommand[channel] - deltaRC[channel] * factor/rcInterpolationFactor; -+ rcCommandSmooth[channel] = lastCommand[channel] - deltaRC[channel] * factor/rcInterpolationFactor; - } - } else { - factor = 0; -@@ -649,8 +649,11 @@ void subTaskMainSubprocesses(void) { -  - const uint32_t startTime = micros(); -  -+ filterRc(); -+ - if (masterConfig.rxConfig.rcSmoothing || flightModeFlags) { -- filterRc(); -+ int axis; -+ for (axis = 0; axis <= 4; axis++) rcCommand[axis] = rcCommandSmooth[axis]; - } -  - // Read out gyro temperature. can use it for something somewhere. maybe get MCU temperature instead? lots of fun possibilities. From db07217afd777a9730a05047b627e33c21ea8632 Mon Sep 17 00:00:00 2001 From: Martin Budden Date: Thu, 16 Jun 2016 09:10:40 +0100 Subject: [PATCH 21/22] Changed tabs to spaces. --- src/main/drivers/io.c | 286 ++++++++++++++++++------------------- src/main/drivers/io_impl.h | 10 +- 2 files changed, 148 insertions(+), 148 deletions(-) diff --git a/src/main/drivers/io.c b/src/main/drivers/io.c index 57bbecdc44..11562cfc98 100644 --- a/src/main/drivers/io.c +++ b/src/main/drivers/io.c @@ -8,115 +8,115 @@ // io ports defs are stored in array by index now struct ioPortDef_s { - rccPeriphTag_t rcc; + rccPeriphTag_t rcc; }; #if defined(STM32F1) const struct ioPortDef_s ioPortDefs[] = { - { RCC_APB2(IOPA) }, - { RCC_APB2(IOPB) }, - { RCC_APB2(IOPC) }, - { RCC_APB2(IOPD) }, - { RCC_APB2(IOPE) }, + { 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), + RCC_APB2(IOPF), #else - 0, + 0, #endif }, { #if defined (STM32F10X_HD) || defined (STM32F10X_XL) || defined (STM32F10X_HD_VL) - RCC_APB2(IOPG), + RCC_APB2(IOPG), #else - 0, + 0, #endif }, }; #elif defined(STM32F3) const struct ioPortDef_s ioPortDefs[] = { - { RCC_AHB(GPIOA) }, - { RCC_AHB(GPIOB) }, - { RCC_AHB(GPIOC) }, - { RCC_AHB(GPIOD) }, - { RCC_AHB(GPIOE) }, - { RCC_AHB(GPIOF) }, + { RCC_AHB(GPIOA) }, + { RCC_AHB(GPIOB) }, + { RCC_AHB(GPIOC) }, + { RCC_AHB(GPIOD) }, + { RCC_AHB(GPIOE) }, + { RCC_AHB(GPIOF) }, }; #elif defined(STM32F4) const struct ioPortDef_s ioPortDefs[] = { - { RCC_AHB1(GPIOA) }, - { RCC_AHB1(GPIOB) }, - { RCC_AHB1(GPIOC) }, - { RCC_AHB1(GPIOD) }, - { RCC_AHB1(GPIOE) }, - { RCC_AHB1(GPIOF) }, + { RCC_AHB1(GPIOA) }, + { RCC_AHB1(GPIOB) }, + { RCC_AHB1(GPIOC) }, + { RCC_AHB1(GPIOD) }, + { RCC_AHB1(GPIOE) }, + { RCC_AHB1(GPIOF) }, }; # endif ioRec_t* IO_Rec(IO_t io) { - return io; + return io; } GPIO_TypeDef* IO_GPIO(IO_t io) { - ioRec_t *ioRec = IO_Rec(io); - return ioRec->gpio; + 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; + 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 + 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); + return IO_GPIOPortIdx(io); } int IO_GPIO_PortSource(IO_t io) { - return IO_GPIOPortIdx(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 + 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); + return IO_GPIOPinIdx(io); } int IO_GPIO_PinSource(IO_t io) { - return IO_GPIOPinIdx(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 (!io) + return 0; #if defined(STM32F1) - return 1 << IO_GPIOPinIdx(io); + return 1 << IO_GPIOPinIdx(io); #elif defined(STM32F3) - return IO_GPIOPinIdx(io); + return IO_GPIOPinIdx(io); #elif defined(STM32F4) - return 1 << IO_GPIOPinIdx(io); + return 1 << IO_GPIOPinIdx(io); #else # error "Unknown target type" #endif @@ -124,151 +124,151 @@ uint32_t IO_EXTI_Line(IO_t io) bool IORead(IO_t io) { - if (!io) - return false; - return !! (IO_GPIO(io)->IDR & IO_Pin(io)); + if (!io) + return false; + return !! (IO_GPIO(io)->IDR & IO_Pin(io)); } void IOWrite(IO_t io, bool hi) { - if (!io) - return; + if (!io) + return; #ifdef STM32F4 - if (hi) { - IO_GPIO(io)->BSRRL = IO_Pin(io); - } - else { - IO_GPIO(io)->BSRRH = IO_Pin(io); - } + if (hi) { + IO_GPIO(io)->BSRRL = IO_Pin(io); + } + else { + IO_GPIO(io)->BSRRH = IO_Pin(io); + } #else - IO_GPIO(io)->BSRR = IO_Pin(io) << (hi ? 0 : 16); + IO_GPIO(io)->BSRR = IO_Pin(io) << (hi ? 0 : 16); #endif } void IOHi(IO_t io) { - if (!io) - return; + if (!io) + return; #ifdef STM32F4 - IO_GPIO(io)->BSRRL = IO_Pin(io); + IO_GPIO(io)->BSRRL = IO_Pin(io); #else - IO_GPIO(io)->BSRR = IO_Pin(io); + IO_GPIO(io)->BSRR = IO_Pin(io); #endif } void IOLo(IO_t io) { - if (!io) - return; + if (!io) + return; #ifdef STM32F4 - IO_GPIO(io)->BSRRH = IO_Pin(io); + IO_GPIO(io)->BSRRH = IO_Pin(io); #else - IO_GPIO(io)->BRR = IO_Pin(io); + IO_GPIO(io)->BRR = IO_Pin(io); #endif } void IOToggle(IO_t io) { - if (!io) - return; - uint32_t mask = IO_Pin(io); - // Read pin state from ODR but write to BSRR because it only changes the pins - // high in the mask value rather than all pins. XORing ODR directly risks - // setting other pins incorrectly because it change all pins' state. + if (!io) + return; + uint32_t mask = IO_Pin(io); + // Read pin state from ODR but write to BSRR because it only changes the pins + // high in the mask value rather than all pins. XORing ODR directly risks + // setting other pins incorrectly because it change all pins' state. #ifdef STM32F4 - if (IO_GPIO(io)->ODR & mask) { - IO_GPIO(io)->BSRRH = mask; - } else { - IO_GPIO(io)->BSRRL = mask; - } + if (IO_GPIO(io)->ODR & mask) { + IO_GPIO(io)->BSRRH = mask; + } else { + IO_GPIO(io)->BSRRL = mask; + } #else - if (IO_GPIO(io)->ODR & mask) - mask <<= 16; // bit is set, shift mask to reset half + if (IO_GPIO(io)->ODR & mask) + mask <<= 16; // bit is set, shift mask to reset half - IO_GPIO(io)->BSRR = mask; + IO_GPIO(io)->BSRR = mask; #endif } // 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; + 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; + 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; + ioRec_t *ioRec = IO_Rec(io); + return ioRec->owner; } resourceType_t IOGetResources(IO_t io) { - ioRec_t *ioRec = IO_Rec(io); - return ioRec->resourcesUsed; + ioRec_t *ioRec = IO_Rec(io); + return ioRec->resourcesUsed; } #if defined(STM32F1) void IOConfigGPIO(IO_t io, ioConfig_t cfg) { - if (!io) - return; - rccPeriphTag_t rcc = ioPortDefs[IO_GPIOPortIdx(io)].rcc; - RCC_ClockCmd(rcc, ENABLE); + 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); + GPIO_InitTypeDef init = { + .GPIO_Pin = IO_Pin(io), + .GPIO_Speed = cfg & 0x03, + .GPIO_Mode = cfg & 0x7c, + }; + GPIO_Init(IO_GPIO(io), &init); } #elif defined(STM32F3) || defined(STM32F4) void IOConfigGPIO(IO_t io, ioConfig_t cfg) { - if (!io) - return; - rccPeriphTag_t rcc = ioPortDefs[IO_GPIOPortIdx(io)].rcc; - RCC_ClockCmd(rcc, ENABLE); + 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); + 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; + 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); + 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); + 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 @@ -279,32 +279,32 @@ 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; + 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++; - } - } - } + 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); + 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; + 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_impl.h b/src/main/drivers/io_impl.h index b7bbcec7f3..3a084949fe 100644 --- a/src/main/drivers/io_impl.h +++ b/src/main/drivers/io_impl.h @@ -5,14 +5,14 @@ #include "platform.h" typedef struct ioDef_s { - ioTag_t tag; + ioTag_t tag; } ioDef_t; typedef struct ioRec_s { - GPIO_TypeDef *gpio; - uint16_t pin; - resourceOwner_t owner; - resourceType_t resourcesUsed; // TODO! + GPIO_TypeDef *gpio; + uint16_t pin; + resourceOwner_t owner; + resourceType_t resourcesUsed; // TODO! } ioRec_t; extern ioRec_t ioRecs[DEFIO_IO_USED_COUNT]; From d73f28fe94b024736619e385ba78e13a4a38af53 Mon Sep 17 00:00:00 2001 From: Evgeny Sychov Date: Thu, 16 Jun 2016 01:34:01 -0700 Subject: [PATCH 22/22] Add support for VTX output power attenuation, Fix timerHardware definition --- src/main/config/config.c | 1 + src/main/config/config_master.h | 1 + src/main/drivers/vtx_soft_spi_rtc6705.c | 5 +++++ src/main/drivers/vtx_soft_spi_rtc6705.h | 12 ++++++++++++ src/main/io/osd.c | 5 ++--- src/main/io/serial_cli.c | 1 + src/main/target/SIRINFPV/target.c | 12 ++++++------ 7 files changed, 28 insertions(+), 9 deletions(-) diff --git a/src/main/config/config.c b/src/main/config/config.c index ff7a2ac1b6..3d39672e59 100755 --- a/src/main/config/config.c +++ b/src/main/config/config.c @@ -435,6 +435,7 @@ static void resetConf(void) #ifdef USE_RTC6705 masterConfig.vtx_channel = 19; // default to Boscam E channel 4 + masterConfig.vtx_power = 1; #endif #ifdef BOARD_HAS_VOLTAGE_DIVIDER diff --git a/src/main/config/config_master.h b/src/main/config/config_master.h index 6adb9d48d7..eb336ed999 100644 --- a/src/main/config/config_master.h +++ b/src/main/config/config_master.h @@ -127,6 +127,7 @@ typedef struct master_t { #ifdef USE_RTC6705 uint8_t vtx_channel; + uint8_t vtx_power; #endif #ifdef OSD diff --git a/src/main/drivers/vtx_soft_spi_rtc6705.c b/src/main/drivers/vtx_soft_spi_rtc6705.c index e66e5de603..b4b8ffce13 100644 --- a/src/main/drivers/vtx_soft_spi_rtc6705.c +++ b/src/main/drivers/vtx_soft_spi_rtc6705.c @@ -148,4 +148,9 @@ void rtc6705_soft_spi_set_channel(uint16_t channel_freq) { rtc6705_write_register(0, 400); rtc6705_write_register(1, (N << 7) | A); } + +void rtc6705_soft_spi_set_rf_power(uint8_t power) { + rtc6705_write_register(7, (power ? PA_CONTROL_DEFAULT : (PA_CONTROL_DEFAULT | PD_Q5G_MASK) & (~(PA5G_PW_MASK | PA5G_BS_MASK)))); +} + #endif diff --git a/src/main/drivers/vtx_soft_spi_rtc6705.h b/src/main/drivers/vtx_soft_spi_rtc6705.h index 6d761418bf..5f4314de1d 100644 --- a/src/main/drivers/vtx_soft_spi_rtc6705.h +++ b/src/main/drivers/vtx_soft_spi_rtc6705.h @@ -17,9 +17,21 @@ #pragma once +#define DP_5G_MASK 0x7000 +#define PA5G_BS_MASK 0x0E00 +#define PA5G_PW_MASK 0x0180 +#define PD_Q5G_MASK 0x0040 +#define QI_5G_MASK 0x0038 +#define PA_BS_MASK 0x0007 + +#define PA_CONTROL_DEFAULT 0x4FBD + + extern char* vtx_bands[]; extern uint16_t vtx_freq[]; extern uint16_t current_vtx_channel; void rtc6705_soft_spi_init(void); void rtc6705_soft_spi_set_channel(uint16_t channel_freq); +void rtc6705_soft_spi_set_rf_power(uint8_t power); + diff --git a/src/main/io/osd.c b/src/main/io/osd.c index 99c38e8bf6..d8fb10c69c 100644 --- a/src/main/io/osd.c +++ b/src/main/io/osd.c @@ -22,7 +22,7 @@ #include #include "platform.h" -#include "scheduler.h" +#include "scheduler/scheduler.h" #include "common/axis.h" #include "common/color.h" @@ -47,7 +47,6 @@ #include "drivers/pwm_rx.h" #include "drivers/adc.h" #include "drivers/bus_i2c.h" -#include "drivers/bus_bst.h" #include "drivers/bus_spi.h" #include "drivers/inverter.h" #include "drivers/flash_m25p16.h" @@ -111,7 +110,6 @@ #include "drivers/vtx_soft_spi_rtc6705.h" #endif -#include "scheduler.h" #include "common/printf.h" #define MICROSECONDS_IN_A_SECOND (1000 * 1000) @@ -707,6 +705,7 @@ void osdInit(void) rtc6705_soft_spi_init(); current_vtx_channel = masterConfig.vtx_channel; rtc6705_soft_spi_set_channel(vtx_freq[current_vtx_channel]); + rtc6705_soft_spi_set_rf_power(masterConfig.vtx_power); #endif max7456_init(masterConfig.osdProfile.system); diff --git a/src/main/io/serial_cli.c b/src/main/io/serial_cli.c index 7e13230922..e8d5ae9372 100644 --- a/src/main/io/serial_cli.c +++ b/src/main/io/serial_cli.c @@ -806,6 +806,7 @@ const clivalue_t valueTable[] = { #endif #ifdef USE_RTC6705 { "vtx_channel", VAR_INT16 | MASTER_VALUE, &masterConfig.vtx_channel, .config.minmax = { 0, 39 } }, + { "vtx_power", VAR_UINT8 | MASTER_VALUE, &masterConfig.vtx_power, .config.minmax = { 0, 1 } }, #endif #ifdef OSD { "osd_system", VAR_UINT8 | MASTER_VALUE, &masterConfig.osdProfile.system, .config.minmax = { 0, 2 } }, diff --git a/src/main/target/SIRINFPV/target.c b/src/main/target/SIRINFPV/target.c index 4ccf123ea2..4ac409d394 100644 --- a/src/main/target/SIRINFPV/target.c +++ b/src/main/target/SIRINFPV/target.c @@ -49,13 +49,13 @@ const uint16_t airPWM[] = { const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { - { TIM4, GPIOB, Pin_6, TIM_Channel_1, TIM4_IRQn, 1, Mode_AF_PP, GPIO_PinSource6, GPIO_AF_2, 0}, // PWM1 - PB6 - { TIM4, GPIOB, Pin_7, TIM_Channel_2, TIM4_IRQn, 1, Mode_AF_PP, GPIO_PinSource7, GPIO_AF_2, 0}, // PWM2 - PB6 - { TIM4, GPIOB, Pin_8, TIM_Channel_3, TIM4_IRQn, 1, Mode_AF_PP, GPIO_PinSource8, GPIO_AF_2, 0}, // PWM3 - PB8 - { TIM4, GPIOB, Pin_9, TIM_Channel_4, TIM4_IRQn, 1, Mode_AF_PP, GPIO_PinSource9, GPIO_AF_2, 0}, // PWM4 - PB9 + { TIM4, IO_TAG(PB6), TIM_Channel_1, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2, 0}, // PWM1 - PB6 + { TIM4, IO_TAG(PB7), TIM_Channel_2, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2, 0}, // PWM2 - PB6 + { TIM4, IO_TAG(PB8), TIM_Channel_3, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2, 0}, // PWM3 - PB8 + { TIM4, IO_TAG(PB9), TIM_Channel_4, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2, 0}, // PWM4 - PB9 - { TIM3, GPIOB, Pin_0, TIM_Channel_3, TIM3_IRQn, 1, Mode_AF_PP, GPIO_PinSource0, GPIO_AF_2, 0}, // PWM5 - PB0 - *TIM3_CH3 - { TIM3, GPIOB, Pin_1, TIM_Channel_4, TIM3_IRQn, 1, Mode_AF_PP, GPIO_PinSource1, GPIO_AF_2, 0}, // PWM6 - PB1 - *TIM3_CH4 + { TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2, 0}, // PWM5 - PB0 - *TIM3_CH3 + { TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2, 0}, // PWM6 - PB1 - *TIM3_CH4 };