Skip to content

Commit

Permalink
Remove USABLE_TIMER_CHANNEL_COUNT and USED_TIMERS definitions
Browse files Browse the repository at this point in the history
  • Loading branch information
digitalentity committed May 8, 2018
1 parent ba19ec8 commit de34c58
Show file tree
Hide file tree
Showing 117 changed files with 168 additions and 286 deletions.
2 changes: 1 addition & 1 deletion src/main/drivers/pwm_esc_detect.c
Original file line number Diff line number Diff line change
Expand Up @@ -36,7 +36,7 @@ uint8_t hardwareMotorType = MOTOR_UNKNOWN;

void detectBrushedESC(void)
{
for (int i = 0; i < USABLE_TIMER_CHANNEL_COUNT; i++) {
for (int i = 0; i < timerHardwareCount; i++) {
if (timerHardware[i].usageFlags & TIM_USE_MC_MOTOR) {
IO_t MotorDetectPin = IOGetByTag(timerHardware[i].tag);
IOInit(MotorDetectPin, OWNER_SYSTEM, RESOURCE_INPUT, 0);
Expand Down
15 changes: 8 additions & 7 deletions src/main/drivers/pwm_mapping.c
Original file line number Diff line number Diff line change
Expand Up @@ -21,15 +21,15 @@

#include "platform.h"

#include "common/memory.h"
#include "drivers/io.h"
#include "io_impl.h"
#include "timer.h"

#include "drivers/io_impl.h"
#include "drivers/timer.h"
#include "drivers/logging.h"

#include "pwm_output.h"
#include "pwm_mapping.h"
#include "rx_pwm.h"
#include "drivers/pwm_output.h"
#include "drivers/pwm_mapping.h"
#include "drivers/rx_pwm.h"

enum {
MAP_TO_NONE,
Expand Down Expand Up @@ -59,12 +59,13 @@ bool CheckGPIOPinSource(ioTag_t tag, GPIO_TypeDef *gpio, uint16_t pin)
pwmIOConfiguration_t *pwmInit(drv_pwm_config_t *init)
{
memset(&pwmIOConfiguration, 0, sizeof(pwmIOConfiguration));
pwmIOConfiguration.ioConfigurations = memAllocate(sizeof(pwmPortConfiguration_t) * timerHardwareCount);

#if defined(USE_RX_PWM) || defined(USE_RX_PPM)
int channelIndex = 0;
#endif

for (int timerIndex = 0; timerIndex < USABLE_TIMER_CHANNEL_COUNT; timerIndex++) {
for (int timerIndex = 0; timerIndex < timerHardwareCount; timerIndex++) {
const timerHardware_t *timerHardwarePtr = &timerHardware[timerIndex];
int type = MAP_TO_NONE;

Expand Down
2 changes: 1 addition & 1 deletion src/main/drivers/pwm_mapping.h
Original file line number Diff line number Diff line change
Expand Up @@ -97,7 +97,7 @@ typedef struct pwmIOConfiguration_s {
uint8_t ioCount;
uint8_t pwmInputCount;
uint8_t ppmInputCount;
pwmPortConfiguration_t ioConfigurations[USABLE_TIMER_CHANNEL_COUNT];
pwmPortConfiguration_t * ioConfigurations;
} pwmIOConfiguration_t;

// This indexes into the read-only hardware definition structure, timerHardware_t
Expand Down
2 changes: 1 addition & 1 deletion src/main/drivers/rx_pwm.c
Original file line number Diff line number Diff line change
Expand Up @@ -368,7 +368,7 @@ void pwmInConfig(const timerHardware_t *timerHardwarePtr, uint8_t channel)

void ppmAvoidPWMTimerClash(const timerHardware_t *timerHardwarePtr, uint8_t motorPwmProtocol)
{
for (int timerIndex = 0; timerIndex < USABLE_TIMER_CHANNEL_COUNT; timerIndex++) {
for (int timerIndex = 0; timerIndex < timerHardwareCount; timerIndex++) {
// If PPM input timer is also mapped to motor - set PPM divisor accordingly
if (((timerHardware[timerIndex].usageFlags & (TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR)) == 0) || timerHardware[timerIndex].tim != timerHardwarePtr->tim)
continue;
Expand Down
16 changes: 3 additions & 13 deletions src/main/drivers/timer.c
Original file line number Diff line number Diff line change
Expand Up @@ -47,12 +47,6 @@

timerConfig_t * timerConfig[HARDWARE_TIMER_DEFINITION_COUNT];

typedef struct {
channelType_t type;
} timerChannelInfo_t;

timerChannelInfo_t timerChannelInfo[USABLE_TIMER_CHANNEL_COUNT];

// return index of timer in timer table. Lowest timer has index 0
uint8_t lookupTimerIndex(const TIM_TypeDef *tim)
{
Expand Down Expand Up @@ -136,6 +130,7 @@ static void timerChConfig_UpdateOverflow(timerConfig_t *cfg, TIM_TypeDef *tim) {

timerConfig_t * timerGetConfigContext(int timerIndex)
{
// If timer context does not exist - allocate memory
if (timerConfig[timerIndex] == NULL) {
timerConfig[timerIndex] = memAllocate(sizeof(timerConfig_t));
}
Expand Down Expand Up @@ -191,16 +186,11 @@ void timerInit(void)
memset(timerConfig, 0, sizeof (timerConfig));

/* enable the timer peripherals */
for (int i = 0; i < USABLE_TIMER_CHANNEL_COUNT; i++) {
for (int i = 0; i < timerHardwareCount; i++) {
unsigned timer = lookupTimerIndex(timerHardware[i].tim);

RCC_ClockCmd(timerDefinitions[timer].rcc, ENABLE);
}

// initialize timer channel structures
for (int i = 0; i < USABLE_TIMER_CHANNEL_COUNT; i++) {
timerChannelInfo[i].type = TYPE_FREE;
}
}

const timerHardware_t *timerGetByTag(ioTag_t tag, timerUsageFlag_e flag)
Expand All @@ -209,7 +199,7 @@ const timerHardware_t *timerGetByTag(ioTag_t tag, timerUsageFlag_e flag)
return NULL;
}

for (int i = 0; i < USABLE_TIMER_CHANNEL_COUNT; i++) {
for (int i = 0; i < timerHardwareCount; i++) {
if (timerHardware[i].tag == tag) {
if (timerHardware[i].usageFlags & flag || flag == 0) {
return &timerHardware[i];
Expand Down
1 change: 1 addition & 0 deletions src/main/drivers/timer.h
Original file line number Diff line number Diff line change
Expand Up @@ -114,6 +114,7 @@ enum {
#endif

extern const timerHardware_t timerHardware[];
extern const int timerHardwareCount;
extern const timerDef_t timerDefinitions[];

typedef enum {
Expand Down
2 changes: 1 addition & 1 deletion src/main/fc/fc_msp.c
Original file line number Diff line number Diff line change
Expand Up @@ -1349,7 +1349,7 @@ static bool mspFcProcessOutCommand(uint16_t cmdMSP, sbuf_t *dst, mspPostProcessF
#endif

case MSP2_INAV_OUTPUT_MAPPING:
for (uint8_t i = 0; i < USABLE_TIMER_CHANNEL_COUNT; ++i)
for (uint8_t i = 0; i < timerHardwareCount; ++i)
if (!(timerHardware[i].usageFlags & (TIM_USE_PPM | TIM_USE_PWM)))
sbufWriteU8(dst, timerHardware[i].usageFlags);
break;
Expand Down
4 changes: 3 additions & 1 deletion src/main/target/AIRBOTF4/target.c
Original file line number Diff line number Diff line change
Expand Up @@ -23,7 +23,7 @@
#include "drivers/timer.h"
#include "drivers/bus.h"

const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
const timerHardware_t timerHardware[] = {
{ TIM12, IO_TAG(PB14), TIM_Channel_1, 0, IOCFG_AF_PP_PD, GPIO_AF_TIM12, TIM_USE_PPM | TIM_USE_PWM }, // PPM / S.BUS input, above MOTOR1
{ TIM12, IO_TAG(PB15), TIM_Channel_2, 0, IOCFG_AF_PP_PD, GPIO_AF_TIM12, 0 }, // Connected: small CH2 pad, not used as PWM, definition inherited from REVO target - GPIO_PartialRemap_TIM3
{ TIM8, IO_TAG(PC6), TIM_Channel_1, 0, IOCFG_AF_PP_PD, GPIO_AF_TIM8, 0 }, // Connected: UART6 TX, not used as PWM, definition inherited from REVO target
Expand All @@ -37,3 +37,5 @@ const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
{ TIM5, IO_TAG(PA1), TIM_Channel_2, 1, IOCFG_AF_PP_PD, GPIO_AF_TIM5, TIM_USE_MC_MOTOR | TIM_USE_MC_SERVO | TIM_USE_FW_SERVO }, // MOTOR_5 - GPIO_PartialRemap_TIM3
{ TIM1, IO_TAG(PA8), TIM_Channel_1, 1, IOCFG_AF_PP_PD, GPIO_AF_TIM1, TIM_USE_MC_MOTOR | TIM_USE_MC_SERVO | TIM_USE_FW_SERVO }, // MOTOR_6
};

const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]);
3 changes: 0 additions & 3 deletions src/main/target/AIRBOTF4/target.h
Original file line number Diff line number Diff line change
Expand Up @@ -155,6 +155,3 @@
#define TARGET_IO_PORTB 0xffff
#define TARGET_IO_PORTC 0xffff
#define TARGET_IO_PORTD 0xffff

#define USABLE_TIMER_CHANNEL_COUNT 12
#define USED_TIMERS ( TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(5) | TIM_N(12) | TIM_N(8) | TIM_N(9) )
4 changes: 3 additions & 1 deletion src/main/target/AIRHEROF3/target.c
Original file line number Diff line number Diff line change
Expand Up @@ -24,7 +24,7 @@
#include "drivers/timer.h"
#include "drivers/bus.h"

const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
const timerHardware_t timerHardware[] = {
{ TIM2, IO_TAG(PA0), TIM_Channel_1, 0, IOCFG_AF_PP, GPIO_AF_1, TIM_USE_PPM | TIM_USE_PWM }, // PWM1 - RC1
{ TIM2, IO_TAG(PA1), TIM_Channel_2, 0, IOCFG_AF_PP, GPIO_AF_1, TIM_USE_PWM }, // PWM2 - RC2
{ TIM2, IO_TAG(PA2), TIM_Channel_3, 0, IOCFG_AF_PP, GPIO_AF_1, TIM_USE_PWM }, // PWM3 - RC3
Expand All @@ -45,3 +45,5 @@ const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
{ TIM8, IO_TAG(PB9), TIM_Channel_3, 1, IOCFG_AF_PP, GPIO_AF_10, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO } // PWM14 - OUT6
#endif
};

const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]);
4 changes: 0 additions & 4 deletions src/main/target/AIRHEROF3/target.h
Original file line number Diff line number Diff line change
Expand Up @@ -116,11 +116,9 @@

#define MAX_PWM_OUTPUT_PORTS 8
#define TARGET_MOTOR_COUNT 4
#define USABLE_TIMER_CHANNEL_COUNT 10
#else
#define MAX_PWM_OUTPUT_PORTS 10
#define TARGET_MOTOR_COUNT 6
#define USABLE_TIMER_CHANNEL_COUNT 12
#endif

#define USE_SPEKTRUM_BIND
Expand All @@ -134,5 +132,3 @@
#define TARGET_IO_PORTC 0xffff
#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) )
3 changes: 2 additions & 1 deletion src/main/target/ALIENFLIGHTF3/target.c
Original file line number Diff line number Diff line change
Expand Up @@ -22,7 +22,7 @@
#include "drivers/pwm_mapping.h"
#include "drivers/timer.h"

const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
const timerHardware_t timerHardware[] = {
// up to 10 Motor Outputs
{ TIM15, IO_TAG(PB15), TIM_Channel_2, 1, IOCFG_AF_PP, GPIO_AF_1, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR }, // PWM1 - PB15 - TIM1_CH3N, TIM15_CH1N, *TIM15_CH2
{ TIM15, IO_TAG(PB14), TIM_Channel_1, 1, IOCFG_AF_PP, GPIO_AF_1, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR }, // PWM2 - PB14 - TIM1_CH2N, *TIM15_CH1
Expand All @@ -39,3 +39,4 @@ const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
{ TIM2, IO_TAG(PA3), TIM_Channel_4, 0, IOCFG_AF_PP_PD, GPIO_AF_1, TIM_USE_PPM } // PPM - PA3 - TIM2_CH4, TIM15_CH2 - PWM13
};

const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]);
4 changes: 0 additions & 4 deletions src/main/target/ALIENFLIGHTF3/target.h
Original file line number Diff line number Diff line change
Expand Up @@ -139,7 +139,3 @@
#define TARGET_IO_PORTC 0xffff
#define TARGET_IO_PORTD (BIT(2))
#define TARGET_IO_PORTF (BIT(0)|BIT(1)|BIT(4))

#define USABLE_TIMER_CHANNEL_COUNT 11
#define USED_TIMERS ( TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(15) | TIM_N(17) )

4 changes: 3 additions & 1 deletion src/main/target/ALIENFLIGHTF4/target.c
Original file line number Diff line number Diff line change
Expand Up @@ -22,7 +22,7 @@
#include "drivers/pwm_mapping.h"
#include "drivers/timer.h"

const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
const timerHardware_t timerHardware[] = {
{ TIM1, IO_TAG(PA8), TIM_Channel_1, 0, IOCFG_IPD, GPIO_AF_TIM1, TIM_USE_PPM | TIM_USE_PWM }, // PWM1 - PA8 RC1
{ TIM3, IO_TAG(PB0), TIM_Channel_3, 0, IOCFG_IPD, GPIO_AF_TIM3, TIM_USE_PWM }, // PWM2 - PB0 RC2
{ TIM3, IO_TAG(PB1), TIM_Channel_4, 0, IOCFG_IPD, GPIO_AF_TIM3, TIM_USE_PWM }, // PWM3 - PB1 RC3
Expand All @@ -37,3 +37,5 @@ const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
{ TIM8, IO_TAG(PC8), TIM_Channel_3, 1, IOCFG_AF_PP, GPIO_AF_TIM8, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO }, // PWM13 - PC8 OUT7
{ TIM8, IO_TAG(PC9), TIM_Channel_4, 1, IOCFG_AF_PP, GPIO_AF_TIM8, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO }, // PWM13 - PC9 OUT8
};

const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]);
4 changes: 0 additions & 4 deletions src/main/target/ALIENFLIGHTF4/target.h
Original file line number Diff line number Diff line change
Expand Up @@ -201,7 +201,3 @@
#define TARGET_IO_PORTB 0xffff
#define TARGET_IO_PORTC 0xffff
#define TARGET_IO_PORTD (BIT(2))

#define USABLE_TIMER_CHANNEL_COUNT 13
#define USED_TIMERS ( TIM_N(1) | TIM_N(3) | TIM_N(4) | TIM_N(5) | TIM_N(8) )

4 changes: 3 additions & 1 deletion src/main/target/ALIENFLIGHTNGF7/target.c
Original file line number Diff line number Diff line change
Expand Up @@ -25,7 +25,7 @@
#define TIM_EN TIMER_OUTPUT_ENABLED
#define TIM_EN_N TIMER_OUTPUT_ENABLED | TIMER_OUTPUT_N_CHANNEL

const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
const timerHardware_t timerHardware[] = {
{ TIM1, IO_TAG(PA8), TIM_CHANNEL_1, 0, IOCFG_AF_PP_PD, GPIO_AF1_TIM1, TIM_USE_PPM | TIM_USE_PWM | TIM_USE_LED }, // PWM1 - PA8 RC1
{ TIM3, IO_TAG(PB1), TIM_CHANNEL_4, 0, IOCFG_AF_PP_PD, GPIO_AF2_TIM3, TIM_USE_PWM | TIM_USE_MC_SERVO }, // PWM2 - PB1 RC2
{ TIM12, IO_TAG(PB15), TIM_CHANNEL_2, 0, IOCFG_AF_PP_PD, GPIO_AF9_TIM12, TIM_USE_PWM | TIM_USE_MC_SERVO }, // PWM3 - PA15 RC3
Expand All @@ -40,3 +40,5 @@ const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
{ TIM8, IO_TAG(PC8), TIM_CHANNEL_3, TIM_EN, IOCFG_AF_PP_PD, GPIO_AF3_TIM8, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO }, // PWM13 - PC8 OUT7
{ TIM8, IO_TAG(PC9), TIM_CHANNEL_4, TIM_EN, IOCFG_AF_PP_PD, GPIO_AF3_TIM8, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO }, // PWM14 - PC9 OUT8
};

const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]);
3 changes: 0 additions & 3 deletions src/main/target/ALIENFLIGHTNGF7/target.h
Original file line number Diff line number Diff line change
Expand Up @@ -209,6 +209,3 @@
#define TARGET_IO_PORTB 0xffff
#define TARGET_IO_PORTC 0xffff
#define TARGET_IO_PORTD (BIT(2))

#define USABLE_TIMER_CHANNEL_COUNT 13
#define USED_TIMERS ( TIM_N(1) | TIM_N(3) | TIM_N(4) | TIM_N(5) | TIM_N(8) | TIM_N(12) )
4 changes: 3 additions & 1 deletion src/main/target/ANYFC/target.c
Original file line number Diff line number Diff line change
Expand Up @@ -22,7 +22,7 @@
#include "drivers/pwm_mapping.h"
#include "drivers/timer.h"

const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
const timerHardware_t timerHardware[] = {
{ TIM12, IO_TAG(PB14), TIM_Channel_1, 0, IOCFG_AF_PP_PD, GPIO_AF_TIM12, TIM_USE_PPM | TIM_USE_PWM }, // S1_IN
{ TIM12, IO_TAG(PB15), TIM_Channel_2, 0, IOCFG_AF_PP_PD, GPIO_AF_TIM12, TIM_USE_PWM }, // S2_IN
{ TIM8, IO_TAG(PC6), TIM_Channel_1, 0, IOCFG_AF_PP_PD, GPIO_AF_TIM8, TIM_USE_PWM }, // S3_IN
Expand All @@ -41,3 +41,5 @@ const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
{ TIM3, IO_TAG(PB5), TIM_Channel_2, 1, IOCFG_AF_PP_PD, GPIO_AF_TIM3, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO }, // S8_OUT 14
{ TIM3, IO_TAG(PB4), TIM_Channel_1, 1, IOCFG_AF_PP_PD, GPIO_AF_TIM3, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO }, // S9_OUT 15
};

const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]);
3 changes: 0 additions & 3 deletions src/main/target/ANYFC/target.h
Original file line number Diff line number Diff line change
Expand Up @@ -141,6 +141,3 @@
#define TARGET_IO_PORTB 0xffff
#define TARGET_IO_PORTC 0xffff
#define TARGET_IO_PORTD 0xffff

#define USABLE_TIMER_CHANNEL_COUNT 16
#define USED_TIMERS ( TIM_N(2) | TIM_N(3) | TIM_N(5) | TIM_N(12) | TIM_N(8) | TIM_N(9))
6 changes: 4 additions & 2 deletions src/main/target/ANYFCF7/target.c
Original file line number Diff line number Diff line change
Expand Up @@ -22,7 +22,7 @@
#include "drivers/pwm_mapping.h"
#include "drivers/timer.h"

const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
const timerHardware_t timerHardware[] = {
{ TIM12, IO_TAG(PB14), TIM_CHANNEL_1, 0, IOCFG_AF_PP_PD, GPIO_AF9_TIM12, TIM_USE_PPM | TIM_USE_PWM }, // S1_IN 1
{ TIM12, IO_TAG(PB15), TIM_CHANNEL_2, 0, IOCFG_AF_PP_PD, GPIO_AF9_TIM12, TIM_USE_PWM }, // S2_IN 2
{ TIM8, IO_TAG(PC6), TIM_CHANNEL_1, 0, IOCFG_AF_PP_PD, GPIO_AF3_TIM8, TIM_USE_PWM | TIM_USE_MC_SERVO }, // S3_IN 3
Expand All @@ -43,7 +43,7 @@ const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
};

// ALTERNATE LAYOUT
//const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
//const timerHardware_t timerHardware[] = {
// { TIM12, IO_TAG(PB14), TIM_CHANNEL_1, TIM8_BRK_TIM12_IRQn, 0, IOCFG_AF_PP_PD, GPIO_AF9_TIM12 }, // S1_IN
// { TIM12, IO_TAG(PB15), TIM_CHANNEL_2, TIM8_BRK_TIM12_IRQn, 0, IOCFG_AF_PP_PD, GPIO_AF9_TIM12 }, // S2_IN
// { TIM8, IO_TAG(PC6), TIM_CHANNEL_1, TIM8_CC_IRQn, 0, IOCFG_AF_PP_PD, GPIO_AF3_TIM8 }, // S3_IN
Expand All @@ -62,3 +62,5 @@ const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
// { TIM3, IO_TAG(PB4), TIM_CHANNEL_1, TIM3_IRQn, 1, IOCFG_AF_PP_PD, GPIO_AF2_TIM3 }, // S9_OUT
// { TIM10, IO_TAG(PB8), TIM_CHANNEL_1, TIM1_UP_TIM10_IRQn, 1, IOCFG_AF_PP_PD, GPIO_AF3_TIM10 }, // S10_OUT
//};

const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]);
4 changes: 0 additions & 4 deletions src/main/target/ANYFCF7/target.h
Original file line number Diff line number Diff line change
Expand Up @@ -71,8 +71,6 @@
#define USE_RANGEFINDER_HCSR04_I2C
#define RANGEFINDER_I2C_BUS BUS_I2C2

#define USABLE_TIMER_CHANNEL_COUNT 16

#define USE_VCP
#define VBUS_SENSING_PIN PA8

Expand Down Expand Up @@ -207,5 +205,3 @@
#define TARGET_IO_PORTC 0xffff
#define TARGET_IO_PORTD 0xffff
#define TARGET_IO_PORTE 0xffff

#define USED_TIMERS ( TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(5) | TIM_N(12) | TIM_N(8) | TIM_N(9) | TIM_N(10) | TIM_N(11))
3 changes: 2 additions & 1 deletion src/main/target/ANYFCM7/target.c
Original file line number Diff line number Diff line change
Expand Up @@ -25,7 +25,7 @@
#define TIM_EN TIMER_OUTPUT_ENABLED
#define TIM_EN_N TIMER_OUTPUT_ENABLED | TIMER_OUTPUT_N_CHANNEL

const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
const timerHardware_t timerHardware[] = {
{ TIM12, IO_TAG(PB14), TIM_CHANNEL_1, 0, IOCFG_AF_PP_PD, GPIO_AF9_TIM12, TIM_USE_PWM | TIM_USE_PPM }, // S1_IN
{ TIM12, IO_TAG(PB15), TIM_CHANNEL_2, 0, IOCFG_AF_PP_PD, GPIO_AF9_TIM12, TIM_USE_PWM }, // S2_IN
{ TIM8, IO_TAG(PC6), TIM_CHANNEL_1, 0, IOCFG_AF_PP_PD, GPIO_AF3_TIM8, TIM_USE_PWM }, // S3_IN
Expand All @@ -45,3 +45,4 @@ const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
{ TIM3, IO_TAG(PB4), TIM_CHANNEL_1, TIM_EN, IOCFG_AF_PP_PD, GPIO_AF2_TIM3, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO }, // S9_OUT PWM15
};

const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]);
4 changes: 0 additions & 4 deletions src/main/target/ANYFCM7/target.h
Original file line number Diff line number Diff line change
Expand Up @@ -59,8 +59,6 @@
#define USE_PITOT_MS4525
#define PITOT_I2C_BUS BUS_I2C2

#define USABLE_TIMER_CHANNEL_COUNT 16

#define USE_VCP
#define VBUS_SENSING_PIN PA8

Expand Down Expand Up @@ -141,5 +139,3 @@
#define TARGET_IO_PORTC 0xffff
#define TARGET_IO_PORTD 0xffff
#define TARGET_IO_PORTE 0xffff

#define USED_TIMERS ( TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(5) | TIM_N(8) | TIM_N(12))
4 changes: 3 additions & 1 deletion src/main/target/ASGARD32F4/target.c
Original file line number Diff line number Diff line change
Expand Up @@ -39,7 +39,7 @@
{ _tim, IO_TAG(_pin), DEF_TIM_CHNL_##_ch, _flags, IOCFG_AF_PP, GPIO_AF_##_tim, _usage }


const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
const timerHardware_t timerHardware[] = {
// DEF_TIM(TIM1, CH1, PA8, TIM_USE_PPM, 0), // PPM - timer clash with SS1_TX

DEF_TIM(TIM8, CH3, PC8, TIM_USE_MC_MOTOR, 1), // M1
Expand All @@ -51,3 +51,5 @@ const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {

DEF_TIM(TIM1, CH2, PA9, TIM_USE_ANY, 0), // SS1
};

const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]);
4 changes: 0 additions & 4 deletions src/main/target/ASGARD32F4/target.h
Original file line number Diff line number Diff line change
Expand Up @@ -171,7 +171,3 @@
#define TARGET_IO_PORTB 0xffff
#define TARGET_IO_PORTC 0xffff
#define TARGET_IO_PORTD 0xffff

#define USABLE_TIMER_CHANNEL_COUNT 5

#define USED_TIMERS ( TIM_N(1) | TIM_N(3) | TIM_N(4) | TIM_N(8) )
4 changes: 3 additions & 1 deletion src/main/target/BEEROTORF4/target.c
Original file line number Diff line number Diff line change
Expand Up @@ -24,7 +24,7 @@
#include "drivers/timer.h"


const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
const timerHardware_t timerHardware[] = {
{ TIM9, IO_TAG(PA3), TIM_Channel_2, 0, IOCFG_AF_PP, GPIO_AF_TIM9, TIM_USE_PPM }, // PPM IN

{ TIM1, IO_TAG(PB0), TIM_Channel_2, 1 | TIMER_OUTPUT_N_CHANNEL, IOCFG_AF_PP, GPIO_AF_TIM1, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR }, // M1
Expand All @@ -38,3 +38,5 @@ const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {

{ TIM4, IO_TAG(PB8), TIM_Channel_3, 1, IOCFG_AF_PP, GPIO_AF_TIM4, TIM_USE_LED }, // LED_STRIP / TRANSPONDER
};

const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]);
3 changes: 0 additions & 3 deletions src/main/target/BEEROTORF4/target.h
Original file line number Diff line number Diff line change
Expand Up @@ -181,6 +181,3 @@
#define TARGET_IO_PORTB 0xffff
#define TARGET_IO_PORTC 0xffff
#define TARGET_IO_PORTD (BIT(2))

#define USABLE_TIMER_CHANNEL_COUNT 10
#define USED_TIMERS ( TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(5) | TIM_N(9) | TIM_N(11) )
Loading

0 comments on commit de34c58

Please sign in to comment.