mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-16 21:05:35 +03:00
Removing some settings for simplicity, motor_pwm_protocol (for all protocols) and motor_pwm_rate (to sync or unsync)
This commit is contained in:
parent
a008c43ffb
commit
827b576f6d
5 changed files with 6 additions and 18 deletions
|
@ -518,7 +518,6 @@ static void resetConf(void)
|
|||
masterConfig.motor_pwm_protocol = PWM_TYPE_ONESHOT125;
|
||||
#endif
|
||||
masterConfig.servo_pwm_rate = 50;
|
||||
masterConfig.use_unsyncedPwm = false;
|
||||
|
||||
#ifdef CC3D
|
||||
masterConfig.use_buzzer_p6 = 0;
|
||||
|
|
|
@ -35,7 +35,6 @@ typedef struct master_t {
|
|||
uint16_t motor_pwm_rate; // The update rate of motor outputs (50-498Hz)
|
||||
uint16_t servo_pwm_rate; // The update rate of servo outputs (50-498Hz)
|
||||
uint8_t motor_pwm_protocol; // Pwm Protocol
|
||||
uint8_t use_unsyncedPwm; // unsync fast pwm protocol from PID loop
|
||||
|
||||
#ifdef USE_SERVOS
|
||||
servoMixer_t customServoMixer[MAX_SERVO_RULES];
|
||||
|
|
|
@ -54,19 +54,11 @@ typedef struct drv_pwm_config_s {
|
|||
bool useSerialRx;
|
||||
bool useRSSIADC;
|
||||
bool useCurrentMeterADC;
|
||||
#ifdef STM32F10X
|
||||
bool useUART2;
|
||||
#endif
|
||||
#ifdef STM32F303xC
|
||||
bool useUART3;
|
||||
#endif
|
||||
#ifdef STM32F4
|
||||
bool useUART2;
|
||||
bool useUART6;
|
||||
#endif
|
||||
bool useVbat;
|
||||
bool useFastPwm;
|
||||
bool useUnsyncedPwm;
|
||||
bool useSoftSerial;
|
||||
bool useLEDStrip;
|
||||
#ifdef SONAR
|
||||
|
|
|
@ -582,12 +582,10 @@ const clivalue_t valueTable[] = {
|
|||
{ "3d_neutral", VAR_UINT16 | MASTER_VALUE, &masterConfig.flight3DConfig.neutral3d, .config.minmax = { PWM_RANGE_ZERO, PWM_RANGE_MAX } },
|
||||
{ "3d_deadband_throttle", VAR_UINT16 | MASTER_VALUE, &masterConfig.flight3DConfig.deadband3d_throttle, .config.minmax = { PWM_RANGE_ZERO, PWM_RANGE_MAX } },
|
||||
|
||||
{ "unsynced_fast_pwm", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.use_unsyncedPwm, .config.lookup = { TABLE_OFF_ON } },
|
||||
{ "fast_pwm_protocol", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.motor_pwm_protocol, .config.lookup = { TABLE_MOTOR_PWM_PROTOCOL } },
|
||||
{ "motor_pwm_protocol", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.motor_pwm_protocol, .config.lookup = { TABLE_MOTOR_PWM_PROTOCOL } },
|
||||
#ifdef CC3D
|
||||
{ "enable_buzzer_p6", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.use_buzzer_p6, .config.lookup = { TABLE_OFF_ON } },
|
||||
#endif
|
||||
{ "motor_pwm_protocol", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.motor_pwm_protocol, .config.lookup = { TABLE_MOTOR_PWM_PROTOCOL } },
|
||||
{ "motor_pwm_rate", VAR_UINT16 | MASTER_VALUE, &masterConfig.motor_pwm_rate, .config.minmax = { 200, 32000 } },
|
||||
{ "servo_pwm_rate", VAR_UINT16 | MASTER_VALUE, &masterConfig.servo_pwm_rate, .config.minmax = { 50, 498 } },
|
||||
|
||||
|
|
|
@ -335,11 +335,11 @@ void init(void)
|
|||
featureClear(FEATURE_ONESHOT125);
|
||||
}
|
||||
|
||||
pwm_params.useFastPwm = (masterConfig.motor_pwm_protocol != PWM_TYPE_CONVENTIONAL && masterConfig.motor_pwm_protocol != PWM_TYPE_BRUSHED); // Configurator feature abused for enabling Fast PWM
|
||||
// Configurator feature abused for enabling Fast PWM
|
||||
pwm_params.useFastPwm = (masterConfig.motor_pwm_protocol != PWM_TYPE_CONVENTIONAL && masterConfig.motor_pwm_protocol != PWM_TYPE_BRUSHED);
|
||||
pwm_params.pwmProtocolType = masterConfig.motor_pwm_protocol;
|
||||
pwm_params.motorPwmRate = masterConfig.motor_pwm_rate;
|
||||
pwm_params.idlePulse = masterConfig.escAndServoConfig.mincommand;
|
||||
pwm_params.useUnsyncedPwm = masterConfig.use_unsyncedPwm;
|
||||
if (feature(FEATURE_3D))
|
||||
pwm_params.idlePulse = masterConfig.flight3DConfig.neutral3d;
|
||||
if (masterConfig.motor_pwm_protocol == PWM_TYPE_BRUSHED)
|
||||
|
@ -351,7 +351,7 @@ void init(void)
|
|||
|
||||
pwmOutputConfiguration_t *pwmOutputConfiguration = pwmInit(&pwm_params);
|
||||
|
||||
syncMotors(pwm_params.useUnsyncedPwm && pwm_params.motorPwmRate != PWM_TYPE_BRUSHED);
|
||||
syncMotors(pwm_params.motorPwmRate == 0 && pwm_params.motorPwmRate != PWM_TYPE_BRUSHED);
|
||||
mixerUsePWMOutputConfiguration(pwmOutputConfiguration);
|
||||
|
||||
if (!feature(FEATURE_ONESHOT125))
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue