From d96586d505210fa6dfa9cd99b12fd50b92617c8a Mon Sep 17 00:00:00 2001 From: J Blackman Date: Mon, 16 Jan 2023 15:50:57 +1100 Subject: [PATCH] Missing define to activate TABLE_VIDEO_SYSTEM (#12200) * Missing define to activate TABLE_VIDEO_SYSTEM * USE_PWM should only be for RX (parallell RX inputs), USE_PWM_OUTPUT is for all others. * Updated gate naming so there is less confusion * Simplified. Note there maybe further occurences. --- docs/Customized Version.md | 14 +++++++------- src/main/cli/cli.c | 12 ++++++------ src/main/cli/settings.c | 10 +++++----- src/main/cli/settings.h | 2 +- src/main/config/config.c | 4 ++-- src/main/drivers/rx/rx_pwm.c | 2 +- src/main/fc/init.c | 4 ++-- src/main/pg/rx.c | 2 +- src/main/pg/rx_pwm.c | 6 +++--- src/main/rx/pwm.c | 2 +- src/main/rx/rx.c | 12 ++++++------ src/main/target/SITL/target.h | 5 +++-- src/main/target/common_post.h | 15 ++++++++++----- src/main/target/common_pre.h | 6 ++++-- 14 files changed, 52 insertions(+), 44 deletions(-) diff --git a/docs/Customized Version.md b/docs/Customized Version.md index 97eca295a..4c408a970 100644 --- a/docs/Customized Version.md +++ b/docs/Customized Version.md @@ -31,9 +31,9 @@ This file specifies the features enabled/disabled depending on the memory flash The first interesting part is where it specifies the features activated for all flight controllers. In the actual version, for example: ``` #define USE_CLI -#define USE_PPM -#define USE_PWM -#define SERIAL_RX +#define USE_RX_PPM +#define USE_RX_PWM +#define USE_SERIALRX #define USE_SERIALRX_CRSF // Team Black Sheep Crossfire protocol #define USE_SERIALRX_IBUS // FlySky and Turnigy receivers #define USE_SERIALRX_SBUS // Frsky and Futaba receivers @@ -96,17 +96,17 @@ After looking carefully to this file, you must know what features you want to di ## Specific features for each Flight Controller -Each flight controller has its own file to specify what features are enabled or disabled only for it. Sometimes they have been disabled by space limitations, but other times it's for limited computing capacity or a bug, so enable them at your own risk. +Each flight controller has its own file to specify what features are enabled or disabled only for it. Sometimes they have been disabled by space limitations, but other times it's for limited computing capacity or a bug, so enable them at your own risk. This file is located in `target/[FLIGHT_CONTROLLER_NAME]/target.h` and it's loaded **after** the `target/common_pre.h`. Any changes in this file will overwrite the default settings, so this file is the place where you must touch to create your custom firmware. -The first thing to do is to *#undef* all the features that we want to disable from the *common_pre.h*. +The first thing to do is to *#undef* all the features that we want to disable from the *common_pre.h*. For example, in a NAZE32, if we're using Serial RX, with a FlySky receiver (that uses de iBus protocol) and we don't have a led strip we will add all this *#undef* to the file. ``` -#undef USE_PPM -#undef USE_PWM +#undef USE_RX_PPM +#undef USE_RX_PWM #undef USE_SERIALRX_CRSF // Team Black Sheep Crossfire protocol #undef USE_SERIALRX_SBUS // Frsky and Futaba receivers #undef USE_SERIALRX_SPEKTRUM // SRXL, DSM2 and DSMX protocol diff --git a/src/main/cli/cli.c b/src/main/cli/cli.c index 1a44a567f..f085c5849 100644 --- a/src/main/cli/cli.c +++ b/src/main/cli/cli.c @@ -5049,24 +5049,24 @@ typedef struct { { owner, pgn, sizeof(type), offsetof(type, member), max } const cliResourceValue_t resourceTable[] = { -#ifdef USE_BEEPER +#if defined(USE_BEEPER) DEFS( OWNER_BEEPER, PG_BEEPER_DEV_CONFIG, beeperDevConfig_t, ioTag) , #endif DEFA( OWNER_MOTOR, PG_MOTOR_CONFIG, motorConfig_t, dev.ioTags[0], MAX_SUPPORTED_MOTORS ), -#ifdef USE_SERVOS +#if defined(USE_SERVOS) DEFA( OWNER_SERVO, PG_SERVO_CONFIG, servoConfig_t, dev.ioTags[0], MAX_SUPPORTED_SERVOS ), #endif -#if defined(USE_PPM) +#if defined(USE_RX_PPM) DEFS( OWNER_PPMINPUT, PG_PPM_CONFIG, ppmConfig_t, ioTag ), #endif -#if defined(USE_PWM) +#if defined(USE_RX_PWM) DEFA( OWNER_PWMINPUT, PG_PWM_CONFIG, pwmConfig_t, ioTags[0], PWM_INPUT_PORT_COUNT ), #endif -#ifdef USE_RANGEFINDER_HCSR04 +#if defined(USE_RANGEFINDER_HCSR04) DEFS( OWNER_SONAR_TRIGGER, PG_SONAR_CONFIG, sonarConfig_t, triggerTag ), DEFS( OWNER_SONAR_ECHO, PG_SONAR_CONFIG, sonarConfig_t, echoTag ), #endif -#ifdef USE_LED_STRIP +#if defined(USE_LED_STRIP) DEFS( OWNER_LED_STRIP, PG_LED_STRIP_CONFIG, ledStripConfig_t, ioTag ), #endif #ifdef USE_UART diff --git a/src/main/cli/settings.c b/src/main/cli/settings.c index 07265c5bf..f406524b7 100644 --- a/src/main/cli/settings.c +++ b/src/main/cli/settings.c @@ -383,7 +383,7 @@ const char * const lookupTableRescueAltitudeMode[] = { }; #endif -#if defined(USE_MAX7456) || defined(USE_FRSKYOSD) +#if defined(USE_VIDEO_SYSTEM) static const char * const lookupTableVideoSystem[] = { "AUTO", "PAL", "NTSC", "HD" }; @@ -597,7 +597,7 @@ const lookupTableEntry_t lookupTables[] = { LOOKUP_TABLE_ENTRY(lookupTableGyro), #endif LOOKUP_TABLE_ENTRY(lookupTableThrottleLimitType), -#if defined(USE_MAX7456) || defined(USE_FRSKYOSD) +#if defined(USE_VIDEO_SYSTEM) LOOKUP_TABLE_ENTRY(lookupTableVideoSystem), #endif #if defined(USE_ITERM_RELAX) @@ -655,7 +655,7 @@ const lookupTableEntry_t lookupTables[] = { const clivalue_t valueTable[] = { // PG_GYRO_CONFIG { PARAM_NAME_GYRO_HARDWARE_LPF, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_GYRO_HARDWARE_LPF }, PG_GYRO_CONFIG, offsetof(gyroConfig_t, gyro_hardware_lpf) }, - + #if defined(USE_GYRO_SPI_ICM20649) { "gyro_high_range", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_GYRO_CONFIG, offsetof(gyroConfig_t, gyro_high_fsr) }, #endif @@ -799,7 +799,7 @@ const clivalue_t valueTable[] = { #endif // PG_PWM_CONFIG -#if defined(USE_PWM) +#if defined(USE_RX_PWM) { "input_filtering_mode", VAR_INT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_PWM_CONFIG, offsetof(pwmConfig_t, inputFilteringMode) }, #endif @@ -1509,7 +1509,7 @@ const clivalue_t valueTable[] = { #endif // PG_VCD_CONFIG -#if defined(USE_MAX7456) || defined(USE_FRSKYOSD) || defined(USE_MSP_DISPLAYPORT) +#if defined(USE_VIDEO_SYSTEM) { "vcd_video_system", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_VIDEO_SYSTEM }, PG_VCD_CONFIG, offsetof(vcdProfile_t, video_system) }, #endif #if defined(USE_MAX7456) diff --git a/src/main/cli/settings.h b/src/main/cli/settings.h index 96b23f014..b55a6f872 100644 --- a/src/main/cli/settings.h +++ b/src/main/cli/settings.h @@ -96,7 +96,7 @@ typedef enum { TABLE_GYRO, #endif TABLE_THROTTLE_LIMIT_TYPE, -#if defined(USE_MAX7456) || defined(USE_FRSKYOSD) +#if defined(USE_VIDEO_SYSTEM) TABLE_VIDEO_SYSTEM, #endif #if defined(USE_ITERM_RELAX) diff --git a/src/main/config/config.c b/src/main/config/config.c index 76181dfc0..eb5931eb7 100644 --- a/src/main/config/config.c +++ b/src/main/config/config.c @@ -352,7 +352,7 @@ static void validateAndFixConfig(void) } else #endif if (rxConfigMutable()->rssi_channel -#if defined(USE_PWM) || defined(USE_PPM) +#if defined(USE_RX_PWM) || defined(USE_RX_PPM) || featureIsConfigured(FEATURE_RX_PPM) || featureIsConfigured(FEATURE_RX_PARALLEL_PWM) #endif ) { @@ -415,7 +415,7 @@ static void validateAndFixConfig(void) // clear features that are not supported. // I have kept them all here in one place, some could be moved to sections of code above. -#ifndef USE_PPM +#ifndef USE_RX_PPM featureDisableImmediate(FEATURE_RX_PPM); #endif diff --git a/src/main/drivers/rx/rx_pwm.c b/src/main/drivers/rx/rx_pwm.c index 75ee9ac8b..fd9932b69 100644 --- a/src/main/drivers/rx/rx_pwm.c +++ b/src/main/drivers/rx/rx_pwm.c @@ -23,7 +23,7 @@ #include "platform.h" -#if defined(USE_PWM) || defined(USE_PPM) +#if defined(USE_RX_PWM) || defined(USE_RX_PPM) #include "build/build_config.h" #include "build/debug.h" diff --git a/src/main/fc/init.c b/src/main/fc/init.c index c08471b30..3ab56faf2 100644 --- a/src/main/fc/init.c +++ b/src/main/fc/init.c @@ -563,12 +563,12 @@ void init(void) #endif if (0) {} -#if defined(USE_PPM) +#if defined(USE_RX_PPM) else if (featureIsEnabled(FEATURE_RX_PPM)) { ppmRxInit(ppmConfig()); } #endif -#if defined(USE_PWM) +#if defined(USE_RX_PWM) else if (featureIsEnabled(FEATURE_RX_PARALLEL_PWM)) { pwmRxInit(pwmConfig()); } diff --git a/src/main/pg/rx.c b/src/main/pg/rx.c index 1aeb9dc19..46a2688b2 100644 --- a/src/main/pg/rx.c +++ b/src/main/pg/rx.c @@ -20,7 +20,7 @@ #include "platform.h" -#if defined(USE_PWM) || defined(USE_PPM) || defined(USE_SERIALRX) || defined(USE_RX_MSP) || defined(USE_RX_SPI) +#if defined(USE_RX_PWM) || defined(USE_RX_PPM) || defined(USE_SERIALRX) || defined(USE_RX_MSP) || defined(USE_RX_SPI) #include "pg/pg.h" #include "pg/pg_ids.h" diff --git a/src/main/pg/rx_pwm.c b/src/main/pg/rx_pwm.c index 753e4d226..a4d2b3c49 100644 --- a/src/main/pg/rx_pwm.c +++ b/src/main/pg/rx_pwm.c @@ -20,7 +20,7 @@ #include "platform.h" -#if defined(USE_PWM) || defined(USE_PPM) +#if defined(USE_RX_PWM) || defined(USE_RX_PPM) #include "drivers/io.h" #include "drivers/nvic.h" @@ -32,7 +32,7 @@ #include "rx_pwm.h" -#ifdef USE_PWM +#ifdef USE_RX_PWM PG_REGISTER_WITH_RESET_FN(pwmConfig_t, pwmConfig, PG_PWM_CONFIG, 0); void pgResetFn_pwmConfig(pwmConfig_t *pwmConfig) @@ -44,7 +44,7 @@ void pgResetFn_pwmConfig(pwmConfig_t *pwmConfig) } #endif -#ifdef USE_PPM +#ifdef USE_RX_PPM PG_REGISTER_WITH_RESET_FN(ppmConfig_t, ppmConfig, PG_PPM_CONFIG, 0); void pgResetFn_ppmConfig(ppmConfig_t *ppmConfig) diff --git a/src/main/rx/pwm.c b/src/main/rx/pwm.c index 27b4cd9ad..cdc2e0002 100644 --- a/src/main/rx/pwm.c +++ b/src/main/rx/pwm.c @@ -26,7 +26,7 @@ #include "platform.h" -#if defined(USE_PWM) || defined(USE_PPM) +#if defined(USE_RX_PWM) || defined(USE_RX_PPM) #include "common/utils.h" diff --git a/src/main/rx/rx.c b/src/main/rx/rx.c index 6064a1900..a3b6e4d14 100644 --- a/src/main/rx/rx.c +++ b/src/main/rx/rx.c @@ -357,7 +357,7 @@ void rxInit(void) break; #endif -#if defined(USE_PWM) || defined(USE_PPM) +#if defined(USE_RX_PWM) || defined(USE_RX_PPM) case RX_PROVIDER_PPM: case RX_PROVIDER_PARALLEL_PWM: rxPwmInit(rxConfig(), &rxRuntimeState); @@ -406,7 +406,7 @@ bool rxAreFlightChannelsValid(void) void suspendRxSignal(void) { -#if defined(USE_PWM) || defined(USE_PPM) +#if defined(USE_RX_PWM) || defined(USE_RX_PPM) if (rxRuntimeState.rxProvider == RX_PROVIDER_PARALLEL_PWM || rxRuntimeState.rxProvider == RX_PROVIDER_PPM) { suspendRxSignalUntil = micros() + DELAY_1500_MS; // 1.5s skipRxSamples = SKIP_RC_SAMPLES_ON_RESUME; @@ -417,7 +417,7 @@ void suspendRxSignal(void) void resumeRxSignal(void) { -#if defined(USE_PWM) || defined(USE_PPM) +#if defined(USE_RX_PWM) || defined(USE_RX_PPM) if (rxRuntimeState.rxProvider == RX_PROVIDER_PARALLEL_PWM || rxRuntimeState.rxProvider == RX_PROVIDER_PPM) { suspendRxSignalUntil = micros(); skipRxSamples = SKIP_RC_SAMPLES_ON_RESUME; @@ -515,7 +515,7 @@ FAST_CODE_NOINLINE void rxFrameCheck(timeUs_t currentTimeUs, timeDelta_t current default: break; -#if defined(USE_PWM) || defined(USE_PPM) +#if defined(USE_RX_PWM) || defined(USE_RX_PPM) case RX_PROVIDER_PPM: if (isPPMDataBeingReceived()) { signalReceived = true; @@ -567,7 +567,7 @@ FAST_CODE_NOINLINE void rxFrameCheck(timeUs_t currentTimeUs, timeDelta_t current DEBUG_SET(DEBUG_RX_SIGNAL_LOSS, 0, rxSignalReceived); } -#if defined(USE_PWM) || defined(USE_PPM) +#if defined(USE_RX_PWM) || defined(USE_RX_PPM) static uint16_t calculateChannelMovingAverage(uint8_t chan, uint16_t sample) { static int16_t rcSamples[MAX_SUPPORTED_RX_PARALLEL_PWM_OR_PPM_CHANNEL_COUNT][PPM_AND_PWM_SAMPLE_COUNT]; @@ -723,7 +723,7 @@ void detectAndApplySignalLossBehaviour(void) sample = constrainf(sample, PWM_PULSE_MIN, PWM_PULSE_MAX); -#if defined(USE_PWM) || defined(USE_PPM) +#if defined(USE_RX_PWM) || defined(USE_RX_PPM) if (rxRuntimeState.rxProvider == RX_PROVIDER_PARALLEL_PWM || rxRuntimeState.rxProvider == RX_PROVIDER_PPM) { // smooth output for PWM and PPM using moving average rcData[channel] = calculateChannelMovingAverage(channel, sample); diff --git a/src/main/target/SITL/target.h b/src/main/target/SITL/target.h index 917ab77b6..7b515b44c 100644 --- a/src/main/target/SITL/target.h +++ b/src/main/target/SITL/target.h @@ -96,8 +96,8 @@ #undef USE_ADC #undef USE_VCP #undef USE_OSD -#undef USE_PPM -#undef USE_PWM +#undef USE_RX_PPM +#undef USE_RX_PWM #undef USE_SERIALRX #undef USE_SERIALRX_CRSF #undef USE_SERIALRX_GHST @@ -108,6 +108,7 @@ #undef USE_SERIALRX_SUMH #undef USE_SERIALRX_XBUS #undef USE_LED_STRIP +#undef USE_PWM_OUTPUT #undef USE_TELEMETRY_FRSKY_HUB #undef USE_TELEMETRY_HOTT #undef USE_TELEMETRY_SMARTPORT diff --git a/src/main/target/common_post.h b/src/main/target/common_post.h index 1da0bedc9..1d060319c 100644 --- a/src/main/target/common_post.h +++ b/src/main/target/common_post.h @@ -322,22 +322,27 @@ #if !defined(USE_SERIAL_4WAY_BLHELI_BOOTLOADER) && !defined(USE_SERIAL_4WAY_SK_BOOTLOADER) #undef USE_SERIAL_4WAY_BLHELI_INTERFACE #elif !defined(USE_SERIAL_4WAY_BLHELI_INTERFACE) && (defined(USE_SERIAL_4WAY_BLHELI_BOOTLOADER) || defined(USE_SERIAL_4WAY_SK_BOOTLOADER)) +#ifndef USE_SERIAL_4WAY_BLHELI_INTERFACE #define USE_SERIAL_4WAY_BLHELI_INTERFACE #endif +#endif - -#if defined(USE_PWM) || defined(USE_DSHOT) || defined(USE_LED_STRIP) || defined(USE_TRANSPONDER) || defined(USE_BEEPER) +#if defined(USE_RX_PWM) || defined(USE_DSHOT) || defined(USE_LED_STRIP) || defined(USE_TRANSPONDER) || defined(USE_BEEPER) || defined(USE_SERIAL_4WAY_BLHELI_INTERFACE) +#ifndef USE_PWM_OUTPUT #define USE_PWM_OUTPUT #endif - -#if !defined(USE_PWM_OUTPUT) -#undef USE_SERIAL_4WAY_BLHELI_INTERFACE // implementation requires USE_PWM_OUTPUT to find motor outputs. #endif #if !defined(USE_LED_STRIP) #undef USE_LED_STRIP_STATUS_MODE #endif +#if defined(USE_MAX7456) || defined(USE_FRSKYOSD) || defined(USE_MSP_DISPLAYPORT) +#ifndef USE_VIDEO_SYSTEM +#define USE_VIDEO_SYSTEM +#endif +#endif + #if defined(USE_LED_STRIP) && !defined(USE_LED_STRIP_STATUS_MODE) #define USE_WS2811_SINGLE_COLOUR #endif diff --git a/src/main/target/common_pre.h b/src/main/target/common_pre.h index 803e73ade..66c009e35 100644 --- a/src/main/target/common_pre.h +++ b/src/main/target/common_pre.h @@ -325,14 +325,15 @@ extern uint8_t _dmaram_end__; #define USE_RANGEFINDER_TF #endif -#define USE_PPM +#define USE_RX_PPM +#define USE_RX_PWM #define USE_BRUSHED_ESC_AUTODETECT // Detect if brushed motors are connected and set defaults appropriately to avoid motors spinning on boot -#define USE_PWM #define USE_PINIO #if !defined(USE_SERIAL_RX) + #define USE_SERIALRX #define USE_SERIALRX_CRSF // Team Black Sheep Crossfire protocol #define USE_SERIALRX_GHST // ImmersionRC Ghost Protocol @@ -342,6 +343,7 @@ extern uint8_t _dmaram_end__; #define USE_SERIALRX_FPORT // FrSky FPort #define USE_SERIALRX_XBUS // JR #define USE_SERIALRX_SRXL2 // Spektrum SRXL2 protocol + #endif // !defined(USE_SERIAL_RX) #if !defined(USE_TELEMETRY) -- 2.11.4.GIT