diff --git a/src/main/drivers/dma.c b/src/main/drivers/dma.c index 62484bcce3..1672cbcab0 100644 --- a/src/main/drivers/dma.c +++ b/src/main/drivers/dma.c @@ -24,6 +24,8 @@ #include "platform.h" +#ifdef USE_DMA + #include "drivers/nvic.h" #include "dma.h" @@ -141,4 +143,5 @@ DMA_Channel_TypeDef* dmaGetRefByIdentifier(const dmaIdentifier_e identifier) dmaChannelDescriptor_t* dmaGetDescriptorByIdentifier(const dmaIdentifier_e identifier) { return &dmaDescriptors[DMA_IDENTIFIER_TO_INDEX(identifier)]; -} \ No newline at end of file +} +#endif diff --git a/src/main/drivers/dma_stm32f4xx.c b/src/main/drivers/dma_stm32f4xx.c index eb1aed2f79..0389e9ce70 100644 --- a/src/main/drivers/dma_stm32f4xx.c +++ b/src/main/drivers/dma_stm32f4xx.c @@ -24,6 +24,8 @@ #include "platform.h" +#ifdef USE_DMA + #include "drivers/nvic.h" #include "dma.h" #include "resource.h" @@ -156,4 +158,5 @@ dmaChannelDescriptor_t* dmaGetDescriptorByIdentifier(const dmaIdentifier_e ident uint32_t dmaGetChannel(const uint8_t channel) { return ((uint32_t)channel*2)<<24; -} \ No newline at end of file +} +#endif diff --git a/src/main/drivers/dma_stm32f7xx.c b/src/main/drivers/dma_stm32f7xx.c index 2cc6273e87..d672f7fb18 100644 --- a/src/main/drivers/dma_stm32f7xx.c +++ b/src/main/drivers/dma_stm32f7xx.c @@ -24,6 +24,8 @@ #include "platform.h" +#ifdef USE_DMA + #include "drivers/nvic.h" #include "drivers/dma.h" #include "resource.h" @@ -139,3 +141,4 @@ uint32_t dmaGetChannel(const uint8_t channel) { return ((uint32_t)channel*2)<<24; } +#endif diff --git a/src/main/drivers/pwm_output.c b/src/main/drivers/pwm_output.c index 581b679ed6..2ca7d60790 100644 --- a/src/main/drivers/pwm_output.c +++ b/src/main/drivers/pwm_output.c @@ -24,6 +24,9 @@ #include #include "platform.h" + +#ifdef USE_PWM_OUTPUT + #include "drivers/time.h" #include "drivers/io.h" @@ -684,7 +687,7 @@ FAST_CODE uint16_t prepareDshotPacket(motorDmaOutput_t *const motor) return packet; } -#endif +#endif // USE_DSHOT #ifdef USE_SERVOS void pwmWriteServo(uint8_t index, float value) @@ -725,7 +728,7 @@ void servoDevInit(const servoDevConfig_t *servoConfig) } } -#endif +#endif // USE_SERVOS #ifdef USE_BEEPER void pwmWriteBeeper(bool onoffBeep) @@ -768,4 +771,5 @@ void beeperPwmInit(const ioTag_t tag, uint16_t frequency) beeperPwm.enabled = false; } } +#endif // USE_BEEPER #endif diff --git a/src/main/drivers/serial_uart.h b/src/main/drivers/serial_uart.h index ee22b64750..667905e577 100644 --- a/src/main/drivers/serial_uart.h +++ b/src/main/drivers/serial_uart.h @@ -41,6 +41,7 @@ typedef enum { typedef struct uartPort_s { serialPort_t port; +#ifdef USE_DMA #if defined(STM32F7) DMA_HandleTypeDef rxDMAHandle; DMA_HandleTypeDef txDMAHandle; @@ -61,6 +62,7 @@ typedef struct uartPort_s { uint32_t txDMAPeripheralBaseAddr; uint32_t rxDMAPeripheralBaseAddr; +#endif // USE_DMA #ifdef USE_HAL_DRIVER // All USARTs can also be used as UART, and we use them only as UART. diff --git a/src/main/drivers/sound_beeper.c b/src/main/drivers/sound_beeper.c index e57d7d9f3c..4e0d077754 100644 --- a/src/main/drivers/sound_beeper.c +++ b/src/main/drivers/sound_beeper.c @@ -41,9 +41,12 @@ void systemBeep(bool onoff) #ifdef USE_BEEPER if (beeperFrequency == 0) { IOWrite(beeperIO, beeperInverted ? onoff : !onoff); - } else { + } +#ifdef USE_PWM_OUTPUT + else { pwmWriteBeeper(onoff); } +#endif #else UNUSED(onoff); #endif @@ -54,10 +57,13 @@ void systemBeepToggle(void) #ifdef USE_BEEPER if (beeperFrequency == 0) { IOToggle(beeperIO); - } else { + } +#ifdef USE_PWM_OUTPUT + else { pwmToggleBeeper(); } #endif +#endif } void beeperInit(const beeperDevConfig_t *config) @@ -72,10 +78,13 @@ void beeperInit(const beeperDevConfig_t *config) IOConfigGPIO(beeperIO, config->isOpenDrain ? IOCFG_OUT_OD : IOCFG_OUT_PP); } systemBeep(false); - } else { + } +#ifdef USE_PWM_OUTPUT + else { const ioTag_t beeperTag = config->ioTag; beeperPwmInit(beeperTag, beeperFrequency); } +#endif #else UNUSED(config); #endif diff --git a/src/main/drivers/timer.c b/src/main/drivers/timer.c index f8037b0119..f617302689 100644 --- a/src/main/drivers/timer.c +++ b/src/main/drivers/timer.c @@ -25,6 +25,8 @@ #include "platform.h" +#ifdef USE_TIMER + #include "build/atomic.h" #include "common/utils.h" @@ -922,3 +924,4 @@ uint16_t timerGetPrescalerByDesiredHertz(TIM_TypeDef *tim, uint32_t hz) } return (uint16_t)((timerClock(tim) + hz / 2 ) / hz) - 1; } +#endif diff --git a/src/main/drivers/timer_common.c b/src/main/drivers/timer_common.c index 6b8dd203f1..5335362142 100644 --- a/src/main/drivers/timer_common.c +++ b/src/main/drivers/timer_common.c @@ -20,6 +20,8 @@ #include "platform.h" +#ifdef USE_TIMER + #include "drivers/io.h" #include "timer.h" @@ -111,3 +113,4 @@ ioTag_t timerioTagGetByUsage(timerUsageFlag_e usageFlag, uint8_t index) #endif return IO_TAG_NONE; } +#endif diff --git a/src/main/drivers/timer_hal.c b/src/main/drivers/timer_hal.c index df4631d1d2..24c2403577 100644 --- a/src/main/drivers/timer_hal.c +++ b/src/main/drivers/timer_hal.c @@ -25,6 +25,8 @@ #include "platform.h" +#ifdef USE_TIMER + #include "build/atomic.h" #include "common/utils.h" @@ -1121,3 +1123,4 @@ HAL_StatusTypeDef DMA_SetCurrDataCounter(TIM_HandleTypeDef *htim, uint32_t Chann /* Return function status */ return HAL_OK; } +#endif diff --git a/src/main/drivers/timer_stm32f10x.c b/src/main/drivers/timer_stm32f10x.c index ba569a67b7..826349be7d 100644 --- a/src/main/drivers/timer_stm32f10x.c +++ b/src/main/drivers/timer_stm32f10x.c @@ -20,6 +20,8 @@ #include "platform.h" +#ifdef USE_TIMER + #include "common/utils.h" #include "stm32f10x.h" @@ -52,3 +54,4 @@ uint32_t timerClock(TIM_TypeDef *tim) UNUSED(tim); return SystemCoreClock; } +#endif diff --git a/src/main/drivers/timer_stm32f30x.c b/src/main/drivers/timer_stm32f30x.c index 8550b65fed..a872b394d4 100644 --- a/src/main/drivers/timer_stm32f30x.c +++ b/src/main/drivers/timer_stm32f30x.c @@ -20,6 +20,8 @@ #include "platform.h" +#ifdef USE_TIMER + #include "common/utils.h" #include "stm32f30x.h" @@ -44,3 +46,4 @@ uint32_t timerClock(TIM_TypeDef *tim) UNUSED(tim); return SystemCoreClock; } +#endif diff --git a/src/main/drivers/timer_stm32f4xx.c b/src/main/drivers/timer_stm32f4xx.c index 94269af10f..9df4eb8a7c 100644 --- a/src/main/drivers/timer_stm32f4xx.c +++ b/src/main/drivers/timer_stm32f4xx.c @@ -20,6 +20,8 @@ #include "platform.h" +#ifdef USE_TIMER + #include "common/utils.h" #include "drivers/dma.h" @@ -220,3 +222,4 @@ uint32_t timerClock(TIM_TypeDef *tim) #error "No timer clock defined correctly for MCU" #endif } +#endif diff --git a/src/main/drivers/timer_stm32f7xx.c b/src/main/drivers/timer_stm32f7xx.c index 237fee68d7..792a1be6b8 100644 --- a/src/main/drivers/timer_stm32f7xx.c +++ b/src/main/drivers/timer_stm32f7xx.c @@ -20,6 +20,8 @@ #include "platform.h" +#ifdef USE_TIMER + #include "common/utils.h" #include "drivers/dma.h" @@ -205,3 +207,4 @@ uint32_t timerClock(TIM_TypeDef *tim) UNUSED(tim); return SystemCoreClock; } +#endif diff --git a/src/main/fc/config.c b/src/main/fc/config.c index aca072abf5..a6f726e50f 100644 --- a/src/main/fc/config.c +++ b/src/main/fc/config.c @@ -426,9 +426,11 @@ static void validateAndFixConfig(void) #endif #if defined(USE_BEEPER) +#ifdef USE_TIMER if (beeperDevConfig()->frequency && !timerGetByTag(beeperDevConfig()->ioTag)) { beeperDevConfigMutable()->frequency = 0; } +#endif if (beeperConfig()->beeper_off_flags & ~BEEPER_ALLOWED_MODES) { beeperConfigMutable()->beeper_off_flags = 0; diff --git a/src/main/fc/init.c b/src/main/fc/init.c index 89bf1a31d3..cd27532bcf 100644 --- a/src/main/fc/init.c +++ b/src/main/fc/init.c @@ -369,7 +369,9 @@ void init(void) mcoInit(mcoConfig()); #endif +#ifdef USE_TIMER timerInit(); // timer must be initialized before any channel is allocated +#endif #ifdef BUS_SWITCH_PIN busSwitchInit(); @@ -402,11 +404,15 @@ void init(void) if (motorConfig()->dev.motorPwmProtocol == PWM_TYPE_BRUSHED) { idlePulse = 0; // brushed motors } +#ifdef USE_PWM_OUTPUT /* Motors needs to be initialized soon as posible because hardware initialization * may send spurious pulses to esc's causing their early initialization. Also ppm * receiver may share timer with motors so motors MUST be initialized here. */ motorDevInit(&motorConfig()->dev, idlePulse, getMotorCount()); systemState |= SYSTEM_STATE_MOTORS_READY; +#else + UNUSED(idlePulse); +#endif if (0) {} #if defined(USE_PPM) @@ -752,9 +758,11 @@ void init(void) #endif // VTX_CONTROL +#ifdef USE_TIMER // start all timers // TODO - not implemented yet timerStart(); +#endif ENABLE_STATE(SMALL_ANGLE); @@ -784,7 +792,9 @@ void init(void) rcdeviceInit(); #endif // USE_RCDEVICE +#ifdef USE_PWM_OUTPUT pwmEnableMotors(); +#endif setArmingDisabled(ARMING_DISABLED_BOOT_GRACE_TIME); diff --git a/src/main/flight/mixer.c b/src/main/flight/mixer.c index 5762cd3b5c..ff6ad27dde 100644 --- a/src/main/flight/mixer.c +++ b/src/main/flight/mixer.c @@ -106,9 +106,11 @@ void pgResetFn_motorConfig(motorConfig_t *motorConfig) motorConfig->dev.useBurstDshot = ENABLE_DSHOT_DMAR; #endif +#ifdef USE_TIMER for (int motorIndex = 0; motorIndex < MAX_SUPPORTED_MOTORS; motorIndex++) { motorConfig->dev.ioTags[motorIndex] = timerioTagGetByUsage(TIM_USE_MOTOR, motorIndex); } +#endif motorConfig->motorPoleCount = 14; // Most brushes motors that we use are 14 poles } @@ -516,6 +518,7 @@ void mixerResetDisarmedMotors(void) void writeMotors(void) { +#ifdef USE_PWM_OUTPUT if (pwmAreMotorsEnabled()) { #if defined(USE_DSHOT) && defined(USE_DSHOT_TELEMETRY) if (!pwmStartMotorUpdate(motorCount)) { @@ -527,6 +530,7 @@ void writeMotors(void) } pwmCompleteMotorUpdate(motorCount); } +#endif } static void writeAllMotors(int16_t mc) @@ -546,8 +550,10 @@ void stopMotors(void) void stopPwmAllMotors(void) { +#ifdef USE_PWM_OUTPUT pwmShutdownPulsesForAllMotors(motorCount); delayMicroseconds(1500); +#endif } static FAST_RAM_ZERO_INIT float throttle = 0; diff --git a/src/main/msp/msp.c b/src/main/msp/msp.c index 12f78548b9..088089e099 100644 --- a/src/main/msp/msp.c +++ b/src/main/msp/msp.c @@ -935,13 +935,18 @@ static bool mspProcessOutCommand(uint8_t cmdMSP, sbuf_t *dst) case MSP_MOTOR: for (unsigned i = 0; i < 8; i++) { +#ifdef USE_PWM_OUTPUT if (i >= MAX_SUPPORTED_MOTORS || !pwmGetMotors()[i].enabled) { sbufWriteU16(dst, 0); continue; } sbufWriteU16(dst, convertMotorToExternal(motor[i])); +#else + sbufWriteU16(dst, 0); +#endif } + break; case MSP_RC: diff --git a/src/main/target/common_pre.h b/src/main/target/common_pre.h index 5324b58e82..17785b20d0 100644 --- a/src/main/target/common_pre.h +++ b/src/main/target/common_pre.h @@ -140,6 +140,10 @@ #define USE_BRUSHED_ESC_AUTODETECT // Detect if brushed motors are connected and set defaults appropriately to avoid motors spinning on boot +#define USE_PWM_OUTPUT +#define USE_DMA +#define USE_TIMER + #define USE_CLI #define USE_SERIAL_PASSTHROUGH #define USE_TASK_STATISTICS