Merge pull request #159 from Pierre-A/cc3d-updates-pa
RSSI monitoring on CC3D
This commit is contained in:
commit
249b09abce
|
@ -70,14 +70,6 @@ void adcInit(drv_adc_config_t *init)
|
|||
adcConfig[ADC_BATTERY].enabled = true;
|
||||
adcConfig[ADC_BATTERY].sampleTime = ADC_SampleTime_239Cycles5;
|
||||
|
||||
if (init->enableCurrentMeter) {
|
||||
GPIO_InitStructure.GPIO_Pin = GPIO_Pin_1;
|
||||
adcConfig[ADC_CURRENT].adcChannel = ADC_Channel_1;
|
||||
adcConfig[ADC_CURRENT].dmaIndex = configuredAdcChannels++;
|
||||
adcConfig[ADC_CURRENT].enabled = true;
|
||||
adcConfig[ADC_CURRENT].sampleTime = ADC_SampleTime_239Cycles5;
|
||||
}
|
||||
GPIO_Init(GPIOA, &GPIO_InitStructure);
|
||||
#else
|
||||
// configure always-present battery index (ADC4)
|
||||
GPIO_InitStructure.GPIO_Pin = GPIO_Pin_4;
|
||||
|
@ -86,19 +78,9 @@ void adcInit(drv_adc_config_t *init)
|
|||
adcConfig[ADC_BATTERY].enabled = true;
|
||||
adcConfig[ADC_BATTERY].sampleTime = ADC_SampleTime_239Cycles5;
|
||||
|
||||
if (init->enableRSSI) {
|
||||
GPIO_InitStructure.GPIO_Pin |= GPIO_Pin_1;
|
||||
|
||||
adcConfig[ADC_RSSI].adcChannel = ADC_Channel_1;
|
||||
adcConfig[ADC_RSSI].dmaIndex = configuredAdcChannels++;
|
||||
adcConfig[ADC_RSSI].enabled = true;
|
||||
adcConfig[ADC_RSSI].sampleTime = ADC_SampleTime_239Cycles5;
|
||||
}
|
||||
|
||||
if (init->enableExternal1) {
|
||||
#ifdef OLIMEXINO
|
||||
GPIO_InitStructure.GPIO_Pin |= GPIO_Pin_5;
|
||||
|
||||
adcConfig[ADC_EXTERNAL1].adcChannel = ADC_Channel_5;
|
||||
adcConfig[ADC_EXTERNAL1].dmaIndex = configuredAdcChannels++;
|
||||
adcConfig[ADC_EXTERNAL1].enabled = true;
|
||||
|
@ -107,26 +89,32 @@ void adcInit(drv_adc_config_t *init)
|
|||
|
||||
#ifdef NAZE
|
||||
GPIO_InitStructure.GPIO_Pin |= GPIO_Pin_5;
|
||||
|
||||
adcConfig[ADC_EXTERNAL1].adcChannel = ADC_Channel_5;
|
||||
adcConfig[ADC_EXTERNAL1].dmaIndex = configuredAdcChannels++;
|
||||
adcConfig[ADC_EXTERNAL1].enabled = true;
|
||||
adcConfig[ADC_EXTERNAL1].sampleTime = ADC_SampleTime_239Cycles5;
|
||||
#endif
|
||||
}
|
||||
#endif // !CC3D
|
||||
|
||||
if (init->enableRSSI) {
|
||||
GPIO_InitStructure.GPIO_Pin |= GPIO_Pin_1;
|
||||
adcConfig[ADC_RSSI].adcChannel = ADC_Channel_1;
|
||||
adcConfig[ADC_RSSI].dmaIndex = configuredAdcChannels++;
|
||||
adcConfig[ADC_RSSI].enabled = true;
|
||||
adcConfig[ADC_RSSI].sampleTime = ADC_SampleTime_239Cycles5;
|
||||
}
|
||||
|
||||
GPIO_Init(GPIOA, &GPIO_InitStructure);
|
||||
|
||||
if (init->enableCurrentMeter) {
|
||||
GPIO_InitStructure.GPIO_Pin = GPIO_Pin_1;
|
||||
GPIO_Init(GPIOB, &GPIO_InitStructure);
|
||||
|
||||
adcConfig[ADC_CURRENT].adcChannel = ADC_Channel_9;
|
||||
adcConfig[ADC_CURRENT].dmaIndex = configuredAdcChannels++;
|
||||
adcConfig[ADC_CURRENT].enabled = true;
|
||||
adcConfig[ADC_CURRENT].sampleTime = ADC_SampleTime_239Cycles5;
|
||||
}
|
||||
#endif // !CC3D
|
||||
|
||||
RCC_AHBPeriphClockCmd(RCC_AHBPeriph_DMA1, ENABLE);
|
||||
RCC_APB2PeriphClockCmd(RCC_APB2Periph_ADC1, ENABLE);
|
||||
|
|
|
@ -305,16 +305,21 @@ pwmOutputConfiguration_t *pwmInit(drv_pwm_config_t *init)
|
|||
#endif
|
||||
|
||||
#ifdef CC3D
|
||||
if (init->useVbat && timerIndex == PWM5) {
|
||||
if (init->useVbat && timerIndex == Vbat_TIMER) {
|
||||
continue;
|
||||
}
|
||||
#endif
|
||||
#ifdef CC3D
|
||||
if (init->useCurrentMeterADC && timerIndex == CurrentMeter_TIMER) {
|
||||
continue;
|
||||
}
|
||||
#endif
|
||||
#ifdef CC3D
|
||||
if (init->useRSSIADC && timerIndex == RSSI_TIMER) {
|
||||
continue;
|
||||
}
|
||||
#endif
|
||||
|
||||
#ifdef CC3D
|
||||
if (init->useCurrentMeterADC && timerIndex == PWM6) {
|
||||
continue;
|
||||
}
|
||||
#endif
|
||||
// hacks to allow current functionality
|
||||
if (type == MAP_TO_PWM_INPUT && !init->useParallelPWM)
|
||||
type = 0;
|
||||
|
|
|
@ -100,12 +100,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
|
||||
{ TIM3, GPIOB, Pin_5, TIM_Channel_2, TIM3_IRQn, 0, Mode_IPD}, // S2_IN - GPIO_PartialRemap_TIM3
|
||||
{ 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 - SoftSerial TX
|
||||
{ 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
|
||||
{ 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_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
|
||||
|
|
|
@ -50,9 +50,12 @@
|
|||
#define SERIAL_PORT_COUNT 3
|
||||
|
||||
#define SOFTSERIAL_1_TIMER TIM3
|
||||
#define SOFTSERIAL_1_TIMER_TX_HARDWARE 1 // PWM 2
|
||||
#define SOFTSERIAL_1_TIMER_RX_HARDWARE 2 // PWM 3
|
||||
#define SOFTSERIAL_1_TIMER_TX_HARDWARE 3 // PWM 4
|
||||
|
||||
#define CurrentMeter_TIMER 3 // PWM4
|
||||
#define Vbat_TIMER 4 // PWM5
|
||||
#define RSSI_TIMER 5 // PWM6
|
||||
|
||||
#define USART3_RX_PIN Pin_11
|
||||
#define USART3_TX_PIN Pin_10
|
||||
|
@ -60,13 +63,10 @@
|
|||
#define USART3_APB1_PERIPHERALS RCC_APB1Periph_USART3
|
||||
#define USART3_APB2_PERIPHERALS RCC_APB2Periph_GPIOB
|
||||
|
||||
|
||||
|
||||
#define USE_SPI
|
||||
#define USE_SPI_DEVICE_1
|
||||
#define USE_SPI_DEVICE_2
|
||||
|
||||
|
||||
#define SENSORS_SET (SENSOR_ACC)
|
||||
|
||||
#define GPS
|
||||
|
|
Loading…
Reference in New Issue