diff --git a/src/main/config/config.c b/src/main/config/config.c index 1927ae0bb3..0c1f5e6345 100644 --- a/src/main/config/config.c +++ b/src/main/config/config.c @@ -943,8 +943,8 @@ void handleOneshotFeatureChangeOnRestart(void) // Shutdown PWM on all motors prior to soft restart StopPwmAllMotors(); delay(50); - // When OneShot125 feature changed state apply additional delay - if ((masterConfig.enabledFeatures ^ activeFeaturesLatch) & FEATURE_ONESHOT125) { + // Apply additional delay when OneShot125 feature changed from on to off state + if (feature(FEATURE_ONESHOT125) && !featureConfigured(FEATURE_ONESHOT125)) { delay(ONESHOT_FEATURE_CHANGED_DELAY_ON_BOOT_MS); } } diff --git a/src/main/drivers/pwm_mapping.c b/src/main/drivers/pwm_mapping.c index e6079e907c..bcdfe93e0c 100644 --- a/src/main/drivers/pwm_mapping.c +++ b/src/main/drivers/pwm_mapping.c @@ -528,7 +528,7 @@ pwmOutputConfiguration_t *pwmInit(drv_pwm_config_t *init) channelIndex++; } else if (type == MAP_TO_MOTOR_OUTPUT) { if (init->useOneshot) { - pwmOneshotMotorConfig(timerHardwarePtr, pwmOutputConfiguration.motorCount, init->idlePulse); + pwmOneshotMotorConfig(timerHardwarePtr, pwmOutputConfiguration.motorCount, 0); } else if (init->motorPwmRate > 500) { pwmBrushedMotorConfig(timerHardwarePtr, pwmOutputConfiguration.motorCount, init->motorPwmRate, init->idlePulse); } else { diff --git a/src/main/main.c b/src/main/main.c index 0500a1abd2..20dd80ee13 100644 --- a/src/main/main.c +++ b/src/main/main.c @@ -90,6 +90,7 @@ #include "debug.h" extern uint32_t previousTime; +extern uint8_t motorControlEnable; #ifdef SOFTSERIAL_LOOPBACK serialPort_t *loopbackPort; @@ -241,6 +242,9 @@ void init(void) mixerUsePWMOutputConfiguration(pwmOutputConfiguration); + if (!feature(FEATURE_ONESHOT125)) + motorControlEnable = true; + systemState |= SYSTEM_STATE_MOTORS_READY; #ifdef BEEPER @@ -456,6 +460,7 @@ void init(void) // Latch active features AGAIN since some may be modified by init(). latchActiveFeatures(); + motorControlEnable = true; systemState |= SYSTEM_STATE_READY; } diff --git a/src/main/mw.c b/src/main/mw.c index 471b4294e0..0cfd46b379 100644 --- a/src/main/mw.c +++ b/src/main/mw.c @@ -97,6 +97,8 @@ uint16_t cycleTime = 0; // this is the number in micro second to achieve int16_t magHold; int16_t headFreeModeHold; +uint8_t motorControlEnable = false; + int16_t telemTemperature1; // gyro sensor temperature static uint32_t disarmAt; // Time of automatic disarm when "Don't spin the motors when armed" is enabled and auto_disarm_delay is nonzero @@ -801,7 +803,9 @@ void loop(void) writeServos(); #endif - writeMotors(); + if (motorControlEnable) { + writeMotors(); + } #ifdef BLACKBOX if (!cliMode && feature(FEATURE_BLACKBOX)) {