Skip to content

Commit

Permalink
rebase
Browse files Browse the repository at this point in the history
Reduce code by supporting only GCR, fix serial_4way, fix f7 dshot bidir

fix ws and eliminate superfluous buffer

use GCR constant instead of 32

decode optimization

bump 4way prot version mumber

bump if version
  • Loading branch information
joelucid committed Aug 2, 2019
1 parent 383ba1c commit 835a5ca
Show file tree
Hide file tree
Showing 8 changed files with 188 additions and 171 deletions.
10 changes: 4 additions & 6 deletions src/main/cli/cli.c
Expand Up @@ -261,7 +261,7 @@ static const char * const *sensorHardwareNames[] = {

#if defined(USE_DSHOT) && defined(USE_DSHOT_TELEMETRY)
extern uint32_t readDoneCount;
extern uint32_t inputBuffer[DSHOT_TELEMETRY_INPUT_LEN];
extern uint32_t inputBuffer[GCR_TELEMETRY_INPUT_LEN];
extern uint32_t setDirectionMicros;
#endif

Expand Down Expand Up @@ -5680,15 +5680,13 @@ static void cliDshotTelemetryInfo(char *cmdline)
}
cliPrintLinefeed();

const bool proshot = (motorConfig()->dev.motorPwmProtocol == PWM_TYPE_PROSHOT1000);
const int modulo = proshot ? MOTOR_NIBBLE_LENGTH_PROSHOT : MOTOR_BITLENGTH;
const int len = proshot ? 8 : DSHOT_TELEMETRY_INPUT_LEN;
const int len = MAX_GCR_EDGES;
for (int i = 0; i < len; i++) {
cliPrintf("%u ", (int)inputBuffer[i]);
}
cliPrintLinefeed();
for (int i = 1; i < len; i+=2) {
cliPrintf("%u ", (int)(inputBuffer[i] + modulo - inputBuffer[i-1]) % modulo);
for (int i = 1; i < len; i++) {
cliPrintf("%u ", (int)(inputBuffer[i] - inputBuffer[i-1]));
}
cliPrintLinefeed();
} else {
Expand Down
6 changes: 6 additions & 0 deletions src/main/drivers/dshot_dpwm.c
Expand Up @@ -112,6 +112,12 @@ static void dshotPwmDisableMotors(void)

static bool dshotPwmEnableMotors(void)
{
for (int i = 0; i < dshotPwmDevice.count; i++) {
motorDmaOutput_t *motor = getMotorDmaOutput(i);
const IO_t motorIO = IOGetByTag(motor->timerHardware->tag);
IOConfigGPIOAF(motorIO, motor->iocfg, motor->timerHardware->alternateFunction);
}

// No special processing required
return true;
}
Expand Down
25 changes: 15 additions & 10 deletions src/main/drivers/dshot_dpwm.h
Expand Up @@ -36,7 +36,11 @@
#define PROSHOT_BIT_WIDTH 3
#define MOTOR_NIBBLE_LENGTH_PROSHOT (PROSHOT_BASE_SYMBOL * 4) // 4uS

#define DSHOT_TELEMETRY_DEADTIME_US (2 * 30 + 10) // 2 * 30uS to switch lines plus 10us grace period
#define DSHOT_TELEMETRY_DEADTIME_US (30 + 5) // 30 to switch lines and 5 to switch lines back

#define MIN_GCR_EDGES 7
#define MAX_GCR_EDGES 22


typedef uint8_t loadDmaBufferFn(uint32_t *dmaBuffer, int stride, uint16_t packet); // function pointer used to encode a digital motor value into the DMA buffer representation
extern FAST_RAM_ZERO_INIT loadDmaBufferFn *loadDmaBuffer;
Expand All @@ -55,16 +59,15 @@ motorDevice_t *dshotPwmDevInit(const struct motorDevConfig_s *motorConfig, uint1
#define DSHOT_DMA_BUFFER_SIZE 18 /* resolution + frame reset (2us) */
#define PROSHOT_DMA_BUFFER_SIZE 6 /* resolution + frame reset (2us) */

#define DSHOT_TELEMETRY_INPUT_LEN 32
#define PROSHOT_TELEMETRY_INPUT_LEN 8
#define GCR_TELEMETRY_INPUT_LEN MAX_GCR_EDGES

// For H7, DMA buffer is placed in a dedicated segment for coherency management
#if defined(STM32H7)
#define DSHOT_DMA_BUFFER_ATTRIBUTE DMA_RAM
#elif defined(STM32F7)
#define DSHOT_DMA_BUFFER_ATTRIBUTE FAST_RAM_ZERO_INIT
#else
#define DSHOT_DMA_BUFFER_ATTRIBUTE // None
#define DSHOT_DMA_BUFFER_ATTRIBUTE
#endif

#if defined(STM32F3) || defined(STM32F4) || defined(STM32F7) || defined(STM32H7)
Expand All @@ -74,29 +77,32 @@ motorDevice_t *dshotPwmDevInit(const struct motorDevConfig_s *motorConfig, uint1
#endif

#ifdef USE_DSHOT_TELEMETRY
STATIC_ASSERT(DSHOT_TELEMETRY_INPUT_LEN >= DSHOT_DMA_BUFFER_SIZE, dshotBufferSizeConstrait);
#define DSHOT_DMA_BUFFER_ALLOC_SIZE DSHOT_TELEMETRY_INPUT_LEN
STATIC_ASSERT(GCR_TELEMETRY_INPUT_LEN >= DSHOT_DMA_BUFFER_SIZE, dshotBufferSizeConstrait);
#define DSHOT_DMA_BUFFER_ALLOC_SIZE GCR_TELEMETRY_INPUT_LEN
#else
#define DSHOT_DMA_BUFFER_ALLOC_SIZE DSHOT_DMA_BUFFER_SIZE
#endif

extern DSHOT_DMA_BUFFER_UNIT dshotDmaBuffer[MAX_SUPPORTED_MOTORS][DSHOT_DMA_BUFFER_ALLOC_SIZE];
extern DSHOT_DMA_BUFFER_UNIT dshotDmaInputBuffer[MAX_SUPPORTED_MOTORS][DSHOT_DMA_BUFFER_ALLOC_SIZE];

#ifdef USE_DSHOT_DMAR
extern DSHOT_DMA_BUFFER_UNIT dshotBurstDmaBuffer[MAX_DMA_TIMERS][DSHOT_DMA_BUFFER_SIZE * 4];
#endif

typedef struct {
TIM_TypeDef *timer;
#if defined(USE_DSHOT) && defined(USE_DSHOT_DMAR)
#if defined(USE_DSHOT)
uint16_t outputPeriod;
#if defined(USE_DSHOT_DMAR)
#if defined(STM32F7) || defined(STM32H7)
TIM_HandleTypeDef timHandle;
DMA_HandleTypeDef hdma_tim;
#endif
dmaResource_t *dmaBurstRef;
uint16_t dmaBurstLength;
uint32_t *dmaBurstBuffer;
timeUs_t inputDirectionStampUs;
#endif
#endif
uint16_t timerDmaSources;
} motorDmaTimer_t;
Expand All @@ -115,6 +121,7 @@ typedef struct motorDmaOutput_s {
#endif
uint8_t output;
uint8_t index;
uint32_t iocfg;

#if defined(USE_HAL_DRIVER) && defined(USE_FULL_LL_DRIVER)
LL_DMA_InitTypeDef dmaInitStruct;
Expand All @@ -124,9 +131,7 @@ typedef struct motorDmaOutput_s {
#endif

#ifdef USE_DSHOT_TELEMETRY
bool useProshot;
volatile bool isInput;
volatile bool hasTelemetry;
uint16_t dshotTelemetryValue;
timeDelta_t dshotTelemetryDeadtimeUs;
bool dshotTelemetryActive;
Expand Down
81 changes: 38 additions & 43 deletions src/main/drivers/pwm_output_dshot.c
Expand Up @@ -50,14 +50,6 @@

#ifdef USE_DSHOT_TELEMETRY

static void processInputIrq(motorDmaOutput_t * const motor)
{
motor->hasTelemetry = true;
xDMA_Cmd(motor->dmaRef, DISABLE);
TIM_DMACmd(motor->timerHardware->tim, motor->timerDmaSource, DISABLE);
readDoneCount++;
}

void dshotEnableChannels(uint8_t motorCount)
{
for (int i = 0; i < motorCount; i++) {
Expand Down Expand Up @@ -101,7 +93,12 @@ FAST_CODE void pwmDshotSetDirectionOutput(
#ifdef USE_DSHOT_TELEMETRY
if (!output) {
motor->isInput = true;
motor->timer->inputDirectionStampUs = micros();
if (!inputStampUs) {
inputStampUs = micros();
}
TIM_ARRPreloadConfig(timer, ENABLE);
timer->ARR = 0xffffffff;

TIM_ICInit(timer, &motor->icInitStruct);

#if defined(STM32F3)
Expand Down Expand Up @@ -142,7 +139,9 @@ FAST_CODE void pwmDshotSetDirectionOutput(
}

xDMA_Init(dmaRef, pDmaInit);
xDMA_ITConfig(dmaRef, DMA_IT_TC, ENABLE);
if (output) {
xDMA_ITConfig(dmaRef, DMA_IT_TC, ENABLE);
}
}


Expand All @@ -165,6 +164,9 @@ void pwmCompleteDshotMotorUpdate(void)
} else
#endif
{
TIM_ARRPreloadConfig(dmaMotorTimers[i].timer, DISABLE);
dmaMotorTimers[i].timer->ARR = dmaMotorTimers[i].outputPeriod;
TIM_ARRPreloadConfig(dmaMotorTimers[i].timer, ENABLE);
TIM_SetCounter(dmaMotorTimers[i].timer, 0);
TIM_DMACmd(dmaMotorTimers[i].timer, dmaMotorTimers[i].timerDmaSources, ENABLE);
dmaMotorTimers[i].timerDmaSources = 0;
Expand All @@ -178,32 +180,27 @@ static void motor_DMA_IRQHandler(dmaChannelDescriptor_t *descriptor)
motorDmaOutput_t * const motor = &dmaMotors[descriptor->userParam];
#ifdef USE_DSHOT_TELEMETRY
uint32_t irqStart = micros();
if (motor->isInput) {
processInputIrq(motor);
} else
#endif
{
#ifdef USE_DSHOT_DMAR
if (useBurstDshot) {
xDMA_Cmd(motor->timerHardware->dmaTimUPRef, DISABLE);
TIM_DMACmd(motor->timerHardware->tim, TIM_DMA_Update, DISABLE);
} else
if (useBurstDshot) {
xDMA_Cmd(motor->timerHardware->dmaTimUPRef, DISABLE);
TIM_DMACmd(motor->timerHardware->tim, TIM_DMA_Update, DISABLE);
} else
#endif
{
xDMA_Cmd(motor->dmaRef, DISABLE);
TIM_DMACmd(motor->timerHardware->tim, motor->timerDmaSource, DISABLE);
}
{
xDMA_Cmd(motor->dmaRef, DISABLE);
TIM_DMACmd(motor->timerHardware->tim, motor->timerDmaSource, DISABLE);
}

#ifdef USE_DSHOT_TELEMETRY
if (useDshotTelemetry) {
pwmDshotSetDirectionOutput(motor, false);
xDMA_SetCurrDataCounter(motor->dmaRef, motor->dmaInputLen);
xDMA_Cmd(motor->dmaRef, ENABLE);
TIM_DMACmd(motor->timerHardware->tim, motor->timerDmaSource, ENABLE);
setDirectionMicros = micros() - irqStart;
}
#endif
if (useDshotTelemetry) {
pwmDshotSetDirectionOutput(motor, false);
xDMA_SetCurrDataCounter(motor->dmaRef, GCR_TELEMETRY_INPUT_LEN);
xDMA_Cmd(motor->dmaRef, ENABLE);
TIM_DMACmd(motor->timerHardware->tim, motor->timerDmaSource, ENABLE);
setDirectionMicros = micros() - irqStart;
}
#endif
DMA_CLEAR_FLAG(descriptor, DMA_IT_TCIF);
}
}
Expand Down Expand Up @@ -254,13 +251,7 @@ void pwmDshotMotorHardwareConfig(const timerHardware_t *timerHardware, uint8_t m
}

motorDmaOutput_t * const motor = &dmaMotors[motorIndex];
#ifdef USE_DSHOT_TELEMETRY
motor->useProshot = (pwmProtocolType == PWM_TYPE_PROSHOT1000);
#endif
motor->timerHardware = timerHardware;

TIM_TypeDef *timer = timerHardware->tim;
const IO_t motorIO = IOGetByTag(timerHardware->tag);

// Boolean configureTimer is always true when different channels of the same timer are processed in sequence,
// causing the timer and the associated DMA initialized more than once.
Expand All @@ -269,6 +260,12 @@ void pwmDshotMotorHardwareConfig(const timerHardware_t *timerHardware, uint8_t m
const uint8_t timerIndex = getTimerIndex(timer);
const bool configureTimer = (timerIndex == dmaMotorTimerCount-1);

motor->timer = &dmaMotorTimers[timerIndex];
motor->index = motorIndex;
motor->timerHardware = timerHardware;

const IO_t motorIO = IOGetByTag(timerHardware->tag);

uint8_t pupMode = 0;
pupMode = (output & TIMER_OUTPUT_INVERTED) ? GPIO_PuPd_DOWN : GPIO_PuPd_UP;
#ifdef USE_DSHOT_TELEMETRY
Expand All @@ -277,7 +274,8 @@ void pwmDshotMotorHardwareConfig(const timerHardware_t *timerHardware, uint8_t m
}
#endif

IOConfigGPIOAF(motorIO, IO_CONFIG(GPIO_Mode_AF, GPIO_Speed_50MHz, GPIO_OType_PP, pupMode), timerHardware->alternateFunction);
motor->iocfg = IO_CONFIG(GPIO_Mode_AF, GPIO_Speed_50MHz, GPIO_OType_PP, pupMode);
IOConfigGPIOAF(motorIO, motor->iocfg, timerHardware->alternateFunction);

if (configureTimer) {
TIM_TimeBaseInitTypeDef TIM_TimeBaseStructure;
Expand Down Expand Up @@ -313,11 +311,9 @@ void pwmDshotMotorHardwareConfig(const timerHardware_t *timerHardware, uint8_t m
motor->icInitStruct.TIM_ICPolarity = TIM_ICPolarity_BothEdge;
motor->icInitStruct.TIM_ICPrescaler = TIM_ICPSC_DIV1;
motor->icInitStruct.TIM_Channel = timerHardware->channel;
motor->icInitStruct.TIM_ICFilter = 0; //2;
motor->icInitStruct.TIM_ICFilter = 2;
#endif

motor->timer = &dmaMotorTimers[timerIndex];
motor->index = motorIndex;

#ifdef USE_DSHOT_DMAR
if (useBurstDshot) {
Expand Down Expand Up @@ -393,10 +389,9 @@ void pwmDshotMotorHardwareConfig(const timerHardware_t *timerHardware, uint8_t m
motor->dmaRef = dmaRef;

#ifdef USE_DSHOT_TELEMETRY
motor->dmaInputLen = motor->useProshot ? PROSHOT_TELEMETRY_INPUT_LEN : DSHOT_TELEMETRY_INPUT_LEN;
motor->dshotTelemetryDeadtimeUs = DSHOT_TELEMETRY_DEADTIME_US + 1000000 *
( 2 + (motor->useProshot ? 4 * MOTOR_NIBBLE_LENGTH_PROSHOT : 16 * MOTOR_BITLENGTH))
/ getDshotHz(pwmProtocolType);
(16 * MOTOR_BITLENGTH) / getDshotHz(pwmProtocolType);
motor->timer->outputPeriod = (pwmProtocolType == PWM_TYPE_PROSHOT1000 ? (MOTOR_NIBBLE_LENGTH_PROSHOT) : MOTOR_BITLENGTH) - 1;
pwmDshotSetDirectionOutput(motor, true);
#else
pwmDshotSetDirectionOutput(motor, true, &OCINIT, &DMAINIT);
Expand Down

0 comments on commit 835a5ca

Please sign in to comment.