mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-16 12:55:19 +03:00
Removing unnecessary idlePulse parameter from pwmOneshotMotorConfig.
This commit is contained in:
parent
0c1a6c5c2f
commit
22a98af25a
2 changed files with 4 additions and 4 deletions
|
@ -31,7 +31,7 @@
|
|||
|
||||
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 pwmOneshotMotorConfig(const timerHardware_t *timerHardware, uint8_t motorIndex, uint16_t idlePulse);
|
||||
void pwmOneshotMotorConfig(const timerHardware_t *timerHardware, uint8_t motorIndex);
|
||||
void pwmServoConfig(const timerHardware_t *timerHardware, uint8_t servoIndex, uint16_t servoPwmRate, uint16_t servoCenterPulse);
|
||||
|
||||
/*
|
||||
|
@ -543,7 +543,7 @@ pwmOutputConfiguration_t *pwmInit(drv_pwm_config_t *init)
|
|||
channelIndex++;
|
||||
} else if (type == MAP_TO_MOTOR_OUTPUT) {
|
||||
if (init->useOneshot) {
|
||||
pwmOneshotMotorConfig(timerHardwarePtr, pwmOutputConfiguration.motorCount, 0);
|
||||
pwmOneshotMotorConfig(timerHardwarePtr, pwmOutputConfiguration.motorCount);
|
||||
} else if (init->motorPwmRate > 500) {
|
||||
pwmBrushedMotorConfig(timerHardwarePtr, pwmOutputConfiguration.motorCount, init->motorPwmRate, init->idlePulse);
|
||||
} else {
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue