Merge pull request #5098 from jflyper/bfdev-configurable-burst-dshot
DShot Make burst and non-burst runtime configurable
This commit is contained in:
commit
1840d645f2
|
@ -47,6 +47,9 @@ static uint16_t freqBeep = 0;
|
||||||
|
|
||||||
static bool pwmMotorsEnabled = false;
|
static bool pwmMotorsEnabled = false;
|
||||||
static bool isDshot = 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)
|
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;
|
loadDmaBuffer = &loadDmaBufferDshot;
|
||||||
pwmCompleteWrite = &pwmCompleteDshotMotorUpdate;
|
pwmCompleteWrite = &pwmCompleteDshotMotorUpdate;
|
||||||
isDshot = true;
|
isDshot = true;
|
||||||
|
#ifdef USE_DSHOT_DMAR
|
||||||
|
if (motorConfig->useBurstDshot) {
|
||||||
|
useBurstDshot = true;
|
||||||
|
}
|
||||||
|
#endif
|
||||||
break;
|
break;
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
|
|
|
@ -109,7 +109,7 @@ typedef enum {
|
||||||
|
|
||||||
typedef struct {
|
typedef struct {
|
||||||
TIM_TypeDef *timer;
|
TIM_TypeDef *timer;
|
||||||
#if defined(USE_DSHOT_DMAR)
|
#if defined(USE_DSHOT) && defined(USE_DSHOT_DMAR)
|
||||||
#if !defined(USE_HAL_DRIVER)
|
#if !defined(USE_HAL_DRIVER)
|
||||||
#ifdef STM32F3
|
#ifdef STM32F3
|
||||||
DMA_Channel_TypeDef *dmaBurstRef;
|
DMA_Channel_TypeDef *dmaBurstRef;
|
||||||
|
@ -118,18 +118,18 @@ typedef struct {
|
||||||
#endif
|
#endif
|
||||||
uint16_t dmaBurstLength;
|
uint16_t dmaBurstLength;
|
||||||
#endif
|
#endif
|
||||||
uint32_t dmaBurstBuffer[DSHOT_DMA_BUFFER_SIZE * 4];
|
|
||||||
#else
|
|
||||||
uint16_t timerDmaSources;
|
|
||||||
#endif
|
#endif
|
||||||
|
uint32_t dmaBurstBuffer[DSHOT_DMA_BUFFER_SIZE * 4];
|
||||||
|
uint16_t timerDmaSources;
|
||||||
} motorDmaTimer_t;
|
} motorDmaTimer_t;
|
||||||
|
|
||||||
typedef struct {
|
typedef struct {
|
||||||
ioTag_t ioTag;
|
ioTag_t ioTag;
|
||||||
const timerHardware_t *timerHardware;
|
const timerHardware_t *timerHardware;
|
||||||
uint16_t value;
|
uint16_t value;
|
||||||
#if !defined(USE_DSHOT_DMAR)
|
#ifdef USE_DSHOT
|
||||||
uint16_t timerDmaSource;
|
uint16_t timerDmaSource;
|
||||||
|
bool configured;
|
||||||
#endif
|
#endif
|
||||||
motorDmaTimer_t *timer;
|
motorDmaTimer_t *timer;
|
||||||
volatile bool requestTelemetry;
|
volatile bool requestTelemetry;
|
||||||
|
@ -170,9 +170,14 @@ typedef struct motorDevConfig_s {
|
||||||
uint8_t motorPwmProtocol; // Pwm Protocol
|
uint8_t motorPwmProtocol; // Pwm Protocol
|
||||||
uint8_t motorPwmInversion; // Active-High vs Active-Low. Useful for brushed FCs converted for brushless operation
|
uint8_t motorPwmInversion; // Active-High vs Active-Low. Useful for brushed FCs converted for brushless operation
|
||||||
uint8_t useUnsyncedPwm;
|
uint8_t useUnsyncedPwm;
|
||||||
|
#ifdef USE_DSHOT_DMAR
|
||||||
|
uint8_t useBurstDshot;
|
||||||
|
#endif
|
||||||
ioTag_t ioTags[MAX_SUPPORTED_MOTORS];
|
ioTag_t ioTags[MAX_SUPPORTED_MOTORS];
|
||||||
} motorDevConfig_t;
|
} motorDevConfig_t;
|
||||||
|
|
||||||
|
extern bool useBurstDshot;
|
||||||
|
|
||||||
void motorDevInit(const motorDevConfig_t *motorDevConfig, uint16_t idlePulse, uint8_t motorCount);
|
void motorDevInit(const motorDevConfig_t *motorDevConfig, uint16_t idlePulse, uint8_t motorCount);
|
||||||
|
|
||||||
typedef struct servoDevConfig_s {
|
typedef struct servoDevConfig_s {
|
||||||
|
|
|
@ -60,28 +60,25 @@ void pwmWriteDshotInt(uint8_t index, uint16_t value)
|
||||||
{
|
{
|
||||||
motorDmaOutput_t *const motor = &dmaMotors[index];
|
motorDmaOutput_t *const motor = &dmaMotors[index];
|
||||||
|
|
||||||
#ifdef USE_DSHOT_DMAR
|
if (!motor->configured) {
|
||||||
if (!motor->timerHardware || !motor->timerHardware->dmaTimUPRef) {
|
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
#else
|
|
||||||
if (!motor->timerHardware || !motor->timerHardware->dmaRef) {
|
|
||||||
return;
|
|
||||||
}
|
|
||||||
#endif
|
|
||||||
|
|
||||||
uint16_t packet = prepareDshotPacket(motor, value);
|
uint16_t packet = prepareDshotPacket(motor, value);
|
||||||
uint8_t bufferSize;
|
uint8_t bufferSize;
|
||||||
|
|
||||||
#ifdef USE_DSHOT_DMAR
|
#ifdef USE_DSHOT_DMAR
|
||||||
bufferSize = loadDmaBuffer(&motor->timer->dmaBurstBuffer[timerLookupChannelIndex(motor->timerHardware->channel)], 4, packet);
|
if (useBurstDshot) {
|
||||||
motor->timer->dmaBurstLength = bufferSize * 4;
|
bufferSize = loadDmaBuffer(&motor->timer->dmaBurstBuffer[timerLookupChannelIndex(motor->timerHardware->channel)], 4, packet);
|
||||||
#else
|
motor->timer->dmaBurstLength = bufferSize * 4;
|
||||||
bufferSize = loadDmaBuffer(motor->dmaBuffer, 1, packet);
|
} else
|
||||||
motor->timer->timerDmaSources |= motor->timerDmaSource;
|
|
||||||
DMA_SetCurrDataCounter(motor->timerHardware->dmaRef, bufferSize);
|
|
||||||
DMA_Cmd(motor->timerHardware->dmaRef, ENABLE);
|
|
||||||
#endif
|
#endif
|
||||||
|
{
|
||||||
|
bufferSize = loadDmaBuffer(motor->dmaBuffer, 1, packet);
|
||||||
|
motor->timer->timerDmaSources |= motor->timerDmaSource;
|
||||||
|
DMA_SetCurrDataCounter(motor->timerHardware->dmaRef, bufferSize);
|
||||||
|
DMA_Cmd(motor->timerHardware->dmaRef, ENABLE);
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
void pwmCompleteDshotMotorUpdate(uint8_t motorCount)
|
void pwmCompleteDshotMotorUpdate(uint8_t motorCount)
|
||||||
|
@ -90,15 +87,18 @@ void pwmCompleteDshotMotorUpdate(uint8_t motorCount)
|
||||||
|
|
||||||
for (int i = 0; i < dmaMotorTimerCount; i++) {
|
for (int i = 0; i < dmaMotorTimerCount; i++) {
|
||||||
#ifdef USE_DSHOT_DMAR
|
#ifdef USE_DSHOT_DMAR
|
||||||
DMA_SetCurrDataCounter(dmaMotorTimers[i].dmaBurstRef, dmaMotorTimers[i].dmaBurstLength);
|
if (useBurstDshot) {
|
||||||
DMA_Cmd(dmaMotorTimers[i].dmaBurstRef, ENABLE);
|
DMA_SetCurrDataCounter(dmaMotorTimers[i].dmaBurstRef, dmaMotorTimers[i].dmaBurstLength);
|
||||||
TIM_DMAConfig(dmaMotorTimers[i].timer, TIM_DMABase_CCR1, TIM_DMABurstLength_4Transfers);
|
DMA_Cmd(dmaMotorTimers[i].dmaBurstRef, ENABLE);
|
||||||
TIM_DMACmd(dmaMotorTimers[i].timer, TIM_DMA_Update, ENABLE);
|
TIM_DMAConfig(dmaMotorTimers[i].timer, TIM_DMABase_CCR1, TIM_DMABurstLength_4Transfers);
|
||||||
#else
|
TIM_DMACmd(dmaMotorTimers[i].timer, TIM_DMA_Update, ENABLE);
|
||||||
TIM_SetCounter(dmaMotorTimers[i].timer, 0);
|
} else
|
||||||
TIM_DMACmd(dmaMotorTimers[i].timer, dmaMotorTimers[i].timerDmaSources, ENABLE);
|
|
||||||
dmaMotorTimers[i].timerDmaSources = 0;
|
|
||||||
#endif
|
#endif
|
||||||
|
{
|
||||||
|
TIM_SetCounter(dmaMotorTimers[i].timer, 0);
|
||||||
|
TIM_DMACmd(dmaMotorTimers[i].timer, dmaMotorTimers[i].timerDmaSources, ENABLE);
|
||||||
|
dmaMotorTimers[i].timerDmaSources = 0;
|
||||||
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -106,13 +106,18 @@ static void motor_DMA_IRQHandler(dmaChannelDescriptor_t *descriptor)
|
||||||
{
|
{
|
||||||
if (DMA_GET_FLAG_STATUS(descriptor, DMA_IT_TCIF)) {
|
if (DMA_GET_FLAG_STATUS(descriptor, DMA_IT_TCIF)) {
|
||||||
motorDmaOutput_t * const motor = &dmaMotors[descriptor->userParam];
|
motorDmaOutput_t * const motor = &dmaMotors[descriptor->userParam];
|
||||||
|
|
||||||
#ifdef USE_DSHOT_DMAR
|
#ifdef USE_DSHOT_DMAR
|
||||||
DMA_Cmd(motor->timerHardware->dmaTimUPRef, DISABLE);
|
if (useBurstDshot) {
|
||||||
TIM_DMACmd(motor->timerHardware->tim, TIM_DMA_Update, DISABLE);
|
DMA_Cmd(motor->timerHardware->dmaTimUPRef, DISABLE);
|
||||||
#else
|
TIM_DMACmd(motor->timerHardware->tim, TIM_DMA_Update, DISABLE);
|
||||||
DMA_Cmd(motor->timerHardware->dmaRef, DISABLE);
|
} else
|
||||||
TIM_DMACmd(motor->timerHardware->tim, motor->timerDmaSource, DISABLE);
|
|
||||||
#endif
|
#endif
|
||||||
|
{
|
||||||
|
DMA_Cmd(motor->timerHardware->dmaRef, DISABLE);
|
||||||
|
TIM_DMACmd(motor->timerHardware->tim, motor->timerDmaSource, DISABLE);
|
||||||
|
}
|
||||||
|
|
||||||
DMA_CLEAR_FLAG(descriptor, DMA_IT_TCIF);
|
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;
|
typedef DMA_Channel_TypeDef dmaStream_t;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
dmaStream_t *dmaRef;
|
||||||
|
|
||||||
#ifdef USE_DSHOT_DMAR
|
#ifdef USE_DSHOT_DMAR
|
||||||
dmaStream_t *dmaRef = timerHardware->dmaTimUPRef;
|
if (useBurstDshot) {
|
||||||
#else
|
dmaRef = timerHardware->dmaTimUPRef;
|
||||||
dmaStream_t *dmaRef = timerHardware->dmaRef;
|
} else
|
||||||
#endif
|
#endif
|
||||||
|
{
|
||||||
|
dmaRef = timerHardware->dmaRef;
|
||||||
|
}
|
||||||
|
|
||||||
if (dmaRef == NULL) {
|
if (dmaRef == NULL) {
|
||||||
return;
|
return;
|
||||||
|
@ -199,76 +209,84 @@ void pwmDshotMotorHardwareConfig(const timerHardware_t *timerHardware, uint8_t m
|
||||||
motor->timer = &dmaMotorTimers[timerIndex];
|
motor->timer = &dmaMotorTimers[timerIndex];
|
||||||
|
|
||||||
#ifdef USE_DSHOT_DMAR
|
#ifdef USE_DSHOT_DMAR
|
||||||
motor->timer->dmaBurstRef = dmaRef;
|
if (useBurstDshot) {
|
||||||
|
motor->timer->dmaBurstRef = dmaRef;
|
||||||
|
|
||||||
if (!configureTimer) {
|
if (!configureTimer) {
|
||||||
return;
|
motor->configured = true;
|
||||||
}
|
return;
|
||||||
#else
|
}
|
||||||
motor->timerDmaSource = timerDmaSource(timerHardware->channel);
|
} else
|
||||||
motor->timer->timerDmaSources &= ~motor->timerDmaSource;
|
|
||||||
#endif
|
#endif
|
||||||
|
{
|
||||||
|
motor->timerDmaSource = timerDmaSource(timerHardware->channel);
|
||||||
|
motor->timer->timerDmaSources &= ~motor->timerDmaSource;
|
||||||
|
}
|
||||||
|
|
||||||
DMA_Cmd(dmaRef, DISABLE);
|
DMA_Cmd(dmaRef, DISABLE);
|
||||||
DMA_DeInit(dmaRef);
|
DMA_DeInit(dmaRef);
|
||||||
DMA_StructInit(&DMA_InitStructure);
|
DMA_StructInit(&DMA_InitStructure);
|
||||||
|
|
||||||
#ifdef USE_DSHOT_DMAR
|
#ifdef USE_DSHOT_DMAR
|
||||||
dmaInit(timerHardware->dmaTimUPIrqHandler, OWNER_TIMUP, timerGetTIMNumber(timerHardware->tim));
|
if (useBurstDshot) {
|
||||||
dmaSetHandler(timerHardware->dmaTimUPIrqHandler, motor_DMA_IRQHandler, NVIC_BUILD_PRIORITY(1, 2), motorIndex);
|
dmaInit(timerHardware->dmaTimUPIrqHandler, OWNER_TIMUP, timerGetTIMNumber(timerHardware->tim));
|
||||||
|
dmaSetHandler(timerHardware->dmaTimUPIrqHandler, motor_DMA_IRQHandler, NVIC_BUILD_PRIORITY(1, 2), motorIndex);
|
||||||
|
|
||||||
#if defined(STM32F3)
|
#if defined(STM32F3)
|
||||||
DMA_InitStructure.DMA_MemoryBaseAddr = (uint32_t)motor->timer->dmaBurstBuffer;
|
DMA_InitStructure.DMA_MemoryBaseAddr = (uint32_t)motor->timer->dmaBurstBuffer;
|
||||||
DMA_InitStructure.DMA_DIR = DMA_DIR_PeripheralDST;
|
DMA_InitStructure.DMA_DIR = DMA_DIR_PeripheralDST;
|
||||||
#else
|
#else
|
||||||
DMA_InitStructure.DMA_Channel = timerHardware->dmaTimUPChannel;
|
DMA_InitStructure.DMA_Channel = timerHardware->dmaTimUPChannel;
|
||||||
DMA_InitStructure.DMA_Memory0BaseAddr = (uint32_t)motor->timer->dmaBurstBuffer;
|
DMA_InitStructure.DMA_Memory0BaseAddr = (uint32_t)motor->timer->dmaBurstBuffer;
|
||||||
DMA_InitStructure.DMA_DIR = DMA_DIR_MemoryToPeripheral;
|
DMA_InitStructure.DMA_DIR = DMA_DIR_MemoryToPeripheral;
|
||||||
DMA_InitStructure.DMA_FIFOMode = DMA_FIFOMode_Enable;
|
DMA_InitStructure.DMA_FIFOMode = DMA_FIFOMode_Enable;
|
||||||
DMA_InitStructure.DMA_FIFOThreshold = DMA_FIFOThreshold_Full;
|
DMA_InitStructure.DMA_FIFOThreshold = DMA_FIFOThreshold_Full;
|
||||||
DMA_InitStructure.DMA_MemoryBurst = DMA_MemoryBurst_Single;
|
DMA_InitStructure.DMA_MemoryBurst = DMA_MemoryBurst_Single;
|
||||||
DMA_InitStructure.DMA_PeripheralBurst = DMA_PeripheralBurst_Single;
|
DMA_InitStructure.DMA_PeripheralBurst = DMA_PeripheralBurst_Single;
|
||||||
#endif
|
#endif
|
||||||
DMA_InitStructure.DMA_PeripheralBaseAddr = (uint32_t)&timerHardware->tim->DMAR;
|
DMA_InitStructure.DMA_PeripheralBaseAddr = (uint32_t)&timerHardware->tim->DMAR;
|
||||||
DMA_InitStructure.DMA_BufferSize = (pwmProtocolType == PWM_TYPE_PROSHOT1000) ? PROSHOT_DMA_BUFFER_SIZE : DSHOT_DMA_BUFFER_SIZE; // XXX
|
DMA_InitStructure.DMA_BufferSize = (pwmProtocolType == PWM_TYPE_PROSHOT1000) ? PROSHOT_DMA_BUFFER_SIZE : DSHOT_DMA_BUFFER_SIZE; // XXX
|
||||||
DMA_InitStructure.DMA_PeripheralInc = DMA_PeripheralInc_Disable;
|
DMA_InitStructure.DMA_PeripheralInc = DMA_PeripheralInc_Disable;
|
||||||
DMA_InitStructure.DMA_MemoryInc = DMA_MemoryInc_Enable;
|
DMA_InitStructure.DMA_MemoryInc = DMA_MemoryInc_Enable;
|
||||||
DMA_InitStructure.DMA_PeripheralDataSize = DMA_PeripheralDataSize_Word;
|
DMA_InitStructure.DMA_PeripheralDataSize = DMA_PeripheralDataSize_Word;
|
||||||
DMA_InitStructure.DMA_MemoryDataSize = DMA_MemoryDataSize_Word;
|
DMA_InitStructure.DMA_MemoryDataSize = DMA_MemoryDataSize_Word;
|
||||||
DMA_InitStructure.DMA_Mode = DMA_Mode_Normal;
|
DMA_InitStructure.DMA_Mode = DMA_Mode_Normal;
|
||||||
DMA_InitStructure.DMA_Priority = DMA_Priority_High;
|
DMA_InitStructure.DMA_Priority = DMA_Priority_High;
|
||||||
|
} else
|
||||||
#else // !USE_DSHOT_DMAR
|
#endif
|
||||||
dmaInit(timerHardware->dmaIrqHandler, OWNER_MOTOR, RESOURCE_INDEX(motorIndex));
|
{
|
||||||
dmaSetHandler(timerHardware->dmaIrqHandler, motor_DMA_IRQHandler, NVIC_BUILD_PRIORITY(1, 2), motorIndex);
|
dmaInit(timerHardware->dmaIrqHandler, OWNER_MOTOR, RESOURCE_INDEX(motorIndex));
|
||||||
|
dmaSetHandler(timerHardware->dmaIrqHandler, motor_DMA_IRQHandler, NVIC_BUILD_PRIORITY(1, 2), motorIndex);
|
||||||
|
|
||||||
#if defined(STM32F3)
|
#if defined(STM32F3)
|
||||||
DMA_InitStructure.DMA_MemoryBaseAddr = (uint32_t)motor->dmaBuffer;
|
DMA_InitStructure.DMA_MemoryBaseAddr = (uint32_t)motor->dmaBuffer;
|
||||||
DMA_InitStructure.DMA_DIR = DMA_DIR_PeripheralDST;
|
DMA_InitStructure.DMA_DIR = DMA_DIR_PeripheralDST;
|
||||||
DMA_InitStructure.DMA_M2M = DMA_M2M_Disable;
|
DMA_InitStructure.DMA_M2M = DMA_M2M_Disable;
|
||||||
#elif defined(STM32F4)
|
#elif defined(STM32F4)
|
||||||
DMA_InitStructure.DMA_Channel = timerHardware->dmaChannel;
|
DMA_InitStructure.DMA_Channel = timerHardware->dmaChannel;
|
||||||
DMA_InitStructure.DMA_Memory0BaseAddr = (uint32_t)motor->dmaBuffer;
|
DMA_InitStructure.DMA_Memory0BaseAddr = (uint32_t)motor->dmaBuffer;
|
||||||
DMA_InitStructure.DMA_DIR = DMA_DIR_MemoryToPeripheral;
|
DMA_InitStructure.DMA_DIR = DMA_DIR_MemoryToPeripheral;
|
||||||
DMA_InitStructure.DMA_FIFOMode = DMA_FIFOMode_Enable;
|
DMA_InitStructure.DMA_FIFOMode = DMA_FIFOMode_Enable;
|
||||||
DMA_InitStructure.DMA_FIFOThreshold = DMA_FIFOThreshold_1QuarterFull;
|
DMA_InitStructure.DMA_FIFOThreshold = DMA_FIFOThreshold_1QuarterFull;
|
||||||
DMA_InitStructure.DMA_MemoryBurst = DMA_MemoryBurst_Single;
|
DMA_InitStructure.DMA_MemoryBurst = DMA_MemoryBurst_Single;
|
||||||
DMA_InitStructure.DMA_PeripheralBurst = DMA_PeripheralBurst_Single;
|
DMA_InitStructure.DMA_PeripheralBurst = DMA_PeripheralBurst_Single;
|
||||||
#endif
|
#endif
|
||||||
DMA_InitStructure.DMA_PeripheralBaseAddr = (uint32_t)timerChCCR(timerHardware);
|
DMA_InitStructure.DMA_PeripheralBaseAddr = (uint32_t)timerChCCR(timerHardware);
|
||||||
DMA_InitStructure.DMA_BufferSize = pwmProtocolType == PWM_TYPE_PROSHOT1000 ? PROSHOT_DMA_BUFFER_SIZE : DSHOT_DMA_BUFFER_SIZE;
|
DMA_InitStructure.DMA_BufferSize = pwmProtocolType == PWM_TYPE_PROSHOT1000 ? PROSHOT_DMA_BUFFER_SIZE : DSHOT_DMA_BUFFER_SIZE;
|
||||||
DMA_InitStructure.DMA_PeripheralInc = DMA_PeripheralInc_Disable;
|
DMA_InitStructure.DMA_PeripheralInc = DMA_PeripheralInc_Disable;
|
||||||
DMA_InitStructure.DMA_MemoryInc = DMA_MemoryInc_Enable;
|
DMA_InitStructure.DMA_MemoryInc = DMA_MemoryInc_Enable;
|
||||||
DMA_InitStructure.DMA_PeripheralDataSize = DMA_PeripheralDataSize_Word;
|
DMA_InitStructure.DMA_PeripheralDataSize = DMA_PeripheralDataSize_Word;
|
||||||
DMA_InitStructure.DMA_MemoryDataSize = DMA_MemoryDataSize_Word;
|
DMA_InitStructure.DMA_MemoryDataSize = DMA_MemoryDataSize_Word;
|
||||||
DMA_InitStructure.DMA_Mode = DMA_Mode_Normal;
|
DMA_InitStructure.DMA_Mode = DMA_Mode_Normal;
|
||||||
DMA_InitStructure.DMA_Priority = DMA_Priority_High;
|
DMA_InitStructure.DMA_Priority = DMA_Priority_High;
|
||||||
#endif // USE_DSHOT_DMAR
|
}
|
||||||
|
|
||||||
// XXX Consolidate common settings in the next refactor
|
// XXX Consolidate common settings in the next refactor
|
||||||
|
|
||||||
DMA_Init(dmaRef, &DMA_InitStructure);
|
DMA_Init(dmaRef, &DMA_InitStructure);
|
||||||
DMA_ITConfig(dmaRef, DMA_IT_TC, ENABLE);
|
DMA_ITConfig(dmaRef, DMA_IT_TC, ENABLE);
|
||||||
|
|
||||||
|
motor->configured = true;
|
||||||
}
|
}
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
|
|
@ -52,33 +52,31 @@ uint8_t getTimerIndex(TIM_TypeDef *timer)
|
||||||
void pwmWriteDshotInt(uint8_t index, uint16_t value)
|
void pwmWriteDshotInt(uint8_t index, uint16_t value)
|
||||||
{
|
{
|
||||||
motorDmaOutput_t *const motor = &dmaMotors[index];
|
motorDmaOutput_t *const motor = &dmaMotors[index];
|
||||||
#ifdef USE_DSHOT_DMAR
|
|
||||||
if (!motor->timerHardware || !motor->timerHardware->dmaTimUPRef) {
|
if (!motor->configured) {
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
#else
|
|
||||||
if (!motor->timerHardware || !motor->timerHardware->dmaRef) {
|
|
||||||
return;
|
|
||||||
}
|
|
||||||
#endif
|
|
||||||
|
|
||||||
uint16_t packet = prepareDshotPacket(motor, value);
|
uint16_t packet = prepareDshotPacket(motor, value);
|
||||||
|
|
||||||
uint8_t bufferSize;
|
uint8_t bufferSize;
|
||||||
|
|
||||||
#ifdef USE_DSHOT_DMAR
|
#ifdef USE_DSHOT_DMAR
|
||||||
bufferSize = loadDmaBuffer(&motor->timer->dmaBurstBuffer[timerLookupChannelIndex(motor->timerHardware->channel)], 4, packet);
|
if (useBurstDshot) {
|
||||||
if(HAL_DMA_STATE_READY == motor->TimHandle.hdma[motor->timerDmaIndex]->State) {
|
bufferSize = loadDmaBuffer(&motor->timer->dmaBurstBuffer[timerLookupChannelIndex(motor->timerHardware->channel)], 4, packet);
|
||||||
HAL_DMA_Start_IT(motor->TimHandle.hdma[motor->timerDmaIndex], (uint32_t)motor->timer->dmaBurstBuffer, (uint32_t)&motor->TimHandle.Instance->DMAR, bufferSize * 4);
|
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
|
}
|
||||||
bufferSize = loadDmaBuffer(motor->dmaBuffer, 1, packet);
|
} else
|
||||||
|
|
||||||
if (DMA_SetCurrDataCounter(&motor->TimHandle, motor->timerHardware->channel, motor->dmaBuffer, bufferSize) != HAL_OK) {
|
|
||||||
/* DMA set error */
|
|
||||||
return;
|
|
||||||
}
|
|
||||||
#endif
|
#endif
|
||||||
|
{
|
||||||
|
bufferSize = loadDmaBuffer(motor->dmaBuffer, 1, packet);
|
||||||
|
|
||||||
|
if (DMA_SetCurrDataCounter(&motor->TimHandle, motor->timerHardware->channel, motor->dmaBuffer, bufferSize) != HAL_OK) {
|
||||||
|
/* DMA set error */
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
void pwmCompleteDshotMotorUpdate(uint8_t motorCount)
|
void pwmCompleteDshotMotorUpdate(uint8_t motorCount)
|
||||||
|
@ -86,24 +84,27 @@ void pwmCompleteDshotMotorUpdate(uint8_t motorCount)
|
||||||
UNUSED(motorCount);
|
UNUSED(motorCount);
|
||||||
for (int i = 0; i < dmaMotorTimerCount; i++) {
|
for (int i = 0; i < dmaMotorTimerCount; i++) {
|
||||||
#ifdef USE_DSHOT_DMAR
|
#ifdef USE_DSHOT_DMAR
|
||||||
/* configure the DMA Burst Mode */
|
if (useBurstDshot) {
|
||||||
LL_TIM_ConfigDMABurst(dmaMotorTimers[i].timer, LL_TIM_DMABURST_BASEADDR_CCR1, LL_TIM_DMABURST_LENGTH_4TRANSFERS);
|
/* configure the DMA Burst Mode */
|
||||||
/* Enable the TIM DMA Request */
|
LL_TIM_ConfigDMABurst(dmaMotorTimers[i].timer, LL_TIM_DMABURST_BASEADDR_CCR1, LL_TIM_DMABURST_LENGTH_4TRANSFERS);
|
||||||
LL_TIM_EnableDMAReq_UPDATE(dmaMotorTimers[i].timer);
|
/* Enable the TIM DMA Request */
|
||||||
/* Reset timer counter */
|
LL_TIM_EnableDMAReq_UPDATE(dmaMotorTimers[i].timer);
|
||||||
LL_TIM_SetCounter(dmaMotorTimers[i].timer, 0);
|
/* Reset timer counter */
|
||||||
if(IS_TIM_ADVANCED_INSTANCE(dmaMotorTimers[i].timer) != RESET) {
|
LL_TIM_SetCounter(dmaMotorTimers[i].timer, 0);
|
||||||
/* Enable the main output */
|
if(IS_TIM_ADVANCED_INSTANCE(dmaMotorTimers[i].timer) != RESET) {
|
||||||
LL_TIM_EnableAllOutputs(dmaMotorTimers[i].timer);
|
/* Enable the main output */
|
||||||
}
|
LL_TIM_EnableAllOutputs(dmaMotorTimers[i].timer);
|
||||||
/* Enable the counter */
|
}
|
||||||
LL_TIM_EnableCounter(dmaMotorTimers[i].timer);
|
/* Enable the counter */
|
||||||
#else
|
LL_TIM_EnableCounter(dmaMotorTimers[i].timer);
|
||||||
/* Reset timer counter */
|
} else
|
||||||
LL_TIM_SetCounter(dmaMotorTimers[i].timer, 0);
|
|
||||||
/* Enable channel DMA requests */
|
|
||||||
dmaMotorTimers[i].timer->DIER |= dmaMotorTimers[i].timerDmaSources;
|
|
||||||
#endif
|
#endif
|
||||||
|
{
|
||||||
|
/* Reset timer counter */
|
||||||
|
LL_TIM_SetCounter(dmaMotorTimers[i].timer, 0);
|
||||||
|
/* Enable channel DMA requests */
|
||||||
|
dmaMotorTimers[i].timer->DIER |= dmaMotorTimers[i].timerDmaSources;
|
||||||
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -112,25 +113,27 @@ static void motor_DMA_IRQHandler(dmaChannelDescriptor_t* descriptor)
|
||||||
motorDmaOutput_t * const motor = &dmaMotors[descriptor->userParam];
|
motorDmaOutput_t * const motor = &dmaMotors[descriptor->userParam];
|
||||||
HAL_DMA_IRQHandler(motor->TimHandle.hdma[motor->timerDmaIndex]);
|
HAL_DMA_IRQHandler(motor->TimHandle.hdma[motor->timerDmaIndex]);
|
||||||
#ifdef USE_DSHOT_DMAR
|
#ifdef USE_DSHOT_DMAR
|
||||||
LL_TIM_DisableCounter(motor->timerHardware->tim);
|
if (useBurstDshot) {
|
||||||
LL_TIM_DisableDMAReq_UPDATE(motor->timerHardware->tim);
|
LL_TIM_DisableCounter(motor->timerHardware->tim);
|
||||||
#else
|
LL_TIM_DisableDMAReq_UPDATE(motor->timerHardware->tim);
|
||||||
__HAL_DMA_DISABLE(&motor->hdma_tim);
|
} else
|
||||||
TIM_DMACmd(&motor->TimHandle, motor->timerHardware->channel, DISABLE);
|
|
||||||
#endif
|
#endif
|
||||||
|
{
|
||||||
|
__HAL_DMA_DISABLE(&motor->hdma_tim);
|
||||||
|
TIM_DMACmd(&motor->TimHandle, motor->timerHardware->channel, DISABLE);
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
void pwmDshotMotorHardwareConfig(const timerHardware_t *timerHardware, uint8_t motorIndex, motorPwmProtocolTypes_e pwmProtocolType, uint8_t output)
|
void pwmDshotMotorHardwareConfig(const timerHardware_t *timerHardware, uint8_t motorIndex, motorPwmProtocolTypes_e pwmProtocolType, uint8_t output)
|
||||||
{
|
{
|
||||||
#ifdef USE_DSHOT_DMAR
|
#ifdef USE_DSHOT_DMAR
|
||||||
if (timerHardware->dmaTimUPRef == NULL) {
|
if (useBurstDshot && timerHardware->dmaTimUPRef == NULL) {
|
||||||
return;
|
return;
|
||||||
}
|
} else
|
||||||
#else
|
#endif
|
||||||
if (timerHardware->dmaRef == NULL) {
|
if (timerHardware->dmaRef == NULL) {
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
#endif
|
|
||||||
|
|
||||||
motorDmaOutput_t * const motor = &dmaMotors[motorIndex];
|
motorDmaOutput_t * const motor = &dmaMotors[motorIndex];
|
||||||
motor->timerHardware = timerHardware;
|
motor->timerHardware = timerHardware;
|
||||||
|
@ -176,36 +179,39 @@ void pwmDshotMotorHardwareConfig(const timerHardware_t *timerHardware, uint8_t m
|
||||||
motor->hdma_tim.Init.PeriphBurst = DMA_PBURST_SINGLE;
|
motor->hdma_tim.Init.PeriphBurst = DMA_PBURST_SINGLE;
|
||||||
|
|
||||||
#ifdef USE_DSHOT_DMAR
|
#ifdef USE_DSHOT_DMAR
|
||||||
motor->timerDmaIndex = TIM_DMA_ID_UPDATE;
|
if (useBurstDshot) {
|
||||||
/* Set the DMAR specific dma handle parameters to be configured */
|
motor->timerDmaIndex = TIM_DMA_ID_UPDATE;
|
||||||
motor->hdma_tim.Init.Channel = timerHardware->dmaTimUPChannel;
|
/* Set the DMAR specific dma handle parameters to be configured */
|
||||||
motor->hdma_tim.Init.FIFOMode = DMA_FIFOMODE_ENABLE;
|
motor->hdma_tim.Init.Channel = timerHardware->dmaTimUPChannel;
|
||||||
|
motor->hdma_tim.Init.FIFOMode = DMA_FIFOMODE_ENABLE;
|
||||||
|
|
||||||
/* Set hdma_tim instance */
|
/* Set hdma_tim instance */
|
||||||
motor->hdma_tim.Instance = timerHardware->dmaTimUPRef;
|
motor->hdma_tim.Instance = timerHardware->dmaTimUPRef;
|
||||||
|
|
||||||
/* Link hdma_tim to hdma[x] (channelx) */
|
/* Link hdma_tim to hdma[x] (channelx) */
|
||||||
__HAL_LINKDMA(&motor->TimHandle, hdma[motor->timerDmaIndex], motor->hdma_tim);
|
__HAL_LINKDMA(&motor->TimHandle, hdma[motor->timerDmaIndex], motor->hdma_tim);
|
||||||
|
|
||||||
dmaInit(timerHardware->dmaTimUPIrqHandler, OWNER_TIMUP, timerGetTIMNumber(timerHardware->tim));
|
dmaInit(timerHardware->dmaTimUPIrqHandler, OWNER_TIMUP, timerGetTIMNumber(timerHardware->tim));
|
||||||
dmaSetHandler(timerHardware->dmaTimUPIrqHandler, motor_DMA_IRQHandler, NVIC_BUILD_PRIORITY(1, 2), motorIndex);
|
dmaSetHandler(timerHardware->dmaTimUPIrqHandler, motor_DMA_IRQHandler, NVIC_BUILD_PRIORITY(1, 2), motorIndex);
|
||||||
#else
|
} else
|
||||||
motor->timerDmaIndex = timerDmaIndex(timerHardware->channel);
|
|
||||||
motor->timer->timerDmaSources |= timerDmaSource(timerHardware->channel);
|
|
||||||
|
|
||||||
/* Set the non-DMAR specific dma handle parameters to be configured */
|
|
||||||
motor->hdma_tim.Init.Channel = timerHardware->dmaChannel;
|
|
||||||
motor->hdma_tim.Init.FIFOMode = DMA_FIFOMODE_DISABLE;
|
|
||||||
|
|
||||||
/* Set hdma_tim instance */
|
|
||||||
motor->hdma_tim.Instance = timerHardware->dmaRef;
|
|
||||||
|
|
||||||
/* Link hdma_tim to hdma[x] (channelx) */
|
|
||||||
__HAL_LINKDMA(&motor->TimHandle, hdma[motor->timerDmaIndex], motor->hdma_tim);
|
|
||||||
|
|
||||||
dmaInit(timerHardware->dmaIrqHandler, OWNER_MOTOR, RESOURCE_INDEX(motorIndex));
|
|
||||||
dmaSetHandler(timerHardware->dmaIrqHandler, motor_DMA_IRQHandler, NVIC_BUILD_PRIORITY(1, 2), motorIndex);
|
|
||||||
#endif
|
#endif
|
||||||
|
{
|
||||||
|
motor->timerDmaIndex = timerDmaIndex(timerHardware->channel);
|
||||||
|
motor->timer->timerDmaSources |= timerDmaSource(timerHardware->channel);
|
||||||
|
|
||||||
|
/* Set the non-DMAR specific dma handle parameters to be configured */
|
||||||
|
motor->hdma_tim.Init.Channel = timerHardware->dmaChannel;
|
||||||
|
motor->hdma_tim.Init.FIFOMode = DMA_FIFOMODE_DISABLE;
|
||||||
|
|
||||||
|
/* Set hdma_tim instance */
|
||||||
|
motor->hdma_tim.Instance = timerHardware->dmaRef;
|
||||||
|
|
||||||
|
/* Link hdma_tim to hdma[x] (channelx) */
|
||||||
|
__HAL_LINKDMA(&motor->TimHandle, hdma[motor->timerDmaIndex], motor->hdma_tim);
|
||||||
|
|
||||||
|
dmaInit(timerHardware->dmaIrqHandler, OWNER_MOTOR, RESOURCE_INDEX(motorIndex));
|
||||||
|
dmaSetHandler(timerHardware->dmaIrqHandler, motor_DMA_IRQHandler, NVIC_BUILD_PRIORITY(1, 2), motorIndex);
|
||||||
|
}
|
||||||
|
|
||||||
/* Initialize TIMx DMA handle */
|
/* Initialize TIMx DMA handle */
|
||||||
if (HAL_DMA_Init(motor->TimHandle.hdma[motor->timerDmaIndex]) != HAL_OK) {
|
if (HAL_DMA_Init(motor->TimHandle.hdma[motor->timerDmaIndex]) != HAL_OK) {
|
||||||
|
@ -228,52 +234,57 @@ void pwmDshotMotorHardwareConfig(const timerHardware_t *timerHardware, uint8_t m
|
||||||
/* Configuration Error */
|
/* Configuration Error */
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
#ifdef USE_DSHOT_DMAR
|
#ifdef USE_DSHOT_DMAR
|
||||||
/* Enable the Output compare channel */
|
if (useBurstDshot) {
|
||||||
uint32_t channels = 0;
|
/* Enable the Output compare channel */
|
||||||
if(output & TIMER_OUTPUT_N_CHANNEL) {
|
uint32_t channels = 0;
|
||||||
switch(motor->timerHardware->channel) {
|
if(output & TIMER_OUTPUT_N_CHANNEL) {
|
||||||
case TIM_CHANNEL_1:
|
switch(motor->timerHardware->channel) {
|
||||||
channels = LL_TIM_CHANNEL_CH1N;
|
case TIM_CHANNEL_1:
|
||||||
break;
|
channels = LL_TIM_CHANNEL_CH1N;
|
||||||
case TIM_CHANNEL_2:
|
break;
|
||||||
channels = LL_TIM_CHANNEL_CH2N;
|
case TIM_CHANNEL_2:
|
||||||
break;
|
channels = LL_TIM_CHANNEL_CH2N;
|
||||||
case TIM_CHANNEL_3:
|
break;
|
||||||
channels = LL_TIM_CHANNEL_CH3N;
|
case TIM_CHANNEL_3:
|
||||||
break;
|
channels = LL_TIM_CHANNEL_CH3N;
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
} else {
|
||||||
|
switch(motor->timerHardware->channel) {
|
||||||
|
case TIM_CHANNEL_1:
|
||||||
|
channels = LL_TIM_CHANNEL_CH1;
|
||||||
|
break;
|
||||||
|
case TIM_CHANNEL_2:
|
||||||
|
channels = LL_TIM_CHANNEL_CH2;
|
||||||
|
break;
|
||||||
|
case TIM_CHANNEL_3:
|
||||||
|
channels = LL_TIM_CHANNEL_CH3;
|
||||||
|
break;
|
||||||
|
case TIM_CHANNEL_4:
|
||||||
|
channels = LL_TIM_CHANNEL_CH4;
|
||||||
|
break;
|
||||||
|
}
|
||||||
}
|
}
|
||||||
} else {
|
|
||||||
switch(motor->timerHardware->channel) {
|
LL_TIM_CC_EnableChannel(motor->timerHardware->tim, channels);
|
||||||
case TIM_CHANNEL_1:
|
} else
|
||||||
channels = LL_TIM_CHANNEL_CH1;
|
#endif
|
||||||
break;
|
{
|
||||||
case TIM_CHANNEL_2:
|
if (output & TIMER_OUTPUT_N_CHANNEL) {
|
||||||
channels = LL_TIM_CHANNEL_CH2;
|
if (HAL_TIMEx_PWMN_Start(&motor->TimHandle, motor->timerHardware->channel) != HAL_OK) {
|
||||||
break;
|
/* Starting PWM generation Error */
|
||||||
case TIM_CHANNEL_3:
|
return;
|
||||||
channels = LL_TIM_CHANNEL_CH3;
|
}
|
||||||
break;
|
} else {
|
||||||
case TIM_CHANNEL_4:
|
if (HAL_TIM_PWM_Start(&motor->TimHandle, motor->timerHardware->channel) != HAL_OK) {
|
||||||
channels = LL_TIM_CHANNEL_CH4;
|
/* Starting PWM generation Error */
|
||||||
break;
|
return;
|
||||||
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
LL_TIM_CC_EnableChannel(motor->timerHardware->tim, channels);
|
motor->configured = true;
|
||||||
#else
|
|
||||||
if (output & TIMER_OUTPUT_N_CHANNEL) {
|
|
||||||
if (HAL_TIMEx_PWMN_Start(&motor->TimHandle, motor->timerHardware->channel) != HAL_OK) {
|
|
||||||
/* Starting PWM generation Error */
|
|
||||||
return;
|
|
||||||
}
|
|
||||||
} else {
|
|
||||||
if (HAL_TIM_PWM_Start(&motor->TimHandle, motor->timerHardware->channel) != HAL_OK) {
|
|
||||||
/* Starting PWM generation Error */
|
|
||||||
return;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
#endif
|
|
||||||
}
|
}
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
|
|
@ -93,6 +93,9 @@ void pgResetFn_motorConfig(motorConfig_t *motorConfig)
|
||||||
motorConfig->maxthrottle = 2000;
|
motorConfig->maxthrottle = 2000;
|
||||||
motorConfig->mincommand = 1000;
|
motorConfig->mincommand = 1000;
|
||||||
motorConfig->digitalIdleOffsetValue = 450;
|
motorConfig->digitalIdleOffsetValue = 450;
|
||||||
|
#ifdef USE_DSHOT_DMAR
|
||||||
|
motorConfig->dev.useBurstDshot = ENABLE_DSHOT_DMAR;
|
||||||
|
#endif
|
||||||
|
|
||||||
int motorIndex = 0;
|
int motorIndex = 0;
|
||||||
for (int i = 0; i < USABLE_TIMER_CHANNEL_COUNT && motorIndex < MAX_SUPPORTED_MOTORS; i++) {
|
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) },
|
{ "min_command", VAR_UINT16 | MASTER_VALUE, .config.minmax = { PWM_PULSE_MIN, PWM_PULSE_MAX }, PG_MOTOR_CONFIG, offsetof(motorConfig_t, mincommand) },
|
||||||
#ifdef USE_DSHOT
|
#ifdef USE_DSHOT
|
||||||
{ "dshot_idle_value", VAR_UINT16 | MASTER_VALUE, .config.minmax = { 0, 2000 }, PG_MOTOR_CONFIG, offsetof(motorConfig_t, digitalIdleOffsetValue) },
|
{ "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
|
#endif
|
||||||
{ "use_unsynced_pwm", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_MOTOR_CONFIG, offsetof(motorConfig_t, dev.useUnsyncedPwm) },
|
{ "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) },
|
{ "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 PB3
|
||||||
#define BEEPER_INVERTED
|
#define BEEPER_INVERTED
|
||||||
|
|
||||||
#define USE_DSHOT_DMAR
|
#define ENABLE_DSHOT_DMAR true
|
||||||
|
|
||||||
// ICM20689 interrupt
|
// ICM20689 interrupt
|
||||||
#define USE_EXTI
|
#define USE_EXTI
|
||||||
|
|
|
@ -26,7 +26,7 @@
|
||||||
#define BEEPER PC15
|
#define BEEPER PC15
|
||||||
#define BEEPER_INVERTED
|
#define BEEPER_INVERTED
|
||||||
|
|
||||||
#define USE_DSHOT_DMAR
|
#define ENABLE_DSHOT_DMAR true
|
||||||
|
|
||||||
#define USABLE_TIMER_CHANNEL_COUNT 10
|
#define USABLE_TIMER_CHANNEL_COUNT 10
|
||||||
|
|
||||||
|
|
|
@ -28,7 +28,7 @@
|
||||||
#define BEEPER_INVERTED
|
#define BEEPER_INVERTED
|
||||||
#define BEEPER_PWM_HZ 3800 // Beeper PWM frequency in Hz
|
#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
|
#define INVERTER_PIN_UART1 PC0 // PC0 used as inverter select GPIO
|
||||||
|
|
||||||
|
|
|
@ -21,7 +21,7 @@
|
||||||
|
|
||||||
#define CONFIG_FASTLOOP_PREFERRED_ACC ACC_NONE
|
#define CONFIG_FASTLOOP_PREFERRED_ACC ACC_NONE
|
||||||
|
|
||||||
#define USE_DSHOT_DMAR
|
#define ENABLE_DSHOT_DMAR true
|
||||||
|
|
||||||
#define LED0_PIN PB7
|
#define LED0_PIN PB7
|
||||||
|
|
||||||
|
|
|
@ -26,7 +26,7 @@
|
||||||
#define BEEPER PC13
|
#define BEEPER PC13
|
||||||
#define BEEPER_INVERTED
|
#define BEEPER_INVERTED
|
||||||
|
|
||||||
#define USE_DSHOT_DMAR
|
#define ENABLE_DSHOT_DMAR true
|
||||||
|
|
||||||
// *************** Gyro & ACC **********************
|
// *************** Gyro & ACC **********************
|
||||||
#define USE_SPI
|
#define USE_SPI
|
||||||
|
|
|
@ -21,16 +21,14 @@
|
||||||
#undef USE_COPY_PROFILE_CMS_MENU
|
#undef USE_COPY_PROFILE_CMS_MENU
|
||||||
#undef USE_TELEMETRY_LTM
|
#undef USE_TELEMETRY_LTM
|
||||||
#undef USE_RTC_TIME
|
#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 TARGET_BOARD_IDENTIFIER "OMNI" // https://en.wikipedia.org/wiki/Omnibus
|
||||||
|
|
||||||
#define CONFIG_FASTLOOP_PREFERRED_ACC ACC_NONE
|
#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 LED0_PIN PB3
|
||||||
|
|
||||||
#define BEEPER PC15
|
#define BEEPER PC15
|
||||||
|
@ -162,9 +160,10 @@
|
||||||
#define DEFAULT_RX_FEATURE FEATURE_RX_PPM
|
#define DEFAULT_RX_FEATURE FEATURE_RX_PPM
|
||||||
#define DEFAULT_FEATURES (FEATURE_OSD)
|
#define DEFAULT_FEATURES (FEATURE_OSD)
|
||||||
|
|
||||||
#define USE_BUTTONS
|
// Disable rarely used buttons in favor of flash space
|
||||||
#define BUTTON_A_PIN PB1
|
//#define USE_BUTTONS
|
||||||
#define BUTTON_B_PIN PB0
|
//#define BUTTON_A_PIN PB1
|
||||||
|
//#define BUTTON_B_PIN PB0
|
||||||
|
|
||||||
//#define AVOID_UART3_FOR_PWM_PPM // Disable this for using UART3
|
//#define AVOID_UART3_FOR_PWM_PPM // Disable this for using UART3
|
||||||
|
|
||||||
|
|
|
@ -54,7 +54,7 @@
|
||||||
#define BEEPER_INVERTED
|
#define BEEPER_INVERTED
|
||||||
|
|
||||||
#if defined(OMNIBUSF4SD) || defined(DYSF4PRO)
|
#if defined(OMNIBUSF4SD) || defined(DYSF4PRO)
|
||||||
#define USE_DSHOT_DMAR
|
#define ENABLE_DSHOT_DMAR true
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifdef OMNIBUSF4SD
|
#ifdef OMNIBUSF4SD
|
||||||
|
|
|
@ -70,7 +70,7 @@
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if defined(REVOLT)
|
#if defined(REVOLT)
|
||||||
#define USE_DSHOT_DMAR
|
#define ENABLE_DSHOT_DMAR true
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// PC0 used as inverter select GPIO
|
// PC0 used as inverter select GPIO
|
||||||
|
|
|
@ -93,12 +93,7 @@
|
||||||
#define USE_RX_FRSKY_SPI
|
#define USE_RX_FRSKY_SPI
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if !defined(STM32F1) && defined(USE_DSHOT)
|
// Burst dshot to default off if not configured explicitly by target
|
||||||
#if !defined(USE_DSHOT_DMA) && !defined(USE_DSHOT_DMAR)
|
#ifndef ENABLE_DSHOT_DMAR
|
||||||
#if !defined(RELEASE_BUILD)
|
#define ENABLE_DSHOT_DMAR false
|
||||||
#define USE_DSHOT_DMAR
|
#endif
|
||||||
#endif // !RELEASE_BUILD
|
|
||||||
#endif // !USE_DSHOT_DMA && !USE_DSHOT_DMAR
|
|
||||||
#endif // !STM32F1 && !STM32F3
|
|
||||||
#undef USE_DSHOT_DMA
|
|
||||||
|
|
||||||
|
|
|
@ -130,6 +130,7 @@
|
||||||
#define USE_CAMERA_CONTROL
|
#define USE_CAMERA_CONTROL
|
||||||
#define USE_CMS
|
#define USE_CMS
|
||||||
#define USE_COPY_PROFILE_CMS_MENU
|
#define USE_COPY_PROFILE_CMS_MENU
|
||||||
|
#define USE_DSHOT_DMAR
|
||||||
#define USE_GYRO_OVERFLOW_CHECK
|
#define USE_GYRO_OVERFLOW_CHECK
|
||||||
#define USE_HUFFMAN
|
#define USE_HUFFMAN
|
||||||
#define USE_MSP_DISPLAYPORT
|
#define USE_MSP_DISPLAYPORT
|
||||||
|
|
Loading…
Reference in New Issue