Merge pull request #170 from borisbstyle/cc3d_ppm_timer_conflict

CC3D - don't share timer between PPM capture and motor output
This commit is contained in:
borisbstyle 2016-02-08 23:00:53 +01:00
commit 7bef1db230
5 changed files with 47 additions and 36 deletions

View File

@ -22,12 +22,14 @@ The 8 pin RC_Input connector has the following pinouts when used in RX_PPM/RX_SE
| --- | --------- | -------------------------------- |
| 1 | Ground | |
| 2 | +5V | |
| 3 | PPM Input | Enable `feature RX_PPM` |
| 3 | Unused | |
| 4 | SoftSerial1 TX / Sonar trigger | |
| 5 | SoftSerial1 RX / Sonar Echo | |
| 5 | SoftSerial1 RX / Sonar Echo / RSSI_ADC | Used either for SOFTSERIAL, SONAR or RSSI_ADC*. Only one feature can be enabled at any time. |
| 6 | Current | Enable `feature CURRENT_METER`. Connect to the output of a current sensor, 0v-3.3v input |
| 7 | Battery Voltage sensor | Enable `feature VBAT`. Connect to main battery using a voltage divider, 0v-3.3v input |
| 8 | RSSI | Enable `feature RSSI_ADC`. Connect to the output of a PWM-RSSI conditioner, 0v-3.3v input |
| 8 | PPM Input | Enable `feature RX_PPM` |
*Connect to the output of a PWM-RSSI conditioner, 0v-3.3v input.
The 6 pin RC_Output connector has the following pinouts when used in RX_PPM/RX_SERIAL mode

View File

@ -890,9 +890,19 @@ void validateAndFixConfig(void)
masterConfig.telemetryConfig.telemetry_inversion = 1;
#endif
#if defined(CC3D) && defined(SONAR) && defined(USE_SOFTSERIAL1)
if (feature(FEATURE_SONAR) && feature(FEATURE_SOFTSERIAL)) {
featureClear(FEATURE_SONAR);
#if defined(LED_STRIP) && defined(TRANSPONDER)
if ((WS2811_DMA_TC_FLAG == TRANSPONDER_DMA_TC_FLAG) && featureConfigured(FEATURE_TRANSPONDER) && featureConfigured(FEATURE_LED_STRIP)) {
featureClear(FEATURE_LED_STRIP);
}
#endif
#if defined(CC3D) && defined(SONAR) && defined(USE_SOFTSERIAL1) && defined(RSSI_ADC_GPIO)
// shared pin
if ((featureConfigured(FEATURE_SONAR) + featureConfigured(FEATURE_SOFTSERIAL) + featureConfigured(FEATURE_RSSI_ADC)) > 1) {
featureClear(FEATURE_SONAR);
featureClear(FEATURE_SOFTSERIAL);
featureClear(FEATURE_RSSI_ADC);
}
#endif

View File

@ -146,18 +146,17 @@ static const uint16_t airPWM[] = {
#ifdef CC3D
static const uint16_t multiPPM[] = {
PWM1 | (MAP_TO_PPM_INPUT << 8), // PPM input
PWM7 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed
PWM8 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed
PWM9 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM10 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM6 | (MAP_TO_PPM_INPUT << 8), // PPM input
PWM7 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #1
PWM8 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #2
PWM9 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #3
PWM10 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #4
PWM11 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM12 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM2 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed
PWM3 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed
PWM4 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed
PWM5 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed
PWM6 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed
0xFFFF
};
@ -178,7 +177,7 @@ static const uint16_t multiPWM[] = {
};
static const uint16_t airPPM[] = {
PWM1 | (MAP_TO_PPM_INPUT << 8), // PPM input
PWM6 | (MAP_TO_PPM_INPUT << 8), // PPM input
PWM7 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM8 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM9 | (MAP_TO_SERVO_OUTPUT << 8),
@ -189,7 +188,6 @@ static const uint16_t airPPM[] = {
PWM3 | (MAP_TO_SERVO_OUTPUT << 8),
PWM4 | (MAP_TO_SERVO_OUTPUT << 8),
PWM5 | (MAP_TO_SERVO_OUTPUT << 8),
PWM6 | (MAP_TO_SERVO_OUTPUT << 8),
0xFFFF
};
@ -209,17 +207,16 @@ static const uint16_t airPWM[] = {
0xFFFF
};
static const uint16_t multiPPM_BP6[] = {
PWM1 | (MAP_TO_PPM_INPUT << 8), // PPM input
PWM7 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed
PWM8 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed
PWM9 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM10 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM6 | (MAP_TO_PPM_INPUT << 8), // PPM input
PWM7 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #1
PWM8 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #2
PWM9 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #3
PWM10 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #4
PWM11 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM2 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed
PWM3 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed
PWM4 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed
PWM5 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed
PWM6 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed
0xFFFF
};
@ -239,7 +236,7 @@ static const uint16_t multiPWM_BP6[] = {
};
static const uint16_t airPPM_BP6[] = {
PWM1 | (MAP_TO_PPM_INPUT << 8), // PPM input
PWM6 | (MAP_TO_PPM_INPUT << 8), // PPM input
PWM7 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM8 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM9 | (MAP_TO_SERVO_OUTPUT << 8),
@ -249,7 +246,6 @@ static const uint16_t airPPM_BP6[] = {
PWM3 | (MAP_TO_SERVO_OUTPUT << 8),
PWM4 | (MAP_TO_SERVO_OUTPUT << 8),
PWM5 | (MAP_TO_SERVO_OUTPUT << 8),
PWM6 | (MAP_TO_SERVO_OUTPUT << 8),
0xFFFF
};
@ -784,11 +780,6 @@ if (init->useBuzzerP6) {
#endif
if (type == MAP_TO_PPM_INPUT) {
#ifdef CC3D
if (init->useOneshot || isMotorBrushed(init->motorPwmRate)) {
ppmAvoidPWMTimerClash(timerHardwarePtr, TIM4);
}
#endif
#ifdef SPARKY
if (init->useOneshot || isMotorBrushed(init->motorPwmRate)) {
ppmAvoidPWMTimerClash(timerHardwarePtr, TIM2);
@ -799,6 +790,14 @@ if (init->useBuzzerP6) {
pwmInConfig(timerHardwarePtr, channelIndex);
channelIndex++;
} else if (type == MAP_TO_MOTOR_OUTPUT) {
#ifdef CC3D
if (init->useOneshot || isMotorBrushed(init->motorPwmRate)){
// Skip it if it would cause PPM capture timer to be reconfigured or manually overflowed
if (timerHardwarePtr->tim == TIM2)
continue;
}
#endif
if (init->useOneshot) {
if (init->useFastPWM) {
fastPWMMotorConfig(timerHardwarePtr, pwmOutputConfiguration.motorCount, init->motorPwmRate, init->idlePulse);

View File

@ -68,12 +68,12 @@ const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
#ifdef CC3D
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
{ TIM4, GPIOB, Pin_6, TIM_Channel_1, TIM4_IRQn, 0, Mode_IPD}, // S1_IN - PPM
{ TIM3, GPIOB, Pin_5, TIM_Channel_2, TIM3_IRQn, 0, Mode_IPD}, // S2_IN - SoftSerial TX - GPIO_PartialRemap_TIM3
{ TIM3, GPIOB, Pin_0, TIM_Channel_3, TIM3_IRQn, 0, Mode_IPD}, // S3_IN - SoftSerial RX
{ TIM3, GPIOB, Pin_1, TIM_Channel_4, TIM3_IRQn, 0, Mode_IPD}, // S4_IN - Current
{ TIM2, GPIOA, Pin_0, TIM_Channel_1, TIM2_IRQn, 0, Mode_IPD}, // S5_IN - Vbattery
{ TIM2, GPIOA, Pin_1, TIM_Channel_2, TIM2_IRQn, 0, Mode_IPD}, // S6_IN - RSSI
{ TIM4, GPIOB, Pin_6, TIM_Channel_1, TIM4_IRQn, 0, Mode_IPD}, // S1_IN
{ TIM3, GPIOB, Pin_5, TIM_Channel_2, TIM3_IRQn, 0, Mode_IPD}, // S2_IN - SoftSerial TX - GPIO_PartialRemap_TIM3 / Sonar trigger
{ TIM3, GPIOB, Pin_0, TIM_Channel_3, TIM3_IRQn, 0, Mode_IPD}, // S3_IN - SoftSerial RX / Sonar echo / RSSI ADC
{ TIM3, GPIOB, Pin_1, TIM_Channel_4, TIM3_IRQn, 0, Mode_IPD}, // S4_IN - Current
{ TIM2, GPIOA, Pin_0, TIM_Channel_1, TIM2_IRQn, 0, Mode_IPD}, // S5_IN - Vbattery
{ TIM2, GPIOA, Pin_1, TIM_Channel_2, TIM2_IRQn, 0, Mode_IPD}, // S6_IN - PPM IN
{ TIM4, GPIOB, Pin_9, TIM_Channel_4, TIM4_IRQn, 1, GPIO_Mode_AF_PP}, // S1_OUT
{ TIM4, GPIOB, Pin_8, TIM_Channel_3, TIM4_IRQn, 1, GPIO_Mode_AF_PP}, // S2_OUT

View File

@ -108,9 +108,9 @@
#define VBAT_ADC_GPIO_PIN GPIO_Pin_0
#define VBAT_ADC_CHANNEL ADC_Channel_0
#define RSSI_ADC_GPIO GPIOA
#define RSSI_ADC_GPIO_PIN GPIO_Pin_1
#define RSSI_ADC_CHANNEL ADC_Channel_1
#define RSSI_ADC_GPIO GPIOB
#define RSSI_ADC_GPIO_PIN GPIO_Pin_0
#define RSSI_ADC_CHANNEL ADC_Channel_8
#define GPS
#define LED_STRIP