mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-15 20:35:33 +03:00
Move motor and servo params out of master_t
This commit is contained in:
parent
ef08d32491
commit
d913ed6a07
11 changed files with 33 additions and 39 deletions
|
@ -1267,9 +1267,9 @@ static bool blackboxWriteSysinfo()
|
|||
BLACKBOX_PRINT_HEADER_LINE("rc_interpolation_interval:%d", masterConfig.rxConfig.rcInterpolationInterval);
|
||||
BLACKBOX_PRINT_HEADER_LINE("airmode_activate_throttle:%d", masterConfig.rxConfig.airModeActivateThreshold);
|
||||
BLACKBOX_PRINT_HEADER_LINE("serialrx_provider:%d", masterConfig.rxConfig.serialrx_provider);
|
||||
BLACKBOX_PRINT_HEADER_LINE("unsynced_fast_pwm:%d", masterConfig.use_unsyncedPwm);
|
||||
BLACKBOX_PRINT_HEADER_LINE("fast_pwm_protocol:%d", masterConfig.motor_pwm_protocol);
|
||||
BLACKBOX_PRINT_HEADER_LINE("motor_pwm_rate:%d", masterConfig.motor_pwm_rate);
|
||||
BLACKBOX_PRINT_HEADER_LINE("unsynced_fast_pwm:%d", masterConfig.motorConfig.useUnsyncedPwm);
|
||||
BLACKBOX_PRINT_HEADER_LINE("fast_pwm_protocol:%d", masterConfig.motorConfig.motorPwmProtocol);
|
||||
BLACKBOX_PRINT_HEADER_LINE("motor_pwm_rate:%d", masterConfig.motorConfig.motorPwmRate);
|
||||
BLACKBOX_PRINT_HEADER_LINE("debug_mode:%d", masterConfig.debug_mode);
|
||||
BLACKBOX_PRINT_HEADER_LINE("features:%d", masterConfig.enabledFeatures);
|
||||
|
||||
|
|
|
@ -245,18 +245,25 @@ void resetMotorConfig(motorConfig_t *motorConfig)
|
|||
{
|
||||
#ifdef BRUSHED_MOTORS
|
||||
motorConfig->minthrottle = 1000;
|
||||
motorConfig->motorPwmRate = BRUSHED_MOTORS_PWM_RATE;
|
||||
motorConfig->motorPwmProtocol = PWM_TYPE_BRUSHED;
|
||||
motorConfig->useUnsyncedPwm = true;
|
||||
#else
|
||||
motorConfig->minthrottle = 1070;
|
||||
motorConfig->motorPwmRate = BRUSHLESS_MOTORS_PWM_RATE;
|
||||
motorConfig->motorPwmProtocol = PWM_TYPE_ONESHOT125;
|
||||
#endif
|
||||
motorConfig->maxthrottle = 2000;
|
||||
motorConfig->mincommand = 1000;
|
||||
motorConfig->maxEscThrottleJumpMs = 0;
|
||||
|
||||
}
|
||||
|
||||
#ifdef USE_SERVOS
|
||||
void resetServoConfig(servoConfig_t *servoConfig)
|
||||
{
|
||||
servoConfig->servoCenterPulse = 1500;
|
||||
servoConfig->servoPwmRate = 50;
|
||||
}
|
||||
#endif
|
||||
|
||||
|
@ -504,17 +511,6 @@ void createDefaultConfig(master_t *config)
|
|||
#endif
|
||||
resetFlight3DConfig(&config->flight3DConfig);
|
||||
|
||||
#ifdef BRUSHED_MOTORS
|
||||
config->motor_pwm_rate = BRUSHED_MOTORS_PWM_RATE;
|
||||
config->motor_pwm_protocol = PWM_TYPE_BRUSHED;
|
||||
config->use_unsyncedPwm = true;
|
||||
#else
|
||||
config->motor_pwm_rate = BRUSHLESS_MOTORS_PWM_RATE;
|
||||
config->motor_pwm_protocol = PWM_TYPE_ONESHOT125;
|
||||
#endif
|
||||
|
||||
config->servo_pwm_rate = 50;
|
||||
|
||||
#ifdef CC3D
|
||||
config->use_buzzer_p6 = 0;
|
||||
#endif
|
||||
|
|
|
@ -77,11 +77,6 @@ typedef struct master_s {
|
|||
servoConfig_t servoConfig;
|
||||
flight3DConfig_t flight3DConfig;
|
||||
|
||||
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;
|
||||
|
||||
#ifdef USE_SERVOS
|
||||
servoMixer_t customServoMixer[MAX_SERVO_RULES];
|
||||
// Servo-related stuff
|
||||
|
|
|
@ -18,10 +18,12 @@
|
|||
#pragma once
|
||||
|
||||
typedef struct motorConfig_s {
|
||||
|
||||
// PWM values, in milliseconds, common range is 1000-2000 (1 to 2ms)
|
||||
uint16_t minthrottle; // Set the minimum throttle command sent to the ESC (Electronic Speed Controller). This is the minimum value that allow motors to run at a idle speed.
|
||||
uint16_t maxthrottle; // This is the maximum value for the ESCs at full power this value can be increased up to 2000
|
||||
uint16_t mincommand; // This is the value for the ESCs when they are not armed. In some cases, this value must be lowered down to 900 for some specific ESCs
|
||||
uint16_t maxEscThrottleJumpMs;
|
||||
uint16_t motorPwmRate; // The update rate of motor outputs (50-498Hz)
|
||||
uint8_t motorPwmProtocol; // Pwm Protocol
|
||||
uint8_t useUnsyncedPwm;
|
||||
} motorConfig_t;
|
||||
|
|
|
@ -705,10 +705,9 @@ const clivalue_t valueTable[] = {
|
|||
#ifdef CC3D
|
||||
{ "enable_buzzer_p6", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.use_buzzer_p6, .config.lookup = { TABLE_OFF_ON } },
|
||||
#endif
|
||||
{ "use_unsynced_pwm", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.use_unsyncedPwm, .config.lookup = { TABLE_OFF_ON } },
|
||||
{ "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 } },
|
||||
{ "use_unsynced_pwm", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.motorConfig.useUnsyncedPwm, .config.lookup = { TABLE_OFF_ON } },
|
||||
{ "motor_pwm_protocol", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.motorConfig.motorPwmProtocol, .config.lookup = { TABLE_MOTOR_PWM_PROTOCOL } },
|
||||
{ "motor_pwm_rate", VAR_UINT16 | MASTER_VALUE, &masterConfig.motorConfig.motorPwmRate, .config.minmax = { 200, 32000 } },
|
||||
|
||||
{ "disarm_kill_switch", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.disarm_kill_switch, .config.lookup = { TABLE_OFF_ON } },
|
||||
{ "gyro_cal_on_first_arm", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.gyro_cal_on_first_arm, .config.lookup = { TABLE_OFF_ON } },
|
||||
|
@ -821,6 +820,7 @@ const clivalue_t valueTable[] = {
|
|||
{ "tri_unarmed_servo", VAR_INT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.mixerConfig.tri_unarmed_servo, .config.lookup = { TABLE_OFF_ON } },
|
||||
{ "servo_lowpass_freq", VAR_UINT16 | MASTER_VALUE, &masterConfig.mixerConfig.servo_lowpass_freq, .config.minmax = { 10, 400} },
|
||||
{ "servo_lowpass_enable", VAR_INT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.mixerConfig.servo_lowpass_enable, .config.lookup = { TABLE_OFF_ON } },
|
||||
{ "servo_pwm_rate", VAR_UINT16 | MASTER_VALUE, &masterConfig.servoConfig.servoPwmRate, .config.minmax = { 50, 498 } },
|
||||
#endif
|
||||
|
||||
{ "rc_rate", VAR_UINT8 | PROFILE_RATE_VALUE, &masterConfig.profile[0].controlRateProfile[0].rcRate8, .config.minmax = { 0, 255 } },
|
||||
|
|
|
@ -20,4 +20,5 @@
|
|||
typedef struct servoConfig_s {
|
||||
// PWM values, in milliseconds, common range is 1000-2000 (1 to 2ms)
|
||||
uint16_t servoCenterPulse; // This is the value for servos when they should be in the middle. e.g. 1500.
|
||||
uint16_t servoPwmRate; // The update rate of servo outputs (50-498Hz)
|
||||
} servoConfig_t;
|
||||
|
|
|
@ -291,20 +291,20 @@ void init(void)
|
|||
pwm_params.useServos = isMixerUsingServos();
|
||||
pwm_params.useChannelForwarding = feature(FEATURE_CHANNEL_FORWARDING);
|
||||
pwm_params.servoCenterPulse = masterConfig.servoConfig.servoCenterPulse;
|
||||
pwm_params.servoPwmRate = masterConfig.servo_pwm_rate;
|
||||
pwm_params.servoPwmRate = masterConfig.servoConfig.servoPwmRate;
|
||||
#endif
|
||||
|
||||
bool use_unsyncedPwm = masterConfig.use_unsyncedPwm || masterConfig.motor_pwm_protocol == PWM_TYPE_CONVENTIONAL || masterConfig.motor_pwm_protocol == PWM_TYPE_BRUSHED;
|
||||
bool use_unsyncedPwm = masterConfig.motorConfig.useUnsyncedPwm || masterConfig.motorConfig.motorPwmProtocol == PWM_TYPE_CONVENTIONAL || masterConfig.motorConfig.motorPwmProtocol == PWM_TYPE_BRUSHED;
|
||||
|
||||
// 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 = use_unsyncedPwm ? masterConfig.motor_pwm_rate : 0;
|
||||
pwm_params.useFastPwm = (masterConfig.motorConfig.motorPwmProtocol != PWM_TYPE_CONVENTIONAL && masterConfig.motorConfig.motorPwmProtocol != PWM_TYPE_BRUSHED);
|
||||
pwm_params.pwmProtocolType = masterConfig.motorConfig.motorPwmProtocol;
|
||||
pwm_params.motorPwmRate = use_unsyncedPwm ? masterConfig.motorConfig.motorPwmRate : 0;
|
||||
pwm_params.idlePulse = masterConfig.motorConfig.mincommand;
|
||||
if (feature(FEATURE_3D))
|
||||
pwm_params.idlePulse = masterConfig.flight3DConfig.neutral3d;
|
||||
|
||||
if (masterConfig.motor_pwm_protocol == PWM_TYPE_BRUSHED) {
|
||||
if (masterConfig.motorConfig.motorPwmProtocol == PWM_TYPE_BRUSHED) {
|
||||
featureClear(FEATURE_3D);
|
||||
pwm_params.idlePulse = 0; // brushed motors
|
||||
}
|
||||
|
|
|
@ -1241,9 +1241,9 @@ static bool processOutCommand(uint8_t cmdMSP)
|
|||
serialize8(masterConfig.gyro_sync_denom);
|
||||
serialize8(masterConfig.pid_process_denom);
|
||||
}
|
||||
serialize8(masterConfig.use_unsyncedPwm);
|
||||
serialize8(masterConfig.motor_pwm_protocol);
|
||||
serialize16(masterConfig.motor_pwm_rate);
|
||||
serialize8(masterConfig.motorConfig.useUnsyncedPwm);
|
||||
serialize8(masterConfig.motorConfig.motorPwmProtocol);
|
||||
serialize16(masterConfig.motorConfig.motorPwmRate);
|
||||
break;
|
||||
case MSP_FILTER_CONFIG :
|
||||
headSerialReply(13);
|
||||
|
@ -1848,9 +1848,9 @@ static bool processInCommand(void)
|
|||
case MSP_SET_ADVANCED_CONFIG :
|
||||
masterConfig.gyro_sync_denom = read8();
|
||||
masterConfig.pid_process_denom = read8();
|
||||
masterConfig.use_unsyncedPwm = read8();
|
||||
masterConfig.motor_pwm_protocol = read8();
|
||||
masterConfig.motor_pwm_rate = read16();
|
||||
masterConfig.motorConfig.useUnsyncedPwm = read8();
|
||||
masterConfig.motorConfig.motorPwmProtocol = read8();
|
||||
masterConfig.motorConfig.motorPwmRate = read16();
|
||||
break;
|
||||
case MSP_SET_FILTER_CONFIG :
|
||||
masterConfig.gyro_soft_lpf_hz = read8();
|
||||
|
|
|
@ -38,7 +38,7 @@ void targetConfiguration(master_t *config)
|
|||
{
|
||||
config->rxConfig.spektrum_sat_bind = 5;
|
||||
config->rxConfig.spektrum_sat_bind_autoreset = 1;
|
||||
config->motor_pwm_rate = 32000;
|
||||
config->motorConfig.motorPwmRate = 32000;
|
||||
config->failsafeConfig.failsafe_delay = 2;
|
||||
config->failsafeConfig.failsafe_off_delay = 0;
|
||||
config->profile[0].pidProfile.P8[ROLL] = 90;
|
||||
|
|
|
@ -47,7 +47,7 @@ void targetConfiguration(master_t *config)
|
|||
config->mag_hardware = MAG_NONE; // disabled by default
|
||||
config->rxConfig.spektrum_sat_bind = 5;
|
||||
config->rxConfig.spektrum_sat_bind_autoreset = 1;
|
||||
config->motor_pwm_rate = 32000;
|
||||
config->motorConfig.motorPwmRate = 32000;
|
||||
config->failsafeConfig.failsafe_delay = 2;
|
||||
config->failsafeConfig.failsafe_off_delay = 0;
|
||||
config->gyro_sync_denom = 2;
|
||||
|
|
|
@ -47,7 +47,7 @@ void targetConfiguration(master_t *config)
|
|||
config->mag_hardware = MAG_NONE; // disabled by default
|
||||
config->rxConfig.spektrum_sat_bind = 5;
|
||||
config->rxConfig.spektrum_sat_bind_autoreset = 1;
|
||||
config->motor_pwm_rate = 32000;
|
||||
config->motorConfig.motorPwmRate = 32000;
|
||||
config->failsafeConfig.failsafe_delay = 2;
|
||||
config->failsafeConfig.failsafe_off_delay = 0;
|
||||
config->gyro_sync_denom = 1;
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue