mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-14 20:10:18 +03:00
Send motor data and then immediately decode prior telemetry data for bitbanged DSHOT (#12685)
* Send motor data and then immediately decode prior telemetry data for bitbanged DSHOT F4 can't handle 8K PID loop * Fix missing cfg_pms.version * Limit G4 to 4K PID rate as per F4
This commit is contained in:
parent
fea097a893
commit
e8126dd6dd
16 changed files with 143 additions and 95 deletions
|
@ -670,8 +670,8 @@ void validateAndFixGyroConfig(void)
|
||||||
// check for looptime restrictions based on motor protocol. Motor times have safety margin
|
// check for looptime restrictions based on motor protocol. Motor times have safety margin
|
||||||
float motorUpdateRestriction;
|
float motorUpdateRestriction;
|
||||||
|
|
||||||
#if defined(STM32F411xE)
|
#if defined(STM32F4) || defined(STM32G4)
|
||||||
/* If bidirectional DSHOT is being used on an F411 then force DSHOT300. The motor update restrictions then applied
|
/* If bidirectional DSHOT is being used on an F4 or G4 then force DSHOT300. The motor update restrictions then applied
|
||||||
* will automatically consider the loop time and adjust pid_process_denom appropriately
|
* will automatically consider the loop time and adjust pid_process_denom appropriately
|
||||||
*/
|
*/
|
||||||
if (motorConfig()->dev.useDshotTelemetry && (motorConfig()->dev.motorPwmProtocol == PWM_TYPE_DSHOT600)) {
|
if (motorConfig()->dev.useDshotTelemetry && (motorConfig()->dev.motorPwmProtocol == PWM_TYPE_DSHOT600)) {
|
||||||
|
|
|
@ -184,7 +184,7 @@ motorDevice_t *motorPwmDevInit(const motorDevConfig_t *motorConfig, uint16_t idl
|
||||||
}
|
}
|
||||||
|
|
||||||
motorPwmDevice.vTable.write = pwmWriteStandard;
|
motorPwmDevice.vTable.write = pwmWriteStandard;
|
||||||
motorPwmDevice.vTable.updateStart = motorUpdateStartNull;
|
motorPwmDevice.vTable.decodeTelemetry = motorDecodeTelemetryNull;
|
||||||
motorPwmDevice.vTable.updateComplete = useUnsyncedPwm ? motorUpdateCompleteNull : pwmCompleteOneshotMotorUpdate;
|
motorPwmDevice.vTable.updateComplete = useUnsyncedPwm ? motorUpdateCompleteNull : pwmCompleteOneshotMotorUpdate;
|
||||||
|
|
||||||
for (int motorIndex = 0; motorIndex < MAX_SUPPORTED_MOTORS && motorIndex < motorCount; motorIndex++) {
|
for (int motorIndex = 0; motorIndex < MAX_SUPPORTED_MOTORS && motorIndex < motorCount; motorIndex++) {
|
||||||
|
|
|
@ -112,7 +112,7 @@ tmr_channel_select_type toCHSelectType(const uint8_t bfChannel, const bool useNC
|
||||||
* Enable the timer channels for all motors
|
* Enable the timer channels for all motors
|
||||||
*
|
*
|
||||||
* Called once for every dshot update if telemetry is being used (not just enabled by #def)
|
* Called once for every dshot update if telemetry is being used (not just enabled by #def)
|
||||||
* Called from pwm_output_dshot_shared.c pwmStartDshotMotorUpdate
|
* Called from pwm_output_dshot_shared.c pwmTelemetryDecode
|
||||||
*/
|
*/
|
||||||
void dshotEnableChannels(uint8_t motorCount)
|
void dshotEnableChannels(uint8_t motorCount)
|
||||||
{
|
{
|
||||||
|
@ -130,7 +130,7 @@ void dshotEnableChannels(uint8_t motorCount)
|
||||||
* Set the timer and dma of the specified motor for use as an output
|
* Set the timer and dma of the specified motor for use as an output
|
||||||
*
|
*
|
||||||
* Called from pwmDshotMotorHardwareConfig in this file and also from
|
* Called from pwmDshotMotorHardwareConfig in this file and also from
|
||||||
* pwmStartDshotMotorUpdate in src/main/drivers/pwm_output_dshot_shared.c
|
* pwmTelemetryDecode in src/main/drivers/pwm_output_dshot_shared.c
|
||||||
*/
|
*/
|
||||||
FAST_CODE void pwmDshotSetDirectionOutput(
|
FAST_CODE void pwmDshotSetDirectionOutput(
|
||||||
motorDmaOutput_t * const motor
|
motorDmaOutput_t * const motor
|
||||||
|
|
|
@ -268,7 +268,7 @@ FAST_CODE uint32_t decode_bb( uint16_t buffer[], uint32_t count, uint32_t bit)
|
||||||
startMargin = p - buffer;
|
startMargin = p - buffer;
|
||||||
DEBUG_SET(DEBUG_DSHOT_TELEMETRY_COUNTS, 3, startMargin);
|
DEBUG_SET(DEBUG_DSHOT_TELEMETRY_COUNTS, 3, startMargin);
|
||||||
|
|
||||||
if(*p & mask) {
|
if (p >= endP) {
|
||||||
// not returning telemetry is ok if the esc cpu is
|
// not returning telemetry is ok if the esc cpu is
|
||||||
// overburdened. in that case no edge will be found and
|
// overburdened. in that case no edge will be found and
|
||||||
// BB_NOEDGE indicates the condition to caller
|
// BB_NOEDGE indicates the condition to caller
|
||||||
|
|
|
@ -218,7 +218,7 @@ void dshotCommandWrite(uint8_t index, uint8_t motorCount, uint8_t command, dshot
|
||||||
|
|
||||||
#ifdef USE_DSHOT_TELEMETRY
|
#ifdef USE_DSHOT_TELEMETRY
|
||||||
timeUs_t timeoutUs = micros() + 1000;
|
timeUs_t timeoutUs = micros() + 1000;
|
||||||
while (!motorGetVTable().updateStart() &&
|
while (!motorGetVTable().decodeTelemetry() &&
|
||||||
cmpTimeUs(timeoutUs, micros()) > 0);
|
cmpTimeUs(timeoutUs, micros()) > 0);
|
||||||
#endif
|
#endif
|
||||||
for (uint8_t i = 0; i < motorDeviceCount(); i++) {
|
for (uint8_t i = 0; i < motorDeviceCount(); i++) {
|
||||||
|
|
|
@ -140,7 +140,7 @@ static motorVTable_t dshotPwmVTable = {
|
||||||
.enable = dshotPwmEnableMotors,
|
.enable = dshotPwmEnableMotors,
|
||||||
.disable = dshotPwmDisableMotors,
|
.disable = dshotPwmDisableMotors,
|
||||||
.isMotorEnabled = dshotPwmIsMotorEnabled,
|
.isMotorEnabled = dshotPwmIsMotorEnabled,
|
||||||
.updateStart = motorUpdateStartNull, // May be updated after copying
|
.decodeTelemetry = motorDecodeTelemetryNull, // May be updated after copying
|
||||||
.write = dshotWrite,
|
.write = dshotWrite,
|
||||||
.writeInt = dshotWriteInt,
|
.writeInt = dshotWriteInt,
|
||||||
.updateComplete = pwmCompleteDshotMotorUpdate,
|
.updateComplete = pwmCompleteDshotMotorUpdate,
|
||||||
|
@ -160,7 +160,7 @@ motorDevice_t *dshotPwmDevInit(const motorDevConfig_t *motorConfig, uint16_t idl
|
||||||
|
|
||||||
#ifdef USE_DSHOT_TELEMETRY
|
#ifdef USE_DSHOT_TELEMETRY
|
||||||
useDshotTelemetry = motorConfig->useDshotTelemetry;
|
useDshotTelemetry = motorConfig->useDshotTelemetry;
|
||||||
dshotPwmDevice.vTable.updateStart = pwmStartDshotMotorUpdate;
|
dshotPwmDevice.vTable.decodeTelemetry = pwmTelemetryDecode;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
switch (motorConfig->motorPwmProtocol) {
|
switch (motorConfig->motorPwmProtocol) {
|
||||||
|
|
|
@ -162,7 +162,7 @@ motorDmaOutput_t *getMotorDmaOutput(uint8_t index);
|
||||||
void pwmWriteDshotInt(uint8_t index, uint16_t value);
|
void pwmWriteDshotInt(uint8_t index, uint16_t value);
|
||||||
bool pwmDshotMotorHardwareConfig(const timerHardware_t *timerHardware, uint8_t motorIndex, uint8_t reorderedMotorIndex, motorPwmProtocolTypes_e pwmProtocolType, uint8_t output);
|
bool pwmDshotMotorHardwareConfig(const timerHardware_t *timerHardware, uint8_t motorIndex, uint8_t reorderedMotorIndex, motorPwmProtocolTypes_e pwmProtocolType, uint8_t output);
|
||||||
#ifdef USE_DSHOT_TELEMETRY
|
#ifdef USE_DSHOT_TELEMETRY
|
||||||
bool pwmStartDshotMotorUpdate(void);
|
bool pwmTelemetryDecode(void);
|
||||||
#endif
|
#endif
|
||||||
void pwmCompleteDshotMotorUpdate(void);
|
void pwmCompleteDshotMotorUpdate(void);
|
||||||
|
|
||||||
|
|
|
@ -60,15 +60,49 @@ void motorWriteAll(float *values)
|
||||||
{
|
{
|
||||||
#ifdef USE_PWM_OUTPUT
|
#ifdef USE_PWM_OUTPUT
|
||||||
if (motorDevice->enabled) {
|
if (motorDevice->enabled) {
|
||||||
#if defined(USE_DSHOT) && defined(USE_DSHOT_TELEMETRY)
|
#ifdef USE_DSHOT_BITBANG
|
||||||
if (!motorDevice->vTable.updateStart()) {
|
if (isDshotBitbangActive(&motorConfig()->dev)) {
|
||||||
return;
|
// Initialise the output buffers
|
||||||
|
if (motorDevice->vTable.updateInit) {
|
||||||
|
motorDevice->vTable.updateInit();
|
||||||
}
|
}
|
||||||
#endif
|
|
||||||
|
// Update the motor data
|
||||||
for (int i = 0; i < motorDevice->count; i++) {
|
for (int i = 0; i < motorDevice->count; i++) {
|
||||||
motorDevice->vTable.write(i, values[i]);
|
motorDevice->vTable.write(i, values[i]);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// Don't attempt to write commands to the motors if telemetry is still being received
|
||||||
|
if (motorDevice->vTable.telemetryWait) {
|
||||||
|
(void)motorDevice->vTable.telemetryWait();
|
||||||
|
}
|
||||||
|
|
||||||
|
// Trigger the transmission of the motor data
|
||||||
motorDevice->vTable.updateComplete();
|
motorDevice->vTable.updateComplete();
|
||||||
|
|
||||||
|
// Perform the decode of the last data received
|
||||||
|
// New data will be received once the send of motor data, triggered above, completes
|
||||||
|
#if defined(USE_DSHOT) && defined(USE_DSHOT_TELEMETRY)
|
||||||
|
motorDevice->vTable.decodeTelemetry();
|
||||||
|
#endif
|
||||||
|
} else
|
||||||
|
#endif
|
||||||
|
{
|
||||||
|
// Perform the decode of the last data received
|
||||||
|
// New data will be received once the send of motor data, triggered above, completes
|
||||||
|
#if defined(USE_DSHOT) && defined(USE_DSHOT_TELEMETRY)
|
||||||
|
motorDevice->vTable.decodeTelemetry();
|
||||||
|
#endif
|
||||||
|
|
||||||
|
// Update the motor data
|
||||||
|
for (int i = 0; i < motorDevice->count; i++) {
|
||||||
|
motorDevice->vTable.write(i, values[i]);
|
||||||
|
}
|
||||||
|
|
||||||
|
// Trigger the transmission of the motor data
|
||||||
|
motorDevice->vTable.updateComplete();
|
||||||
|
|
||||||
|
}
|
||||||
}
|
}
|
||||||
#else
|
#else
|
||||||
UNUSED(values);
|
UNUSED(values);
|
||||||
|
@ -193,7 +227,7 @@ static bool motorIsEnabledNull(uint8_t index)
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
bool motorUpdateStartNull(void)
|
bool motorDecodeTelemetryNull(void)
|
||||||
{
|
{
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
@ -235,7 +269,7 @@ static const motorVTable_t motorNullVTable = {
|
||||||
.enable = motorEnableNull,
|
.enable = motorEnableNull,
|
||||||
.disable = motorDisableNull,
|
.disable = motorDisableNull,
|
||||||
.isMotorEnabled = motorIsEnabledNull,
|
.isMotorEnabled = motorIsEnabledNull,
|
||||||
.updateStart = motorUpdateStartNull,
|
.decodeTelemetry = motorDecodeTelemetryNull,
|
||||||
.write = motorWriteNull,
|
.write = motorWriteNull,
|
||||||
.writeInt = motorWriteIntNull,
|
.writeInt = motorWriteIntNull,
|
||||||
.updateComplete = motorUpdateCompleteNull,
|
.updateComplete = motorUpdateCompleteNull,
|
||||||
|
|
|
@ -50,7 +50,9 @@ typedef struct motorVTable_s {
|
||||||
bool (*enable)(void);
|
bool (*enable)(void);
|
||||||
void (*disable)(void);
|
void (*disable)(void);
|
||||||
bool (*isMotorEnabled)(uint8_t index);
|
bool (*isMotorEnabled)(uint8_t index);
|
||||||
bool (*updateStart)(void);
|
bool (*telemetryWait)(void);
|
||||||
|
bool (*decodeTelemetry)(void);
|
||||||
|
void (*updateInit)(void);
|
||||||
void (*write)(uint8_t index, float value);
|
void (*write)(uint8_t index, float value);
|
||||||
void (*writeInt)(uint8_t index, uint16_t value);
|
void (*writeInt)(uint8_t index, uint16_t value);
|
||||||
void (*updateComplete)(void);
|
void (*updateComplete)(void);
|
||||||
|
@ -70,7 +72,7 @@ typedef struct motorDevice_s {
|
||||||
|
|
||||||
void motorPostInitNull();
|
void motorPostInitNull();
|
||||||
void motorWriteNull(uint8_t index, float value);
|
void motorWriteNull(uint8_t index, float value);
|
||||||
bool motorUpdateStartNull(void);
|
bool motorDecodeTelemetryNull(void);
|
||||||
void motorUpdateCompleteNull(void);
|
void motorUpdateCompleteNull(void);
|
||||||
|
|
||||||
void motorPostInit();
|
void motorPostInit();
|
||||||
|
|
|
@ -199,7 +199,7 @@ static uint32_t decodeTelemetryPacket(uint32_t buffer[], uint32_t count)
|
||||||
* Process dshot telemetry packets before switching the channels back to outputs
|
* Process dshot telemetry packets before switching the channels back to outputs
|
||||||
*
|
*
|
||||||
*/
|
*/
|
||||||
FAST_CODE_NOINLINE bool pwmStartDshotMotorUpdate(void)
|
FAST_CODE_NOINLINE bool pwmTelemetryDecode(void)
|
||||||
{
|
{
|
||||||
if (!useDshotTelemetry) {
|
if (!useDshotTelemetry) {
|
||||||
return true;
|
return true;
|
||||||
|
|
|
@ -59,7 +59,7 @@ void pwmDshotSetDirectionOutput(
|
||||||
#endif
|
#endif
|
||||||
);
|
);
|
||||||
|
|
||||||
bool pwmStartDshotMotorUpdate(void);
|
bool pwmTelemetryDecode(void);
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
#endif
|
#endif
|
||||||
|
|
|
@ -46,6 +46,7 @@
|
||||||
#include "drivers/timer.h"
|
#include "drivers/timer.h"
|
||||||
|
|
||||||
#include "pg/motor.h"
|
#include "pg/motor.h"
|
||||||
|
#include "pg/pinio.h"
|
||||||
|
|
||||||
// DEBUG_DSHOT_TELEMETRY_COUNTS
|
// DEBUG_DSHOT_TELEMETRY_COUNTS
|
||||||
// 0 - Count of telemetry packets read
|
// 0 - Count of telemetry packets read
|
||||||
|
@ -337,6 +338,8 @@ FAST_IRQ_HANDLER void bbDMAIrqHandler(dmaChannelDescriptor_t *descriptor)
|
||||||
#ifdef DEBUG_COUNT_INTERRUPT
|
#ifdef DEBUG_COUNT_INTERRUPT
|
||||||
bbPort->inputIrq++;
|
bbPort->inputIrq++;
|
||||||
#endif
|
#endif
|
||||||
|
// Disable DMA as telemetry reception is complete
|
||||||
|
bbDMA_Cmd(bbPort, DISABLE);
|
||||||
} else {
|
} else {
|
||||||
#ifdef DEBUG_COUNT_INTERRUPT
|
#ifdef DEBUG_COUNT_INTERRUPT
|
||||||
bbPort->outputIrq++;
|
bbPort->outputIrq++;
|
||||||
|
@ -452,7 +455,7 @@ static bool bbMotorConfig(IO_t io, uint8_t motorIndex, motorPwmProtocolTypes_e p
|
||||||
|
|
||||||
if (!bbPort || !dmaAllocate(dmaGetIdentifier(bbPort->dmaResource), bbPort->owner.owner, bbPort->owner.resourceIndex)) {
|
if (!bbPort || !dmaAllocate(dmaGetIdentifier(bbPort->dmaResource), bbPort->owner.owner, bbPort->owner.resourceIndex)) {
|
||||||
bbDevice.vTable.write = motorWriteNull;
|
bbDevice.vTable.write = motorWriteNull;
|
||||||
bbDevice.vTable.updateStart = motorUpdateStartNull;
|
bbDevice.vTable.decodeTelemetry = motorDecodeTelemetryNull;
|
||||||
bbDevice.vTable.updateComplete = motorUpdateCompleteNull;
|
bbDevice.vTable.updateComplete = motorUpdateCompleteNull;
|
||||||
|
|
||||||
return false;
|
return false;
|
||||||
|
@ -504,15 +507,9 @@ static bool bbMotorConfig(IO_t io, uint8_t motorIndex, motorPwmProtocolTypes_e p
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
static bool bbUpdateStart(void)
|
static bool bbTelemetryWait(void)
|
||||||
{
|
{
|
||||||
#ifdef USE_DSHOT_TELEMETRY
|
// Wait for telemetry reception to complete
|
||||||
if (useDshotTelemetry) {
|
|
||||||
#ifdef USE_DSHOT_TELEMETRY_STATS
|
|
||||||
const timeMs_t currentTimeMs = millis();
|
|
||||||
#endif
|
|
||||||
|
|
||||||
// Wait for telemetry reception to complete before decode
|
|
||||||
bool telemetryPending;
|
bool telemetryPending;
|
||||||
bool telemetryWait = false;
|
bool telemetryWait = false;
|
||||||
const timeUs_t startTimeUs = micros();
|
const timeUs_t startTimeUs = micros();
|
||||||
|
@ -526,13 +523,32 @@ static bool bbUpdateStart(void)
|
||||||
telemetryWait |= telemetryPending;
|
telemetryWait |= telemetryPending;
|
||||||
|
|
||||||
if (cmpTimeUs(micros(), startTimeUs) > DSHOT_TELEMETRY_TIMEOUT) {
|
if (cmpTimeUs(micros(), startTimeUs) > DSHOT_TELEMETRY_TIMEOUT) {
|
||||||
return false;
|
break;
|
||||||
}
|
}
|
||||||
} while (telemetryPending);
|
} while (telemetryPending);
|
||||||
|
|
||||||
if (telemetryWait) {
|
if (telemetryWait) {
|
||||||
DEBUG_SET(DEBUG_DSHOT_TELEMETRY_COUNTS, 2, debug[2] + 1);
|
DEBUG_SET(DEBUG_DSHOT_TELEMETRY_COUNTS, 2, debug[2] + 1);
|
||||||
} else {
|
}
|
||||||
|
|
||||||
|
return telemetryWait;
|
||||||
|
}
|
||||||
|
|
||||||
|
static void bbUpdateInit(void)
|
||||||
|
{
|
||||||
|
for (int i = 0; i < usedMotorPorts; i++) {
|
||||||
|
bbOutputDataClear(bbPorts[i].portOutputBuffer);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
static bool bbDecodeTelemetry(void)
|
||||||
|
{
|
||||||
|
#ifdef USE_DSHOT_TELEMETRY
|
||||||
|
if (useDshotTelemetry) {
|
||||||
|
#ifdef USE_DSHOT_TELEMETRY_STATS
|
||||||
|
const timeMs_t currentTimeMs = millis();
|
||||||
|
#endif
|
||||||
|
|
||||||
#ifdef USE_DSHOT_CACHE_MGMT
|
#ifdef USE_DSHOT_CACHE_MGMT
|
||||||
for (int i = 0; i < usedMotorPorts; i++) {
|
for (int i = 0; i < usedMotorPorts; i++) {
|
||||||
bbPort_t *bbPort = &bbPorts[i];
|
bbPort_t *bbPort = &bbPorts[i];
|
||||||
|
@ -543,12 +559,12 @@ static bool bbUpdateStart(void)
|
||||||
#ifdef STM32F4
|
#ifdef STM32F4
|
||||||
uint32_t rawValue = decode_bb_bitband(
|
uint32_t rawValue = decode_bb_bitband(
|
||||||
bbMotors[motorIndex].bbPort->portInputBuffer,
|
bbMotors[motorIndex].bbPort->portInputBuffer,
|
||||||
bbMotors[motorIndex].bbPort->portInputCount - bbDMA_Count(bbMotors[motorIndex].bbPort),
|
bbMotors[motorIndex].bbPort->portInputCount,
|
||||||
bbMotors[motorIndex].pinIndex);
|
bbMotors[motorIndex].pinIndex);
|
||||||
#else
|
#else
|
||||||
uint32_t rawValue = decode_bb(
|
uint32_t rawValue = decode_bb(
|
||||||
bbMotors[motorIndex].bbPort->portInputBuffer,
|
bbMotors[motorIndex].bbPort->portInputBuffer,
|
||||||
bbMotors[motorIndex].bbPort->portInputCount - bbDMA_Count(bbMotors[motorIndex].bbPort),
|
bbMotors[motorIndex].bbPort->portInputCount,
|
||||||
bbMotors[motorIndex].pinIndex);
|
bbMotors[motorIndex].pinIndex);
|
||||||
#endif
|
#endif
|
||||||
if (rawValue == DSHOT_TELEMETRY_NOEDGE) {
|
if (rawValue == DSHOT_TELEMETRY_NOEDGE) {
|
||||||
|
@ -576,12 +592,6 @@ static bool bbUpdateStart(void)
|
||||||
dshotTelemetryState.rawValueState = DSHOT_RAW_VALUE_STATE_NOT_PROCESSED;
|
dshotTelemetryState.rawValueState = DSHOT_RAW_VALUE_STATE_NOT_PROCESSED;
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
}
|
|
||||||
|
|
||||||
for (int i = 0; i < usedMotorPorts; i++) {
|
|
||||||
bbDMA_Cmd(&bbPorts[i], DISABLE);
|
|
||||||
bbOutputDataClear(bbPorts[i].portOutputBuffer);
|
|
||||||
}
|
|
||||||
|
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
@ -718,7 +728,9 @@ static motorVTable_t bbVTable = {
|
||||||
.enable = bbEnableMotors,
|
.enable = bbEnableMotors,
|
||||||
.disable = bbDisableMotors,
|
.disable = bbDisableMotors,
|
||||||
.isMotorEnabled = bbIsMotorEnabled,
|
.isMotorEnabled = bbIsMotorEnabled,
|
||||||
.updateStart = bbUpdateStart,
|
.telemetryWait = bbTelemetryWait,
|
||||||
|
.decodeTelemetry = bbDecodeTelemetry,
|
||||||
|
.updateInit = bbUpdateInit,
|
||||||
.write = bbWrite,
|
.write = bbWrite,
|
||||||
.writeInt = bbWriteInt,
|
.writeInt = bbWriteInt,
|
||||||
.updateComplete = bbUpdateComplete,
|
.updateComplete = bbUpdateComplete,
|
||||||
|
@ -765,7 +777,7 @@ motorDevice_t *dshotBitbangDevInit(const motorDevConfig_t *motorConfig, uint8_t
|
||||||
if (!IOIsFreeOrPreinit(io)) {
|
if (!IOIsFreeOrPreinit(io)) {
|
||||||
/* not enough motors initialised for the mixer or a break in the motors */
|
/* not enough motors initialised for the mixer or a break in the motors */
|
||||||
bbDevice.vTable.write = motorWriteNull;
|
bbDevice.vTable.write = motorWriteNull;
|
||||||
bbDevice.vTable.updateStart = motorUpdateStartNull;
|
bbDevice.vTable.decodeTelemetry = motorDecodeTelemetryNull;
|
||||||
bbDevice.vTable.updateComplete = motorUpdateCompleteNull;
|
bbDevice.vTable.updateComplete = motorUpdateCompleteNull;
|
||||||
bbStatus = DSHOT_BITBANG_STATUS_MOTOR_PIN_CONFLICT;
|
bbStatus = DSHOT_BITBANG_STATUS_MOTOR_PIN_CONFLICT;
|
||||||
return NULL;
|
return NULL;
|
||||||
|
|
|
@ -215,7 +215,7 @@ motorDevice_t *motorPwmDevInit(const motorDevConfig_t *motorConfig, uint16_t idl
|
||||||
}
|
}
|
||||||
|
|
||||||
motorPwmDevice.vTable.write = pwmWriteStandard;
|
motorPwmDevice.vTable.write = pwmWriteStandard;
|
||||||
motorPwmDevice.vTable.updateStart = motorUpdateStartNull;
|
motorPwmDevice.vTable.decodeTelemetry = motorDecodeTelemetryNull;
|
||||||
motorPwmDevice.vTable.updateComplete = useUnsyncedPwm ? motorUpdateCompleteNull : pwmCompleteOneshotMotorUpdate;
|
motorPwmDevice.vTable.updateComplete = useUnsyncedPwm ? motorUpdateCompleteNull : pwmCompleteOneshotMotorUpdate;
|
||||||
|
|
||||||
for (int motorIndex = 0; motorIndex < MAX_SUPPORTED_MOTORS && motorIndex < motorCount; motorIndex++) {
|
for (int motorIndex = 0; motorIndex < MAX_SUPPORTED_MOTORS && motorIndex < motorCount; motorIndex++) {
|
||||||
|
|
|
@ -619,7 +619,7 @@ static motorDevice_t motorPwmDevice = {
|
||||||
.enable = pwmEnableMotors,
|
.enable = pwmEnableMotors,
|
||||||
.disable = pwmDisableMotors,
|
.disable = pwmDisableMotors,
|
||||||
.isMotorEnabled = pwmIsMotorEnabled,
|
.isMotorEnabled = pwmIsMotorEnabled,
|
||||||
.updateStart = motorUpdateStartNull,
|
.decodeTelemetry = motorDecodeTelemetryNull,
|
||||||
.write = pwmWriteMotor,
|
.write = pwmWriteMotor,
|
||||||
.writeInt = pwmWriteMotorInt,
|
.writeInt = pwmWriteMotorInt,
|
||||||
.updateComplete = pwmCompleteMotorUpdate,
|
.updateComplete = pwmCompleteMotorUpdate,
|
||||||
|
|
Loading…
Add table
Add a link
Reference in a new issue