mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-13 11:29:58 +03:00
FIX: USE_PWM not working (#12004)
This commit is contained in:
parent
b125bec6e4
commit
af1001a35c
6 changed files with 57 additions and 88 deletions
10
Makefile
10
Makefile
|
@ -97,10 +97,6 @@ HSE_VALUE ?= 8000000
|
|||
# used for turning on features like VCP and SDCARD
|
||||
FEATURES =
|
||||
|
||||
# used to disable features based on flash space shortage (larger number => more features disabled)
|
||||
FEATURE_CUT_LEVEL_SUPPLIED := $(FEATURE_CUT_LEVEL)
|
||||
FEATURE_CUT_LEVEL =
|
||||
|
||||
ifneq ($(BOARD),)
|
||||
# silently ignore if the file is not present. Allows for target defaults.
|
||||
-include $(ROOT)/src/main/board/$(BOARD)/board.mk
|
||||
|
@ -173,12 +169,6 @@ ifneq ($(HSE_VALUE),)
|
|||
DEVICE_FLAGS := $(DEVICE_FLAGS) -DHSE_VALUE=$(HSE_VALUE)
|
||||
endif
|
||||
|
||||
ifneq ($(FEATURE_CUT_LEVEL_SUPPLIED),)
|
||||
DEVICE_FLAGS := $(DEVICE_FLAGS) -DFEATURE_CUT_LEVEL=$(FEATURE_CUT_LEVEL_SUPPLIED)
|
||||
else ifneq ($(FEATURE_CUT_LEVEL),)
|
||||
DEVICE_FLAGS := $(DEVICE_FLAGS) -DFEATURE_CUT_LEVEL=$(FEATURE_CUT_LEVEL)
|
||||
endif
|
||||
|
||||
TARGET_DIR = $(ROOT)/src/main/target/$(TARGET)
|
||||
TARGET_DIR_SRC = $(notdir $(wildcard $(TARGET_DIR)/*.c))
|
||||
|
||||
|
|
|
@ -1414,7 +1414,9 @@ static void cliSerialPassthrough(const char *cmdName, char *cmdline)
|
|||
bool enableBaudCb = false;
|
||||
int port1PinioDtr = 0;
|
||||
bool port1ResetOnDtr = false;
|
||||
#ifdef USE_PWM_OUTPUT
|
||||
bool escSensorPassthrough = false;
|
||||
#endif
|
||||
char *saveptr;
|
||||
char* tok = strtok_r(cmdline, " ", &saveptr);
|
||||
int index = 0;
|
||||
|
@ -1423,7 +1425,9 @@ static void cliSerialPassthrough(const char *cmdName, char *cmdline)
|
|||
switch (index) {
|
||||
case 0:
|
||||
if (strcasestr(tok, "esc_sensor")) {
|
||||
#ifdef USE_PWM_OUTPUT
|
||||
escSensorPassthrough = true;
|
||||
#endif
|
||||
const serialPortConfig_t *portConfig = findSerialPortConfig(FUNCTION_ESC_SENSOR);
|
||||
ports[0].id = portConfig->identifier;
|
||||
} else {
|
||||
|
@ -4937,11 +4941,7 @@ static void printVersion(const char *cmdName, bool printBoardInfo)
|
|||
MSP_API_VERSION_STRING
|
||||
);
|
||||
|
||||
#ifdef FEATURE_CUT_LEVEL
|
||||
cliPrintLinef(" / FEATURE CUT LEVEL %d", FEATURE_CUT_LEVEL);
|
||||
#else
|
||||
cliPrintLinefeed();
|
||||
#endif
|
||||
|
||||
#if defined(USE_CUSTOM_DEFAULTS)
|
||||
if (hasCustomDefaults()) {
|
||||
|
|
|
@ -70,6 +70,8 @@ void motorWriteAll(float *values)
|
|||
}
|
||||
motorDevice->vTable.updateComplete();
|
||||
}
|
||||
#else
|
||||
UNUSED(values);
|
||||
#endif
|
||||
}
|
||||
|
||||
|
|
|
@ -241,7 +241,7 @@ static bool mspIsMspArmingEnabled(void)
|
|||
static uint8_t mspPassthroughMode;
|
||||
static uint8_t mspPassthroughArgument;
|
||||
|
||||
#ifdef USE_ESCSERIAL
|
||||
#if defined(USE_ESCSERIAL) && defined(USE_SERIAL_4WAY_BLHELI_INTERFACE)
|
||||
static void mspEscPassthroughFn(serialPort_t *serialPort)
|
||||
{
|
||||
escEnablePassthrough(serialPort, &motorConfig()->dev, mspPassthroughArgument, mspPassthroughMode);
|
||||
|
|
|
@ -379,6 +379,10 @@
|
|||
#undef BEEPER_PWM_HZ
|
||||
#endif
|
||||
|
||||
#if defined(USE_PWM) || defined(USE_DSHOT) || defined(USE_LED_STRIP) || defined(USE_TRANSPONDER) || defined(USE_BEEPER)
|
||||
#define USE_PWM_OUTPUT
|
||||
#endif
|
||||
|
||||
#if defined(USE_DSHOT) || defined(USE_LED_STRIP) || defined(USE_TRANSPONDER)
|
||||
#define USE_TIMER_DMA
|
||||
#else
|
||||
|
|
|
@ -224,10 +224,7 @@ extern uint8_t _dmaram_end__;
|
|||
#define DMA_RAM_RW
|
||||
#endif
|
||||
|
||||
#define USE_BRUSHED_ESC_AUTODETECT // Detect if brushed motors are connected and set defaults appropriately to avoid motors spinning on boot
|
||||
|
||||
#define USE_MOTOR
|
||||
#define USE_PWM_OUTPUT
|
||||
#define USE_DMA
|
||||
#define USE_TIMER
|
||||
|
||||
|
@ -236,8 +233,16 @@ extern uint8_t _dmaram_end__;
|
|||
#define USE_GYRO_REGISTER_DUMP // Adds gyroregisters command to cli to dump configured register values
|
||||
#define USE_IMU_CALC
|
||||
|
||||
#if (!defined(CLOUD_BUILD))
|
||||
#if !defined(CLOUD_BUILD)
|
||||
|
||||
#define USE_PPM
|
||||
|
||||
#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_PINIOBOX
|
||||
|
||||
#define USE_SERIALRX
|
||||
#define USE_SERIALRX_CRSF // Team Black Sheep Crossfire protocol
|
||||
#define USE_SERIALRX_GHST // ImmersionRC Ghost Protocol
|
||||
|
@ -252,8 +257,42 @@ extern uint8_t _dmaram_end__;
|
|||
#define USE_TELEMETRY_CRSF
|
||||
#define USE_TELEMETRY_GHST
|
||||
#define USE_TELEMETRY_SRXL
|
||||
|
||||
#define USE_SERVOS
|
||||
|
||||
#define USE_VTX
|
||||
|
||||
#define USE_TELEMETRY_HOTT
|
||||
#define USE_TELEMETRY_LTM
|
||||
#define USE_SERIALRX_SUMH // Graupner legacy protocol
|
||||
#define USE_SERIALRX_XBUS // JR
|
||||
#define USE_CRSF_CMS_TELEMETRY
|
||||
#define USE_CRSF_LINK_STATISTICS
|
||||
|
||||
#define USE_SERIALRX_JETIEXBUS
|
||||
#define USE_TELEMETRY_IBUS
|
||||
#define USE_TELEMETRY_IBUS_EXTENDED
|
||||
#define USE_TELEMETRY_JETIEXBUS
|
||||
#define USE_TELEMETRY_MAVLINK
|
||||
#define USE_SERIALRX_SRXL2 // Spektrum SRXL2 protocol
|
||||
|
||||
#define USE_GPS
|
||||
#define USE_OSD
|
||||
#define USE_LED_STRIP
|
||||
|
||||
#endif // !defined(CLOUD_BUILD)
|
||||
|
||||
#if defined(USE_VTX)
|
||||
#define USE_VTX_COMMON
|
||||
#define USE_VTX_CONTROL
|
||||
#define USE_VTX_SMARTAUDIO
|
||||
#define USE_VTX_TRAMP
|
||||
#define USE_VTX_MSP
|
||||
#define USE_VTX_TABLE
|
||||
#endif
|
||||
|
||||
#define USE_HUFFMAN
|
||||
|
||||
#define PID_PROFILE_COUNT 4
|
||||
#define CONTROL_RATE_PROFILE_COUNT 4
|
||||
|
||||
|
@ -262,7 +301,6 @@ extern uint8_t _dmaram_end__;
|
|||
#define USE_CLI_BATCH
|
||||
#define USE_RESOURCE_MGMT
|
||||
#define USE_RUNAWAY_TAKEOFF // Runaway Takeoff Prevention (anti-taz)
|
||||
#define USE_SERVOS
|
||||
|
||||
#define USE_GYRO_OVERFLOW_CHECK
|
||||
#define USE_YAW_SPIN_RECOVERY
|
||||
|
@ -271,63 +309,30 @@ extern uint8_t _dmaram_end__;
|
|||
#define USE_DSHOT_DMAR
|
||||
#endif
|
||||
|
||||
#if ((TARGET_FLASH_SIZE > 256 && !defined(FEATURE_CUT_LEVEL)) || (FEATURE_CUT_LEVEL < 12))
|
||||
#define USE_CMS
|
||||
#define USE_MSP_DISPLAYPORT
|
||||
#define USE_MSP_OVER_TELEMETRY
|
||||
#define USE_OSD_OVER_MSP_DISPLAYPORT
|
||||
#define USE_LED_STRIP
|
||||
#endif
|
||||
|
||||
#if ((TARGET_FLASH_SIZE > 256 && !defined(FEATURE_CUT_LEVEL)) || (FEATURE_CUT_LEVEL < 11))
|
||||
#define USE_VTX_COMMON
|
||||
#define USE_VTX_CONTROL
|
||||
#define USE_VTX_SMARTAUDIO
|
||||
#define USE_VTX_TRAMP
|
||||
#define USE_VTX_MSP
|
||||
#endif
|
||||
|
||||
#if ((TARGET_FLASH_SIZE > 256 && !defined(FEATURE_CUT_LEVEL)) || (FEATURE_CUT_LEVEL < 10))
|
||||
#define USE_VIRTUAL_CURRENT_METER
|
||||
#define USE_CAMERA_CONTROL
|
||||
#define USE_ESC_SENSOR
|
||||
#define USE_SERIAL_4WAY_BLHELI_BOOTLOADER
|
||||
#define USE_RCDEVICE
|
||||
#endif
|
||||
|
||||
#if ((TARGET_FLASH_SIZE > 256 && !defined(FEATURE_CUT_LEVEL)) || (FEATURE_CUT_LEVEL < 9))
|
||||
#define USE_GYRO_LPF2
|
||||
#endif
|
||||
|
||||
#if ((TARGET_FLASH_SIZE > 256 && !defined(FEATURE_CUT_LEVEL)) || (FEATURE_CUT_LEVEL < 8))
|
||||
#define USE_LAUNCH_CONTROL
|
||||
#define USE_DYN_LPF
|
||||
#define USE_D_MIN
|
||||
#endif
|
||||
|
||||
#if ((TARGET_FLASH_SIZE > 256 && !defined(FEATURE_CUT_LEVEL)) || (FEATURE_CUT_LEVEL < 7))
|
||||
#define USE_THROTTLE_BOOST
|
||||
#define USE_INTEGRATED_YAW_CONTROL
|
||||
#endif
|
||||
|
||||
#if ((TARGET_FLASH_SIZE > 256 && !defined(FEATURE_CUT_LEVEL)) || (FEATURE_CUT_LEVEL < 6))
|
||||
#define USE_ITERM_RELAX
|
||||
#define USE_RC_SMOOTHING_FILTER
|
||||
#define USE_THRUST_LINEARIZATION
|
||||
#define USE_TPA_MODE
|
||||
#endif
|
||||
|
||||
#if ((TARGET_FLASH_SIZE > 256 && !defined(FEATURE_CUT_LEVEL)) || (FEATURE_CUT_LEVEL < 5))
|
||||
#define USE_PWM
|
||||
#endif
|
||||
|
||||
#if ((TARGET_FLASH_SIZE > 256 && !defined(FEATURE_CUT_LEVEL)) || (FEATURE_CUT_LEVEL < 4))
|
||||
#define USE_HUFFMAN
|
||||
#define USE_PINIO
|
||||
#define USE_PINIOBOX
|
||||
#endif
|
||||
|
||||
#if ((TARGET_FLASH_SIZE > 256 && !defined(FEATURE_CUT_LEVEL)) || (FEATURE_CUT_LEVEL < 3))
|
||||
#ifdef USE_SERIALRX_SPEKTRUM
|
||||
#define USE_SPEKTRUM_BIND
|
||||
#define USE_SPEKTRUM_BIND_PLUG
|
||||
|
@ -337,21 +342,10 @@ extern uint8_t _dmaram_end__;
|
|||
#define USE_SPEKTRUM_VTX_CONTROL
|
||||
#define USE_SPEKTRUM_VTX_TELEMETRY
|
||||
#define USE_SPEKTRUM_CMS_TELEMETRY
|
||||
#endif
|
||||
|
||||
#define USE_PIN_PULL_UP_DOWN
|
||||
#endif
|
||||
#endif
|
||||
|
||||
#if ((TARGET_FLASH_SIZE > 256 && !defined(FEATURE_CUT_LEVEL)) || (FEATURE_CUT_LEVEL < 2))
|
||||
#if (!defined(CLOUD_BUILD))
|
||||
#define USE_TELEMETRY_HOTT
|
||||
#define USE_TELEMETRY_LTM
|
||||
#define USE_SERIALRX_SUMH // Graupner legacy protocol
|
||||
#define USE_SERIALRX_XBUS // JR
|
||||
|
||||
#endif
|
||||
#endif
|
||||
|
||||
#if ((TARGET_FLASH_SIZE > 256 && !defined(FEATURE_CUT_LEVEL)) || (FEATURE_CUT_LEVEL < 1))
|
||||
#define USE_BOARD_INFO
|
||||
#define USE_EXTENDED_CMS_MENUS
|
||||
#define USE_RTC_TIME
|
||||
|
@ -360,13 +354,6 @@ extern uint8_t _dmaram_end__;
|
|||
#define USE_RX_RSSI_DBM
|
||||
#define USE_RX_RSNR
|
||||
|
||||
#if !defined(CLOUD_BUILD)
|
||||
#define USE_CRSF_CMS_TELEMETRY
|
||||
#define USE_CRSF_LINK_STATISTICS
|
||||
#endif
|
||||
#endif
|
||||
|
||||
#if (TARGET_FLASH_SIZE > 256)
|
||||
#define USE_AIRMODE_LPF
|
||||
#define USE_CANVAS
|
||||
#define USE_FRSKYOSD
|
||||
|
@ -384,7 +371,6 @@ extern uint8_t _dmaram_end__;
|
|||
#define USE_CMS_FAILSAFE_MENU
|
||||
#define USE_CMS_GPS_RESCUE_MENU
|
||||
#define USE_TELEMETRY_SENSORS_DISABLED_DETAILS
|
||||
#define USE_VTX_TABLE
|
||||
#define USE_PERSISTENT_STATS
|
||||
#define USE_PROFILE_NAMES
|
||||
#define USE_FEEDFORWARD
|
||||
|
@ -396,18 +382,6 @@ extern uint8_t _dmaram_end__;
|
|||
#define USE_CRSF_V3
|
||||
#define USE_CRAFTNAME_MSGS
|
||||
|
||||
#if (!defined(CLOUD_BUILD))
|
||||
#define USE_SERIALRX_JETIEXBUS
|
||||
#define USE_TELEMETRY_IBUS
|
||||
#define USE_TELEMETRY_IBUS_EXTENDED
|
||||
#define USE_TELEMETRY_JETIEXBUS
|
||||
#define USE_TELEMETRY_MAVLINK
|
||||
#define USE_SERIALRX_SRXL2 // Spektrum SRXL2 protocol
|
||||
|
||||
#define USE_GPS
|
||||
#define USE_OSD
|
||||
#endif
|
||||
|
||||
#ifdef USE_GPS
|
||||
#define USE_GPS_NMEA
|
||||
#define USE_GPS_UBLOX
|
||||
|
@ -420,7 +394,6 @@ extern uint8_t _dmaram_end__;
|
|||
#define USE_OSD_PROFILES
|
||||
#define USE_OSD_STICK_OVERLAY
|
||||
#endif
|
||||
#endif
|
||||
|
||||
#if (TARGET_FLASH_SIZE > 512)
|
||||
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue