summaryrefslogtreecommitdiff
path: root/nuttx/arch
diff options
context:
space:
mode:
Diffstat (limited to 'nuttx/arch')
-rw-r--r--nuttx/arch/arm/src/stm32/Kconfig16
-rw-r--r--nuttx/arch/arm/src/stm32/Make.defs6
-rw-r--r--nuttx/arch/arm/src/stm32/chip/stm32_otgfs.h7
-rw-r--r--nuttx/arch/arm/src/stm32/chip/stm32f40xxx_pinmap.h19
-rw-r--r--nuttx/arch/arm/src/stm32/chip/stm32f40xxx_vectors.h4
-rw-r--r--nuttx/arch/arm/src/stm32/stm32_otgfs.h2
-rw-r--r--nuttx/arch/arm/src/stm32/stm32_otgfsdev.c30
-rw-r--r--nuttx/arch/arm/src/stm32/stm32_otgfshost.c15
-rw-r--r--nuttx/arch/arm/src/stm32/stm32f40xxx_rcc.c7
9 files changed, 85 insertions, 21 deletions
diff --git a/nuttx/arch/arm/src/stm32/Kconfig b/nuttx/arch/arm/src/stm32/Kconfig
index 03c36b755..0b8b1f975 100644
--- a/nuttx/arch/arm/src/stm32/Kconfig
+++ b/nuttx/arch/arm/src/stm32/Kconfig
@@ -752,6 +752,19 @@ config STM32_OTGHS
default n
depends on STM32_STM32F20XX || STM32_STM32F40XX
+config STM32_OTGHS_FS_MODE
+ bool "Use OTG HS in FS mode"
+ default n
+ depends on STM32_OTGHS && !STM32_OTGFS
+ select STM32_OTGFS2
+ ---help---
+ The STM32 USB HS module can operate in legacy FS mode using the
+ built-in FS PHY in the HS module. This mode can only be used if
+ the OTG FS block is not being used since they use on the same
+ driver, and all the base address are different (the driver
+ uses #define defined addresses which are re-mapped when this
+ option is selected).
+
config STM32_PWR
bool "PWR"
default n
@@ -992,6 +1005,9 @@ config STM32_I2C
config STM32_CAN
bool
+config STM32_OTGFS2
+ bool
+
menu "Alternate Pin Mapping"
choice
diff --git a/nuttx/arch/arm/src/stm32/Make.defs b/nuttx/arch/arm/src/stm32/Make.defs
index 0491c91a1..18a92ed40 100644
--- a/nuttx/arch/arm/src/stm32/Make.defs
+++ b/nuttx/arch/arm/src/stm32/Make.defs
@@ -118,12 +118,18 @@ endif
ifeq ($(CONFIG_STM32_OTGFS),y)
CHIP_CSRCS += stm32_otgfsdev.c
endif
+ifeq ($(CONFIG_STM32_OTGFS2),y)
+CHIP_CSRCS += stm32_otgfsdev.c
+endif
endif
ifeq ($(CONFIG_USBHOST),y)
ifeq ($(CONFIG_STM32_OTGFS),y)
CHIP_CSRCS += stm32_otgfshost.c
endif
+ifeq ($(CONFIG_STM32_OTGFS2),y)
+CHIP_CSRCS += stm32_otgfshost.c
+endif
endif
ifneq ($(CONFIG_IDLE_CUSTOM),y)
diff --git a/nuttx/arch/arm/src/stm32/chip/stm32_otgfs.h b/nuttx/arch/arm/src/stm32/chip/stm32_otgfs.h
index ee34172cf..7c574f3b0 100644
--- a/nuttx/arch/arm/src/stm32/chip/stm32_otgfs.h
+++ b/nuttx/arch/arm/src/stm32/chip/stm32_otgfs.h
@@ -59,6 +59,13 @@
#define OTGFS_PID_MDATA (3) /* Non-control */
#define OTGFS_PID_SETUP (3) /* Control */
+/* If OTGFS2 is defined (FS mode of the HS module), then remap the OTGFS base address */
+
+#ifdef CONFIG_STM32_OTGFS2
+# undef STM32_OTGFS_BASE
+# define STM32_OTGFS_BASE STM32_OTGHS_BASE
+#endif
+
/* Register Offsets *********************************************************************************/
/* Core global control and status registers */
diff --git a/nuttx/arch/arm/src/stm32/chip/stm32f40xxx_pinmap.h b/nuttx/arch/arm/src/stm32/chip/stm32f40xxx_pinmap.h
index 65effbee5..47a731dc1 100644
--- a/nuttx/arch/arm/src/stm32/chip/stm32f40xxx_pinmap.h
+++ b/nuttx/arch/arm/src/stm32/chip/stm32f40xxx_pinmap.h
@@ -396,23 +396,20 @@
#define GPIO_OTGFS_SDA (GPIO_ALT|GPIO_AF10|GPIO_PORTB|GPIO_PIN9)
#define GPIO_OTGFS_SOF (GPIO_ALT|GPIO_FLOAT|GPIO_AF10|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTA|GPIO_PIN8)
-#ifdef CONFIG_STM32_STM32F429
-# define GPIO_OTG2FS_DM (GPIO_ALT|GPIO_AF12|GPIO_PORTB|GPIO_PIN14)
-# define GPIO_OTG2FS_DP (GPIO_ALT|GPIO_AF12|GPIO_PORTC|GPIO_PIN15)
-# define GPIO_OTG2FS_ID (GPIO_ALT|GPIO_AF12|GPIO_PORTB|GPIO_PIN12)
-# define GPIO_OTG2FS_SCL (GPIO_ALT|GPIO_AF12|GPIO_PORTB|GPIO_PIN10)
-# define GPIO_OTG2FS_SDA (GPIO_ALT|GPIO_AF12|GPIO_PORTB|GPIO_PIN11)
-# define GPIO_OTG2FS_SOF (GPIO_ALT|GPIO_AF12|GPIO_PORTA|GPIO_PIN4)
+#ifdef CONFIG_STM32_OTGFS2
+# define GPIO_OTGFS2_DM (GPIO_ALT|GPIO_FLOAT|GPIO_AF12|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTB|GPIO_PIN14)
+# define GPIO_OTGFS2_DP (GPIO_ALT|GPIO_FLOAT|GPIO_AF12|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTB|GPIO_PIN15)
+# define GPIO_OTGFS2_ID (GPIO_ALT|GPIO_PULLUP|GPIO_AF12|GPIO_SPEED_100MHz|GPIO_OPENDRAIN|GPIO_PORTB|GPIO_PIN12)
#endif
-#define GPIO_OTGHS_DM (GPIO_ALT|GPIO_AF12|GPIO_PORTB|GPIO_PIN14)
-#define GPIO_OTGHS_DP (GPIO_ALT|GPIO_AF12|GPIO_PORTC|GPIO_PIN15)
-#define GPIO_OTGHS_ID (GPIO_ALT|GPIO_AF12|GPIO_PORTB|GPIO_PIN12)
+#define GPIO_OTGHS_DM (GPIO_ALT|GPIO_FLOAT|GPIO_AF12|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTB|GPIO_PIN14)
+#define GPIO_OTGHS_DP (GPIO_ALT|GPIO_FLOAT|GPIO_AF12|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTB|GPIO_PIN15)
+#define GPIO_OTGHS_ID (GPIO_ALT|GPIO_PULLUP|GPIO_AF12|GPIO_SPEED_100MHz|GPIO_OPENDRAIN|GPIO_PORTB|GPIO_PIN12)
#define GPIO_OTGHS_INTN_1 (GPIO_ALT|GPIO_AF12|GPIO_PORTB|GPIO_PIN1)
#define GPIO_OTGFS_INTN_2 (GPIO_ALT|GPIO_AF10|GPIO_PORTB|GPIO_PIN6)
#define GPIO_OTGHS_SCL (GPIO_ALT|GPIO_AF12|GPIO_PORTB|GPIO_PIN10)
#define GPIO_OTGHS_SDA (GPIO_ALT|GPIO_AF12|GPIO_PORTB|GPIO_PIN11)
-#define GPIO_OTGHS_SOF (GPIO_ALT|GPIO_AF12|GPIO_PORTA|GPIO_PIN4)
+#define GPIO_OTGHS_SOF (GPIO_ALT|GPIO_FLOAT|GPIO_AF12|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTA|GPIO_PIN4)
#define GPIO_OTGHS_ULPI_CK (GPIO_ALT|GPIO_AF10|GPIO_PORTA|GPIO_PIN5)
#define GPIO_OTGHS_ULPI_D0 (GPIO_ALT|GPIO_AF10|GPIO_PORTA|GPIO_PIN3)
diff --git a/nuttx/arch/arm/src/stm32/chip/stm32f40xxx_vectors.h b/nuttx/arch/arm/src/stm32/chip/stm32f40xxx_vectors.h
index a5a535aa8..145ce0b9d 100644
--- a/nuttx/arch/arm/src/stm32/chip/stm32f40xxx_vectors.h
+++ b/nuttx/arch/arm/src/stm32/chip/stm32f40xxx_vectors.h
@@ -52,8 +52,10 @@
/* Reserve interrupt table entries for I/O interrupts. */
-# if defined(CONFIG_STM32_STM32F427) || defined(CONFIG_STM32_STM32F429)
+# if defined(CONFIG_STM32_STM32F427)
# define ARMV7M_PERIPHERAL_INTERRUPTS 87
+# elif defined(CONFIG_STM32_STM32F429)
+# define ARMV7M_PERIPHERAL_INTERRUPTS 91
# else
# define ARMV7M_PERIPHERAL_INTERRUPTS 82
# endif
diff --git a/nuttx/arch/arm/src/stm32/stm32_otgfs.h b/nuttx/arch/arm/src/stm32/stm32_otgfs.h
index 673b88503..d7452bc47 100644
--- a/nuttx/arch/arm/src/stm32/stm32_otgfs.h
+++ b/nuttx/arch/arm/src/stm32/stm32_otgfs.h
@@ -47,7 +47,7 @@
#include "stm32.h"
#include "chip/stm32_otgfs.h"
-#ifdef CONFIG_STM32_OTGFS
+#if defined(CONFIG_STM32_OTGFS) || defined (CONFIG_STM32_OTGFS2)
/************************************************************************************
* Pre-processor Definitions
diff --git a/nuttx/arch/arm/src/stm32/stm32_otgfsdev.c b/nuttx/arch/arm/src/stm32/stm32_otgfsdev.c
index 04806e70e..30ebd5977 100644
--- a/nuttx/arch/arm/src/stm32/stm32_otgfsdev.c
+++ b/nuttx/arch/arm/src/stm32/stm32_otgfsdev.c
@@ -62,7 +62,7 @@
#include "stm32_otgfs.h"
-#if defined(CONFIG_USBDEV) && defined(CONFIG_STM32_OTGFS)
+#if defined(CONFIG_USBDEV) && (defined(CONFIG_STM32_OTGFS) || defined(CONFIG_STM32_OTGFS2))
/*******************************************************************************
* Definitions
@@ -276,6 +276,13 @@
# define MAX(a,b) ((a) > (b) ? (a) : (b))
#endif
+/* For OTGFS2 mode (FS mode of HS module), remap the IRQ number *****************/
+
+#ifdef CONFIG_STM32_OTGFS2
+# undef STM32_IRQ_OTGFS
+# define STM32_IRQ_OTGFS STM32_IRQ_OTGHS
+#endif
+
/*******************************************************************************
* Private Types
*******************************************************************************/
@@ -2041,11 +2048,8 @@ static void stm32_usbreset(struct stm32_usbdev_s *priv)
static inline void stm32_ep0out_testmode(FAR struct stm32_usbdev_s *priv,
uint16_t index)
{
- uint32_t regval;
uint8_t testmode;
- regval = stm32_getreg(STM32_OTGFS_DCTL);
-
testmode = index >> 8;
switch (testmode)
{
@@ -4416,7 +4420,6 @@ static int stm32_ep_submit(FAR struct usbdev_ep_s *ep, FAR struct usbdev_req_s *
static int stm32_ep_cancel(FAR struct usbdev_ep_s *ep, FAR struct usbdev_req_s *req)
{
FAR struct stm32_ep_s *privep = (FAR struct stm32_ep_s *)ep;
- FAR struct stm32_usbdev_s *priv;
irqstate_t flags;
#ifdef CONFIG_DEBUG
@@ -4428,7 +4431,6 @@ static int stm32_ep_cancel(FAR struct usbdev_ep_s *ep, FAR struct usbdev_req_s *
#endif
usbtrace(TRACE_EPCANCEL, privep->epphy);
- priv = privep->dev;
flags = irqsave();
@@ -5140,6 +5142,16 @@ static void stm32_hwinitialize(FAR struct stm32_usbdev_s *priv)
stm32_putreg(OTGFS_GAHBCFG_TXFELVL, STM32_OTGFS_GAHBCFG);
+ /* For OTGFS2 mode (FS mode of the HS module), we must select the FS PHY
+ * mode prior to issuing a soft reset.
+ */
+
+#ifdef CONFIG_STM32_OTGFS2
+ regval = stm32_getreg(STM32_OTGFS_GUSBCFG);
+ regval |= OTGFS_GUSBCFG_PHYSEL;
+ stm32_putreg(regval, STM32_OTGFS_GUSBCFG);
+#endif
+
/* Common USB OTG core initialization */
/* Reset after a PHY select and set Host mode. First, wait for AHB master
* IDLE state.
@@ -5397,9 +5409,15 @@ void up_usbinitialize(void)
* *Pins may vary from device-to-device.
*/
+#ifdef CONFIG_STM32_OTGFS2
+ stm32_configgpio(GPIO_OTGFS2_DM);
+ stm32_configgpio(GPIO_OTGFS2_DP);
+ stm32_configgpio(GPIO_OTGFS2_ID); /* Only needed for OTG */
+#else
stm32_configgpio(GPIO_OTGFS_DM);
stm32_configgpio(GPIO_OTGFS_DP);
stm32_configgpio(GPIO_OTGFS_ID); /* Only needed for OTG */
+#endif
/* SOF output pin configuration is configurable. */
diff --git a/nuttx/arch/arm/src/stm32/stm32_otgfshost.c b/nuttx/arch/arm/src/stm32/stm32_otgfshost.c
index c3a795faf..68cfe7fca 100644
--- a/nuttx/arch/arm/src/stm32/stm32_otgfshost.c
+++ b/nuttx/arch/arm/src/stm32/stm32_otgfshost.c
@@ -65,7 +65,7 @@
#include "stm32_usbhost.h"
-#if defined(CONFIG_USBHOST) && defined(CONFIG_STM32_OTGFS)
+#if defined(CONFIG_USBHOST) && (defined(CONFIG_STM32_OTGFS) || defined(CONFIG_STM32_OTGFS2))
/*******************************************************************************
* Definitions
@@ -163,6 +163,13 @@
# define MAX(a, b) (((a) > (b)) ? (a) : (b))
#endif
+/* For OTGFS2 mode (FS mode of HS module), remap the IRQ number *****************/
+
+#ifdef CONFIG_STM32_OTGFS2
+# undef STM32_IRQ_OTGFS
+# define STM32_IRQ_OTGFS STM32_IRQ_OTGHS
+#endif
+
/*******************************************************************************
* Private Types
*******************************************************************************/
@@ -4310,9 +4317,15 @@ FAR struct usbhost_connection_s *stm32_otgfshost_initialize(int controller)
* *Pins may vary from device-to-device.
*/
+#ifdef CONFIG_STM32_OTGFS2
+ stm32_configgpio(GPIO_OTGFS2_DM);
+ stm32_configgpio(GPIO_OTGFS2_DP);
+ stm32_configgpio(GPIO_OTGFS2_ID); /* Only needed for OTG */
+#else
stm32_configgpio(GPIO_OTGFS_DM);
stm32_configgpio(GPIO_OTGFS_DP);
stm32_configgpio(GPIO_OTGFS_ID); /* Only needed for OTG */
+#endif
/* SOF output pin configuration is configurable */
diff --git a/nuttx/arch/arm/src/stm32/stm32f40xxx_rcc.c b/nuttx/arch/arm/src/stm32/stm32f40xxx_rcc.c
index 712798efe..77eb39563 100644
--- a/nuttx/arch/arm/src/stm32/stm32f40xxx_rcc.c
+++ b/nuttx/arch/arm/src/stm32/stm32f40xxx_rcc.c
@@ -197,9 +197,14 @@ static inline void rcc_enableahb1(void)
#ifdef CONFIG_STM32_OTGHS
/* USB OTG HS */
- regval |= (RCC_AHB1ENR_OTGHSEN|RCC_AHB1ENR_OTGHSULPIEN);
+#ifdef CONFIG_STM32_OTGFS2
+ regval |= RCC_AHB1ENR_OTGHSEN;
+#else
+ regval |= RCC_AHB1ENR_OTGHSULPIEN;
#endif
+#endif /* CONFIG_STM32_OTGHS */
+
putreg32(regval, STM32_RCC_AHB1ENR); /* Enable peripherals */
}