From 19f22f5120f590b0e99dadeaadc1a752a87c934e Mon Sep 17 00:00:00 2001 From: J Blackman Date: Sun, 12 Feb 2023 14:06:49 +1100 Subject: [PATCH] Method for adding defaults using defines for resources. (#12342) * Method for adding defaults using defines for resources. * As we will always be using the fullTimerHardware, we just need to configure the pin mapping. This is done in the config.h as #define TIMER_PIN_MAPPING \ TIMER_PIN_MAP(0, PA0, 1, 0) \ TIMER_PIN_MAP(0, PA1, 1, 0) timerHardware[] dependencies to be removed in another PR * Adding missing pin definitions (removing dependency on timerHardware) * Typo * In case MOTOR1_PIN is not defined, but a motor is configured --- src/main/drivers/camera_control.c | 6 +++++- src/main/fc/init.c | 10 +++++++--- src/main/flight/servos.c | 15 ++++++++++++--- src/main/io/ledstrip.c | 6 +++++- src/main/io/transponder_ir.c | 6 +++++- src/main/pg/motor.c | 19 ++++++++++++++++--- src/main/pg/rx_pwm.c | 21 +++++++++++++++++---- src/main/pg/timerio.c | 28 +++++----------------------- 8 files changed, 72 insertions(+), 39 deletions(-) diff --git a/src/main/drivers/camera_control.c b/src/main/drivers/camera_control.c index c6003573f1..531f76b990 100644 --- a/src/main/drivers/camera_control.c +++ b/src/main/drivers/camera_control.c @@ -60,7 +60,11 @@ void pgResetFn_cameraControlConfig(cameraControlConfig_t *cameraControlConfig) cameraControlConfig->refVoltage = 330; cameraControlConfig->keyDelayMs = 180; cameraControlConfig->internalResistance = 470; - cameraControlConfig->ioTag = timerioTagGetByUsage(TIM_USE_CAMERA_CONTROL, 0); +#ifdef CAMERA_CONTROL_PIN + cameraControlConfig->ioTag = IO_TAG(CAMERA_CONTROL_PIN); +#else + cameraControlConfig->ioTag = IO_TAG_NONE; +#endif cameraControlConfig->inverted = 0; // Output is inverted externally cameraControlConfig->buttonResistanceValues[CAMERA_CONTROL_KEY_ENTER] = 450; cameraControlConfig->buttonResistanceValues[CAMERA_CONTROL_KEY_LEFT] = 270; diff --git a/src/main/fc/init.c b/src/main/fc/init.c index 59023cc617..04d1a561eb 100644 --- a/src/main/fc/init.c +++ b/src/main/fc/init.c @@ -294,10 +294,14 @@ void init(void) targetConfiguration(); #endif -#ifdef USE_BRUSHED_ESC_AUTODETECT +#if defined(USE_BRUSHED_ESC_AUTODETECT) // Opportunistically use the first motor pin of the default configuration for detection. // We are doing this as with some boards, timing seems to be important, and the later detection will fail. - ioTag_t motorIoTag = timerioTagGetByUsage(TIM_USE_MOTOR, 0); +#if defined(MOTOR1_PIN) + ioTag_t motorIoTag = IO_TAG(MOTOR1_PIN); +#else + ioTag_t motorIoTag = IO_TAG_NONE; +#endif if (motorIoTag) { detectBrushedESC(motorIoTag); @@ -427,7 +431,7 @@ void init(void) dbgPinInit(); #endif -#ifdef USE_BRUSHED_ESC_AUTODETECT +#if defined(USE_BRUSHED_ESC_AUTODETECT) // Now detect again with the actually configured pin for motor 1, if it is not the default pin. ioTag_t configuredMotorIoTag = motorConfig()->dev.ioTags[0]; diff --git a/src/main/flight/servos.c b/src/main/flight/servos.c index d1e50d5814..71b26b4d8d 100644 --- a/src/main/flight/servos.c +++ b/src/main/flight/servos.c @@ -66,9 +66,18 @@ void pgResetFn_servoConfig(servoConfig_t *servoConfig) servoConfig->servo_lowpass_freq = 0; servoConfig->channelForwardingStartChannel = AUX1; - for (unsigned servoIndex = 0; servoIndex < MAX_SUPPORTED_SERVOS; servoIndex++) { - servoConfig->dev.ioTags[servoIndex] = timerioTagGetByUsage(TIM_USE_SERVO, servoIndex); - } +#ifdef SERVO1_PIN + servoConfig->dev.ioTags[0] = IO_TAG(SERVO1_PIN); +#endif +#ifdef SERVO2_PIN + servoConfig->dev.ioTags[1] = IO_TAG(SERVO2_PIN); +#endif +#ifdef SERVO3_PIN + servoConfig->dev.ioTags[2] = IO_TAG(SERVO3_PIN); +#endif +#ifdef SERVO4_PIN + servoConfig->dev.ioTags[3] = IO_TAG(SERVO4_PIN); +#endif } PG_REGISTER_ARRAY(servoMixer_t, MAX_SERVO_RULES, customServoMixers, PG_SERVO_MIXER, 0); diff --git a/src/main/io/ledstrip.c b/src/main/io/ledstrip.c index dad564c66f..4335a73ed3 100644 --- a/src/main/io/ledstrip.c +++ b/src/main/io/ledstrip.c @@ -133,7 +133,11 @@ void pgResetFn_ledStripConfig(ledStripConfig_t *ledStripConfig) ledStripConfig->ledstrip_visual_beeper_color = VISUAL_BEEPER_COLOR; ledStripConfig->ledstrip_brightness = 100; #ifndef UNIT_TEST - ledStripConfig->ioTag = timerioTagGetByUsage(TIM_USE_LED, 0); +#ifdef LED_STRIP_PIN + ledStripConfig->ioTag = IO_TAG(LED_STRIP_PIN); +#else + ledStripConfig->ioTag = IO_TAG_NONE; +#endif #endif } diff --git a/src/main/io/transponder_ir.c b/src/main/io/transponder_ir.c index 3255417641..1d62dd9e0e 100644 --- a/src/main/io/transponder_ir.c +++ b/src/main/io/transponder_ir.c @@ -54,7 +54,11 @@ void pgResetFn_transponderConfig(transponderConfig_t *transponderConfig) .data = { 0x12, 0x34, 0x56, 0x78, 0x9A, 0xBC, 0x0, 0x0, 0x0 }, // Note, this is NOT a valid transponder code, it's just for testing production hardware .ioTag = IO_TAG_NONE ); - transponderConfig->ioTag = timerioTagGetByUsage(TIM_USE_TRANSPONDER, 0); +#ifdef TRANSPONDER_PIN + transponderConfig->ioTag = IO_TAG(TRANSPONDER_PIN); +#else + transponderConfig->ioTag = IO_TAG_NONE; +#endif } static bool transponderInitialised = false; diff --git a/src/main/pg/motor.c b/src/main/pg/motor.c index 3f70786fd0..bb695fb687 100644 --- a/src/main/pg/motor.c +++ b/src/main/pg/motor.c @@ -67,9 +67,22 @@ void pgResetFn_motorConfig(motorConfig_t *motorConfig) #endif #ifdef USE_TIMER - for (int motorIndex = 0; motorIndex < MAX_SUPPORTED_MOTORS; motorIndex++) { - motorConfig->dev.ioTags[motorIndex] = timerioTagGetByUsage(TIM_USE_MOTOR, motorIndex); - } +#ifdef MOTOR1_PIN + motorConfig->dev.ioTags[0] = IO_TAG(MOTOR1_PIN); +#endif +#ifdef MOTOR2_PIN + motorConfig->dev.ioTags[1] = IO_TAG(MOTOR2_PIN); +#endif +#ifdef MOTOR3_PIN + motorConfig->dev.ioTags[2] = IO_TAG(MOTOR3_PIN); +#endif +#ifdef MOTOR4_PIN + motorConfig->dev.ioTags[3] = IO_TAG(MOTOR4_PIN); +#endif +/* + NOTE as we predominantly build for quads, the default motor pin defines is 4, + add more if a specific configuration ever requires it. +*/ #endif motorConfig->motorPoleCount = 14; // Most brushes motors that we use are 14 poles diff --git a/src/main/pg/rx_pwm.c b/src/main/pg/rx_pwm.c index a4d2b3c494..a42e037f36 100644 --- a/src/main/pg/rx_pwm.c +++ b/src/main/pg/rx_pwm.c @@ -38,9 +38,18 @@ PG_REGISTER_WITH_RESET_FN(pwmConfig_t, pwmConfig, PG_PWM_CONFIG, 0); void pgResetFn_pwmConfig(pwmConfig_t *pwmConfig) { pwmConfig->inputFilteringMode = INPUT_FILTERING_DISABLED; - for (unsigned inputIndex = 0; inputIndex < PWM_INPUT_PORT_COUNT; inputIndex++) { - pwmConfig->ioTags[inputIndex] = timerioTagGetByUsage(TIM_USE_PWM, inputIndex); - } +#ifdef RX_PWM1_PIN + pwmConfig->ioTags[0] = IO_TAG(RX_PWM1_PIN); +#endif +#ifdef RX_PWM2_PIN + pwmConfig->ioTags[1] = IO_TAG(RX_PWM2_PIN); +#endif +#ifdef RX_PWM3_PIN + pwmConfig->ioTags[2] = IO_TAG(RX_PWM3_PIN); +#endif +#ifdef RX_PWM4_PIN + pwmConfig->ioTags[3] = IO_TAG(RX_PWM4_PIN); +#endif } #endif @@ -49,7 +58,11 @@ PG_REGISTER_WITH_RESET_FN(ppmConfig_t, ppmConfig, PG_PPM_CONFIG, 0); void pgResetFn_ppmConfig(ppmConfig_t *ppmConfig) { - ppmConfig->ioTag = timerioTagGetByUsage(TIM_USE_PPM, 0); +#ifdef RX_PPM_PIN + ppmConfig->ioTag = IO_TAG(RX_PPM_PIN); +#else + ppmConfig->ioTag = IO_TAG_NONE; +#endif } #endif diff --git a/src/main/pg/timerio.c b/src/main/pg/timerio.c index 03d5df2319..84915868b0 100644 --- a/src/main/pg/timerio.c +++ b/src/main/pg/timerio.c @@ -29,33 +29,15 @@ #include "timerio.h" +#define TIMER_PIN_MAP(idx, pin, pos, dmaOpt) \ + { config[idx].ioTag = IO_TAG(pin); config[idx].index = pos; config[idx].dmaopt = dmaOpt; } + PG_REGISTER_ARRAY_WITH_RESET_FN(timerIOConfig_t, MAX_TIMER_PINMAP_COUNT, timerIOConfig, PG_TIMER_IO_CONFIG, 0); void pgResetFn_timerIOConfig(timerIOConfig_t *config) { -#if defined(USE_TIMER_MGMT) && USABLE_TIMER_CHANNEL_COUNT > 0 - unsigned configIndex = 0; - for (unsigned timerIndex = 0; timerIndex < USABLE_TIMER_CHANNEL_COUNT; timerIndex++) { - const timerHardware_t *configuredTimer = &timerHardware[timerIndex]; - unsigned positionIndex = 1; - for (unsigned fullTimerIndex = 0; fullTimerIndex < FULL_TIMER_CHANNEL_COUNT; fullTimerIndex++) { - const timerHardware_t *timer = &fullTimerHardware[fullTimerIndex]; - if (timer->tag == configuredTimer->tag) { - if (timer->tim == configuredTimer->tim && timer->channel == configuredTimer->channel) { - config[configIndex].ioTag = timer->tag; - config[configIndex].index = positionIndex; - - config[configIndex].dmaopt = dmaGetOptionByTimer(configuredTimer); - - configIndex++; - - break; - } else { - positionIndex++; - } - } - } - } +#ifdef TIMER_PIN_MAPPING + TIMER_PIN_MAPPING #else UNUSED(config); #endif