mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-14 03:50:02 +03:00
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.
This commit is contained in:
parent
5ce7c509a1
commit
d96586d505
14 changed files with 53 additions and 45 deletions
|
@ -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:
|
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_CLI
|
||||||
#define USE_PPM
|
#define USE_RX_PPM
|
||||||
#define USE_PWM
|
#define USE_RX_PWM
|
||||||
#define SERIAL_RX
|
#define USE_SERIALRX
|
||||||
#define USE_SERIALRX_CRSF // Team Black Sheep Crossfire protocol
|
#define USE_SERIALRX_CRSF // Team Black Sheep Crossfire protocol
|
||||||
#define USE_SERIALRX_IBUS // FlySky and Turnigy receivers
|
#define USE_SERIALRX_IBUS // FlySky and Turnigy receivers
|
||||||
#define USE_SERIALRX_SBUS // Frsky and Futaba 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
|
## 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.
|
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.
|
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_RX_PPM
|
||||||
#undef USE_PWM
|
#undef USE_RX_PWM
|
||||||
#undef USE_SERIALRX_CRSF // Team Black Sheep Crossfire protocol
|
#undef USE_SERIALRX_CRSF // Team Black Sheep Crossfire protocol
|
||||||
#undef USE_SERIALRX_SBUS // Frsky and Futaba receivers
|
#undef USE_SERIALRX_SBUS // Frsky and Futaba receivers
|
||||||
#undef USE_SERIALRX_SPEKTRUM // SRXL, DSM2 and DSMX protocol
|
#undef USE_SERIALRX_SPEKTRUM // SRXL, DSM2 and DSMX protocol
|
||||||
|
|
|
@ -5049,24 +5049,24 @@ typedef struct {
|
||||||
{ owner, pgn, sizeof(type), offsetof(type, member), max }
|
{ owner, pgn, sizeof(type), offsetof(type, member), max }
|
||||||
|
|
||||||
const cliResourceValue_t resourceTable[] = {
|
const cliResourceValue_t resourceTable[] = {
|
||||||
#ifdef USE_BEEPER
|
#if defined(USE_BEEPER)
|
||||||
DEFS( OWNER_BEEPER, PG_BEEPER_DEV_CONFIG, beeperDevConfig_t, ioTag) ,
|
DEFS( OWNER_BEEPER, PG_BEEPER_DEV_CONFIG, beeperDevConfig_t, ioTag) ,
|
||||||
#endif
|
#endif
|
||||||
DEFA( OWNER_MOTOR, PG_MOTOR_CONFIG, motorConfig_t, dev.ioTags[0], MAX_SUPPORTED_MOTORS ),
|
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 ),
|
DEFA( OWNER_SERVO, PG_SERVO_CONFIG, servoConfig_t, dev.ioTags[0], MAX_SUPPORTED_SERVOS ),
|
||||||
#endif
|
#endif
|
||||||
#if defined(USE_PPM)
|
#if defined(USE_RX_PPM)
|
||||||
DEFS( OWNER_PPMINPUT, PG_PPM_CONFIG, ppmConfig_t, ioTag ),
|
DEFS( OWNER_PPMINPUT, PG_PPM_CONFIG, ppmConfig_t, ioTag ),
|
||||||
#endif
|
#endif
|
||||||
#if defined(USE_PWM)
|
#if defined(USE_RX_PWM)
|
||||||
DEFA( OWNER_PWMINPUT, PG_PWM_CONFIG, pwmConfig_t, ioTags[0], PWM_INPUT_PORT_COUNT ),
|
DEFA( OWNER_PWMINPUT, PG_PWM_CONFIG, pwmConfig_t, ioTags[0], PWM_INPUT_PORT_COUNT ),
|
||||||
#endif
|
#endif
|
||||||
#ifdef USE_RANGEFINDER_HCSR04
|
#if defined(USE_RANGEFINDER_HCSR04)
|
||||||
DEFS( OWNER_SONAR_TRIGGER, PG_SONAR_CONFIG, sonarConfig_t, triggerTag ),
|
DEFS( OWNER_SONAR_TRIGGER, PG_SONAR_CONFIG, sonarConfig_t, triggerTag ),
|
||||||
DEFS( OWNER_SONAR_ECHO, PG_SONAR_CONFIG, sonarConfig_t, echoTag ),
|
DEFS( OWNER_SONAR_ECHO, PG_SONAR_CONFIG, sonarConfig_t, echoTag ),
|
||||||
#endif
|
#endif
|
||||||
#ifdef USE_LED_STRIP
|
#if defined(USE_LED_STRIP)
|
||||||
DEFS( OWNER_LED_STRIP, PG_LED_STRIP_CONFIG, ledStripConfig_t, ioTag ),
|
DEFS( OWNER_LED_STRIP, PG_LED_STRIP_CONFIG, ledStripConfig_t, ioTag ),
|
||||||
#endif
|
#endif
|
||||||
#ifdef USE_UART
|
#ifdef USE_UART
|
||||||
|
|
|
@ -383,7 +383,7 @@ const char * const lookupTableRescueAltitudeMode[] = {
|
||||||
};
|
};
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if defined(USE_MAX7456) || defined(USE_FRSKYOSD)
|
#if defined(USE_VIDEO_SYSTEM)
|
||||||
static const char * const lookupTableVideoSystem[] = {
|
static const char * const lookupTableVideoSystem[] = {
|
||||||
"AUTO", "PAL", "NTSC", "HD"
|
"AUTO", "PAL", "NTSC", "HD"
|
||||||
};
|
};
|
||||||
|
@ -597,7 +597,7 @@ const lookupTableEntry_t lookupTables[] = {
|
||||||
LOOKUP_TABLE_ENTRY(lookupTableGyro),
|
LOOKUP_TABLE_ENTRY(lookupTableGyro),
|
||||||
#endif
|
#endif
|
||||||
LOOKUP_TABLE_ENTRY(lookupTableThrottleLimitType),
|
LOOKUP_TABLE_ENTRY(lookupTableThrottleLimitType),
|
||||||
#if defined(USE_MAX7456) || defined(USE_FRSKYOSD)
|
#if defined(USE_VIDEO_SYSTEM)
|
||||||
LOOKUP_TABLE_ENTRY(lookupTableVideoSystem),
|
LOOKUP_TABLE_ENTRY(lookupTableVideoSystem),
|
||||||
#endif
|
#endif
|
||||||
#if defined(USE_ITERM_RELAX)
|
#if defined(USE_ITERM_RELAX)
|
||||||
|
@ -655,7 +655,7 @@ const lookupTableEntry_t lookupTables[] = {
|
||||||
const clivalue_t valueTable[] = {
|
const clivalue_t valueTable[] = {
|
||||||
// PG_GYRO_CONFIG
|
// 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) },
|
{ 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)
|
#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) },
|
{ "gyro_high_range", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_GYRO_CONFIG, offsetof(gyroConfig_t, gyro_high_fsr) },
|
||||||
#endif
|
#endif
|
||||||
|
@ -799,7 +799,7 @@ const clivalue_t valueTable[] = {
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// PG_PWM_CONFIG
|
// 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) },
|
{ "input_filtering_mode", VAR_INT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_PWM_CONFIG, offsetof(pwmConfig_t, inputFilteringMode) },
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
@ -1509,7 +1509,7 @@ const clivalue_t valueTable[] = {
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// PG_VCD_CONFIG
|
// 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) },
|
{ "vcd_video_system", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_VIDEO_SYSTEM }, PG_VCD_CONFIG, offsetof(vcdProfile_t, video_system) },
|
||||||
#endif
|
#endif
|
||||||
#if defined(USE_MAX7456)
|
#if defined(USE_MAX7456)
|
||||||
|
|
|
@ -96,7 +96,7 @@ typedef enum {
|
||||||
TABLE_GYRO,
|
TABLE_GYRO,
|
||||||
#endif
|
#endif
|
||||||
TABLE_THROTTLE_LIMIT_TYPE,
|
TABLE_THROTTLE_LIMIT_TYPE,
|
||||||
#if defined(USE_MAX7456) || defined(USE_FRSKYOSD)
|
#if defined(USE_VIDEO_SYSTEM)
|
||||||
TABLE_VIDEO_SYSTEM,
|
TABLE_VIDEO_SYSTEM,
|
||||||
#endif
|
#endif
|
||||||
#if defined(USE_ITERM_RELAX)
|
#if defined(USE_ITERM_RELAX)
|
||||||
|
|
|
@ -352,7 +352,7 @@ static void validateAndFixConfig(void)
|
||||||
} else
|
} else
|
||||||
#endif
|
#endif
|
||||||
if (rxConfigMutable()->rssi_channel
|
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)
|
|| featureIsConfigured(FEATURE_RX_PPM) || featureIsConfigured(FEATURE_RX_PARALLEL_PWM)
|
||||||
#endif
|
#endif
|
||||||
) {
|
) {
|
||||||
|
@ -415,7 +415,7 @@ static void validateAndFixConfig(void)
|
||||||
// clear features that are not supported.
|
// clear features that are not supported.
|
||||||
// I have kept them all here in one place, some could be moved to sections of code above.
|
// 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);
|
featureDisableImmediate(FEATURE_RX_PPM);
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
|
|
@ -23,7 +23,7 @@
|
||||||
|
|
||||||
#include "platform.h"
|
#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/build_config.h"
|
||||||
#include "build/debug.h"
|
#include "build/debug.h"
|
||||||
|
|
|
@ -563,12 +563,12 @@ void init(void)
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
if (0) {}
|
if (0) {}
|
||||||
#if defined(USE_PPM)
|
#if defined(USE_RX_PPM)
|
||||||
else if (featureIsEnabled(FEATURE_RX_PPM)) {
|
else if (featureIsEnabled(FEATURE_RX_PPM)) {
|
||||||
ppmRxInit(ppmConfig());
|
ppmRxInit(ppmConfig());
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
#if defined(USE_PWM)
|
#if defined(USE_RX_PWM)
|
||||||
else if (featureIsEnabled(FEATURE_RX_PARALLEL_PWM)) {
|
else if (featureIsEnabled(FEATURE_RX_PARALLEL_PWM)) {
|
||||||
pwmRxInit(pwmConfig());
|
pwmRxInit(pwmConfig());
|
||||||
}
|
}
|
||||||
|
|
|
@ -20,7 +20,7 @@
|
||||||
|
|
||||||
#include "platform.h"
|
#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.h"
|
||||||
#include "pg/pg_ids.h"
|
#include "pg/pg_ids.h"
|
||||||
|
|
|
@ -20,7 +20,7 @@
|
||||||
|
|
||||||
#include "platform.h"
|
#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/io.h"
|
||||||
#include "drivers/nvic.h"
|
#include "drivers/nvic.h"
|
||||||
|
@ -32,7 +32,7 @@
|
||||||
|
|
||||||
#include "rx_pwm.h"
|
#include "rx_pwm.h"
|
||||||
|
|
||||||
#ifdef USE_PWM
|
#ifdef USE_RX_PWM
|
||||||
PG_REGISTER_WITH_RESET_FN(pwmConfig_t, pwmConfig, PG_PWM_CONFIG, 0);
|
PG_REGISTER_WITH_RESET_FN(pwmConfig_t, pwmConfig, PG_PWM_CONFIG, 0);
|
||||||
|
|
||||||
void pgResetFn_pwmConfig(pwmConfig_t *pwmConfig)
|
void pgResetFn_pwmConfig(pwmConfig_t *pwmConfig)
|
||||||
|
@ -44,7 +44,7 @@ void pgResetFn_pwmConfig(pwmConfig_t *pwmConfig)
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifdef USE_PPM
|
#ifdef USE_RX_PPM
|
||||||
PG_REGISTER_WITH_RESET_FN(ppmConfig_t, ppmConfig, PG_PPM_CONFIG, 0);
|
PG_REGISTER_WITH_RESET_FN(ppmConfig_t, ppmConfig, PG_PPM_CONFIG, 0);
|
||||||
|
|
||||||
void pgResetFn_ppmConfig(ppmConfig_t *ppmConfig)
|
void pgResetFn_ppmConfig(ppmConfig_t *ppmConfig)
|
||||||
|
|
|
@ -26,7 +26,7 @@
|
||||||
|
|
||||||
#include "platform.h"
|
#include "platform.h"
|
||||||
|
|
||||||
#if defined(USE_PWM) || defined(USE_PPM)
|
#if defined(USE_RX_PWM) || defined(USE_RX_PPM)
|
||||||
|
|
||||||
#include "common/utils.h"
|
#include "common/utils.h"
|
||||||
|
|
||||||
|
|
|
@ -357,7 +357,7 @@ void rxInit(void)
|
||||||
break;
|
break;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if defined(USE_PWM) || defined(USE_PPM)
|
#if defined(USE_RX_PWM) || defined(USE_RX_PPM)
|
||||||
case RX_PROVIDER_PPM:
|
case RX_PROVIDER_PPM:
|
||||||
case RX_PROVIDER_PARALLEL_PWM:
|
case RX_PROVIDER_PARALLEL_PWM:
|
||||||
rxPwmInit(rxConfig(), &rxRuntimeState);
|
rxPwmInit(rxConfig(), &rxRuntimeState);
|
||||||
|
@ -406,7 +406,7 @@ bool rxAreFlightChannelsValid(void)
|
||||||
|
|
||||||
void suspendRxSignal(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) {
|
if (rxRuntimeState.rxProvider == RX_PROVIDER_PARALLEL_PWM || rxRuntimeState.rxProvider == RX_PROVIDER_PPM) {
|
||||||
suspendRxSignalUntil = micros() + DELAY_1500_MS; // 1.5s
|
suspendRxSignalUntil = micros() + DELAY_1500_MS; // 1.5s
|
||||||
skipRxSamples = SKIP_RC_SAMPLES_ON_RESUME;
|
skipRxSamples = SKIP_RC_SAMPLES_ON_RESUME;
|
||||||
|
@ -417,7 +417,7 @@ void suspendRxSignal(void)
|
||||||
|
|
||||||
void resumeRxSignal(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) {
|
if (rxRuntimeState.rxProvider == RX_PROVIDER_PARALLEL_PWM || rxRuntimeState.rxProvider == RX_PROVIDER_PPM) {
|
||||||
suspendRxSignalUntil = micros();
|
suspendRxSignalUntil = micros();
|
||||||
skipRxSamples = SKIP_RC_SAMPLES_ON_RESUME;
|
skipRxSamples = SKIP_RC_SAMPLES_ON_RESUME;
|
||||||
|
@ -515,7 +515,7 @@ FAST_CODE_NOINLINE void rxFrameCheck(timeUs_t currentTimeUs, timeDelta_t current
|
||||||
default:
|
default:
|
||||||
|
|
||||||
break;
|
break;
|
||||||
#if defined(USE_PWM) || defined(USE_PPM)
|
#if defined(USE_RX_PWM) || defined(USE_RX_PPM)
|
||||||
case RX_PROVIDER_PPM:
|
case RX_PROVIDER_PPM:
|
||||||
if (isPPMDataBeingReceived()) {
|
if (isPPMDataBeingReceived()) {
|
||||||
signalReceived = true;
|
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);
|
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 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];
|
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);
|
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) {
|
if (rxRuntimeState.rxProvider == RX_PROVIDER_PARALLEL_PWM || rxRuntimeState.rxProvider == RX_PROVIDER_PPM) {
|
||||||
// smooth output for PWM and PPM using moving average
|
// smooth output for PWM and PPM using moving average
|
||||||
rcData[channel] = calculateChannelMovingAverage(channel, sample);
|
rcData[channel] = calculateChannelMovingAverage(channel, sample);
|
||||||
|
|
|
@ -96,8 +96,8 @@
|
||||||
#undef USE_ADC
|
#undef USE_ADC
|
||||||
#undef USE_VCP
|
#undef USE_VCP
|
||||||
#undef USE_OSD
|
#undef USE_OSD
|
||||||
#undef USE_PPM
|
#undef USE_RX_PPM
|
||||||
#undef USE_PWM
|
#undef USE_RX_PWM
|
||||||
#undef USE_SERIALRX
|
#undef USE_SERIALRX
|
||||||
#undef USE_SERIALRX_CRSF
|
#undef USE_SERIALRX_CRSF
|
||||||
#undef USE_SERIALRX_GHST
|
#undef USE_SERIALRX_GHST
|
||||||
|
@ -108,6 +108,7 @@
|
||||||
#undef USE_SERIALRX_SUMH
|
#undef USE_SERIALRX_SUMH
|
||||||
#undef USE_SERIALRX_XBUS
|
#undef USE_SERIALRX_XBUS
|
||||||
#undef USE_LED_STRIP
|
#undef USE_LED_STRIP
|
||||||
|
#undef USE_PWM_OUTPUT
|
||||||
#undef USE_TELEMETRY_FRSKY_HUB
|
#undef USE_TELEMETRY_FRSKY_HUB
|
||||||
#undef USE_TELEMETRY_HOTT
|
#undef USE_TELEMETRY_HOTT
|
||||||
#undef USE_TELEMETRY_SMARTPORT
|
#undef USE_TELEMETRY_SMARTPORT
|
||||||
|
|
|
@ -322,22 +322,27 @@
|
||||||
#if !defined(USE_SERIAL_4WAY_BLHELI_BOOTLOADER) && !defined(USE_SERIAL_4WAY_SK_BOOTLOADER)
|
#if !defined(USE_SERIAL_4WAY_BLHELI_BOOTLOADER) && !defined(USE_SERIAL_4WAY_SK_BOOTLOADER)
|
||||||
#undef USE_SERIAL_4WAY_BLHELI_INTERFACE
|
#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))
|
#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
|
#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)
|
|
||||||
#define USE_PWM_OUTPUT
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if !defined(USE_PWM_OUTPUT)
|
#if defined(USE_RX_PWM) || defined(USE_DSHOT) || defined(USE_LED_STRIP) || defined(USE_TRANSPONDER) || defined(USE_BEEPER) || defined(USE_SERIAL_4WAY_BLHELI_INTERFACE)
|
||||||
#undef USE_SERIAL_4WAY_BLHELI_INTERFACE // implementation requires USE_PWM_OUTPUT to find motor outputs.
|
#ifndef USE_PWM_OUTPUT
|
||||||
|
#define USE_PWM_OUTPUT
|
||||||
|
#endif
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if !defined(USE_LED_STRIP)
|
#if !defined(USE_LED_STRIP)
|
||||||
#undef USE_LED_STRIP_STATUS_MODE
|
#undef USE_LED_STRIP_STATUS_MODE
|
||||||
#endif
|
#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)
|
#if defined(USE_LED_STRIP) && !defined(USE_LED_STRIP_STATUS_MODE)
|
||||||
#define USE_WS2811_SINGLE_COLOUR
|
#define USE_WS2811_SINGLE_COLOUR
|
||||||
#endif
|
#endif
|
||||||
|
|
|
@ -325,14 +325,15 @@ extern uint8_t _dmaram_end__;
|
||||||
#define USE_RANGEFINDER_TF
|
#define USE_RANGEFINDER_TF
|
||||||
#endif
|
#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_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
|
#define USE_PINIO
|
||||||
|
|
||||||
#if !defined(USE_SERIAL_RX)
|
#if !defined(USE_SERIAL_RX)
|
||||||
|
|
||||||
#define USE_SERIALRX
|
#define USE_SERIALRX
|
||||||
#define USE_SERIALRX_CRSF // Team Black Sheep Crossfire protocol
|
#define USE_SERIALRX_CRSF // Team Black Sheep Crossfire protocol
|
||||||
#define USE_SERIALRX_GHST // ImmersionRC Ghost 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_FPORT // FrSky FPort
|
||||||
#define USE_SERIALRX_XBUS // JR
|
#define USE_SERIALRX_XBUS // JR
|
||||||
#define USE_SERIALRX_SRXL2 // Spektrum SRXL2 protocol
|
#define USE_SERIALRX_SRXL2 // Spektrum SRXL2 protocol
|
||||||
|
|
||||||
#endif // !defined(USE_SERIAL_RX)
|
#endif // !defined(USE_SERIAL_RX)
|
||||||
|
|
||||||
#if !defined(USE_TELEMETRY)
|
#if !defined(USE_TELEMETRY)
|
||||||
|
|
Loading…
Add table
Add a link
Reference in a new issue