1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-16 12:55:19 +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:
Dominic Clifton 2014-11-05 22:32:44 +00:00
parent 2d119cba78
commit 30c550b83d
2 changed files with 52 additions and 1 deletions

View file

@ -13,9 +13,13 @@ have an on-board USB to uart adapter which connect to the processor's serial por
Currently there is no support for virtual com port functionality on the CC3D which means that cleanflight Currently there is no support for virtual com port functionality on the CC3D which means that cleanflight
does not currently use the USB socket at all. does not currently use the USB socket at all.
The board cannot current be used for hexacopters/octocopters.
Tricopter & Airplane support is untested, please report success failure if you try it.
# Pinouts # Pinouts
The 8 pin RC_Input connector has the following pinouts. The 8 pin RC_Input connector has the following pinouts when used in RX_PPM/RX_SERIAL mode
| Pin | Function | Notes | | Pin | Function | Notes |
| --- | ---------| ------| | --- | ---------| ------|
@ -28,6 +32,41 @@ The 8 pin RC_Input connector has the following pinouts.
| 7 | Battery Voltage sensor | Enable `feature VBAT`. Connect to main battery using a voltage divider, 0v-3.3v input | | 7 | Battery Voltage sensor | Enable `feature VBAT`. Connect to main battery using a voltage divider, 0v-3.3v input |
| 8 | Current | Enable `feature CURRENT_METER`. Connect to the output of a current sensor, 0v-3.3v input | | 8 | Current | Enable `feature CURRENT_METER`. Connect to the output of a current sensor, 0v-3.3v input |
The 6 pin RC_Output connector has the following pinouts when used in RX_PPM/RX_SERIAL mode
| Pin | Function | Notes |
| --- | ----------| ------|
| 1 | MOTOR 1 | |
| 2 | MOTOR 2 | |
| 3 | MOTOR 3 | |
| 4 | MOTOR 4 | |
| 5 | Led Strip | |
| 5 | Unused | |
The 8 pin RC_Input connector has the following pinouts when used in RX_PARALLEL_PWM mode
| Pin | Function | Notes |
| --- | ---------| ------|
| 1 | Ground | |
| 2 | +5V | |
| 3 | Unused | |
| 4 | CH1 | |
| 5 | CH2 | |
| 6 | CH3 | |
| 7 | CH4 | |
| 3 | Unused | |
The 6 pin RC_Output connector has the following pinouts when used in RX_PARALLEL_PWM mode
| Pin | Function | Notes |
| --- | ---------| ------|
| 1 | MOTOR 1 | |
| 2 | MOTOR 2 | |
| 3 | MOTOR 3 | |
| 4 | MOTOR 4 | |
| 5 | Unused | |
| 5 | Unused | |
# Serial Ports # Serial Ports
| Value | Identifier | Board Markings | Notes | | Value | Identifier | Board Markings | Notes |

View file

@ -347,6 +347,18 @@ pwmOutputConfiguration_t *pwmInit(drv_pwm_config_t *init)
type = MAP_TO_SERVO_OUTPUT; 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) { if (type == MAP_TO_PPM_INPUT) {
ppmInConfig(timerHardwarePtr); ppmInConfig(timerHardwarePtr);
} else if (type == MAP_TO_PWM_INPUT) { } else if (type == MAP_TO_PWM_INPUT) {