diff --git a/src/main/config/config.c b/src/main/config/config.c index c145c78e13..ccaca2eb17 100644 --- a/src/main/config/config.c +++ b/src/main/config/config.c @@ -284,7 +284,7 @@ static void validateAndFixConfig(void) } } - if ((motorConfig()->dev.motorProtocol == MOTOR_PROTOCOL_STANDARD) && (motorConfig()->dev.motorPwmRate > BRUSHLESS_MOTORS_PWM_RATE)) { + if ((motorConfig()->dev.motorProtocol == MOTOR_PROTOCOL_PWM50HZ ) && (motorConfig()->dev.motorPwmRate > BRUSHLESS_MOTORS_PWM_RATE)) { motorConfigMutable()->dev.motorPwmRate = BRUSHLESS_MOTORS_PWM_RATE; } @@ -598,7 +598,7 @@ void validateAndFixGyroConfig(void) } #endif // USE_DSHOT && USE_PID_DENOM_CHECK switch (motorConfig()->dev.motorProtocol) { - case MOTOR_PROTOCOL_STANDARD: + case MOTOR_PROTOCOL_PWM50HZ : motorUpdateRestriction = 1.0f / BRUSHLESS_MOTORS_PWM_RATE; break; case MOTOR_PROTOCOL_ONESHOT125: @@ -624,7 +624,7 @@ void validateAndFixGyroConfig(void) bool configuredMotorProtocolDshot = false; checkMotorProtocolEnabled(&motorConfig()->dev, &configuredMotorProtocolDshot); // Prevent overriding the max rate of motors - if (!configuredMotorProtocolDshot && motorConfig()->dev.motorProtocol != MOTOR_PROTOCOL_STANDARD) { + if (!configuredMotorProtocolDshot && motorConfig()->dev.motorProtocol != MOTOR_PROTOCOL_PWM50HZ ) { const uint32_t maxEscRate = lrintf(1.0f / motorUpdateRestriction); motorConfigMutable()->dev.motorPwmRate = MIN(motorConfig()->dev.motorPwmRate, maxEscRate); } diff --git a/src/main/drivers/dshot_command.c b/src/main/drivers/dshot_command.c index aca08ce337..33c29282ca 100644 --- a/src/main/drivers/dshot_command.c +++ b/src/main/drivers/dshot_command.c @@ -139,7 +139,7 @@ static dshotCommandControl_t* addCommand(void) static bool allMotorsAreIdle(void) { for (unsigned i = 0; i < motorDeviceCount(); i++) { - if (motorIsMotorIdle(i)) { + if (!motorIsMotorIdle(i)) { return false; } } diff --git a/src/main/drivers/motor.c b/src/main/drivers/motor.c index 3d64d07ebb..82479dc558 100644 --- a/src/main/drivers/motor.c +++ b/src/main/drivers/motor.c @@ -58,7 +58,7 @@ void motorShutdown(void) motorDevice->initialized = false; switch (motorConfig()->dev.motorProtocol) { - case MOTOR_PROTOCOL_STANDARD: + case MOTOR_PROTOCOL_PWM50HZ : case MOTOR_PROTOCOL_ONESHOT125: case MOTOR_PROTOCOL_ONESHOT42: case MOTOR_PROTOCOL_MULTISHOT: @@ -125,9 +125,9 @@ void motorWriteAll(float *values) #endif } -void motorRequestTelemetry(uint8_t index) +void motorRequestTelemetry(unsigned index) { - if (index > motorDevice->count - 1) { + if (index >= motorDevice->count) { return; } @@ -170,7 +170,7 @@ bool checkMotorProtocolEnabled(const motorDevConfig_t *motorDevConfig, bool *isP bool isDshot = false; switch (motorDevConfig->motorProtocol) { - case MOTOR_PROTOCOL_STANDARD: + case MOTOR_PROTOCOL_PWM50HZ : case MOTOR_PROTOCOL_ONESHOT125: case MOTOR_PROTOCOL_ONESHOT42: case MOTOR_PROTOCOL_MULTISHOT: @@ -248,13 +248,7 @@ static void motorDisableNull(void) { } -static bool motorIsEnabledNull(uint8_t index) -{ - UNUSED(index); - return false; -} - -static bool motorIsIdleNull(uint8_t index) +static bool motorIsEnabledNull(unsigned index) { UNUSED(index); return false; @@ -309,7 +303,8 @@ static const motorVTable_t motorNullVTable = { .convertExternalToMotor = motorConvertFromExternalNull, .convertMotorToExternal = motorConvertToExternalNull, .shutdown = motorShutdownNull, - .isMotorIdle = motorIsIdleNull, + .requestTelemetry = NULL, + .isMotorIdle = NULL, }; static motorDevice_t motorNullDevice = { @@ -407,7 +402,7 @@ bool motorIsMotorEnabled(uint8_t index) return motorDevice->vTable.isMotorEnabled(index); } -bool motorIsMotorIdle(uint8_t index) +bool motorIsMotorIdle(unsigned index) { return motorDevice->vTable.isMotorIdle ? motorDevice->vTable.isMotorIdle(index) : false; } diff --git a/src/main/drivers/motor.h b/src/main/drivers/motor.h index 4cf936e2b5..3c451882fe 100644 --- a/src/main/drivers/motor.h +++ b/src/main/drivers/motor.h @@ -35,7 +35,7 @@ void motorUpdateCompleteNull(void); void motorPostInit(); void motorWriteAll(float *values); -void motorRequestTelemetry(uint8_t index); +void motorRequestTelemetry(unsigned index); void motorInitEndpoints(const motorConfig_t *motorConfig, float outputLimit, float *outputLow, float *outputHigh, float *disarm, float *deadbandMotor3DHigh, float *deadbandMotor3DLow); @@ -56,7 +56,7 @@ void motorEnable(void); float motorEstimateMaxRpm(void); bool motorIsEnabled(void); bool motorIsMotorEnabled(uint8_t index); -bool motorIsMotorIdle(uint8_t index); +bool motorIsMotorIdle(unsigned index); timeMs_t motorGetMotorEnableTimeMs(void); void motorShutdown(void); // Replaces stopPwmAllMotors diff --git a/src/main/drivers/motor_types.h b/src/main/drivers/motor_types.h index 764e3150ee..33cd100b8f 100644 --- a/src/main/drivers/motor_types.h +++ b/src/main/drivers/motor_types.h @@ -28,7 +28,7 @@ #define MOTOR_OUTPUT_LIMIT_PERCENT_MAX 100 typedef enum { - MOTOR_PROTOCOL_STANDARD = 0, + MOTOR_PROTOCOL_PWM50HZ = 0, MOTOR_PROTOCOL_ONESHOT125, MOTOR_PROTOCOL_ONESHOT42, MOTOR_PROTOCOL_MULTISHOT, @@ -49,7 +49,7 @@ typedef struct motorVTable_s { uint16_t (*convertMotorToExternal)(float motorValue); bool (*enable)(void); void (*disable)(void); - bool (*isMotorEnabled)(uint8_t index); + bool (*isMotorEnabled)(unsigned index); bool (*telemetryWait)(void); bool (*decodeTelemetry)(void); void (*updateInit)(void); @@ -57,10 +57,10 @@ typedef struct motorVTable_s { void (*writeInt)(uint8_t index, uint16_t value); void (*updateComplete)(void); void (*shutdown)(void); - bool (*isMotorIdle)(uint8_t index); + bool (*isMotorIdle)(unsigned index); // Digital commands - void (*requestTelemetry)(uint8_t index); + void (*requestTelemetry)(unsigned index); } motorVTable_t; typedef struct motorDevice_s { diff --git a/src/main/pg/motor.c b/src/main/pg/motor.c index 86113ee32a..80f75c98c7 100644 --- a/src/main/pg/motor.c +++ b/src/main/pg/motor.c @@ -51,14 +51,14 @@ PG_REGISTER_WITH_RESET_FN(motorConfig_t, motorConfig, PG_MOTOR_CONFIG, 3); void pgResetFn_motorConfig(motorConfig_t *motorConfig) { -#ifdef BRUSHED_MOTORS +#ifdef USE_BRUSHED_MOTORS motorConfig->dev.motorPwmRate = BRUSHED_MOTORS_PWM_RATE; motorConfig->dev.motorProtocol = MOTOR_PROTOCOL_BRUSHED; motorConfig->dev.useUnsyncedUpdate = true; #else motorConfig->dev.motorPwmRate = BRUSHLESS_MOTORS_PWM_RATE; #ifndef USE_DSHOT - if (motorConfig->dev.motorProtocol == MOTOR_PROTOCOL_STANDARD) { + if (motorConfig->dev.motorProtocol == MOTOR_PROTOCOL_PWM50HZ ) { motorConfig->dev.useUnsyncedUpdate = true; } motorConfig->dev.motorProtocol = MOTOR_PROTOCOL_DISABLED; diff --git a/src/main/pg/motor.h b/src/main/pg/motor.h index d13b345671..e829b15472 100644 --- a/src/main/pg/motor.h +++ b/src/main/pg/motor.h @@ -33,12 +33,14 @@ #define BRUSHLESS_MOTORS_PWM_RATE 480 #endif +//TODO: Timers are platform specific. This should be moved to platform specific code. typedef enum { DSHOT_BITBANGED_TIMER_AUTO = 0, DSHOT_BITBANGED_TIMER_TIM1, DSHOT_BITBANGED_TIMER_TIM8, } dshotBitbangedTimer_e; +//TODO: DMAR is platform specific. This should be moved to platform specific code. typedef enum { DSHOT_DMAR_OFF, DSHOT_DMAR_ON, @@ -51,7 +53,7 @@ typedef enum { } dshotTelemetry_e; typedef struct motorDevConfig_s { - uint16_t motorPwmRate; // The update rate of motor outputs (50-498Hz) + uint16_t motorPwmRate; // The update rate of motor outputs (50-498Hz) uint8_t motorProtocol; // Pwm Protocol uint8_t motorInversion; // Active-High vs Active-Low. Useful for brushed FCs converted for brushless operation uint8_t useUnsyncedUpdate; diff --git a/src/platform/APM32/dshot_bitbang.c b/src/platform/APM32/dshot_bitbang.c index 331e48c064..bac6caff8b 100644 --- a/src/platform/APM32/dshot_bitbang.c +++ b/src/platform/APM32/dshot_bitbang.c @@ -665,7 +665,7 @@ static void bbShutdown(void) return; } -static bool bbIsMotorEnabled(uint8_t index) +static bool bbIsMotorEnabled(unsigned index) { return bbMotors[index].enabled; } diff --git a/src/platform/APM32/pwm_output_apm32.c b/src/platform/APM32/pwm_output_apm32.c index b95d4e42de..5250877923 100644 --- a/src/platform/APM32/pwm_output_apm32.c +++ b/src/platform/APM32/pwm_output_apm32.c @@ -116,7 +116,7 @@ bool pwmEnableMotors(void) return (motorPwmVTable.write != &pwmWriteUnused); } -bool pwmIsMotorEnabled(uint8_t index) +bool pwmIsMotorEnabled(unsigned index) { return motors[index].enabled; } @@ -151,6 +151,8 @@ static motorVTable_t motorPwmVTable = { .shutdown = pwmShutdownPulsesForAllMotors, .convertExternalToMotor = pwmConvertFromExternal, .convertMotorToExternal = pwmConvertToExternal, + .requestTelemetry = NULL, + .isMotorIdle = NULL, }; motorDevice_t *motorPwmDevInit(const motorDevConfig_t *motorConfig, uint16_t idlePulse, uint8_t motorCount, bool useUnsyncedUpdate) @@ -180,7 +182,7 @@ motorDevice_t *motorPwmDevInit(const motorDevConfig_t *motorConfig, uint16_t idl useUnsyncedUpdate = true; idlePulse = 0; break; - case MOTOR_PROTOCOL_STANDARD: + case MOTOR_PROTOCOL_PWM50HZ : sMin = 1e-3f; sLen = 1e-3f; useUnsyncedUpdate = true; diff --git a/src/platform/APM32/pwm_output_dshot_apm32.c b/src/platform/APM32/pwm_output_dshot_apm32.c index 30ae7bdab0..64738d1b97 100644 --- a/src/platform/APM32/pwm_output_dshot_apm32.c +++ b/src/platform/APM32/pwm_output_dshot_apm32.c @@ -47,9 +47,9 @@ #ifdef USE_DSHOT_TELEMETRY -void dshotEnableChannels(uint8_t motorCount) +void dshotEnableChannels(unsigned motorCount) { - for (int i = 0; i < motorCount; i++) { + for (unsigned i = 0; i < motorCount; i++) { if (dmaMotors[i].output & TIMER_OUTPUT_N_CHANNEL) { DDL_TMR_CC_EnableChannel(dmaMotors[i].timerHardware->tim, dmaMotors[i].llChannel << 4); } else { diff --git a/src/platform/AT32/dshot_bitbang.c b/src/platform/AT32/dshot_bitbang.c index a86bef1125..20eb05cd22 100644 --- a/src/platform/AT32/dshot_bitbang.c +++ b/src/platform/AT32/dshot_bitbang.c @@ -657,7 +657,7 @@ static void bbShutdown(void) return; } -static bool bbIsMotorEnabled(uint8_t index) +static bool bbIsMotorEnabled(unsigned index) { return bbMotors[index].enabled; } diff --git a/src/platform/AT32/pwm_output_at32bsp.c b/src/platform/AT32/pwm_output_at32bsp.c index 49779a8752..62da81f576 100644 --- a/src/platform/AT32/pwm_output_at32bsp.c +++ b/src/platform/AT32/pwm_output_at32bsp.c @@ -112,7 +112,7 @@ bool pwmEnableMotors(void) return (motorPwmVTable.write != &pwmWriteUnused); } -bool pwmIsMotorEnabled(uint8_t index) +bool pwmIsMotorEnabled(unsigned index) { return motors[index].enabled; } @@ -147,6 +147,8 @@ static motorVTable_t motorPwmVTable = { .shutdown = pwmShutdownPulsesForAllMotors, .convertExternalToMotor = pwmConvertFromExternal, .convertMotorToExternal = pwmConvertToExternal, + .requestTelemetry = NULL, + .isMotorIdle = NULL, }; motorDevice_t *motorPwmDevInit(const motorDevConfig_t *motorConfig, uint16_t idlePulse, uint8_t motorCount, bool useUnsyncedUpdate) @@ -176,7 +178,7 @@ motorDevice_t *motorPwmDevInit(const motorDevConfig_t *motorConfig, uint16_t idl useUnsyncedUpdate = true; idlePulse = 0; break; - case MOTOR_PROTOCOL_STANDARD: + case MOTOR_PROTOCOL_PWM50HZ : sMin = 1e-3f; sLen = 1e-3f; useUnsyncedUpdate = true; diff --git a/src/platform/AT32/pwm_output_dshot.c b/src/platform/AT32/pwm_output_dshot.c index 68a2c23d0b..892a995d6a 100644 --- a/src/platform/AT32/pwm_output_dshot.c +++ b/src/platform/AT32/pwm_output_dshot.c @@ -114,9 +114,9 @@ tmr_channel_select_type toCHSelectType(const uint8_t bfChannel, const bool useNC * Called once for every dshot update if telemetry is being used (not just enabled by #def) * Called from pwm_output_dshot_shared.c pwmTelemetryDecode */ -void dshotEnableChannels(uint8_t motorCount) +void dshotEnableChannels(unsigned motorCount) { - for (int i = 0; i < motorCount; i++) { + for (unsigned i = 0; i < motorCount; i++) { tmr_primary_mode_select(dmaMotors[i].timerHardware->tim, TMR_PRIMARY_SEL_COMPARE); tmr_channel_select_type atCh = toCHSelectType(dmaMotors[i].timerHardware->channel, dmaMotors[i].output & TIMER_OUTPUT_N_CHANNEL); diff --git a/src/platform/SIMULATOR/sitl.c b/src/platform/SIMULATOR/sitl.c index b26a0d0647..29a5dee8dd 100644 --- a/src/platform/SIMULATOR/sitl.c +++ b/src/platform/SIMULATOR/sitl.c @@ -575,7 +575,7 @@ static void pwmShutdownPulsesForAllMotors(void) motorPwmDevice.enabled = false; } -bool pwmIsMotorEnabled(uint8_t index) +bool pwmIsMotorEnabled(unsigned index) { return motors[index].enabled; } @@ -624,6 +624,8 @@ static motorDevice_t motorPwmDevice = { .writeInt = pwmWriteMotorInt, .updateComplete = pwmCompleteMotorUpdate, .shutdown = pwmShutdownPulsesForAllMotors, + .requestTelemetry = NULL, + .isMotorIdle = NULL, } }; diff --git a/src/platform/STM32/dshot_bitbang.c b/src/platform/STM32/dshot_bitbang.c index 364ccec954..0990848520 100644 --- a/src/platform/STM32/dshot_bitbang.c +++ b/src/platform/STM32/dshot_bitbang.c @@ -697,7 +697,7 @@ static void bbShutdown(void) return; } -static bool bbIsMotorEnabled(uint8_t index) +static bool bbIsMotorEnabled(unsigned index) { return bbMotors[index].enabled; } diff --git a/src/platform/STM32/pwm_output.c b/src/platform/STM32/pwm_output.c index dc86e6daa7..bea0a9b2bb 100644 --- a/src/platform/STM32/pwm_output.c +++ b/src/platform/STM32/pwm_output.c @@ -144,7 +144,7 @@ bool pwmEnableMotors(void) return (motorPwmVTable.write != &pwmWriteUnused); } -bool pwmIsMotorEnabled(uint8_t index) +bool pwmIsMotorEnabled(unsigned index) { return motors[index].enabled; } @@ -179,6 +179,8 @@ static motorVTable_t motorPwmVTable = { .shutdown = pwmShutdownPulsesForAllMotors, .convertExternalToMotor = pwmConvertFromExternal, .convertMotorToExternal = pwmConvertToExternal, + .requestTelemetry = NULL, + .isMotorIdle = NULL, }; motorDevice_t *motorPwmDevInit(const motorDevConfig_t *motorConfig, uint16_t idlePulse, uint8_t motorCount, bool useUnsyncedUpdate) @@ -208,7 +210,7 @@ motorDevice_t *motorPwmDevInit(const motorDevConfig_t *motorConfig, uint16_t idl useUnsyncedUpdate = true; idlePulse = 0; break; - case MOTOR_PROTOCOL_STANDARD: + case MOTOR_PROTOCOL_PWM50HZ : sMin = 1e-3f; sLen = 1e-3f; useUnsyncedUpdate = true; diff --git a/src/platform/STM32/pwm_output_dshot.c b/src/platform/STM32/pwm_output_dshot.c index 1119471f75..bddbba54b4 100644 --- a/src/platform/STM32/pwm_output_dshot.c +++ b/src/platform/STM32/pwm_output_dshot.c @@ -48,9 +48,9 @@ #ifdef USE_DSHOT_TELEMETRY -void dshotEnableChannels(uint8_t motorCount) +void dshotEnableChannels(unsigned motorCount) { - for (int i = 0; i < motorCount; i++) { + for (unsigned i = 0; i < motorCount; i++) { if (dmaMotors[i].output & TIMER_OUTPUT_N_CHANNEL) { TIM_CCxNCmd(dmaMotors[i].timerHardware->tim, dmaMotors[i].timerHardware->channel, TIM_CCxN_Enable); } else { diff --git a/src/platform/STM32/pwm_output_dshot_hal.c b/src/platform/STM32/pwm_output_dshot_hal.c index 1ac173f90d..2d313d778c 100644 --- a/src/platform/STM32/pwm_output_dshot_hal.c +++ b/src/platform/STM32/pwm_output_dshot_hal.c @@ -47,9 +47,9 @@ #ifdef USE_DSHOT_TELEMETRY -void dshotEnableChannels(uint8_t motorCount) +void dshotEnableChannels(unsigned motorCount) { - for (int i = 0; i < motorCount; i++) { + for (unsigned i = 0; i < motorCount; i++) { if (dmaMotors[i].output & TIMER_OUTPUT_N_CHANNEL) { LL_EX_TIM_CC_EnableNChannel(dmaMotors[i].timerHardware->tim, dmaMotors[i].llChannel); } else { diff --git a/src/platform/common/stm32/dshot_bitbang_impl.h b/src/platform/common/stm32/dshot_bitbang_impl.h index 9331a732f4..ab23eeb0ac 100644 --- a/src/platform/common/stm32/dshot_bitbang_impl.h +++ b/src/platform/common/stm32/dshot_bitbang_impl.h @@ -277,5 +277,5 @@ void bbDMA_Cmd(bbPort_t *bbPort, FunctionalState NewState); #endif int bbDMA_Count(bbPort_t *bbPort); -void bbDshotRequestTelemetry(uint8_t motorIndex); -bool bbDshotIsMotorIdle(uint8_t motorIndex); +void bbDshotRequestTelemetry(unsigned motorIndex); +bool bbDshotIsMotorIdle(unsigned motorIndex); diff --git a/src/platform/common/stm32/dshot_bitbang_shared.c b/src/platform/common/stm32/dshot_bitbang_shared.c index a020227aad..2820d2307a 100644 --- a/src/platform/common/stm32/dshot_bitbang_shared.c +++ b/src/platform/common/stm32/dshot_bitbang_shared.c @@ -21,8 +21,11 @@ #include "dshot_bitbang_impl.h" -void bbDshotRequestTelemetry(uint8_t motorIndex) +void bbDshotRequestTelemetry(unsigned motorIndex) { + if (motorIndex >= ARRAYLEN(bbMotors)) { + return; + } bbMotor_t *const bbmotor = &bbMotors[motorIndex]; if (!bbmotor->configured) { @@ -31,8 +34,12 @@ void bbDshotRequestTelemetry(uint8_t motorIndex) bbmotor->protocolControl.requestTelemetry = true; } -bool bbDshotIsMotorIdle(uint8_t motorIndex) +bool bbDshotIsMotorIdle(unsigned motorIndex) { + if (motorIndex >= ARRAYLEN(bbMotors)) { + return false; + } + bbMotor_t *const bbmotor = &bbMotors[motorIndex]; - return bbmotor->protocolControl.value; + return bbmotor->protocolControl.value != 0; } diff --git a/src/platform/common/stm32/dshot_dpwm.c b/src/platform/common/stm32/dshot_dpwm.c index e0db84c475..8376680b23 100644 --- a/src/platform/common/stm32/dshot_dpwm.c +++ b/src/platform/common/stm32/dshot_dpwm.c @@ -121,7 +121,7 @@ static bool dshotPwmEnableMotors(void) return true; } -static bool dshotPwmIsMotorEnabled(uint8_t index) +static bool dshotPwmIsMotorEnabled(unsigned index) { return motors[index].enabled; } diff --git a/src/platform/common/stm32/dshot_dpwm.h b/src/platform/common/stm32/dshot_dpwm.h index 806bdf1135..63a403bd4e 100644 --- a/src/platform/common/stm32/dshot_dpwm.h +++ b/src/platform/common/stm32/dshot_dpwm.h @@ -153,7 +153,7 @@ typedef struct motorDmaOutput_s { DSHOT_DMA_BUFFER_UNIT *dmaBuffer; } motorDmaOutput_t; -motorDmaOutput_t *getMotorDmaOutput(uint8_t index); +motorDmaOutput_t *getMotorDmaOutput(unsigned index); void pwmWriteDshotInt(uint8_t index, uint16_t value); bool pwmDshotMotorHardwareConfig(const timerHardware_t *timerHardware, uint8_t motorIndex, uint8_t reorderedMotorIndex, motorProtocolTypes_e pwmProtocolType, uint8_t output); diff --git a/src/platform/common/stm32/pwm_output_dshot_shared.c b/src/platform/common/stm32/pwm_output_dshot_shared.c index f5788d193b..b49edb0f3a 100644 --- a/src/platform/common/stm32/pwm_output_dshot_shared.c +++ b/src/platform/common/stm32/pwm_output_dshot_shared.c @@ -63,21 +63,26 @@ FAST_DATA_ZERO_INIT uint32_t inputStampUs; FAST_DATA_ZERO_INIT dshotTelemetryCycleCounters_t dshotDMAHandlerCycleCounters; #endif -motorDmaOutput_t *getMotorDmaOutput(uint8_t index) +motorDmaOutput_t *getMotorDmaOutput(unsigned index) { + if (index >= ARRAYLEN(dmaMotors)) { + return NULL; + } return &dmaMotors[index]; } -bool pwmDshotIsMotorIdle(uint8_t index) +bool pwmDshotIsMotorIdle(unsigned index) { const motorDmaOutput_t *motor = getMotorDmaOutput(index); - return motor->protocolControl.value; + return motor && motor->protocolControl.value != 0; } -void pwmDshotRequestTelemetry(uint8_t index) +void pwmDshotRequestTelemetry(unsigned index) { motorDmaOutput_t * const motor = getMotorDmaOutput(index); - motor->protocolControl.requestTelemetry = true; + if (motor) { + motor->protocolControl.requestTelemetry = true; + } } uint8_t getTimerIndex(TIM_TypeDef *timer) @@ -153,7 +158,7 @@ FAST_CODE void pwmWriteDshotInt(uint8_t index, uint16_t value) #ifdef USE_DSHOT_TELEMETRY -void dshotEnableChannels(uint8_t motorCount); +void dshotEnableChannels(unsigned motorCount); static uint32_t decodeTelemetryPacket(const uint32_t buffer[], uint32_t count) { diff --git a/src/platform/common/stm32/pwm_output_dshot_shared.h b/src/platform/common/stm32/pwm_output_dshot_shared.h index 4183091f66..38f226b305 100644 --- a/src/platform/common/stm32/pwm_output_dshot_shared.h +++ b/src/platform/common/stm32/pwm_output_dshot_shared.h @@ -29,8 +29,8 @@ extern FAST_DATA_ZERO_INIT motorDmaTimer_t dmaMotorTimers[MAX_DMA_TIMERS]; extern FAST_DATA_ZERO_INIT motorDmaOutput_t dmaMotors[MAX_SUPPORTED_MOTORS]; uint8_t getTimerIndex(TIM_TypeDef *timer); -motorDmaOutput_t *getMotorDmaOutput(uint8_t index); -void dshotEnableChannels(uint8_t motorCount); +motorDmaOutput_t *getMotorDmaOutput(unsigned index); +void dshotEnableChannels(unsigned motorCount); #ifdef USE_DSHOT_TELEMETRY void pwmDshotSetDirectionOutput( @@ -44,8 +44,8 @@ void pwmDshotSetDirectionOutput( #endif ); -void pwmDshotRequestTelemetry(uint8_t index); -bool pwmDshotIsMotorIdle(uint8_t index); +void pwmDshotRequestTelemetry(unsigned index); +bool pwmDshotIsMotorIdle(unsigned index); bool pwmTelemetryDecode(void); #endif