mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-17 13:25:30 +03:00
FastPWM as part of Oneshot125 (dynamic oneshot)
bool correction IdlePulse
This commit is contained in:
parent
77534ed6f6
commit
fa9cd0440b
7 changed files with 16 additions and 20 deletions
|
@ -128,7 +128,7 @@ static uint32_t activeFeaturesLatch = 0;
|
||||||
static uint8_t currentControlRateProfileIndex = 0;
|
static uint8_t currentControlRateProfileIndex = 0;
|
||||||
controlRateConfig_t *currentControlRateProfile;
|
controlRateConfig_t *currentControlRateProfile;
|
||||||
|
|
||||||
static const uint8_t EEPROM_CONF_VERSION = 108;
|
static const uint8_t EEPROM_CONF_VERSION = 109;
|
||||||
|
|
||||||
static void resetAccelerometerTrims(flightDynamicsTrims_t *accelerometerTrims)
|
static void resetAccelerometerTrims(flightDynamicsTrims_t *accelerometerTrims)
|
||||||
{
|
{
|
||||||
|
@ -442,6 +442,7 @@ static void resetConf(void)
|
||||||
masterConfig.motor_pwm_rate = BRUSHLESS_MOTORS_PWM_RATE;
|
masterConfig.motor_pwm_rate = BRUSHLESS_MOTORS_PWM_RATE;
|
||||||
#endif
|
#endif
|
||||||
masterConfig.servo_pwm_rate = 50;
|
masterConfig.servo_pwm_rate = 50;
|
||||||
|
masterConfig.use_fast_pwm = 0;
|
||||||
|
|
||||||
#ifdef GPS
|
#ifdef GPS
|
||||||
// gps/nav stuff
|
// gps/nav stuff
|
||||||
|
@ -747,14 +748,6 @@ void validateAndFixConfig(void)
|
||||||
featureClear(FEATURE_RX_PPM);
|
featureClear(FEATURE_RX_PPM);
|
||||||
}
|
}
|
||||||
|
|
||||||
if (featureConfigured(FEATURE_ONESHOT125)) {
|
|
||||||
featureClear(FEATURE_FASTPWM);
|
|
||||||
}
|
|
||||||
|
|
||||||
if (featureConfigured(FEATURE_FASTPWM)) {
|
|
||||||
featureClear(FEATURE_ONESHOT125);
|
|
||||||
}
|
|
||||||
|
|
||||||
if (featureConfigured(FEATURE_RX_PARALLEL_PWM)) {
|
if (featureConfigured(FEATURE_RX_PARALLEL_PWM)) {
|
||||||
#if defined(STM32F10X)
|
#if defined(STM32F10X)
|
||||||
// rssi adc needs the same ports
|
// rssi adc needs the same ports
|
||||||
|
|
|
@ -42,8 +42,7 @@ typedef enum {
|
||||||
FEATURE_DISPLAY = 1 << 17,
|
FEATURE_DISPLAY = 1 << 17,
|
||||||
FEATURE_ONESHOT125 = 1 << 18,
|
FEATURE_ONESHOT125 = 1 << 18,
|
||||||
FEATURE_BLACKBOX = 1 << 19,
|
FEATURE_BLACKBOX = 1 << 19,
|
||||||
FEATURE_CHANNEL_FORWARDING = 1 << 20,
|
FEATURE_CHANNEL_FORWARDING = 1 << 20
|
||||||
FEATURE_FASTPWM = 1 << 21
|
|
||||||
} features_e;
|
} features_e;
|
||||||
|
|
||||||
void handleOneshotFeatureChangeOnRestart(void);
|
void handleOneshotFeatureChangeOnRestart(void);
|
||||||
|
|
|
@ -37,6 +37,7 @@ typedef struct master_t {
|
||||||
|
|
||||||
uint16_t motor_pwm_rate; // The update rate of motor outputs (50-498Hz)
|
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)
|
uint16_t servo_pwm_rate; // The update rate of servo outputs (50-498Hz)
|
||||||
|
uint8_t use_fast_pwm; // Use fast PWM implementation when oneshot enabled
|
||||||
|
|
||||||
// global sensor-related stuff
|
// global sensor-related stuff
|
||||||
|
|
||||||
|
|
|
@ -31,7 +31,7 @@
|
||||||
|
|
||||||
void pwmBrushedMotorConfig(const timerHardware_t *timerHardware, uint8_t motorIndex, uint16_t motorPwmRate, uint16_t idlePulse);
|
void pwmBrushedMotorConfig(const timerHardware_t *timerHardware, uint8_t motorIndex, uint16_t motorPwmRate, uint16_t idlePulse);
|
||||||
void pwmBrushlessMotorConfig(const timerHardware_t *timerHardware, uint8_t motorIndex, uint16_t motorPwmRate, uint16_t idlePulse);
|
void pwmBrushlessMotorConfig(const timerHardware_t *timerHardware, uint8_t motorIndex, uint16_t motorPwmRate, uint16_t idlePulse);
|
||||||
void fastPWMMotorConfig(const timerHardware_t *timerHardware, uint8_t motorIndex, uint16_t idlePulse);
|
void fastPWMMotorConfig(const timerHardware_t *timerHardware, uint8_t motorIndex, uint16_t motorPwmRate, uint16_t idlePulse);
|
||||||
void pwmOneshotMotorConfig(const timerHardware_t *timerHardware, uint8_t motorIndex);
|
void pwmOneshotMotorConfig(const timerHardware_t *timerHardware, uint8_t motorIndex);
|
||||||
void pwmServoConfig(const timerHardware_t *timerHardware, uint8_t servoIndex, uint16_t servoPwmRate, uint16_t servoCenterPulse);
|
void pwmServoConfig(const timerHardware_t *timerHardware, uint8_t servoIndex, uint16_t servoPwmRate, uint16_t servoCenterPulse);
|
||||||
|
|
||||||
|
@ -638,9 +638,11 @@ pwmOutputConfiguration_t *pwmInit(drv_pwm_config_t *init)
|
||||||
channelIndex++;
|
channelIndex++;
|
||||||
} else if (type == MAP_TO_MOTOR_OUTPUT) {
|
} else if (type == MAP_TO_MOTOR_OUTPUT) {
|
||||||
if (init->useOneshot) {
|
if (init->useOneshot) {
|
||||||
pwmOneshotMotorConfig(timerHardwarePtr, pwmOutputConfiguration.motorCount);
|
if (init->useFastPWM) {
|
||||||
} else if (init->useFastPWM) {
|
fastPWMMotorConfig(timerHardwarePtr, pwmOutputConfiguration.motorCount, init->motorPwmRate, init->idlePulse);
|
||||||
fastPWMMotorConfig(timerHardwarePtr, pwmOutputConfiguration.motorCount, init->idlePulse);
|
} else {
|
||||||
|
pwmOneshotMotorConfig(timerHardwarePtr, pwmOutputConfiguration.motorCount);
|
||||||
|
}
|
||||||
} else if (isMotorBrushed(init->motorPwmRate)) {
|
} else if (isMotorBrushed(init->motorPwmRate)) {
|
||||||
pwmBrushedMotorConfig(timerHardwarePtr, pwmOutputConfiguration.motorCount, init->motorPwmRate, init->idlePulse);
|
pwmBrushedMotorConfig(timerHardwarePtr, pwmOutputConfiguration.motorCount, init->motorPwmRate, init->idlePulse);
|
||||||
} else {
|
} else {
|
||||||
|
|
|
@ -190,10 +190,10 @@ void pwmBrushlessMotorConfig(const timerHardware_t *timerHardware, uint8_t motor
|
||||||
motors[motorIndex]->pwmWritePtr = pwmWriteStandard;
|
motors[motorIndex]->pwmWritePtr = pwmWriteStandard;
|
||||||
}
|
}
|
||||||
|
|
||||||
void fastPWMMotorConfig(const timerHardware_t *timerHardware, uint8_t motorIndex, uint16_t idlePulse)
|
void fastPWMMotorConfig(const timerHardware_t *timerHardware, uint8_t motorIndex, uint16_t motorPwmRate, uint16_t idlePulse)
|
||||||
{
|
{
|
||||||
uint32_t hz = PWM_BRUSHED_TIMER_MHZ * 1000000;
|
uint32_t hz = PWM_BRUSHED_TIMER_MHZ * 1000000;
|
||||||
motors[motorIndex] = pwmOutConfig(timerHardware, ONESHOT125_TIMER_MHZ, hz / 4000, idlePulse);
|
motors[motorIndex] = pwmOutConfig(timerHardware, ONESHOT125_TIMER_MHZ, hz / motorPwmRate, idlePulse);
|
||||||
motors[motorIndex]->pwmWritePtr = pwmWriteStandard;
|
motors[motorIndex]->pwmWritePtr = pwmWriteStandard;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -175,7 +175,7 @@ static const char * const featureNames[] = {
|
||||||
"SERVO_TILT", "SOFTSERIAL", "GPS", "FAILSAFE",
|
"SERVO_TILT", "SOFTSERIAL", "GPS", "FAILSAFE",
|
||||||
"SONAR", "TELEMETRY", "CURRENT_METER", "3D", "RX_PARALLEL_PWM",
|
"SONAR", "TELEMETRY", "CURRENT_METER", "3D", "RX_PARALLEL_PWM",
|
||||||
"RX_MSP", "RSSI_ADC", "LED_STRIP", "DISPLAY", "ONESHOT125",
|
"RX_MSP", "RSSI_ADC", "LED_STRIP", "DISPLAY", "ONESHOT125",
|
||||||
"BLACKBOX", "CHANNEL_FORWARDING","FASTPWM", NULL
|
"BLACKBOX", "CHANNEL_FORWARDING", NULL
|
||||||
};
|
};
|
||||||
|
|
||||||
// sync this with rxFailsafeChannelMode_e
|
// sync this with rxFailsafeChannelMode_e
|
||||||
|
@ -346,6 +346,7 @@ const clivalue_t valueTable[] = {
|
||||||
|
|
||||||
{ "motor_pwm_rate", VAR_UINT16 | MASTER_VALUE, &masterConfig.motor_pwm_rate, 50, 32000 },
|
{ "motor_pwm_rate", VAR_UINT16 | MASTER_VALUE, &masterConfig.motor_pwm_rate, 50, 32000 },
|
||||||
{ "servo_pwm_rate", VAR_UINT16 | MASTER_VALUE, &masterConfig.servo_pwm_rate, 50, 498 },
|
{ "servo_pwm_rate", VAR_UINT16 | MASTER_VALUE, &masterConfig.servo_pwm_rate, 50, 498 },
|
||||||
|
{ "enable_fast_pwm", VAR_UINT8 | MASTER_VALUE, &masterConfig.use_fast_pwm, 0, 1 },
|
||||||
|
|
||||||
{ "retarded_arm", VAR_UINT8 | MASTER_VALUE, &masterConfig.retarded_arm, 0, 1 },
|
{ "retarded_arm", VAR_UINT8 | MASTER_VALUE, &masterConfig.retarded_arm, 0, 1 },
|
||||||
{ "disarm_kill_switch", VAR_UINT8 | MASTER_VALUE, &masterConfig.disarm_kill_switch, 0, 1 },
|
{ "disarm_kill_switch", VAR_UINT8 | MASTER_VALUE, &masterConfig.disarm_kill_switch, 0, 1 },
|
||||||
|
|
|
@ -256,12 +256,12 @@ void init(void)
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
pwm_params.useOneshot = feature(FEATURE_ONESHOT125);
|
pwm_params.useOneshot = feature(FEATURE_ONESHOT125);
|
||||||
pwm_params.useFastPWM = feature(FEATURE_FASTPWM);
|
pwm_params.useFastPWM = masterConfig.use_fast_pwm ? true : false;
|
||||||
pwm_params.motorPwmRate = masterConfig.motor_pwm_rate;
|
pwm_params.motorPwmRate = masterConfig.motor_pwm_rate;
|
||||||
pwm_params.idlePulse = masterConfig.escAndServoConfig.mincommand;
|
pwm_params.idlePulse = masterConfig.escAndServoConfig.mincommand;
|
||||||
if (feature(FEATURE_3D))
|
if (feature(FEATURE_3D))
|
||||||
pwm_params.idlePulse = masterConfig.flight3DConfig.neutral3d;
|
pwm_params.idlePulse = masterConfig.flight3DConfig.neutral3d;
|
||||||
if (pwm_params.motorPwmRate > 500)
|
if (pwm_params.motorPwmRate > 500 && !masterConfig.use_fast_pwm)
|
||||||
pwm_params.idlePulse = 0; // brushed motors
|
pwm_params.idlePulse = 0; // brushed motors
|
||||||
|
|
||||||
pwmRxInit(masterConfig.inputFilteringMode);
|
pwmRxInit(masterConfig.inputFilteringMode);
|
||||||
|
|
Loading…
Add table
Add a link
Reference in a new issue