mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-17 21:35:44 +03:00
Add new basic feature conditionals (#8175)
Add new basic feature conditionals
This commit is contained in:
commit
d9382ad012
18 changed files with 79 additions and 7 deletions
|
@ -24,6 +24,8 @@
|
||||||
|
|
||||||
#include "platform.h"
|
#include "platform.h"
|
||||||
|
|
||||||
|
#ifdef USE_DMA
|
||||||
|
|
||||||
#include "drivers/nvic.h"
|
#include "drivers/nvic.h"
|
||||||
#include "dma.h"
|
#include "dma.h"
|
||||||
|
|
||||||
|
@ -141,4 +143,5 @@ DMA_Channel_TypeDef* dmaGetRefByIdentifier(const dmaIdentifier_e identifier)
|
||||||
dmaChannelDescriptor_t* dmaGetDescriptorByIdentifier(const dmaIdentifier_e identifier)
|
dmaChannelDescriptor_t* dmaGetDescriptorByIdentifier(const dmaIdentifier_e identifier)
|
||||||
{
|
{
|
||||||
return &dmaDescriptors[DMA_IDENTIFIER_TO_INDEX(identifier)];
|
return &dmaDescriptors[DMA_IDENTIFIER_TO_INDEX(identifier)];
|
||||||
}
|
}
|
||||||
|
#endif
|
||||||
|
|
|
@ -24,6 +24,8 @@
|
||||||
|
|
||||||
#include "platform.h"
|
#include "platform.h"
|
||||||
|
|
||||||
|
#ifdef USE_DMA
|
||||||
|
|
||||||
#include "drivers/nvic.h"
|
#include "drivers/nvic.h"
|
||||||
#include "dma.h"
|
#include "dma.h"
|
||||||
#include "resource.h"
|
#include "resource.h"
|
||||||
|
@ -156,4 +158,5 @@ dmaChannelDescriptor_t* dmaGetDescriptorByIdentifier(const dmaIdentifier_e ident
|
||||||
uint32_t dmaGetChannel(const uint8_t channel)
|
uint32_t dmaGetChannel(const uint8_t channel)
|
||||||
{
|
{
|
||||||
return ((uint32_t)channel*2)<<24;
|
return ((uint32_t)channel*2)<<24;
|
||||||
}
|
}
|
||||||
|
#endif
|
||||||
|
|
|
@ -24,6 +24,8 @@
|
||||||
|
|
||||||
#include "platform.h"
|
#include "platform.h"
|
||||||
|
|
||||||
|
#ifdef USE_DMA
|
||||||
|
|
||||||
#include "drivers/nvic.h"
|
#include "drivers/nvic.h"
|
||||||
#include "drivers/dma.h"
|
#include "drivers/dma.h"
|
||||||
#include "resource.h"
|
#include "resource.h"
|
||||||
|
@ -139,3 +141,4 @@ uint32_t dmaGetChannel(const uint8_t channel)
|
||||||
{
|
{
|
||||||
return ((uint32_t)channel*2)<<24;
|
return ((uint32_t)channel*2)<<24;
|
||||||
}
|
}
|
||||||
|
#endif
|
||||||
|
|
|
@ -24,6 +24,9 @@
|
||||||
#include <math.h>
|
#include <math.h>
|
||||||
|
|
||||||
#include "platform.h"
|
#include "platform.h"
|
||||||
|
|
||||||
|
#ifdef USE_PWM_OUTPUT
|
||||||
|
|
||||||
#include "drivers/time.h"
|
#include "drivers/time.h"
|
||||||
|
|
||||||
#include "drivers/io.h"
|
#include "drivers/io.h"
|
||||||
|
@ -684,7 +687,7 @@ FAST_CODE uint16_t prepareDshotPacket(motorDmaOutput_t *const motor)
|
||||||
|
|
||||||
return packet;
|
return packet;
|
||||||
}
|
}
|
||||||
#endif
|
#endif // USE_DSHOT
|
||||||
|
|
||||||
#ifdef USE_SERVOS
|
#ifdef USE_SERVOS
|
||||||
void pwmWriteServo(uint8_t index, float value)
|
void pwmWriteServo(uint8_t index, float value)
|
||||||
|
@ -725,7 +728,7 @@ void servoDevInit(const servoDevConfig_t *servoConfig)
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
#endif
|
#endif // USE_SERVOS
|
||||||
|
|
||||||
#ifdef USE_BEEPER
|
#ifdef USE_BEEPER
|
||||||
void pwmWriteBeeper(bool onoffBeep)
|
void pwmWriteBeeper(bool onoffBeep)
|
||||||
|
@ -768,4 +771,5 @@ void beeperPwmInit(const ioTag_t tag, uint16_t frequency)
|
||||||
beeperPwm.enabled = false;
|
beeperPwm.enabled = false;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
#endif // USE_BEEPER
|
||||||
#endif
|
#endif
|
||||||
|
|
|
@ -41,6 +41,7 @@ typedef enum {
|
||||||
typedef struct uartPort_s {
|
typedef struct uartPort_s {
|
||||||
serialPort_t port;
|
serialPort_t port;
|
||||||
|
|
||||||
|
#ifdef USE_DMA
|
||||||
#if defined(STM32F7)
|
#if defined(STM32F7)
|
||||||
DMA_HandleTypeDef rxDMAHandle;
|
DMA_HandleTypeDef rxDMAHandle;
|
||||||
DMA_HandleTypeDef txDMAHandle;
|
DMA_HandleTypeDef txDMAHandle;
|
||||||
|
@ -61,6 +62,7 @@ typedef struct uartPort_s {
|
||||||
|
|
||||||
uint32_t txDMAPeripheralBaseAddr;
|
uint32_t txDMAPeripheralBaseAddr;
|
||||||
uint32_t rxDMAPeripheralBaseAddr;
|
uint32_t rxDMAPeripheralBaseAddr;
|
||||||
|
#endif // USE_DMA
|
||||||
|
|
||||||
#ifdef USE_HAL_DRIVER
|
#ifdef USE_HAL_DRIVER
|
||||||
// All USARTs can also be used as UART, and we use them only as UART.
|
// All USARTs can also be used as UART, and we use them only as UART.
|
||||||
|
|
|
@ -41,9 +41,12 @@ void systemBeep(bool onoff)
|
||||||
#ifdef USE_BEEPER
|
#ifdef USE_BEEPER
|
||||||
if (beeperFrequency == 0) {
|
if (beeperFrequency == 0) {
|
||||||
IOWrite(beeperIO, beeperInverted ? onoff : !onoff);
|
IOWrite(beeperIO, beeperInverted ? onoff : !onoff);
|
||||||
} else {
|
}
|
||||||
|
#ifdef USE_PWM_OUTPUT
|
||||||
|
else {
|
||||||
pwmWriteBeeper(onoff);
|
pwmWriteBeeper(onoff);
|
||||||
}
|
}
|
||||||
|
#endif
|
||||||
#else
|
#else
|
||||||
UNUSED(onoff);
|
UNUSED(onoff);
|
||||||
#endif
|
#endif
|
||||||
|
@ -54,10 +57,13 @@ void systemBeepToggle(void)
|
||||||
#ifdef USE_BEEPER
|
#ifdef USE_BEEPER
|
||||||
if (beeperFrequency == 0) {
|
if (beeperFrequency == 0) {
|
||||||
IOToggle(beeperIO);
|
IOToggle(beeperIO);
|
||||||
} else {
|
}
|
||||||
|
#ifdef USE_PWM_OUTPUT
|
||||||
|
else {
|
||||||
pwmToggleBeeper();
|
pwmToggleBeeper();
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
void beeperInit(const beeperDevConfig_t *config)
|
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);
|
IOConfigGPIO(beeperIO, config->isOpenDrain ? IOCFG_OUT_OD : IOCFG_OUT_PP);
|
||||||
}
|
}
|
||||||
systemBeep(false);
|
systemBeep(false);
|
||||||
} else {
|
}
|
||||||
|
#ifdef USE_PWM_OUTPUT
|
||||||
|
else {
|
||||||
const ioTag_t beeperTag = config->ioTag;
|
const ioTag_t beeperTag = config->ioTag;
|
||||||
beeperPwmInit(beeperTag, beeperFrequency);
|
beeperPwmInit(beeperTag, beeperFrequency);
|
||||||
}
|
}
|
||||||
|
#endif
|
||||||
#else
|
#else
|
||||||
UNUSED(config);
|
UNUSED(config);
|
||||||
#endif
|
#endif
|
||||||
|
|
|
@ -25,6 +25,8 @@
|
||||||
|
|
||||||
#include "platform.h"
|
#include "platform.h"
|
||||||
|
|
||||||
|
#ifdef USE_TIMER
|
||||||
|
|
||||||
#include "build/atomic.h"
|
#include "build/atomic.h"
|
||||||
|
|
||||||
#include "common/utils.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;
|
return (uint16_t)((timerClock(tim) + hz / 2 ) / hz) - 1;
|
||||||
}
|
}
|
||||||
|
#endif
|
||||||
|
|
|
@ -20,6 +20,8 @@
|
||||||
|
|
||||||
#include "platform.h"
|
#include "platform.h"
|
||||||
|
|
||||||
|
#ifdef USE_TIMER
|
||||||
|
|
||||||
#include "drivers/io.h"
|
#include "drivers/io.h"
|
||||||
#include "timer.h"
|
#include "timer.h"
|
||||||
|
|
||||||
|
@ -111,3 +113,4 @@ ioTag_t timerioTagGetByUsage(timerUsageFlag_e usageFlag, uint8_t index)
|
||||||
#endif
|
#endif
|
||||||
return IO_TAG_NONE;
|
return IO_TAG_NONE;
|
||||||
}
|
}
|
||||||
|
#endif
|
||||||
|
|
|
@ -25,6 +25,8 @@
|
||||||
|
|
||||||
#include "platform.h"
|
#include "platform.h"
|
||||||
|
|
||||||
|
#ifdef USE_TIMER
|
||||||
|
|
||||||
#include "build/atomic.h"
|
#include "build/atomic.h"
|
||||||
|
|
||||||
#include "common/utils.h"
|
#include "common/utils.h"
|
||||||
|
@ -1121,3 +1123,4 @@ HAL_StatusTypeDef DMA_SetCurrDataCounter(TIM_HandleTypeDef *htim, uint32_t Chann
|
||||||
/* Return function status */
|
/* Return function status */
|
||||||
return HAL_OK;
|
return HAL_OK;
|
||||||
}
|
}
|
||||||
|
#endif
|
||||||
|
|
|
@ -20,6 +20,8 @@
|
||||||
|
|
||||||
#include "platform.h"
|
#include "platform.h"
|
||||||
|
|
||||||
|
#ifdef USE_TIMER
|
||||||
|
|
||||||
#include "common/utils.h"
|
#include "common/utils.h"
|
||||||
|
|
||||||
#include "stm32f10x.h"
|
#include "stm32f10x.h"
|
||||||
|
@ -52,3 +54,4 @@ uint32_t timerClock(TIM_TypeDef *tim)
|
||||||
UNUSED(tim);
|
UNUSED(tim);
|
||||||
return SystemCoreClock;
|
return SystemCoreClock;
|
||||||
}
|
}
|
||||||
|
#endif
|
||||||
|
|
|
@ -20,6 +20,8 @@
|
||||||
|
|
||||||
#include "platform.h"
|
#include "platform.h"
|
||||||
|
|
||||||
|
#ifdef USE_TIMER
|
||||||
|
|
||||||
#include "common/utils.h"
|
#include "common/utils.h"
|
||||||
|
|
||||||
#include "stm32f30x.h"
|
#include "stm32f30x.h"
|
||||||
|
@ -44,3 +46,4 @@ uint32_t timerClock(TIM_TypeDef *tim)
|
||||||
UNUSED(tim);
|
UNUSED(tim);
|
||||||
return SystemCoreClock;
|
return SystemCoreClock;
|
||||||
}
|
}
|
||||||
|
#endif
|
||||||
|
|
|
@ -20,6 +20,8 @@
|
||||||
|
|
||||||
#include "platform.h"
|
#include "platform.h"
|
||||||
|
|
||||||
|
#ifdef USE_TIMER
|
||||||
|
|
||||||
#include "common/utils.h"
|
#include "common/utils.h"
|
||||||
|
|
||||||
#include "drivers/dma.h"
|
#include "drivers/dma.h"
|
||||||
|
@ -220,3 +222,4 @@ uint32_t timerClock(TIM_TypeDef *tim)
|
||||||
#error "No timer clock defined correctly for MCU"
|
#error "No timer clock defined correctly for MCU"
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
|
#endif
|
||||||
|
|
|
@ -20,6 +20,8 @@
|
||||||
|
|
||||||
#include "platform.h"
|
#include "platform.h"
|
||||||
|
|
||||||
|
#ifdef USE_TIMER
|
||||||
|
|
||||||
#include "common/utils.h"
|
#include "common/utils.h"
|
||||||
|
|
||||||
#include "drivers/dma.h"
|
#include "drivers/dma.h"
|
||||||
|
@ -205,3 +207,4 @@ uint32_t timerClock(TIM_TypeDef *tim)
|
||||||
UNUSED(tim);
|
UNUSED(tim);
|
||||||
return SystemCoreClock;
|
return SystemCoreClock;
|
||||||
}
|
}
|
||||||
|
#endif
|
||||||
|
|
|
@ -426,9 +426,11 @@ static void validateAndFixConfig(void)
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if defined(USE_BEEPER)
|
#if defined(USE_BEEPER)
|
||||||
|
#ifdef USE_TIMER
|
||||||
if (beeperDevConfig()->frequency && !timerGetByTag(beeperDevConfig()->ioTag)) {
|
if (beeperDevConfig()->frequency && !timerGetByTag(beeperDevConfig()->ioTag)) {
|
||||||
beeperDevConfigMutable()->frequency = 0;
|
beeperDevConfigMutable()->frequency = 0;
|
||||||
}
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
if (beeperConfig()->beeper_off_flags & ~BEEPER_ALLOWED_MODES) {
|
if (beeperConfig()->beeper_off_flags & ~BEEPER_ALLOWED_MODES) {
|
||||||
beeperConfigMutable()->beeper_off_flags = 0;
|
beeperConfigMutable()->beeper_off_flags = 0;
|
||||||
|
|
|
@ -369,7 +369,9 @@ void init(void)
|
||||||
mcoInit(mcoConfig());
|
mcoInit(mcoConfig());
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
#ifdef USE_TIMER
|
||||||
timerInit(); // timer must be initialized before any channel is allocated
|
timerInit(); // timer must be initialized before any channel is allocated
|
||||||
|
#endif
|
||||||
|
|
||||||
#ifdef BUS_SWITCH_PIN
|
#ifdef BUS_SWITCH_PIN
|
||||||
busSwitchInit();
|
busSwitchInit();
|
||||||
|
@ -402,11 +404,15 @@ void init(void)
|
||||||
if (motorConfig()->dev.motorPwmProtocol == PWM_TYPE_BRUSHED) {
|
if (motorConfig()->dev.motorPwmProtocol == PWM_TYPE_BRUSHED) {
|
||||||
idlePulse = 0; // brushed motors
|
idlePulse = 0; // brushed motors
|
||||||
}
|
}
|
||||||
|
#ifdef USE_PWM_OUTPUT
|
||||||
/* Motors needs to be initialized soon as posible because hardware initialization
|
/* Motors needs to be initialized soon as posible because hardware initialization
|
||||||
* may send spurious pulses to esc's causing their early initialization. Also ppm
|
* 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. */
|
* receiver may share timer with motors so motors MUST be initialized here. */
|
||||||
motorDevInit(&motorConfig()->dev, idlePulse, getMotorCount());
|
motorDevInit(&motorConfig()->dev, idlePulse, getMotorCount());
|
||||||
systemState |= SYSTEM_STATE_MOTORS_READY;
|
systemState |= SYSTEM_STATE_MOTORS_READY;
|
||||||
|
#else
|
||||||
|
UNUSED(idlePulse);
|
||||||
|
#endif
|
||||||
|
|
||||||
if (0) {}
|
if (0) {}
|
||||||
#if defined(USE_PPM)
|
#if defined(USE_PPM)
|
||||||
|
@ -752,9 +758,11 @@ void init(void)
|
||||||
|
|
||||||
#endif // VTX_CONTROL
|
#endif // VTX_CONTROL
|
||||||
|
|
||||||
|
#ifdef USE_TIMER
|
||||||
// start all timers
|
// start all timers
|
||||||
// TODO - not implemented yet
|
// TODO - not implemented yet
|
||||||
timerStart();
|
timerStart();
|
||||||
|
#endif
|
||||||
|
|
||||||
ENABLE_STATE(SMALL_ANGLE);
|
ENABLE_STATE(SMALL_ANGLE);
|
||||||
|
|
||||||
|
@ -784,7 +792,9 @@ void init(void)
|
||||||
rcdeviceInit();
|
rcdeviceInit();
|
||||||
#endif // USE_RCDEVICE
|
#endif // USE_RCDEVICE
|
||||||
|
|
||||||
|
#ifdef USE_PWM_OUTPUT
|
||||||
pwmEnableMotors();
|
pwmEnableMotors();
|
||||||
|
#endif
|
||||||
|
|
||||||
setArmingDisabled(ARMING_DISABLED_BOOT_GRACE_TIME);
|
setArmingDisabled(ARMING_DISABLED_BOOT_GRACE_TIME);
|
||||||
|
|
||||||
|
|
|
@ -106,9 +106,11 @@ void pgResetFn_motorConfig(motorConfig_t *motorConfig)
|
||||||
motorConfig->dev.useBurstDshot = ENABLE_DSHOT_DMAR;
|
motorConfig->dev.useBurstDshot = ENABLE_DSHOT_DMAR;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
#ifdef USE_TIMER
|
||||||
for (int motorIndex = 0; motorIndex < MAX_SUPPORTED_MOTORS; motorIndex++) {
|
for (int motorIndex = 0; motorIndex < MAX_SUPPORTED_MOTORS; motorIndex++) {
|
||||||
motorConfig->dev.ioTags[motorIndex] = timerioTagGetByUsage(TIM_USE_MOTOR, motorIndex);
|
motorConfig->dev.ioTags[motorIndex] = timerioTagGetByUsage(TIM_USE_MOTOR, motorIndex);
|
||||||
}
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
motorConfig->motorPoleCount = 14; // Most brushes motors that we use are 14 poles
|
motorConfig->motorPoleCount = 14; // Most brushes motors that we use are 14 poles
|
||||||
}
|
}
|
||||||
|
@ -516,6 +518,7 @@ void mixerResetDisarmedMotors(void)
|
||||||
|
|
||||||
void writeMotors(void)
|
void writeMotors(void)
|
||||||
{
|
{
|
||||||
|
#ifdef USE_PWM_OUTPUT
|
||||||
if (pwmAreMotorsEnabled()) {
|
if (pwmAreMotorsEnabled()) {
|
||||||
#if defined(USE_DSHOT) && defined(USE_DSHOT_TELEMETRY)
|
#if defined(USE_DSHOT) && defined(USE_DSHOT_TELEMETRY)
|
||||||
if (!pwmStartMotorUpdate(motorCount)) {
|
if (!pwmStartMotorUpdate(motorCount)) {
|
||||||
|
@ -527,6 +530,7 @@ void writeMotors(void)
|
||||||
}
|
}
|
||||||
pwmCompleteMotorUpdate(motorCount);
|
pwmCompleteMotorUpdate(motorCount);
|
||||||
}
|
}
|
||||||
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
static void writeAllMotors(int16_t mc)
|
static void writeAllMotors(int16_t mc)
|
||||||
|
@ -546,8 +550,10 @@ void stopMotors(void)
|
||||||
|
|
||||||
void stopPwmAllMotors(void)
|
void stopPwmAllMotors(void)
|
||||||
{
|
{
|
||||||
|
#ifdef USE_PWM_OUTPUT
|
||||||
pwmShutdownPulsesForAllMotors(motorCount);
|
pwmShutdownPulsesForAllMotors(motorCount);
|
||||||
delayMicroseconds(1500);
|
delayMicroseconds(1500);
|
||||||
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
static FAST_RAM_ZERO_INIT float throttle = 0;
|
static FAST_RAM_ZERO_INIT float throttle = 0;
|
||||||
|
|
|
@ -935,13 +935,18 @@ static bool mspProcessOutCommand(uint8_t cmdMSP, sbuf_t *dst)
|
||||||
|
|
||||||
case MSP_MOTOR:
|
case MSP_MOTOR:
|
||||||
for (unsigned i = 0; i < 8; i++) {
|
for (unsigned i = 0; i < 8; i++) {
|
||||||
|
#ifdef USE_PWM_OUTPUT
|
||||||
if (i >= MAX_SUPPORTED_MOTORS || !pwmGetMotors()[i].enabled) {
|
if (i >= MAX_SUPPORTED_MOTORS || !pwmGetMotors()[i].enabled) {
|
||||||
sbufWriteU16(dst, 0);
|
sbufWriteU16(dst, 0);
|
||||||
continue;
|
continue;
|
||||||
}
|
}
|
||||||
|
|
||||||
sbufWriteU16(dst, convertMotorToExternal(motor[i]));
|
sbufWriteU16(dst, convertMotorToExternal(motor[i]));
|
||||||
|
#else
|
||||||
|
sbufWriteU16(dst, 0);
|
||||||
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case MSP_RC:
|
case MSP_RC:
|
||||||
|
|
|
@ -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_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_CLI
|
||||||
#define USE_SERIAL_PASSTHROUGH
|
#define USE_SERIAL_PASSTHROUGH
|
||||||
#define USE_TASK_STATISTICS
|
#define USE_TASK_STATISTICS
|
||||||
|
|
Loading…
Add table
Add a link
Reference in a new issue