More info for the Shenzhou board configuration

git-svn-id: https://nuttx.svn.sourceforge.net/svnroot/nuttx/trunk@5109 7fd9a85b-ad96-42d3-883c-3090e2eb8679
This commit is contained in:
patacongo 2012-09-07 22:30:35 +00:00
parent aee93b655a
commit e41adbb552
6 changed files with 726 additions and 81 deletions

View File

@ -1562,13 +1562,32 @@ config STM32_MII
---help---
Support Ethernet MII interface.
choice
prompt "MII clock configuration"
default STM32_MII_MCO if STM32_STM32F10XX
default STM32_MII_MCO1 if STM32_STM32F20XX || STM32_STM32F40XX
depends on STM32_MII
config STM32_MII_MCO
bool "Use MC0 as MII clock"
depends on STM32_STM32F10XX
---help---
Use MCO to clock the MII interface. Default: Use MC0
config STM32_MII_MCO1
bool "Use MC01 as MII clock"
depends on (STM32_STM32F20XX || STM32_STM32F40XX)
---help---
Use MCO1 to clock the MII interface. Default: Use MC01
config STM32_MII_MCO2
bool "Use MC02 as MII clock"
default n
depends on STM32_MII
depends on (STM32_STM32F20XX || STM32_STM32F40XX)
---help---
Use MCO2 to clock the MII interface. Default: Use MC01
endchoice
config STM32_AUTONEG
bool "Use autonegtiation"
default y
@ -1643,11 +1662,6 @@ config STM32_RMII
default y if !STM32_MII
depends on STM32_ETHMAC
config STM32_MII_MCO1
bool
default y if !STM32_MII_MCO2
depends on STM32_MII
menu "USB Host Configuration"
config STM32_OTGFS_RXFIFO_SIZE

View File

@ -2659,7 +2659,7 @@ static inline void stm32_ethgpioconfig(FAR struct stm32_ethmac_s *priv)
/* Setup MCO pin for alternative usage */
#if defined(CONFIG_STM32_RMII_MCO)
#if defined(CONFIG_STM32_MII_MCO)
stm32_configgpio(GPIO_MCO);
stm32_mcoconfig(BOARD_CFGR_MCO_SOURCE);
#endif

View File

@ -368,7 +368,7 @@ CONFIG_NET_MULTICAST=n
CONFIG_STM32_PHYADDR=1
CONFIG_STM32_MII=n
CONFIG_STM32_RMII=y
CONFIG_STM32_RMII_MCO=y
CONFIG_STM32_MII_MCO=y
CONFIG_STM32_AUTONEG=y
#CONFIG_STM32_ETHFD
#CONFIG_STM32_ETH100MB

View File

@ -40,30 +40,36 @@ Contents
STM32F107VCT Pin Usage
======================
-- ---- -------------- -------------------------------------------------------------------
PN NAME SIGNAL NOTES
-- ---- -------------- -------------------------------------------------------------------
23 PA0 WAKEUP Connected to KEY4. Active low: Closing KEY4 pulls WAKEUP to ground.
24 PA1 MII_RX_CLK
RMII_REF_CLK
25 PA2 MII_MDIO
26 PA3 315M_VT
29 PA4 DAC_OUT1
30 PA5 DAC_OUT2 JP10
SPI1_SCK
31 PA6 SPI1_MISO
32 PA7 SPI1_MOSI
67 PA8 MCO
68 PA9 USB_VBUS JP3
USART1_TX
69 PA10 USB_ID JP5
USART1TX
70 PA11 USB_DM
71 PA12 USB_DP
29 PA4 DAC_OUT1 To CON5(CN14)
30 PA5 DAC_OUT2 To CON5(CN14). JP10
SPI1_SCK To the SD card, SPI FLASH
31 PA6 SPI1_MISO To the SD card, SPI FLASH
32 PA7 SPI1_MOSI To the SD card, SPI FLASH
67 PA8 MCO To DM9161AEP PHY
68 PA9 USB_VBUS MINI-USB-AB. JP3
USART1_TX MAX3232 to CN5
69 PA10 USB_ID MINI-USB-AB. JP5
USART1_RX MAX3232 to CN5
70 PA11 USB_DM MINI-USB-AB
71 PA12 USB_DP MINI-USB-AB
72 PA13 TMS/SWDIO
76 PA14 TCK/SWCLK
77 PA15 TDI
35 PB0 ADC_IN1
36 PB1 ADC_IN2
37 PB2 DATA_LE
-- ---- -------------- -------------------------------------------------------------------
PN NAME SIGNAL NOTES
-- ---- -------------- -------------------------------------------------------------------
35 PB0 ADC_IN1 To CON5(CN14)
36 PB1 ADC_IN2 To CON5(CN14)
37 PB2 DATA_LE To TFT LCD (CN13)
BOOT1 JP13
89 PB3 TDO/SWO
90 PB4 TRST
@ -71,73 +77,85 @@ STM32F107VCT Pin Usage
92 PB6 CAN2_TX JP11
I2C1_SCL
93 PB7 I2C1_SDA
95 PB8 USB_PWR
96 PB9 F_CS
47 PB10 USERKEY
48 PB11 MII_TX_EN
51 PB12 I2S_WS
MII_TXD0
52 PB13 I2S_CK
MII_TXD1
95 PB8 USB_PWR Drives USB VBUS
96 PB9 F_CS To both the TFT LCD (CN13) and to the W25X16 SPI FLASH
47 PB10 USERKEY Connected to KEY2
48 PB11 MII_TX_EN Ethernet PHY
51 PB12 I2S_WS Audio DAC
MII_TXD0 Ethernet PHY
52 PB13 I2S_CK Audio DAC
MII_TXD1 Ethernet PHY
53 PB14 SD_CD
54 PB15 I2S_DIN
54 PB15 I2S_DIN Audio DAC
-- ---- -------------- -------------------------------------------------------------------
PN NAME SIGNAL NOTES
-- ---- -------------- -------------------------------------------------------------------
15 PC0 POTENTIO_METER
16 PC1 MII_MDC
16 PC1 MII_MDC Ethernet PHY
17 PC2 WIRELESS_INT
18 PC3 WIRELESS_CE
33 PC4 USERKEY2
34 PC5 TP_INT JP6
MII_INT
63 PC6 I2S_MCK Pulled high
64 PC7 LCD_CS Pulled high
65 PC8 LCD_CS Pulled high
66 PC9 TP_CS Pulled hight
78 PC10 SPI3_SCK
79 PC11 SPI3_MISO
80 PC12 SPI3_MOSI
7 PC13 TAMPER
18 PC3 WIRELESS_CE To the NRF24L01 2.4G wireless module
33 PC4 USERKEY2 Connected to KEY1
34 PC5 TP_INT JP6. To TFT LCD (CN13) module
MII_INT Ethernet PHY
63 PC6 I2S_MCK Audio DAC. Active low: Pulled high
64 PC7 PCM1770_CS Audio DAC. Active low: Pulled high
65 PC8 LCD_CS TFT LCD (CN13). Active low: Pulled high
66 PC9 TP_CS TFT LCD (CN13). Active low: Pulled high
78 PC10 SPI3_SCK To TFT LCD (CN13), the NRF24L01 2.4G wireless module
79 PC11 SPI3_MISO To TFT LCD (CN13), the NRF24L01 2.4G wireless module
80 PC12 SPI3_MOSI To TFT LCD (CN13), the NRF24L01 2.4G wireless module
7 PC13 TAMPER Connected to KEY3
8 PC14 OSC32_IN Y1 32.768Khz XTAL
9 PC15 OSC32_OUT Y1 32.768Khz XTAL
-- ---- -------------- -------------------------------------------------------------------
PN NAME SIGNAL NOTES
-- ---- -------------- -------------------------------------------------------------------
81 PD0 CAN1_RX
82 PD1 CAN1_TX
83 PD2 LED1
84 PD3 LED2
85 PD4 LED3
86 PD5 485_TX
USART2_TX
87 PD6 485_RX JP4
USART2_RX
88 PD7 LED4
485_DIR
55 PD8 MII_RX_DV
RMII_CRSDV
56 PD9 MII_RXD0
57 PD10 MII_RXD1
58 PD11 SD_CS
59 PD12 WIRELESS_CS
60 PD13 LCD_RS
61 PD14 LCD_WR
62 PD15 LCD_RD
83 PD2 LED1 Active low: Pulled high
84 PD3 LED2 Active low: Pulled high
85 PD4 LED3 Active low: Pulled high
86 PD5 485_TX Same as USART2_TX but goes to SP3485
USART2_TX MAX3232 to CN6
87 PD6 485_RX Save as USART2_RX but goes to SP3485 (see JP4)
USART2_RX MAX3232 to CN6
88 PD7 LED4 Active low: Pulled high
485_DIR SP3485 read enable (not)
55 PD8 MII_RX_DV Ethernet PHY
RMII_CRSDV Ethernet PHY
56 PD9 MII_RXD0 Ethernet PHY
57 PD10 MII_RXD1 Ethernet PHY
58 PD11 SD_CS Active low: Pulled high
59 PD12 WIRELESS_CS To the NRF24L01 2.4G wireless module
60 PD13 LCD_RS To TFT LCD (CN13)
61 PD14 LCD_WR To TFT LCD (CN13)
62 PD15 LCD_RD To TFT LCD (CN13)
97 PE0 DB00
98 PE1 DB01
1 PE2 DB02
2 PE3 DB03
3 PE4 DB04
4 PE5 DB05
5 PE6 DB06
38 PE7 DB07
39 PE8 DB08
40 PE9 DB09
41 PE10 DB10
42 PE11 DB11
43 PE12 DB12
44 PE13 DB13
45 PE14 DB14
46 PE15 DB15
-- ---- -------------- -------------------------------------------------------------------
PN NAME SIGNAL NOTES
-- ---- -------------- -------------------------------------------------------------------
97 PE0 DB00 To TFT LCD (CN13)
98 PE1 DB01 To TFT LCD (CN13)
1 PE2 DB02 To TFT LCD (CN13)
2 PE3 DB03 To TFT LCD (CN13)
3 PE4 DB04 To TFT LCD (CN13)
4 PE5 DB05 To TFT LCD (CN13)
5 PE6 DB06 To TFT LCD (CN13)
38 PE7 DB07 To TFT LCD (CN13)
39 PE8 DB08 To TFT LCD (CN13)
40 PE9 DB09 To TFT LCD (CN13)
41 PE10 DB10 To TFT LCD (CN13)
42 PE11 DB11 To TFT LCD (CN13)
43 PE12 DB12 To TFT LCD (CN13)
44 PE13 DB13 To TFT LCD (CN13)
45 PE14 DB14 To TFT LCD (CN13)
46 PE15 DB15 To TFT LCD (CN13)
-- ---- -------------- -------------------------------------------------------------------
PN NAME SIGNAL NOTES
-- ---- -------------- -------------------------------------------------------------------
73 N/C
12 OSC_IN Y2 25Mhz XTAL
@ -155,7 +173,6 @@ STM32F107VCT Pin Usage
19 VSSA VSSA
20 VREF- VREF-
Development Environment
=======================

View File

@ -0,0 +1,354 @@
/************************************************************************************
* configs/shenzhou/include/board.h
*
* Copyright (C) 2012 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name NuttX nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
************************************************************************************/
/************************************************************************************
* Included Files
************************************************************************************/
#include <nuttx/config.h>
#ifndef __ASSEMBLY__
# include <stdint.h>
#endif
#include "stm32_rcc.h"
#include "stm32_sdio.h"
#include "stm32_internal.h"
/************************************************************************************
* Pre-processor Definitions
************************************************************************************/
#define BOARD_CFGR_MCO_SOURCE RCC_CFGR_PLL3CLK
/* Clocking *************************************************************************/
/* On-board crystal frequency is 25MHz (HSE) */
#define STM32_BOARD_XTAL 25000000ul
#define STM32_PLL_FREQUENCY (72000000)
#define STM32_SYSCLK_FREQUENCY STM32_PLL_FREQUENCY
#define STM32_HCLK_FREQUENCY STM32_PLL_FREQUENCY
#define STM32_BOARD_HCLK STM32_HCLK_FREQUENCY /* same as above, to satisfy compiler */
/* APB2 clock (PCLK2) is HCLK (72MHz) */
#define STM32_RCC_CFGR_PPRE2 RCC_CFGR_PPRE2_HCLK
#define STM32_PCLK2_FREQUENCY STM32_HCLK_FREQUENCY
#define STM32_APB2_CLKIN (STM32_PCLK2_FREQUENCY) /* Timers 2-7, 12-14 */
/* APB2 timers 1 and 8 will receive PCLK2. */
#define STM32_APB2_TIM1_CLKIN (STM32_PCLK2_FREQUENCY)
#define STM32_APB2_TIM8_CLKIN (STM32_PCLK2_FREQUENCY)
/* APB1 clock (PCLK1) is HCLK/2 (36MHz) */
#define STM32_RCC_CFGR_PPRE1 RCC_CFGR_PPRE1_HCLKd2
#define STM32_PCLK1_FREQUENCY (STM32_HCLK_FREQUENCY/2)
/* APB1 timers 2-4 will be twice PCLK1 (I presume the remaining will receive PCLK1) */
#define STM32_APB1_TIM2_CLKIN (2*STM32_PCLK1_FREQUENCY)
#define STM32_APB1_TIM3_CLKIN (2*STM32_PCLK1_FREQUENCY)
#define STM32_APB1_TIM4_CLKIN (2*STM32_PCLK1_FREQUENCY)
#define STM32_APB1_TIM5_CLKIN (STM32_PCLK1_FREQUENCY)
#define STM32_APB1_TIM6_CLKIN (STM32_PCLK1_FREQUENCY)
#define STM32_APB1_TIM7_CLKIN (STM32_PCLK1_FREQUENCY)
/* LED definitions ******************************************************************/
/* If CONFIG_ARCH_LEDS is not defined, then the user can control the LEDs in any
* way. The following definitions are used to access individual LEDs.
*/
/* LED index values for use with stm32_setled() */
#define BOARD_LED1 0
#define BOARD_LED2 1
#define BOARD_LED3 2
#define BOARD_LED4 3
#define BOARD_NLEDS 4
/* LED bits for use with stm32_setleds() */
#define BOARD_LED1_BIT (1 << BOARD_LED1)
#define BOARD_LED2_BIT (1 << BOARD_LED2)
#define BOARD_LED3_BIT (1 << BOARD_LED3)
#define BOARD_LED4_BIT (1 << BOARD_LED4)
/* If CONFIG_ARCH_LEDs is defined, then NuttX will control the 4 LEDs on board the
* STM3240G-EVAL. The following definitions describe how NuttX controls the LEDs:
*/
#define LED_STARTED 0 /* LED1 */
#define LED_HEAPALLOCATE 1 /* LED2 */
#define LED_IRQSENABLED 2 /* LED1 + LED2 */
#define LED_STACKCREATED 3 /* LED3 */
#define LED_INIRQ 4 /* LED1 + LED3 */
#define LED_SIGNAL 5 /* LED2 + LED3 */
#define LED_ASSERTION 6 /* LED1 + LED2 + LED3 */
#define LED_PANIC 7 /* N/C + N/C + N/C + LED4 */
/* Button definitions ***************************************************************/
/* The STM3240G-EVAL supports three buttons: */
#define BUTTON_KEY1 0 /* Name printed on board */
#define BUTTON_KEY2 1
#define BUTTON_KEY3 2
#define BUTTON_KEY4 3
#define NUM_BUTTONS 4
#define BUTTON_USERKEY2 BUTTON_KEY1 /* Names in schematic */
#define BUTTON_USERKEY BUTTON_KEY2
#define BUTTON_TAMPER BUTTON_KEY3
#define BUTTON_WAKEUP BUTTON_KEY4
#define BUTTON_KEY1_BIT (1 << BUTTON_KEY1)
#define BUTTON_KEY2_BIT (1 << BUTTON_KEY2)
#define BUTTON_KEY3_BIT (1 << BUTTON_KEY3)
#define BUTTON_KEY4_BIT (1 << BUTTON_KEY4)
#define BUTTON_USERKEY2_BIT BUTTON_KEY1_BIT
#define BUTTON_USERKEY_BIT BUTTON_KEY2_BIT
#define BUTTON_TAMPER_BIT BUTTON_KEY3_BIT
#define BUTTON_WAKEUP_BIT BUTTON_KEY4_BIT
/* Pin selections ******************************************************************/
/* Ethernet
*
* -- ---- -------------- ----------------------------------------------------------
* PN NAME SIGNAL NOTES
* -- ---- -------------- ----------------------------------------------------------
* 24 PA1 MII_RX_CLK Ethernet PHY
* RMII_REF_CLK Ethernet PHY
* 25 PA2 MII_MDIO Ethernet PHY
* 48 PB11 MII_TX_EN Ethernet PHY
* 51 PB12 MII_TXD0 Ethernet PHY
* 52 PB13 MII_TXD1 Ethernet PHY
* 16 PC1 MII_MDC Ethernet PHY
* 34 PC5 MII_INT Ethernet PHY
* 55 PD8 MII_RX_DV Ethernet PHY. Requires CONFIG_STM32_ETH_REMAP
* 55 PD8 RMII_CRSDV Ethernet PHY. Requires CONFIG_STM32_ETH_REMAP
* 56 PD9 MII_RXD0 Ethernet PHY. Requires CONFIG_STM32_ETH_REMAP
* 57 PD10 MII_RXD1 Ethernet PHY. Requires CONFIG_STM32_ETH_REMAP
*
* 67 PA8 MCO DM9161AEP
*/
#ifdef CONFIG_STM32_ETHMAC
# ifndef CONFIG_STM32_ETH_REMAP
# error "STM32 Ethernet requires CONFIG_STM32_ETH_REMAP"
# endif
# ifndef CONFIG_STM32_MII
# error "STM32 Ethernet requires CONFIG_STM32_MII"
# endif
# ifndef CONFIG_STM32_MII_MCO
# error "STM32 Ethernet requires CONFIG_STM32_MII_MCO"
# endif
#endif
/* USB
*
* -- ---- -------------- ----------------------------------------------------------
* PN NAME SIGNAL NOTES
* -- ---- -------------- ----------------------------------------------------------
* 68 PA9 USB_VBUS MINI-USB-AB. JP3
* 69 PA10 USB_ID MINI-USB-AB. JP5
* 70 PA11 USB_DM MINI-USB-AB
* 71 PA12 USB_DP MINI-USB-AB
* 95 PB8 USB_PWR Drives USB VBUS
*/
/* UARTS/USARTS
*
* -- ---- -------------- ----------------------------------------------------------
* PN NAME SIGNAL NOTES
* -- ---- -------------- ----------------------------------------------------------
* 68 PA9 USART1_TX MAX3232 to CN5. Requires CONFIG_STM32_USART1_REMAP
* 69 PA10 USART1_RX MAX3232 to CN5. Requires CONFIG_STM32_USART1_REMAP
* 86 PD5 USART2_TX MAX3232 to CN6. Requires CONFIG_STM32_USART2_REMAP
* 87 PD6 USART2_RX MAX3232 to CN6. Requires CONFIG_STM32_USART2_REMAP
* 86 PD5 485_TX Same as USART2_TX but goes to SP3485
* 87 PD6 485_RX Save as USART2_RX but goes to SP3485 (see JP4)
*/
#if defined(CONFIG_STM32_USART1) && !defined(CONFIG_STM32_USART1_REMAP)
# error "CONFIG_STM32_USART1 requires CONFIG_STM32_USART1_REMAP"
#endif
#if defined(CONFIG_STM32_USART2) && !defined(CONFIG_STM32_USART2_REMAP)
# error "CONFIG_STM32_USART2 requires CONFIG_STM32_USART2_REMAP"
#endif
/* SPI
*
* -- ---- -------------- ----------------------------------------------------------
* PN NAME SIGNAL NOTES
* -- ---- -------------- ----------------------------------------------------------
* 30 PA5 SPI1_SCK To the SD card, SPI FLASH.
* Requires !CONFIG_STM32_SPI1_REMAP
* 31 PA6 SPI1_MISO To the SD card, SPI FLASH.
* Requires !CONFIG_STM32_SPI1_REMAP
* 32 PA7 SPI1_MOSI To the SD card, SPI FLASH.
* Requires !CONFIG_STM32_SPI1_REMAP
* 78 PC10 SPI3_SCK To TFT LCD (CN13), the NRF24L01 2.4G wireless module.
* Requires CONFIG_STM32_SPI3_REMAP.
* 79 PC11 SPI3_MISO To TFT LCD (CN13), the NRF24L01 2.4G wireless module.
* Requires CONFIG_STM32_SPI3_REMAP.
* 80 PC12 SPI3_MOSI To TFT LCD (CN13), the NRF24L01 2.4G wireless module.
* Requires CONFIG_STM32_SPI3_REMAP.
*/
#if defined(CONFIG_STM32_SPI1) && defined(CONFIG_STM32_SPI1_REMAP)
# error "CONFIG_STM32_SPI1 must not have CONFIG_STM32_SPI1_REMAP"
#endif
#if defined(CONFIG_STM32_SPI3) && !defined(CONFIG_STM32_SPI3_REMAP)
# error "CONFIG_STM32_SPI3 requires CONFIG_STM32_SPI3_REMAP"
#endif
/* DAC
*
* -- ---- -------------- ----------------------------------------------------------
* PN NAME SIGNAL NOTES
* -- ---- -------------- ----------------------------------------------------------
* 29 PA4 DAC_OUT1 To CON5(CN14)
* 30 PA5 DAC_OUT2 To CON5(CN14). JP10
*/
/* ADC
*
* -- ---- -------------- ----------------------------------------------------------
* PN NAME SIGNAL NOTES
* -- ---- -------------- ----------------------------------------------------------
* 35 PB0 ADC_IN1 GPIO_ADC12_IN8. To CON5(CN14)
* 36 PB1 ADC_IN2 GPIO_ADC12_IN9. To CON5(CN14)
* 15 PC0 POTENTIO_METER GPIO_ADC12_IN10
*/
/* CAN
*
* -- ---- -------------- ----------------------------------------------------------
* PN NAME SIGNAL NOTES
* -- ---- -------------- ----------------------------------------------------------
* 91 PB5 CAN2_RX Requires CONFIG_STM32_CAN2_REMAP.
* 92 PB6 CAN2_TX Requires CONFIG_STM32_CAN2_REMAP. See also JP11
* 81 PD0 CAN1_RX Requires CONFIG_STM32_CAN1_REMAP2.
* 82 PD1 CAN1_TX Requires CONFIG_STM32_CAN1_REMAP2.
*/
#if defined(CONFIG_STM32_CAN1) && !defined(CONFIG_STM32_CAN1_REMAP2)
# error "CONFIG_STM32_CAN1 requires CONFIG_STM32_CAN1_REMAP2"
#endif
#if defined(CONFIG_STM32_CAN2) && !defined(CONFIG_STM32_CAN2_REMAP)
# error "CONFIG_STM32_CAN2 requires CONFIG_STM32_CAN2_REMAP"
#endif
/* I2C
*
* -- ---- -------------- ----------------------------------------------------------
* PN NAME SIGNAL NOTES
* -- ---- -------------- ----------------------------------------------------------
* 92 PB6 I2C1_SCL Requires !CONFIG_STM32_I2C1_REMAP
* 93 PB7 I2C1_SDA
*/
#if defined(CONFIG_STM32_I2C1) && defined(CONFIG_STM32_I2C1_REMAP)
# error "CONFIG_STM32_I2C1 must not have CONFIG_STM32_I2C1_REMAP"
#endif
/* I2S
*
* -- ---- -------------- ----------------------------------------------------------
* PN NAME SIGNAL NOTES
* -- ---- -------------- ----------------------------------------------------------
* 51 PB12 I2S_WS GPIO_I2S2_WS. Audio DAC
* 52 PB13 I2S_CK GPIO_I2S2_CK. Audio DAC
* 54 PB15 I2S_DIN ??? Audio DAC data in.
* 63 PC6 I2S_MCK GPIO_I2S2_MCK. Audio DAC. Active low: Pulled high
*/
/************************************************************************************
* Public Function Prototypes
************************************************************************************/
/************************************************************************************
* Name: stm32_boardinitialize
*
* Description:
* All STM32 architectures must provide the following entry point. This entry point
* is called early in the intitialization -- after all memory has been configured
* and mapped but before any devices have been initialized.
*
************************************************************************************/
void stm32_boardinitialize(void);
/************************************************************************************
* Name: stm32_board_clockconfig
*
* Description:
* Any STM32 board may replace the "standard" board clock configuration logic with
* its own, custom clock cofiguration logic.
*
************************************************************************************/
#ifdef CONFIG_ARCH_BOARD_STM32_CUSTOM_CLOCKCONFIG
void stm32_board_clockconfig(void);
#endif
/************************************************************************************
* Name: stm32_selectrmii
*
* Description:
* Selects the RMII inteface.
*
* Input Parameters:
* None
*
* Returned Value:
* None
*
************************************************************************************/
static inline void stm32_selectrmii(void)
{
uint32_t regval;
regval = getreg32(STM32_AFIO_MAPR);
regval |= AFIO_MAPR_MII_RMII_SEL;
putreg32(regval, STM32_AFIO_MAPR);
}

View File

@ -0,0 +1,260 @@
/****************************************************************************************************
* configs/shenzhou/src/shenzhou-internal.h
* arch/arm/src/board/shenzhou-internal.n
*
* Copyright (C) 2012 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name NuttX nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************************************/
#ifndef __CONFIGS_SHENZHOUL_SRC_SHENZHOU_INTERNAL_H
#define __CONFIGS_SHENZHOUL_SRC_SHENZHOU_INTERNAL_H
/****************************************************************************************************
* Included Files
****************************************************************************************************/
#include <nuttx/config.h>
#include <nuttx/compiler.h>
#include <stdint.h>
/****************************************************************************************************
* Definitions
****************************************************************************************************/
/* Configuration ************************************************************************************/
/* How many SPI modules does this chip support? */
#if STM32_NSPI < 1
# undef CONFIG_STM32_SPI1
# undef CONFIG_STM32_SPI2
# undef CONFIG_STM32_SPI3
#elif STM32_NSPI < 2
# undef CONFIG_STM32_SPI2
# undef CONFIG_STM32_SPI3
#elif STM32_NSPI < 3
# undef CONFIG_STM32_SPI3
#endif
/* Shenzhou GPIO Configuration **********************************************************************/
/* STM3240G-EVAL GPIOs ******************************************************************************/
/* Wireless
*
* -- ---- -------------- -------------------------------------------------------------------
* PN NAME SIGNAL NOTES
* -- ---- -------------- -------------------------------------------------------------------
* 26 PA3 315M_VT
* 17 PC2 WIRELESS_INT
* 18 PC3 WIRELESS_CE To the NRF24L01 2.4G wireless module
* 59 PD12 WIRELESS_CS To the NRF24L01 2.4G wireless module
*/
/* To be provided */
/* Buttons
*
* -- ---- -------------- -------------------------------------------------------------------
* PN NAME SIGNAL NOTES
* -- ---- -------------- -------------------------------------------------------------------
* 23 PA0 WAKEUP Connected to KEY4. Active low: Closing KEY4 pulls WAKEUP to ground.
* 47 PB10 USERKEY Connected to KEY2
* 33 PC4 USERKEY2 Connected to KEY1
* 7 PC13 TAMPER Connected to KEY3
*/
/* BUTTONS -- NOTE that all have EXTI interrupts configured */
#define MIN_IRQBUTTON BUTTON_KEY1
#define MAX_IRQBUTTON BUTTON_KEY4
#define NUM_IRQBUTTONS (BUTTON_KEY4 - BUTTON_KEY1 + 1)
#define GPIO_BTN_WAKEUP (GPIO_INPUT|GPIO_FLOAT|GPIO_EXTI|GPIO_PORTA|GPIO_PIN0)
#define GPIO_BTN_USERKEY (GPIO_INPUT|GPIO_FLOAT|GPIO_EXTI|GPIO_PORTB|GPIO_PIN10)
#define GPIO_BTN_USERKEY2 (GPIO_INPUT|GPIO_FLOAT|GPIO_EXTI|GPIO_PORTC|GPIO_PIN4)
#define GPIO_BTN_TAMPER (GPIO_INPUT|GPIO_FLOAT|GPIO_EXTI|GPIO_PORTC|GPIO_PIN13)
/* LEDs
*
* -- ---- -------------- -------------------------------------------------------------------
* PN NAME SIGNAL NOTES
* -- ---- -------------- -------------------------------------------------------------------
* 83 PD2 LED1 Active low: Pulled high
* 84 PD3 LED2 Active low: Pulled high
* 85 PD4 LED3 Active low: Pulled high
* 88 PD7 LED4 Active low: Pulled high
*/
#define GPIO_LED1 (GPIO_OUTPUT|GPIO_CNF_OUTPP|GPIO_MODE_50MHz|\
GPIO_OUTPUT_CLEAR|GPIO_PORTD|GPIO_PIN2)
#define GPIO_LED2 (GPIO_OUTPUT|GPIO_CNF_OUTPP|GPIO_MODE_50MHz|\
GPIO_OUTPUT_CLEAR|GPIO_PORTD|GPIO_PIN3)
#define GPIO_LED3 (GPIO_OUTPUT|GPIO_CNF_OUTPP|GPIO_MODE_50MHz|\
GPIO_OUTPUT_CLEAR|GPIO_PORTD|GPIO_PIN4)
#define GPIO_LED4 (GPIO_OUTPUT|GPIO_CNF_OUTPP|GPIO_MODE_50MHz|\
GPIO_OUTPUT_CLEAR|GPIO_PORTD|GPIO_PIN5)
/* TFT LCD
*
* -- ---- -------------- -------------------------------------------------------------------
* PN NAME SIGNAL NOTES
* -- ---- -------------- -------------------------------------------------------------------
* 37 PB2 DATA_LE To TFT LCD (CN13)
* 96 PB9 F_CS To both the TFT LCD (CN13) and to the W25X16 SPI FLASH
* 34 PC5 TP_INT JP6. To TFT LCD (CN13) module
* 65 PC8 LCD_CS Active low: Pulled high
* 66 PC9 TP_CS Active low: Pulled high
* 60 PD13 LCD_RS To TFT LCD (CN13)
* 61 PD14 LCD_WR To TFT LCD (CN13)
* 62 PD15 LCD_RD To TFT LCD (CN13)
* 97 PE0 DB00 To TFT LCD (CN13)
* 98 PE1 DB01 To TFT LCD (CN13)
* 1 PE2 DB02 To TFT LCD (CN13)
* 2 PE3 DB03 To TFT LCD (CN13)
* 3 PE4 DB04 To TFT LCD (CN13)
* 4 PE5 DB05 To TFT LCD (CN13)
* 5 PE6 DB06 To TFT LCD (CN13)
* 38 PE7 DB07 To TFT LCD (CN13)
* 39 PE8 DB08 To TFT LCD (CN13)
* 40 PE9 DB09 To TFT LCD (CN13)
* 41 PE10 DB10 To TFT LCD (CN13)
* 42 PE11 DB11 To TFT LCD (CN13)
* 43 PE12 DB12 To TFT LCD (CN13)
* 44 PE13 DB13 To TFT LCD (CN13)
* 45 PE14 DB14 To TFT LCD (CN13)
* 46 PE15 DB15 To TFT LCD (CN13)
*/
/* To be provided */
/* RS-485
*
* -- ---- -------------- -------------------------------------------------------------------
* PN NAME SIGNAL NOTES
* -- ---- -------------- -------------------------------------------------------------------
* 88 PD7 485_DIR SP3485 read enable (not)
*/
/* To be provided */
/* USB
*
* -- ---- -------------- -------------------------------------------------------------------
* PN NAME SIGNAL NOTES
* -- ---- -------------- -------------------------------------------------------------------
* 95 PB8 USB_PWR Drives USB VBUS
*/
#define GPIO_USB_PWR (GPIO_OUTPUT|GPIO_FLOAT|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTB|GPIO_PIN8)
/* Audio DAC
*
* -- ---- -------------- -------------------------------------------------------------------
* PN NAME SIGNAL NOTES
* -- ---- -------------- -------------------------------------------------------------------
*/
/* To be provided */
/* SPI FLASH
*
* -- ---- -------------- -------------------------------------------------------------------
* PN NAME SIGNAL NOTES
* -- ---- -------------- -------------------------------------------------------------------
* 96 PB9 F_CS To both the TFT LCD (CN13) and to the W25X16 SPI FLASH
*/
#define GPIO_FLASH_CS (GPIO_OUTPUT|GPIO_CNF_OUTPP|GPIO_MODE_50MHz|\
GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN9)
/* SD Card
*
* -- ---- -------------- -------------------------------------------------------------------
* PN NAME SIGNAL NOTES
* -- ---- -------------- -------------------------------------------------------------------
* 53 PB14 SD_CD Active low: Pulled high
* 58 PD11 SD_CS
*/
#define GPIO_SD_CD (GPIO_INPUT|GPIO_FLOAT|GPIO_EXTI|GPIO_PORTB|GPIO_PIN14)
#define GPIO_SD_CS (GPIO_OUTPUT|GPIO_CNF_OUTPP|GPIO_MODE_50MHz|\
GPIO_OUTPUT_SET|GPIO_PORTD|GPIO_PIN11)
/****************************************************************************************************
* Public Types
****************************************************************************************************/
/****************************************************************************************************
* Public data
****************************************************************************************************/
#ifndef __ASSEMBLY__
/****************************************************************************************************
* Public Functions
****************************************************************************************************/
/****************************************************************************************************
* Name: stm32_spiinitialize
*
* Description:
* Called to configure SPI chip select GPIO pins for the STM3240G-EVAL board.
*
****************************************************************************************************/
void weak_function stm32_spiinitialize(void);
/****************************************************************************************************
* Name: stm32_usbinitialize
*
* Description:
* Called from stm32_usbinitialize very early in inialization to setup USB-related GPIO pins for
* the STM3240G-EVAL board.
*
****************************************************************************************************/
#ifdef CONFIG_STM32_OTGFS
void weak_function stm32_usbinitialize(void);
#endif
/****************************************************************************************************
* Name: stm32_usbhost_initialize
*
* Description:
* Called at application startup time to initialize the USB host functionality. This function will
* start a thread that will monitor for device connection/disconnection events.
*
****************************************************************************************************/
#if defined(CONFIG_STM32_OTGFS) && defined(CONFIG_USBHOST)
int stm32_usbhost_initialize(void);
#endif
#endif /* __ASSEMBLY__ */
#endif /* __CONFIGS_SHENZHOUL_SRC_SHENZHOU_INTERNAL_H */