mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-15 20:35:33 +03:00
CC3D - Support 4 PWM inputs and 4 PWM outputs.
Avoid timer clashes on CC3D when using Parallel PWM input. More work needs to be done on the PWM RX/Output code to negate timer clashes.
This commit is contained in:
parent
2d119cba78
commit
30c550b83d
2 changed files with 52 additions and 1 deletions
|
@ -347,6 +347,18 @@ pwmOutputConfiguration_t *pwmInit(drv_pwm_config_t *init)
|
|||
type = MAP_TO_SERVO_OUTPUT;
|
||||
}
|
||||
|
||||
#ifdef CC3D
|
||||
if (init->useParallelPWM) {
|
||||
if ((type == MAP_TO_SERVO_OUTPUT || type == MAP_TO_MOTOR_OUTPUT) && (timerHardwarePtr->tim == TIM2 || timerHardwarePtr->tim == TIM3)) {
|
||||
continue;
|
||||
}
|
||||
if (type == MAP_TO_PWM_INPUT && timerHardwarePtr->tim == TIM4) {
|
||||
continue;
|
||||
}
|
||||
|
||||
}
|
||||
#endif
|
||||
|
||||
if (type == MAP_TO_PPM_INPUT) {
|
||||
ppmInConfig(timerHardwarePtr);
|
||||
} else if (type == MAP_TO_PWM_INPUT) {
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue