Some repartitioning of STM32 functionality to better support a USB host driver

git-svn-id: https://nuttx.svn.sourceforge.net/svnroot/nuttx/trunk@5028 7fd9a85b-ad96-42d3-883c-3090e2eb8679
This commit is contained in:
patacongo 2012-08-15 17:58:54 +00:00
parent 3cc812dbad
commit dd681d7fff
12 changed files with 195 additions and 38 deletions

View File

@ -76,6 +76,12 @@ CMN_CSRCS += stm32_otgfsdev.c
endif endif
endif endif
ifeq ($(CONFIG_USBHOST),y)
ifeq ($(CONFIG_STM32_OTGFS),y)
CMN_CSRCS += stm32_otgfshost.c
endif
endif
ifeq ($(CONFIG_ARMV7M_CMNVECTOR),y) ifeq ($(CONFIG_ARMV7M_CMNVECTOR),y)
CHIP_ASRCS += stm32_vectors.S CHIP_ASRCS += stm32_vectors.S
endif endif

View File

@ -1,5 +1,5 @@
/******************************************************************************* /*******************************************************************************
* arch/arm/src/stm32/stm32_usbhost.c * arch/arm/src/stm32/stm32_otgfshost.c
* *
* Copyright (C) 2012 Gregory Nutt. All rights reserved. * Copyright (C) 2012 Gregory Nutt. All rights reserved.
* Authors: Gregory Nutt <gnutt@nuttx.org> * Authors: Gregory Nutt <gnutt@nuttx.org>

View File

@ -47,6 +47,8 @@
#include "chip.h" #include "chip.h"
#include "chip/stm32_otgfs.h" #include "chip/stm32_otgfs.h"
#if defined(CONFIG_STM32_OTGFS) && defined(CONFIG_USBHOST)
/************************************************************************************ /************************************************************************************
* Public Functions * Public Functions
************************************************************************************/ ************************************************************************************/
@ -61,11 +63,40 @@ extern "C" {
#define EXTERN extern #define EXTERN extern
#endif #endif
/***********************************************************************************
* Name: stm32_usbhost_vbusdrive
*
* Description:
* Enable/disable driving of VBUS 5V output. This function must be provided be
* each platform that implements the STM32 OTG FS host interface
*
* "On-chip 5 V VBUS generation is not supported. For this reason, a charge pump
* or, if 5 V are available on the application board, a basic power switch, must
* be added externally to drive the 5 V VBUS line. The external charge pump can
* be driven by any GPIO output. When the application decides to power on VBUS
* using the chosen GPIO, it must also set the port power bit in the host port
* control and status register (PPWR bit in OTG_FS_HPRT).
*
* "The application uses this field to control power to this port, and the core
* clears this bit on an overcurrent condition."
*
* Input Parameters:
* iface - For future growth to handle multiple USB host interface. Should be zero.
* enable - true: enable VBUS power; false: disable VBUS power
*
* Returned Value:
* None
*
***********************************************************************************/
EXTERN void stm32_usbhost_vbusdrive(int iface, bool enable);
#undef EXTERN #undef EXTERN
#if defined(__cplusplus) #if defined(__cplusplus)
} }
#endif #endif
#endif /* __ASSEMBLY__ */ #endif /* __ASSEMBLY__ */
#endif /* CONFIG_STM32_OTGFS && CONFIG_USBHOST */
#endif /* __ARCH_ARM_SRC_STM32_STM32_USBHOST_H */ #endif /* __ARCH_ARM_SRC_STM32_STM32_USBHOST_H */

View File

@ -616,7 +616,7 @@ static void stm32_stdclockconfig(void)
/* Set the PLL dividers and multiplers to configure the main PLL */ /* Set the PLL dividers and multiplers to configure the main PLL */
regval = (STM32_PLLCFG_PLLM | STM32_PLLCFG_PLLN |STM32_PLLCFG_PLLP | regval = (STM32_PLLCFG_PLLM | STM32_PLLCFG_PLLN |STM32_PLLCFG_PLLP |
RCC_PLLCFG_PLLSRC_HSE | STM32_PLLCFG_PPQ); RCC_PLLCFG_PLLSRC_HSE | STM32_PLLCFG_PLLQ);
putreg32(regval, STM32_RCC_PLLCFG); putreg32(regval, STM32_RCC_PLLCFG);
/* Enable the main PLL */ /* Enable the main PLL */

View File

@ -618,7 +618,7 @@ static void stm32_stdclockconfig(void)
/* Set the PLL dividers and multiplers to configure the main PLL */ /* Set the PLL dividers and multiplers to configure the main PLL */
regval = (STM32_PLLCFG_PLLM | STM32_PLLCFG_PLLN |STM32_PLLCFG_PLLP | regval = (STM32_PLLCFG_PLLM | STM32_PLLCFG_PLLN |STM32_PLLCFG_PLLP |
RCC_PLLCFG_PLLSRC_HSE | STM32_PLLCFG_PPQ); RCC_PLLCFG_PLLSRC_HSE | STM32_PLLCFG_PLLQ);
putreg32(regval, STM32_RCC_PLLCFG); putreg32(regval, STM32_RCC_PLLCFG);
/* Enable the main PLL */ /* Enable the main PLL */

View File

@ -77,7 +77,7 @@
* PLLM : 25 (STM32_PLLCFG_PLLM) * PLLM : 25 (STM32_PLLCFG_PLLM)
* PLLN : 240 (STM32_PLLCFG_PLLN) * PLLN : 240 (STM32_PLLCFG_PLLN)
* PLLP : 2 (STM32_PLLCFG_PLLP) * PLLP : 2 (STM32_PLLCFG_PLLP)
* PLLQ : 5 (STM32_PLLCFG_PPQ) * PLLQ : 5 (STM32_PLLCFG_PLLQ)
* Main regulator output voltage : Scale1 mode Needed for high speed SYSCLK * Main regulator output voltage : Scale1 mode Needed for high speed SYSCLK
* Flash Latency(WS) : 5 * Flash Latency(WS) : 5
* Prefetch Buffer : OFF * Prefetch Buffer : OFF
@ -117,7 +117,7 @@
#define STM32_PLLCFG_PLLM RCC_PLLCFG_PLLM(25) #define STM32_PLLCFG_PLLM RCC_PLLCFG_PLLM(25)
#define STM32_PLLCFG_PLLN RCC_PLLCFG_PLLN(240) #define STM32_PLLCFG_PLLN RCC_PLLCFG_PLLN(240)
#define STM32_PLLCFG_PLLP RCC_PLLCFG_PLLP_2 #define STM32_PLLCFG_PLLP RCC_PLLCFG_PLLP_2
#define STM32_PLLCFG_PPQ RCC_PLLCFG_PLLQ(5) #define STM32_PLLCFG_PLLQ RCC_PLLCFG_PLLQ(5)
#define STM32_SYSCLK_FREQUENCY 120000000ul #define STM32_SYSCLK_FREQUENCY 120000000ul

View File

@ -56,8 +56,8 @@ ifeq ($(CONFIG_ARCH_BUTTONS),y)
CSRCS += up_buttons.c CSRCS += up_buttons.c
endif endif
ifeq ($(CONFIG_USBDEV),y) ifeq ($(CONFIG_STM32_OTGFS),y)
CSRCS += up_usbdev.c CSRCS += up_usb.c
endif endif
ifeq ($(CONFIG_STM32_FSMC),y) ifeq ($(CONFIG_STM32_FSMC),y)

View File

@ -134,9 +134,14 @@
* PF11 OTG_FS_Overcurrent * PF11 OTG_FS_Overcurrent
*/ */
#define GPIO_OTGFS_VBUS (GPIO_INPUT|GPIO_FLOAT|GPIO_SPEED_100MHz|GPIO_OPENDRAIN|GPIO_PORTA|GPIO_PIN9) #define GPIO_OTGFS_VBUS (GPIO_INPUT|GPIO_FLOAT|GPIO_SPEED_100MHz|GPIO_OPENDRAIN|GPIO_PORTA|GPIO_PIN9)
#define GPIO_OTGFS_PWRON (GPIO_OUTPUT|GPIO_FLOAT|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTH|GPIO_PIN5) #define GPIO_OTGFS_PWRON (GPIO_OUTPUT|GPIO_FLOAT|GPIO_OUTPUT_SET|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTH|GPIO_PIN5)
#define GPIO_OTGFS_OVER (GPIO_INPUT|GPIO_FLOAT|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTF|GPIO_PIN11)
#ifdef CONFIG_USBHOST
# define GPIO_OTGFS_OVER (GPIO_INPUT|GPIO_EXTI|GPIO_FLOAT|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTF|GPIO_PIN11)
#else
# define GPIO_OTGFS_OVER (GPIO_INPUT|GPIO_FLOAT|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTF|GPIO_PIN11)
#endif
/* The STM3220G-EVAL has two STMPE811QTR I/O expanders on board both connected /* The STM3220G-EVAL has two STMPE811QTR I/O expanders on board both connected
* to the STM32 via I2C1. They share a common interrupt line: PI2. * to the STM32 via I2C1. They share a common interrupt line: PI2.
@ -212,47 +217,63 @@
void weak_function stm32_spiinitialize(void); void weak_function stm32_spiinitialize(void);
/************************************************************************************ /****************************************************************************************************
* Name: stm32_usbinitialize * Name: stm32_usbinitialize
* *
* Description: * Description:
* Called to setup USB-related GPIO pins for the STM3210E-EVAL board. * Called from stm32_usbinitialize very early in inialization to setup USB-related GPIO pins for
* the STM3220G-EVAL board.
* *
************************************************************************************/ ****************************************************************************************************/
#ifdef CONFIG_STM32_OTGFS
void weak_function stm32_usbinitialize(void); 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)
void stm32_usbhost_initialize(void);
#endif
/****************************************************************************************************
* Name: stm32_extmemgpios * Name: stm32_extmemgpios
* *
* Description: * Description:
* Initialize GPIOs for external memory usage * Initialize GPIOs for external memory usage
* *
************************************************************************************/ ****************************************************************************************************/
#ifdef CONFIG_STM32_FSMC #ifdef CONFIG_STM32_FSMC
void stm32_extmemgpios(const uint32_t *gpios, int ngpios); void stm32_extmemgpios(const uint32_t *gpios, int ngpios);
#endif #endif
/************************************************************************************ /****************************************************************************************************
* Name: stm32_extmemaddr * Name: stm32_extmemaddr
* *
* Description: * Description:
* Initialize adress line GPIOs for external memory access * Initialize adress line GPIOs for external memory access
* *
************************************************************************************/ ****************************************************************************************************/
#ifdef CONFIG_STM32_FSMC #ifdef CONFIG_STM32_FSMC
void stm32_extmemaddr(int naddrs); void stm32_extmemaddr(int naddrs);
#endif #endif
/************************************************************************************ /****************************************************************************************************
* Name: stm32_extmemdata * Name: stm32_extmemdata
* *
* Description: * Description:
* Initialize data line GPIOs for external memory access * Initialize data line GPIOs for external memory access
* *
************************************************************************************/ ****************************************************************************************************/
#ifdef CONFIG_STM32_FSMC #ifdef CONFIG_STM32_FSMC
void stm32_extmemdata(int ndata); void stm32_extmemdata(int ndata);
@ -264,7 +285,7 @@ void stm32_extmemdata(int ndata);
* Description: * Description:
* enable clocking to the FSMC module * enable clocking to the FSMC module
* *
************************************************************************************/ ****************************************************************************************************/
#ifdef CONFIG_STM32_FSMC #ifdef CONFIG_STM32_FSMC
void stm32_enablefsmc(void); void stm32_enablefsmc(void);
@ -276,7 +297,7 @@ void stm32_enablefsmc(void);
* Description: * Description:
* enable clocking to the FSMC module * enable clocking to the FSMC module
* *
************************************************************************************/ ****************************************************************************************************/
#ifdef CONFIG_STM32_FSMC #ifdef CONFIG_STM32_FSMC
void stm32_disablefsmc(void); void stm32_disablefsmc(void);
@ -306,7 +327,7 @@ void stm32_disablefsmc(void);
* word and uses the needed byte only). The NBL[1:0] are always kept low * word and uses the needed byte only). The NBL[1:0] are always kept low
* during read transactions. * during read transactions.
* *
************************************************************************************/ ****************************************************************************************************/
#ifdef CONFIG_STM32_FSMC #ifdef CONFIG_STM32_FSMC
void stm32_selectsram(void); void stm32_selectsram(void);
@ -318,7 +339,7 @@ void stm32_selectsram(void);
* Description: * Description:
* Disable SRAM * Disable SRAM
* *
************************************************************************************/ ****************************************************************************************************/
#ifdef CONFIG_STM32_FSMC #ifdef CONFIG_STM32_FSMC
void stm32_deselectsram(void); void stm32_deselectsram(void);
@ -330,7 +351,7 @@ void stm32_deselectsram(void);
* Description: * Description:
* Initialize to the LCD * Initialize to the LCD
* *
************************************************************************************/ ****************************************************************************************************/
#ifdef CONFIG_STM32_FSMC #ifdef CONFIG_STM32_FSMC
void stm32_selectlcd(void); void stm32_selectlcd(void);
@ -342,7 +363,7 @@ void stm32_selectlcd(void);
* Description: * Description:
* Disable the LCD * Disable the LCD
* *
************************************************************************************/ ****************************************************************************************************/
#ifdef CONFIG_STM32_FSMC #ifdef CONFIG_STM32_FSMC
void stm32_deselectlcd(void); void stm32_deselectlcd(void);

View File

@ -88,12 +88,12 @@ void stm32_boardinitialize(void)
stm32_selectsram(); stm32_selectsram();
#endif #endif
/* Initialize USB is 1) USBDEV is selected, 2) the OTG FS controller is not /* Initialize USB if the 1) OTG FS controller is in the configuration and 2)
* disabled, and 3) the weak function stm32_usbinitialize() has been brought * the weak function stm32_usbinitialize() has been brought into the build.
* into the build. * Presumeably either CONFIG_USBDEV or CONFIG_USBHOST is also selected.
*/ */
#if defined(CONFIG_USBDEV) && defined(CONFIG_STM32_OTGFS) #ifdef CONFIG_STM32_OTGFS
if (stm32_usbinitialize) if (stm32_usbinitialize)
{ {
stm32_usbinitialize(); stm32_usbinitialize();

View File

@ -1,6 +1,6 @@
/************************************************************************************ /************************************************************************************
* configs/stm3220g-eval/src/up_usbdev.c * configs/stm3220g-eval/src/up_usb.c
* arch/arm/src/board/up_boot.c * arch/arm/src/board/up_usb.c
* *
* Copyright (C) 2012 Gregory Nutt. All rights reserved. * Copyright (C) 2012 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org> * Author: Gregory Nutt <gnutt@nuttx.org>
@ -52,10 +52,19 @@
#include "stm32_internal.h" #include "stm32_internal.h"
#include "stm3220g-internal.h" #include "stm3220g-internal.h"
#ifdef CONFIG_STM32_OTGFS
/************************************************************************************ /************************************************************************************
* Definitions * Definitions
************************************************************************************/ ************************************************************************************/
#if defined(CONFIG_USBDEV) || defined(CONFIG_USBDEV)
# define HAVE_USB 1
#else
# warning "CONFIG_STM32_OTGFS is enabled but neither CONFIG_USBDEV nor CONFIG_USBDEV"
# undef HAVE_USB
#endif
/************************************************************************************ /************************************************************************************
* Private Functions * Private Functions
************************************************************************************/ ************************************************************************************/
@ -68,23 +77,109 @@
* Name: stm32_usbinitialize * Name: stm32_usbinitialize
* *
* Description: * Description:
* Called to setup USB-related GPIO pins for the STM3210E-EVAL board. * Called from stm32_usbinitialize very early in inialization to setup USB-related
* GPIO pins for the STM3220G-EVAL board.
* *
************************************************************************************/ ************************************************************************************/
void stm32_usbinitialize(void) void stm32_usbinitialize(void)
{ {
/* The OTG FS has an internal soft pull-up */ #ifdef HAVE_USB
/* The OTG FS has an internal soft pull-up. No GPIO configuration is required */
/* Configure the OTG FS VBUS sensing GPIO, Power On, and Overcurrent GPIOs */ /* Configure the OTG FS VBUS sensing GPIO, Power On, and Overcurrent GPIOs */
#ifdef CONFIG_STM32_OTGFS
stm32_configgpio(GPIO_OTGFS_VBUS); stm32_configgpio(GPIO_OTGFS_VBUS);
stm32_configgpio(GPIO_OTGFS_PWRON); stm32_configgpio(GPIO_OTGFS_PWRON);
stm32_configgpio(GPIO_OTGFS_OVER); stm32_configgpio(GPIO_OTGFS_OVER);
#endif #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.
*
***********************************************************************************/
#ifdef CONFIG_USBHOST
void stm32_usbhost_initialize(void)
{
#warning "Missing logic"
}
#endif
/***********************************************************************************
* Name: stm32_usbhost_vbusdrive
*
* Description:
* Enable/disable driving of VBUS 5V output. This function must be provided be
* each platform that implements the STM32 OTG FS host interface
*
* "On-chip 5 V VBUS generation is not supported. For this reason, a charge pump
* or, if 5 V are available on the application board, a basic power switch, must
* be added externally to drive the 5 V VBUS line. The external charge pump can
* be driven by any GPIO output. When the application decides to power on VBUS
* using the chosen GPIO, it must also set the port power bit in the host port
* control and status register (PPWR bit in OTG_FS_HPRT).
*
* "The application uses this field to control power to this port, and the core
* clears this bit on an overcurrent condition."
*
* Input Parameters:
* iface - For future growth to handle multiple USB host interface. Should be zero.
* enable - true: enable VBUS power; false: disable VBUS power
*
* Returned Value:
* None
*
***********************************************************************************/
#ifdef CONFIG_USBHOST
void stm32_usbhost_vbusdrive(int iface, bool enable)
{
DEBUGASSERT(iface == 0);
if (enable)
{
/* Enable the Power Switch by driving the enable pin low */
stm32_gpiowrite(GPIO_OTGFS_PWRON, false);
}
else
{
/* Disable the Power Switch by driving the enable pin high */
stm32_gpiowrite(GPIO_OTGFS_PWRON, true);
}
}
#endif
/************************************************************************************
* Name: stm32_setup_overcurrent
*
* Description:
* Setup to receive an interrupt-level callback if an overcurrent condition is
* detected.
*
* Input paramter:
* handler - New overcurrent interrupt handler
*
* Returned value:
* Old overcurrent interrupt handler
*
************************************************************************************/
#ifdef CONFIG_USBHOST
xcpt_t stm32_setup_overcurrent(xcpt_t handler)
{
return stm32_gpiosetevent(GPIO_OTGFS_OVER, true, true, true, handler);
}
#endif
/************************************************************************************ /************************************************************************************
* Name: stm32_usbsuspend * Name: stm32_usbsuspend
* *
@ -96,8 +191,12 @@ void stm32_usbinitialize(void)
* *
************************************************************************************/ ************************************************************************************/
#ifdef CONFIG_USBDEV
void stm32_usbsuspend(FAR struct usbdev_s *dev, bool resume) void stm32_usbsuspend(FAR struct usbdev_s *dev, bool resume)
{ {
ulldbg("resume: %d\n", resume); ulldbg("resume: %d\n", resume);
} }
#endif
#endif /* CONFIG_STM32_OTGFS */

View File

@ -75,7 +75,7 @@
* PLLM : 25 (STM32_PLLCFG_PLLM) * PLLM : 25 (STM32_PLLCFG_PLLM)
* PLLN : 336 (STM32_PLLCFG_PLLN) * PLLN : 336 (STM32_PLLCFG_PLLN)
* PLLP : 2 (STM32_PLLCFG_PLLP) * PLLP : 2 (STM32_PLLCFG_PLLP)
* PLLQ : 7 (STM32_PLLCFG_PPQ) * PLLQ : 7 (STM32_PLLCFG_PLLQ)
* Main regulator output voltage : Scale1 mode Needed for high speed SYSCLK * Main regulator output voltage : Scale1 mode Needed for high speed SYSCLK
* Flash Latency(WS) : 5 * Flash Latency(WS) : 5
* Prefetch Buffer : OFF * Prefetch Buffer : OFF
@ -114,7 +114,7 @@
#define STM32_PLLCFG_PLLM RCC_PLLCFG_PLLM(25) #define STM32_PLLCFG_PLLM RCC_PLLCFG_PLLM(25)
#define STM32_PLLCFG_PLLN RCC_PLLCFG_PLLN(336) #define STM32_PLLCFG_PLLN RCC_PLLCFG_PLLN(336)
#define STM32_PLLCFG_PLLP RCC_PLLCFG_PLLP_2 #define STM32_PLLCFG_PLLP RCC_PLLCFG_PLLP_2
#define STM32_PLLCFG_PPQ RCC_PLLCFG_PLLQ(7) #define STM32_PLLCFG_PLLQ RCC_PLLCFG_PLLQ(7)
#define STM32_SYSCLK_FREQUENCY 168000000ul #define STM32_SYSCLK_FREQUENCY 168000000ul

View File

@ -68,7 +68,7 @@
* PLLM : 8 (STM32_PLLCFG_PLLM) * PLLM : 8 (STM32_PLLCFG_PLLM)
* PLLN : 336 (STM32_PLLCFG_PLLN) * PLLN : 336 (STM32_PLLCFG_PLLN)
* PLLP : 2 (STM32_PLLCFG_PLLP) * PLLP : 2 (STM32_PLLCFG_PLLP)
* PLLQ : 7 (STM32_PLLCFG_PPQ) * PLLQ : 7 (STM32_PLLCFG_PLLQ)
* Main regulator output voltage : Scale1 mode Needed for high speed SYSCLK * Main regulator output voltage : Scale1 mode Needed for high speed SYSCLK
* Flash Latency(WS) : 5 * Flash Latency(WS) : 5
* Prefetch Buffer : OFF * Prefetch Buffer : OFF
@ -107,7 +107,7 @@
#define STM32_PLLCFG_PLLM RCC_PLLCFG_PLLM(8) #define STM32_PLLCFG_PLLM RCC_PLLCFG_PLLM(8)
#define STM32_PLLCFG_PLLN RCC_PLLCFG_PLLN(336) #define STM32_PLLCFG_PLLN RCC_PLLCFG_PLLN(336)
#define STM32_PLLCFG_PLLP RCC_PLLCFG_PLLP_2 #define STM32_PLLCFG_PLLP RCC_PLLCFG_PLLP_2
#define STM32_PLLCFG_PPQ RCC_PLLCFG_PLLQ(7) #define STM32_PLLCFG_PLLQ RCC_PLLCFG_PLLQ(7)
#define STM32_SYSCLK_FREQUENCY 168000000ul #define STM32_SYSCLK_FREQUENCY 168000000ul