mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-17 13:25:30 +03:00
DMA bit banging Dshot, first cut
F405 working (OMNIBUSF4SD target) F411 not tested F722 working, needs testing (OMNINXT7 target) F74x not working NOX target (temporary) bb_dshot with telemetry on f4 bbshot f7 targets and fix crash due to missing debug pins remove empty line add empty lines remove OMNIBUSF4 specific debug pins add missing comma add missing comma Use separate bbTimerHardware array to fix unified targets eliminate now unneeded timerGetByUsage don't duplicate timer1 def Add auto mode, rename dshot_bbshot to dshot_bitbang remove newline renamve various files various changes to address feedback address feedback address feedback add pacer timers to timer show don't disable telemetry if dshot_bitbang is on or auto Address feedback, add faster decode implementation based on bit banding, modify dma parameters to reduce required memory bandwidth on half remove debug output remove NOINLINE Protect gpio direction change with critical sections FIXWS_SAVE_INDEX add static back in no forward typedef address review feedback disallow proshot1000 with dshot bitbang Extracted and plumbed up 'dbgPin'.
This commit is contained in:
parent
37b059532f
commit
adf6fd1764
33 changed files with 2065 additions and 77 deletions
668
src/main/drivers/dshot_bitbang.c
Normal file
668
src/main/drivers/dshot_bitbang.c
Normal file
|
@ -0,0 +1,668 @@
|
|||
/*
|
||||
* This file is part of Cleanflight and Betaflight.
|
||||
*
|
||||
* Cleanflight and Betaflight are free software. You can redistribute
|
||||
* this software and/or modify this software under the terms of the
|
||||
* GNU General Public License as published by the Free Software
|
||||
* Foundation, either version 3 of the License, or (at your option)
|
||||
* any later version.
|
||||
*
|
||||
* Cleanflight and Betaflight are distributed in the hope that they
|
||||
* will be useful, but WITHOUT ANY WARRANTY; without even the implied
|
||||
* warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
|
||||
* See the GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with this software.
|
||||
*
|
||||
* If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#include <stdint.h>
|
||||
#include <math.h>
|
||||
#include <string.h>
|
||||
|
||||
#include "platform.h"
|
||||
|
||||
#ifdef USE_DSHOT_BITBANG
|
||||
|
||||
#include "build/debug.h"
|
||||
|
||||
#include "drivers/io.h"
|
||||
#include "drivers/io_impl.h"
|
||||
#include "drivers/dma.h"
|
||||
#include "drivers/dma_reqmap.h"
|
||||
#include "drivers/dshot.h"
|
||||
#include "drivers/dshot_bitbang.h"
|
||||
#include "drivers/dshot_bitbang_impl.h"
|
||||
#include "drivers/dshot_command.h"
|
||||
#include "drivers/motor.h"
|
||||
#include "drivers/nvic.h"
|
||||
#include "drivers/pwm_output.h" // XXX for pwmOutputPort_t motors[]; should go away with refactoring
|
||||
#include "drivers/dshot_bitbang_decode.h"
|
||||
#include "drivers/time.h"
|
||||
#include "drivers/timer.h"
|
||||
|
||||
#include "pg/motor.h"
|
||||
|
||||
//TODO: Change these to be only used if USE_DEBUG_PIN is not defined once the debug_pin functionality has been merged
|
||||
#define dbgPinInit()
|
||||
#define dbgPinHi(x)
|
||||
#define dbgPinLo(x)
|
||||
|
||||
FAST_RAM_ZERO_INIT bbPacer_t bbPacers[MAX_MOTOR_PACERS]; // TIM1 or TIM8
|
||||
FAST_RAM_ZERO_INIT int usedMotorPacers = 0;
|
||||
|
||||
FAST_RAM_ZERO_INIT bbPort_t bbPorts[MAX_SUPPORTED_MOTOR_PORTS];
|
||||
FAST_RAM_ZERO_INIT int usedMotorPorts;
|
||||
|
||||
FAST_RAM_ZERO_INIT bbMotor_t bbMotors[MAX_SUPPORTED_MOTORS];
|
||||
|
||||
FAST_RAM_ZERO_INIT bbPort_t *gpioToMotorPort[10]; // GPIO group to bbPort mappin
|
||||
static FAST_RAM_ZERO_INIT int motorCount;
|
||||
dshotBitbangStatus_e bbStatus;
|
||||
|
||||
// For MCUs that use MPU to control DMA coherency, there might be a performance hit
|
||||
// on manipulating input buffer content especially if it is read multiple times,
|
||||
// as the buffer region is attributed as not cachable.
|
||||
// If this is not desirable, we should use manual cache invalidation.
|
||||
|
||||
#if defined(STM32F4)
|
||||
#define BB_OUTPUT_BUFFER_ATTRIBUTE
|
||||
#define BB_INPUT_BUFFER_ATTRIBUTE
|
||||
#elif defined(STM32F7)
|
||||
#define BB_OUTPUT_BUFFER_ATTRIBUTE FAST_RAM_ZERO_INIT
|
||||
#define BB_INPUT_BUFFER_ATTRIBUTE FAST_RAM_ZERO_INIT
|
||||
#elif defined(STM32H7)
|
||||
#define BB_OUTPUT_BUFFER_ATTRIBUTE DMA_RAM
|
||||
#define BB_INPUT_BUFFER_ATTRIBUTE DMA_RAM
|
||||
#endif
|
||||
|
||||
BB_OUTPUT_BUFFER_ATTRIBUTE uint32_t bbOutputBuffer[MOTOR_DSHOT_BUFFER_SIZE * MAX_SUPPORTED_MOTOR_PORTS];
|
||||
BB_INPUT_BUFFER_ATTRIBUTE uint16_t bbInputBuffer[DSHOT_BITBANG_PORT_INPUT_BUFFER_LENGTH * MAX_SUPPORTED_MOTOR_PORTS];
|
||||
|
||||
uint8_t bbPuPdMode;
|
||||
FAST_RAM_ZERO_INIT timeUs_t dshotFrameUs;
|
||||
|
||||
|
||||
const timerHardware_t bbTimerHardware[] = {
|
||||
#if defined(STM32F4) || defined(STM32F7)
|
||||
DEF_TIM(TIM1, CH1, NONE, TIM_USE_NONE, 0, 1),
|
||||
DEF_TIM(TIM1, CH1, NONE, TIM_USE_NONE, 0, 2),
|
||||
DEF_TIM(TIM1, CH2, NONE, TIM_USE_NONE, 0, 1),
|
||||
DEF_TIM(TIM1, CH3, NONE, TIM_USE_NONE, 0, 1),
|
||||
DEF_TIM(TIM1, CH4, NONE, TIM_USE_NONE, 0, 0),
|
||||
#if !defined(STM32F40_41xxx)
|
||||
DEF_TIM(TIM8, CH1, NONE, TIM_USE_NONE, 0, 1),
|
||||
DEF_TIM(TIM8, CH2, NONE, TIM_USE_NONE, 0, 1),
|
||||
DEF_TIM(TIM8, CH3, NONE, TIM_USE_NONE, 0, 1),
|
||||
DEF_TIM(TIM8, CH4, NONE, TIM_USE_NONE, 0, 0),
|
||||
#endif
|
||||
#endif
|
||||
};
|
||||
|
||||
// DMA GPIO output buffer formatting
|
||||
|
||||
static void bbOutputDataInit(uint32_t *buffer, uint16_t portMask, bool inverted)
|
||||
{
|
||||
uint32_t resetMask;
|
||||
uint32_t setMask;
|
||||
|
||||
if (inverted) {
|
||||
resetMask = portMask;
|
||||
setMask = (portMask << 16);
|
||||
} else {
|
||||
resetMask = (portMask << 16);
|
||||
setMask = portMask;
|
||||
}
|
||||
|
||||
int bitpos;
|
||||
|
||||
for (bitpos = 0; bitpos < 16; bitpos++) {
|
||||
buffer[bitpos * 3 + 0] |= setMask ; // Always set all ports
|
||||
buffer[bitpos * 3 + 1] = 0; // Reset bits are port dependent
|
||||
buffer[bitpos * 3 + 2] |= resetMask; // Always reset all ports
|
||||
}
|
||||
}
|
||||
|
||||
static void bbOutputDataSet(uint32_t *buffer, int pinNumber, uint16_t value, bool inverted)
|
||||
{
|
||||
uint32_t middleBit;
|
||||
|
||||
if (inverted) {
|
||||
middleBit = (1 << (pinNumber + 0));
|
||||
} else {
|
||||
middleBit = (1 << (pinNumber + 16));
|
||||
}
|
||||
|
||||
for (int pos = 0; pos < 16; pos++) {
|
||||
if (!(value & 0x8000)) {
|
||||
buffer[pos * 3 + 1] |= middleBit;
|
||||
}
|
||||
value <<= 1;
|
||||
}
|
||||
}
|
||||
|
||||
static void bbOutputDataClear(uint32_t *buffer)
|
||||
{
|
||||
// Middle position to no change
|
||||
for (int bitpos = 0; bitpos < 16; bitpos++) {
|
||||
buffer[bitpos * 3 + 1] = 0;
|
||||
}
|
||||
}
|
||||
|
||||
// bbPacer management
|
||||
|
||||
static bbPacer_t *bbFindMotorPacer(TIM_TypeDef *tim)
|
||||
{
|
||||
for (int i = 0; i < MAX_MOTOR_PACERS; i++) {
|
||||
|
||||
bbPacer_t *bbPacer = &bbPacers[i];
|
||||
|
||||
if (bbPacer->tim == NULL) {
|
||||
bbPacer->tim = tim;
|
||||
++usedMotorPacers;
|
||||
return bbPacer;
|
||||
}
|
||||
|
||||
if (bbPacer->tim == tim) {
|
||||
return bbPacer;
|
||||
}
|
||||
}
|
||||
|
||||
return NULL;
|
||||
}
|
||||
|
||||
// bbPort management
|
||||
|
||||
static bbPort_t *bbFindMotorPort(int portIndex)
|
||||
{
|
||||
for (int i = 0; i < usedMotorPorts; i++) {
|
||||
if (bbPorts[i].portIndex == portIndex) {
|
||||
return &bbPorts[i];
|
||||
}
|
||||
}
|
||||
return NULL;
|
||||
}
|
||||
|
||||
static bbPort_t *bbAllocMotorPort(int portIndex)
|
||||
{
|
||||
if (usedMotorPorts == MAX_SUPPORTED_MOTOR_PORTS) {
|
||||
return NULL;
|
||||
}
|
||||
|
||||
bbPort_t *bbPort = &bbPorts[usedMotorPorts];
|
||||
|
||||
if (!bbPort->timhw) {
|
||||
// No more pacer channel available
|
||||
bbStatus = DSHOT_BITBANG_NO_PACER;
|
||||
return NULL;
|
||||
}
|
||||
|
||||
gpioToMotorPort[portIndex] = bbPort;
|
||||
++usedMotorPorts;
|
||||
|
||||
return bbPort;
|
||||
}
|
||||
|
||||
const timerHardware_t* dshotBitbangGetPacerTimer(int index)
|
||||
{
|
||||
return index < usedMotorPorts ? bbPorts[index].timhw : NULL;
|
||||
}
|
||||
|
||||
// Return frequency of smallest change [state/sec]
|
||||
|
||||
static uint32_t getDshotBaseFrequency(motorPwmProtocolTypes_e pwmProtocolType)
|
||||
{
|
||||
switch (pwmProtocolType) {
|
||||
case(PWM_TYPE_DSHOT1200):
|
||||
return MOTOR_DSHOT1200_SYMBOL_RATE * MOTOR_DSHOT_STATE_PER_SYMBOL;
|
||||
case(PWM_TYPE_DSHOT600):
|
||||
return MOTOR_DSHOT600_SYMBOL_RATE * MOTOR_DSHOT_STATE_PER_SYMBOL;
|
||||
case(PWM_TYPE_DSHOT300):
|
||||
return MOTOR_DSHOT300_SYMBOL_RATE * MOTOR_DSHOT_STATE_PER_SYMBOL;
|
||||
default:
|
||||
case(PWM_TYPE_DSHOT150):
|
||||
return MOTOR_DSHOT150_SYMBOL_RATE * MOTOR_DSHOT_STATE_PER_SYMBOL;
|
||||
}
|
||||
}
|
||||
|
||||
static void bbAllocDma(bbPort_t *bbPort)
|
||||
{
|
||||
const timerHardware_t *timhw = bbPort->timhw;
|
||||
|
||||
#ifdef USE_DMA_SPEC
|
||||
dmaoptValue_t dmaopt = dmaGetOptionByTimer(timhw);
|
||||
const dmaChannelSpec_t *dmaChannelSpec = dmaGetChannelSpecByTimerValue(timhw->tim, timhw->channel, dmaopt);
|
||||
bbPort->dmaResource = dmaChannelSpec->ref;
|
||||
bbPort->dmaChannel = dmaChannelSpec->channel;
|
||||
#else
|
||||
bbPort->dmaResource = timhw->dmaRef;
|
||||
bbPort->dmaChannel = timhw->dmaChannel;
|
||||
#endif
|
||||
|
||||
dmaIdentifier_e dmaIdentifier = dmaGetIdentifier(bbPort->dmaResource);
|
||||
dmaInit(dmaIdentifier, OWNER_DSHOT_BITBANG, RESOURCE_INDEX(bbPort - bbPorts));
|
||||
bbPort->dmaSource = timerDmaSource(timhw->channel);
|
||||
|
||||
bbPacer_t *bbPacer = bbFindMotorPacer(timhw->tim);
|
||||
bbPacer->dmaSources |= bbPort->dmaSource;
|
||||
|
||||
dmaSetHandler(dmaIdentifier, bbDMAIrqHandler, NVIC_BUILD_PRIORITY(2, 1), (uint32_t)bbPort);
|
||||
|
||||
bbDMA_ITConfig(bbPort);
|
||||
}
|
||||
|
||||
void bbDMAIrqHandler(dmaChannelDescriptor_t *descriptor)
|
||||
{
|
||||
dbgPinHi(0);
|
||||
|
||||
bbPort_t *bbPort = (bbPort_t *)descriptor->userParam;
|
||||
|
||||
bbDMA_Cmd(bbPort, DISABLE);
|
||||
|
||||
bbTIM_DMACmd(bbPort->timhw->tim, bbPort->dmaSource, DISABLE);
|
||||
|
||||
if (DMA_GET_FLAG_STATUS(descriptor, DMA_IT_TEIF)) {
|
||||
while (1) {};
|
||||
}
|
||||
|
||||
DMA_CLEAR_FLAG(descriptor, DMA_IT_TCIF);
|
||||
|
||||
#ifdef USE_DSHOT_TELEMETRY
|
||||
if (useDshotTelemetry) {
|
||||
if (bbPort->direction == DSHOT_BITBANG_DIRECTION_INPUT) {
|
||||
#ifdef DEBUG_COUNT_INTERRUPT
|
||||
bbPort->inputIrq++;
|
||||
#endif
|
||||
} else {
|
||||
#ifdef DEBUG_COUNT_INTERRUPT
|
||||
bbPort->outputIrq++;
|
||||
#endif
|
||||
|
||||
// Switch to input
|
||||
|
||||
bbSwitchToInput(bbPort);
|
||||
|
||||
bbTIM_DMACmd(bbPort->timhw->tim, bbPort->dmaSource, ENABLE);
|
||||
}
|
||||
}
|
||||
#endif
|
||||
dbgPinLo(0);
|
||||
}
|
||||
|
||||
// Setup bbPorts array elements so that they each have a TIM1 or TIM8 channel
|
||||
// in timerHardware array for BB-DShot.
|
||||
|
||||
static void bbFindPacerTimer(void)
|
||||
{
|
||||
const timerHardware_t *timer;
|
||||
bool usedTimerChannels[32][CC_CHANNELS_PER_TIMER] = {0};
|
||||
|
||||
for (int bbPortIndex = 0; bbPortIndex < MAX_SUPPORTED_MOTOR_PORTS; bbPortIndex++) {
|
||||
for (unsigned timerIndex = 0; timerIndex < ARRAYLEN(bbTimerHardware); timerIndex++) {
|
||||
timer = &bbTimerHardware[timerIndex];
|
||||
int timNumber = timerGetTIMNumber(timer->tim);
|
||||
bool timerConflict = false;
|
||||
for (int channel = 0; channel < CC_CHANNELS_PER_TIMER; channel++) {
|
||||
if(timerGetOwner(timNumber, CC_CHANNEL_FROM_INDEX(channel))->owner != OWNER_FREE) {
|
||||
timerConflict = true;
|
||||
break;
|
||||
}
|
||||
}
|
||||
if (timerConflict) {
|
||||
continue;
|
||||
}
|
||||
|
||||
#ifdef USE_DMA_SPEC
|
||||
dmaoptValue_t dmaopt = dmaGetOptionByTimer(timer);
|
||||
const dmaChannelSpec_t *dmaChannelSpec = dmaGetChannelSpecByTimerValue(timer->tim, timer->channel, dmaopt);
|
||||
dmaResource_t *dma = dmaChannelSpec->ref;
|
||||
#else
|
||||
dmaResource_t *dma = timer->dmaRef;
|
||||
#endif
|
||||
dmaIdentifier_e dmaIdentifier = dmaGetIdentifier(dma);
|
||||
if (dmaGetOwner(dmaIdentifier)->owner == OWNER_FREE &&
|
||||
!usedTimerChannels[timNumber][timer->channel]) {
|
||||
usedTimerChannels[timNumber][timer->channel] = true;
|
||||
break;
|
||||
}
|
||||
}
|
||||
bbPorts[bbPortIndex].timhw = timer;
|
||||
}
|
||||
}
|
||||
|
||||
static void bbTimebaseSetup(bbPort_t *bbPort, motorPwmProtocolTypes_e dshotProtocolType)
|
||||
{
|
||||
uint32_t timerclock = timerClock(bbPort->timhw->tim);
|
||||
|
||||
uint32_t outputFreq = getDshotBaseFrequency(dshotProtocolType);
|
||||
dshotFrameUs = 1000000 * 17 * 3 / outputFreq;
|
||||
bbPort->outputARR = timerclock / outputFreq - 1;
|
||||
|
||||
// XXX Explain this formula
|
||||
uint32_t inputFreq = outputFreq * 5 * 2 * DSHOT_BITBANG_TELEMETRY_OVER_SAMPLE / 24;
|
||||
bbPort->inputARR = timerclock / inputFreq - 1;
|
||||
}
|
||||
|
||||
//
|
||||
// bb only use pin info associated with timerHardware entry designated as TIM_USE_MOTOR;
|
||||
// it does not use the timer channel associated with the pin.
|
||||
//
|
||||
|
||||
static bool bbMotorConfig(IO_t io, uint8_t motorIndex, motorPwmProtocolTypes_e pwmProtocolType, uint8_t output)
|
||||
{
|
||||
int pinIndex = IO_GPIOPinIdx(io);
|
||||
int portIndex = IO_GPIOPortIdx(io);
|
||||
|
||||
bbPort_t *bbPort = bbFindMotorPort(portIndex);
|
||||
|
||||
if (!bbPort) {
|
||||
|
||||
// New port group
|
||||
|
||||
bbPort = bbAllocMotorPort(portIndex);
|
||||
if (!bbPort) {
|
||||
return false;
|
||||
}
|
||||
|
||||
bbPort->gpio = IO_GPIO(io);
|
||||
bbPort->portIndex = portIndex;
|
||||
|
||||
bbPort->portOutputCount = MOTOR_DSHOT_BUFFER_SIZE;
|
||||
bbPort->portOutputBuffer = &bbOutputBuffer[(bbPort - bbPorts) * MOTOR_DSHOT_BUFFER_SIZE];
|
||||
|
||||
bbPort->portInputCount = DSHOT_BITBANG_PORT_INPUT_BUFFER_LENGTH;
|
||||
bbPort->portInputBuffer = &bbInputBuffer[(bbPort - bbPorts) * DSHOT_BITBANG_PORT_INPUT_BUFFER_LENGTH];
|
||||
|
||||
bbTimebaseSetup(bbPort, pwmProtocolType);
|
||||
bbTIM_TimeBaseInit(bbPort, bbPort->outputARR);
|
||||
bbTimerChannelInit(bbPort);
|
||||
|
||||
bbAllocDma(bbPort);
|
||||
bbDMAPreconfigure(bbPort, DSHOT_BITBANG_DIRECTION_OUTPUT);
|
||||
bbDMAPreconfigure(bbPort, DSHOT_BITBANG_DIRECTION_INPUT);
|
||||
|
||||
bbDMA_ITConfig(bbPort);
|
||||
}
|
||||
|
||||
bbMotors[motorIndex].pinIndex = pinIndex;
|
||||
bbMotors[motorIndex].io = io;
|
||||
bbMotors[motorIndex].output = output;
|
||||
bbMotors[motorIndex].bbPort = bbPort;
|
||||
|
||||
IOInit(io, OWNER_MOTOR, RESOURCE_INDEX(motorIndex));
|
||||
|
||||
// Setup GPIO_MODER and GPIO_ODR register manipulation values
|
||||
|
||||
bbGpioSetup(&bbMotors[motorIndex]);
|
||||
|
||||
#ifdef USE_DSHOT_TELEMETRY
|
||||
if (useDshotTelemetry) {
|
||||
bbOutputDataInit(bbPort->portOutputBuffer, (1 << pinIndex), DSHOT_BITBANG_INVERTED);
|
||||
} else
|
||||
#endif
|
||||
{
|
||||
bbOutputDataInit(bbPort->portOutputBuffer, (1 << pinIndex), DSHOT_BITBANG_NONINVERTED);
|
||||
}
|
||||
|
||||
bbSwitchToOutput(bbPort);
|
||||
|
||||
bbMotors[motorIndex].configured = true;
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
static FAST_RAM_ZERO_INIT motorDevice_t bbDevice;
|
||||
static FAST_RAM_ZERO_INIT timeUs_t lastSendUs;
|
||||
|
||||
static bool bbUpdateStart(void)
|
||||
{
|
||||
#ifdef USE_DSHOT_TELEMETRY
|
||||
if (useDshotTelemetry) {
|
||||
#ifdef USE_DSHOT_TELEMETRY_STATS
|
||||
const timeMs_t currentTimeMs = millis();
|
||||
#endif
|
||||
timeUs_t currentUs = micros();
|
||||
// don't send while telemetry frames might still be incoming
|
||||
if (cmpTimeUs(currentUs, lastSendUs) < (timeDelta_t)(40 + 2 * dshotFrameUs)) {
|
||||
return false;
|
||||
}
|
||||
|
||||
for (int motorIndex = 0; motorIndex < MAX_SUPPORTED_MOTORS && motorIndex < motorCount; motorIndex++) {
|
||||
#ifdef STM32F4
|
||||
uint32_t value = decode_bb_bitband(
|
||||
bbMotors[motorIndex].bbPort->portInputBuffer,
|
||||
bbMotors[motorIndex].bbPort->portInputCount - bbDMA_Count(bbMotors[motorIndex].bbPort),
|
||||
bbMotors[motorIndex].pinIndex);
|
||||
#else
|
||||
uint32_t value = decode_bb(
|
||||
bbMotors[motorIndex].bbPort->portInputBuffer,
|
||||
bbMotors[motorIndex].bbPort->portInputCount - bbDMA_Count(bbMotors[motorIndex].bbPort),
|
||||
bbMotors[motorIndex].pinIndex);
|
||||
#endif
|
||||
if (value == BB_NOEDGE) {
|
||||
continue;
|
||||
}
|
||||
dshotTelemetryState.readCount++;
|
||||
|
||||
if (value != BB_INVALID) {
|
||||
dshotTelemetryState.motorState[motorIndex].telemetryValue = value;
|
||||
dshotTelemetryState.motorState[motorIndex].telemetryActive = true;
|
||||
if (motorIndex < 4) {
|
||||
DEBUG_SET(DEBUG_DSHOT_RPM_TELEMETRY, motorIndex, value);
|
||||
}
|
||||
} else {
|
||||
dshotTelemetryState.invalidPacketCount++;
|
||||
}
|
||||
#ifdef USE_DSHOT_TELEMETRY_STATS
|
||||
updateDshotTelemetryQuality(&dshotTelemetryQuality[motorIndex], value != BB_INVALID, currentTimeMs);
|
||||
#endif
|
||||
}
|
||||
}
|
||||
#endif
|
||||
for (int i = 0; i < usedMotorPorts; i++) {
|
||||
bbDMA_Cmd(&bbPorts[i], DISABLE);
|
||||
bbOutputDataClear(bbPorts[i].portOutputBuffer);
|
||||
}
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
static void bbWriteInt(uint8_t motorIndex, uint16_t value)
|
||||
{
|
||||
bbMotor_t *const bbmotor = &bbMotors[motorIndex];
|
||||
|
||||
if (!bbmotor->configured) {
|
||||
return;
|
||||
}
|
||||
|
||||
// If there is a command ready to go overwrite the value and send that instead
|
||||
|
||||
if (dshotCommandIsProcessing()) {
|
||||
value = dshotCommandGetCurrent(motorIndex);
|
||||
if (value) {
|
||||
bbmotor->protocolControl.requestTelemetry = true;
|
||||
}
|
||||
}
|
||||
|
||||
bbmotor->protocolControl.value = value;
|
||||
|
||||
uint16_t packet = prepareDshotPacket(&bbmotor->protocolControl);
|
||||
|
||||
bbPort_t *bbPort = bbmotor->bbPort;
|
||||
|
||||
#ifdef USE_DSHOT_TELEMETRY
|
||||
if (useDshotTelemetry) {
|
||||
bbOutputDataSet(bbPort->portOutputBuffer, bbmotor->pinIndex, packet, DSHOT_BITBANG_INVERTED);
|
||||
} else
|
||||
#endif
|
||||
{
|
||||
bbOutputDataSet(bbPort->portOutputBuffer, bbmotor->pinIndex, packet, DSHOT_BITBANG_NONINVERTED);
|
||||
}
|
||||
}
|
||||
|
||||
static void bbWrite(uint8_t motorIndex, float value)
|
||||
{
|
||||
bbWriteInt(motorIndex, value);
|
||||
}
|
||||
|
||||
static void bbUpdateComplete(void)
|
||||
{
|
||||
// If there is a dshot command loaded up, time it correctly with motor update
|
||||
|
||||
if (!dshotCommandQueueEmpty()) {
|
||||
if (!dshotCommandOutputIsEnabled(bbDevice.count)) {
|
||||
return;
|
||||
}
|
||||
}
|
||||
|
||||
#ifdef USE_DSHOT_TELEMETRY
|
||||
for (int i = 0; i < usedMotorPorts; i++) {
|
||||
bbPort_t *bbPort = &bbPorts[i];
|
||||
|
||||
if (useDshotTelemetry) {
|
||||
if (bbPort->direction == DSHOT_BITBANG_DIRECTION_INPUT) {
|
||||
bbPort->inputActive = false;
|
||||
bbSwitchToOutput(bbPort);
|
||||
}
|
||||
|
||||
|
||||
bbDMA_Cmd(bbPort, ENABLE);
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
||||
lastSendUs = micros();
|
||||
for (int i = 0; i < usedMotorPacers; i++) {
|
||||
bbPacer_t *bbPacer = &bbPacers[i];
|
||||
bbTIM_DMACmd(bbPacer->tim, bbPacer->dmaSources, ENABLE);
|
||||
}
|
||||
}
|
||||
|
||||
static bool bbEnableMotors(void)
|
||||
{
|
||||
for (int i = 0; i < motorCount; i++) {
|
||||
IOConfigGPIO(bbMotors[i].io, bbMotors[i].iocfg);
|
||||
}
|
||||
return true;
|
||||
}
|
||||
|
||||
static void bbDisableMotors(void)
|
||||
{
|
||||
return;
|
||||
}
|
||||
|
||||
static void bbShutdown(void)
|
||||
{
|
||||
return;
|
||||
}
|
||||
|
||||
static bool bbIsMotorEnabled(uint8_t index)
|
||||
{
|
||||
return bbMotors[index].enabled;
|
||||
}
|
||||
|
||||
static const motorDevConfig_t *lastMotorConfig;
|
||||
|
||||
static void bbPostInit()
|
||||
{
|
||||
bbFindPacerTimer();
|
||||
|
||||
for (int motorIndex = 0; motorIndex < MAX_SUPPORTED_MOTORS && motorIndex < motorCount; motorIndex++) {
|
||||
|
||||
if (!bbMotorConfig(bbMotors[motorIndex].io, motorIndex, lastMotorConfig->motorPwmProtocol, bbMotors[motorIndex].output)) {
|
||||
return NULL;
|
||||
}
|
||||
|
||||
|
||||
bbMotors[motorIndex].enabled = true;
|
||||
|
||||
// Fill in motors structure for 4way access (XXX Should be refactored)
|
||||
|
||||
motors[motorIndex].enabled = true;
|
||||
}
|
||||
}
|
||||
|
||||
static motorVTable_t bbVTable = {
|
||||
.postInit = bbPostInit,
|
||||
.enable = bbEnableMotors,
|
||||
.disable = bbDisableMotors,
|
||||
.isMotorEnabled = bbIsMotorEnabled,
|
||||
.updateStart = bbUpdateStart,
|
||||
.write = bbWrite,
|
||||
.writeInt = bbWriteInt,
|
||||
.updateComplete = bbUpdateComplete,
|
||||
.convertExternalToMotor = dshotConvertFromExternal,
|
||||
.convertMotorToExternal = dshotConvertToExternal,
|
||||
.shutdown = bbShutdown,
|
||||
};
|
||||
|
||||
dshotBitbangStatus_e dshotBitbangGetStatus()
|
||||
{
|
||||
return bbStatus;
|
||||
}
|
||||
|
||||
motorDevice_t *dshotBitbangDevInit(const motorDevConfig_t *motorConfig, uint8_t count)
|
||||
{
|
||||
dbgPinInit();
|
||||
dbgPinLo(0);
|
||||
dbgPinLo(1);
|
||||
|
||||
lastMotorConfig = motorConfig;
|
||||
bbDevice.vTable = bbVTable;
|
||||
motorCount = count;
|
||||
bbStatus = DSHOT_BITBANG_OK;
|
||||
|
||||
#ifdef USE_DSHOT_TELEMETRY
|
||||
useDshotTelemetry = motorConfig->useDshotTelemetry;
|
||||
#endif
|
||||
|
||||
for (int motorIndex = 0; motorIndex < MAX_SUPPORTED_MOTORS && motorIndex < motorCount; motorIndex++) {
|
||||
const timerHardware_t *timerHardware = timerGetByTag(motorConfig->ioTags[motorIndex]);
|
||||
const IO_t io = IOGetByTag(motorConfig->ioTags[motorIndex]);
|
||||
|
||||
uint8_t output = motorConfig->motorPwmInversion ? timerHardware->output ^ TIMER_OUTPUT_INVERTED : timerHardware->output;
|
||||
bbPuPdMode = (output & TIMER_OUTPUT_INVERTED) ? BB_GPIO_PULLDOWN : BB_GPIO_PULLUP;
|
||||
|
||||
#ifdef USE_DSHOT_TELEMETRY
|
||||
if (useDshotTelemetry) {
|
||||
output ^= TIMER_OUTPUT_INVERTED;
|
||||
}
|
||||
#endif
|
||||
|
||||
if (!IOIsFreeOrPreinit(io)) {
|
||||
/* not enough motors initialised for the mixer or a break in the motors */
|
||||
bbDevice.vTable.write = motorWriteNull;
|
||||
bbDevice.vTable.updateComplete = motorUpdateCompleteNull;
|
||||
bbStatus = DSHOT_BITBANG_MOTOR_PIN_CONFLICT;
|
||||
return NULL;
|
||||
}
|
||||
|
||||
int pinIndex = IO_GPIOPinIdx(io);
|
||||
|
||||
bbMotors[motorIndex].pinIndex = pinIndex;
|
||||
bbMotors[motorIndex].io = io;
|
||||
bbMotors[motorIndex].output = output;
|
||||
#if defined(STM32F4) || defined(STM32F3)
|
||||
bbMotors[motorIndex].iocfg = IO_CONFIG(GPIO_Mode_OUT, GPIO_Speed_50MHz, GPIO_OType_PP, bbPuPdMode);
|
||||
#elif defined(STM32F7)
|
||||
bbMotors[motorIndex].iocfg = IO_CONFIG(GPIO_MODE_OUTPUT_PP, GPIO_SPEED_FREQ_VERY_HIGH, bbPuPdMode);
|
||||
#endif
|
||||
|
||||
IOInit(io, OWNER_MOTOR, RESOURCE_INDEX(motorIndex));
|
||||
IOConfigGPIO(io, bbMotors[motorIndex].iocfg);
|
||||
if (output & TIMER_OUTPUT_INVERTED) {
|
||||
IOLo(io);
|
||||
} else {
|
||||
IOHi(io);
|
||||
}
|
||||
|
||||
// Fill in motors structure for 4way access (XXX Should be refactored)
|
||||
motors[motorIndex].io = bbMotors[motorIndex].io;
|
||||
}
|
||||
|
||||
return &bbDevice;
|
||||
}
|
||||
|
||||
#endif // USE_DSHOT_BB
|
Loading…
Add table
Add a link
Reference in a new issue