1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-15 12:25:20 +03:00

Updated timerHardware_t to drop pinsource, and use new IO tags.

This commit is contained in:
blckmn 2016-06-13 09:02:33 +10:00
parent 3815f77e77
commit 8b1cc05e1d
11 changed files with 120 additions and 123 deletions

View file

@ -11,7 +11,7 @@ struct ioPortDef_s {
rccPeriphTag_t rcc; rccPeriphTag_t rcc;
}; };
#if defined(STM32F10X) #if defined(STM32F1)
const struct ioPortDef_s ioPortDefs[] = { const struct ioPortDef_s ioPortDefs[] = {
{ RCC_APB2(IOPA) }, { RCC_APB2(IOPA) },
{ RCC_APB2(IOPB) }, { RCC_APB2(IOPB) },
@ -33,7 +33,7 @@ const struct ioPortDef_s ioPortDefs[] = {
#endif #endif
}, },
}; };
#elif defined(STM32F303xC) #elif defined(STM32F3)
const struct ioPortDef_s ioPortDefs[] = { const struct ioPortDef_s ioPortDefs[] = {
{ RCC_AHB(GPIOA) }, { RCC_AHB(GPIOA) },
{ RCC_AHB(GPIOB) }, { RCC_AHB(GPIOB) },
@ -111,11 +111,11 @@ uint32_t IO_EXTI_Line(IO_t io)
{ {
if (!io) if (!io)
return 0; return 0;
#if defined(STM32F10X) #if defined(STM32F1)
return 1 << IO_GPIOPinIdx(io); return 1 << IO_GPIOPinIdx(io);
#elif defined(STM32F303xC) #elif defined(STM32F3)
return IO_GPIOPinIdx(io); return IO_GPIOPinIdx(io);
#elif defined(STM32F40_41xxx) || defined(STM32F411xE) #elif defined(STM32F4)
return 1 << IO_GPIOPinIdx(io); return 1 << IO_GPIOPinIdx(io);
#else #else
# error "Unknown target type" # error "Unknown target type"
@ -133,7 +133,7 @@ void IOWrite(IO_t io, bool hi)
{ {
if (!io) if (!io)
return; return;
#if defined(STM32F40_41xxx) || defined(STM32F411xE) #ifdef STM32F4
if (hi) { if (hi) {
IO_GPIO(io)->BSRRL = IO_Pin(io); IO_GPIO(io)->BSRRL = IO_Pin(io);
} }
@ -149,7 +149,7 @@ void IOHi(IO_t io)
{ {
if (!io) if (!io)
return; return;
#if defined(STM32F40_41xxx) || defined(STM32F411xE) #ifdef STM32F4
IO_GPIO(io)->BSRRL = IO_Pin(io); IO_GPIO(io)->BSRRL = IO_Pin(io);
#else #else
IO_GPIO(io)->BSRR = IO_Pin(io); IO_GPIO(io)->BSRR = IO_Pin(io);
@ -160,7 +160,7 @@ void IOLo(IO_t io)
{ {
if (!io) if (!io)
return; return;
#if defined(STM32F40_41xxx) || defined(STM32F411xE) #ifdef STM32F4
IO_GPIO(io)->BSRRH = IO_Pin(io); IO_GPIO(io)->BSRRH = IO_Pin(io);
#else #else
IO_GPIO(io)->BRR = IO_Pin(io); 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 // 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 // high in the mask value rather than all pins. XORing ODR directly risks
// setting other pins incorrectly because it change all pins' state. // setting other pins incorrectly because it change all pins' state.
#if defined(STM32F40_41xxx) || defined(STM32F411xE) #ifdef STM32F4
if (IO_GPIO(io)->ODR & mask) { if (IO_GPIO(io)->ODR & mask) {
IO_GPIO(io)->BSRRH = mask; IO_GPIO(io)->BSRRH = mask;
} else { } else {
@ -216,7 +216,7 @@ resourceType_t IOGetResources(IO_t io)
return ioRec->resourcesUsed; return ioRec->resourcesUsed;
} }
#if defined(STM32F10X) #if defined(STM32F1)
void IOConfigGPIO(IO_t io, ioConfig_t cfg) 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); 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) void IOConfigGPIO(IO_t io, ioConfig_t cfg)
{ {

View file

@ -3,6 +3,7 @@
#include <stdbool.h> #include <stdbool.h>
#include <stdint.h> #include <stdint.h>
#include <platform.h>
#include "resource.h" #include "resource.h"
// IO pin identification // IO pin identification
@ -33,7 +34,7 @@ typedef void* IO_t; // type specifying IO pin. Currently ioRec_t poin
// helps masking CPU differences // helps masking CPU differences
typedef uint8_t ioConfig_t; // packed IO configuration typedef uint8_t ioConfig_t; // packed IO configuration
#if defined(STM32F10X) #if defined(STM32F1)
// mode is using only bits 6-2 // mode is using only bits 6-2
# define IO_CONFIG(mode, speed) ((mode) | (speed)) # 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_IPU IO_CONFIG(GPIO_Mode_IPU, GPIO_Speed_2MHz)
# define IOCFG_IN_FLOATING IO_CONFIG(GPIO_Mode_IN_FLOATING, 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)) # define IO_CONFIG(mode, speed, otype, pupd) ((mode) | ((speed) << 2) | ((otype) << 4) | ((pupd) << 5))
@ -58,13 +59,14 @@ typedef uint8_t ioConfig_t; // packed IO configuration
# define IOCFG_IPU IO_CONFIG(GPIO_Mode_IN, 0, 0, GPIO_PuPd_UP) # 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_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_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_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 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_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_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_IPU IO_CONFIG(GPIO_Mode_IN, 0, 0, GPIO_PuPd_UP)
@ -100,7 +102,7 @@ resourceType_t IOGetResources(IO_t io);
IO_t IOGetByTag(ioTag_t tag); IO_t IOGetByTag(ioTag_t tag);
void IOConfigGPIO(IO_t io, ioConfig_t cfg); 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); void IOConfigGPIOAF(IO_t io, ioConfig_t cfg, uint8_t af);
#endif #endif

View file

@ -19,19 +19,20 @@ extern ioRec_t ioRecs[DEFIO_IO_USED_COUNT];
int IO_GPIOPortIdx(IO_t io); int IO_GPIOPortIdx(IO_t io);
int IO_GPIOPinIdx(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_PinSource(IO_t io);
int IO_GPIO_PortSource(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_PortSourceGPIO(IO_t io);
int IO_EXTI_PinSource(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); uint32_t IO_EXTI_Line(IO_t io);
ioRec_t *IO_Rec(IO_t io); ioRec_t *IO_Rec(IO_t io);

View file

@ -23,6 +23,8 @@
#include "platform.h" #include "platform.h"
#include "gpio.h" #include "gpio.h"
#include "io.h"
#include "io_impl.h"
#include "timer.h" #include "timer.h"
#include "pwm_output.h" #include "pwm_output.h"
@ -91,6 +93,16 @@ pwmOutputConfiguration_t *pwmGetOutputConfiguration(void)
return &pwmOutputConfiguration; 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) pwmOutputConfiguration_t *pwmInit(drv_pwm_config_t *init)
{ {
int i = 0; int i = 0;
@ -132,7 +144,7 @@ pwmOutputConfiguration_t *pwmInit(drv_pwm_config_t *init)
#if defined(STM32F303xC) && defined(USE_USART3) #if defined(STM32F303xC) && defined(USE_USART3)
// skip UART3 ports (PB10/PB11) // 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; continue;
#endif #endif
@ -151,7 +163,7 @@ pwmOutputConfiguration_t *pwmInit(drv_pwm_config_t *init)
if (timerHardwarePtr->tim == LED_STRIP_TIMER) if (timerHardwarePtr->tim == LED_STRIP_TIMER)
continue; continue;
#if defined(STM32F303xC) && defined(WS2811_GPIO) && defined(WS2811_PIN_SOURCE) #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; continue;
#endif #endif
} }
@ -159,28 +171,28 @@ pwmOutputConfiguration_t *pwmInit(drv_pwm_config_t *init)
#endif #endif
#ifdef VBAT_ADC_GPIO #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; continue;
} }
#endif #endif
#ifdef RSSI_ADC_GPIO #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; continue;
} }
#endif #endif
#ifdef CURRENT_METER_ADC_GPIO #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; continue;
} }
#endif #endif
#ifdef SONAR #ifdef SONAR
if (init->sonarGPIOConfig && timerHardwarePtr->gpio == init->sonarGPIOConfig->gpio && if (init->sonarGPIOConfig &&
( (
timerHardwarePtr->pin == init->sonarGPIOConfig->triggerPin || CheckGPIOPin(timerHardwarePtr->pin, init->sonarGPIOConfig->gpio, init->sonarGPIOConfig->triggerPin) ||
timerHardwarePtr->pin == init->sonarGPIOConfig->echoPin CheckGPIOPin(timerHardwarePtr->pin, init->sonarGPIOConfig->gpio, init->sonarGPIOConfig->echoPin)
) )
) { ) {
continue; continue;

View file

@ -22,7 +22,7 @@
#include "platform.h" #include "platform.h"
#include "gpio.h" #include "io.h"
#include "timer.h" #include "timer.h"
#include "flight/failsafe.h" // FIXME dependency into the main code from a driver #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; IOInit(IOGetByTag(pin), OWNER_PWMOUTPUT_MOTOR, RESOURCE_OUTPUT);
IOConfigGPIO(IOGetByTag(pin), mode);
cfg.pin = pin;
cfg.mode = mode;
cfg.speed = Speed_2MHz;
gpioInit(gpio, &cfg);
} }
static pwmOutputPort_t *pwmOutConfig(const timerHardware_t *timerHardware, uint8_t mhz, uint16_t period, uint16_t value) 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++]; pwmOutputPort_t *p = &pwmOutputPorts[allocatedOutputPortCount++];
configTimeBase(timerHardware->tim, period, mhz); 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); pwmOCConfig(timerHardware->tim, timerHardware->channel, value, timerHardware->outputInverted);

View file

@ -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; IOInit(IOGetByTag(pin), OWNER_PWMINPUT, RESOURCE_INPUT);
IOConfigGPIO(IOGetByTag(pin), mode);
cfg.pin = pin;
cfg.mode = mode;
cfg.speed = Speed_2MHz;
gpioInit(gpio, &cfg);
} }
void pwmICConfig(TIM_TypeDef *tim, uint8_t channel, uint16_t polarity) 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->mode = INPUT_MODE_PWM;
self->timerHardware = timerHardwarePtr; self->timerHardware = timerHardwarePtr;
pwmGPIOConfig(timerHardwarePtr->gpio, timerHardwarePtr->pin, timerHardwarePtr->gpioInputMode); pwmGPIOConfig(timerHardwarePtr->pin, timerHardwarePtr->ioMode);
pwmICConfig(timerHardwarePtr->tim, timerHardwarePtr->channel, TIM_ICPolarity_Rising); pwmICConfig(timerHardwarePtr->tim, timerHardwarePtr->channel, TIM_ICPolarity_Rising);
timerConfigure(timerHardwarePtr, (uint16_t)PWM_TIMER_PERIOD, PWM_TIMER_MHZ); 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->mode = INPUT_MODE_PPM;
self->timerHardware = timerHardwarePtr; self->timerHardware = timerHardwarePtr;
pwmGPIOConfig(timerHardwarePtr->gpio, timerHardwarePtr->pin, timerHardwarePtr->gpioInputMode); pwmGPIOConfig(timerHardwarePtr->pin, timerHardwarePtr->ioMode);
pwmICConfig(timerHardwarePtr->tim, timerHardwarePtr->channel, TIM_ICPolarity_Rising); pwmICConfig(timerHardwarePtr->tim, timerHardwarePtr->channel, TIM_ICPolarity_Rising);
timerConfigure(timerHardwarePtr, (uint16_t)PPM_TIMER_PERIOD, PWM_TIMER_MHZ); timerConfigure(timerHardwarePtr, (uint16_t)PPM_TIMER_PERIOD, PWM_TIMER_MHZ);

View file

@ -30,7 +30,7 @@
#include "nvic.h" #include "nvic.h"
#include "system.h" #include "system.h"
#include "gpio.h" #include "io.h"
#include "timer.h" #include "timer.h"
#include "serial.h" #include "serial.h"
@ -48,6 +48,8 @@
typedef struct softSerial_s { typedef struct softSerial_s {
serialPort_t port; serialPort_t port;
IO_t rxIO;
IO_t txIO;
const timerHardware_t *rxTimerHardware; const timerHardware_t *rxTimerHardware;
volatile uint8_t rxBuffer[SOFTSERIAL_BUFFER_SIZE]; volatile uint8_t rxBuffer[SOFTSERIAL_BUFFER_SIZE];
@ -92,30 +94,24 @@ void setTxSignal(softSerial_t *softSerial, uint8_t state)
} }
if (state) { if (state) {
digitalHi(softSerial->txTimerHardware->gpio, softSerial->txTimerHardware->pin); IOHi(softSerial->txIO);
} else { } 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; IOInit(IOGetByTag(pin), OWNER_SOFTSERIAL_RXTX, RESOURCE_USART);
IOConfigGPIO(IOGetByTag(pin), mode);
cfg.pin = pin;
cfg.mode = mode;
cfg.speed = Speed_2MHz;
gpioInit(gpio, &cfg);
} }
void serialInputPortConfig(const timerHardware_t *timerHardwarePtr) void serialInputPortConfig(ioTag_t pin)
{ {
#ifdef STM32F10X #ifdef STM32F1
softSerialGPIOConfig(timerHardwarePtr->gpio, timerHardwarePtr->pin, Mode_IPU); softSerialGPIOConfig(pin, IOCFG_IPU);
#else #else
#ifdef STM32F303xC softSerialGPIOConfig(pin, IOCFG_AF_PP_UP);
softSerialGPIOConfig(timerHardwarePtr->gpio, timerHardwarePtr->pin, Mode_AF_PP_PU);
#endif
#endif #endif
} }
@ -168,9 +164,9 @@ static void serialTimerRxConfig(const timerHardware_t *timerHardwarePtr, uint8_t
timerChConfigCallbacks(timerHardwarePtr, &softSerialPorts[reference].edgeCb, NULL); 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) static void resetBuffers(softSerial_t *softSerial)
@ -222,8 +218,11 @@ serialPort_t *openSoftSerial(softSerialPortIndex_e portIndex, serialReceiveCallb
softSerial->softSerialPortIndex = portIndex; softSerial->softSerialPortIndex = portIndex;
serialOutputPortConfig(softSerial->txTimerHardware); softSerial->txIO = IOGetByTag(softSerial->txTimerHardware->pin);
serialInputPortConfig(softSerial->rxTimerHardware); serialOutputPortConfig(softSerial->txTimerHardware->pin);
softSerial->rxIO = IOGetByTag(softSerial->rxTimerHardware->pin);
serialInputPortConfig(softSerial->rxTimerHardware->pin);
setTxSignal(softSerial, ENABLE); setTxSignal(softSerial, ENABLE);
delay(50); delay(50);

View file

@ -353,14 +353,10 @@ void timerChClearCCFlag(const timerHardware_t *timHw)
} }
// configure timer channel GPIO mode // 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; IOInit(IOGetByTag(timHw->pin), OWNER_TIMER, RESOURCE_TIMER);
IOConfigGPIO(IOGetByTag(timHw->pin), mode);
cfg.pin = timHw->pin;
cfg.mode = mode;
cfg.speed = Speed_2MHz;
gpioInit(timHw->gpio, &cfg);
} }
// calculate input filter constant // calculate input filter constant
@ -656,19 +652,13 @@ void timerInit(void)
RCC_AHBPeriphClockCmd(TIMER_AHB_PERIPHERALS, ENABLE); RCC_AHBPeriphClockCmd(TIMER_AHB_PERIPHERALS, ENABLE);
#endif #endif
#ifdef STM32F303xC #if defined(STM32F3) || defined(STM32F4)
for (uint8_t timerIndex = 0; timerIndex < USABLE_TIMER_CHANNEL_COUNT; timerIndex++) { for (uint8_t timerIndex = 0; timerIndex < USABLE_TIMER_CHANNEL_COUNT; timerIndex++) {
const timerHardware_t *timerHardwarePtr = &timerHardware[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 #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++) { for(int i = 0; i < USABLE_TIMER_CHANNEL_COUNT; i++) {
timerChannelInfo[i].type = TYPE_FREE; timerChannelInfo[i].type = TYPE_FREE;

View file

@ -17,6 +17,8 @@
#pragma once #pragma once
#include "io.h"
#if !defined(USABLE_TIMER_CHANNEL_COUNT) #if !defined(USABLE_TIMER_CHANNEL_COUNT)
#define USABLE_TIMER_CHANNEL_COUNT 14 #define USABLE_TIMER_CHANNEL_COUNT 14
#endif #endif
@ -64,14 +66,12 @@ typedef struct timerOvrHandlerRec_s {
typedef struct { typedef struct {
TIM_TypeDef *tim; TIM_TypeDef *tim;
GPIO_TypeDef *gpio; ioTag_t pin;
uint16_t pin;
uint8_t channel; uint8_t channel;
uint8_t irq; uint8_t irq;
uint8_t outputEnable; uint8_t outputEnable;
GPIO_Mode gpioInputMode; ioConfig_t ioMode;
#if defined(STM32F3) || defined(STM32F4) #if defined(STM32F3) || defined(STM32F4)
uint8_t gpioPinSource; // TODO - this can be removed and pinSource calculated from pin
uint8_t alternateFunction; uint8_t alternateFunction;
#endif #endif
uint8_t outputInverted; 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* timerChCCRLo(const timerHardware_t* timHw);
volatile timCCR_t* timerChCCRHi(const timerHardware_t* timHw); volatile timCCR_t* timerChCCRHi(const timerHardware_t* timHw);
void timerChConfigOC(const timerHardware_t* timHw, bool outEnable, bool stateHigh); 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 timerChCCHandlerInit(timerCCHandlerRec_t *self, timerCCHandlerCallback *fn);
void timerChOvrHandlerInit(timerOvrHandlerRec_t *self, timerOvrHandlerCallback *fn); void timerChOvrHandlerInit(timerOvrHandlerRec_t *self, timerOvrHandlerCallback *fn);

View file

@ -3,6 +3,7 @@
#include <stdint.h> #include <stdint.h>
#include <platform.h> #include <platform.h>
#include "drivers/io.h"
#include "drivers/pwm_mapping.h" #include "drivers/pwm_mapping.h"
const uint16_t multiPPM[] = { const uint16_t multiPPM[] = {
@ -50,12 +51,12 @@ const uint16_t airPWM[] = {
}; };
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { 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 { TIM8, IO_TAG(PC7), TIM_Channel_2, TIM8_CC_IRQn, 0, Mode_IPD, 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, IO_TAG(PA0), TIM_Channel_1, TIM5_IRQn, 1, Mode_AF_PP, 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 { TIM5, IO_TAG(PA1), TIM_Channel_2, TIM5_IRQn, 1, Mode_AF_PP, 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 { TIM2, IO_TAG(PA2), TIM_Channel_3, TIM2_IRQn, 1, Mode_AF_PP, 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 { TIM9, IO_TAG(PA3), TIM_Channel_2, TIM1_BRK_TIM9_IRQn, 1, Mode_AF_PP, 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, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, 1, Mode_AF_PP, 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 { TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, 1, Mode_AF_PP, GPIO_AF_TIM3, 0}, // S6_OUT
}; };

View file

@ -72,19 +72,19 @@ const uint16_t airPWM[] = {
}; };
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
{ TIM2, GPIOA, Pin_0, TIM_Channel_1, TIM2_IRQn, 0, Mode_IPD, 0}, // PWM1 - RC1 { TIM2, IO_TAG(PA0), 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, IO_TAG(PA1), 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, IO_TAG(PA2), 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 { TIM2, IO_TAG(PA3), 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, IO_TAG(PA6), 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, IO_TAG(PA7), 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, IO_TAG(PB0), 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 { TIM3, IO_TAG(PB1), 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, IO_TAG(PA8), 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 { TIM1, IO_TAG(PA11),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, IO_TAG(PB6), 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, IO_TAG(PB7), 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, IO_TAG(PB8), 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 { TIM4, IO_TAG(PB9), TIM_Channel_4, TIM4_IRQn, 0, Mode_IPD, 0} // PWM14 - OUT6
}; };