diff --git a/src/main/cli/settings.c b/src/main/cli/settings.c index 126e5e51a2..f75ec4f1a5 100644 --- a/src/main/cli/settings.c +++ b/src/main/cli/settings.c @@ -843,7 +843,8 @@ const clivalue_t valueTable[] = { { "dshot_burst", VAR_UINT8 | HARDWARE_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON_AUTO }, PG_MOTOR_CONFIG, offsetof(motorConfig_t, dev.useBurstDshot) }, #endif #ifdef USE_DSHOT_TELEMETRY - { PARAM_NAME_DSHOT_BIDIR, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_MOTOR_CONFIG, offsetof(motorConfig_t, dev.useDshotTelemetry) }, + { PARAM_NAME_DSHOT_BIDIR, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_MOTOR_CONFIG, offsetof(motorConfig_t, dev.useDshotTelemetry) }, + { "dshot_edt", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_MOTOR_CONFIG, offsetof(motorConfig_t, dev.useDshotEdt) }, #endif #ifdef USE_DSHOT_BITBANG { "dshot_bitbang", VAR_UINT8 | HARDWARE_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON_AUTO }, PG_MOTOR_CONFIG, offsetof(motorConfig_t, dev.useDshotBitbang) }, diff --git a/src/main/drivers/dshot.c b/src/main/drivers/dshot.c index 6d83ea88d0..3203fd5ede 100644 --- a/src/main/drivers/dshot.c +++ b/src/main/drivers/dshot.c @@ -134,8 +134,151 @@ FAST_CODE uint16_t prepareDshotPacket(dshotProtocolControl_t *pcb) FAST_DATA_ZERO_INIT dshotTelemetryState_t dshotTelemetryState; +static uint32_t dshot_decode_eRPM_telemetry_value(uint16_t value) +{ + // eRPM range + if (value == 0x0fff) { + return 0; + } + + // Convert value to 16 bit from the GCR telemetry format (eeem mmmm mmmm) + value = (value & 0x01ff) << ((value & 0xfe00) >> 9); + if (!value) { + return DSHOT_TELEMETRY_INVALID; + } + + // Convert period to erpm * 100 + return (1000000 * 60 / 100 + value / 2) / value; +} + +static void dshot_decode_telemetry_value(uint8_t motorIndex, uint32_t *pDecoded, dshotTelemetryType_t *pType) +{ + uint16_t value = dshotTelemetryState.motorState[motorIndex].rawValue; + + if (dshotTelemetryState.motorState[motorIndex].telemetryTypes == DSHOT_NORMAL_TELEMETRY_MASK) { /* Check DSHOT_TELEMETRY_TYPE_eRPM mask */ + // Decode eRPM telemetry + *pDecoded = dshot_decode_eRPM_telemetry_value(value); + + // Set telemetry type + *pType = DSHOT_TELEMETRY_TYPE_eRPM; + } else { + // Decode Extended DSHOT telemetry + switch (value & 0x0f00) { + + case 0x0200: + // Temperature range (in degree Celsius, just like Blheli_32 and KISS) + *pDecoded = value & 0x00ff; + + // Set telemetry type + *pType = DSHOT_TELEMETRY_TYPE_TEMPERATURE; + break; + + case 0x0400: + // Voltage range (0-63,75V step 0,25V) + *pDecoded = value & 0x00ff; + + // Set telemetry type + *pType = DSHOT_TELEMETRY_TYPE_VOLTAGE; + break; + + case 0x0600: + // Current range (0-255A step 1A) + *pDecoded = value & 0x00ff; + + // Set telemetry type + *pType = DSHOT_TELEMETRY_TYPE_CURRENT; + break; + + case 0x0800: + // Debug 1 value + *pDecoded = value & 0x00ff; + + // Set telemetry type + *pType = DSHOT_TELEMETRY_TYPE_DEBUG1; + break; + + case 0x0A00: + // Debug 2 value + *pDecoded = value & 0x00ff; + + // Set telemetry type + *pType = DSHOT_TELEMETRY_TYPE_DEBUG2; + break; + + case 0x0C00: + // Debug 3 value + *pDecoded = value & 0x00ff; + + // Set telemetry type + *pType = DSHOT_TELEMETRY_TYPE_DEBUG3; + break; + + case 0x0E00: + // State / events + *pDecoded = value & 0x00ff; + + // Set telemetry type + *pType = DSHOT_TELEMETRY_TYPE_STATE_EVENTS; + break; + + default: + // Decode as eRPM + *pDecoded = dshot_decode_eRPM_telemetry_value(value); + + // Set telemetry type + *pType = DSHOT_TELEMETRY_TYPE_eRPM; + break; + + } + } +} + +static void dshotUpdateTelemetryData(uint8_t motorIndex, dshotTelemetryType_t type, uint32_t value) +{ + // Update telemetry data + dshotTelemetryState.motorState[motorIndex].telemetryData[type] = value; + dshotTelemetryState.motorState[motorIndex].telemetryTypes |= (1 << type); + + // Update max temp + if ((type == DSHOT_TELEMETRY_TYPE_TEMPERATURE) && (value > dshotTelemetryState.motorState[motorIndex].maxTemp)) { + dshotTelemetryState.motorState[motorIndex].maxTemp = value; + } +} + uint16_t getDshotTelemetry(uint8_t index) { + // Process telemetry in case it haven“t been processed yet + if (dshotTelemetryState.rawValueState == DSHOT_RAW_VALUE_STATE_NOT_PROCESSED) { + const unsigned motorCount = motorDeviceCount(); + uint32_t rpmTotal = 0; + uint32_t rpmSamples = 0; + + // Decode all telemetry data now to discharge interrupt from this task + for (uint8_t k = 0; k < motorCount; k++) { + dshotTelemetryType_t type; + uint32_t value; + + dshot_decode_telemetry_value(k, &value, &type); + + if (value != DSHOT_TELEMETRY_INVALID) { + dshotUpdateTelemetryData(k, type, value); + + if (type == DSHOT_TELEMETRY_TYPE_eRPM) { + rpmTotal += value; + rpmSamples++; + } + } + } + + // Update average + if (rpmSamples > 0) { + dshotTelemetryState.averageRpm = rpmTotal / rpmSamples; + } + + // Set state to processed + dshotTelemetryState.rawValueState = DSHOT_RAW_VALUE_STATE_PROCESSED; + } + return dshotTelemetryState.motorState[index].telemetryData[DSHOT_TELEMETRY_TYPE_eRPM]; } @@ -158,42 +301,9 @@ bool isDshotTelemetryActive(void) return false; } -dshotTelemetryType_t dshot_get_telemetry_type_to_decode(uint8_t motorIndex) -{ - dshotTelemetryType_t type; - - // Prepare the allowed telemetry to be read - if ((dshotTelemetryState.motorState[motorIndex].telemetryTypes & DSHOT_EXTENDED_TELEMETRY_MASK) != 0) { - // Allow decoding all kind of telemetry frames - type = DSHOT_TELEMETRY_TYPE_COUNT; - } else if (dshotCommandGetCurrent(motorIndex) == DSHOT_CMD_EXTENDED_TELEMETRY_ENABLE) { - // No empty command queue check needed because responses are always originated after a request - // Always checking the current existing request - // Allow decoding only extended telemetry enable frame (during arming) - type = DSHOT_TELEMETRY_TYPE_STATE_EVENTS; - } else { - // Allow decoding only eRPM telemetry frame - type = DSHOT_TELEMETRY_TYPE_eRPM; - } - - return type; -} - void dshotCleanTelemetryData(void) { - memset(dshotTelemetryState.motorState, 0, MAX_SUPPORTED_MOTORS * sizeof(dshotTelemetryMotorState_t)); -} - -FAST_CODE void dshotUpdateTelemetryData(uint8_t motorIndex, dshotTelemetryType_t type, uint16_t value) -{ - // Update telemetry data - dshotTelemetryState.motorState[motorIndex].telemetryData[type] = value; - dshotTelemetryState.motorState[motorIndex].telemetryTypes |= (1 << type); - - // Update max temp - if ((type == DSHOT_TELEMETRY_TYPE_TEMPERATURE) && (value > dshotTelemetryState.motorState[motorIndex].maxTemp)) { - dshotTelemetryState.motorState[motorIndex].maxTemp = value; - } + memset(&dshotTelemetryState, 0, sizeof(dshotTelemetryState)); } uint32_t erpmToRpm(uint16_t erpm) @@ -285,124 +395,3 @@ void validateAndfixMotorOutputReordering(uint8_t *array, const unsigned size) } } } - -static uint32_t dshot_decode_eRPM_telemetry_value(uint32_t value) -{ - // eRPM range - 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 DSHOT_TELEMETRY_INVALID; - } - - // Convert period to erpm * 100 - return (1000000 * 60 / 100 + value / 2) / value; -} - -uint32_t dshot_decode_telemetry_value(uint32_t value, dshotTelemetryType_t *type) -{ - uint32_t decoded; - - switch (*type) { - - case DSHOT_TELEMETRY_TYPE_eRPM: - // Expect only eRPM telemetry - decoded = dshot_decode_eRPM_telemetry_value(value); - break; - - case DSHOT_TELEMETRY_TYPE_STATE_EVENTS: - // Expect an extended telemetry enable frame - if (value == 0x0E00) { - // Decode - decoded = 0; - - // Set telemetry type - *type = DSHOT_TELEMETRY_TYPE_STATE_EVENTS; - } else { - // Unexpected frame - decoded = DSHOT_TELEMETRY_INVALID; - - // Set telemetry type - *type = DSHOT_TELEMETRY_TYPE_eRPM; - } - break; - - default: - // Extended DSHOT telemetry - switch (value & 0x0f00) { - - case 0x0200: - // Temperature range (in degree Celsius, just like Blheli_32 and KISS) - decoded = value & 0x00ff; - - // Set telemetry type - *type = DSHOT_TELEMETRY_TYPE_TEMPERATURE; - break; - - case 0x0400: - // Voltage range (0-63,75V step 0,25V) - decoded = value & 0x00ff; - - // Set telemetry type - *type = DSHOT_TELEMETRY_TYPE_VOLTAGE; - break; - - case 0x0600: - // Current range (0-255A step 1A) - decoded = value & 0x00ff; - - // Set telemetry type - *type = DSHOT_TELEMETRY_TYPE_CURRENT; - break; - - case 0x0800: - // Debug 1 value - decoded = value & 0x00ff; - - // Set telemetry type - *type = DSHOT_TELEMETRY_TYPE_DEBUG1; - break; - - case 0x0A00: - // Debug 2 value - decoded = value & 0x00ff; - - // Set telemetry type - *type = DSHOT_TELEMETRY_TYPE_DEBUG2; - break; - - case 0x0C00: - // Debug 3 value - decoded = value & 0x00ff; - - // Set telemetry type - *type = DSHOT_TELEMETRY_TYPE_DEBUG3; - break; - - case 0x0E00: - // State / events - decoded = value & 0x00ff; - - // Set telemetry type - *type = DSHOT_TELEMETRY_TYPE_STATE_EVENTS; - break; - - default: - // Decode as eRPM - decoded = dshot_decode_eRPM_telemetry_value(value); - - // Set telemetry type - *type = DSHOT_TELEMETRY_TYPE_eRPM; - break; - - } - break; - - } - - return decoded; -} diff --git a/src/main/drivers/dshot.h b/src/main/drivers/dshot.h index fb41b87de0..27b6733386 100644 --- a/src/main/drivers/dshot.h +++ b/src/main/drivers/dshot.h @@ -54,7 +54,8 @@ typedef struct dshotTelemetryQuality_s { extern dshotTelemetryQuality_t dshotTelemetryQuality[MAX_SUPPORTED_MOTORS]; #endif // USE_DSHOT_TELEMETRY_STATS -#define DSHOT_EXTENDED_TELEMETRY_MASK (~(1<portInputBuffer, bbMotors[motorIndex].bbPort->portInputCount - bbDMA_Count(bbMotors[motorIndex].bbPort), - bbMotors[motorIndex].pinIndex, &type); + bbMotors[motorIndex].pinIndex); #else - uint32_t value = decode_bb( + uint32_t rawValue = decode_bb( bbMotors[motorIndex].bbPort->portInputBuffer, bbMotors[motorIndex].bbPort->portInputCount - bbDMA_Count(bbMotors[motorIndex].bbPort), - bbMotors[motorIndex].pinIndex, &type); + bbMotors[motorIndex].pinIndex); #endif - if (value == DSHOT_TELEMETRY_NOEDGE) { + if (rawValue == DSHOT_TELEMETRY_NOEDGE) { continue; } dshotTelemetryState.readCount++; - if (value != DSHOT_TELEMETRY_INVALID) { - if (type == DSHOT_TELEMETRY_TYPE_eRPM) { - totalErpm += value; - totalMotorsWithErpmData++; + if (rawValue != DSHOT_TELEMETRY_INVALID) { + // Check EDT enable or store raw value + if ((rawValue == 0x0E00) && (dshotCommandGetCurrent(motorIndex) == DSHOT_CMD_EXTENDED_TELEMETRY_ENABLE)) { + dshotTelemetryState.motorState[motorIndex].telemetryTypes = DSHOT_TELEMETRY_TYPE_STATE_EVENTS; + } else { + dshotTelemetryState.motorState[motorIndex].rawValue = rawValue; } - dshotUpdateTelemetryData(motorIndex, type, value); + if (motorIndex < 4) { - DEBUG_SET(DEBUG_DSHOT_RPM_TELEMETRY, motorIndex, value); + DEBUG_SET(DEBUG_DSHOT_RPM_TELEMETRY, motorIndex, rawValue); } } else { dshotTelemetryState.invalidPacketCount++; } #ifdef USE_DSHOT_TELEMETRY_STATS - updateDshotTelemetryQuality(&dshotTelemetryQuality[motorIndex], value != DSHOT_TELEMETRY_INVALID, currentTimeMs); + updateDshotTelemetryQuality(&dshotTelemetryQuality[motorIndex], rawValue != DSHOT_TELEMETRY_INVALID, currentTimeMs); #endif } - // Calculate average when possible - if (totalMotorsWithErpmData > 0) { - dshotTelemetryState.averageRpm = erpmToRpm(totalErpm / totalMotorsWithErpmData); - } + dshotTelemetryState.rawValueState = DSHOT_RAW_VALUE_STATE_NOT_PROCESSED; } #endif for (int i = 0; i < usedMotorPorts; i++) { diff --git a/src/main/drivers/dshot_bitbang_decode.c b/src/main/drivers/dshot_bitbang_decode.c index b0cb630c41..388b4dc32c 100644 --- a/src/main/drivers/dshot_bitbang_decode.c +++ b/src/main/drivers/dshot_bitbang_decode.c @@ -43,7 +43,7 @@ int sequenceIndex = 0; #endif -static uint32_t decode_bb_value(uint32_t value, uint16_t buffer[], uint32_t count, uint32_t bit, dshotTelemetryType_t *type) +static uint32_t decode_bb_value(uint32_t value, uint16_t buffer[], uint32_t count, uint32_t bit) { #ifndef DEBUG_BBDECODE UNUSED(buffer); @@ -75,14 +75,14 @@ static uint32_t decode_bb_value(uint32_t value, uint16_t buffer[], uint32_t coun #endif value = DSHOT_TELEMETRY_INVALID; } else { - value = dshot_decode_telemetry_value(decodedValue >> 4, type); + value = decodedValue >> 4; } return value; } -uint32_t decode_bb_bitband( uint16_t buffer[], uint32_t count, uint32_t bit, dshotTelemetryType_t *type) +uint32_t decode_bb_bitband( uint16_t buffer[], uint32_t count, uint32_t bit) { #ifdef DEBUG_BBDECODE memset(sequence, 0, sizeof(sequence)); @@ -193,10 +193,10 @@ uint32_t decode_bb_bitband( uint16_t buffer[], uint32_t count, uint32_t bit, dsh value |= 1 << (nlen - 1); } - return decode_bb_value(value, buffer, count, bit, type); + return decode_bb_value(value, buffer, count, bit); } -FAST_CODE uint32_t decode_bb( uint16_t buffer[], uint32_t count, uint32_t bit, dshotTelemetryType_t *type) +FAST_CODE uint32_t decode_bb( uint16_t buffer[], uint32_t count, uint32_t bit) { #ifdef DEBUG_BBDECODE memset(sequence, 0, sizeof(sequence)); @@ -286,7 +286,7 @@ FAST_CODE uint32_t decode_bb( uint16_t buffer[], uint32_t count, uint32_t bit, d value |= 1 << (nlen - 1); } - return decode_bb_value(value, buffer, count, bit, type); + return decode_bb_value(value, buffer, count, bit); } #endif diff --git a/src/main/drivers/dshot_bitbang_decode.h b/src/main/drivers/dshot_bitbang_decode.h index a6854f817d..cddb5764b8 100644 --- a/src/main/drivers/dshot_bitbang_decode.h +++ b/src/main/drivers/dshot_bitbang_decode.h @@ -24,8 +24,8 @@ -uint32_t decode_bb(uint16_t buffer[], uint32_t count, uint32_t mask, dshotTelemetryType_t *type); -uint32_t decode_bb_bitband( uint16_t buffer[], uint32_t count, uint32_t bit, dshotTelemetryType_t *type); +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 diff --git a/src/main/drivers/pwm_output_dshot_shared.c b/src/main/drivers/pwm_output_dshot_shared.c index b438b57f4a..ffa5b9a334 100644 --- a/src/main/drivers/pwm_output_dshot_shared.c +++ b/src/main/drivers/pwm_output_dshot_shared.c @@ -127,7 +127,7 @@ 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, dshotTelemetryType_t *type) +static uint32_t decodeTelemetryPacket(uint32_t buffer[], uint32_t count) { uint32_t value = 0; uint32_t oldValue = buffer[0]; @@ -170,7 +170,7 @@ static uint32_t decodeTelemetryPacket(uint32_t buffer[], uint32_t count, dshotTe return DSHOT_TELEMETRY_INVALID; } - return dshot_decode_telemetry_value(decodedValue >> 4, type); + return decodedValue >> 4; } #endif @@ -186,9 +186,6 @@ FAST_CODE_NOINLINE bool pwmStartDshotMotorUpdate(void) const timeMs_t currentTimeMs = millis(); #endif const timeUs_t currentUs = micros(); - dshotTelemetryType_t type; - uint32_t totalErpm = 0; - uint32_t totalMotorsWithErpmData = 0; for (int i = 0; i < dshotPwmDevice.count; i++) { timeDelta_t usSinceInput = cmpTimeUs(currentUs, inputStampUs); @@ -208,27 +205,26 @@ FAST_CODE_NOINLINE bool pwmStartDshotMotorUpdate(void) TIM_DMACmd(dmaMotors[i].timerHardware->tim, dmaMotors[i].timerDmaSource, DISABLE); #endif - uint16_t value; + uint16_t rawValue; if (edges > MIN_GCR_EDGES) { dshotTelemetryState.readCount++; - // Get dshot telemetry type to decode - type = dshot_get_telemetry_type_to_decode(i); - - value = decodeTelemetryPacket(dmaMotors[i].dmaBuffer, edges, &type); + rawValue = decodeTelemetryPacket(dmaMotors[i].dmaBuffer, edges); #ifdef USE_DSHOT_TELEMETRY_STATS bool validTelemetryPacket = false; #endif - if (value != DSHOT_TELEMETRY_INVALID) { - if (type == DSHOT_TELEMETRY_TYPE_eRPM) { - totalErpm += value; - totalMotorsWithErpmData++; + if (rawValue != DSHOT_TELEMETRY_INVALID) { + // Check EDT enable or store raw value + if ((rawValue == 0x0E00) && (dshotCommandGetCurrent(i) == DSHOT_CMD_EXTENDED_TELEMETRY_ENABLE)) { + dshotTelemetryState.motorState[i].telemetryTypes = DSHOT_TELEMETRY_TYPE_STATE_EVENTS; + } else { + dshotTelemetryState.motorState[i].rawValue = rawValue; } - dshotUpdateTelemetryData(value, type, value); + if (i < 4) { - DEBUG_SET(DEBUG_DSHOT_RPM_TELEMETRY, i, value); + DEBUG_SET(DEBUG_DSHOT_RPM_TELEMETRY, i, rawValue); } #ifdef USE_DSHOT_TELEMETRY_STATS validTelemetryPacket = true; @@ -247,9 +243,7 @@ FAST_CODE_NOINLINE bool pwmStartDshotMotorUpdate(void) pwmDshotSetDirectionOutput(&dmaMotors[i]); } - if (totalMotorsWithErpmData > 0) { - dshotTelemetryState.averageRpm = erpmToRpm(totalErpm / totalMotorsWithErpmData); - } + dshotTelemetryState.rawValueState = DSHOT_RAW_VALUE_STATE_NOT_PROCESSED; inputStampUs = 0; dshotEnableChannels(dshotPwmDevice.count); return true; diff --git a/src/main/fc/core.c b/src/main/fc/core.c index e57f3e8e4e..6473655cca 100644 --- a/src/main/fc/core.c +++ b/src/main/fc/core.c @@ -509,29 +509,32 @@ void tryArm(void) return; } - + if (isMotorProtocolDshot()) { #if defined(USE_ESC_SENSOR) && defined(USE_DSHOT_TELEMETRY) - // Try to activate extended DSHOT telemetry only if no esc sensor exists and dshot telemetry is active - if (isMotorProtocolDshot() && !featureIsEnabled(FEATURE_ESC_SENSOR) && motorConfig()->dev.useDshotTelemetry) { - dshotCleanTelemetryData(); - dshotCommandWrite(ALL_MOTORS, getMotorCount(), DSHOT_CMD_EXTENDED_TELEMETRY_ENABLE, DSHOT_CMD_TYPE_INLINE); - } + // Try to activate extended DSHOT telemetry only if no esc sensor exists and dshot telemetry is active + if (!featureIsEnabled(FEATURE_ESC_SENSOR) && motorConfig()->dev.useDshotTelemetry) { + dshotCleanTelemetryData(); + if (motorConfig()->dev.useDshotEdt) { + dshotCommandWrite(ALL_MOTORS, getMotorCount(), DSHOT_CMD_EXTENDED_TELEMETRY_ENABLE, DSHOT_CMD_TYPE_INLINE); + } + } #endif - if (isMotorProtocolDshot() && isModeActivationConditionPresent(BOXFLIPOVERAFTERCRASH)) { - // Set motor spin direction - if (!(IS_RC_MODE_ACTIVE(BOXFLIPOVERAFTERCRASH) || (tryingToArm == ARMING_DELAYED_CRASHFLIP))) { - flipOverAfterCrashActive = false; - if (!featureIsEnabled(FEATURE_3D)) { - dshotCommandWrite(ALL_MOTORS, getMotorCount(), DSHOT_CMD_SPIN_DIRECTION_NORMAL, DSHOT_CMD_TYPE_INLINE); - } - } else { - flipOverAfterCrashActive = true; + if (isModeActivationConditionPresent(BOXFLIPOVERAFTERCRASH)) { + // Set motor spin direction + if (!(IS_RC_MODE_ACTIVE(BOXFLIPOVERAFTERCRASH) || (tryingToArm == ARMING_DELAYED_CRASHFLIP))) { + flipOverAfterCrashActive = false; + if (!featureIsEnabled(FEATURE_3D)) { + dshotCommandWrite(ALL_MOTORS, getMotorCount(), DSHOT_CMD_SPIN_DIRECTION_NORMAL, DSHOT_CMD_TYPE_INLINE); + } + } else { + flipOverAfterCrashActive = true; #ifdef USE_RUNAWAY_TAKEOFF - runawayTakeoffCheckDisabled = false; + runawayTakeoffCheckDisabled = false; #endif - if (!featureIsEnabled(FEATURE_3D)) { - dshotCommandWrite(ALL_MOTORS, getMotorCount(), DSHOT_CMD_SPIN_DIRECTION_REVERSED, DSHOT_CMD_TYPE_INLINE); + if (!featureIsEnabled(FEATURE_3D)) { + dshotCommandWrite(ALL_MOTORS, getMotorCount(), DSHOT_CMD_SPIN_DIRECTION_REVERSED, DSHOT_CMD_TYPE_INLINE); + } } } } diff --git a/src/main/pg/motor.h b/src/main/pg/motor.h index a295ad0e96..a2ea0fb551 100644 --- a/src/main/pg/motor.h +++ b/src/main/pg/motor.h @@ -44,6 +44,7 @@ typedef struct motorDevConfig_s { uint8_t useUnsyncedPwm; uint8_t useBurstDshot; uint8_t useDshotTelemetry; + uint8_t useDshotEdt; ioTag_t ioTags[MAX_SUPPORTED_MOTORS]; uint8_t motorTransportProtocol; uint8_t useDshotBitbang;