Merge branch 'development' into ready_to_merge

This commit is contained in:
blckmn 2016-06-19 19:29:51 +10:00
commit 03b7ab62dc
37 changed files with 157 additions and 156 deletions

View File

@ -44,6 +44,7 @@
#define JEDEC_ID_MICRON_M25P16 0x202015
#define JEDEC_ID_MICRON_N25Q064 0x20BA17
#define JEDEC_ID_WINBOND_W25Q64 0xEF4017
#define JEDEC_ID_MACRONIX_MX25L6406E 0xC22017
#define JEDEC_ID_MICRON_N25Q128 0x20ba18
#define JEDEC_ID_WINBOND_W25Q128 0xEF4018
@ -163,6 +164,7 @@ static bool m25p16_readIdentification()
break;
case JEDEC_ID_MICRON_N25Q064:
case JEDEC_ID_WINBOND_W25Q64:
case JEDEC_ID_MACRONIX_MX25L6406E:
geometry.sectors = 128;
geometry.pagesPerSector = 256;
break;
@ -204,8 +206,12 @@ bool m25p16_init()
IOInit(m25p16CsPin, OWNER_FLASH, RESOURCE_SPI);
IOConfigGPIO(m25p16CsPin, SPI_IO_CS_CFG);
DISABLE_M25P16;
#ifndef M25P16_SPI_SHARED
//Maximum speed for standard READ command is 20mHz, other commands tolerate 25mHz
spiSetDivisor(M25P16_SPI_INSTANCE, SPI_18MHZ_CLOCK_DIVIDER);
#endif
return m25p16_readIdentification();
}

View File

@ -213,6 +213,12 @@ pwmOutputConfiguration_t *pwmInit(drv_pwm_config_t *init)
type = MAP_TO_SERVO_OUTPUT;
#endif
#if defined(DOGE)
// remap outputs 1+2 (PWM2+3) as servos
if ((timerIndex == PWM2 || timerIndex == PWM3) && timerHardwarePtr->tim == TIM4)
type = MAP_TO_SERVO_OUTPUT;
#endif
#if defined(COLIBRI_RACE) || defined(LUX_RACE)
// remap PWM1+2 as servos
if ((timerIndex == PWM6 || timerIndex == PWM7 || timerIndex == PWM8 || timerIndex == PWM9) && timerHardwarePtr->tim == TIM2)

View File

@ -27,6 +27,8 @@
#include "nvic.h"
#include "gpio.h"
#include "gpio.h"
#include "rcc.h"
#include "system.h"
#include "timer.h"
@ -51,7 +53,7 @@ typedef struct timerConfig_s {
timerCCHandlerRec_t *edgeCallback[CC_CHANNELS_PER_TIMER];
timerOvrHandlerRec_t *overflowCallback[CC_CHANNELS_PER_TIMER];
timerOvrHandlerRec_t *overflowCallbackActive; // null-terminated linkded list of active overflow callbacks
uint32_t forcedOverflowTimerValue;
uint32_t forcedOverflowTimerValue;
} timerConfig_t;
timerConfig_t timerConfig[USED_TIMER_COUNT];
@ -141,6 +143,16 @@ static inline uint8_t lookupChannelIndex(const uint16_t channel)
return channel >> 2;
}
rccPeriphTag_t timerRCC(TIM_TypeDef *tim)
{
for (uint8_t i = 0; i < HARDWARE_TIMER_DEFINITION_COUNT; i++) {
if (timerDefinitions[i].TIMx == tim) {
return timerDefinitions[i].rcc;
}
}
return 0;
}
void timerNVICConfigure(uint8_t irq)
{
NVIC_InitTypeDef NVIC_InitStructure;
@ -162,19 +174,19 @@ void configTimeBase(TIM_TypeDef *tim, uint16_t period, uint8_t mhz)
// "The counter clock frequency (CK_CNT) is equal to f CK_PSC / (PSC[15:0] + 1)." - STM32F10x Reference Manual 14.4.11
// Thus for 1Mhz: 72000000 / 1000000 = 72, 72 - 1 = 71 = TIM_Prescaler
#if defined (STM32F40_41xxx)
if (tim == TIM1 || tim == TIM8 || tim == TIM9 || tim == TIM10 || tim == TIM11) {
TIM_TimeBaseStructure.TIM_Prescaler = (SystemCoreClock / ((uint32_t)mhz * 1000000)) - 1;
}
else {
TIM_TimeBaseStructure.TIM_Prescaler = (SystemCoreClock / 2 / ((uint32_t)mhz * 1000000)) - 1;
}
if (tim == TIM1 || tim == TIM8 || tim == TIM9 || tim == TIM10 || tim == TIM11) {
TIM_TimeBaseStructure.TIM_Prescaler = (SystemCoreClock / ((uint32_t)mhz * 1000000)) - 1;
}
else {
TIM_TimeBaseStructure.TIM_Prescaler = (SystemCoreClock / 2 / ((uint32_t)mhz * 1000000)) - 1;
}
#elif defined (STM32F411xE)
if (tim == TIM1 || tim == TIM9 || tim == TIM10 || tim == TIM11) {
TIM_TimeBaseStructure.TIM_Prescaler = (SystemCoreClock / ((uint32_t)mhz * 1000000)) - 1;
}
else {
TIM_TimeBaseStructure.TIM_Prescaler = (SystemCoreClock / 2 / ((uint32_t)mhz * 1000000)) - 1;
}
if (tim == TIM1 || tim == TIM9 || tim == TIM10 || tim == TIM11) {
TIM_TimeBaseStructure.TIM_Prescaler = (SystemCoreClock / ((uint32_t)mhz * 1000000)) - 1;
}
else {
TIM_TimeBaseStructure.TIM_Prescaler = (SystemCoreClock / 2 / ((uint32_t)mhz * 1000000)) - 1;
}
#else
TIM_TimeBaseStructure.TIM_Prescaler = (SystemCoreClock / ((uint32_t)mhz * 1000000)) - 1;
#endif
@ -197,17 +209,14 @@ void timerConfigure(const timerHardware_t *timerHardwarePtr, uint16_t period, ui
timerNVICConfigure(TIM1_UP_IRQn);
break;
#endif
#if defined (STM32F40_41xxx)
#if defined (STM32F40_41xxx) || defined(STM32F411xE)
case TIM1_CC_IRQn:
timerNVICConfigure(TIM1_UP_TIM10_IRQn);
break;
case TIM8_CC_IRQn:
timerNVICConfigure(TIM8_UP_TIM13_IRQn);
break;
#endif
#if defined (STM32F411xE)
case TIM1_CC_IRQn:
timerNVICConfigure(TIM1_UP_TIM10_IRQn);
#if defined (STM32F40_41xxx)
case TIM8_CC_IRQn:
timerNVICConfigure(TIM8_UP_TIM13_IRQn);
break;
#endif
#ifdef STM32F303xC
@ -640,17 +649,10 @@ void timerInit(void)
GPIO_PinRemapConfig(GPIO_PartialRemap_TIM3, ENABLE);
#endif
#ifdef TIMER_APB1_PERIPHERALS
RCC_APB1PeriphClockCmd(TIMER_APB1_PERIPHERALS, ENABLE);
#endif
#ifdef TIMER_APB2_PERIPHERALS
RCC_APB2PeriphClockCmd(TIMER_APB2_PERIPHERALS, ENABLE);
#endif
#ifdef TIMER_AHB_PERIPHERALS
RCC_AHBPeriphClockCmd(TIMER_AHB_PERIPHERALS, ENABLE);
#endif
/* enable the timer peripherals */
for (uint8_t i = 0; i < USABLE_TIMER_CHANNEL_COUNT; i++) {
RCC_ClockCmd(timerRCC(timerHardware[i].tim), ENABLE);
}
#if defined(STM32F3) || defined(STM32F4)
for (uint8_t timerIndex = 0; timerIndex < USABLE_TIMER_CHANNEL_COUNT; timerIndex++) {

View File

@ -18,6 +18,7 @@
#pragma once
#include "io.h"
#include "rcc.h"
#if !defined(USABLE_TIMER_CHANNEL_COUNT)
#define USABLE_TIMER_CHANNEL_COUNT 14
@ -64,6 +65,11 @@ typedef struct timerOvrHandlerRec_s {
struct timerOvrHandlerRec_s* next;
} timerOvrHandlerRec_t;
typedef struct timerDef_s {
TIM_TypeDef *TIMx;
rccPeriphTag_t rcc;
} timerDef_t;
typedef struct {
TIM_TypeDef *tim;
ioTag_t pin;
@ -77,7 +83,21 @@ typedef struct {
uint8_t outputInverted;
} timerHardware_t;
#ifdef STM32F1
#if defined(STM32F10X_XL) || defined(STM32F10X_HD_VL)
#define HARDWARE_TIMER_DEFINITION_COUNT 14
#elif defined(STM32F10X_HD) || defined(STM32F10X_CL)
#define HARDWARE_TIMER_DEFINITION_COUNT 7
#else
#define HARDWARE_TIMER_DEFINITION_COUNT 4
#endif
#elif defined(STM32F3)
#define HARDWARE_TIMER_DEFINITION_COUNT 10
#elif defined(STM32F4)
#define HARDWARE_TIMER_DEFINITION_COUNT 14
#endif
extern const timerHardware_t timerHardware[];
extern const timerDef_t timerDefinitions[];
typedef enum {
TYPE_FREE,
@ -124,3 +144,4 @@ void timerForceOverflow(TIM_TypeDef *tim);
void configTimeBase(TIM_TypeDef *tim, uint16_t period, uint8_t mhz); // TODO - just for migration
rccPeriphTag_t timerRCC(TIM_TypeDef *tim);

View File

@ -6,6 +6,29 @@
*/
#include "stm32f10x.h"
#include "rcc.h"
#include "timer.h"
const timerDef_t timerDefinitions[HARDWARE_TIMER_DEFINITION_COUNT] = {
{ .TIMx = TIM1, .rcc = RCC_APB2(TIM1) },
{ .TIMx = TIM2, .rcc = RCC_APB1(TIM2) },
{ .TIMx = TIM3, .rcc = RCC_APB1(TIM3) },
{ .TIMx = TIM4, .rcc = RCC_APB1(TIM4) },
#if defined(STM32F10X_HD) || defined(STM32F10X_CL) || defined(STM32F10X_XL) || defined(STM32F10X_HD_VL)
{ .TIMx = TIM5, .rcc = RCC_APB1(TIM5) },
{ .TIMx = TIM6, .rcc = RCC_APB1(TIM6) },
{ .TIMx = TIM7, .rcc = RCC_APB1(TIM7) },
#endif
#if defined(STM32F10X_XL) || defined(STM32F10X_HD_VL)
{ .TIMx = TIM8, .rcc = RCC_APB1(TIM8) },
{ .TIMx = TIM9, .rcc = RCC_APB2(TIM9) },
{ .TIMx = TIM10, .rcc = RCC_APB2(TIM10) },
{ .TIMx = TIM11, .rcc = RCC_APB2(TIM11) },
{ .TIMx = TIM12, .rcc = RCC_APB1(TIM12) },
{ .TIMx = TIM13, .rcc = RCC_APB1(TIM13) },
{ .TIMx = TIM14, .rcc = RCC_APB1(TIM14) },
#endif
};
/**
* @brief Selects the TIM Output Compare Mode.

View File

@ -6,6 +6,22 @@
*/
#include "stm32f30x.h"
#include "rcc.h"
#include "timer.h"
const timerDef_t timerDefinitions[HARDWARE_TIMER_DEFINITION_COUNT] = {
{ .TIMx = TIM1, .rcc = RCC_APB2(TIM1) },
{ .TIMx = TIM2, .rcc = RCC_APB1(TIM2) },
{ .TIMx = TIM3, .rcc = RCC_APB1(TIM3) },
{ .TIMx = TIM4, .rcc = RCC_APB1(TIM4) },
{ .TIMx = TIM6, .rcc = RCC_APB1(TIM6) },
{ .TIMx = TIM7, .rcc = RCC_APB1(TIM7) },
{ .TIMx = TIM8, .rcc = RCC_APB2(TIM8) },
{ .TIMx = TIM15, .rcc = RCC_APB2(TIM15) },
{ .TIMx = TIM16, .rcc = RCC_APB2(TIM16) },
{ .TIMx = TIM17, .rcc = RCC_APB2(TIM17) },
};
/**
* @brief Selects the TIM Output Compare Mode.

View File

@ -6,6 +6,8 @@
*/
#include "stm32f4xx.h"
#include "timer.h"
#include "rcc.h"
/**
* @brief Selects the TIM Output Compare Mode.
@ -32,6 +34,23 @@
#define CCMR_Offset ((uint16_t)0x0018)
const timerDef_t timerDefinitions[HARDWARE_TIMER_DEFINITION_COUNT] = {
{ .TIMx = TIM1, .rcc = RCC_APB2(TIM1) },
{ .TIMx = TIM2, .rcc = RCC_APB1(TIM2) },
{ .TIMx = TIM3, .rcc = RCC_APB1(TIM3) },
{ .TIMx = TIM4, .rcc = RCC_APB1(TIM4) },
{ .TIMx = TIM5, .rcc = RCC_APB1(TIM5) },
{ .TIMx = TIM6, .rcc = RCC_APB1(TIM6) },
{ .TIMx = TIM7, .rcc = RCC_APB1(TIM7) },
{ .TIMx = TIM8, .rcc = RCC_APB2(TIM8) },
{ .TIMx = TIM9, .rcc = RCC_APB2(TIM9) },
{ .TIMx = TIM10, .rcc = RCC_APB2(TIM10) },
{ .TIMx = TIM11, .rcc = RCC_APB2(TIM11) },
{ .TIMx = TIM12, .rcc = RCC_APB1(TIM12) },
{ .TIMx = TIM13, .rcc = RCC_APB1(TIM13) },
{ .TIMx = TIM14, .rcc = RCC_APB1(TIM14) },
};
void TIM_SelectOCxM_NoDisable(TIM_TypeDef* TIMx, uint16_t TIM_Channel, uint16_t TIM_OCMode)
{
uint32_t tmp = 0;
@ -65,3 +84,4 @@ void TIM_SelectOCxM_NoDisable(TIM_TypeDef* TIMx, uint16_t TIM_Channel, uint16_t
*(__IO uint32_t *) tmp |= (uint16_t)(TIM_OCMode << 8);
}
}

View File

@ -152,9 +152,5 @@
#define TARGET_IO_PORTF (BIT(0)|BIT(1)|BIT(4))
#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(15) | TIM_N(17))
#define TIMER_APB1_PERIPHERALS (RCC_APB1Periph_TIM2 | RCC_APB1Periph_TIM3)
#define TIMER_APB2_PERIPHERALS (RCC_APB2Periph_TIM1 | RCC_APB2Periph_TIM15 | RCC_APB2Periph_TIM17)
#define TIMER_AHB_PERIPHERALS (RCC_AHBPeriph_GPIOA | RCC_AHBPeriph_GPIOB)
#define USED_TIMERS ( TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(15) | TIM_N(17) )

View File

@ -202,6 +202,5 @@
#define TARGET_IO_PORTC 0xffff
#define TARGET_IO_PORTD (BIT(2))
#define USED_TIMERS ( TIM_N(1) | TIM_N(3) | TIM_N(4) | TIM_N(5) | TIM_N(8))
#define TIMER_APB1_PERIPHERALS (RCC_APB1Periph_TIM3 | RCC_APB1Periph_TIM4 | RCC_APB1Periph_TIM5 | RCC_AHB1Periph_GPIOA | RCC_AHB1Periph_GPIOB | RCC_AHB1Periph_GPIOC)
#define TIMER_APB2_PERIPHERALS (RCC_APB2Periph_TIM1 | RCC_APB2Periph_TIM8)
#define USED_TIMERS ( TIM_N(1) | TIM_N(3) | TIM_N(4) | TIM_N(5) | TIM_N(8) )

View File

@ -52,11 +52,11 @@ const uint16_t airPWM[] = {
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
{ 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
{ 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

@ -149,5 +149,3 @@
#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)
#define TIMER_APB2_PERIPHERALS (RCC_APB2Periph_TIM8 | RCC_APB2Periph_TIM9)

View File

@ -135,9 +135,6 @@
// IO - from schematics
#define TARGET_IO_PORTA 0xffff
#define TARGET_IO_PORTB 0xffff
#define TARGET_IO_PORTC (BIT(14))
#define TARGET_IO_PORTC ( BIT(14) )
#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4))
#define TIMER_APB1_PERIPHERALS (RCC_APB1Periph_TIM2 | RCC_APB1Periph_TIM3 | RCC_APB1Periph_TIM4)
#define TIMER_APB2_PERIPHERALS (RCC_APB2Periph_TIM1 | RCC_APB2Periph_GPIOA | RCC_APB2Periph_GPIOB)
#define USED_TIMERS ( TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) )

View File

@ -133,7 +133,3 @@
#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))
#define TIMER_APB1_PERIPHERALS (RCC_APB1Periph_TIM2 | RCC_APB1Periph_TIM3 | RCC_APB1Periph_TIM4)
#define TIMER_APB2_PERIPHERALS (RCC_APB2Periph_TIM1 | RCC_APB2Periph_TIM8 | RCC_APB2Periph_TIM15 | RCC_APB2Periph_TIM16 | RCC_APB2Periph_TIM17)
#define TIMER_AHB_PERIPHERALS (RCC_AHBPeriph_GPIOA | RCC_AHBPeriph_GPIOB | RCC_AHBPeriph_GPIOC | RCC_AHBPeriph_GPIOD | RCC_AHBPeriph_GPIOF)

View File

@ -68,8 +68,4 @@
#define TARGET_IO_PORTB 0xffff
#define TARGET_IO_PORTC (BIT(13)|BIT(14)|BIT(15))
#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4))
#define TIMER_APB1_PERIPHERALS (RCC_APB1Periph_TIM2 | RCC_APB1Periph_TIM3 | RCC_APB1Periph_TIM4)
#define TIMER_APB2_PERIPHERALS (RCC_APB2Periph_TIM1 | RCC_APB2Periph_GPIOA | RCC_APB2Periph_GPIOB)
#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4))

View File

@ -180,7 +180,3 @@
#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(15))
#define TIMER_APB1_PERIPHERALS (RCC_APB1Periph_TIM2 | RCC_APB1Periph_TIM3)
#define TIMER_APB2_PERIPHERALS (RCC_APB2Periph_TIM1 | RCC_APB2Periph_TIM15)
#define TIMER_AHB_PERIPHERALS (RCC_AHBPeriph_GPIOA | RCC_AHBPeriph_GPIOC)

View File

@ -73,6 +73,12 @@
#define SPI2_MOSI_PIN PB15
#define SPI2_MOSI_PIN_SOURCE GPIO_PinSource15
#define USE_FLASHFS
#define USE_FLASH_M25P16
#define M25P16_SPI_SHARED
#define M25P16_CS_PIN PC15
#define M25P16_SPI_INSTANCE SPI2
// timer definitions in drivers/timer.c
// channel mapping in drivers/pwm_mapping.c
// only 6 outputs available on hardware
@ -188,9 +194,5 @@
#define TARGET_IO_PORTC (BIT(13)|BIT(14)|BIT(15))
#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(4) | TIM_N(15))
#define TIMER_APB1_PERIPHERALS (RCC_APB1Periph_TIM2 | RCC_APB1Periph_TIM3 | RCC_APB1Periph_TIM4)
#define TIMER_APB2_PERIPHERALS (RCC_APB2Periph_TIM1 | RCC_APB2Periph_TIM15)
#define TIMER_AHB_PERIPHERALS (RCC_AHBPeriph_GPIOA | RCC_AHBPeriph_GPIOB)
#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(15))

View File

@ -1,5 +1,5 @@
F3_TARGETS += $(TARGET)
FEATURES = VCP
FEATURES = VCP ONBOARDFLASH
TARGET_SRC = \
drivers/accgyro_mpu.c \

View File

@ -125,8 +125,5 @@
#define TARGET_IO_PORTD (BIT(0)|BIT(1)|BIT(2))
#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4))
#define TIMER_APB1_PERIPHERALS (RCC_APB1Periph_TIM2 | RCC_APB1Periph_TIM3 | RCC_APB1Periph_TIM4)
#define TIMER_APB2_PERIPHERALS (RCC_APB2Periph_TIM1 | RCC_APB2Periph_GPIOA | RCC_APB2Periph_GPIOB)
#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4))

View File

@ -202,9 +202,5 @@
#define TARGET_IO_PORTD 0xffff
#define TARGET_IO_PORTF (BIT(4))
#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(16) |TIM_N(17))
#define TIMER_APB1_PERIPHERALS (RCC_APB1Periph_TIM2 | RCC_APB1Periph_TIM3 | RCC_APB1Periph_TIM4)
#define TIMER_APB2_PERIPHERALS (RCC_APB2Periph_TIM1 | RCC_APB2Periph_TIM16 | RCC_APB2Periph_TIM17)
#define TIMER_AHB_PERIPHERALS (RCC_AHBPeriph_GPIOA | RCC_AHBPeriph_GPIOB)
#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(16) |TIM_N(17))

View File

@ -163,6 +163,3 @@
#define USED_TIMERS ( TIM_N(2) | TIM_N(3) | TIM_N(8) | TIM_N(9))
#define TIMER_APB1_PERIPHERALS (RCC_APB1Periph_TIM2 | RCC_APB1Periph_TIM3 | RCC_AHB1Periph_GPIOA | RCC_AHB1Periph_GPIOB | RCC_AHB1Periph_GPIOC)
#define TIMER_APB2_PERIPHERALS (RCC_APB2Periph_TIM8 | RCC_APB2Periph_TIM9)

View File

@ -138,7 +138,3 @@
#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(15) | TIM_N(16) |TIM_N(17))
#define TIMER_APB1_PERIPHERALS (RCC_APB1Periph_TIM2 | RCC_APB1Periph_TIM3 | RCC_APB1Periph_TIM4)
#define TIMER_APB2_PERIPHERALS (RCC_APB2Periph_TIM1 | RCC_APB2Periph_TIM15 | RCC_APB2Periph_TIM16 | RCC_APB2Periph_TIM17)
#define TIMER_AHB_PERIPHERALS (RCC_AHBPeriph_GPIOA | RCC_AHBPeriph_GPIOB)

View File

@ -100,9 +100,4 @@
#define TARGET_IO_PORTD 0xffff
#define TARGET_IO_PORTF (BIT(4))
#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))
#define TIMER_APB2_PERIPHERALS (RCC_APB2Periph_TIM1 | RCC_APB2Periph_TIM15 | RCC_APB2Periph_TIM17 | RCC_APB2Periph_TIM16 | RCC_APB2Periph_TIM8)
#define TIMER_APB1_PERIPHERALS (RCC_APB1Periph_TIM2 | RCC_APB1Periph_TIM3 | RCC_APB1Periph_TIM4)
#define TIMER_AHB_PERIPHERALS (RCC_AHBPeriph_GPIOA | RCC_AHBPeriph_GPIOB)
#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

@ -150,7 +150,3 @@
#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(15))
#define TIMER_APB1_PERIPHERALS (RCC_APB1Periph_TIM2 | RCC_APB1Periph_TIM3)
#define TIMER_APB2_PERIPHERALS (RCC_APB2Periph_TIM1 | RCC_APB2Periph_TIM15)
#define TIMER_AHB_PERIPHERALS (RCC_AHBPeriph_GPIOA | RCC_AHBPeriph_GPIOC)

View File

@ -186,8 +186,5 @@
// !!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 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

@ -194,11 +194,7 @@
// IO - assuming all IOs on 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_PORTC ( BIT(13) | BIT(14) | BIT(15) )
#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4))
#define TIMER_APB1_PERIPHERALS (RCC_APB1Periph_TIM2 | RCC_APB1Periph_TIM3 | RCC_APB1Periph_TIM4)
#define TIMER_APB2_PERIPHERALS (RCC_APB2Periph_TIM1 | RCC_APB2Periph_GPIOA | RCC_APB2Periph_GPIOB)
#define USED_TIMERS ( TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) )

View File

@ -110,8 +110,4 @@
#define TARGET_IO_PORTD (BIT(2))
#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4))
#define TIMER_APB1_PERIPHERALS (RCC_APB1Periph_TIM2 | RCC_APB1Periph_TIM3 | RCC_APB1Periph_TIM4)
#define TIMER_APB2_PERIPHERALS (RCC_APB2Periph_TIM1 | RCC_APB2Periph_GPIOA | RCC_APB2Periph_GPIOB)
#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4))

View File

@ -167,7 +167,3 @@
#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

@ -141,8 +141,6 @@
#define TARGET_IO_PORTD (BIT(0)|BIT(1)|BIT(2))
#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4))
#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4))
#define TIMER_APB1_PERIPHERALS (RCC_APB1Periph_TIM2 | RCC_APB1Periph_TIM3 | RCC_APB1Periph_TIM4)
#define TIMER_APB2_PERIPHERALS (RCC_APB2Periph_TIM1 | RCC_APB2Periph_GPIOA | RCC_APB2Periph_GPIOB)

View File

@ -134,7 +134,3 @@
#define TARGET_IO_PORTD 0xffff
#define USED_TIMERS ( TIM_N(2) | TIM_N(3) | TIM_N(5) | TIM_N(12) | TIM_N(8) | TIM_N(9))
#define TIMER_APB1_PERIPHERALS (RCC_APB1Periph_TIM2 | RCC_APB1Periph_TIM3 | RCC_APB1Periph_TIM5 | RCC_APB1Periph_TIM12 | RCC_AHB1Periph_GPIOA | RCC_AHB1Periph_GPIOB | RCC_AHB1Periph_GPIOC)
#define TIMER_APB2_PERIPHERALS (RCC_APB2Periph_TIM8 | RCC_APB2Periph_TIM9)

View File

@ -120,5 +120,3 @@
#define USED_TIMERS ( TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(5) )
#define TIMER_APB1_PERIPHERALS (RCC_APB1Periph_TIM2 | RCC_APB1Periph_TIM3 | RCC_APB1Periph_TIM4 | RCC_APB1Periph_TIM5 | RCC_AHB1Periph_GPIOA | RCC_AHB1Periph_GPIOB)
#define TIMER_APB2_PERIPHERALS (RCC_APB2Periph_TIM1)

View File

@ -155,9 +155,4 @@
#define TARGET_IO_PORTF (BIT(0)|BIT(1)|BIT(4))
#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(15) | TIM_N(16) |TIM_N(17))
#define TIMER_APB1_PERIPHERALS (RCC_APB1Periph_TIM2 | RCC_APB1Periph_TIM3 | RCC_APB1Periph_TIM4)
#define TIMER_APB2_PERIPHERALS (RCC_APB2Periph_TIM1 | RCC_APB2Periph_TIM15 | RCC_APB2Periph_TIM16 | RCC_APB2Periph_TIM17)
#define TIMER_AHB_PERIPHERALS (RCC_AHBPeriph_GPIOA | RCC_AHBPeriph_GPIOB)
#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(15) | TIM_N(16) |TIM_N(17))

View File

@ -136,7 +136,3 @@
#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(15) | TIM_N(16) |TIM_N(17))
#define TIMER_APB1_PERIPHERALS (RCC_APB1Periph_TIM2 | RCC_APB1Periph_TIM3)
#define TIMER_APB2_PERIPHERALS (RCC_APB2Periph_TIM1 | RCC_APB2Periph_TIM15 | RCC_APB2Periph_TIM16 | RCC_APB2Periph_TIM17)
#define TIMER_AHB_PERIPHERALS (RCC_AHBPeriph_GPIOA | RCC_AHBPeriph_GPIOB)

View File

@ -169,9 +169,6 @@
#define TARGET_IO_PORTF (BIT(0)|BIT(1)|BIT(4))
#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(15) | TIM_N(17))
#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(15) | TIM_N(17))
#define TIMER_APB1_PERIPHERALS (RCC_APB1Periph_TIM2 | RCC_APB1Periph_TIM3)
#define TIMER_APB2_PERIPHERALS (RCC_APB2Periph_TIM1 | RCC_APB2Periph_TIM15 | RCC_APB2Periph_TIM17)
#define TIMER_AHB_PERIPHERALS (RCC_AHBPeriph_GPIOA | RCC_AHBPeriph_GPIOB)

View File

@ -163,9 +163,6 @@
#define TARGET_IO_PORTC (BIT(13)|BIT(14)|BIT(15))
#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(4) | TIM_N(15) | TIM_N(16) |TIM_N(17))
#define USED_TIMERS ( TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(15) | TIM_N(16) | TIM_N(17) )
#define TIMER_APB1_PERIPHERALS (RCC_APB1Periph_TIM2 | RCC_APB1Periph_TIM3 | RCC_APB1Periph_TIM4)
#define TIMER_APB2_PERIPHERALS (RCC_APB2Periph_TIM1 | RCC_APB2Periph_TIM15 | RCC_APB2Periph_TIM16 | RCC_APB2Periph_TIM17)
#define TIMER_AHB_PERIPHERALS (RCC_AHBPeriph_GPIOA | RCC_AHBPeriph_GPIOB)

View File

@ -200,9 +200,5 @@
#define TARGET_IO_PORTF (BIT(0)|BIT(1)|BIT(4))
#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(8) | TIM_N(15))
#define TIMER_APB1_PERIPHERALS (RCC_APB1Periph_TIM2 | RCC_APB1Periph_TIM3)
#define TIMER_APB2_PERIPHERALS (RCC_APB2Periph_TIM1 | RCC_APB2Periph_TIM8 | RCC_APB2Periph_TIM15)
#define TIMER_AHB_PERIPHERALS (RCC_AHBPeriph_GPIOA | RCC_AHBPeriph_GPIOB)
#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(8) | TIM_N(15))

View File

@ -215,7 +215,3 @@
#define TARGET_IO_PORTF (BIT(0)|BIT(1)|BIT(4))
#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(15) | TIM_N(16) |TIM_N(17))
#define TIMER_APB1_PERIPHERALS (RCC_APB1Periph_TIM2 | RCC_APB1Periph_TIM3 | RCC_APB1Periph_TIM4)
#define TIMER_APB2_PERIPHERALS (RCC_APB2Periph_TIM1 | RCC_APB2Periph_TIM15 | RCC_APB2Periph_TIM16 | RCC_APB2Periph_TIM17)
#define TIMER_AHB_PERIPHERALS (RCC_AHBPeriph_GPIOA | RCC_AHBPeriph_GPIOB)

View File

@ -190,7 +190,3 @@
#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(8) | TIM_N(16) | TIM_N(17))
#define TIMER_APB1_PERIPHERALS (RCC_APB1Periph_TIM2 | RCC_APB1Periph_TIM3 | RCC_APB1Periph_TIM4)
#define TIMER_APB2_PERIPHERALS (RCC_APB2Periph_TIM1 | RCC_APB2Periph_TIM8 | RCC_APB2Periph_TIM16 | RCC_APB2Periph_TIM17)
#define TIMER_AHB_PERIPHERALS (RCC_AHBPeriph_GPIOA | RCC_AHBPeriph_GPIOB | RCC_AHBPeriph_GPIOC | RCC_AHBPeriph_GPIOD)