Make burst and non-burst runtime configurable
This commit is contained in:
parent
5866a1a662
commit
9475988218
|
@ -47,6 +47,9 @@ static uint16_t freqBeep = 0;
|
|||
|
||||
static bool pwmMotorsEnabled = false;
|
||||
static bool isDshot = false;
|
||||
#ifdef USE_DSHOT_DMAR
|
||||
bool useBurstDshot = false;
|
||||
#endif
|
||||
|
||||
static void pwmOCConfig(TIM_TypeDef *tim, uint8_t channel, uint16_t value, uint8_t output)
|
||||
{
|
||||
|
@ -260,6 +263,11 @@ void motorDevInit(const motorDevConfig_t *motorConfig, uint16_t idlePulse, uint8
|
|||
loadDmaBuffer = &loadDmaBufferDshot;
|
||||
pwmCompleteWrite = &pwmCompleteDshotMotorUpdate;
|
||||
isDshot = true;
|
||||
#ifdef USE_DSHOT_DMAR
|
||||
if (motorConfig->useBurstDshot) {
|
||||
useBurstDshot = true;
|
||||
}
|
||||
#endif
|
||||
break;
|
||||
#endif
|
||||
}
|
||||
|
|
|
@ -109,7 +109,7 @@ typedef enum {
|
|||
|
||||
typedef struct {
|
||||
TIM_TypeDef *timer;
|
||||
#if defined(USE_DSHOT_DMAR)
|
||||
#if defined(USE_DSHOT) && defined(USE_DSHOT_DMAR)
|
||||
#if !defined(USE_HAL_DRIVER)
|
||||
#ifdef STM32F3
|
||||
DMA_Channel_TypeDef *dmaBurstRef;
|
||||
|
@ -118,18 +118,18 @@ typedef struct {
|
|||
#endif
|
||||
uint16_t dmaBurstLength;
|
||||
#endif
|
||||
uint32_t dmaBurstBuffer[DSHOT_DMA_BUFFER_SIZE * 4];
|
||||
#else
|
||||
uint16_t timerDmaSources;
|
||||
#endif
|
||||
uint32_t dmaBurstBuffer[DSHOT_DMA_BUFFER_SIZE * 4];
|
||||
uint16_t timerDmaSources;
|
||||
} motorDmaTimer_t;
|
||||
|
||||
typedef struct {
|
||||
ioTag_t ioTag;
|
||||
const timerHardware_t *timerHardware;
|
||||
uint16_t value;
|
||||
#if !defined(USE_DSHOT_DMAR)
|
||||
#ifdef USE_DSHOT
|
||||
uint16_t timerDmaSource;
|
||||
bool configured;
|
||||
#endif
|
||||
motorDmaTimer_t *timer;
|
||||
volatile bool requestTelemetry;
|
||||
|
@ -170,9 +170,14 @@ typedef struct motorDevConfig_s {
|
|||
uint8_t motorPwmProtocol; // Pwm Protocol
|
||||
uint8_t motorPwmInversion; // Active-High vs Active-Low. Useful for brushed FCs converted for brushless operation
|
||||
uint8_t useUnsyncedPwm;
|
||||
#ifdef USE_DSHOT_DMAR
|
||||
uint8_t useBurstDshot;
|
||||
#endif
|
||||
ioTag_t ioTags[MAX_SUPPORTED_MOTORS];
|
||||
} motorDevConfig_t;
|
||||
|
||||
extern bool useBurstDshot;
|
||||
|
||||
void motorDevInit(const motorDevConfig_t *motorDevConfig, uint16_t idlePulse, uint8_t motorCount);
|
||||
|
||||
typedef struct servoDevConfig_s {
|
||||
|
|
|
@ -60,28 +60,25 @@ void pwmWriteDshotInt(uint8_t index, uint16_t value)
|
|||
{
|
||||
motorDmaOutput_t *const motor = &dmaMotors[index];
|
||||
|
||||
#ifdef USE_DSHOT_DMAR
|
||||
if (!motor->timerHardware || !motor->timerHardware->dmaTimUPRef) {
|
||||
if (!motor->configured) {
|
||||
return;
|
||||
}
|
||||
#else
|
||||
if (!motor->timerHardware || !motor->timerHardware->dmaRef) {
|
||||
return;
|
||||
}
|
||||
#endif
|
||||
|
||||
uint16_t packet = prepareDshotPacket(motor, value);
|
||||
uint8_t bufferSize;
|
||||
|
||||
#ifdef USE_DSHOT_DMAR
|
||||
if (useBurstDshot) {
|
||||
bufferSize = loadDmaBuffer(&motor->timer->dmaBurstBuffer[timerLookupChannelIndex(motor->timerHardware->channel)], 4, packet);
|
||||
motor->timer->dmaBurstLength = bufferSize * 4;
|
||||
#else
|
||||
} else
|
||||
#endif
|
||||
{
|
||||
bufferSize = loadDmaBuffer(motor->dmaBuffer, 1, packet);
|
||||
motor->timer->timerDmaSources |= motor->timerDmaSource;
|
||||
DMA_SetCurrDataCounter(motor->timerHardware->dmaRef, bufferSize);
|
||||
DMA_Cmd(motor->timerHardware->dmaRef, ENABLE);
|
||||
#endif
|
||||
}
|
||||
}
|
||||
|
||||
void pwmCompleteDshotMotorUpdate(uint8_t motorCount)
|
||||
|
@ -90,15 +87,18 @@ void pwmCompleteDshotMotorUpdate(uint8_t motorCount)
|
|||
|
||||
for (int i = 0; i < dmaMotorTimerCount; i++) {
|
||||
#ifdef USE_DSHOT_DMAR
|
||||
if (useBurstDshot) {
|
||||
DMA_SetCurrDataCounter(dmaMotorTimers[i].dmaBurstRef, dmaMotorTimers[i].dmaBurstLength);
|
||||
DMA_Cmd(dmaMotorTimers[i].dmaBurstRef, ENABLE);
|
||||
TIM_DMAConfig(dmaMotorTimers[i].timer, TIM_DMABase_CCR1, TIM_DMABurstLength_4Transfers);
|
||||
TIM_DMACmd(dmaMotorTimers[i].timer, TIM_DMA_Update, ENABLE);
|
||||
#else
|
||||
} else
|
||||
#endif
|
||||
{
|
||||
TIM_SetCounter(dmaMotorTimers[i].timer, 0);
|
||||
TIM_DMACmd(dmaMotorTimers[i].timer, dmaMotorTimers[i].timerDmaSources, ENABLE);
|
||||
dmaMotorTimers[i].timerDmaSources = 0;
|
||||
#endif
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -106,13 +106,18 @@ static void motor_DMA_IRQHandler(dmaChannelDescriptor_t *descriptor)
|
|||
{
|
||||
if (DMA_GET_FLAG_STATUS(descriptor, DMA_IT_TCIF)) {
|
||||
motorDmaOutput_t * const motor = &dmaMotors[descriptor->userParam];
|
||||
|
||||
#ifdef USE_DSHOT_DMAR
|
||||
if (useBurstDshot) {
|
||||
DMA_Cmd(motor->timerHardware->dmaTimUPRef, DISABLE);
|
||||
TIM_DMACmd(motor->timerHardware->tim, TIM_DMA_Update, DISABLE);
|
||||
#else
|
||||
} else
|
||||
#endif
|
||||
{
|
||||
DMA_Cmd(motor->timerHardware->dmaRef, DISABLE);
|
||||
TIM_DMACmd(motor->timerHardware->tim, motor->timerDmaSource, DISABLE);
|
||||
#endif
|
||||
}
|
||||
|
||||
DMA_CLEAR_FLAG(descriptor, DMA_IT_TCIF);
|
||||
}
|
||||
}
|
||||
|
@ -125,11 +130,16 @@ void pwmDshotMotorHardwareConfig(const timerHardware_t *timerHardware, uint8_t m
|
|||
typedef DMA_Channel_TypeDef dmaStream_t;
|
||||
#endif
|
||||
|
||||
dmaStream_t *dmaRef;
|
||||
|
||||
#ifdef USE_DSHOT_DMAR
|
||||
dmaStream_t *dmaRef = timerHardware->dmaTimUPRef;
|
||||
#else
|
||||
dmaStream_t *dmaRef = timerHardware->dmaRef;
|
||||
if (useBurstDshot) {
|
||||
dmaRef = timerHardware->dmaTimUPRef;
|
||||
} else
|
||||
#endif
|
||||
{
|
||||
dmaRef = timerHardware->dmaRef;
|
||||
}
|
||||
|
||||
if (dmaRef == NULL) {
|
||||
return;
|
||||
|
@ -195,21 +205,26 @@ void pwmDshotMotorHardwareConfig(const timerHardware_t *timerHardware, uint8_t m
|
|||
motor->timer = &dmaMotorTimers[timerIndex];
|
||||
|
||||
#ifdef USE_DSHOT_DMAR
|
||||
if (useBurstDshot) {
|
||||
motor->timer->dmaBurstRef = dmaRef;
|
||||
|
||||
if (!configureTimer) {
|
||||
motor->configured = true;
|
||||
return;
|
||||
}
|
||||
#else
|
||||
} else
|
||||
#endif
|
||||
{
|
||||
motor->timerDmaSource = timerDmaSource(timerHardware->channel);
|
||||
motor->timer->timerDmaSources &= ~motor->timerDmaSource;
|
||||
#endif
|
||||
}
|
||||
|
||||
DMA_Cmd(dmaRef, DISABLE);
|
||||
DMA_DeInit(dmaRef);
|
||||
DMA_StructInit(&DMA_InitStructure);
|
||||
|
||||
#ifdef USE_DSHOT_DMAR
|
||||
if (useBurstDshot) {
|
||||
dmaInit(timerHardware->dmaTimUPIrqHandler, OWNER_TIMUP, timerGetTIMNumber(timerHardware->tim));
|
||||
dmaSetHandler(timerHardware->dmaTimUPIrqHandler, motor_DMA_IRQHandler, NVIC_BUILD_PRIORITY(1, 2), motorIndex);
|
||||
|
||||
|
@ -233,8 +248,9 @@ void pwmDshotMotorHardwareConfig(const timerHardware_t *timerHardware, uint8_t m
|
|||
DMA_InitStructure.DMA_MemoryDataSize = DMA_MemoryDataSize_Word;
|
||||
DMA_InitStructure.DMA_Mode = DMA_Mode_Normal;
|
||||
DMA_InitStructure.DMA_Priority = DMA_Priority_High;
|
||||
|
||||
#else // !USE_DSHOT_DMAR
|
||||
} else
|
||||
#endif
|
||||
{
|
||||
dmaInit(timerHardware->dmaIrqHandler, OWNER_MOTOR, RESOURCE_INDEX(motorIndex));
|
||||
dmaSetHandler(timerHardware->dmaIrqHandler, motor_DMA_IRQHandler, NVIC_BUILD_PRIORITY(1, 2), motorIndex);
|
||||
|
||||
|
@ -259,12 +275,14 @@ void pwmDshotMotorHardwareConfig(const timerHardware_t *timerHardware, uint8_t m
|
|||
DMA_InitStructure.DMA_MemoryDataSize = DMA_MemoryDataSize_Word;
|
||||
DMA_InitStructure.DMA_Mode = DMA_Mode_Normal;
|
||||
DMA_InitStructure.DMA_Priority = DMA_Priority_High;
|
||||
#endif // USE_DSHOT_DMAR
|
||||
}
|
||||
|
||||
// XXX Consolidate common settings in the next refactor
|
||||
|
||||
DMA_Init(dmaRef, &DMA_InitStructure);
|
||||
DMA_ITConfig(dmaRef, DMA_IT_TC, ENABLE);
|
||||
|
||||
motor->configured = true;
|
||||
}
|
||||
|
||||
#endif
|
||||
|
|
|
@ -52,33 +52,31 @@ uint8_t getTimerIndex(TIM_TypeDef *timer)
|
|||
void pwmWriteDshotInt(uint8_t index, uint16_t value)
|
||||
{
|
||||
motorDmaOutput_t *const motor = &dmaMotors[index];
|
||||
#ifdef USE_DSHOT_DMAR
|
||||
if (!motor->timerHardware || !motor->timerHardware->dmaTimUPRef) {
|
||||
|
||||
if (!motor->configured) {
|
||||
return;
|
||||
}
|
||||
#else
|
||||
if (!motor->timerHardware || !motor->timerHardware->dmaRef) {
|
||||
return;
|
||||
}
|
||||
#endif
|
||||
|
||||
uint16_t packet = prepareDshotPacket(motor, value);
|
||||
|
||||
uint8_t bufferSize;
|
||||
|
||||
#ifdef USE_DSHOT_DMAR
|
||||
if (useBurstDshot) {
|
||||
bufferSize = loadDmaBuffer(&motor->timer->dmaBurstBuffer[timerLookupChannelIndex(motor->timerHardware->channel)], 4, packet);
|
||||
if(HAL_DMA_STATE_READY == motor->TimHandle.hdma[motor->timerDmaIndex]->State) {
|
||||
if (HAL_DMA_STATE_READY == motor->TimHandle.hdma[motor->timerDmaIndex]->State) {
|
||||
HAL_DMA_Start_IT(motor->TimHandle.hdma[motor->timerDmaIndex], (uint32_t)motor->timer->dmaBurstBuffer, (uint32_t)&motor->TimHandle.Instance->DMAR, bufferSize * 4);
|
||||
}
|
||||
#else
|
||||
} else
|
||||
#endif
|
||||
{
|
||||
bufferSize = loadDmaBuffer(motor->dmaBuffer, 1, packet);
|
||||
|
||||
if (DMA_SetCurrDataCounter(&motor->TimHandle, motor->timerHardware->channel, motor->dmaBuffer, bufferSize) != HAL_OK) {
|
||||
/* DMA set error */
|
||||
return;
|
||||
}
|
||||
#endif
|
||||
}
|
||||
}
|
||||
|
||||
void pwmCompleteDshotMotorUpdate(uint8_t motorCount)
|
||||
|
@ -86,6 +84,7 @@ void pwmCompleteDshotMotorUpdate(uint8_t motorCount)
|
|||
UNUSED(motorCount);
|
||||
for (int i = 0; i < dmaMotorTimerCount; i++) {
|
||||
#ifdef USE_DSHOT_DMAR
|
||||
if (useBurstDshot) {
|
||||
/* configure the DMA Burst Mode */
|
||||
LL_TIM_ConfigDMABurst(dmaMotorTimers[i].timer, LL_TIM_DMABURST_BASEADDR_CCR1, LL_TIM_DMABURST_LENGTH_4TRANSFERS);
|
||||
/* Enable the TIM DMA Request */
|
||||
|
@ -98,12 +97,14 @@ void pwmCompleteDshotMotorUpdate(uint8_t motorCount)
|
|||
}
|
||||
/* Enable the counter */
|
||||
LL_TIM_EnableCounter(dmaMotorTimers[i].timer);
|
||||
#else
|
||||
} else
|
||||
#endif
|
||||
{
|
||||
/* Reset timer counter */
|
||||
LL_TIM_SetCounter(dmaMotorTimers[i].timer, 0);
|
||||
/* Enable channel DMA requests */
|
||||
dmaMotorTimers[i].timer->DIER |= dmaMotorTimers[i].timerDmaSources;
|
||||
#endif
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -112,25 +113,27 @@ static void motor_DMA_IRQHandler(dmaChannelDescriptor_t* descriptor)
|
|||
motorDmaOutput_t * const motor = &dmaMotors[descriptor->userParam];
|
||||
HAL_DMA_IRQHandler(motor->TimHandle.hdma[motor->timerDmaIndex]);
|
||||
#ifdef USE_DSHOT_DMAR
|
||||
if (useBurstDshot) {
|
||||
LL_TIM_DisableCounter(motor->timerHardware->tim);
|
||||
LL_TIM_DisableDMAReq_UPDATE(motor->timerHardware->tim);
|
||||
#else
|
||||
} else
|
||||
#endif
|
||||
{
|
||||
__HAL_DMA_DISABLE(&motor->hdma_tim);
|
||||
TIM_DMACmd(&motor->TimHandle, motor->timerHardware->channel, DISABLE);
|
||||
#endif
|
||||
}
|
||||
}
|
||||
|
||||
void pwmDshotMotorHardwareConfig(const timerHardware_t *timerHardware, uint8_t motorIndex, motorPwmProtocolTypes_e pwmProtocolType, uint8_t output)
|
||||
{
|
||||
#ifdef USE_DSHOT_DMAR
|
||||
if (timerHardware->dmaTimUPRef == NULL) {
|
||||
if (useBurstDshot && timerHardware->dmaTimUPRef == NULL) {
|
||||
return;
|
||||
}
|
||||
#else
|
||||
} else
|
||||
#endif
|
||||
if (timerHardware->dmaRef == NULL) {
|
||||
return;
|
||||
}
|
||||
#endif
|
||||
|
||||
motorDmaOutput_t * const motor = &dmaMotors[motorIndex];
|
||||
motor->timerHardware = timerHardware;
|
||||
|
@ -172,6 +175,7 @@ void pwmDshotMotorHardwareConfig(const timerHardware_t *timerHardware, uint8_t m
|
|||
motor->hdma_tim.Init.PeriphBurst = DMA_PBURST_SINGLE;
|
||||
|
||||
#ifdef USE_DSHOT_DMAR
|
||||
if (useBurstDshot) {
|
||||
motor->timerDmaIndex = TIM_DMA_ID_UPDATE;
|
||||
/* Set the DMAR specific dma handle parameters to be configured */
|
||||
motor->hdma_tim.Init.Channel = timerHardware->dmaTimUPChannel;
|
||||
|
@ -185,7 +189,9 @@ void pwmDshotMotorHardwareConfig(const timerHardware_t *timerHardware, uint8_t m
|
|||
|
||||
dmaInit(timerHardware->dmaTimUPIrqHandler, OWNER_TIMUP, timerGetTIMNumber(timerHardware->tim));
|
||||
dmaSetHandler(timerHardware->dmaTimUPIrqHandler, motor_DMA_IRQHandler, NVIC_BUILD_PRIORITY(1, 2), motorIndex);
|
||||
#else
|
||||
} else
|
||||
#endif
|
||||
{
|
||||
motor->timerDmaIndex = timerDmaIndex(timerHardware->channel);
|
||||
motor->timer->timerDmaSources |= timerDmaSource(timerHardware->channel);
|
||||
|
||||
|
@ -201,7 +207,7 @@ void pwmDshotMotorHardwareConfig(const timerHardware_t *timerHardware, uint8_t m
|
|||
|
||||
dmaInit(timerHardware->dmaIrqHandler, OWNER_MOTOR, RESOURCE_INDEX(motorIndex));
|
||||
dmaSetHandler(timerHardware->dmaIrqHandler, motor_DMA_IRQHandler, NVIC_BUILD_PRIORITY(1, 2), motorIndex);
|
||||
#endif
|
||||
}
|
||||
|
||||
/* Initialize TIMx DMA handle */
|
||||
if (HAL_DMA_Init(motor->TimHandle.hdma[motor->timerDmaIndex]) != HAL_OK) {
|
||||
|
@ -224,7 +230,9 @@ void pwmDshotMotorHardwareConfig(const timerHardware_t *timerHardware, uint8_t m
|
|||
/* Configuration Error */
|
||||
return;
|
||||
}
|
||||
|
||||
#ifdef USE_DSHOT_DMAR
|
||||
if (useBurstDshot) {
|
||||
/* Enable the Output compare channel */
|
||||
uint32_t channels = 0;
|
||||
if(output & TIMER_OUTPUT_N_CHANNEL) {
|
||||
|
@ -257,7 +265,9 @@ void pwmDshotMotorHardwareConfig(const timerHardware_t *timerHardware, uint8_t m
|
|||
}
|
||||
|
||||
LL_TIM_CC_EnableChannel(motor->timerHardware->tim, channels);
|
||||
#else
|
||||
} else
|
||||
#endif
|
||||
{
|
||||
if (output & TIMER_OUTPUT_N_CHANNEL) {
|
||||
if (HAL_TIMEx_PWMN_Start(&motor->TimHandle, motor->timerHardware->channel) != HAL_OK) {
|
||||
/* Starting PWM generation Error */
|
||||
|
@ -269,7 +279,8 @@ void pwmDshotMotorHardwareConfig(const timerHardware_t *timerHardware, uint8_t m
|
|||
return;
|
||||
}
|
||||
}
|
||||
#endif
|
||||
}
|
||||
}
|
||||
|
||||
motor->configured = true;
|
||||
}
|
||||
#endif
|
||||
|
|
|
@ -93,6 +93,9 @@ void pgResetFn_motorConfig(motorConfig_t *motorConfig)
|
|||
motorConfig->maxthrottle = 2000;
|
||||
motorConfig->mincommand = 1000;
|
||||
motorConfig->digitalIdleOffsetValue = 450;
|
||||
#ifdef USE_DSHOT_DMAR
|
||||
motorConfig->dev.useBurstDshot = ENABLE_DSHOT_DMAR;
|
||||
#endif
|
||||
|
||||
int motorIndex = 0;
|
||||
for (int i = 0; i < USABLE_TIMER_CHANNEL_COUNT && motorIndex < MAX_SUPPORTED_MOTORS; i++) {
|
||||
|
|
|
@ -446,6 +446,9 @@ const clivalue_t valueTable[] = {
|
|||
{ "min_command", VAR_UINT16 | MASTER_VALUE, .config.minmax = { PWM_PULSE_MIN, PWM_PULSE_MAX }, PG_MOTOR_CONFIG, offsetof(motorConfig_t, mincommand) },
|
||||
#ifdef USE_DSHOT
|
||||
{ "dshot_idle_value", VAR_UINT16 | MASTER_VALUE, .config.minmax = { 0, 2000 }, PG_MOTOR_CONFIG, offsetof(motorConfig_t, digitalIdleOffsetValue) },
|
||||
#ifdef USE_DSHOT_DMAR
|
||||
{ "dshot_burst", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_MOTOR_CONFIG, offsetof(motorConfig_t, dev.useBurstDshot) },
|
||||
#endif
|
||||
#endif
|
||||
{ "use_unsynced_pwm", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_MOTOR_CONFIG, offsetof(motorConfig_t, dev.useUnsyncedPwm) },
|
||||
{ "motor_pwm_protocol", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_MOTOR_PWM_PROTOCOL }, PG_MOTOR_CONFIG, offsetof(motorConfig_t, dev.motorPwmProtocol) },
|
||||
|
|
|
@ -25,7 +25,7 @@
|
|||
#define BEEPER PB3
|
||||
#define BEEPER_INVERTED
|
||||
|
||||
#define USE_DSHOT_DMAR
|
||||
#define ENABLE_DSHOT_DMAR true
|
||||
|
||||
// ICM20689 interrupt
|
||||
#define USE_EXTI
|
||||
|
|
|
@ -26,7 +26,7 @@
|
|||
#define BEEPER PC15
|
||||
#define BEEPER_INVERTED
|
||||
|
||||
#define USE_DSHOT_DMAR
|
||||
#define ENABLE_DSHOT_DMAR true
|
||||
|
||||
#define USABLE_TIMER_CHANNEL_COUNT 10
|
||||
|
||||
|
|
|
@ -28,7 +28,7 @@
|
|||
#define BEEPER_INVERTED
|
||||
#define BEEPER_PWM_HZ 3800 // Beeper PWM frequency in Hz
|
||||
|
||||
#define USE_DSHOT_DMAR
|
||||
#define ENABLE_DSHOT_DMAR true
|
||||
|
||||
#define INVERTER_PIN_UART1 PC0 // PC0 used as inverter select GPIO
|
||||
|
||||
|
|
|
@ -21,7 +21,7 @@
|
|||
|
||||
#define CONFIG_FASTLOOP_PREFERRED_ACC ACC_NONE
|
||||
|
||||
#define USE_DSHOT_DMAR
|
||||
#define ENABLE_DSHOT_DMAR true
|
||||
|
||||
#define LED0_PIN PB7
|
||||
|
||||
|
|
|
@ -26,7 +26,7 @@
|
|||
#define BEEPER PC13
|
||||
#define BEEPER_INVERTED
|
||||
|
||||
#define USE_DSHOT_DMAR
|
||||
#define ENABLE_DSHOT_DMAR true
|
||||
|
||||
// *************** Gyro & ACC **********************
|
||||
#define USE_SPI
|
||||
|
|
|
@ -21,16 +21,14 @@
|
|||
#undef USE_COPY_PROFILE_CMS_MENU
|
||||
#undef USE_TELEMETRY_LTM
|
||||
#undef USE_RTC_TIME
|
||||
#undef USE_GYRO_OVERFLOW_CHECK
|
||||
|
||||
#undef USE_DSHOT_DMAR // OMNIBUS (F3) does not benefit from burst Dshot
|
||||
|
||||
#define TARGET_BOARD_IDENTIFIER "OMNI" // https://en.wikipedia.org/wiki/Omnibus
|
||||
|
||||
#define CONFIG_FASTLOOP_PREFERRED_ACC ACC_NONE
|
||||
|
||||
// Can be configured for DMAR, but keep it legacy DSHOT for backward compatibility of
|
||||
// Motor x 1 + Servo x 3 on PWM1~4 use case.
|
||||
#define USE_DSHOT_DMA
|
||||
|
||||
#define LED0_PIN PB3
|
||||
|
||||
#define BEEPER PC15
|
||||
|
@ -162,9 +160,10 @@
|
|||
#define DEFAULT_RX_FEATURE FEATURE_RX_PPM
|
||||
#define DEFAULT_FEATURES (FEATURE_OSD)
|
||||
|
||||
#define USE_BUTTONS
|
||||
#define BUTTON_A_PIN PB1
|
||||
#define BUTTON_B_PIN PB0
|
||||
// Disable rarely used buttons in favor of flash space
|
||||
//#define USE_BUTTONS
|
||||
//#define BUTTON_A_PIN PB1
|
||||
//#define BUTTON_B_PIN PB0
|
||||
|
||||
//#define AVOID_UART3_FOR_PWM_PPM // Disable this for using UART3
|
||||
|
||||
|
|
|
@ -54,7 +54,7 @@
|
|||
#define BEEPER_INVERTED
|
||||
|
||||
#if defined(OMNIBUSF4SD) || defined(DYSF4PRO)
|
||||
#define USE_DSHOT_DMAR
|
||||
#define ENABLE_DSHOT_DMAR true
|
||||
#endif
|
||||
|
||||
#ifdef OMNIBUSF4SD
|
||||
|
|
|
@ -70,7 +70,7 @@
|
|||
#endif
|
||||
|
||||
#if defined(REVOLT)
|
||||
#define USE_DSHOT_DMAR
|
||||
#define ENABLE_DSHOT_DMAR true
|
||||
#endif
|
||||
|
||||
// PC0 used as inverter select GPIO
|
||||
|
|
|
@ -93,12 +93,7 @@
|
|||
#define USE_RX_FRSKY_SPI
|
||||
#endif
|
||||
|
||||
#if !defined(STM32F1) && defined(USE_DSHOT)
|
||||
#if !defined(USE_DSHOT_DMA) && !defined(USE_DSHOT_DMAR)
|
||||
#if !defined(RELEASE_BUILD)
|
||||
#define USE_DSHOT_DMAR
|
||||
#endif // !RELEASE_BUILD
|
||||
#endif // !USE_DSHOT_DMA && !USE_DSHOT_DMAR
|
||||
#endif // !STM32F1 && !STM32F3
|
||||
#undef USE_DSHOT_DMA
|
||||
|
||||
// Burst dshot to default off if not configured explicitly by target
|
||||
#ifndef ENABLE_DSHOT_DMAR
|
||||
#define ENABLE_DSHOT_DMAR false
|
||||
#endif
|
||||
|
|
|
@ -130,6 +130,7 @@
|
|||
#define USE_CAMERA_CONTROL
|
||||
#define USE_CMS
|
||||
#define USE_COPY_PROFILE_CMS_MENU
|
||||
#define USE_DSHOT_DMAR
|
||||
#define USE_GYRO_OVERFLOW_CHECK
|
||||
#define USE_HUFFMAN
|
||||
#define USE_MSP_DISPLAYPORT
|
||||
|
|
Loading…
Reference in New Issue