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
|
@ -175,6 +175,9 @@ MCU_COMMON_SRC = \
|
|||
drivers/bus_i2c_stm32f10x.c \
|
||||
drivers/bus_spi_stdperiph.c \
|
||||
drivers/dma_stm32f4xx.c \
|
||||
drivers/dshot_bitbang.c \
|
||||
drivers/dshot_bitbang_decode.c \
|
||||
drivers/dshot_bitbang_stdperiph.c \
|
||||
drivers/inverter.c \
|
||||
drivers/light_ws2811strip_stdperiph.c \
|
||||
drivers/transponder_ir_io_stdperiph.c \
|
||||
|
|
|
@ -174,6 +174,9 @@ MCU_COMMON_SRC = \
|
|||
drivers/transponder_ir_io_hal.c \
|
||||
drivers/bus_spi_ll.c \
|
||||
drivers/persistent.c \
|
||||
drivers/dshot_bitbang.c \
|
||||
drivers/dshot_bitbang_decode.c \
|
||||
drivers/dshot_bitbang_ll.c \
|
||||
drivers/pwm_output_dshot_hal.c \
|
||||
drivers/pwm_output_dshot_shared.c \
|
||||
drivers/timer_hal.c \
|
||||
|
|
|
@ -5616,12 +5616,28 @@ static void showTimers(void)
|
|||
cliRepeat('-', 23);
|
||||
#endif
|
||||
|
||||
#ifdef USE_DSHOT_BITBANG
|
||||
resourceOwner_t bitbangOwner = { OWNER_DSHOT_BITBANG, 0 };
|
||||
#endif
|
||||
int8_t timerNumber;
|
||||
for (int i = 0; (timerNumber = timerGetNumberByIndex(i)); i++) {
|
||||
cliPrintf("TIM%d:", timerNumber);
|
||||
bool timerUsed = false;
|
||||
for (unsigned timerIndex = 0; timerIndex < CC_CHANNELS_PER_TIMER; timerIndex++) {
|
||||
const resourceOwner_t *timerOwner = timerGetOwner(timerNumber, CC_CHANNEL_FROM_INDEX(timerIndex));
|
||||
#ifdef USE_DSHOT_BITBANG
|
||||
if (!timerOwner->owner) {
|
||||
const timerHardware_t* timer;
|
||||
int pacerIndex = 0;
|
||||
while ((timer = dshotBitbangGetPacerTimer(pacerIndex++))) {
|
||||
if (timerGetTIMNumber(timer->tim) == timerNumber && timer->channel == CC_CHANNEL_FROM_INDEX(timerIndex)) {
|
||||
timerOwner = &bitbangOwner;
|
||||
bitbangOwner.resourceIndex++;
|
||||
break;
|
||||
}
|
||||
}
|
||||
}
|
||||
#endif
|
||||
if (timerOwner->owner) {
|
||||
if (!timerUsed) {
|
||||
timerUsed = true;
|
||||
|
@ -5879,12 +5895,11 @@ static void cliDshotTelemetryInfo(char *cmdline)
|
|||
UNUSED(cmdline);
|
||||
|
||||
if (useDshotTelemetry) {
|
||||
cliPrintLinef("Dshot reads: %u", readDoneCount);
|
||||
cliPrintLinef("Dshot invalid pkts: %u", dshotInvalidPacketCount);
|
||||
cliPrintLinef("Dshot reads: %u", dshotTelemetryState.readCount);
|
||||
cliPrintLinef("Dshot invalid pkts: %u", dshotTelemetryState.invalidPacketCount);
|
||||
uint32_t directionChangeCycles = dshotDMAHandlerCycleCounters.changeDirectionCompletedAt - dshotDMAHandlerCycleCounters.irqAt;
|
||||
uint32_t directionChangeDurationUs = clockCyclesToMicros(directionChangeCycles);
|
||||
cliPrintLinef("Dshot directionChange cycles: %u, micros: %u", directionChangeCycles, directionChangeDurationUs);
|
||||
cliPrintLinef("Dshot packet decode micros: %u", decodePacketDurationUs);
|
||||
cliPrintLinefeed();
|
||||
|
||||
#ifdef USE_DSHOT_TELEMETRY_STATS
|
||||
|
@ -5913,12 +5928,19 @@ static void cliDshotTelemetryInfo(char *cmdline)
|
|||
cliPrintLinefeed();
|
||||
|
||||
const int len = MAX_GCR_EDGES;
|
||||
#ifdef DEBUG_BBDECODE
|
||||
extern uint16_t bbBuffer[134];
|
||||
for (int i = 0; i < 134; i++) {
|
||||
cliPrintf("%u ", (int)bbBuffer[i]);
|
||||
}
|
||||
cliPrintLinefeed();
|
||||
#endif
|
||||
for (int i = 0; i < len; i++) {
|
||||
cliPrintf("%u ", (int)inputBuffer[i]);
|
||||
cliPrintf("%u ", (int)dshotTelemetryState.inputBuffer[i]);
|
||||
}
|
||||
cliPrintLinefeed();
|
||||
for (int i = 1; i < len; i++) {
|
||||
cliPrintf("%u ", (int)(inputBuffer[i] - inputBuffer[i-1]));
|
||||
cliPrintf("%u ", (int)(dshotTelemetryState.inputBuffer[i] - dshotTelemetryState.inputBuffer[i-1]));
|
||||
}
|
||||
cliPrintLinefeed();
|
||||
} else {
|
||||
|
@ -6566,4 +6588,5 @@ void cliEnter(serialPort_t *serialPort)
|
|||
resetCommandBatch();
|
||||
#endif
|
||||
}
|
||||
|
||||
#endif // USE_CLI
|
||||
|
|
|
@ -469,6 +469,10 @@ static const char * const lookupTablePositionAltSource[] = {
|
|||
"DEFAULT", "BARO_ONLY", "GPS_ONLY"
|
||||
};
|
||||
|
||||
static const char * const lookupTableDshotBitbang[] = {
|
||||
"OFF", "ON", "AUTO"
|
||||
};
|
||||
|
||||
#define LOOKUP_TABLE_ENTRY(name) { name, ARRAYLEN(name) }
|
||||
|
||||
const lookupTableEntry_t lookupTables[] = {
|
||||
|
@ -583,6 +587,7 @@ const lookupTableEntry_t lookupTables[] = {
|
|||
LOOKUP_TABLE_ENTRY(lookupTableGyroFilterDebug),
|
||||
|
||||
LOOKUP_TABLE_ENTRY(lookupTablePositionAltSource),
|
||||
LOOKUP_TABLE_ENTRY(lookupTableDshotBitbang),
|
||||
};
|
||||
|
||||
#undef LOOKUP_TABLE_ENTRY
|
||||
|
@ -755,6 +760,9 @@ const clivalue_t valueTable[] = {
|
|||
#ifdef USE_DSHOT_TELEMETRY
|
||||
{ "dshot_bidir", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_MOTOR_CONFIG, offsetof(motorConfig_t, dev.useDshotTelemetry) },
|
||||
#endif
|
||||
#ifdef USE_DSHOT_BITBANG
|
||||
{ "dshot_bitbang", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_DSHOT_BITBANG }, PG_MOTOR_CONFIG, offsetof(motorConfig_t, dev.useDshotBitbang) },
|
||||
#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) },
|
||||
|
|
|
@ -135,6 +135,7 @@ typedef enum {
|
|||
#endif
|
||||
TABLE_GYRO_FILTER_DEBUG,
|
||||
TABLE_POSITION_ALT_SOURCE,
|
||||
TABLE_DSHOT_BITBANG,
|
||||
|
||||
LOOKUP_TABLE_COUNT
|
||||
} lookupTableIndex_e;
|
||||
|
@ -248,4 +249,4 @@ extern const char * const lookupTableRescueAltitudeMode[];
|
|||
|
||||
extern const char * const lookupTableItermRelax[];
|
||||
|
||||
extern const char * const lookupTableItermRelaxType[];
|
||||
extern const char * const lookupTableItermRelaxType[];
|
||||
|
|
|
@ -50,6 +50,7 @@
|
|||
|
||||
#include "rx/rx.h"
|
||||
|
||||
|
||||
void dshotInitEndpoints(float outputLimit, float *outputLow, float *outputHigh, float *disarm, float *deadbandMotor3dHigh, float *deadbandMotor3dLow) {
|
||||
float outputLimitOffset = (DSHOT_MAX_THROTTLE - DSHOT_MIN_THROTTLE) * (1 - outputLimit);
|
||||
*disarm = DSHOT_CMD_MOTOR_STOP;
|
||||
|
@ -131,4 +132,37 @@ FAST_CODE uint16_t prepareDshotPacket(dshotProtocolControl_t *pcb)
|
|||
|
||||
return packet;
|
||||
}
|
||||
|
||||
#ifdef USE_DSHOT_TELEMETRY
|
||||
FAST_RAM_ZERO_INIT dshotTelemetryState_t dshotTelemetryState;
|
||||
|
||||
uint16_t getDshotTelemetry(uint8_t index)
|
||||
{
|
||||
return dshotTelemetryState.motorState[index].telemetryValue;
|
||||
}
|
||||
|
||||
#endif
|
||||
|
||||
#ifdef USE_DSHOT_TELEMETRY_STATS
|
||||
FAST_RAM_ZERO_INIT dshotTelemetryQuality_t dshotTelemetryQuality[MAX_SUPPORTED_MOTORS];
|
||||
|
||||
void updateDshotTelemetryQuality(dshotTelemetryQuality_t *qualityStats, bool packetValid, timeMs_t currentTimeMs)
|
||||
{
|
||||
uint8_t statsBucketIndex = (currentTimeMs / DSHOT_TELEMETRY_QUALITY_BUCKET_MS) % DSHOT_TELEMETRY_QUALITY_BUCKET_COUNT;
|
||||
if (statsBucketIndex != qualityStats->lastBucketIndex) {
|
||||
qualityStats->packetCountSum -= qualityStats->packetCountArray[statsBucketIndex];
|
||||
qualityStats->invalidCountSum -= qualityStats->invalidCountArray[statsBucketIndex];
|
||||
qualityStats->packetCountArray[statsBucketIndex] = 0;
|
||||
qualityStats->invalidCountArray[statsBucketIndex] = 0;
|
||||
qualityStats->lastBucketIndex = statsBucketIndex;
|
||||
}
|
||||
qualityStats->packetCountSum++;
|
||||
qualityStats->packetCountArray[statsBucketIndex]++;
|
||||
if (!packetValid) {
|
||||
qualityStats->invalidCountSum++;
|
||||
qualityStats->invalidCountArray[statsBucketIndex]++;
|
||||
}
|
||||
}
|
||||
#endif // USE_DSHOT_TELEMETRY_STATS
|
||||
|
||||
#endif // USE_DSHOT
|
||||
|
|
|
@ -20,10 +20,34 @@
|
|||
|
||||
#pragma once
|
||||
|
||||
#include "common/time.h"
|
||||
|
||||
#define DSHOT_MIN_THROTTLE 48
|
||||
#define DSHOT_MAX_THROTTLE 2047
|
||||
#define DSHOT_3D_FORWARD_MIN_THROTTLE 1048
|
||||
|
||||
#define MIN_GCR_EDGES 7
|
||||
#define MAX_GCR_EDGES 22
|
||||
|
||||
// comment out to see frame dump of corrupted frames in dshot_telemetry_info
|
||||
//#define DEBUG_BBDECODE
|
||||
|
||||
#ifdef USE_DSHOT_TELEMETRY_STATS
|
||||
#define DSHOT_TELEMETRY_QUALITY_WINDOW 1 // capture a rolling 1 second of packet stats
|
||||
#define DSHOT_TELEMETRY_QUALITY_BUCKET_MS 100 // determines the granularity of the stats and the overall number of rolling buckets
|
||||
#define DSHOT_TELEMETRY_QUALITY_BUCKET_COUNT (DSHOT_TELEMETRY_QUALITY_WINDOW * 1000 / DSHOT_TELEMETRY_QUALITY_BUCKET_MS)
|
||||
|
||||
typedef struct dshotTelemetryQuality_s {
|
||||
uint32_t packetCountSum;
|
||||
uint32_t invalidCountSum;
|
||||
uint32_t packetCountArray[DSHOT_TELEMETRY_QUALITY_BUCKET_COUNT];
|
||||
uint32_t invalidCountArray[DSHOT_TELEMETRY_QUALITY_BUCKET_COUNT];
|
||||
uint8_t lastBucketIndex;
|
||||
} dshotTelemetryQuality_t;
|
||||
|
||||
extern dshotTelemetryQuality_t dshotTelemetryQuality[MAX_SUPPORTED_MOTORS];
|
||||
#endif // USE_DSHOT_TELEMETRY_STATS
|
||||
|
||||
typedef struct dshotProtocolControl_s {
|
||||
uint16_t value;
|
||||
bool requestTelemetry;
|
||||
|
@ -37,7 +61,26 @@ FAST_CODE uint16_t prepareDshotPacket(dshotProtocolControl_t *pcb);
|
|||
|
||||
#ifdef USE_DSHOT_TELEMETRY
|
||||
extern bool useDshotTelemetry;
|
||||
extern uint32_t dshotInvalidPacketCount;
|
||||
|
||||
typedef struct dshotTelemetryMotorState_s {
|
||||
uint16_t telemetryValue;
|
||||
bool telemetryActive;
|
||||
} dshotTelemetryMotorState_t;
|
||||
|
||||
|
||||
typedef struct dshotTelemetryState_s {
|
||||
bool useDshotTelemetry;
|
||||
uint32_t invalidPacketCount;
|
||||
uint32_t readCount;
|
||||
dshotTelemetryMotorState_t motorState[MAX_SUPPORTED_MOTORS];
|
||||
uint32_t inputBuffer[MAX_GCR_EDGES];
|
||||
} dshotTelemetryState_t;
|
||||
|
||||
extern dshotTelemetryState_t dshotTelemetryState;
|
||||
|
||||
#ifdef USE_DSHOT_TELEMETRY_STATS
|
||||
void updateDshotTelemetryQuality(dshotTelemetryQuality_t *qualityStats, bool packetValid, timeMs_t currentTimeMs);
|
||||
#endif
|
||||
#endif
|
||||
|
||||
uint16_t getDshotTelemetry(uint8_t index);
|
||||
|
|
|
@ -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
|
|
@ -0,0 +1,41 @@
|
|||
/*
|
||||
* 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/>.
|
||||
*/
|
||||
|
||||
#pragma once
|
||||
|
||||
#include "drivers/timer.h"
|
||||
|
||||
typedef enum {
|
||||
DSHOT_BITBANG_OFF,
|
||||
DSHOT_BITBANG_ON,
|
||||
DSHOT_BITBANG_AUTO,
|
||||
} dshotBitbangMode_e;
|
||||
|
||||
typedef enum {
|
||||
DSHOT_BITBANG_OK,
|
||||
DSHOT_BITBANG_MOTOR_PIN_CONFLICT,
|
||||
DSHOT_BITBANG_NO_PACER
|
||||
} dshotBitbangStatus_e;
|
||||
|
||||
struct motorDevConfig_s;
|
||||
struct motorDevice_s;
|
||||
struct motorDevice_s *dshotBitbangDevInit(const struct motorDevConfig_s *motorConfig, uint8_t motorCount);
|
||||
dshotBitbangStatus_e dshotBitbangGetStatus();
|
||||
const timerHardware_t* dshotBitbangGetPacerTimer(int index);
|
|
@ -0,0 +1,290 @@
|
|||
#include <stdint.h>
|
||||
#include <string.h>
|
||||
#include <stdio.h>
|
||||
|
||||
#include "platform.h"
|
||||
|
||||
#if defined(USE_DSHOT_TELEMETRY)
|
||||
|
||||
#include "common/maths.h"
|
||||
#include "common/utils.h"
|
||||
#include "drivers/dshot.h"
|
||||
#include "drivers/dshot_bitbang_decode.h"
|
||||
|
||||
#define MIN_VALID_BBSAMPLES ((21 - 2) * 3)
|
||||
#define MAX_VALID_BBSAMPLES ((21 + 2) * 3)
|
||||
|
||||
// setting this define in dshot.h allows the cli command dshot_telemetry_info to
|
||||
// display the received telemetry data in raw form which helps identify
|
||||
// the root cause of packet decoding issues.
|
||||
|
||||
#ifdef DEBUG_BBDECODE
|
||||
uint16_t bbBuffer[134];
|
||||
#endif
|
||||
|
||||
|
||||
/* Bit band SRAM definitions */
|
||||
#define BITBAND_SRAM_REF 0x20000000
|
||||
#define BITBAND_SRAM_BASE 0x22000000
|
||||
#define BITBAND_SRAM(a,b) ((BITBAND_SRAM_BASE + (((a)-BITBAND_SRAM_REF)<<5) + ((b)<<2))) // Convert SRAM address
|
||||
|
||||
typedef struct bitBandWord_s {
|
||||
uint32_t value;
|
||||
uint32_t junk[15];
|
||||
} bitBandWord_t;
|
||||
|
||||
#ifdef DEBUG_BBDECODE
|
||||
uint32_t sequence[MAX_GCR_EDGES];
|
||||
int sequenceIndex = 0;
|
||||
#endif
|
||||
|
||||
|
||||
static uint32_t decode_bb_value(uint32_t value, uint16_t buffer[], uint32_t count, uint32_t bit)
|
||||
{
|
||||
#ifndef DEBUG_BBDECODE
|
||||
UNUSED(buffer);
|
||||
UNUSED(count);
|
||||
UNUSED(bit);
|
||||
#endif
|
||||
#define iv 0xffffffff
|
||||
// First bit is start bit so discard it.
|
||||
value &= 0xfffff;
|
||||
static const uint32_t decode[32] = {
|
||||
iv, iv, iv, iv, iv, iv, iv, iv, iv, 9, 10, 11, iv, 13, 14, 15,
|
||||
iv, iv, 2, 3, iv, 5, 6, 7, iv, 0, 8, 1, iv, 4, 12, iv };
|
||||
|
||||
uint32_t decodedValue = decode[value & 0x1f];
|
||||
decodedValue |= decode[(value >> 5) & 0x1f] << 4;
|
||||
decodedValue |= decode[(value >> 10) & 0x1f] << 8;
|
||||
decodedValue |= decode[(value >> 15) & 0x1f] << 12;
|
||||
|
||||
uint32_t csum = decodedValue;
|
||||
csum = csum ^ (csum >> 8); // xor bytes
|
||||
csum = csum ^ (csum >> 4); // xor nibbles
|
||||
|
||||
if ((csum & 0xf) != 0xf || decodedValue > 0xffff) {
|
||||
#ifdef DEBUG_BBDECODE
|
||||
memcpy(dshotTelemetryState.inputBuffer, sequence, sizeof(sequence));
|
||||
for (unsigned i = 0; i < count; i++) {
|
||||
bbBuffer[i] = !!(buffer[i] & (1 << bit));
|
||||
}
|
||||
#endif
|
||||
value = BB_INVALID;
|
||||
} else {
|
||||
value = decodedValue >> 4;
|
||||
|
||||
if (value == 0x0fff) {
|
||||
return 0;
|
||||
}
|
||||
// Convert value to 16 bit from the GCR telemetry format (eeem mmmm mmmm)
|
||||
value = (value & 0x000001ff) << ((value & 0xfffffe00) >> 9);
|
||||
if (!value) {
|
||||
return BB_INVALID;
|
||||
}
|
||||
// Convert period to erpm * 100
|
||||
value = (1000000 * 60 / 100 + value / 2) / value;
|
||||
}
|
||||
return value;
|
||||
}
|
||||
|
||||
|
||||
uint32_t decode_bb_bitband( uint16_t buffer[], uint32_t count, uint32_t bit)
|
||||
{
|
||||
#ifdef DEBUG_BBDECODE
|
||||
memset(sequence, 0, sizeof(sequence));
|
||||
sequenceIndex = 0;
|
||||
#endif
|
||||
uint32_t value = 0;
|
||||
|
||||
bitBandWord_t* p = (bitBandWord_t*)BITBAND_SRAM((uint32_t)buffer, bit);
|
||||
bitBandWord_t* b = p;
|
||||
bitBandWord_t* endP = p + (count - MIN_VALID_BBSAMPLES);
|
||||
|
||||
// Eliminate leading high signal level by looking for first zero bit in data stream.
|
||||
// Manual loop unrolling and branch hinting to produce faster code.
|
||||
while (p < endP) {
|
||||
if (__builtin_expect((!(p++)->value), 0) ||
|
||||
__builtin_expect((!(p++)->value), 0) ||
|
||||
__builtin_expect((!(p++)->value), 0) ||
|
||||
__builtin_expect((!(p++)->value), 0)) {
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
if (p >= endP) {
|
||||
// not returning telemetry is ok if the esc cpu is
|
||||
// overburdened. in that case no edge will be found and
|
||||
// BB_NOEDGE indicates the condition to caller
|
||||
return BB_NOEDGE;
|
||||
}
|
||||
|
||||
int remaining = MIN(count - (p - b), (unsigned int)MAX_VALID_BBSAMPLES);
|
||||
|
||||
bitBandWord_t* oldP = p;
|
||||
uint32_t bits = 0;
|
||||
endP = p + remaining;
|
||||
|
||||
#ifdef DEBUG_BBDECODE
|
||||
sequence[sequenceIndex++] = p - b;
|
||||
#endif
|
||||
|
||||
while (endP > p) {
|
||||
while (endP > p) {
|
||||
// Look for next positive edge. Manual loop unrolling and branch hinting to produce faster code.
|
||||
if(__builtin_expect(!(p++)->value, 1) &&
|
||||
__builtin_expect(!(p++)->value, 1) &&
|
||||
__builtin_expect(!(p++)->value, 1) &&
|
||||
__builtin_expect(!(p++)->value, 1)) {
|
||||
continue;
|
||||
}
|
||||
|
||||
#ifdef DEBUG_BBDECODE
|
||||
sequence[sequenceIndex++] = p - b;
|
||||
#endif
|
||||
// A level of length n gets decoded to a sequence of bits of
|
||||
// the form 1000 with a length of (n+1) / 3 to account for 3x
|
||||
// oversampling.
|
||||
const int len = MAX((p - oldP + 1) / 3, 1);
|
||||
bits += len;
|
||||
value <<= len;
|
||||
value |= 1 << (len - 1);
|
||||
oldP = p;
|
||||
break;
|
||||
}
|
||||
|
||||
// Look for next zero edge. Manual loop unrolling and branch hinting to produce faster code.
|
||||
while (endP > p) {
|
||||
if (__builtin_expect((p++)->value, 1) &&
|
||||
__builtin_expect((p++)->value, 1) &&
|
||||
__builtin_expect((p++)->value, 1) &&
|
||||
__builtin_expect((p++)->value, 1)) {
|
||||
continue;
|
||||
}
|
||||
#ifdef DEBUG_BBDECODE
|
||||
sequence[sequenceIndex++] = p - b;
|
||||
#endif
|
||||
// A level of length n gets decoded to a sequence of bits of
|
||||
// the form 1000 with a length of (n+1) / 3 to account for 3x
|
||||
// oversampling.
|
||||
const int len = MAX((p - oldP + 1) / 3, 1);
|
||||
bits += len;
|
||||
value <<= len;
|
||||
value |= 1 << (len - 1);
|
||||
oldP = p;
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
if (bits < 18) {
|
||||
return BB_NOEDGE;
|
||||
}
|
||||
|
||||
// length of last sequence has to be inferred since the last bit with inverted dshot is high
|
||||
const int nlen = 21 - bits;
|
||||
if (nlen < 0) {
|
||||
value = BB_INVALID;
|
||||
}
|
||||
|
||||
#ifdef DEBUG_BBDECODE
|
||||
sequence[sequenceIndex] = sequence[sequenceIndex] + (nlen) * 3;
|
||||
sequenceIndex++;
|
||||
#endif
|
||||
if (nlen > 0) {
|
||||
value <<= nlen;
|
||||
value |= 1 << (nlen - 1);
|
||||
}
|
||||
return decode_bb_value(value, buffer, count, bit);
|
||||
}
|
||||
|
||||
FAST_CODE uint32_t decode_bb( uint16_t buffer[], uint32_t count, uint32_t bit)
|
||||
{
|
||||
#ifdef DEBUG_BBDECODE
|
||||
memset(sequence, 0, sizeof(sequence));
|
||||
sequenceIndex = 0;
|
||||
#endif
|
||||
uint32_t mask = 1 << bit;
|
||||
|
||||
#ifdef DEBUG_BBDECODE
|
||||
uint32_t sequence[MAX_GCR_EDGES];
|
||||
memset(sequence, 0, sizeof(sequence));
|
||||
int sequenceIndex = 0;
|
||||
#endif
|
||||
|
||||
uint16_t lastValue = 0;
|
||||
uint32_t value = 0;
|
||||
|
||||
uint16_t* p = buffer;
|
||||
uint16_t* endP = p + count - MIN_VALID_BBSAMPLES;
|
||||
// Eliminate leading high signal level by looking for first zero bit in data stream.
|
||||
// Manual loop unrolling and branch hinting to produce faster code.
|
||||
while (p < endP) {
|
||||
if (__builtin_expect(!(*p++ & mask), 0) ||
|
||||
__builtin_expect(!(*p++ & mask), 0) ||
|
||||
__builtin_expect(!(*p++ & mask), 0) ||
|
||||
__builtin_expect(!(*p++ & mask), 0)) {
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
if(*p & mask) {
|
||||
// not returning telemetry is ok if the esc cpu is
|
||||
// overburdened. in that case no edge will be found and
|
||||
// BB_NOEDGE indicates the condition to caller
|
||||
return BB_NOEDGE;
|
||||
}
|
||||
|
||||
int remaining = MIN(count - (p - buffer), (unsigned int)MAX_VALID_BBSAMPLES);
|
||||
|
||||
uint16_t* oldP = p;
|
||||
uint32_t bits = 0;
|
||||
endP = p + remaining;
|
||||
|
||||
#ifdef DEBUG_BBDECODE
|
||||
sequence[sequenceIndex++] = p - buffer;
|
||||
#endif
|
||||
|
||||
// Look for next edge. Manual loop unrolling and branch hinting to produce faster code.
|
||||
while (endP > p) {
|
||||
if (__builtin_expect((*p++ & mask) == lastValue, 1) &&
|
||||
__builtin_expect((*p++ & mask) == lastValue, 1) &&
|
||||
__builtin_expect((*p++ & mask) == lastValue, 1) &&
|
||||
__builtin_expect((*p++ & mask) == lastValue, 1)) {
|
||||
continue;
|
||||
}
|
||||
|
||||
#ifdef DEBUG_BBDECODE
|
||||
sequence[sequenceIndex++] = p - buffer;
|
||||
#endif
|
||||
// A level of length n gets decoded to a sequence of bits of
|
||||
// the form 1000 with a length of (n+1) / 3 to account for 3x
|
||||
// oversampling.
|
||||
const int len = MAX((p - oldP + 1) / 3,1);
|
||||
bits += len;
|
||||
value <<= len;
|
||||
value |= 1 << (len - 1);
|
||||
oldP = p;
|
||||
lastValue = *(p-1) & mask;
|
||||
}
|
||||
|
||||
// length of last sequence has to be inferred since the last bit with inverted dshot is high
|
||||
if (bits < 18) {
|
||||
return BB_NOEDGE;
|
||||
}
|
||||
|
||||
const int nlen = 21 - bits;
|
||||
#ifdef DEBUG_BBDECODE
|
||||
sequence[sequenceIndex] = sequence[sequenceIndex] + (nlen) * 3;
|
||||
sequenceIndex++;
|
||||
#endif
|
||||
|
||||
if (nlen < 0) {
|
||||
value = BB_INVALID;
|
||||
}
|
||||
if (nlen > 0) {
|
||||
value <<= nlen;
|
||||
value |= 1 << (nlen - 1);
|
||||
}
|
||||
return decode_bb_value(value, buffer, count, bit);
|
||||
}
|
||||
|
||||
#endif
|
|
@ -0,0 +1,29 @@
|
|||
/*
|
||||
* 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/>.
|
||||
*/
|
||||
|
||||
#if defined(USE_DSHOT) && defined(USE_DSHOT_TELEMETRY)
|
||||
|
||||
#define BB_NOEDGE 0xfffe
|
||||
#define BB_INVALID 0xffff
|
||||
|
||||
uint32_t decode_bb(uint16_t buffer[], uint32_t count, uint32_t mask);
|
||||
uint32_t decode_bb_bitband( uint16_t buffer[], uint32_t count, uint32_t bit);
|
||||
|
||||
#endif
|
|
@ -0,0 +1,217 @@
|
|||
/*
|
||||
* 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/>.
|
||||
*/
|
||||
|
||||
#pragma once
|
||||
|
||||
#include "common/time.h"
|
||||
#include "drivers/motor.h"
|
||||
|
||||
#define USE_DMA_REGISTER_CACHE
|
||||
|
||||
#define DEBUG_COUNT_INTERRUPT
|
||||
#define DEBUG_MONITOR_PACER
|
||||
|
||||
#define MAX_SUPPORTED_MOTOR_PORTS 4 // Max direct dshot port groups, limited by number of usable timer (TIM1 and TIM8) x number of channels per timer (4), 3 is enough to cover motor pins on GPIOA, GPIOB and GPIOC.
|
||||
|
||||
#define DSHOT_BITBANG_TELEMETRY_OVER_SAMPLE 3
|
||||
|
||||
#define DSHOT_BITBANG_DIRECTION_OUTPUT 0
|
||||
#define DSHOT_BITBANG_DIRECTION_INPUT 1
|
||||
|
||||
#define DSHOT_BITBANG_INVERTED true
|
||||
#define DSHOT_BITBANG_NONINVERTED false
|
||||
|
||||
// XXX MOTOR_xSHOTyyyy_HZ is not usable as generic frequency for timers.
|
||||
// XXX Trying to fiddle with constants here.
|
||||
|
||||
// Symbol rate [symbol/sec]
|
||||
#define MOTOR_DSHOT1200_SYMBOL_RATE (1200 * 1000)
|
||||
#define MOTOR_DSHOT600_SYMBOL_RATE (600 * 1000)
|
||||
#define MOTOR_DSHOT300_SYMBOL_RATE (300 * 1000)
|
||||
#define MOTOR_DSHOT150_SYMBOL_RATE (150 * 1000)
|
||||
|
||||
#define MOTOR_DSHOT_SYMBOL_TIME_NS(rate) (1000000000 / (rate))
|
||||
|
||||
#define MOTOR_DSHOT_BIT_PER_SYMBOL 1
|
||||
|
||||
#define MOTOR_DSHOT_STATE_PER_SYMBOL 3 // Initial high, 0/1, low
|
||||
|
||||
#define MOTOR_DSHOT_FRAME_BITS 16
|
||||
|
||||
#define MOTOR_DSHOT_FRAME_TIME_NS(rate) ((MOTOR_DSHOT_FRAME_BITS / MOTOR_DSHOT_BIT_PER_SYMBOL) * MOTOR_DSHOT_SYMBOL_TIME_NS(rate))
|
||||
|
||||
#define MOTOR_DSHOT_TELEMETRY_WINDOW_US (30000 + MOTOR_DSHOT_FRAME_TIME_NS(rate) * (1.1)) / 1000
|
||||
|
||||
#define MOTOR_DSHOT_CHANGE_INTERVAL_NS(rate) (MOTOR_DSHOT_SYMBOL_TIME_NS(rate) / MOTOR_DSHOT_STATE_PER_SYMBOL)
|
||||
|
||||
#define MOTOR_DSHOT_GCR_CHANGE_INTERVAL_NS(rate) (MOTOR_DSHOT_CHANGE_INTERVAL_NS(rate) * 5 / 4)
|
||||
|
||||
#define MOTOR_DSHOT_BUFFER_SIZE ((MOTOR_DSHOT_FRAME_BITS / MOTOR_DSHOT_BIT_PER_SYMBOL) * MOTOR_DSHOT_STATE_PER_SYMBOL)
|
||||
|
||||
#ifdef USE_HAL_DRIVER
|
||||
#define BB_GPIO_PULLDOWN GPIO_PULLDOWN
|
||||
#define BB_GPIO_PULLUP GPIO_PULLUP
|
||||
#else
|
||||
#define BB_GPIO_PULLDOWN GPIO_PuPd_DOWN
|
||||
#define BB_GPIO_PULLUP GPIO_PuPd_UP
|
||||
#endif
|
||||
|
||||
#ifdef USE_DMA_REGISTER_CACHE
|
||||
typedef struct dmaRegCache_s {
|
||||
#if defined(STM32F4) || defined(STM32F7)
|
||||
uint32_t CR;
|
||||
uint32_t FCR;
|
||||
uint32_t NDTR;
|
||||
uint32_t PAR;
|
||||
uint32_t M0AR;
|
||||
#else
|
||||
#error No MCU dependent code here
|
||||
#endif
|
||||
} dmaRegCache_t;
|
||||
#endif
|
||||
|
||||
// Per pacer timer
|
||||
|
||||
typedef struct bbPacer_s {
|
||||
TIM_TypeDef *tim;
|
||||
uint16_t dmaSources;
|
||||
} bbPacer_t;
|
||||
|
||||
// Per GPIO port and timer channel
|
||||
|
||||
typedef struct bbPort_s {
|
||||
int portIndex;
|
||||
GPIO_TypeDef *gpio;
|
||||
const timerHardware_t *timhw;
|
||||
#ifdef USE_HAL_DRIVER
|
||||
uint32_t llChannel;
|
||||
#endif
|
||||
|
||||
uint16_t dmaSource;
|
||||
|
||||
dmaResource_t *dmaResource; // DMA resource for this port & timer channel
|
||||
uint32_t dmaChannel; // DMA channel or peripheral request
|
||||
|
||||
uint8_t direction;
|
||||
|
||||
#ifdef USE_DMA_REGISTER_CACHE
|
||||
// DMA resource register cache
|
||||
dmaRegCache_t dmaRegOutput;
|
||||
dmaRegCache_t dmaRegInput;
|
||||
#endif
|
||||
|
||||
// For direct manipulation of GPIO_MODER register
|
||||
uint32_t gpioModeMask;
|
||||
uint32_t gpioModeInput;
|
||||
uint32_t gpioModeOutput;
|
||||
|
||||
// Idle value
|
||||
uint32_t gpioIdleBSRR;
|
||||
|
||||
#ifdef USE_HAL_DRIVER
|
||||
LL_TIM_InitTypeDef timeBaseInit;
|
||||
#else
|
||||
TIM_TimeBaseInitTypeDef timeBaseInit;
|
||||
#endif
|
||||
|
||||
// Output
|
||||
uint16_t outputARR;
|
||||
#ifdef USE_HAL_DRIVER
|
||||
LL_DMA_InitTypeDef outputDmaInit;
|
||||
#else
|
||||
DMA_InitTypeDef outputDmaInit;
|
||||
#endif
|
||||
uint32_t *portOutputBuffer;
|
||||
uint32_t portOutputCount;
|
||||
|
||||
// Input
|
||||
uint16_t inputARR;
|
||||
#ifdef USE_HAL_DRIVER
|
||||
LL_DMA_InitTypeDef inputDmaInit;
|
||||
#else
|
||||
DMA_InitTypeDef inputDmaInit;
|
||||
#endif
|
||||
uint16_t *portInputBuffer;
|
||||
uint32_t portInputCount;
|
||||
bool inputActive;
|
||||
|
||||
// Misc
|
||||
#ifdef DEBUG_COUNT_INTERRUPT
|
||||
uint32_t outputIrq;
|
||||
uint32_t inputIrq;
|
||||
#endif
|
||||
} bbPort_t;
|
||||
|
||||
// Per motor output
|
||||
|
||||
typedef struct bbMotor_s {
|
||||
dshotProtocolControl_t protocolControl;
|
||||
int pinIndex; // pinIndex of this motor output within a group that bbPort points to
|
||||
int portIndex;
|
||||
IO_t io; // IO_t for this output
|
||||
uint8_t output;
|
||||
uint32_t iocfg;
|
||||
bbPort_t *bbPort;
|
||||
bool configured;
|
||||
bool enabled;
|
||||
} bbMotor_t;
|
||||
|
||||
#define MAX_MOTOR_PACERS 4
|
||||
extern FAST_RAM_ZERO_INIT bbPacer_t bbPacers[MAX_MOTOR_PACERS]; // TIM1 or TIM8
|
||||
extern FAST_RAM_ZERO_INIT int usedMotorPacers;
|
||||
|
||||
extern FAST_RAM_ZERO_INIT bbPort_t bbPorts[MAX_SUPPORTED_MOTOR_PORTS];
|
||||
extern FAST_RAM_ZERO_INIT int usedMotorPorts;
|
||||
|
||||
extern FAST_RAM_ZERO_INIT bbMotor_t bbMotors[MAX_SUPPORTED_MOTORS];
|
||||
|
||||
extern uint8_t bbPuPdMode;
|
||||
|
||||
// DMA buffers
|
||||
// Note that we are not sharing input and output buffers,
|
||||
// as output buffer is only modified for middle bits
|
||||
|
||||
// DMA output buffer:
|
||||
// DShot requires 3 [word/bit] * 16 [bit] = 48 [word]
|
||||
extern uint32_t bbOutputBuffer[MOTOR_DSHOT_BUFFER_SIZE * MAX_SUPPORTED_MOTOR_PORTS];
|
||||
|
||||
// DMA input buffer
|
||||
// (30us + <frame time> + <slack>) / <input sampling clock perid>
|
||||
// <frame time> = <DShot symbol time> * 16
|
||||
// Temporary size for DS600
|
||||
// <frame time> = 26us
|
||||
// <sampling period> = 0.44us
|
||||
// <slack> = 10%
|
||||
// (30 + 26 + 3) / 0.44 = 134
|
||||
#define DSHOT_BITBANG_PORT_INPUT_BUFFER_LENGTH 134
|
||||
extern uint16_t bbInputBuffer[DSHOT_BITBANG_PORT_INPUT_BUFFER_LENGTH * MAX_SUPPORTED_MOTOR_PORTS];
|
||||
|
||||
void bbGpioSetup(bbMotor_t *bbMotor);
|
||||
void bbTimerChannelInit(bbPort_t *bbPort);
|
||||
void bbDMAPreconfigure(bbPort_t *bbPort, uint8_t direction);
|
||||
void bbDMAIrqHandler(dmaChannelDescriptor_t *descriptor);
|
||||
void bbSwitchToOutput(bbPort_t * bbPort);
|
||||
void bbSwitchToInput(bbPort_t * bbPort);
|
||||
|
||||
void bbTIM_TimeBaseInit(bbPort_t *bbPort, uint16_t period);
|
||||
void bbTIM_DMACmd(TIM_TypeDef* TIMx, uint16_t TIM_DMASource, FunctionalState NewState);
|
||||
void bbDMA_ITConfig(bbPort_t *bbPort);
|
||||
void bbDMA_Cmd(bbPort_t *bbPort, FunctionalState NewState);
|
||||
int bbDMA_Count(bbPort_t *bbPort);
|
|
@ -0,0 +1,314 @@
|
|||
/*
|
||||
* 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/atomic.h"
|
||||
#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_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/time.h"
|
||||
#include "drivers/timer.h"
|
||||
|
||||
#include "pg/motor.h"
|
||||
|
||||
// Setup GPIO_MODER and GPIO_ODR register manipulation values
|
||||
|
||||
void bbGpioSetup(bbMotor_t *bbMotor)
|
||||
{
|
||||
bbPort_t *bbPort = bbMotor->bbPort;
|
||||
int pinIndex = bbMotor->pinIndex;
|
||||
|
||||
bbPort->gpioModeMask |= (GPIO_MODER_MODER0 << (pinIndex * 2));
|
||||
bbPort->gpioModeInput |= (LL_GPIO_MODE_INPUT << (pinIndex * 2));
|
||||
bbPort->gpioModeOutput |= (LL_GPIO_MODE_OUTPUT << (pinIndex * 2));
|
||||
|
||||
#ifdef USE_DSHOT_TELEMETRY
|
||||
if (useDshotTelemetry) {
|
||||
bbPort->gpioIdleBSRR |= (1 << pinIndex); // BS (lower half)
|
||||
} else
|
||||
#endif
|
||||
{
|
||||
bbPort->gpioIdleBSRR |= (1 << (pinIndex + 16)); // BR (higher half)
|
||||
}
|
||||
|
||||
#ifdef USE_DSHOT_TELEMETRY
|
||||
if (useDshotTelemetry) {
|
||||
IOWrite(bbMotor->io, 1);
|
||||
} else
|
||||
#endif
|
||||
{
|
||||
IOWrite(bbMotor->io, 0);
|
||||
}
|
||||
|
||||
#if defined(STM32F7)
|
||||
IOConfigGPIO(bbMotor->io, IO_CONFIG(GPIO_MODE_OUTPUT_PP, GPIO_SPEED_FREQ_HIGH, bbPuPdMode));
|
||||
#else
|
||||
#error MCU dependent code required
|
||||
#endif
|
||||
}
|
||||
|
||||
void bbTimerChannelInit(bbPort_t *bbPort)
|
||||
{
|
||||
const timerHardware_t *timhw = bbPort->timhw;
|
||||
|
||||
switch (bbPort->timhw->channel) {
|
||||
case TIM_CHANNEL_1: bbPort->llChannel = LL_TIM_CHANNEL_CH1; break;
|
||||
case TIM_CHANNEL_2: bbPort->llChannel = LL_TIM_CHANNEL_CH2; break;
|
||||
case TIM_CHANNEL_3: bbPort->llChannel = LL_TIM_CHANNEL_CH3; break;
|
||||
case TIM_CHANNEL_4: bbPort->llChannel = LL_TIM_CHANNEL_CH4; break;
|
||||
}
|
||||
|
||||
LL_TIM_OC_InitTypeDef ocInit;
|
||||
LL_TIM_OC_StructInit(&ocInit);
|
||||
ocInit.OCMode = LL_TIM_OCMODE_PWM1;
|
||||
ocInit.OCIdleState = LL_TIM_OCIDLESTATE_HIGH;
|
||||
ocInit.OCState = LL_TIM_OCSTATE_ENABLE;
|
||||
ocInit.OCPolarity = LL_TIM_OCPOLARITY_LOW;
|
||||
ocInit.CompareValue = 10; // Duty doesn't matter, but too value small would make monitor output invalid
|
||||
|
||||
//TIM_Cmd(bbPort->timhw->tim, DISABLE);
|
||||
LL_TIM_DisableCounter(bbPort->timhw->tim);
|
||||
|
||||
//timerOCInit(timhw->tim, timhw->channel, &TIM_OCStruct);
|
||||
LL_TIM_OC_Init(timhw->tim, bbPort->llChannel, &ocInit);
|
||||
|
||||
//timerOCPreloadConfig(timhw->tim, timhw->channel, TIM_OCPreload_Enable);
|
||||
LL_TIM_OC_EnablePreload(timhw->tim, bbPort->llChannel);
|
||||
|
||||
#ifdef DEBUG_MONITOR_PACER
|
||||
if (timhw->tag) {
|
||||
IO_t io = IOGetByTag(timhw->tag);
|
||||
IOConfigGPIOAF(io, IOCFG_AF_PP, timhw->alternateFunction);
|
||||
IOInit(io, OWNER_DSHOT_BITBANG, 0);
|
||||
//TIM_CtrlPWMOutputs(timhw->tim, ENABLE);
|
||||
LL_TIM_EnableAllOutputs(timhw->tim);
|
||||
}
|
||||
#endif
|
||||
|
||||
// Enable and keep it running
|
||||
|
||||
//TIM_Cmd(bbPort->timhw->tim, ENABLE);
|
||||
LL_TIM_EnableCounter(bbPort->timhw->tim);
|
||||
}
|
||||
|
||||
#ifdef USE_DMA_REGISTER_CACHE
|
||||
void bbLoadDMARegs(dmaResource_t *dmaResource, dmaRegCache_t *dmaRegCache)
|
||||
{
|
||||
((DMA_ARCH_TYPE *)dmaResource)->CR = dmaRegCache->CR;
|
||||
((DMA_ARCH_TYPE *)dmaResource)->FCR = dmaRegCache->FCR;
|
||||
((DMA_ARCH_TYPE *)dmaResource)->NDTR = dmaRegCache->NDTR;
|
||||
((DMA_ARCH_TYPE *)dmaResource)->PAR = dmaRegCache->PAR;
|
||||
((DMA_ARCH_TYPE *)dmaResource)->M0AR = dmaRegCache->M0AR;
|
||||
}
|
||||
|
||||
static void bbSaveDMARegs(dmaResource_t *dmaResource, dmaRegCache_t *dmaRegCache)
|
||||
{
|
||||
dmaRegCache->CR = ((DMA_ARCH_TYPE *)dmaResource)->CR;
|
||||
dmaRegCache->FCR = ((DMA_ARCH_TYPE *)dmaResource)->FCR;
|
||||
dmaRegCache->NDTR = ((DMA_ARCH_TYPE *)dmaResource)->NDTR;
|
||||
dmaRegCache->PAR = ((DMA_ARCH_TYPE *)dmaResource)->PAR;
|
||||
dmaRegCache->M0AR = ((DMA_ARCH_TYPE *)dmaResource)->M0AR;
|
||||
}
|
||||
#endif
|
||||
|
||||
void bbSwitchToOutput(bbPort_t * bbPort)
|
||||
{
|
||||
// Output idle level before switching to output
|
||||
// Use BSRR register for this
|
||||
// Normal: Use BR (higher half)
|
||||
// Inverted: Use BS (lower half)
|
||||
|
||||
WRITE_REG(bbPort->gpio->BSRR, bbPort->gpioIdleBSRR);
|
||||
|
||||
// Set GPIO to output
|
||||
|
||||
ATOMIC_BLOCK(NVIC_PRIO_TIMER) {
|
||||
MODIFY_REG(bbPort->gpio->MODER, bbPort->gpioModeMask, bbPort->gpioModeOutput);
|
||||
}
|
||||
|
||||
// Reinitialize port group DMA for output
|
||||
|
||||
dmaResource_t *dmaResource = bbPort->dmaResource;
|
||||
#ifdef USE_DMA_REGISTER_CACHE
|
||||
bbDMA_Cmd(bbPort, DISABLE);
|
||||
bbLoadDMARegs(dmaResource, &bbPort->dmaRegOutput);
|
||||
#else
|
||||
//xDMA_DeInit(dmaResource);
|
||||
xLL_EX_DMA_Deinit(dmaResource);
|
||||
//xDMA_Init(dmaResource, &bbPort->outputDmaInit);
|
||||
xLL_EX_DMA_Init(dmaResource, &bbPort->outputDmaInit);
|
||||
// Needs this, as it is DeInit'ed above...
|
||||
//xDMA_ITConfig(dmaResource, DMA_IT_TC, ENABLE);
|
||||
xLL_EX_DMA_EnableIT_TC(dmaResource);
|
||||
#endif
|
||||
|
||||
// Reinitialize pacer timer for output
|
||||
|
||||
bbPort->timhw->tim->ARR = bbPort->outputARR;
|
||||
|
||||
bbPort->direction = DSHOT_BITBANG_DIRECTION_OUTPUT;
|
||||
}
|
||||
|
||||
#ifdef USE_DSHOT_TELEMETRY
|
||||
void bbSwitchToInput(bbPort_t *bbPort)
|
||||
{
|
||||
// Set GPIO to input
|
||||
|
||||
ATOMIC_BLOCK(NVIC_PRIO_TIMER) {
|
||||
MODIFY_REG(bbPort->gpio->MODER, bbPort->gpioModeMask, bbPort->gpioModeInput);
|
||||
}
|
||||
|
||||
// Reinitialize port group DMA for input
|
||||
|
||||
dmaResource_t *dmaResource = bbPort->dmaResource;
|
||||
#ifdef USE_DMA_REGISTER_CACHE
|
||||
bbLoadDMARegs(dmaResource, &bbPort->dmaRegInput);
|
||||
#else
|
||||
//xDMA_DeInit(dmaResource);
|
||||
xLL_EX_DMA_Deinit(dmaResource);
|
||||
//xDMA_Init(dmaResource, &bbPort->inputDmaInit);
|
||||
xLL_EX_DMA_Init(dmaResource, &bbPort->inputDmaInit);
|
||||
|
||||
// Needs this, as it is DeInit'ed above...
|
||||
//xDMA_ITConfig(dmaResource, DMA_IT_TC, ENABLE);
|
||||
xLL_EX_DMA_EnableIT_TC(dmaResource);
|
||||
#endif
|
||||
|
||||
// Reinitialize pacer timer for input
|
||||
|
||||
bbPort->timhw->tim->ARR = bbPort->inputARR;
|
||||
|
||||
bbDMA_Cmd(bbPort, ENABLE);
|
||||
|
||||
bbPort->direction = DSHOT_BITBANG_DIRECTION_INPUT;
|
||||
}
|
||||
#endif
|
||||
|
||||
void bbDMAPreconfigure(bbPort_t *bbPort, uint8_t direction)
|
||||
{
|
||||
LL_DMA_InitTypeDef *dmainit = (direction == DSHOT_BITBANG_DIRECTION_OUTPUT) ? &bbPort->outputDmaInit : &bbPort->inputDmaInit;
|
||||
|
||||
LL_DMA_StructInit(dmainit);
|
||||
|
||||
dmainit->Mode = LL_DMA_MODE_NORMAL;
|
||||
dmainit->Channel = bbPort->dmaChannel;
|
||||
dmainit->PeriphOrM2MSrcIncMode = LL_DMA_PERIPH_NOINCREMENT;
|
||||
dmainit->MemoryOrM2MDstIncMode = LL_DMA_MEMORY_INCREMENT;
|
||||
dmainit->FIFOMode = LL_DMA_FIFOMODE_ENABLE ;
|
||||
#if 0
|
||||
dmainit->DMA_FIFOThreshold = DMA_FIFOThreshold_1QuarterFull ;
|
||||
dmainit->DMA_MemoryBurst = DMA_MemoryBurst_Single ;
|
||||
dmainit->DMA_PeripheralBurst = DMA_PeripheralBurst_Single;
|
||||
#endif
|
||||
|
||||
if (direction == DSHOT_BITBANG_DIRECTION_OUTPUT) {
|
||||
dmainit->Priority = LL_DMA_PRIORITY_VERYHIGH;
|
||||
dmainit->Direction = LL_DMA_DIRECTION_MEMORY_TO_PERIPH;
|
||||
dmainit->NbData = bbPort->portOutputCount;
|
||||
dmainit->PeriphOrM2MSrcAddress = (uint32_t)&bbPort->gpio->BSRR;
|
||||
dmainit->PeriphOrM2MSrcDataSize = LL_DMA_PDATAALIGN_WORD;
|
||||
dmainit->MemoryOrM2MDstAddress = (uint32_t)bbPort->portOutputBuffer;
|
||||
dmainit->MemoryOrM2MDstDataSize = LL_DMA_MDATAALIGN_WORD;
|
||||
|
||||
#ifdef USE_DMA_REGISTER_CACHE
|
||||
xLL_EX_DMA_Init(bbPort->dmaResource, dmainit);
|
||||
bbSaveDMARegs(bbPort->dmaResource, &bbPort->dmaRegOutput);
|
||||
#endif
|
||||
} else {
|
||||
dmainit->Priority = LL_DMA_PRIORITY_HIGH;
|
||||
dmainit->Direction = LL_DMA_DIRECTION_PERIPH_TO_MEMORY;
|
||||
dmainit->NbData = bbPort->portInputCount;
|
||||
|
||||
dmainit->PeriphOrM2MSrcAddress = (uint32_t)&bbPort->gpio->IDR;
|
||||
dmainit->PeriphOrM2MSrcDataSize = LL_DMA_PDATAALIGN_HALFWORD;
|
||||
dmainit->MemoryOrM2MDstAddress = (uint32_t)bbPort->portInputBuffer;
|
||||
dmainit->MemoryOrM2MDstDataSize = LL_DMA_MDATAALIGN_WORD;
|
||||
|
||||
#ifdef USE_DMA_REGISTER_CACHE
|
||||
xLL_EX_DMA_Init(bbPort->dmaResource, dmainit);
|
||||
bbSaveDMARegs(bbPort->dmaResource, &bbPort->dmaRegInput);
|
||||
#endif
|
||||
}
|
||||
}
|
||||
|
||||
void bbTIM_TimeBaseInit(bbPort_t *bbPort, uint16_t period)
|
||||
{
|
||||
LL_TIM_InitTypeDef *init = &bbPort->timeBaseInit;
|
||||
|
||||
init->Prescaler = 0; // Feed raw timerClock
|
||||
init->ClockDivision = LL_TIM_CLOCKDIVISION_DIV1;
|
||||
init->CounterMode = LL_TIM_COUNTERMODE_UP;
|
||||
init->Autoreload = period;
|
||||
//TIM_TimeBaseInit(bbPort->timhw->tim, &bbPort->timeBaseInit);
|
||||
LL_TIM_Init(bbPort->timhw->tim, init);
|
||||
MODIFY_REG(bbPort->timhw->tim->CR1, TIM_CR1_ARPE, TIM_AUTORELOAD_PRELOAD_ENABLE);
|
||||
}
|
||||
|
||||
void bbTIM_DMACmd(TIM_TypeDef* TIMx, uint16_t TIM_DMASource, FunctionalState NewState)
|
||||
{
|
||||
//TIM_DMACmd(TIMx, TIM_DMASource, NewState);
|
||||
if (NewState == ENABLE) {
|
||||
SET_BIT(TIMx->DIER, TIM_DMASource);
|
||||
} else {
|
||||
CLEAR_BIT(TIMx->DIER, TIM_DMASource);
|
||||
}
|
||||
}
|
||||
|
||||
void bbDMA_ITConfig(bbPort_t *bbPort)
|
||||
{
|
||||
//xDMA_ITConfig(bbPort->dmaResource, DMA_IT_TC, ENABLE);
|
||||
|
||||
xLL_EX_DMA_EnableIT_TC(bbPort->dmaResource);
|
||||
|
||||
SET_BIT(((DMA_Stream_TypeDef *)(bbPort->dmaResource))->CR, DMA_SxCR_TCIE|DMA_SxCR_TEIE);
|
||||
}
|
||||
|
||||
void bbDMA_Cmd(bbPort_t *bbPort, FunctionalState NewState)
|
||||
{
|
||||
//xDMA_Cmd(bbPort->dmaResource, NewState);
|
||||
|
||||
if (NewState == ENABLE) {
|
||||
xLL_EX_DMA_EnableResource(bbPort->dmaResource);
|
||||
} else {
|
||||
xLL_EX_DMA_DisableResource(bbPort->dmaResource);
|
||||
}
|
||||
}
|
||||
|
||||
int bbDMA_Count(bbPort_t *bbPort)
|
||||
{
|
||||
return xLL_EX_DMA_GetDataLength(bbPort->dmaResource);
|
||||
}
|
||||
#endif // USE_DSHOT_BITBANG
|
|
@ -0,0 +1,290 @@
|
|||
/*
|
||||
* 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/atomic.h"
|
||||
#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_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/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)
|
||||
|
||||
void bbGpioSetup(bbMotor_t *bbMotor)
|
||||
{
|
||||
bbPort_t *bbPort = bbMotor->bbPort;
|
||||
int pinIndex = bbMotor->pinIndex;
|
||||
|
||||
bbPort->gpioModeMask |= (GPIO_MODER_MODER0 << (pinIndex * 2));
|
||||
bbPort->gpioModeInput |= (GPIO_Mode_IN << (pinIndex * 2));
|
||||
bbPort->gpioModeOutput |= (GPIO_Mode_OUT << (pinIndex * 2));
|
||||
|
||||
#ifdef USE_DSHOT_TELEMETRY
|
||||
if (useDshotTelemetry) {
|
||||
bbPort->gpioIdleBSRR |= (1 << pinIndex); // BS (lower half)
|
||||
} else
|
||||
#endif
|
||||
{
|
||||
bbPort->gpioIdleBSRR |= (1 << (pinIndex + 16)); // BR (higher half)
|
||||
}
|
||||
|
||||
#ifdef USE_DSHOT_TELEMETRY
|
||||
if (useDshotTelemetry) {
|
||||
IOWrite(bbMotor->io, 1);
|
||||
} else
|
||||
#endif
|
||||
{
|
||||
IOWrite(bbMotor->io, 0);
|
||||
}
|
||||
|
||||
#if defined(STM32F4)
|
||||
IOConfigGPIO(bbMotor->io, IO_CONFIG(GPIO_Mode_OUT, GPIO_Speed_50MHz, GPIO_OType_PP, bbPuPdMode));
|
||||
#else
|
||||
#error MCU dependent code required
|
||||
#endif
|
||||
}
|
||||
|
||||
void bbTimerChannelInit(bbPort_t *bbPort)
|
||||
{
|
||||
const timerHardware_t *timhw = bbPort->timhw;
|
||||
|
||||
TIM_OCInitTypeDef TIM_OCStruct;
|
||||
|
||||
TIM_OCStructInit(&TIM_OCStruct);
|
||||
TIM_OCStruct.TIM_OCMode = TIM_OCMode_PWM1;
|
||||
TIM_OCStruct.TIM_OCIdleState = TIM_OCIdleState_Set;
|
||||
TIM_OCStruct.TIM_OutputState = TIM_OutputState_Enable;
|
||||
TIM_OCStruct.TIM_OCPolarity = TIM_OCPolarity_Low;
|
||||
|
||||
TIM_OCStruct.TIM_Pulse = 10; // Duty doesn't matter, but too value small would make monitor output invalid
|
||||
|
||||
TIM_Cmd(bbPort->timhw->tim, DISABLE);
|
||||
|
||||
timerOCInit(timhw->tim, timhw->channel, &TIM_OCStruct);
|
||||
// timerOCPreloadConfig(timhw->tim, timhw->channel, TIM_OCPreload_Enable);
|
||||
|
||||
#ifdef DEBUG_MONITOR_PACER
|
||||
if (timhw->tag) {
|
||||
IO_t io = IOGetByTag(timhw->tag);
|
||||
IOConfigGPIOAF(io, IOCFG_AF_PP, timhw->alternateFunction);
|
||||
IOInit(io, OWNER_DSHOT_BITBANG, 0);
|
||||
TIM_CtrlPWMOutputs(timhw->tim, ENABLE);
|
||||
}
|
||||
#endif
|
||||
|
||||
// Enable and keep it running
|
||||
|
||||
TIM_Cmd(bbPort->timhw->tim, ENABLE);
|
||||
}
|
||||
|
||||
#ifdef USE_DMA_REGISTER_CACHE
|
||||
|
||||
void bbLoadDMARegs(dmaResource_t *dmaResource, dmaRegCache_t *dmaRegCache)
|
||||
{
|
||||
((DMA_Stream_TypeDef *)dmaResource)->CR = dmaRegCache->CR;
|
||||
((DMA_Stream_TypeDef *)dmaResource)->FCR = dmaRegCache->FCR;
|
||||
((DMA_Stream_TypeDef *)dmaResource)->NDTR = dmaRegCache->NDTR;
|
||||
((DMA_Stream_TypeDef *)dmaResource)->PAR = dmaRegCache->PAR;
|
||||
((DMA_Stream_TypeDef *)dmaResource)->M0AR = dmaRegCache->M0AR;
|
||||
}
|
||||
|
||||
static void bbSaveDMARegs(dmaResource_t *dmaResource, dmaRegCache_t *dmaRegCache)
|
||||
{
|
||||
dmaRegCache->CR = ((DMA_Stream_TypeDef *)dmaResource)->CR;
|
||||
dmaRegCache->FCR = ((DMA_Stream_TypeDef *)dmaResource)->FCR;
|
||||
dmaRegCache->NDTR = ((DMA_Stream_TypeDef *)dmaResource)->NDTR;
|
||||
dmaRegCache->PAR = ((DMA_Stream_TypeDef *)dmaResource)->PAR;
|
||||
dmaRegCache->M0AR = ((DMA_Stream_TypeDef *)dmaResource)->M0AR;
|
||||
}
|
||||
#endif
|
||||
|
||||
void bbSwitchToOutput(bbPort_t * bbPort)
|
||||
{
|
||||
dbgPinHi(1);
|
||||
// Output idle level before switching to output
|
||||
// Use BSRR register for this
|
||||
// Normal: Use BR (higher half)
|
||||
// Inverted: Use BS (lower half)
|
||||
|
||||
WRITE_REG(bbPort->gpio->BSRRL, bbPort->gpioIdleBSRR);
|
||||
|
||||
// Set GPIO to output
|
||||
ATOMIC_BLOCK(NVIC_PRIO_TIMER) {
|
||||
MODIFY_REG(bbPort->gpio->MODER, bbPort->gpioModeMask, bbPort->gpioModeOutput);
|
||||
}
|
||||
|
||||
// Reinitialize port group DMA for output
|
||||
|
||||
dmaResource_t *dmaResource = bbPort->dmaResource;
|
||||
#ifdef USE_DMA_REGISTER_CACHE
|
||||
bbLoadDMARegs(dmaResource, &bbPort->dmaRegOutput);
|
||||
#else
|
||||
xDMA_DeInit(dmaResource);
|
||||
xDMA_Init(dmaResource, &bbPort->outputDmaInit);
|
||||
// Needs this, as it is DeInit'ed above...
|
||||
xDMA_ITConfig(dmaResource, DMA_IT_TC, ENABLE);
|
||||
#endif
|
||||
|
||||
// Reinitialize pacer timer for output
|
||||
|
||||
bbPort->timhw->tim->ARR = bbPort->outputARR;
|
||||
|
||||
bbPort->direction = DSHOT_BITBANG_DIRECTION_OUTPUT;
|
||||
|
||||
dbgPinLo(1);
|
||||
}
|
||||
|
||||
#ifdef USE_DSHOT_TELEMETRY
|
||||
void bbSwitchToInput(bbPort_t *bbPort)
|
||||
{
|
||||
dbgPinHi(1);
|
||||
|
||||
// Set GPIO to input
|
||||
|
||||
ATOMIC_BLOCK(NVIC_PRIO_TIMER) {
|
||||
MODIFY_REG(bbPort->gpio->MODER, bbPort->gpioModeMask, bbPort->gpioModeInput);
|
||||
}
|
||||
|
||||
// Reinitialize port group DMA for input
|
||||
|
||||
dmaResource_t *dmaResource = bbPort->dmaResource;
|
||||
#ifdef USE_DMA_REGISTER_CACHE
|
||||
bbLoadDMARegs(dmaResource, &bbPort->dmaRegInput);
|
||||
#else
|
||||
xDMA_DeInit(dmaResource);
|
||||
xDMA_Init(dmaResource, &bbPort->inputDmaInit);
|
||||
// Needs this, as it is DeInit'ed above...
|
||||
xDMA_ITConfig(dmaResource, DMA_IT_TC, ENABLE);
|
||||
#endif
|
||||
|
||||
// Reinitialize pacer timer for input
|
||||
|
||||
bbPort->timhw->tim->CNT = 0;
|
||||
bbPort->timhw->tim->ARR = bbPort->inputARR;
|
||||
|
||||
bbDMA_Cmd(bbPort, ENABLE);
|
||||
|
||||
bbPort->direction = DSHOT_BITBANG_DIRECTION_INPUT;
|
||||
|
||||
dbgPinLo(1);
|
||||
}
|
||||
#endif
|
||||
|
||||
void bbDMAPreconfigure(bbPort_t *bbPort, uint8_t direction)
|
||||
{
|
||||
DMA_InitTypeDef *dmainit = (direction == DSHOT_BITBANG_DIRECTION_OUTPUT) ? &bbPort->outputDmaInit : &bbPort->inputDmaInit;
|
||||
|
||||
DMA_StructInit(dmainit);
|
||||
|
||||
dmainit->DMA_Mode = DMA_Mode_Normal;
|
||||
dmainit->DMA_Channel = bbPort->dmaChannel;
|
||||
dmainit->DMA_PeripheralInc = DMA_PeripheralInc_Disable;
|
||||
dmainit->DMA_MemoryInc = DMA_MemoryInc_Enable;
|
||||
dmainit->DMA_FIFOMode = DMA_FIFOMode_Enable ;
|
||||
dmainit->DMA_FIFOThreshold = DMA_FIFOThreshold_1QuarterFull ;
|
||||
dmainit->DMA_MemoryBurst = DMA_MemoryBurst_Single ;
|
||||
dmainit->DMA_PeripheralBurst = DMA_PeripheralBurst_Single;
|
||||
|
||||
if (direction == DSHOT_BITBANG_DIRECTION_OUTPUT) {
|
||||
dmainit->DMA_Priority = DMA_Priority_High;
|
||||
dmainit->DMA_DIR = DMA_DIR_MemoryToPeripheral;
|
||||
dmainit->DMA_BufferSize = bbPort->portOutputCount;
|
||||
dmainit->DMA_PeripheralBaseAddr = (uint32_t)&bbPort->gpio->BSRRL;
|
||||
dmainit->DMA_PeripheralDataSize = DMA_PeripheralDataSize_Word;
|
||||
dmainit->DMA_Memory0BaseAddr = (uint32_t)bbPort->portOutputBuffer;
|
||||
dmainit->DMA_MemoryDataSize = DMA_MemoryDataSize_Word;
|
||||
|
||||
#ifdef USE_DMA_REGISTER_CACHE
|
||||
xDMA_Init(bbPort->dmaResource, dmainit);
|
||||
bbSaveDMARegs(bbPort->dmaResource, &bbPort->dmaRegOutput);
|
||||
#endif
|
||||
} else {
|
||||
dmainit->DMA_Priority = DMA_Priority_VeryHigh;
|
||||
dmainit->DMA_DIR = DMA_DIR_PeripheralToMemory;
|
||||
dmainit->DMA_BufferSize = bbPort->portInputCount;
|
||||
|
||||
dmainit->DMA_PeripheralBaseAddr = (uint32_t)&bbPort->gpio->IDR;
|
||||
|
||||
dmainit->DMA_PeripheralDataSize = DMA_PeripheralDataSize_HalfWord;
|
||||
dmainit->DMA_Memory0BaseAddr = (uint32_t)bbPort->portInputBuffer;
|
||||
dmainit->DMA_MemoryDataSize = DMA_MemoryDataSize_Word;
|
||||
|
||||
#ifdef USE_DMA_REGISTER_CACHE
|
||||
xDMA_Init(bbPort->dmaResource, dmainit);
|
||||
bbSaveDMARegs(bbPort->dmaResource, &bbPort->dmaRegInput);
|
||||
#endif
|
||||
}
|
||||
}
|
||||
|
||||
void bbTIM_TimeBaseInit(bbPort_t *bbPort, uint16_t period)
|
||||
{
|
||||
TIM_TimeBaseInitTypeDef *init = &bbPort->timeBaseInit;
|
||||
|
||||
init->TIM_Prescaler = 0; // Feed raw timerClock
|
||||
init->TIM_ClockDivision = TIM_CKD_DIV1;
|
||||
init->TIM_CounterMode = TIM_CounterMode_Up;
|
||||
init->TIM_Period = period;
|
||||
TIM_TimeBaseInit(bbPort->timhw->tim, init);
|
||||
TIM_ARRPreloadConfig(bbPort->timhw->tim, ENABLE);
|
||||
}
|
||||
|
||||
void bbTIM_DMACmd(TIM_TypeDef* TIMx, uint16_t TIM_DMASource, FunctionalState NewState)
|
||||
{
|
||||
TIM_DMACmd(TIMx, TIM_DMASource, NewState);
|
||||
}
|
||||
|
||||
void bbDMA_ITConfig(bbPort_t *bbPort)
|
||||
{
|
||||
xDMA_ITConfig(bbPort->dmaResource, DMA_IT_TC, ENABLE);
|
||||
}
|
||||
|
||||
void bbDMA_Cmd(bbPort_t *bbPort, FunctionalState NewState)
|
||||
{
|
||||
xDMA_Cmd(bbPort->dmaResource, NewState);
|
||||
}
|
||||
|
||||
int bbDMA_Count(bbPort_t *bbPort)
|
||||
{
|
||||
return xDMA_GetCurrDataCounter(bbPort->dmaResource);
|
||||
}
|
||||
|
||||
#endif // USE_DSHOT_BB
|
|
@ -138,6 +138,7 @@ static FAST_CODE void dshotWrite(uint8_t index, float value)
|
|||
}
|
||||
|
||||
static motorVTable_t dshotPwmVTable = {
|
||||
.postInit = motorPostInitNull,
|
||||
.enable = dshotPwmEnableMotors,
|
||||
.disable = dshotPwmDisableMotors,
|
||||
.isMotorEnabled = dshotPwmIsMotorEnabled,
|
||||
|
|
|
@ -40,9 +40,6 @@
|
|||
|
||||
#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;
|
||||
|
@ -134,9 +131,7 @@ typedef struct motorDmaOutput_s {
|
|||
|
||||
#ifdef USE_DSHOT_TELEMETRY
|
||||
volatile bool isInput;
|
||||
uint16_t dshotTelemetryValue;
|
||||
timeDelta_t dshotTelemetryDeadtimeUs;
|
||||
bool dshotTelemetryActive;
|
||||
uint8_t dmaInputLen;
|
||||
|
||||
#ifdef USE_HAL_DRIVER
|
||||
|
|
|
@ -37,6 +37,7 @@
|
|||
#include "drivers/motor.h"
|
||||
#include "drivers/pwm_output.h" // for PWM_TYPE_* and others
|
||||
#include "drivers/time.h"
|
||||
#include "drivers/dshot_bitbang.h"
|
||||
#include "drivers/dshot_dpwm.h"
|
||||
|
||||
#include "fc/rc_controls.h" // for flight3DConfig_t
|
||||
|
@ -122,6 +123,15 @@ uint16_t motorConvertToExternal(float motorValue)
|
|||
|
||||
static bool isDshot = false; // XXX Should go somewhere else
|
||||
|
||||
void motorPostInit()
|
||||
{
|
||||
motorDevice->vTable.postInit();
|
||||
}
|
||||
|
||||
void motorPostInitNull(void)
|
||||
{
|
||||
}
|
||||
|
||||
static bool motorEnableNull(void)
|
||||
{
|
||||
return false;
|
||||
|
@ -169,6 +179,7 @@ static uint16_t motorConvertToExternalNull(float value)
|
|||
}
|
||||
|
||||
static const motorVTable_t motorNullVTable = {
|
||||
.postInit = motorPostInitNull,
|
||||
.enable = motorEnableNull,
|
||||
.disable = motorDisableNull,
|
||||
.updateStart = motorUpdateStartNull,
|
||||
|
@ -206,7 +217,15 @@ void motorDevInit(const motorDevConfig_t *motorConfig, uint16_t idlePulse, uint8
|
|||
case PWM_TYPE_DSHOT600:
|
||||
case PWM_TYPE_DSHOT1200:
|
||||
case PWM_TYPE_PROSHOT1000:
|
||||
motorDevice = dshotPwmDevInit(motorConfig, idlePulse, motorCount, useUnsyncedPwm);
|
||||
#ifdef USE_DSHOT_BITBANG
|
||||
if (isDshotBitbangActive(motorConfig)) {
|
||||
motorDevice = dshotBitbangDevInit(motorConfig, motorCount);
|
||||
} else
|
||||
#endif
|
||||
{
|
||||
motorDevice = dshotPwmDevInit(motorConfig, idlePulse, motorCount, useUnsyncedPwm);
|
||||
}
|
||||
|
||||
isDshot = true;
|
||||
break;
|
||||
#endif
|
||||
|
@ -255,4 +274,12 @@ bool isMotorProtocolDshot(void)
|
|||
{
|
||||
return isDshot;
|
||||
}
|
||||
|
||||
#ifdef USE_DSHOT_BITBANG
|
||||
bool isDshotBitbangActive(const motorDevConfig_t *motorConfig) {
|
||||
return motorConfig->useDshotBitbang == DSHOT_BITBANG_ON ||
|
||||
(motorConfig->useDshotBitbang == DSHOT_BITBANG_AUTO && motorConfig->useDshotTelemetry && motorConfig->motorPwmProtocol != PWM_TYPE_PROSHOT1000);
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif // USE_MOTOR
|
||||
|
|
|
@ -41,6 +41,7 @@ typedef enum {
|
|||
|
||||
typedef struct motorVTable_s {
|
||||
// Common
|
||||
void (*postInit)(void);
|
||||
float (*convertExternalToMotor)(uint16_t externalValue);
|
||||
uint16_t (*convertMotorToExternal)(float motorValue);
|
||||
bool (*enable)(void);
|
||||
|
@ -63,10 +64,12 @@ typedef struct motorDevice_s {
|
|||
bool enabled;
|
||||
} motorDevice_t;
|
||||
|
||||
void motorPostInitNull();
|
||||
void motorWriteNull(uint8_t index, float value);
|
||||
bool motorUpdateStartNull(void);
|
||||
void motorUpdateCompleteNull(void);
|
||||
|
||||
void motorPostInit();
|
||||
void motorWriteAll(float *values);
|
||||
|
||||
void motorInitEndpoints(float outputLimit, float *outputLow, float *outputHigh, float *disarm, float *deadbandMotor3DHigh, float *deadbandMotor3DLow);
|
||||
|
@ -83,3 +86,9 @@ void motorEnable(void);
|
|||
bool motorIsEnabled(void);
|
||||
bool motorIsMotorEnabled(uint8_t index);
|
||||
void motorShutdown(void); // Replaces stopPwmAllMotors
|
||||
|
||||
#ifdef USE_DSHOT_BITBANG
|
||||
struct motorDevConfig_s;
|
||||
typedef struct motorDevConfig_s motorDevConfig_t;
|
||||
bool isDshotBitbangActive(const motorDevConfig_t *motorConfig);
|
||||
#endif
|
||||
|
|
|
@ -50,6 +50,7 @@ void detectBrushedESC(ioTag_t motorIoTag)
|
|||
} else {
|
||||
hardwareMotorType = MOTOR_BRUSHED;
|
||||
}
|
||||
IORelease(motorDetectPin);
|
||||
}
|
||||
|
||||
uint8_t getDetectedMotorType(void)
|
||||
|
|
|
@ -172,6 +172,7 @@ static uint16_t pwmConvertToExternal(float motorValue)
|
|||
}
|
||||
|
||||
static motorVTable_t motorPwmVTable = {
|
||||
.postInit = motorPostInitNull,
|
||||
.enable = pwmEnableMotors,
|
||||
.disable = pwmDisableMotors,
|
||||
.isMotorEnabled = pwmIsMotorEnabled,
|
||||
|
|
|
@ -49,22 +49,6 @@
|
|||
|
||||
#include "pwm_output_dshot_shared.h"
|
||||
|
||||
#ifdef USE_DSHOT_TELEMETRY_STATS
|
||||
#define DSHOT_TELEMETRY_QUALITY_WINDOW 1 // capture a rolling 1 second of packet stats
|
||||
#define DSHOT_TELEMETRY_QUALITY_BUCKET_MS 100 // determines the granularity of the stats and the overall number of rolling buckets
|
||||
#define DSHOT_TELEMETRY_QUALITY_BUCKET_COUNT (DSHOT_TELEMETRY_QUALITY_WINDOW * 1000 / DSHOT_TELEMETRY_QUALITY_BUCKET_MS)
|
||||
|
||||
typedef struct dshotTelemetryQuality_s {
|
||||
uint32_t packetCountSum;
|
||||
uint32_t invalidCountSum;
|
||||
uint32_t packetCountArray[DSHOT_TELEMETRY_QUALITY_BUCKET_COUNT];
|
||||
uint32_t invalidCountArray[DSHOT_TELEMETRY_QUALITY_BUCKET_COUNT];
|
||||
uint8_t lastBucketIndex;
|
||||
} dshotTelemetryQuality_t;
|
||||
|
||||
static FAST_RAM_ZERO_INIT dshotTelemetryQuality_t dshotTelemetryQuality[MAX_SUPPORTED_MOTORS];
|
||||
#endif // USE_DSHOT_TELEMETRY_STATS
|
||||
|
||||
FAST_RAM_ZERO_INIT uint8_t dmaMotorTimerCount = 0;
|
||||
#ifdef STM32F7
|
||||
FAST_RAM_ZERO_INIT motorDmaTimer_t dmaMotorTimers[MAX_DMA_TIMERS];
|
||||
|
@ -75,12 +59,8 @@ motorDmaOutput_t dmaMotors[MAX_SUPPORTED_MOTORS];
|
|||
#endif
|
||||
|
||||
#ifdef USE_DSHOT_TELEMETRY
|
||||
uint32_t readDoneCount;
|
||||
|
||||
// TODO remove once debugging no longer needed
|
||||
FAST_RAM_ZERO_INIT uint32_t dshotInvalidPacketCount;
|
||||
FAST_RAM_ZERO_INIT uint32_t inputBuffer[GCR_TELEMETRY_INPUT_LEN];
|
||||
FAST_RAM_ZERO_INIT uint32_t decodePacketDurationUs;
|
||||
FAST_RAM_ZERO_INIT uint32_t inputStampUs;
|
||||
|
||||
FAST_RAM_ZERO_INIT dshotDMAHandlerCycleCounters_t dshotDMAHandlerCycleCounters;
|
||||
|
@ -117,8 +97,8 @@ FAST_CODE void pwmWriteDshotInt(uint8_t index, uint16_t value)
|
|||
#ifdef USE_DSHOT_TELEMETRY
|
||||
// reset telemetry debug statistics every time telemetry is enabled
|
||||
if (value == DSHOT_CMD_SIGNAL_LINE_CONTINUOUS_ERPM_TELEMETRY) {
|
||||
dshotInvalidPacketCount = 0;
|
||||
readDoneCount = 0;
|
||||
dshotTelemetryState.invalidPacketCount = 0;
|
||||
dshotTelemetryState.readCount = 0;
|
||||
}
|
||||
#endif
|
||||
if (value) {
|
||||
|
@ -155,9 +135,9 @@ FAST_CODE void pwmWriteDshotInt(uint8_t index, uint16_t value)
|
|||
|
||||
void dshotEnableChannels(uint8_t motorCount);
|
||||
|
||||
|
||||
static uint32_t decodeTelemetryPacket(uint32_t buffer[], uint32_t count)
|
||||
{
|
||||
uint32_t start = micros();
|
||||
uint32_t value = 0;
|
||||
uint32_t oldValue = buffer[0];
|
||||
int bits = 0;
|
||||
|
@ -196,13 +176,11 @@ static uint32_t decodeTelemetryPacket(uint32_t buffer[], uint32_t count)
|
|||
csum = csum ^ (csum >> 4); // xor nibbles
|
||||
|
||||
if ((csum & 0xf) != 0xf) {
|
||||
decodePacketDurationUs = micros() - start;
|
||||
return 0xffff;
|
||||
}
|
||||
decodedValue >>= 4;
|
||||
|
||||
if (decodedValue == 0x0fff) {
|
||||
decodePacketDurationUs = micros() - start;
|
||||
return 0;
|
||||
}
|
||||
decodedValue = (decodedValue & 0x000001ff) << ((decodedValue & 0xfffffe00) >> 9);
|
||||
|
@ -210,38 +188,12 @@ static uint32_t decodeTelemetryPacket(uint32_t buffer[], uint32_t count)
|
|||
return 0xffff;
|
||||
}
|
||||
uint32_t ret = (1000000 * 60 / 100 + decodedValue / 2) / decodedValue;
|
||||
decodePacketDurationUs = micros() - start;
|
||||
return ret;
|
||||
}
|
||||
|
||||
uint16_t getDshotTelemetry(uint8_t index)
|
||||
{
|
||||
return dmaMotors[index].dshotTelemetryValue;
|
||||
}
|
||||
|
||||
#endif
|
||||
|
||||
#ifdef USE_DSHOT_TELEMETRY
|
||||
#ifdef USE_DSHOT_TELEMETRY_STATS
|
||||
void updateDshotTelemetryQuality(dshotTelemetryQuality_t *qualityStats, bool packetValid, timeMs_t currentTimeMs)
|
||||
{
|
||||
uint8_t statsBucketIndex = (currentTimeMs / DSHOT_TELEMETRY_QUALITY_BUCKET_MS) % DSHOT_TELEMETRY_QUALITY_BUCKET_COUNT;
|
||||
if (statsBucketIndex != qualityStats->lastBucketIndex) {
|
||||
qualityStats->packetCountSum -= qualityStats->packetCountArray[statsBucketIndex];
|
||||
qualityStats->invalidCountSum -= qualityStats->invalidCountArray[statsBucketIndex];
|
||||
qualityStats->packetCountArray[statsBucketIndex] = 0;
|
||||
qualityStats->invalidCountArray[statsBucketIndex] = 0;
|
||||
qualityStats->lastBucketIndex = statsBucketIndex;
|
||||
}
|
||||
qualityStats->packetCountSum++;
|
||||
qualityStats->packetCountArray[statsBucketIndex]++;
|
||||
if (!packetValid) {
|
||||
qualityStats->invalidCountSum++;
|
||||
qualityStats->invalidCountArray[statsBucketIndex]++;
|
||||
}
|
||||
}
|
||||
#endif // USE_DSHOT_TELEMETRY_STATS
|
||||
|
||||
FAST_CODE_NOINLINE bool pwmStartDshotMotorUpdate(void)
|
||||
{
|
||||
if (!useDshotTelemetry) {
|
||||
|
@ -272,15 +224,15 @@ FAST_CODE_NOINLINE bool pwmStartDshotMotorUpdate(void)
|
|||
uint16_t value = 0xffff;
|
||||
|
||||
if (edges > MIN_GCR_EDGES) {
|
||||
readDoneCount++;
|
||||
dshotTelemetryState.readCount++;
|
||||
value = decodeTelemetryPacket(dmaMotors[i].dmaBuffer, edges);
|
||||
|
||||
#ifdef USE_DSHOT_TELEMETRY_STATS
|
||||
bool validTelemetryPacket = false;
|
||||
#endif
|
||||
if (value != 0xffff) {
|
||||
dmaMotors[i].dshotTelemetryValue = value;
|
||||
dmaMotors[i].dshotTelemetryActive = true;
|
||||
dshotTelemetryState.motorState[i].telemetryValue = value;
|
||||
dshotTelemetryState.motorState[i].telemetryActive = true;
|
||||
if (i < 4) {
|
||||
DEBUG_SET(DEBUG_DSHOT_RPM_TELEMETRY, i, value);
|
||||
}
|
||||
|
@ -288,9 +240,9 @@ FAST_CODE_NOINLINE bool pwmStartDshotMotorUpdate(void)
|
|||
validTelemetryPacket = true;
|
||||
#endif
|
||||
} else {
|
||||
dshotInvalidPacketCount++;
|
||||
dshotTelemetryState.invalidPacketCount++;
|
||||
if (i == 0) {
|
||||
memcpy(inputBuffer,dmaMotors[i].dmaBuffer,sizeof(inputBuffer));
|
||||
memcpy(dshotTelemetryState.inputBuffer,dmaMotors[i].dmaBuffer,sizeof(dshotTelemetryState.inputBuffer));
|
||||
}
|
||||
}
|
||||
#ifdef USE_DSHOT_TELEMETRY_STATS
|
||||
|
@ -307,7 +259,7 @@ FAST_CODE_NOINLINE bool pwmStartDshotMotorUpdate(void)
|
|||
|
||||
bool isDshotMotorTelemetryActive(uint8_t motorIndex)
|
||||
{
|
||||
return dmaMotors[motorIndex].dshotTelemetryActive;
|
||||
return dshotTelemetryState.motorState[motorIndex].telemetryActive;
|
||||
}
|
||||
|
||||
bool isDshotTelemetryActive(void)
|
||||
|
@ -325,7 +277,7 @@ int16_t getDshotTelemetryMotorInvalidPercent(uint8_t motorIndex)
|
|||
{
|
||||
int16_t invalidPercent = 0;
|
||||
|
||||
if (dmaMotors[motorIndex].dshotTelemetryActive) {
|
||||
if (dshotTelemetryState.motorState[motorIndex].telemetryActive) {
|
||||
const uint32_t totalCount = dshotTelemetryQuality[motorIndex].packetCountSum;
|
||||
const uint32_t invalidCount = dshotTelemetryQuality[motorIndex].invalidCountSum;
|
||||
if (totalCount > 0) {
|
||||
|
|
|
@ -44,9 +44,6 @@ extern motorDmaOutput_t dmaMotors[MAX_SUPPORTED_MOTORS];
|
|||
extern uint32_t readDoneCount;
|
||||
|
||||
// TODO remove once debugging no longer needed
|
||||
FAST_RAM_ZERO_INIT extern uint32_t dshotInvalidPacketCount;
|
||||
FAST_RAM_ZERO_INIT extern uint32_t inputBuffer[GCR_TELEMETRY_INPUT_LEN];
|
||||
FAST_RAM_ZERO_INIT extern uint32_t decodePacketDurationUs;
|
||||
FAST_RAM_ZERO_INIT extern uint32_t inputStampUs;
|
||||
|
||||
typedef struct dshotDMAHandlerCycleCounters_s {
|
||||
|
|
|
@ -106,5 +106,6 @@ const char * const ownerNames[OWNER_TOTAL_COUNT] = {
|
|||
"QSPI_BK2CS",
|
||||
"BARO_XCLR",
|
||||
"PULLUP",
|
||||
"PULLDOWN"
|
||||
"PULLDOWN",
|
||||
"DSHOT_BITBANG",
|
||||
};
|
||||
|
|
|
@ -105,6 +105,7 @@ typedef enum {
|
|||
OWNER_BARO_XCLR,
|
||||
OWNER_PULLUP,
|
||||
OWNER_PULLDOWN,
|
||||
OWNER_DSHOT_BITBANG,
|
||||
OWNER_TOTAL_COUNT
|
||||
} resourceOwner_e;
|
||||
|
||||
|
|
|
@ -158,5 +158,6 @@ ioTag_t timerioTagGetByUsage(timerUsageFlag_e usageFlag, uint8_t index)
|
|||
#endif
|
||||
return IO_TAG_NONE;
|
||||
}
|
||||
|
||||
#endif
|
||||
|
||||
|
|
|
@ -605,6 +605,16 @@
|
|||
|
||||
// AF table
|
||||
|
||||
// NONE
|
||||
#define DEF_TIM_AF__NONE__TCH_TIM1_CH1 D(1, 1)
|
||||
#define DEF_TIM_AF__NONE__TCH_TIM1_CH2 D(1, 1)
|
||||
#define DEF_TIM_AF__NONE__TCH_TIM1_CH3 D(1, 1)
|
||||
#define DEF_TIM_AF__NONE__TCH_TIM1_CH4 D(1, 1)
|
||||
#define DEF_TIM_AF__NONE__TCH_TIM8_CH1 D(3, 8)
|
||||
#define DEF_TIM_AF__NONE__TCH_TIM8_CH2 D(3, 8)
|
||||
#define DEF_TIM_AF__NONE__TCH_TIM8_CH3 D(3, 8)
|
||||
#define DEF_TIM_AF__NONE__TCH_TIM8_CH4 D(3, 8)
|
||||
|
||||
//PORTA
|
||||
#define DEF_TIM_AF__PA0__TCH_TIM2_CH1 D(1, 2)
|
||||
#define DEF_TIM_AF__PA1__TCH_TIM2_CH2 D(1, 2)
|
||||
|
@ -1004,4 +1014,6 @@
|
|||
#define DEF_TIM_AF__PI6__TCH_TIM8_CH2 D(3, 8)
|
||||
#define DEF_TIM_AF__PI7__TCH_TIM8_CH3 D(3, 8)
|
||||
|
||||
|
||||
#endif
|
||||
|
||||
|
|
|
@ -389,6 +389,13 @@ static void validateAndFixConfig(void)
|
|||
}
|
||||
}
|
||||
|
||||
#if defined(USE_DSHOT_TELEMETRY) && defined(USE_DSHOT_BITBANG)
|
||||
if (motorConfig()->dev.motorPwmProtocol == PWM_TYPE_PROSHOT1000 && motorConfig()->dev.useDshotTelemetry &&
|
||||
motorConfig()->dev.useDshotBitbang == DSHOT_BITBANG_ON) {
|
||||
motorConfigMutable()->dev.useDshotBitbang = DSHOT_BITBANG_AUTO;
|
||||
}
|
||||
#endif
|
||||
|
||||
// clear features that are not supported.
|
||||
// I have kept them all here in one place, some could be moved to sections of code above.
|
||||
|
||||
|
@ -504,7 +511,7 @@ static void validateAndFixConfig(void)
|
|||
}
|
||||
|
||||
#if defined(USE_DSHOT_TELEMETRY)
|
||||
if ((!usingDshotProtocol || motorConfig()->dev.useBurstDshot || !systemConfig()->schedulerOptimizeRate)
|
||||
if ((!usingDshotProtocol || (motorConfig()->dev.useDshotBitbang == DSHOT_BITBANG_OFF && motorConfig()->dev.useBurstDshot) || !systemConfig()->schedulerOptimizeRate)
|
||||
&& motorConfig()->dev.useDshotTelemetry) {
|
||||
motorConfigMutable()->dev.useDshotTelemetry = false;
|
||||
}
|
||||
|
|
|
@ -85,6 +85,7 @@
|
|||
|
||||
#include "osd/osd.h"
|
||||
|
||||
#include "pg/motor.h"
|
||||
#include "pg/pg.h"
|
||||
#include "pg/pg_ids.h"
|
||||
#include "pg/rx.h"
|
||||
|
@ -308,6 +309,14 @@ void updateArmingStatus(void)
|
|||
}
|
||||
#endif
|
||||
|
||||
#ifdef USE_DSHOT_BITBANG
|
||||
if (isDshotBitbangActive(&motorConfig()->dev) && dshotBitbangGetStatus() != DSHOT_BITBANG_OK) {
|
||||
setArmingDisabled(ARMING_DISABLED_DSHOT_BITBANG);
|
||||
} else {
|
||||
unsetArmingDisabled(ARMING_DISABLED_DSHOT_BITBANG);
|
||||
}
|
||||
#endif
|
||||
|
||||
if (IS_RC_MODE_ACTIVE(BOXPARALYZE)) {
|
||||
setArmingDisabled(ARMING_DISABLED_PARALYZE);
|
||||
}
|
||||
|
|
|
@ -918,6 +918,7 @@ void init(void)
|
|||
#endif // USE_RCDEVICE
|
||||
|
||||
#ifdef USE_MOTOR
|
||||
motorPostInit();
|
||||
motorEnable();
|
||||
#endif
|
||||
|
||||
|
|
|
@ -62,7 +62,8 @@ typedef enum {
|
|||
ARMING_DISABLED_RESC = (1 << 19),
|
||||
ARMING_DISABLED_RPMFILTER = (1 << 20),
|
||||
ARMING_DISABLED_REBOOT_REQUIRED = (1 << 21),
|
||||
ARMING_DISABLED_ARM_SWITCH = (1 << 22), // Needs to be the last element, since it's always activated if one of the others is active when arming
|
||||
ARMING_DISABLED_DSHOT_BITBANG = (1 << 22),
|
||||
ARMING_DISABLED_ARM_SWITCH = (1 << 23), // Needs to be the last element, since it's always activated if one of the others is active when arming
|
||||
} armingDisableFlags_e;
|
||||
|
||||
#define ARMING_DISABLE_FLAGS_COUNT (LOG2(ARMING_DISABLED_ARM_SWITCH) + 1)
|
||||
|
|
|
@ -73,6 +73,10 @@ void pgResetFn_motorConfig(motorConfig_t *motorConfig)
|
|||
#endif
|
||||
|
||||
motorConfig->motorPoleCount = 14; // Most brushes motors that we use are 14 poles
|
||||
|
||||
#ifdef USE_DSHOT_BITBANG
|
||||
motorConfig->dev.useDshotBitbang = DSHOT_BITBANG_AUTO;
|
||||
#endif
|
||||
}
|
||||
|
||||
#endif // USE_MOTOR
|
||||
|
|
|
@ -23,6 +23,7 @@
|
|||
#include "pg/pg.h"
|
||||
|
||||
#include "drivers/io.h"
|
||||
#include "drivers/dshot_bitbang.h"
|
||||
|
||||
typedef struct motorDevConfig_s {
|
||||
uint16_t motorPwmRate; // The update rate of motor outputs (50-498Hz)
|
||||
|
@ -33,6 +34,7 @@ typedef struct motorDevConfig_s {
|
|||
uint8_t useDshotTelemetry;
|
||||
ioTag_t ioTags[MAX_SUPPORTED_MOTORS];
|
||||
uint8_t motorTransportProtocol;
|
||||
uint8_t useDshotBitbang;
|
||||
} motorDevConfig_t;
|
||||
|
||||
typedef struct motorConfig_s {
|
||||
|
|
|
@ -52,6 +52,7 @@
|
|||
#define USE_FAST_RAM
|
||||
#endif
|
||||
#define USE_DSHOT
|
||||
#define USE_DSHOT_BITBANG
|
||||
#define USE_DSHOT_TELEMETRY
|
||||
#define USE_DSHOT_TELEMETRY_STATS
|
||||
#define USE_RPM_FILTER
|
||||
|
@ -82,6 +83,7 @@
|
|||
#define USE_ITCM_RAM
|
||||
#define USE_FAST_RAM
|
||||
#define USE_DSHOT
|
||||
#define USE_DSHOT_BITBANG
|
||||
#define USE_DSHOT_TELEMETRY
|
||||
#define USE_DSHOT_TELEMETRY_STATS
|
||||
#define USE_RPM_FILTER
|
||||
|
|
Loading…
Reference in New Issue