merge upstream into development branch

This commit is contained in:
Evgeny Sychov 2016-06-16 00:01:20 -07:00
commit 7e9fc71289
77 changed files with 913 additions and 612 deletions

View File

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

View File

@ -13,6 +13,7 @@ targets=("PUBLISHMETA=True" \
"TARGET=RMDO" \
"TARGET=SPARKY" \
"TARGET=MOTOLAB" \
"TARGET=PIKOBLX" \
"TARGET=IRCFUSIONF3" \
"TARGET=ALIENFLIGHTF1" \
"TARGET=ALIENFLIGHTF3" \

View File

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

View File

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

View File

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

View File

@ -3,11 +3,12 @@
#include <stdbool.h>
#include <stdint.h>
#include <platform.h>
#include "resource.h"
// IO pin identification
// make sure that ioTag_t can't be assigned into IO_t without warning
typedef uint8_t ioTag_t; // packet tag to specify IO pin
typedef 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
@ -33,42 +34,32 @@ 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))
#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(STM32F303xC)
#elif defined(STM32F3) || 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)
#elif defined(STM32F40_41xxx) || defined(STM32F411xE)
# 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_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 +91,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

View File

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

View File

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

View File

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

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

View File

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

View File

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

View File

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

View File

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

View File

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

View File

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

View File

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

View File

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

View File

@ -24,7 +24,6 @@
#include <ctype.h>
#include "platform.h"
#include "scheduler.h"
#include "version.h"
#include "debug.h"
@ -44,6 +43,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"
@ -90,7 +91,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
@ -140,6 +142,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);
@ -299,6 +302,7 @@ const clicmd_t cmdTable[] = {
CLI_COMMAND_DEF("profile", "change profile",
"[<index>]", cliProfile),
CLI_COMMAND_DEF("rateprofile", "change rate profile", "[<index>]", 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),
@ -1889,6 +1893,10 @@ static void dumpValues(uint16_t valueSection)
cliPrintf("set %s = ", valueTable[i].name);
cliPrintVar(value, 0);
cliPrint("\r\n");
#ifdef STM32F4
delayMicroseconds(1000);
#endif
}
}
@ -3022,6 +3030,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);

View File

@ -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"
@ -64,6 +63,8 @@
#include "telemetry/telemetry.h"
#include "scheduler/scheduler.h"
#include "sensors/boardalignment.h"
#include "sensors/sensors.h"
#include "sensors/battery.h"

View File

@ -22,8 +22,6 @@
#include <math.h>
#include "platform.h"
#include "scheduler.h"
#include "common/axis.h"
#include "common/color.h"
#include "common/maths.h"
@ -47,7 +45,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 +56,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"
@ -75,6 +76,8 @@
#include "io/osd.h"
#include "io/vtx.h"
#include "scheduler/scheduler.h"
#include "sensors/sensors.h"
#include "sensors/sonar.h"
#include "sensors/barometer.h"
@ -351,10 +354,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.

View File

@ -21,7 +21,6 @@
#include <math.h>
#include "platform.h"
#include "scheduler.h"
#include "debug.h"
#include "common/maths.h"
@ -88,6 +87,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 {
@ -841,8 +843,9 @@ void taskUpdateBattery(void)
}
}
bool taskUpdateRxCheck(void)
bool taskUpdateRxCheck(uint32_t currentDeltaTime)
{
UNUSED(currentDeltaTime);
updateRx(currentTime);
return shouldProcessRx(currentTime);
}

View File

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

View File

@ -20,33 +20,9 @@
#include <stdint.h>
#include <platform.h>
#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 OSD
void taskUpdateOsd(void);
#endif
#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] = {

View File

@ -0,0 +1,45 @@
/*
* 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 <http://www.gnu.org/licenses/>.
*/
#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 OSD
void taskUpdateOsd(void);
#endif
#ifdef USE_BST
void taskBstReadWrite(void);
void taskBstMasterProcess(void);
#endif

View File

@ -20,8 +20,6 @@
#include <math.h>
#include "platform.h"
#include "scheduler.h"
#include "common/maths.h"
#include "drivers/barometer.h"

View File

@ -88,47 +88,11 @@ 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 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;
#elif defined(USE_HARDWARE_REVISION_DETECTION)
return selectMPUIntExtiConfigByHardwareRevision();
#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;
#endif
}
#ifdef USE_FAKE_GYRO

View File

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

View File

@ -14,6 +14,9 @@
* You should have received a copy of the GNU General Public License
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
*/
#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);

View File

@ -3,6 +3,7 @@
#include <stdint.h>
#include <platform.h>
#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
};

View File

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

View File

@ -1,6 +1,7 @@
#include <stdbool.h>
#include <platform.h>
#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
};

View File

@ -3,6 +3,7 @@
#include <stdint.h>
#include <platform.h>
#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, 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
};

View File

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

View File

@ -3,6 +3,7 @@
#include <stdint.h>
#include <platform.h>
#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
};

View File

@ -3,6 +3,7 @@
#include <stdint.h>
#include <platform.h>
#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
};

View File

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

View File

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

View File

@ -14,7 +14,10 @@
* You should have received a copy of the GNU General Public License
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
*/
#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);

View File

@ -3,6 +3,7 @@
#include <stdint.h>
#include <platform.h>
#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
};

View File

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

View File

@ -12,7 +12,7 @@
#include <build_config.h>
#include "nvic.h"
#include "drivers/nvic.h"
#include "bus_bst.h"

View File

@ -69,6 +69,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);

View File

@ -17,8 +17,6 @@
#pragma once
#include "drivers/bus_bst.h"
void bstProcessInCommand(void);
void bstSlaveProcessInCommand(void);
void taskBstMasterProcess(void);

View File

@ -3,6 +3,7 @@
#include <stdint.h>
#include <platform.h>
#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
};

View File

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

View File

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

View File

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

View File

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

View File

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

View File

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

View File

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

View File

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

View File

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

View File

@ -0,0 +1 @@
# AFROMINI is a VARIANT of NAZE being recognized as rev4, but needs to use rev5

View File

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

View File

@ -14,6 +14,9 @@
* You should have received a copy of the GNU General Public License
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
*/
#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);

View File

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

View File

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

View File

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

View File

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

View File

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

View File

@ -0,0 +1,55 @@
#include <stdbool.h>
#include <stdint.h>
#include <platform.h>
#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, 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
};

View File

@ -0,0 +1,173 @@
/*
* 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 <http://www.gnu.org/licenses/>.
*/
#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 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
#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)

View File

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

View File

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

View File

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

View File

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

View File

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

View File

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

View File

@ -3,6 +3,7 @@
#include <stdint.h>
#include <platform.h>
#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
};

View File

@ -3,6 +3,7 @@
#include <stdint.h>
#include <platform.h>
#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
};

View File

@ -3,6 +3,7 @@
#include <stdint.h>
#include <platform.h>
#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
};

View File

@ -3,6 +3,7 @@
#include <stdint.h>
#include <platform.h>
#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
};

View File

@ -19,7 +19,7 @@
extern "C" {
#include "platform.h"
#include "scheduler.h"
#include "scheduler/scheduler.h"
}
#include "unittest_macros.h"