CC3D - Hack to enable a simple quad configuration using PPM input to be
tested. PPM and motor outputs conflict since they use the same timers so this just avoids conflicts.
This commit is contained in:
parent
668e8f1298
commit
053a28dc62
|
@ -139,6 +139,16 @@ static const uint16_t airPWM[] = {
|
|||
#endif
|
||||
|
||||
#if USABLE_TIMER_CHANNEL_COUNT == 12
|
||||
#ifdef CC3D // XXX HACK while PPM and MOTOR code conflicts.
|
||||
static const uint16_t multiPPM[] = {
|
||||
PWM6 | (TYPE_IP << 8), // PPM input
|
||||
PWM7 | (TYPE_M << 8), // Swap to servo if needed
|
||||
PWM8 | (TYPE_M << 8), // Swap to servo if needed
|
||||
PWM9 | (TYPE_M << 8),
|
||||
PWM10 | (TYPE_M << 8),
|
||||
0xFFFF
|
||||
};
|
||||
#else
|
||||
static const uint16_t multiPPM[] = {
|
||||
PWM1 | (TYPE_IP << 8), // PPM input
|
||||
PWM7 | (TYPE_M << 8), // Swap to servo if needed
|
||||
|
@ -154,7 +164,7 @@ static const uint16_t multiPPM[] = {
|
|||
PWM6 | (TYPE_M << 8), // Swap to servo if needed
|
||||
0xFFFF
|
||||
};
|
||||
|
||||
#endif
|
||||
static const uint16_t multiPWM[] = {
|
||||
PWM1 | (TYPE_IW << 8), // input #1
|
||||
PWM2 | (TYPE_IW << 8),
|
||||
|
|
|
@ -104,12 +104,12 @@ const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
|
|||
{ TIM2, GPIOA, Pin_0, TIM_Channel_1, TIM2_IRQn, 0, Mode_IPD}, // S5_IN
|
||||
{ TIM2, GPIOA, Pin_1, TIM_Channel_2, TIM2_IRQn, 0, Mode_IPD}, // S6_IN
|
||||
|
||||
{ TIM4, GPIOB, Pin_9, TIM_Channel_4, TIM4_IRQn, 0, GPIO_Mode_AF_PP}, // S1_OUT
|
||||
{ TIM4, GPIOB, Pin_8, TIM_Channel_3, TIM4_IRQn, 0, GPIO_Mode_AF_PP}, // S2_OUT
|
||||
{ TIM4, GPIOB, Pin_7, TIM_Channel_2, TIM4_IRQn, 0, GPIO_Mode_AF_PP}, // S3_OUT
|
||||
{ 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
|
||||
{ TIM4, GPIOB, Pin_7, TIM_Channel_2, TIM4_IRQn, 1, GPIO_Mode_AF_PP}, // S3_OUT
|
||||
{ TIM1, GPIOA, Pin_8, TIM_Channel_1, TIM1_CC_IRQn, 1, GPIO_Mode_AF_PP}, // S4_OUT
|
||||
{ TIM3, GPIOB, Pin_4, TIM_Channel_1, TIM3_IRQn, 0, GPIO_Mode_AF_PP}, // S5_OUT - GPIO_PartialRemap_TIM3
|
||||
{ TIM2, GPIOA, Pin_2, TIM_Channel_3, TIM2_IRQn, 0, GPIO_Mode_AF_PP}, // S6_OUT
|
||||
{ TIM3, GPIOB, Pin_4, TIM_Channel_1, TIM3_IRQn, 1, GPIO_Mode_AF_PP}, // S5_OUT - GPIO_PartialRemap_TIM3
|
||||
{ TIM2, GPIOA, Pin_2, TIM_Channel_3, TIM2_IRQn, 1, GPIO_Mode_AF_PP}, // S6_OUT
|
||||
};
|
||||
|
||||
#define MAX_TIMERS 4 // TIM1..TIM4
|
||||
|
|
Loading…
Reference in New Issue