diff --git a/src/main/config/config.h b/src/main/config/config.h index cd85647e0..de57ceccd 100644 --- a/src/main/config/config.h +++ b/src/main/config/config.h @@ -44,8 +44,8 @@ typedef enum { FEATURE_BLACKBOX = 1 << 19, FEATURE_CHANNEL_FORWARDING = 1 << 20, FEATURE_MULTISHOT = 1 << 21, - FEATURE_ONESHOT_PWM_RATE = 1 << 22, - FEATURE_MULTISHOT_PWM_RATE = 1 << 23, + FEATURE_USE_PWM_RATE = 1 << 22, + FEATURE_RESERVED = 1 << 23, FEATURE_TX_STYLE_EXPO = 1 << 24, FEATURE_SBUS_INVERTER = 1 << 25, } features_e; diff --git a/src/main/drivers/pwm_mapping.c b/src/main/drivers/pwm_mapping.c index 41eee7c59..401b8a572 100755 --- a/src/main/drivers/pwm_mapping.c +++ b/src/main/drivers/pwm_mapping.c @@ -1156,7 +1156,7 @@ if (init->useBuzzerP6) { } else { - if (init->useOneshotPwmRate) + if (init->usePwmRate) { pwmOneshotPwmRateMotorConfig(timerHardwarePtr, pwmOutputConfiguration.motorCount, init->motorPwmRate, init->idlePulse); } @@ -1168,7 +1168,7 @@ if (init->useBuzzerP6) { pwmOutputConfiguration.portConfigurations[pwmOutputConfiguration.outputCount].flags = PWM_PF_MOTOR | PWM_PF_OUTPUT_PROTOCOL_ONESHOT|PWM_PF_OUTPUT_PROTOCOL_PWM ; } else if (init->useMultiShot) { - if (init->useMultiShotPwmRate) + if (init->usePwmRate) { pwmMultiShotPwmRateMotorConfig(timerHardwarePtr, pwmOutputConfiguration.motorCount, init->motorPwmRate, init->idlePulse); } diff --git a/src/main/drivers/pwm_mapping.h b/src/main/drivers/pwm_mapping.h index 6d3d26ebc..175071217 100644 --- a/src/main/drivers/pwm_mapping.h +++ b/src/main/drivers/pwm_mapping.h @@ -67,9 +67,8 @@ typedef struct drv_pwm_config_s { #endif bool useVbat; bool useOneshot; - bool useOneshotPwmRate; bool useMultiShot; - bool useMultiShotPwmRate; + bool usePwmRate; bool useFastPWM; bool useSoftSerial; bool useLEDStrip; diff --git a/src/main/flight/mixer.c b/src/main/flight/mixer.c index 9e67f2933..51c0e79a5 100755 --- a/src/main/flight/mixer.c +++ b/src/main/flight/mixer.c @@ -642,7 +642,7 @@ void writeMotors(void) pwmWriteMotor(i, motor[i]); if (feature(FEATURE_MULTISHOT) || (feature(FEATURE_ONESHOT125))) { - if ( feature(FEATURE_MULTISHOT_PWM_RATE) || feature(FEATURE_ONESHOT_PWM_RATE) ) { } else { + if (!feature(FEATURE_USE_PWM_RATE)) { pwmCompleteOneshotMotorUpdate(motorCount); } } diff --git a/src/main/io/serial_cli.c b/src/main/io/serial_cli.c index 08c1487f7..a60719b63 100644 --- a/src/main/io/serial_cli.c +++ b/src/main/io/serial_cli.c @@ -176,8 +176,8 @@ static const char * const featureNames[] = { "SERVO_TILT", "SOFTSERIAL", "GPS", "FAILSAFE", "SONAR", "TELEMETRY", "CURRENT_METER", "3D", "RX_PARALLEL_PWM", "RX_MSP", "RSSI_ADC", "LED_STRIP", "DISPLAY", "ONESHOT125", - "BLACKBOX", "CHANNEL_FORWARDING", "MULTISHOT", "ONESHOT_PWM_RATE", - "MULTISHOT_PWM_RATE", "TX_STYLE_EXPO", "SBUS_INVERTER", NULL + "BLACKBOX", "CHANNEL_FORWARDING", "MULTISHOT", "USE_PWM_RATE", + "RESERVED", "TX_STYLE_EXPO", "SBUS_INVERTER", NULL }; // sync this with rxFailsafeChannelMode_e diff --git a/src/main/main.c b/src/main/main.c index fd9bb321e..8e63a840a 100644 --- a/src/main/main.c +++ b/src/main/main.c @@ -276,9 +276,8 @@ void init(void) #endif pwm_params.useOneshot = feature(FEATURE_ONESHOT125); - pwm_params.useOneshotPwmRate = feature(FEATURE_ONESHOT_PWM_RATE); pwm_params.useMultiShot = feature(FEATURE_MULTISHOT); - pwm_params.useMultiShotPwmRate = feature(FEATURE_MULTISHOT_PWM_RATE); + pwm_params.usePwmRate = feature(FEATURE_USE_PWM_RATE); pwm_params.useFastPWM = masterConfig.use_fast_pwm ? true : false; pwm_params.motorPwmRate = masterConfig.motor_pwm_rate; if (feature(FEATURE_3D)) @@ -287,20 +286,19 @@ void init(void) } else { - if ((pwm_params.motorPwmRate > 500 && !masterConfig.use_fast_pwm) && !feature(FEATURE_ONESHOT_PWM_RATE) && !feature(FEATURE_MULTISHOT_PWM_RATE)) + if ((pwm_params.motorPwmRate > 500 && !masterConfig.use_fast_pwm) && !feature(FEATURE_USE_PWM_RATE)) { pwm_params.idlePulse = 0; // brushed motors } else { - if (feature(FEATURE_MULTISHOT_PWM_RATE)) { + if (feature(FEATURE_USE_PWM_RATE)) { pwm_params.idlePulse = (uint16_t)((float)(masterConfig.escAndServoConfig.mincommand-1000) / 4.1666f)+60; } else { pwm_params.idlePulse = (uint16_t)((float)masterConfig.escAndServoConfig.mincommand*1.5f); } } - } - + } pwmOutputConfiguration_t *pwmOutputConfiguration = pwmInit(&pwm_params);