1
0
mirror of https://bitbucket.org/librepilot/librepilot.git synced 2024-12-01 09:24:10 +01:00

OP-176 PIOS/ADC: Decrease the priority of the ADC DMA/IRQ

git-svn-id: svn://svn.openpilot.org/OpenPilot/trunk@2360 ebee16cc-31ac-478f-84a7-5cbb03baadba
This commit is contained in:
peabody124 2011-01-09 20:49:43 +00:00 committed by peabody124
parent 0175e25ddf
commit 5734e1f437
2 changed files with 2 additions and 2 deletions

View File

@ -353,7 +353,7 @@ TIM8 | Servo 5 | Servo 6 | Servo 7 | Servo 8
/* With an ADCCLK = 14 MHz and a sampling time of 293.5 cycles: */
/* Tconv = 239.5 + 12.5 = 252 cycles = 18?s */
/* (1 / (ADCCLK / CYCLES)) = Sample Time (?S) */
#define PIOS_ADC_IRQ_PRIO PIOS_IRQ_PRIO_MID
#define PIOS_ADC_IRQ_PRIO PIOS_IRQ_PRIO_LOW
//-------------------------
// GPIO

View File

@ -142,7 +142,7 @@ void PIOS_ADC_Init(void)
DMA_InitStructure.DMA_PeripheralDataSize = DMA_PeripheralDataSize_Word;
DMA_InitStructure.DMA_MemoryDataSize = DMA_MemoryDataSize_Word;
DMA_InitStructure.DMA_Mode = DMA_Mode_Circular;
DMA_InitStructure.DMA_Priority = DMA_Priority_High;
DMA_InitStructure.DMA_Priority = DMA_Priority_Low;
DMA_InitStructure.DMA_M2M = DMA_M2M_Disable;
DMA_Init(DMA1_Channel1, &DMA_InitStructure);
DMA_Cmd(DMA1_Channel1, ENABLE);