mirror of
https://bitbucket.org/librepilot/librepilot.git
synced 2025-02-20 10:54:14 +01:00
OP-176 OP-238 Flight/IRQ and DMA: Increased the priority of the AHRS DMA
transfer, seems to reduce CRC errors git-svn-id: svn://svn.openpilot.org/OpenPilot/trunk@2356 ebee16cc-31ac-478f-84a7-5cbb03baadba
This commit is contained in:
parent
0f07d7f671
commit
85b7619617
@ -114,7 +114,7 @@ const struct pios_spi_cfg pios_spi_sdcard_cfg = {
|
||||
.flags = (DMA1_FLAG_TC2 | DMA1_FLAG_TE2 | DMA1_FLAG_HT2 | DMA1_FLAG_GL2),
|
||||
.init = {
|
||||
.NVIC_IRQChannel = DMA1_Channel2_IRQn,
|
||||
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGH,
|
||||
.NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID,
|
||||
.NVIC_IRQChannelSubPriority = 0,
|
||||
.NVIC_IRQChannelCmd = ENABLE,
|
||||
},
|
||||
@ -229,7 +229,7 @@ const struct pios_spi_cfg pios_spi_ahrs_cfg = {
|
||||
.DMA_PeripheralDataSize = DMA_PeripheralDataSize_Byte,
|
||||
.DMA_MemoryDataSize = DMA_MemoryDataSize_Byte,
|
||||
.DMA_Mode = DMA_Mode_Normal,
|
||||
.DMA_Priority = DMA_Priority_Medium,
|
||||
.DMA_Priority = DMA_Priority_High,
|
||||
.DMA_M2M = DMA_M2M_Disable,
|
||||
},
|
||||
},
|
||||
@ -243,7 +243,7 @@ const struct pios_spi_cfg pios_spi_ahrs_cfg = {
|
||||
.DMA_PeripheralDataSize = DMA_PeripheralDataSize_Byte,
|
||||
.DMA_MemoryDataSize = DMA_MemoryDataSize_Byte,
|
||||
.DMA_Mode = DMA_Mode_Normal,
|
||||
.DMA_Priority = DMA_Priority_Medium,
|
||||
.DMA_Priority = DMA_Priority_High,
|
||||
.DMA_M2M = DMA_M2M_Disable,
|
||||
},
|
||||
},
|
||||
|
Loading…
x
Reference in New Issue
Block a user