mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-20 06:45:16 +03:00
quick implementation of fastpwm
This commit is contained in:
parent
26ab91687f
commit
7bd79e159c
7 changed files with 23 additions and 2 deletions
|
@ -742,6 +742,14 @@ 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
|
||||||
|
|
|
@ -43,7 +43,8 @@ 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);
|
||||||
|
|
|
@ -31,6 +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 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);
|
||||||
|
|
||||||
|
@ -548,6 +549,8 @@ pwmOutputConfiguration_t *pwmInit(drv_pwm_config_t *init)
|
||||||
} else if (type == MAP_TO_MOTOR_OUTPUT) {
|
} else if (type == MAP_TO_MOTOR_OUTPUT) {
|
||||||
if (init->useOneshot) {
|
if (init->useOneshot) {
|
||||||
pwmOneshotMotorConfig(timerHardwarePtr, pwmOutputConfiguration.motorCount);
|
pwmOneshotMotorConfig(timerHardwarePtr, pwmOutputConfiguration.motorCount);
|
||||||
|
} else if (init->useFastPWM) {
|
||||||
|
fastPWMMotorConfig(timerHardwarePtr, pwmOutputConfiguration.motorCount, init->idlePulse);
|
||||||
} else if (init->motorPwmRate > 500) {
|
} else if (init->motorPwmRate > 500) {
|
||||||
pwmBrushedMotorConfig(timerHardwarePtr, pwmOutputConfiguration.motorCount, init->motorPwmRate, init->idlePulse);
|
pwmBrushedMotorConfig(timerHardwarePtr, pwmOutputConfiguration.motorCount, init->motorPwmRate, init->idlePulse);
|
||||||
} else {
|
} else {
|
||||||
|
|
|
@ -56,6 +56,7 @@ typedef struct drv_pwm_config_t {
|
||||||
#endif
|
#endif
|
||||||
bool useVbat;
|
bool useVbat;
|
||||||
bool useOneshot;
|
bool useOneshot;
|
||||||
|
bool useFastPWM;
|
||||||
bool useSoftSerial;
|
bool useSoftSerial;
|
||||||
bool useLEDStrip;
|
bool useLEDStrip;
|
||||||
#ifdef SONAR
|
#ifdef SONAR
|
||||||
|
|
|
@ -186,6 +186,13 @@ 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)
|
||||||
|
{
|
||||||
|
uint32_t hz = PWM_BRUSHED_TIMER_MHZ * 1000000;
|
||||||
|
motors[motorIndex] = pwmOutConfig(timerHardware, ONESHOT125_TIMER_MHZ, hz / 4000, idlePulse);
|
||||||
|
motors[motorIndex]->pwmWritePtr = pwmWriteStandard;
|
||||||
|
}
|
||||||
|
|
||||||
void pwmOneshotMotorConfig(const timerHardware_t *timerHardware, uint8_t motorIndex)
|
void pwmOneshotMotorConfig(const timerHardware_t *timerHardware, uint8_t motorIndex)
|
||||||
{
|
{
|
||||||
motors[motorIndex] = pwmOutConfig(timerHardware, ONESHOT125_TIMER_MHZ, 0xFFFF, 0);
|
motors[motorIndex] = pwmOutConfig(timerHardware, ONESHOT125_TIMER_MHZ, 0xFFFF, 0);
|
||||||
|
|
|
@ -166,7 +166,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", NULL
|
"BLACKBOX", "CHANNEL_FORWARDING","FASTPWM", NULL
|
||||||
};
|
};
|
||||||
|
|
||||||
#ifndef CJMCU
|
#ifndef CJMCU
|
||||||
|
|
|
@ -255,6 +255,7 @@ 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.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))
|
||||||
|
|
Loading…
Add table
Add a link
Reference in a new issue