Browse Source

[bsp] [stm32] 更新spi usart的时钟设置 更新脚本设置

Hao Zhu 6 years ago
parent
commit
ec93984094

+ 60 - 0
bsp/stm32/libraries/HAL_Drivers/config/f7/pwm_config.h

@@ -0,0 +1,60 @@
+/*
+ * Copyright (c) 2006-2018, RT-Thread Development Team
+ *
+ * SPDX-License-Identifier: Apache-2.0
+ *
+ * Change Logs:
+ * Date           Author       Notes
+ * 2018-12-13     zylx         first version
+ */
+
+#ifndef __PWM_CONFIG_H__
+#define __PWM_CONFIG_H__
+
+#include <rtthread.h>
+
+#ifdef BSP_USING_PWM2
+#ifndef PWM2_CONFIG
+#define PWM2_CONFIG                             \
+    {                                           \
+       .tim_handle.Instance     = TIM2,         \
+       .name                    = "pwm2",       \
+       .channel                 = 0             \
+    }
+#endif /* PWM2_CONFIG */
+#endif /* BSP_USING_PWM2 */
+
+#ifdef BSP_USING_PWM3
+#ifndef PWM3_CONFIG
+#define PWM3_CONFIG                             \
+    {                                           \
+       .tim_handle.Instance     = TIM3,         \
+       .name                    = "pwm3",       \
+       .channel                 = 0             \
+    }
+#endif /* PWM3_CONFIG */
+#endif /* BSP_USING_PWM3 */
+
+#ifdef BSP_USING_PWM4
+#ifndef PWM4_CONFIG
+#define PWM4_CONFIG                             \
+    {                                           \
+       .tim_handle.Instance     = TIM4,         \
+       .name                    = "pwm4",       \
+       .channel                 = 0             \
+    }
+#endif /* PWM4_CONFIG */
+#endif /* BSP_USING_PWM4 */
+
+#ifdef BSP_USING_PWM5
+#ifndef PWM5_CONFIG
+#define PWM5_CONFIG                             \
+    {                                           \
+       .tim_handle.Instance     = TIM5,         \
+       .name                    = "pwm5",       \
+       .channel                 = 0             \
+    }
+#endif /* PWM5_CONFIG */
+#endif /* BSP_USING_PWM5 */
+
+#endif /* __PWM_CONFIG_H__ */

+ 38 - 0
bsp/stm32/libraries/HAL_Drivers/config/f7/sdio_config.h

@@ -0,0 +1,38 @@
+/*
+ * Copyright (c) 2006-2018, RT-Thread Development Team
+ *
+ * SPDX-License-Identifier: Apache-2.0
+ *
+ * Change Logs:
+ * Date           Author       Notes
+ * 2018-12-13     BalanceTWK   first version
+ */
+
+#ifndef __SDIO_CONFIG_H__
+#define __SDIO_CONFIG_H__
+
+#include <rtthread.h>
+#include "stm32f7xx_hal.h"
+
+#ifdef BSP_USING_SDIO
+#define SDIO_BUS_CONFIG                                  \
+    {                                                    \
+        .Instance = SDIO,                                \
+        .dma_rx.dma_rcc = RCC_AHB1ENR_DMA2EN,            \
+        .dma_tx.dma_rcc = RCC_AHB1ENR_DMA2EN,            \
+        .dma_rx.Instance = DMA2_Stream3,                 \
+        .dma_rx.channel = DMA_CHANNEL_4,                 \
+        .dma_rx.dma_irq = DMA2_Stream3_IRQn,             \
+        .dma_tx.Instance = DMA2_Stream6,                 \
+        .dma_tx.channel = DMA_CHANNEL_4,                 \
+        .dma_tx.dma_irq = DMA2_Stream6_IRQn,             \
+    }
+
+#define SPI1_DMA_RX_IRQHandler           DMA2_Stream3_IRQHandler
+#define SPI1_DMA_TX_IRQHandler           DMA2_Stream6_IRQHandler
+#endif
+
+#endif /*__SDIO_CONFIG_H__ */
+
+
+

+ 59 - 0
bsp/stm32/libraries/HAL_Drivers/config/f7/tim_config.h

@@ -0,0 +1,59 @@
+/*
+ * Copyright (c) 2006-2018, RT-Thread Development Team
+ *
+ * SPDX-License-Identifier: Apache-2.0
+ *
+ * Change Logs:
+ * Date           Author       Notes
+ * 2018-12-11     zylx         first version
+ */
+
+#ifndef __TIM_CONFIG_H__
+#define __TIM_CONFIG_H__
+
+#include <rtthread.h>
+
+#ifndef TIM_DEV_INFO_CONFIG
+#define TIM_DEV_INFO_CONFIG                     \
+    {                                           \
+        .maxfreq = 1000000,                     \
+        .minfreq = 3000,                        \
+        .maxcnt  = 0xFFFF,                      \
+        .cntmode = HWTIMER_CNTMODE_UP,          \
+    }
+#endif /* TIM_DEV_INFO_CONFIG */
+
+#ifdef BSP_USING_TIM11
+#ifndef TIM11_CONFIG
+#define TIM11_CONFIG                                        \
+    {                                                       \
+       .tim_handle.Instance     = TIM11,                    \
+       .tim_irqn                = TIM1_TRG_COM_TIM11_IRQn,  \
+       .name                    = "timer11",                \
+    }
+#endif /* TIM11_CONFIG */
+#endif /* BSP_USING_TIM11 */
+
+#ifdef BSP_USING_TIM13
+#ifndef TIM13_CONFIG
+#define TIM13_CONFIG                                        \
+    {                                                       \
+       .tim_handle.Instance     = TIM13,                    \
+       .tim_irqn                = TIM8_UP_TIM13_IRQn,       \
+       .name                    = "timer13",                \
+    }
+#endif /* TIM13_CONFIG */
+#endif /* BSP_USING_TIM13 */
+
+#ifdef BSP_USING_TIM14
+#ifndef TIM14_CONFIG
+#define TIM14_CONFIG                                        \
+    {                                                       \
+       .tim_handle.Instance     = TIM14,                    \
+       .tim_irqn                = TIM8_TRG_COM_TIM14_IRQn,  \
+       .name                    = "timer14",                \
+    }
+#endif /* TIM14_CONFIG */
+#endif /* BSP_USING_TIM14 */
+
+#endif /* __TIM_CONFIG_H__ */

+ 11 - 0
bsp/stm32/libraries/HAL_Drivers/drv_config.h

@@ -18,18 +18,29 @@
 #include "f1/uart_config.h"
 #include "f1/spi_config.h"
 #include "f1/adc_config.h"
+#include "f1/tim_config.h"
+#include "f1/sdio_config.h"
+#include "f1/pwm_config.h"
 #elif  defined(SOC_SERIES_STM32F4)
 #include "f4/uart_config.h"
 #include "f4/spi_config.h"
 #include "f4/adc_config.h"
+#include "f4/tim_config.h"
+#include "f4/sdio_config.h"
+#include "f4/pwm_config.h"
 #elif  defined(SOC_SERIES_STM32F7)
 #include "f7/uart_config.h"
 #include "f7/spi_config.h"
 #include "f7/adc_config.h"
+#include "f7/tim_config.h"
+#include "f7/sdio_config.h"
+#include "f7/pwm_config.h"
 #elif  defined(SOC_SERIES_STM32L4)
 #include "l4/uart_config.h"
 #include "l4/spi_config.h"
 #include "l4/adc_config.h"
+#include "l4/tim_config.h"
+#include "l4/pwm_config.h"
 #endif
 
 #endif

+ 4 - 0
bsp/stm32/libraries/HAL_Drivers/drv_spi.c

@@ -488,6 +488,10 @@ static int rt_hw_spi_bus_init(void)
             SET_BIT(RCC->AHB1ENR, spi_config[i].dma_rx.dma_rcc);
             /* Delay after an RCC peripheral clock enabling */
             tmpreg = READ_BIT(RCC->AHB1ENR, spi_config[i].dma_rx.dma_rcc);
+#elif defined(SOC_SERIES_STM32F7)
+            SET_BIT(RCC->APB2ENR, RCC_APB2ENR_SPI1EN);\
+            /* Delay after an RCC peripheral clock enabling */ \
+            tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_SPI1EN);\
 #endif
             UNUSED(tmpreg); /* To avoid compiler warnings */
         }

+ 5 - 1
bsp/stm32/libraries/HAL_Drivers/drv_usart.c

@@ -492,7 +492,11 @@ static void stm32_dma_config(struct rt_serial_device *serial)
         /* enable DMA clock && Delay after an RCC peripheral clock enabling*/
         SET_BIT(RCC->AHBENR, uart->config->dma_rcc);
         tmpreg = READ_BIT(RCC->AHBENR, uart->config->dma_rcc);
-#elif defined(SOC_SERIES_STM32F4) || defined(SOC_SERIES_STM32F7) || defined(SOC_SERIES_STM32L4)
+#elif defined(SOC_SERIES_STM32F4) || defined(SOC_SERIES_STM32L4)
+        /* enable DMA clock && Delay after an RCC peripheral clock enabling*/
+        SET_BIT(RCC->AHB1ENR, uart->config->dma_rcc);
+        tmpreg = READ_BIT(RCC->AHB1ENR, uart->config->dma_rcc);
+#elif defined(SOC_SERIES_STM32F7)
         /* enable DMA clock && Delay after an RCC peripheral clock enabling*/
         SET_BIT(RCC->AHB1ENR, uart->config->dma_rcc);
         tmpreg = READ_BIT(RCC->AHB1ENR, uart->config->dma_rcc);

+ 86 - 2
bsp/stm32/libraries/STM32F7xx_HAL/SConscript

@@ -6,11 +6,95 @@ cwd = GetCurrentDir()
 
 # The set of source files associated with this SConscript file.
 
-src = Glob('STM32F7xx_HAL_Driver/Src/*.c')
-src += Split('''
+src = Split('''
 CMSIS/Device/ST/STM32F7xx/Source/Templates/system_stm32f7xx.c
+STM32F7xx_HAL_Driver/Src/stm32f7xx_hal.c
+STM32F7xx_HAL_Driver/Src/stm32f7xx_hal_cec.c
+STM32F7xx_HAL_Driver/Src/stm32f7xx_hal_cortex.c
+STM32F7xx_HAL_Driver/Src/stm32f7xx_hal_crc.c
+STM32F7xx_HAL_Driver/Src/stm32f7xx_hal_cryp.c
+STM32F7xx_HAL_Driver/Src/stm32f7xx_hal_cryp_ex.c
+STM32F7xx_HAL_Driver/Src/stm32f7xx_hal_dma.c
+STM32F7xx_HAL_Driver/Src/stm32f7xx_hal_dma_ex.c
+STM32F7xx_HAL_Driver/Src/stm32f7xx_hal_pwr.c
+STM32F7xx_HAL_Driver/Src/stm32f7xx_hal_pwr_ex.c
+STM32F7xx_HAL_Driver/Src/stm32f7xx_hal_rcc.c
+STM32F7xx_HAL_Driver/Src/stm32f7xx_hal_rcc_ex.c
+STM32F7xx_HAL_Driver/Src/stm32f7xx_hal_rng.c
+STM32F7xx_HAL_Driver/Src/stm32f7xx_hal_sram.c
 ''')
 
+if GetDepend(['RT_USING_PIN']):
+    src += ['STM32F7xx_HAL_Driver/Src/stm32f7xx_hal_gpio.c']
+    
+if GetDepend(['RT_USING_SERIAL']):
+    src += ['STM32F7xx_HAL_Driver/Src/stm32f7xx_hal_uart.c']
+    src += ['STM32F7xx_HAL_Driver/Src/stm32f7xx_hal_usart.c']
+
+if GetDepend(['RT_USING_I2C']):
+    src += ['STM32F7xx_HAL_Driver/Src/stm32f7xx_hal_i2c.c']
+    src += ['STM32F7xx_HAL_Driver/Src/stm32f7xx_hal_i2c_ex.c']
+
+if GetDepend(['RT_USING_SPI']):
+    src += ['STM32F7xx_HAL_Driver/Src/stm32f7xx_hal_spi.c']
+    src += ['STM32F7xx_HAL_Driver/Src/stm32f7xx_hal_qspi.c']
+
+if GetDepend(['RT_USING_USB_HOST']) or GetDepend(['RT_USING_USB_DEVICE']):
+    src += ['STM32F7xx_HAL_Driver/Src/stm32f7xx_hal_pccard.c']
+    src += ['STM32F7xx_HAL_Driver/Src/stm32f7xx_hal_pcd.c'] 
+    src += ['STM32F7xx_HAL_Driver/Src/stm32f7xx_hal_pcd_ex.c']
+    src += ['STM32F7xx_HAL_Driver/Src/stm32f7xx_hal_hcd.c']
+    src += ['STM32F7xx_HAL_Driver/Src/stm32f7xx_ll_usb.c']
+
+if GetDepend(['RT_USING_CAN']):
+    src += ['STM32F7xx_HAL_Driver/Src/stm32f7xx_hal_can.c']
+
+if GetDepend(['RT_USING_HWTIMER']) or GetDepend(['RT_USING_PWM']):
+    src += ['STM32F7xx_HAL_Driver/Src/stm32f7xx_hal_tim.c']
+    src += ['STM32F7xx_HAL_Driver/Src/stm32f7xx_hal_tim_ex.c']
+    src += ['STM32F7xx_HAL_Driver/Src/stm32f7xx_hal_lptim.c']
+
+if GetDepend(['BSP_USING_ETH']):
+    src += ['STM32F7xx_HAL_Driver/Src/stm32f7xx_hal_eth.c']
+
+if GetDepend(['RT_USING_ADC']):
+    src += ['STM32F7xx_HAL_Driver/Src/stm32f7xx_hal_adc.c']
+    src += ['STM32F7xx_HAL_Driver/Src/stm32f7xx_hal_adc_ex.c']
+
+if GetDepend(['RT_USING_RTC']):
+    src += ['STM32F7xx_HAL_Driver/Src/stm32f7xx_hal_rtc.c']
+    src += ['STM32F7xx_HAL_Driver/Src/stm32f7xx_hal_rtc_ex.c']
+
+if GetDepend(['RT_USING_WDT']):
+    src += ['STM32F7xx_HAL_Driver/Src/stm32f7xx_hal_iwdg.c']
+    src += ['STM32F7xx_HAL_Driver/Src/stm32f7xx_hal_wwdg.c']
+
+if GetDepend(['RT_USING_SDIO']):
+    src += ['STM32F7xx_HAL_Driver/Src/stm32f7xx_ll_sdmmc.c']
+    src += ['STM32F7xx_HAL_Driver/Src/stm32f7xx_hal_sd.c']
+
+if GetDepend(['RT_USING_AUDIO']):
+    src += ['STM32F7xx_HAL_Driver/Src/stm32f7xx_hal_i2s.c']
+    src += ['STM32F7xx_HAL_Driver/Src/stm32f7xx_hal_i2s_ex.c']
+    src += ['STM32F7xx_HAL_Driver/Src/stm32f7xx_hal_sai.c']
+    src += ['STM32F7xx_HAL_Driver/Src/stm32f7xx_hal_sai_ex.c']
+
+if GetDepend(['RT_USING_MTD_NOR']):
+    src += ['STM32F7xx_HAL_Driver/Src/stm32f7xx_hal_nor.c']
+
+if GetDepend(['RT_USING_MTD_NAND']):
+    src += ['STM32F7xx_HAL_Driver/Src/stm32f7xx_hal_nand.c']
+
+if GetDepend(['BSP_USING_SDRAM']):
+    src += ['STM32F7xx_HAL_Driver/Src/stm32f7xx_ll_fmc.c']
+    src += ['STM32F7xx_HAL_Driver/Src/stm32f7xx_ll_fsmc.c']
+    src += ['STM32F7xx_HAL_Driver/Src/stm32f7xx_hal_sdram.c']
+
+if GetDepend(['BSP_USING_ON_CHIP_FLASH']):
+    src += ['STM32F7xx_HAL_Driver/Src/stm32f7xx_hal_flash.c']
+    src += ['STM32F7xx_HAL_Driver/Src/stm32f7xx_hal_flash_ex.c']
+    src += ['STM32F7xx_HAL_Driver/Src/stm32f7xx_hal_flash_ramfunc.c']
+
 path = [cwd + '/STM32F7xx_HAL_Driver/Inc',
     cwd + '/CMSIS/Device/ST/STM32F7xx/Include',
     cwd + '/CMSIS/Include']

+ 78 - 39
bsp/stm32/stm32f767-fire-challenger/board/Kconfig

@@ -34,6 +34,40 @@ menu "Onboard Peripheral Drivers"
         select PKG_USING_MPU6XXX
         default n
 
+    config BSP_USING_ETH
+        bool "Enable Ethernet"
+        default n
+        select RT_USING_LWIP
+        if BSP_USING_ETH
+            config EXTERNAL_PHY_ADDRESS
+                hex
+                default 0x00
+        endif
+
+    config BSP_USING_RGB
+        bool "Enable RGB LED (timer5 channel1 - 3)"
+        select RT_USING_PWM
+        select BSP_USING_PWM
+        select BSP_USING_PWM5
+        select BSP_USING_PWM5_CH1
+        select BSP_USING_PWM5_CH2
+        select BSP_USING_PWM5_CH3
+        default n    
+
+    config BSP_USING_POT
+        bool "Enable potentiometer"
+        select BSP_USING_ADC
+        select BSP_USING_ADC1
+        default n
+
+    config BSP_USING_SDCARD
+        bool "Enable SDCARD (sdio)"
+        select BSP_USING_SDIO
+        select RT_USING_DFS
+        select RT_USING_DFS_ELMFAT
+        select RT_USING_PIN
+        default n
+
 endmenu
 
 menu "On-chip Peripheral Drivers"
@@ -90,6 +124,47 @@ menu "On-chip Peripheral Drivers"
         select RT_USING_QSPI
         select RT_USING_SPI
         default n
+
+    menuconfig BSP_USING_TIM
+        bool "Enable timer"
+        default n
+        select RT_USING_HWTIMER
+        if BSP_USING_TIM
+            config BSP_USING_TIM11
+                bool "Enable TIM11"
+                default n
+
+            config BSP_USING_TIM13
+                bool "Enable TIM13"
+                default n
+
+            config BSP_USING_TIM14
+                bool "Enable TIM14"
+                default n
+        endif
+
+    menuconfig BSP_USING_PWM
+        bool "Enable pwm"
+        default n
+        select RT_USING_PWM
+        if BSP_USING_PWM
+        menuconfig BSP_USING_PWM5
+            bool "Enable timer5 output pwm"
+            default n
+            if BSP_USING_PWM5
+                config BSP_USING_PWM5_CH1
+                    bool "Enable PWM5 channel1"
+                    default n
+
+                config BSP_USING_PWM5_CH2
+                    bool "Enable PWM5 channel2"
+                    default n
+
+                config BSP_USING_PWM5_CH3
+                    bool "Enable PWM5 channel3"
+                    default n
+            endif
+        endif
         
     menuconfig BSP_USING_ADC
         bool "Enable ADC"
@@ -109,24 +184,6 @@ menu "On-chip Peripheral Drivers"
                 default n
         endif
 
-    menuconfig BSP_USING_I2C1
-        bool "Enable I2C1 BUS (software simulation)"
-        default n
-        select RT_USING_I2C
-        select RT_USING_I2C_BITOPS
-        select RT_USING_PIN
-        if BSP_USING_I2C1
-            comment "Notice: PB6 --> 22; PB7 --> 23" 
-            config BSP_I2C1_SCL_PIN
-                int "I2C1 scl pin number"
-                range 1 176
-                default 22
-            config BSP_I2C1_SDA_PIN
-                int "I2C1 sda pin number"
-                range 1 176
-                default 23
-        endif
-
     menuconfig BSP_USING_I2C2
         bool "Enable I2C2 BUS (software simulation)"
         default n
@@ -134,33 +191,15 @@ menu "On-chip Peripheral Drivers"
         select RT_USING_I2C_BITOPS
         select RT_USING_PIN
         if BSP_USING_I2C2
-            comment "Notice: PC15 --> 47; PD0 --> 48"
+            comment "Notice: PH4 --> 116; PH5 --> 117"
             config BSP_I2C2_SCL_PIN
                 int "i2c2 scl pin number"
                 range 1 176
-                default 47
+                default 116
             config BSP_I2C2_SDA_PIN
                 int "I2C2 sda pin number"
                 range 1 176
-                default 48
-        endif
-
-    menuconfig BSP_USING_I2C3
-        bool "Enable I2C3 BUS (software simulation)"
-        default n
-        select RT_USING_I2C
-        select RT_USING_I2C_BITOPS
-        select RT_USING_PIN
-        if BSP_USING_I2C3
-            comment "Notice: PF12 --> 92; PF13 --> 93"
-            config BSP_I2C3_SCL_PIN
-                int "i2c3 scl pin number"
-                range 1 176
-                default 92
-            config BSP_I2C3_SDA_PIN
-                int "I2C3 sda pin number"
-                range 1 176
-                default 93
+                default 117
         endif
 
     menuconfig BSP_USING_I2C4

+ 3 - 0
bsp/stm32/stm32f767-fire-challenger/board/SConscript

@@ -18,6 +18,9 @@ if GetDepend(['BSP_USING_ETH']):
 if GetDepend(['BSP_USING_QSPI_FLASH']):
     src += Glob('ports/drv_qspi_flash.c')
 
+if GetDepend(['BSP_USING_SDCARD']):
+    src += Glob('ports/sdcard_port.c')
+
 path =  [cwd]
 path += [cwd + '/CubeMX_Config/Inc']
 path += [cwd + '/ports']