aboutsummaryrefslogtreecommitdiff
diff options
context:
space:
mode:
authorLorenz Meier <lm@inf.ethz.ch>2012-08-27 07:25:05 +0200
committerLorenz Meier <lm@inf.ethz.ch>2012-08-27 07:25:05 +0200
commit58b51743f2886120062056a12f9f52ef0e77653a (patch)
tree24f620766043e5b133f8c818e5431041f5545055
parent2963dc679a63309a7b26da1677208fbdb4aec146 (diff)
parent4636d41390d0e8afa80da3f9a53600a80ed672bf (diff)
downloadpx4-firmware-58b51743f2886120062056a12f9f52ef0e77653a.tar.gz
px4-firmware-58b51743f2886120062056a12f9f52ef0e77653a.tar.bz2
px4-firmware-58b51743f2886120062056a12f9f52ef0e77653a.zip
Merge branch 'master' of github.com:PX4/Firmware into px4dev_new_driver_wip
-rwxr-xr-xapps/ChangeLog.txt14
-rw-r--r--apps/examples/ostest/prioinherit.c14
-rw-r--r--nuttx/ChangeLog39
-rw-r--r--nuttx/Makefile8
-rw-r--r--nuttx/ReleaseNotes64
-rw-r--r--nuttx/arch/Kconfig37
-rw-r--r--nuttx/arch/arm/Kconfig6
-rw-r--r--nuttx/arch/arm/src/stm32/Kconfig53
-rw-r--r--nuttx/arch/arm/src/stm32/Make.defs6
-rw-r--r--nuttx/arch/arm/src/stm32/chip/stm32_otgfs.h61
-rw-r--r--nuttx/arch/arm/src/stm32/chip/stm32f20xxx_pinmap.h2
-rw-r--r--nuttx/arch/arm/src/stm32/chip/stm32f40xxx_pinmap.h2
-rw-r--r--nuttx/arch/arm/src/stm32/stm32_otgfsdev.c26
-rw-r--r--nuttx/arch/arm/src/stm32/stm32_otgfshost.c4095
-rw-r--r--nuttx/arch/arm/src/stm32/stm32_usbhost.c2695
-rw-r--r--nuttx/arch/arm/src/stm32/stm32_usbhost.h57
-rw-r--r--nuttx/arch/arm/src/stm32/stm32f20xxx_rcc.c2
-rw-r--r--nuttx/arch/arm/src/stm32/stm32f40xxx_rcc.c2
-rw-r--r--nuttx/configs/Kconfig703
-rw-r--r--nuttx/configs/px4fmu/Kconfig26
-rwxr-xr-xnuttx/configs/px4fmu/include/board.h2
-rw-r--r--nuttx/configs/px4fmu/nsh/Make.defs2
-rw-r--r--nuttx/configs/px4fmu/nsh/appconfig3
-rwxr-xr-xnuttx/configs/px4fmu/nsh/defconfig268
-rw-r--r--nuttx/configs/px4io/io/Make.defs2
-rwxr-xr-xnuttx/configs/px4io/io/defconfig55
-rw-r--r--nuttx/drivers/Kconfig4
-rw-r--r--nuttx/drivers/lcd/Kconfig39
-rw-r--r--nuttx/drivers/sensors/Make.defs3
-rw-r--r--nuttx/drivers/usbhost/usbhost_enumerate.c12
-rw-r--r--nuttx/drivers/usbhost/usbhost_hidkbd.c6
-rw-r--r--nuttx/drivers/usbhost/usbhost_storage.c113
-rw-r--r--nuttx/include/nuttx/usb/usbhost.h28
-rw-r--r--nuttx/include/semaphore.h23
-rw-r--r--nuttx/lib/semaphore/sem_init.c9
-rw-r--r--nuttx/sched/Kconfig2
-rw-r--r--nuttx/sched/os_start.c21
-rw-r--r--nuttx/sched/sched_waitpid.c3
-rw-r--r--nuttx/sched/sem_holder.c112
-rw-r--r--nuttx/tools/mkconfig.c7
40 files changed, 4855 insertions, 3771 deletions
diff --git a/apps/ChangeLog.txt b/apps/ChangeLog.txt
index 01ef090a0..6c151ae50 100755
--- a/apps/ChangeLog.txt
+++ b/apps/ChangeLog.txt
@@ -248,7 +248,7 @@
being set to the priority of the parent thread; losing its configured
priority. Reported by Mike Smith.
-6.21 2012-xx-xx Gregory Nutt <gnutt@nuttx.org>
+6.21 2012-08-25 Gregory Nutt <gnutt@nuttx.org>
* apps/include/: Stylistic clean-up of all header files.
* apps/modbus and apps/include/modbus: A port of freemodbus-v1.5.0
@@ -259,9 +259,9 @@
* apps/modbus: Add CONFIG_MB_TERMIOS. If the driver doesn't support
termios ioctls, then don't bother trying to configure the baud, parity
etc.
- * apps/nslib: If waitpid() is supported, then NSH not catches the
+ * apps/nshlib: If waitpid() is supported, then NSH now catches the
return value from spawned applications (provided by Mike Smith)
- * apps/nslib: Lock the schedule while starting built-in applications
+ * apps/nshlib: Lock the scheduler while starting built-in applications
in order to eliminate race conditions (also from Mike Smith).
* apps/examples/adc, pwm, and qencoder: Add support for testing
devices with multiple ADC, PWM, and QE devices.
@@ -272,9 +272,15 @@
properties of mounted file systems.
* apps/nshlib/nsh_parse.c: Extend help command options. 'help' with
no arguments outputs a short list of commands. With -v lists all
- command line details. And command name can be added to just get
+ command line details. A command name can be added to just get
help on one command.
* system/readline.c: If character input/output is interrupted by a
signal, then readline() will try the read/write again.
* apps/*/Make.defs: Numerous fixes needed to use the automated
configuration (from Richard Cochran).
+
+6.22 2012-xx-xx Gregory Nutt <gnutt@nuttx.org>
+
+ * apps/netutils/thttpd/thttpd_cgi.c: Missing NULL in argv[]
+ list (contributed by Kate).
+
diff --git a/apps/examples/ostest/prioinherit.c b/apps/examples/ostest/prioinherit.c
index 993c9e14a..87849abcf 100644
--- a/apps/examples/ostest/prioinherit.c
+++ b/apps/examples/ostest/prioinherit.c
@@ -58,12 +58,22 @@
#ifndef CONFIG_SEM_PREALLOCHOLDERS
# define CONFIG_SEM_PREALLOCHOLDERS 0
#endif
-#define NLOWPRI_THREADS (CONFIG_SEM_PREALLOCHOLDERS+1)
+
+#if CONFIG_SEM_PREALLOCHOLDERS > 3
+# define NLOWPRI_THREADS 3
+#else
+# define NLOWPRI_THREADS (CONFIG_SEM_PREALLOCHOLDERS+1)
+#endif
#ifndef CONFIG_SEM_NNESTPRIO
# define CONFIG_SEM_NNESTPRIO 0
#endif
-#define NHIGHPRI_THREADS (CONFIG_SEM_NNESTPRIO+1)
+
+#if CONFIG_SEM_NNESTPRIO > 3
+# define NHIGHPRI_THREADS 3
+#else
+# define NHIGHPRI_THREADS (CONFIG_SEM_NNESTPRIO+1)
+#endif
/****************************************************************************
* Private Data
diff --git a/nuttx/ChangeLog b/nuttx/ChangeLog
index 48f1866c3..cb7f4079d 100644
--- a/nuttx/ChangeLog
+++ b/nuttx/ChangeLog
@@ -2280,7 +2280,7 @@
the particular condition that revealed the bug occurred. My impression is
that this latter bugfix also fixes some STM32 USB performance problems.
* configs/hymini-stm32v: A configuration for the HY-Mini STM32v board contributed
- by Laurent Latil. Theses changes also include support for the STM32F103VCT6.
+ by Laurent Latil. These changes also include support for the STM32F103VCT6.
* arch/configs/stm3240g-eval/src/up_pwm.c: Add hooks needed to use the new
apps/examples/pwm test of the STM32 PWM driver.
* drivers/mtd/mp25x.c: Add ability to use different SPI modes and different
@@ -2977,7 +2977,7 @@
* configs/lpc4330-xplorer/nsh: Add an NSH configuration for the LPC4330
Xplorer board.
-6.21 2012-xx-xx Gregory Nutt <gnutt@nuttx.org>
+6.21 2012-08-25 Gregory Nutt <gnutt@nuttx.org>
* configs/lpc4330-xplorer/up_nsh.c: Add support for a basic SPIFI block
driver for use by NSH. Does not work! Crashes on first SPIFI write.
@@ -3024,7 +3024,7 @@
but the driver still does not work.
* arch/arm/src/stm32 and arch/arm/include/stm32: Make name of RTC ALARM interrupt
common on STM32 F1,2,4
- * arch/arm/src/stm32 and arch/arm/include/stm32: Add add support for the
+ * arch/arm/src/stm32 and arch/arm/include/stm32: Add support for the
STM32F100x "Value Line" devices. This includes changes to stm32F10xx_rcc.c that
add the ability to run the chip off the internal oscillator. There is no open
board configuration for this part yet (the STM32VLDiscovery would be a candidate).
@@ -3050,7 +3050,7 @@
* include/termios.h and lib/termios/*: Redesigned yet again (this is getting
painful. NuttX now supports the BOTHER baud setting just as Linux does. termios
Bxxx definitions are again encoded; cf[set|get][o|i]speed now deal with only the
- encoded values. If the encode baud is set to BOTHER, then the values in the (non-
+ encoded values. If the encoded baud is set to BOTHER, then the values in the (non-
standard) c_ispeed and c_ospeed baud values may be accessed directly.
* arch/arm/src/stm32/stm32_serial.c: Add minimal termios support for the STM32
(BOTHER style baud settings only). Contributed by Mike Smith.
@@ -3063,8 +3063,7 @@
* arch/arm/src/stm32/stm32_sdio.c and chip/stm32f20xx_pinmap.h: STM32 F2 SDIO
fixes from Gary Teravskis and Scott Rondestvedt.
* include/termios.h and lib/termios/*: Replace cfsetispeed and cfsetospeed with
- cfsetspeed (with definitions for the input/outputs in termios.h). Same for
- cfgetispeed and cfgetospeed.
+ cfsetspeed (with definitions for the input/outputs in termios.h).
* configs/stm32f4discovery/src and configs/stm32f4discovery/pm: Add a power
management configuration for the STM32F4Discovery and supporting logic. This
check-in also includes some fixes for the F4 RTC alarm logic.
@@ -3090,10 +3089,10 @@
* arch/mips/src/pic32mx/pic32mx-gpio.c: Now supports the PIC32MX1/2 ANSEL
IOPORT register.
* lib/string/lib_memchr.c: Add support for memchr() (contributed by Mike Smith)
- * lib/string/lib_memccpy.c: Add support for memcpy()
+ * lib/string/lib_memccpy.c: Add support for memccpy()
* arch/arm/src/lpc17xx/lpc17_serial.c: Now supports ioctl commands to change
the baud using tcsetattr() (contributed by Chris Taglia).
- * arch/*/src/*_serial.c: Fix ioctl method return values. Theses methods
+ * arch/*/src/*_serial.c: Fix ioctl method return values. These methods
should return a negated errno value; they should not set the errno
variable.
* sched/on_exit.c, sched/task_exithook.c, and include/nuttx/sched.c: Add
@@ -3118,7 +3117,7 @@
* arch/arm/src/stm32/stm32*_rcc.c and .h: If CONFIG_PM is defined, add a
function called stm32_clockenable() that can be used by PM logic to re-start
the PLL after re-awakening from deep sleep modes.
- * fs/fs_foreachinode.c and fs/fs_foreachmountpoint.c: All logic to traverse
+ * fs/fs_foreachinode.c and fs/fs_foreachmountpoint.c: Add logic to traverse
inodes and mountpoints in the NuttX pseudo-file system.
* fs/fat/fs_fat32.c: Max. filename length reported by statfs() was wrong
if FAT long file names were enabled.
@@ -3137,7 +3136,7 @@
LPC31xx has the same USB IP, but will require some additional initialization
(and lots of testing) before it can be used with the LPC43xx.
* nuttx/Documentation/NuttShell.html: Added a section covering ways to
- customize the behavior or NSH.
+ customize the behavior of NSH.
* arch/arm/src/stm32/chip/stm32f1*_pinmap.h: STM32 CAN TX/RX pins reversed;
inconsistent conditional compilation. Reported by Max Holtzberg.
* arch/arm/*/stm32: Add support for STM32 F107 "Connectivity Line"
@@ -3166,5 +3165,23 @@
for all 8-bit AVR platforms (Thanks Richard Cochran).
* lib/stdio/lib_*stream.c: Revised to handle new error return values from
serial.c.
- * arch/arm/src/stm32/stm32_spi.c: SPI driver can now survice re-
+ * arch/arm/src/stm32/stm32_spi.c: SPI driver can now service re-
initialization (Mike Smith).
+ * tools/mkconfig.c: If CONFIG_DRAM_END is not specified, this tool
+ will provide default definition of (CONFIG_DRAM_START + CONFIG_DRAM_SIZE)
+ * arch/arm/src/stm32/stm32_otgfshost.c: Renamed from stm32_usbhost.c.
+ This is nearly code complete and, with any luck, will be available
+ in NuttX-6.21.
+ * configs/*/defconfig: Update all defconfig files to remove syntax
+ that is incompatible with the mconf configuration tool.
+ * arch/arm/src/stm32/stm32_otgfshost.c: This driver now appears to be
+ functional (although more testing is necesary).
+
+6.22 2012-xx-xx Gregory Nutt <gnutt@nuttx.org>
+
+ * include/semaphore.h, sched/sem_holders.c, and lib/semaphore/sem_init.c:
+ Fix some strange (and probably wrong) list handling when
+ CONFIG_PRIORITY_INHERITANCE and CONFIG_SEM_PREALLOCHOLDERS are defined.
+ This list handling was probably causing errors reported by Mike Smith
+ * sched/sched_waitpid.c: Fix a possible issue with logic logic that
+ should be brought into a critical section (suggested by Mike Smith)
diff --git a/nuttx/Makefile b/nuttx/Makefile
index ea83d69ee..b0a17efd2 100644
--- a/nuttx/Makefile
+++ b/nuttx/Makefile
@@ -276,8 +276,8 @@ include/stdarg.h:
endif
# Targets used to build include/nuttx/version.h. Creation of version.h is
-# part of the overall NuttX configuration sequency. Notice that the
-# tools/mkversion tool is cuilt and used to create include/nuttx/version.h
+# part of the overall NuttX configuration sequence. Notice that the
+# tools/mkversion tool is built and used to create include/nuttx/version.h
tools/mkversion:
@$(MAKE) -C tools -f Makefile.host TOPDIR="$(TOPDIR)" mkversion
@@ -293,8 +293,8 @@ include/nuttx/version.h: $(TOPDIR)/.version tools/mkversion
@tools/mkversion $(TOPDIR) > include/nuttx/version.h
# Targets used to build include/nuttx/config.h. Creation of config.h is
-# part of the overall NuttX configuration sequency. Notice that the
-# tools/mkconfig tool is cuilt and used to create include/nuttx/config.h
+# part of the overall NuttX configuration sequence. Notice that the
+# tools/mkconfig tool is built and used to create include/nuttx/config.h
tools/mkconfig:
@$(MAKE) -C tools -f Makefile.host TOPDIR="$(TOPDIR)" mkconfig
diff --git a/nuttx/ReleaseNotes b/nuttx/ReleaseNotes
index 26af0e38d..98e71614c 100644
--- a/nuttx/ReleaseNotes
+++ b/nuttx/ReleaseNotes
@@ -2999,3 +2999,67 @@ Bugfixes (see the change log for details) :
on Z80.
As well as other, less critical bugs (see the ChangeLog for details)
+
+NuttX-6.21
+^^^^^^^^^^
+
+The 88th release of NuttX, Version 6.21, was made on August 25, 2012,
+and is available for download from the SourceForge website. Note
+that release consists of two tarballs: nuttx-6.21.tar.gz and
+apps-6.21.tar.gz. Both may be needed (see the top-level nuttx/README.txt
+file for build information).
+
+This release corresponds with SVN release number: r5052
+
+Additional new features and extended functionality:
+
+ * Core: Add support for multiple registered atexit() functions. Syslog
+ extended: Now any character driver may be used for the debug logging
+ device. Mountpoint traversal logic.
+ * Drivers: Added support for the TI PGA112-7 amplifier/multiplexor.
+ * LPC43xx: Added clock ramp-up logic to run at 204 MHz
+ * LPC43xx Drivers: SPIFI block driver, RS-485 support, Minimal termios
+ support. Framework for USB0 device controller driver.
+ * LPC17xx Drivers: Minimal termios support
+ * STM32: Support for STM32 F1 "Value Line" (contributed by Mike Smith).
+ Add support for STM32 F107 "Connectivity Line" (contributed by Max
+ Holtzberg).
+ Clock restart logic needed for recovery from low power modes.
+ * STM32 Drivers: RTC alarm support. Usable for wakeup from sleep mode,
+ Minimal serial termios support. USB OTG FS host driver (alpha).
+ * STM32 Boards: Add power management hooks for the STM32F4Discovery,
+ Add support for the Olimex STM32-P107 (contributed by Max Holtzberg).
+ * PIC32: Add support for the Pinguino MIPS toolchain.
+ * PIC32 Drivers: GPIO driver now supports F1 analog regiaters (ANSEL).
+ * PIC32 Boards: Add support for the PGA117 on the Mirtoo module.
+ * Calypso: Add support for the SSD1783 LCD on the Compal E99.
+ * Library: cfsetispeed(), cfsetospeed(), tcflush(), memchr(), and
+ memccpy().
+ * Applications: Port of freemodbus-v1.5.0. Add support for testing
+ devices with multiple ADC, PWM, and QE devices.
+ NSH: NSH 'mount' command (with no arguments) will now show mounted
+ volumes. Add new NSH 'df' command. Extended 'help' support. NSH
+ now catches the return value from spawned applications (provided
+ by Mike Smith).
+ * Build System: mkconfig will not define CONFIG_DRAM_END. A lot of
+ progress has been made on the automated NuttX configuration logic
+ (Thanks go to Richard Cochran).
+ * Documentation: Document ways to customize the behavior of NSH.
+
+Bugfixes (see the change log for details) :
+
+ * Serial drivers (all): Fix ioctl return value. Common "upper half"
+ serial driver will now return with EINTR if a serial wait is
+ interrupted by a signal.
+ * FAT: Fix statfs() file name length.
+ * LPC43xx: Clock configuration.
+ * STM32: Pinmap fixes, SPI driver re-initialization
+ * STM32 Boards: Correct and lower SDIO frequency for F2 and f4 boards.
+ * AVR: C++ build issues.
+ * PM: Fix a place where interrupts were not be re-enabled.
+ * Applications: NSH application start-up race conditions.
+ * Library: Fieldwidth and justification for %s format. Fixed several
+ issues with presenting floating point numbers. NULL definition
+ for C++
+
+As well as other, less critical bugs (see the ChangeLog for details)
diff --git a/nuttx/arch/Kconfig b/nuttx/arch/Kconfig
index 6e0e0fb9d..fea56b739 100644
--- a/nuttx/arch/Kconfig
+++ b/nuttx/arch/Kconfig
@@ -19,11 +19,13 @@ config ARCH_ARM
config ARCH_AVR
bool "AVR"
+ select ARCH_NOINTC
---help---
Atmel 8-bit bit AVR and 32-bit AVR32 architectures
config ARCH_HC
bool "Freescale HC"
+ select ARCH_NOINTC
---help---
Freescale HC architectures (M9S12)
@@ -39,7 +41,8 @@ config ARCH_RGMP
http://rgmp.sourceforge.net/wiki/index.php/Main_Page.
config ARCH_SH
- bool "Rensas"
+ bool "Renesas"
+ select ARCH_NOINTC
---help---
Renesas architectures (SH and M16C).
@@ -90,3 +93,35 @@ source arch/sim/Kconfig
source arch/x86/Kconfig
source arch/z16/Kconfig
source arch/z80/Kconfig
+
+comment "Architecture Options"
+
+config ARCH_NOINTC
+ bool
+ default n
+
+config ARCH_STACKDUMP
+ bool "Dump stack on assertions"
+ default n
+ ---help---
+ Enable to do stack dumps after assertions
+
+comment "Board Settings"
+
+config BOARD_LOOPSPERMSEC
+ int "Loops per millisecond"
+ help
+ Must be calibrated for correct operation of delay loops.
+ You simply use a stop watch to measure the 100 second delay
+ then adjust CONFIG_BOARD_LOOPSPERMSEC until it is actually
+ is 100 seconds.
+
+config DRAM_START
+ hex "DRAM start address"
+ help
+ The physical start address of installed RAM.
+
+config DRAM_SIZE
+ int "DRAM size"
+ help
+ The size in bytes of the installed RAM.
diff --git a/nuttx/arch/arm/Kconfig b/nuttx/arch/arm/Kconfig
index 40dcb1105..f587cc274 100644
--- a/nuttx/arch/arm/Kconfig
+++ b/nuttx/arch/arm/Kconfig
@@ -118,12 +118,6 @@ config ARCH_CHIP
default "stm32" if ARCH_CHIP_STM32
default "str71x" if ARCH_CHIP_STR71X
-config ARCH_STACKDUMP
- bool "Dump stack on assertions"
- default n
- ---help---
- Enable to do stack dumps after assertions
-
config ARCH_LEDS
bool "Use board LEDs to show state"
default y
diff --git a/nuttx/arch/arm/src/stm32/Kconfig b/nuttx/arch/arm/src/stm32/Kconfig
index 5d0d48f88..bf7c59c11 100644
--- a/nuttx/arch/arm/src/stm32/Kconfig
+++ b/nuttx/arch/arm/src/stm32/Kconfig
@@ -1910,3 +1910,56 @@ config STM32_MII_MCO1
bool
default y if !STM32_MII_MCO2
depends on STM32_MII
+
+menu "USB Host Configuration"
+
+config STM32_OTGFS_RXFIFO_SIZE
+ int "Rx Packet Size"
+ default 128
+ depends on USBHOST && STM32_OTGFS
+ ---help---
+ Size of the RX FIFO in 32-bit words. Default 128 (512 bytes)
+
+config STM32_OTGFS_NPTXFIFO_SIZE
+ int "Non-periodic Tx FIFO Size"
+ default 96
+ depends on USBHOST && STM32_OTGFS
+ ---help---
+ Size of the non-periodic Tx FIFO in 32-bit words. Default 96 (384 bytes)
+
+config STM32_OTGFS_PTXFIFO_SIZE
+ int "Periodic Tx FIFO size"
+ default 128
+ depends on USBHOST && STM32_OTGFS
+ ---help---
+ Size of the periodic Tx FIFO in 32-bit words. Default 96 (384 bytes)
+
+config STM32_OTGFS_DESCSIZE
+ int "Descriptor Size"
+ default 128
+ depends on USBHOST && STM32_OTGFS
+ ---help---
+ Maximum size to allocate for descriptor memory descriptor. Default: 128
+
+config STM32_OTGFS_SOFINTR
+ bool "Enable SOF interrupts"
+ default n
+ depends on USBHOST && STM32_OTGFS
+ ---help---
+ Enable SOF interrupts. Why would you ever want to do that?
+
+config STM32_USBHOST_REGDEBUG
+ bool "Register-Level Debug"
+ default n
+ depends on USBHOST && STM32_OTGFS
+ ---help---
+ Enable very low-level register access debug. Depends on CONFIG_DEBUG.
+
+config STM32_USBHOST_PKTDUMP
+ bool "Packet Dump Debug"
+ default n
+ depends on USBHOST && STM32_OTGFS
+ ---help---
+ Dump all incoming and outgoing USB packets. Depends on CONFIG_DEBUG.
+
+endmenu
diff --git a/nuttx/arch/arm/src/stm32/Make.defs b/nuttx/arch/arm/src/stm32/Make.defs
index 1deb23189..32e84a78a 100644
--- a/nuttx/arch/arm/src/stm32/Make.defs
+++ b/nuttx/arch/arm/src/stm32/Make.defs
@@ -81,6 +81,12 @@ CMN_CSRCS += stm32_otgfsdev.c
endif
endif
+ifeq ($(CONFIG_USBHOST),y)
+ifeq ($(CONFIG_STM32_OTGFS),y)
+CMN_CSRCS += stm32_otgfshost.c
+endif
+endif
+
ifeq ($(CONFIG_ARMV7M_CMNVECTOR),y)
CHIP_ASRCS += stm32_vectors.S
endif
diff --git a/nuttx/arch/arm/src/stm32/chip/stm32_otgfs.h b/nuttx/arch/arm/src/stm32/chip/stm32_otgfs.h
index d3bf7eb54..ee34172cf 100644
--- a/nuttx/arch/arm/src/stm32/chip/stm32_otgfs.h
+++ b/nuttx/arch/arm/src/stm32/chip/stm32_otgfs.h
@@ -46,6 +46,18 @@
/****************************************************************************************************
* Pre-processor Definitions
****************************************************************************************************/
+/* General definitions */
+
+#define OTGFS_EPTYPE_CTRL (0) /* Control */
+#define OTGFS_EPTYPE_ISOC (1) /* Isochronous */
+#define OTGFS_EPTYPE_BULK (2) /* Bulk */
+#define OTGFS_EPTYPE_INTR (3) /* Interrupt */
+
+#define OTGFS_PID_DATA0 (0)
+#define OTGFS_PID_DATA2 (1)
+#define OTGFS_PID_DATA1 (2)
+#define OTGFS_PID_MDATA (3) /* Non-control */
+#define OTGFS_PID_SETUP (3) /* Control */
/* Register Offsets *********************************************************************************/
/* Core global control and status registers */
@@ -125,8 +137,8 @@
#define STM32_OTGFS_HCTSIZ3_OFFSET 0x0570 /* Host channel-3 interrupt register */
#define STM32_OTGFS_HCTSIZ4_OFFSET 0x0590 /* Host channel-4 interrupt register */
#define STM32_OTGFS_HCTSIZ5_OFFSET 0x05b0 /* Host channel-5 interrupt register */
-#define STM32_OTGFS_HCTSIZ6_OFFSET 0x05d9 /* Host channel-6 interrupt register */
-#define STM32_OTGFS_HCTSIZ7_OFFSET 0x05f9 /* Host channel-7 interrupt register */
+#define STM32_OTGFS_HCTSIZ6_OFFSET 0x05d0 /* Host channel-6 interrupt register */
+#define STM32_OTGFS_HCTSIZ7_OFFSET 0x05f0 /* Host channel-7 interrupt register */
/* Device-mode control and status registers */
@@ -193,6 +205,10 @@
#define STM32_OTGFS_DOEPTSIZ2_OFFSET 0x00b50 /* Device OUT endpoint-2 transfer size register */
#define STM32_OTGFS_DOEPTSIZ3_OFFSET 0x00b70 /* Device OUT endpoint-3 transfer size register */
+/* Power and clock gating registers */
+
+#define STM32_OTGFS_PCGCCTL_OFFSET 0x0e00 /* Power and clock gating control register */
+
/* Data FIFO (DFIFO) access registers */
#define STM32_OTGFS_DFIFO_DEP_OFFSET(n) (0x1000 + ((n) << 12))
@@ -204,15 +220,11 @@
#define STM32_OTGFS_DFIFO_DEP1_OFFSET 0x2000 /* 0x2000-0x2ffc Device IN/OUT Endpoint 1 DFIFO Write/Read Access */
#define STM32_OTGFS_DFIFO_HCH1_OFFSET 0x2000 /* 0x2000-0x2ffc Host OUT/IN Channel 1 DFIFO Read/Write Access */
-#define STM32_OTGFS_DFIFO_DEP2_OFFSET 0x3000 /* 0x3000-0x3ffc Device IN/OUT Endpoint 1 DFIFO Write/Read Access */
-#define STM32_OTGFS_DFIFO_HCH2_OFFSET 0x3000 /* 0x3000-0x3ffc Host OUT/IN Channel 1 DFIFO Read/Write Access */
-
-#define STM32_OTGFS_DFIFO_DEP3_OFFSET 0x4000 /* 0x4000-0x4ffc Device IN/OUT Endpoint 1 DFIFO Write/Read Access */
-#define STM32_OTGFS_DFIFO_HCH3_OFFSET 0x4000 /* 0x4000-0x4ffc Host OUT/IN Channel 1 DFIFO Read/Write Access */
+#define STM32_OTGFS_DFIFO_DEP2_OFFSET 0x3000 /* 0x3000-0x3ffc Device IN/OUT Endpoint 2 DFIFO Write/Read Access */
+#define STM32_OTGFS_DFIFO_HCH2_OFFSET 0x3000 /* 0x3000-0x3ffc Host OUT/IN Channel 2 DFIFO Read/Write Access */
-/* Power and clock gating registers */
-
-#define STM32_OTGFS_PCGCCTL_OFFSET 0x0e00 /* Power and clock gating control register */
+#define STM32_OTGFS_DFIFO_DEP3_OFFSET 0x4000 /* 0x4000-0x4ffc Device IN/OUT Endpoint 3 DFIFO Write/Read Access */
+#define STM32_OTGFS_DFIFO_HCH3_OFFSET 0x4000 /* 0x4000-0x4ffc Host OUT/IN Channel 3 DFIFO Read/Write Access */
/* Register Addresses *******************************************************************************/
@@ -349,6 +361,10 @@
#define STM32_OTGFS_DOEPTSIZ2 (STM32_OTGFS_BASE+STM32_OTGFS_DOEPTSIZ2_OFFSET)
#define STM32_OTGFS_DOEPTSIZ3 (STM32_OTGFS_BASE+STM32_OTGFS_DOEPTSIZ3_OFFSET)
+/* Power and clock gating registers */
+
+#define STM32_OTGFS_PCGCCTL (STM32_OTGFS_BASE+STM32_OTGFS_PCGCCTL_OFFSET)
+
/* Data FIFO (DFIFO) access registers */
#define STM32_OTGFS_DFIFO_DEP(n) (STM32_OTGFS_BASE+STM32_OTGFS_DFIFO_DEP_OFFSET(n))
@@ -366,10 +382,6 @@
#define STM32_OTGFS_DFIFO_DEP3 (STM32_OTGFS_BASE+STM32_OTGFS_DFIFO_DEP3_OFFSET)
#define STM32_OTGFS_DFIFO_HCH3 (STM32_OTGFS_BASE+STM32_OTGFS_DFIFO_HCH3_OFFSET)
-/* Power and clock gating registers */
-
-#define STM32_OTGFS_PCGCCTL (STM32_OTGFS_BASE+STM32_OTGFS_PCGCCTL_OFFSET)
-
/* Register Bitfield Definitions ********************************************************************/
/* Core global control and status registers */
@@ -411,7 +423,9 @@
#define OTGFS_GUSBCFG_TOCAL_SHIFT (0) /* Bits 0-2: FS timeout calibration */
#define OTGFS_GUSBCFG_TOCAL_MASK (7 << OTGFS_GUSBCFG_TOCAL_SHIFT)
- /* Bits 3-6: Reserved, must be kept at reset value */
+ /* Bits 3-5: Reserved, must be kept at reset value */
+#define OTGFS_GUSBCFG_PHYSEL (1 << 6) /* Bit 6: Full Speed serial transceiver select */
+ /* Bit 7: Reserved, must be kept at reset value */
#define OTGFS_GUSBCFG_SRPCAP (1 << 8) /* Bit 8: SRP-capable */
#define OTGFS_GUSBCFG_HNPCAP (1 << 9) /* Bit 9: HNP-capable */
#define OTGFS_GUSBCFG_TRDT_SHIFT (10) /* Bits 10-13: USB turnaround time */
@@ -491,7 +505,7 @@
#define OTGFS_GRXSTSH_PKTSTS_MASK (15 << OTGFS_GRXSTSH_PKTSTS_SHIFT)
# define OTGFS_GRXSTSH_PKTSTS_INRECVD (2 << OTGFS_GRXSTSH_PKTSTS_SHIFT) /* IN data packet received */
# define OTGFS_GRXSTSH_PKTSTS_INDONE (3 << OTGFS_GRXSTSH_PKTSTS_SHIFT) /* IN transfer completed */
-# define OTGFS_GRXSTSH_PKTSTS_DTOGERR (2 << OTGFS_GRXSTSH_PKTSTS_SHIFT) /* Data toggle error */
+# define OTGFS_GRXSTSH_PKTSTS_DTOGERR (5 << OTGFS_GRXSTSH_PKTSTS_SHIFT) /* Data toggle error */
# define OTGFS_GRXSTSH_PKTSTS_HALTED (7 << OTGFS_GRXSTSH_PKTSTS_SHIFT) /* Channel halted */
/* Bits 21-31: Reserved, must be kept at reset value */
/* Receive status debug read/OTG status read and pop registers (device mode) */
@@ -559,7 +573,7 @@
# define OTGFS_HNPTXSTS_EPNUM_SHIFT (27) /* Bits 27-30: Endpoint number */
# define OTGFS_HNPTXSTS_EPNUM_MASK (15 << OTGFS_HNPTXSTS_EPNUM_SHIFT)
/* Bit 31 Reserved, must be kept at reset value */
-/* general core configuration register */
+/* General core configuration register */
/* Bits 15:0 Reserved, must be kept at reset value */
#define OTGFS_GCCFG_PWRDWN (1 << 16) /* Bit 16: Power down */
/* Bit 17 Reserved, must be kept at reset value */
@@ -625,9 +639,11 @@
# define OTGFS_HPTXSTS_TYPE_HALT (3 << OTGFS_HPTXSTS_TYPE_SHIFT) /* Disable channel command */
# define OTGFS_HPTXSTS_EPNUM_SHIFT (27) /* Bits 27-30: Endpoint number */
# define OTGFS_HPTXSTS_EPNUM_MASK (15 << OTGFS_HPTXSTS_EPNUM_SHIFT)
+# define OTGFS_HPTXSTS_CHNUM_SHIFT (27) /* Bits 27-30: Channel number */
+# define OTGFS_HPTXSTS_CHNUM_MASK (15 << OTGFS_HPTXSTS_CHNUM_SHIFT)
# define OTGFS_HPTXSTS_ODD (1 << 24) /* Bit 31: Send in odd (vs even) frame */
-/* Host all channels interrupt and all channels interrupt mask registers */
+/* Host all channels interrupt and all channels interrupt mask registers */
#define OTGFS_HAINT(n) (1 << (n)) /* Bits 15:0 HAINTM: Channel interrupt */
@@ -664,7 +680,7 @@
/* Host channel-n characteristics register */
-#define OTGFS_HCCHAR0_MPSIZ_SHIFT (0) /* Bits 0-10: Maximum packet size */
+#define OTGFS_HCCHAR_MPSIZ_SHIFT (0) /* Bits 0-10: Maximum packet size */
#define OTGFS_HCCHAR_MPSIZ_MASK (0x7ff << OTGFS_HCCHAR_MPSIZ_SHIFT)
#define OTGFS_HCCHAR_EPNUM_SHIFT (11) /* Bits 11-14: Endpoint number */
#define OTGFS_HCCHAR_EPNUM_MASK (15 << OTGFS_HCCHAR_EPNUM_SHIFT)
@@ -695,7 +711,7 @@
#define OTGFS_HCINT_STALL (1 << 3) /* Bit 3: STALL response received interrupt */
#define OTGFS_HCINT_NAK (1 << 4) /* Bit 4: NAK response received interrupt */
#define OTGFS_HCINT_ACK (1 << 5) /* Bit 5: ACK response received/transmitted interrupt */
-#define OTGFS_HCINTMSK_NYET (1 << 6) /* Bit 6: response received interrupt mask */
+#define OTGFS_HCINT_NYET (1 << 6) /* Bit 6: Response received interrupt */
#define OTGFS_HCINT_TXERR (1 << 7) /* Bit 7: Transaction error */
#define OTGFS_HCINT_BBERR (1 << 8) /* Bit 8: Babble error */
#define OTGFS_HCINT_FRMOR (1 << 9) /* Bit 9: Frame overrun */
@@ -712,7 +728,8 @@
# define OTGFS_HCTSIZ_DPID_DATA0 (0 << OTGFS_HCTSIZ_DPID_SHIFT)
# define OTGFS_HCTSIZ_DPID_DATA2 (1 << OTGFS_HCTSIZ_DPID_SHIFT)
# define OTGFS_HCTSIZ_DPID_DATA1 (2 << OTGFS_HCTSIZ_DPID_SHIFT)
-# define OTGFS_HCTSIZ_DPID_MDATA (3 << OTGFS_HCTSIZ_DPID_SHIFT)
+# define OTGFS_HCTSIZ_DPID_MDATA (3 << OTGFS_HCTSIZ_DPID_SHIFT) /* Non-control */
+# define OTGFS_HCTSIZ_PID_SETUP (3 << OTGFS_HCTSIZ_DPID_SHIFT) /* Control */
/* Bit 31 Reserved, must be kept at reset value */
/* Device-mode control and status registers */
@@ -989,8 +1006,6 @@
# define OTGFS_DOEPTSIZ_RXDPID_DATA1 (2 << OTGFS_DOEPTSIZ_RXDPID_SHIFT)
# define OTGFS_DOEPTSIZ_RXDPID_MDATA (3 << OTGFS_DOEPTSIZ_RXDPID_SHIFT)
/* Bit 31: Reserved, must be kept at reset value */
-/* Power and clock gating registers */
-
/* Power and clock gating control register */
#define OTGFS_PCGCCTL_STPPCLK (1 << 0) /* Bit 0: Stop PHY clock */
diff --git a/nuttx/arch/arm/src/stm32/chip/stm32f20xxx_pinmap.h b/nuttx/arch/arm/src/stm32/chip/stm32f20xxx_pinmap.h
index 2c8587855..c59cd565a 100644
--- a/nuttx/arch/arm/src/stm32/chip/stm32f20xxx_pinmap.h
+++ b/nuttx/arch/arm/src/stm32/chip/stm32f20xxx_pinmap.h
@@ -365,7 +365,7 @@
#define GPIO_JTMS_SWDIO (GPIO_ALT|GPIO_AF0|GPIO_PORTA|GPIO_PIN13)
#define GPIO_JTRST (GPIO_ALT|GPIO_AF0|GPIO_PORTB|GPIO_PIN4)
-/* OTG FS/HS */
+/* OTG FS/HS (VBUS PA9 is not an alternate configuration) */
#define GPIO_OTGFS_DM (GPIO_ALT|GPIO_FLOAT|GPIO_AF10|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTA|GPIO_PIN11)
#define GPIO_OTGFS_DP (GPIO_ALT|GPIO_FLOAT|GPIO_AF10|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTA|GPIO_PIN12)
diff --git a/nuttx/arch/arm/src/stm32/chip/stm32f40xxx_pinmap.h b/nuttx/arch/arm/src/stm32/chip/stm32f40xxx_pinmap.h
index a588b56a2..ae2436a70 100644
--- a/nuttx/arch/arm/src/stm32/chip/stm32f40xxx_pinmap.h
+++ b/nuttx/arch/arm/src/stm32/chip/stm32f40xxx_pinmap.h
@@ -365,7 +365,7 @@
#define GPIO_JTMS_SWDIO (GPIO_ALT|GPIO_AF0|GPIO_PORTA|GPIO_PIN13)
#define GPIO_JTRST (GPIO_ALT|GPIO_AF0|GPIO_PORTB|GPIO_PIN4)
-/* OTG FS/HS */
+/* OTG FS/HS (VBUS PA9 is not an alternate configuration) */
#define GPIO_OTGFS_DM (GPIO_ALT|GPIO_FLOAT|GPIO_AF10|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTA|GPIO_PIN11)
#define GPIO_OTGFS_DP (GPIO_ALT|GPIO_FLOAT|GPIO_AF10|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTA|GPIO_PIN12)
diff --git a/nuttx/arch/arm/src/stm32/stm32_otgfsdev.c b/nuttx/arch/arm/src/stm32/stm32_otgfsdev.c
index 39c40d80a..81c919cdf 100644
--- a/nuttx/arch/arm/src/stm32/stm32_otgfsdev.c
+++ b/nuttx/arch/arm/src/stm32/stm32_otgfsdev.c
@@ -4086,7 +4086,7 @@ static void *stm32_ep_allocbuffer(FAR struct usbdev_ep_s *ep, unsigned bytes)
*
*******************************************************************************/
-#ifdef CONFIG_LPC313x_USBDEV_DMA
+#ifdef CONFIG_STM32_USBDEV_DMA
static void stm32_ep_freebuffer(FAR struct usbdev_ep_s *ep, FAR void *buf)
{
usbtrace(TRACE_EPFREEBUFFER, privep->epphy);
@@ -4645,7 +4645,6 @@ static int stm32_wakeup(struct usbdev_s *dev)
regval &= ~(OTGFS_PCGCCTL_STPPCLK | OTGFS_PCGCCTL_GATEHCLK);
stm32_putreg(regval, STM32_OTGFS_PCGCCTL);
#endif
-
/* Activate Remote wakeup signaling */
regval = stm32_getreg(STM32_OTGFS_DCTL);
@@ -4971,7 +4970,7 @@ static void stm32_hwinitialize(FAR struct stm32_usbdev_s *priv)
#ifndef CONFIG_USBDEV_VBUSSENSING
regval |= OTGFS_GCCFG_NOVBUSSENS;
#endif
-#ifdef CONFIG_USBDEV_SOFOUTPUT
+#ifdef CONFIG_STM32_OTGFS_SOFOUTPUT
regval |= OTGFS_GCCFG_SOFOUTEN;
#endif
stm32_putreg(regval, STM32_OTGFS_GCCFG);
@@ -5173,12 +5172,29 @@ void up_usbinitialize(void)
* current detection.
*/
- /* Configure OTG FS alternate function pins */
+ /* Configure OTG FS alternate function pins
+ *
+ * PIN* SIGNAL DIRECTION
+ * ---- ----------- ----------
+ * PA8 OTG_FS_SOF SOF clock output
+ * PA9 OTG_FS_VBUS VBUS input for device, Driven by external regulator by
+ * host (not an alternate function)
+ * PA10 OTG_FS_ID OTG ID pin (only needed in Dual mode)
+ * PA11 OTG_FS_DM D- I/O
+ * PA12 OTG_FS_DP D+ I/O
+ *
+ * *Pins may vary from device-to-device.
+ */
stm32_configgpio(GPIO_OTGFS_DM);
stm32_configgpio(GPIO_OTGFS_DP);
- stm32_configgpio(GPIO_OTGFS_ID);
+ stm32_configgpio(GPIO_OTGFS_ID); /* Only needed for OTG */
+
+ /* SOF output pin configuration is configurable. */
+
+#ifdef CONFIG_STM32_OTGFS_SOFOUTPUT
stm32_configgpio(GPIO_OTGFS_SOF);
+#endif
/* Uninitialize the hardware so that we know that we are starting from a
* known state. */
diff --git a/nuttx/arch/arm/src/stm32/stm32_otgfshost.c b/nuttx/arch/arm/src/stm32/stm32_otgfshost.c
new file mode 100644
index 000000000..0b09070dc
--- /dev/null
+++ b/nuttx/arch/arm/src/stm32/stm32_otgfshost.c
@@ -0,0 +1,4095 @@
+/*******************************************************************************
+ * arch/arm/src/stm32/stm32_otgfshost.c
+ *
+ * Copyright (C) 2012 Gregory Nutt. All rights reserved.
+ * Authors: 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>
+
+#include <sys/types.h>
+#include <stdint.h>
+#include <stdbool.h>
+#include <stdlib.h>
+#include <semaphore.h>
+#include <string.h>
+#include <errno.h>
+#include <debug.h>
+
+#include <nuttx/arch.h>
+#include <nuttx/kmalloc.h>
+#include <nuttx/usb/usb.h>
+#include <nuttx/usb/usbhost.h>
+
+#include <arch/irq.h>
+
+#include "chip.h" /* Includes default GPIO settings */
+#include <arch/board/board.h> /* May redefine GPIO settings */
+
+#include "up_arch.h"
+#include "up_internal.h"
+
+#include "stm32_usbhost.h"
+
+#if defined(CONFIG_USBHOST) && defined(CONFIG_STM32_OTGFS)
+
+/*******************************************************************************
+ * Definitions
+ *******************************************************************************/
+/* Configuration ***************************************************************/
+/*
+ * STM32 USB OTG FS Host Driver Support
+ *
+ * Pre-requisites
+ *
+ * CONFIG_USBHOST - Enable general USB host support
+ * CONFIG_STM32_OTGFS - Enable the STM32 USB OTG FS block
+ * CONFIG_STM32_SYSCFG - Needed
+ *
+ * Options:
+ *
+ * CONFIG_STM32_OTGFS_RXFIFO_SIZE - Size of the RX FIFO in 32-bit words.
+ * Default 128 (512 bytes)
+ * CONFIG_STM32_OTGFS_NPTXFIFO_SIZE - Size of the non-periodic Tx FIFO
+ * in 32-bit words. Default 96 (384 bytes)
+ * CONFIG_STM32_OTGFS_PTXFIFO_SIZE - Size of the periodic Tx FIFO in 32-bit
+ * words. Default 96 (384 bytes)
+ * CONFIG_STM32_OTGFS_DESCSIZE - Maximum size of a descriptor. Default: 128
+ * CONFIG_STM32_OTGFS_SOFINTR - Enable SOF interrupts. Why would you ever
+ * want to do that?
+ * CONFIG_STM32_USBHOST_REGDEBUG - Enable very low-level register access
+ * debug. Depends on CONFIG_DEBUG.
+ * CONFIG_STM32_USBHOST_PKTDUMP - Dump all incoming and outgoing USB
+ * packets. Depends on CONFIG_DEBUG.
+ */
+
+/* Pre-requistites (partial) */
+
+#ifndef CONFIG_STM32_SYSCFG
+# error "CONFIG_STM32_SYSCFG is required"
+#endif
+
+/* Default RxFIFO size */
+
+#ifndef CONFIG_STM32_OTGFS_RXFIFO_SIZE
+# define CONFIG_STM32_OTGFS_RXFIFO_SIZE 128
+#endif
+
+/* Default host non-periodic Tx FIFO size */
+
+#ifndef CONFIG_STM32_OTGFS_NPTXFIFO_SIZE
+# define CONFIG_STM32_OTGFS_NPTXFIFO_SIZE 96
+#endif
+
+/* Default host periodic Tx fifo size register */
+
+#ifndef CONFIG_STM32_OTGFS_PTXFIFO_SIZE
+# define CONFIG_STM32_OTGFS_PTXFIFO_SIZE 96
+#endif
+
+/* Maximum size of a descriptor */
+
+#ifndef CONFIG_STM32_OTGFS_DESCSIZE
+# define CONFIG_STM32_OTGFS_DESCSIZE 128
+#endif
+
+/* Register/packet debug depends on CONFIG_DEBUG */
+
+#ifndef CONFIG_DEBUG
+# undef CONFIG_STM32_USBHOST_REGDEBUG
+# undef CONFIG_STM32_USBHOST_PKTDUMP
+#endif
+
+/* HCD Setup *******************************************************************/
+/* Hardware capabilities */
+
+#define STM32_NHOST_CHANNELS 8 /* Number of host channels */
+#define STM32_MAX_PACKET_SIZE 64 /* Full speed max packet size */
+#define STM32_EP0_DEF_PACKET_SIZE 8 /* EP0 default packet size */
+#define STM32_EP0_MAX_PACKET_SIZE 64 /* EP0 FS max packet size */
+#define STM32_MAX_TX_FIFOS 15 /* Max number of TX FIFOs */
+#define STM32_MAX_PKTCOUNT 256 /* Max packet count */
+#define STM32_RETRY_COUNT 3 /* Number of retries */
+#define STM32_DEF_DEVADDR 0 /* Default device address */
+
+/* Delays **********************************************************************/
+
+#define STM32_READY_DELAY 200000 /* In loop counts */
+#define STM32_FLUSH_DELAY 200000 /* In loop counts */
+#define STM32_NOTREADY_DELAY 5000 /* In frames */
+
+/* Ever-present MIN/MAX macros */
+
+#ifndef MIN
+# define MIN(a, b) (((a) < (b)) ? (a) : (b))
+#endif
+
+#ifndef MAX
+# define MAX(a, b) (((a) > (b)) ? (a) : (b))
+#endif
+
+/*******************************************************************************
+ * Private Types
+ *******************************************************************************/
+
+/* The following enumeration represents the various states of the USB host
+ * state machine (for debug purposes only)
+ */
+
+enum stm32_smstate_e
+{
+ SMSTATE_DETACHED = 0, /* Not attached to a device */
+ SMSTATE_ATTACHED, /* Attached to a device */
+ SMSTATE_ENUM, /* Attached, enumerating */
+ SMSTATE_CLASS_BOUND, /* Enumeration complete, class bound */
+};
+
+/* This enumeration provides the reason for the channel halt. */
+
+enum stm32_chreason_e
+{
+ CHREASON_IDLE = 0, /* Inactive (initial state) */
+ CHREASON_FREED, /* Channel is no longer in use */
+ CHREASON_XFRC, /* Transfer complete */
+ CHREASON_NAK, /* NAK received */
+ CHREASON_NYET, /* NotYet received */
+ CHREASON_STALL, /* Endpoint stalled */
+ CHREASON_TXERR, /* Transfer error received */
+ CHREASON_DTERR, /* Data toggle error received */
+ CHREASON_FRMOR /* Frame overrun */
+};
+
+/* This structure retains the state of one host channel. NOTE: Since there
+ * is only one channel operation active at a time, some of the fields in
+ * in the structure could be moved in struct stm32_ubhost_s to achieve
+ * some memory savings.
+ */
+
+struct stm32_chan_s
+{
+ sem_t waitsem; /* Channel wait semaphore */
+ volatile uint8_t result; /* The result of the transfer */
+ volatile uint8_t chreason; /* Channel halt reason. See enum stm32_chreason_e */
+ uint8_t epno; /* Device endpoint number (0-127) */
+ uint8_t eptype; /* See OTGFS_EPTYPE_* definitions */
+ uint8_t pid; /* Data PID */
+ uint8_t npackets; /* Number of packets (for data toggle) */
+ bool inuse; /* True: This channel is "in use" */
+ volatile bool indata1; /* IN data toggle. True: DATA01 (Bulk and INTR only) */
+ volatile bool outdata1; /* OUT data toggle. True: DATA01 */
+ bool in; /* True: IN endpoint */
+ volatile bool waiter; /* True: Thread is waiting for a channel event */
+ uint16_t maxpacket; /* Max packet size */
+ volatile uint16_t buflen; /* Buffer length (remaining) */
+ volatile uint16_t inflight; /* Number of Tx bytes "in-flight" */
+ FAR uint8_t *buffer; /* Transfer buffer pointer */
+};
+
+/* This structure retains the state of the USB host controller */
+
+struct stm32_usbhost_s
+{
+ /* Common device fields. This must be the first thing defined in the
+ * structure so that it is possible to simply cast from struct usbhost_s
+ * to structstm32_usbhost_s.
+ */
+
+ struct usbhost_driver_s drvr;
+
+ /* The bound device class driver */
+
+ struct usbhost_class_s *class;
+
+ /* Overall driver status */
+
+ volatile uint8_t smstate; /* The state of the USB host state machine */
+ uint8_t devaddr; /* Device address */
+ uint8_t ep0in; /* EP0 IN control channel index */
+ uint8_t ep0out; /* EP0 OUT control channel index */
+ uint8_t ep0size; /* EP0 max packet size */
+ uint8_t chidx; /* ID of channel waiting for space in Tx FIFO */
+ bool lowspeed; /* True: low speed device */
+ volatile bool connected; /* Connected to device */
+ volatile bool eventwait; /* True: Thread is waiting for a port event */
+ sem_t exclsem; /* Support mutually exclusive access */
+ sem_t eventsem; /* Semaphore to wait for a port event */
+
+ /* The state of each host channel */
+
+ struct stm32_chan_s chan[STM32_MAX_TX_FIFOS];
+};
+
+/*******************************************************************************
+ * Private Function Prototypes
+ *******************************************************************************/
+
+/* Register operations ********************************************************/
+
+#ifdef CONFIG_STM32_USBHOST_REGDEBUG
+static void stm32_printreg(uint32_t addr, uint32_t val, bool iswrite);
+static void stm32_checkreg(uint32_t addr, uint32_t val, bool iswrite);
+static uint32_t stm32_getreg(uint32_t addr);
+static void stm32_putreg(uint32_t addr, uint32_t value);
+#else
+# define stm32_getreg(addr) getreg32(addr)
+# define stm32_putreg(addr,val) putreg32(val,addr)
+#endif
+
+static inline void stm32_modifyreg(uint32_t addr, uint32_t clrbits,
+ uint32_t setbits);
+
+#ifdef CONFIG_STM32_USBHOST_PKTDUMP
+# define stm32_pktdump(m,b,n) lib_dumpbuffer(m,b,n)
+#else
+# define stm32_pktdump(m,b,n)
+#endif
+
+/* Semaphores ******************************************************************/
+
+static void stm32_takesem(sem_t *sem);
+#define stm32_givesem(s) sem_post(s);
+
+/* Byte stream access helper functions *****************************************/
+
+static inline uint16_t stm32_getle16(const uint8_t *val);
+
+/* Channel management **********************************************************/
+
+static int stm32_chan_alloc(FAR struct stm32_usbhost_s *priv);
+static inline void stm32_chan_free(FAR struct stm32_usbhost_s *priv, int chidx);
+static inline void stm32_chan_freeall(FAR struct stm32_usbhost_s *priv);
+static void stm32_chan_configure(FAR struct stm32_usbhost_s *priv, int chidx);
+static void stm32_chan_halt(FAR struct stm32_usbhost_s *priv, int chidx,
+ enum stm32_chreason_e chreason);
+static int stm32_chan_waitsetup(FAR struct stm32_usbhost_s *priv,
+ FAR struct stm32_chan_s *chan);
+static int stm32_chan_wait(FAR struct stm32_usbhost_s *priv,
+ FAR struct stm32_chan_s *chan);
+static void stm32_chan_wakeup(FAR struct stm32_usbhost_s *priv,
+ FAR struct stm32_chan_s *chan);
+
+/* Control/data transfer logic *************************************************/
+
+static void stm32_transfer_start(FAR struct stm32_usbhost_s *priv, int chidx);
+static inline uint16_t stm32_getframe(void);
+static int stm32_ctrl_sendsetup(FAR struct stm32_usbhost_s *priv,
+ FAR const struct usb_ctrlreq_s *req);
+static int stm32_ctrl_senddata(FAR struct stm32_usbhost_s *priv,
+ FAR uint8_t *buffer, unsigned int buflen);
+static int stm32_ctrl_recvdata(FAR struct stm32_usbhost_s *priv,
+ FAR uint8_t *buffer, unsigned int buflen);
+
+/* Interrupt handling **********************************************************/
+/* Lower level interrupt handlers */
+
+static void stm32_gint_wrpacket(FAR struct stm32_usbhost_s *priv,
+ FAR uint8_t *buffer, int chidx, int buflen);
+static inline void stm32_gint_hcinisr(FAR struct stm32_usbhost_s *priv,
+ int chidx);
+static inline void stm32_gint_hcoutisr(FAR struct stm32_usbhost_s *priv,
+ int chidx);
+static void stm32_gint_connected(FAR struct stm32_usbhost_s *priv);
+static void stm32_gint_disconnected(FAR struct stm32_usbhost_s *priv);
+
+/* Second level interrupt handlers */
+
+#ifdef CONFIG_STM32_OTGFS_SOFINTR
+static inline void stm32_gint_sofisr(FAR struct stm32_usbhost_s *priv);
+#endif
+static inline void stm32_gint_rxflvlisr(FAR struct stm32_usbhost_s *priv);
+static inline void stm32_gint_nptxfeisr(FAR struct stm32_usbhost_s *priv);
+static inline void stm32_gint_ptxfeisr(FAR struct stm32_usbhost_s *priv);
+static inline void stm32_gint_hcisr(FAR struct stm32_usbhost_s *priv);
+static inline void stm32_gint_hprtisr(FAR struct stm32_usbhost_s *priv);
+static inline void stm32_gint_discisr(FAR struct stm32_usbhost_s *priv);
+static inline void stm32_gint_iisooxfrisr(FAR struct stm32_usbhost_s *priv);
+
+/* First level, global interrupt handler */
+
+static int stm32_gint_isr(int irq, FAR void *context);
+
+/* Interrupt controls */
+
+static void stm32_gint_enable(void);
+static void stm32_gint_disable(void);
+static inline void stm32_hostinit_enable(void);
+static void stm32_txfe_enable(FAR struct stm32_usbhost_s *priv, int chidx);
+
+/* USB host controller operations **********************************************/
+
+static int stm32_wait(FAR struct usbhost_driver_s *drvr, bool connected);
+static int stm32_enumerate(FAR struct usbhost_driver_s *drvr);
+static int stm32_ep0configure(FAR struct usbhost_driver_s *drvr, uint8_t funcaddr,
+ uint16_t maxpacketsize);
+static int stm32_epalloc(FAR struct usbhost_driver_s *drvr,
+ FAR const FAR struct usbhost_epdesc_s *epdesc,
+ FAR usbhost_ep_t *ep);
+static int stm32_epfree(FAR struct usbhost_driver_s *drvr, usbhost_ep_t ep);
+static int stm32_alloc(FAR struct usbhost_driver_s *drvr,
+ FAR uint8_t **buffer, FAR size_t *maxlen);
+static int stm32_free(FAR struct usbhost_driver_s *drvr, FAR uint8_t *buffer);
+static int stm32_ioalloc(FAR struct usbhost_driver_s *drvr,
+ FAR uint8_t **buffer, size_t buflen);
+static int stm32_iofree(FAR struct usbhost_driver_s *drvr, FAR uint8_t *buffer);
+static int stm32_ctrlin(FAR struct usbhost_driver_s *drvr,
+ FAR const struct usb_ctrlreq_s *req,
+ FAR uint8_t *buffer);
+static int stm32_ctrlout(FAR struct usbhost_driver_s *drvr,
+ FAR const struct usb_ctrlreq_s *req,
+ FAR const uint8_t *buffer);
+static int stm32_transfer(FAR struct usbhost_driver_s *drvr, usbhost_ep_t ep,
+ FAR uint8_t *buffer, size_t buflen);
+static void stm32_disconnect(FAR struct usbhost_driver_s *drvr);
+
+/* Initialization **************************************************************/
+
+static void stm32_portreset(FAR struct stm32_usbhost_s *priv);
+static inline void stm32_flush_txfifos(uint32_t txfnum);
+static inline void stm32_flush_rxfifo(void);
+static void stm32_vbusdrive(FAR struct stm32_usbhost_s *priv, bool state);
+static void stm32_host_initialize(FAR struct stm32_usbhost_s *priv);
+static inline void stm32_sw_initialize(FAR struct stm32_usbhost_s *priv);
+static inline int stm32_hw_initialize(FAR struct stm32_usbhost_s *priv);
+
+/*******************************************************************************
+ * Private Data
+ *******************************************************************************/
+
+/* In this driver implementation, support is provided for only a single a single
+ * USB device. All status information can be simply retained in a single global
+ * instance.
+ */
+
+static struct stm32_usbhost_s g_usbhost =
+{
+ .drvr =
+ {
+ .wait = stm32_wait,
+ .enumerate = stm32_enumerate,
+ .ep0configure = stm32_ep0configure,
+ .epalloc = stm32_epalloc,
+ .epfree = stm32_epfree,
+ .alloc = stm32_alloc,
+ .free = stm32_free,
+ .ioalloc = stm32_ioalloc,
+ .iofree = stm32_iofree,
+ .ctrlin = stm32_ctrlin,
+ .ctrlout = stm32_ctrlout,
+ .transfer = stm32_transfer,
+ .disconnect = stm32_disconnect,
+ },
+ .class = NULL,
+};
+
+/*******************************************************************************
+ * Public Data
+ *******************************************************************************/
+
+/*******************************************************************************
+ * Private Functions
+ *******************************************************************************/
+
+/*******************************************************************************
+ * Name: stm32_printreg
+ *
+ * Description:
+ * Print the contents of an STM32xx register operation
+ *
+ *******************************************************************************/
+
+#ifdef CONFIG_STM32_USBHOST_REGDEBUG
+static void stm32_printreg(uint32_t addr, uint32_t val, bool iswrite)
+{
+ lldbg("%08x%s%08x\n", addr, iswrite ? "<-" : "->", val);
+}
+#endif
+
+/*******************************************************************************
+ * Name: stm32_checkreg
+ *
+ * Description:
+ * Get the contents of an STM32 register
+ *
+ *******************************************************************************/
+
+#ifdef CONFIG_STM32_USBHOST_REGDEBUG
+static void stm32_checkreg(uint32_t addr, uint32_t val, bool iswrite)
+{
+ static uint32_t prevaddr = 0;
+ static uint32_t preval = 0;
+ static uint32_t count = 0;
+ static bool prevwrite = false;
+
+ /* Is this the same value that we read from/wrote to the same register last time?
+ * Are we polling the register? If so, suppress the output.
+ */
+
+ if (addr == prevaddr && val == preval && prevwrite == iswrite)
+ {
+ /* Yes.. Just increment the count */
+
+ count++;
+ }
+ else
+ {
+ /* No this is a new address or value or operation. Were there any
+ * duplicate accesses before this one?
+ */
+
+ if (count > 0)
+ {
+ /* Yes.. Just one? */
+
+ if (count == 1)
+ {
+ /* Yes.. Just one */
+
+ stm32_printreg(prevaddr, preval, prevwrite);
+ }
+ else
+ {
+ /* No.. More than one. */
+
+ lldbg("[repeats %d more times]\n", count);
+ }
+ }
+
+ /* Save the new address, value, count, and operation for next time */
+
+ prevaddr = addr;
+ preval = val;
+ count = 0;
+ prevwrite = iswrite;
+
+ /* Show the new regisgter access */
+
+ stm32_printreg(addr, val, iswrite);
+ }
+}
+#endif
+
+/*******************************************************************************
+ * Name: stm32_getreg
+ *
+ * Description:
+ * Get the contents of an STM32 register
+ *
+ *******************************************************************************/
+
+#ifdef CONFIG_STM32_USBHOST_REGDEBUG
+static uint32_t stm32_getreg(uint32_t addr)
+{
+ /* Read the value from the register */
+
+ uint32_t val = getreg32(addr);
+
+ /* Check if we need to print this value */
+
+ stm32_checkreg(addr, val, false);
+ return val;
+}
+#endif
+
+/*******************************************************************************
+ * Name: stm32_putreg
+ *
+ * Description:
+ * Set the contents of an STM32 register to a value
+ *
+ *******************************************************************************/
+
+#ifdef CONFIG_STM32_USBHOST_REGDEBUG
+static void stm32_putreg(uint32_t addr, uint32_t val)
+{
+ /* Check if we need to print this value */
+
+ stm32_checkreg(addr, val, true);
+
+ /* Write the value */
+
+ putreg32(val, addr);
+}
+#endif
+
+/*******************************************************************************
+ * Name: stm32_modifyreg
+ *
+ * Description:
+ * Modify selected bits of an STM32 register.
+ *
+ *******************************************************************************/
+
+static inline void stm32_modifyreg(uint32_t addr, uint32_t clrbits, uint32_t setbits)
+{
+ stm32_putreg(addr, (((stm32_getreg(addr)) & ~clrbits) | setbits));
+}
+
+/****************************************************************************
+ * Name: stm32_takesem
+ *
+ * Description:
+ * This is just a wrapper to handle the annoying behavior of semaphore
+ * waits that return due to the receipt of a signal.
+ *
+ *******************************************************************************/
+
+static void stm32_takesem(sem_t *sem)
+{
+ /* Take the semaphore (perhaps waiting) */
+
+ while (sem_wait(sem) != 0)
+ {
+ /* The only case that an error should occr here is if the wait was
+ * awakened by a signal.
+ */
+
+ ASSERT(errno == EINTR);
+ }
+}
+
+/****************************************************************************
+ * Name: stm32_getle16
+ *
+ * Description:
+ * Get a (possibly unaligned) 16-bit little endian value.
+ *
+ *******************************************************************************/
+
+static inline uint16_t stm32_getle16(const uint8_t *val)
+{
+ return (uint16_t)val[1] << 8 | (uint16_t)val[0];
+}
+
+/*******************************************************************************
+ * Name: stm32_chan_alloc
+ *
+ * Description:
+ * Allocate a channel.
+ *
+ *******************************************************************************/
+
+static int stm32_chan_alloc(FAR struct stm32_usbhost_s *priv)
+{
+ int chidx;
+
+ /* Search the table of channels */
+
+ for (chidx = 0 ; chidx < STM32_NHOST_CHANNELS ; chidx++)
+ {
+ /* Is this channel available? */
+
+ if (!priv->chan[chidx].inuse)
+ {
+ /* Yes... make it "in use" and return the index */
+
+ priv->chan[chidx].inuse = true;
+ return chidx;
+ }
+ }
+
+ /* All of the channels are "in-use" */
+
+ return -EBUSY;
+}
+
+/*******************************************************************************
+ * Name: stm32_chan_free
+ *
+ * Description:
+ * Free a previoiusly allocated channel.
+ *
+ *******************************************************************************/
+
+static void stm32_chan_free(FAR struct stm32_usbhost_s *priv, int chidx)
+{
+ DEBUGASSERT((unsigned)chidx < STM32_NHOST_CHANNELS);
+
+ /* Halt the channel */
+
+ stm32_chan_halt(priv, chidx, CHREASON_FREED);
+
+ /* Mark the channel available */
+
+ priv->chan[chidx].inuse = false;
+}
+
+/*******************************************************************************
+ * Name: stm32_chan_freeall
+ *
+ * Description:
+ * Free all channels.
+ *
+ *******************************************************************************/
+
+static inline void stm32_chan_freeall(FAR struct stm32_usbhost_s *priv)
+{
+ uint8_t chidx;
+
+ /* Free all host channels */
+
+ for (chidx = 2; chidx < STM32_NHOST_CHANNELS ; chidx ++)
+ {
+ stm32_chan_free(priv, chidx);
+ }
+}
+
+/*******************************************************************************
+ * Name: stm32_chan_configure
+ *
+ * Description:
+ * Configure or re-configure a host channel. Host channels are configured
+ * when endpoint is allocated and EP0 (only) is re-configured with the
+ * max packet size or device address changes.
+ *
+ *******************************************************************************/
+
+static void stm32_chan_configure(FAR struct stm32_usbhost_s *priv, int chidx)
+{
+ uint32_t regval;
+
+ /* Clear any old pending interrupts for this host channel. */
+
+ stm32_putreg(STM32_OTGFS_HCINT(chidx), 0xffffffff);
+
+ /* Enable channel interrupts required for transfers on this channel. */
+
+ regval = 0;
+
+ switch (priv->chan[chidx].eptype)
+ {
+ case OTGFS_EPTYPE_CTRL:
+ case OTGFS_EPTYPE_BULK:
+ {
+ /* Interrupts required for CTRL and BULK endpoints */
+
+ regval |= (OTGFS_HCINT_XFRC | OTGFS_HCINT_STALL | OTGFS_HCINT_NAK |
+ OTGFS_HCINT_TXERR | OTGFS_HCINT_DTERR);
+
+ /* Additional setting for IN/OUT endpoints */
+
+ if (priv->chan[chidx].in)
+ {
+ regval |= OTGFS_HCINT_BBERR;
+ }
+ else
+ {
+ regval |= OTGFS_HCINT_NYET;
+ }
+ }
+ break;
+
+ case OTGFS_EPTYPE_INTR:
+ {
+ /* Interrupts required for INTR endpoints */
+
+ regval |= (OTGFS_HCINT_XFRC | OTGFS_HCINT_STALL | OTGFS_HCINT_NAK |
+ OTGFS_HCINT_TXERR | OTGFS_HCINT_FRMOR | OTGFS_HCINT_DTERR);
+
+ /* Additional setting for IN endpoints */
+
+ if (priv->chan[chidx].in)
+ {
+ regval |= OTGFS_HCINT_BBERR;
+ }
+ }
+ break;
+
+ case OTGFS_EPTYPE_ISOC:
+ {
+ /* Interrupts required for ISOC endpoints */
+
+ regval |= (OTGFS_HCINT_XFRC | OTGFS_HCINT_ACK | OTGFS_HCINT_FRMOR);
+
+ /* Additional setting for IN endpoints */
+
+ if (priv->chan[chidx].in)
+ {
+ regval |= (OTGFS_HCINT_TXERR | OTGFS_HCINT_BBERR);
+ }
+ }
+ break;
+ }
+
+ stm32_putreg(STM32_OTGFS_HCINTMSK(chidx), regval);
+
+ /* Enable the top level host channel interrupt. */
+
+ stm32_modifyreg(STM32_OTGFS_HAINTMSK, 0, OTGFS_HAINT(chidx));
+
+ /* Make sure host channel interrupts are enabled. */
+
+ stm32_modifyreg(STM32_OTGFS_GINTMSK, 0, OTGFS_GINT_HC);
+
+ /* Program the HCCHAR register */
+
+ regval = ((uint32_t)priv->chan[chidx].maxpacket << OTGFS_HCCHAR_MPSIZ_SHIFT) |
+ ((uint32_t)priv->chan[chidx].epno << OTGFS_HCCHAR_EPNUM_SHIFT) |
+ ((uint32_t)priv->chan[chidx].eptype << OTGFS_HCCHAR_EPTYP_SHIFT) |
+ ((uint32_t)priv->devaddr << OTGFS_HCCHAR_DAD_SHIFT);
+
+ /* Special case settings for low speed devices */
+
+ if (priv->lowspeed)
+ {
+ regval |= OTGFS_HCCHAR_LSDEV;
+ }
+
+ /* Special case settings for IN endpoints */
+
+ if (priv->chan[chidx].in)
+ {
+ regval |= OTGFS_HCCHAR_EPDIR_IN;
+ }
+
+ /* Special case settings for INTR endpoints */
+
+ if (priv->chan[chidx].eptype == OTGFS_EPTYPE_INTR)
+ {
+ regval |= OTGFS_HCCHAR_ODDFRM;
+ }
+
+ /* Write the channel configuration */
+
+ stm32_putreg(STM32_OTGFS_HCCHAR(chidx), regval);
+}
+
+/*******************************************************************************
+ * Name: stm32_chan_halt
+ *
+ * Description:
+ * Halt the channel associated with 'chidx' by setting the CHannel DISable
+ * (CHDIS) bit in in the HCCHAR register.
+ *
+ *******************************************************************************/
+
+static void stm32_chan_halt(FAR struct stm32_usbhost_s *priv, int chidx,
+ enum stm32_chreason_e chreason)
+{
+ uint32_t hcchar;
+ uint32_t intmsk;
+ uint32_t eptype;
+ unsigned int avail;
+
+ /* Save the recon for the halt. We need this in the channel halt interrrupt
+ * handling logic to know what to do next.
+ */
+
+ priv->chan[chidx].chreason = (uint8_t)chreason;
+
+ /* "The application can disable any channel by programming the OTG_FS_HCCHARx
+ * register with the CHDIS and CHENA bits set to 1. This enables the OTG_FS
+ * host to flush the posted requests (if any) and generates a channel halted
+ * interrupt. The application must wait for the CHH interrupt in OTG_FS_HCINTx
+ * before reallocating the channel for other transactions. The OTG_FS host
+ * does not interrupt the transaction that has already been started on the
+ * USB."
+ */
+
+ hcchar = stm32_getreg(STM32_OTGFS_HCCHAR(chidx));
+ hcchar |= (OTGFS_HCCHAR_CHDIS | OTGFS_HCCHAR_CHENA);
+
+ /* Get the endpoint type from the HCCHAR register */
+
+ eptype = hcchar & OTGFS_HCCHAR_EPTYP_MASK;
+
+ /* Check for space in the Tx FIFO to issue the halt.
+ *
+ * "Before disabling a channel, the application must ensure that there is at
+ * least one free space available in the non-periodic request queue (when
+ * disabling a non-periodic channel) or the periodic request queue (when
+ * disabling a periodic channel). The application can simply flush the
+ * posted requests when the Request queue is full (before disabling the
+ * channel), by programming the OTG_FS_HCCHARx register with the CHDIS bit
+ * set to 1, and the CHENA bit cleared to 0.
+ */
+
+ if (eptype == OTGFS_HCCHAR_EPTYP_CTRL || eptype == OTGFS_HCCHAR_EPTYP_BULK)
+ {
+ /* Get the number of words available in the non-periodic Tx FIFO. */
+
+ avail = stm32_getreg(STM32_OTGFS_HNPTXSTS) & OTGFS_HNPTXSTS_NPTXFSAV_MASK;
+ }
+ else /* if (eptype == OTGFS_HCCHAR_EPTYP_ISOC || eptype == OTGFS_HCCHAR_EPTYP_INTR) */
+ {
+ /* Get the number of words available in the non-periodic Tx FIFO. */
+
+ avail = stm32_getreg(STM32_OTGFS_HPTXSTS) & OTGFS_HPTXSTS_PTXFSAVL_MASK;
+ }
+
+ /* Check if there is any space available in the Tx FIFO. */
+
+ if (avail == 0)
+ {
+ /* The Tx FIFO is full... disable the channel to flush the requests */
+
+ hcchar &= ~OTGFS_HCCHAR_CHENA;
+ }
+
+ /* Unmask the CHannel Halted (CHH) interrupt */
+
+ intmsk = stm32_getreg(STM32_OTGFS_HCINTMSK(chidx));
+ intmsk |= OTGFS_HCINT_CHH;
+ stm32_putreg(STM32_OTGFS_HCINTMSK(chidx), intmsk);
+
+ /* Halt the channel by setting CHDIS (and maybe CHENA) in the HCCHAR */
+
+ stm32_putreg(STM32_OTGFS_HCCHAR(chidx), hcchar);
+}
+
+/*******************************************************************************
+ * Name: stm32_chan_waitsetup
+ *
+ * Description:
+ * Set the request for the transfer complete event well BEFORE enabling the
+ * transfer (as soon as we are absolutely committed to the to avoid transfer).
+ * We do this to minimize race conditions. This logic would have to be expanded
+ * if we want to have more than one packet in flight at a time!
+ *
+ * Assumptions:
+ * Called from a normal thread context BEFORE the transfer has been started.
+ *
+ *******************************************************************************/
+
+static int stm32_chan_waitsetup(FAR struct stm32_usbhost_s *priv,
+ FAR struct stm32_chan_s *chan)
+{
+ irqstate_t flags = irqsave();
+ int ret = -ENODEV;
+
+ /* Is the device still connected? */
+
+ if (priv->connected)
+ {
+ /* Yes.. then set waiter to indicate that we expect to be informed when
+ * either (1) the device is disconnected, or (2) the transfer completed.
+ */
+
+ chan->waiter = true;
+ ret = OK;
+ }
+
+ irqrestore(flags);
+ return ret;
+}
+
+/*******************************************************************************
+ * Name: stm32_chan_wait
+ *
+ * Description:
+ * Wait for a transfer on a channel to complete.
+ *
+ * Assumptions:
+ * Called from a normal thread context
+ *
+ *******************************************************************************/
+
+static int stm32_chan_wait(FAR struct stm32_usbhost_s *priv,
+ FAR struct stm32_chan_s *chan)
+{
+ irqstate_t flags;
+ int ret;
+
+ /* Disable interrupts so that the following operations will be atomic. On
+ * the OTG FS global interrupt needs to be disabled. However, here we disable
+ * all interrupts to exploit that fact that interrupts will be re-enabled
+ * while we wait.
+ */
+
+ flags = irqsave();
+
+ /* Loop, testing for an end of transfer conditino. The channel 'result'
+ * was set to EBUSY and 'waiter' was set to true before the transfer; 'waiter'
+ * will be set to false and 'result' will be set appropriately when the
+ * tranfer is completed.
+ */
+
+ do
+ {
+ /* Wait for the transfer to complete. NOTE the transfer may already
+ * completed before we get here or the transfer may complete while we
+ * wait here.
+ */
+
+ ret = sem_wait(&chan->waitsem);
+
+ /* sem_wait should succeeed. But it is possible that we could be
+ * awakened by a signal too.
+ */
+
+ DEBUGASSERT(ret == OK || get_errno() == EINTR);
+ }
+ while (chan->waiter);
+
+ /* The transfer is complete re-enable interrupts and return the result */
+
+ ret = -(int)chan->result;
+ irqrestore(flags);
+ return ret;
+}
+
+/*******************************************************************************
+ * Name: stm32_chan_wakeup
+ *
+ * Description:
+ * A channel transfer has completed... wakeup any threads waiting for the
+ * transfer to complete.
+ *
+ * Assumptions:
+ * This function is called from the transfer complete interrupt handler for
+ * the channel. Interrupts are disabled.
+ *
+ *******************************************************************************/
+
+static void stm32_chan_wakeup(FAR struct stm32_usbhost_s *priv,
+ FAR struct stm32_chan_s *chan)
+{
+ /* Is the the transfer complete? Is there a thread waiting for this transfer
+ * to complete?
+ */
+
+ if (chan->result != EBUSY && chan->waiter)
+ {
+ ullvdbg("Wakeup with result: %d\n", chan->result);
+ stm32_givesem(&chan->waitsem);
+ chan->waiter = false;
+ }
+}
+
+/*******************************************************************************
+ * Name: stm32_transfer_start
+ *
+ * Description:
+ * Start at transfer on the select IN or OUT channel.
+ *
+ *******************************************************************************/
+
+static void stm32_transfer_start(FAR struct stm32_usbhost_s *priv, int chidx)
+{
+ FAR struct stm32_chan_s *chan;
+ uint32_t regval;
+ unsigned int npackets;
+ unsigned int maxpacket;
+ unsigned int avail;
+ unsigned int wrsize;
+ unsigned int minsize;
+
+ /* Set up the initial state of the transfer */
+
+ chan = &priv->chan[chidx];
+ uvdbg("chidx: %d buflen: %d\n", chidx, chan->buflen);
+
+ chan->result = EBUSY;
+ chan->inflight = 0;
+ priv->chidx = chidx;
+
+ /* Compute the expected number of packets associated to the transfer.
+ * If the transfer length is zero (or less than the size of one maximum
+ * size packet), then one packet is expected.
+ */
+
+ /* If the transfer size is greater than one packet, then calculate the
+ * number of packets that will be received/sent, including any partial
+ * final packet.
+ */
+
+ maxpacket = chan->maxpacket;
+
+ if (chan->buflen > maxpacket)
+ {
+ npackets = (chan->buflen + maxpacket - 1) / maxpacket;
+
+ /* Clip if the buffer length if it exceeds the maximum number of
+ * packets that can be transferred (this should not happen).
+ */
+
+ if (npackets > STM32_MAX_PKTCOUNT)
+ {
+ npackets = STM32_MAX_PKTCOUNT;
+ chan->buflen = STM32_MAX_PKTCOUNT * maxpacket;
+ ulldbg("CLIP: chidx: %d buflen: %d\n", chidx, chan->buflen);
+ }
+ }
+ else
+ {
+ /* One packet will be sent/received (might be a zero length packet) */
+
+ npackets = 1;
+ }
+
+ /* If it is an IN transfer, then adjust the size of the buffer UP to
+ * a full number of packets. Hmmm... couldn't this cause an overrun
+ * into unallocated memory?
+ */
+
+#if 0 /* Think about this */
+ if (chan->in)
+ {
+ /* Force the buffer length to an even multiple of maxpacket */
+
+ chan->buflen = npackets * maxpacket;
+ }
+#endif
+
+ /* Save the number of packets in the transfer. We will need this in
+ * order to set the next data toggle correctly when the transfer
+ * completes.
+ */
+
+ chan->npackets = (uint8_t)npackets;
+
+ /* Setup the HCTSIZn register */
+
+ regval = ((uint32_t)chan->buflen << OTGFS_HCTSIZ_XFRSIZ_SHIFT) |
+ ((uint32_t)npackets << OTGFS_HCTSIZ_PKTCNT_SHIFT) |
+ ((uint32_t)chan->pid << OTGFS_HCTSIZ_DPID_SHIFT);
+ stm32_putreg(STM32_OTGFS_HCTSIZ(chidx), regval);
+
+ /* Setup the HCCHAR register: Frame oddness and host channel enable */
+
+ regval = stm32_getreg(STM32_OTGFS_HCCHAR(chidx));
+
+ /* Set/clear the Odd Frame bit. Check for an even frame; if so set Odd
+ * Frame. This field is applicable for only periodic (isochronous and
+ * interrupt) channels.
+ */
+
+ if ((stm32_getreg(STM32_OTGFS_HFNUM) & 1) == 0)
+ {
+ regval |= OTGFS_HCCHAR_ODDFRM;
+ }
+
+ regval &= ~OTGFS_HCCHAR_CHDIS;
+ regval |= OTGFS_HCCHAR_CHENA;
+ stm32_putreg(STM32_OTGFS_HCCHAR(chidx), regval);
+
+ /* If this is an out transfer, then we need to do more.. we need to copy
+ * the outgoing data into the correct TxFIFO.
+ */
+
+ if (!chan->in && chan->buflen > 0)
+ {
+ /* Handle non-periodic (CTRL and BULK) OUT transfers differently than
+ * periodic (INTR and ISOC) OUT transfers.
+ */
+
+ minsize = MIN(chan->buflen, chan->maxpacket);
+
+ switch (chan->eptype)
+ {
+ case OTGFS_EPTYPE_CTRL: /* Non periodic transfer */
+ case OTGFS_EPTYPE_BULK:
+ {
+ /* Read the Non-periodic Tx FIFO status register */
+
+ regval = stm32_getreg(STM32_OTGFS_HNPTXSTS);
+ avail = ((regval & OTGFS_HNPTXSTS_NPTXFSAV_MASK) >> OTGFS_HNPTXSTS_NPTXFSAV_SHIFT) << 2;
+ }
+ break;
+
+ /* Periodic transfer */
+
+ case OTGFS_EPTYPE_INTR:
+ case OTGFS_EPTYPE_ISOC:
+ {
+ /* Read the Non-periodic Tx FIFO status register */
+
+ regval = stm32_getreg(STM32_OTGFS_HPTXSTS);
+ avail = ((regval & OTGFS_HPTXSTS_PTXFSAVL_MASK) >> OTGFS_HPTXSTS_PTXFSAVL_SHIFT) << 2;
+ }
+ break;
+
+ default:
+ DEBUGASSERT(false);
+ return;
+ }
+
+ /* Is there space in the TxFIFO to hold the minimum size packet? */
+
+ if (minsize <= avail)
+ {
+ /* Yes.. Get the size of the biggest thing that we can put in the Tx FIFO now */
+
+ wrsize = chan->buflen;
+ if (wrsize > avail)
+ {
+ /* Clip the write size to the number of full, max sized packets
+ * that will fit in the Tx FIFO.
+ */
+
+ unsigned int wrpackets = avail / chan->maxpacket;
+ wrsize = wrpackets * chan->maxpacket;
+ }
+
+ /* Write packet into the Tx FIFO. */
+
+ stm32_gint_wrpacket(priv, chan->buffer, chidx, wrsize);
+ }
+
+ /* Did we put the entire buffer into the Tx FIFO? */
+
+ if (chan->buflen > avail)
+ {
+ /* No, there was insufficient space to hold the entire transfer ...
+ * Enable the Tx FIFO interrupt to handle the transfer when the Tx
+ * FIFO becomes empty.
+ */
+
+ stm32_txfe_enable(priv, chidx);
+ }
+ }
+}
+
+/*******************************************************************************
+ * Name: stm32_getframe
+ *
+ * Description:
+ * Get the current frame number.
+ *
+ *******************************************************************************/
+
+static inline uint16_t stm32_getframe(void)
+{
+ return (uint16_t)(stm32_getreg(STM32_OTGFS_HFNUM) & OTGFS_HFNUM_FRNUM_MASK);
+}
+
+/*******************************************************************************
+ * Name: stm32_ctrl_sendsetup
+ *
+ * Description:
+ * Send an IN/OUT SETUP packet.
+ *
+ *******************************************************************************/
+
+static int stm32_ctrl_sendsetup(FAR struct stm32_usbhost_s *priv,
+ FAR const struct usb_ctrlreq_s *req)
+{
+ FAR struct stm32_chan_s *chan;
+ uint16_t start = stm32_getframe();
+ uint16_t elapsed;
+ int ret;
+
+ chan = &priv->chan[priv->ep0out];
+
+ /* Loop while the device reports NAK (and a timeout is not exceeded */
+
+ do
+ {
+ /* Send the SETUP packet */
+
+ chan->pid = OTGFS_PID_SETUP;
+ chan->buffer = (FAR uint8_t *)req;
+ chan->buflen = USB_SIZEOF_CTRLREQ;
+
+ /* Set up for the wait BEFORE starting the transfer */
+
+ ret = stm32_chan_waitsetup(priv, chan);
+ if (ret != OK)
+ {
+ udbg("ERROR: Device disconnected\n");
+ return ret;
+ }
+
+ /* Start the transfer */
+
+ stm32_transfer_start(priv, priv->ep0out);
+
+ /* Wait for the transfer to complete */
+
+ ret = stm32_chan_wait(priv, chan);
+
+ /* Return on success and for all failures other than EAGAIN. EAGAIN
+ * means that the device NAKed the SETUP command and that we should
+ * try a few more times.
+ */
+
+ if (ret != -EAGAIN)
+ {
+ /* Output some debug information if the transfer failed */
+
+ if (ret < 0)
+ {
+ udbg("Transfer failed: %d\n", ret);
+ }
+
+ /* Return the result in any event */
+
+ return ret;
+ }
+
+ /* Get the elpased time (in frames) */
+
+ elapsed = stm32_getframe() - start;
+ }
+ while (elapsed < STM32_NOTREADY_DELAY);
+
+ return -ETIMEDOUT;
+}
+
+/*******************************************************************************
+ * Name: stm32_ctrl_senddata
+ *
+ * Description:
+ * Send data in the data phase of an OUT control transfer. Or send status
+ * in the status phase of an IN control transfer
+ *
+ *******************************************************************************/
+
+static int stm32_ctrl_senddata(FAR struct stm32_usbhost_s *priv,
+ FAR uint8_t *buffer, unsigned int buflen)
+{
+ FAR struct stm32_chan_s *chan = &priv->chan[priv->ep0out];
+ int ret;
+
+ /* Save buffer information */
+
+ chan->buffer = buffer;
+ chan->buflen = buflen;
+
+ /* Set the DATA PID */
+
+ if (buflen == 0)
+ {
+ /* For status OUT stage with buflen == 0, set PID DATA1 */
+
+ chan->outdata1 = true;
+ }
+
+ /* Set the Data PID as per the outdata1 boolean */
+
+ chan->pid = chan->outdata1 ? OTGFS_PID_DATA1 : OTGFS_PID_DATA0;
+
+ /* Set up for the wait BEFORE starting the transfer */
+
+ ret = stm32_chan_waitsetup(priv, chan);
+ if (ret != OK)
+ {
+ udbg("ERROR: Device disconnected\n");
+ return ret;
+ }
+
+ /* Start the transfer */
+
+ stm32_transfer_start(priv, priv->ep0out);
+
+ /* Wait for the transfer to complete and return the result */
+
+ return stm32_chan_wait(priv, chan);
+}
+
+/*******************************************************************************
+ * Name: stm32_ctrl_recvdata
+ *
+ * Description:
+ * Receive data in the data phase of an IN control transfer. Or receive status
+ * in the status phase of an OUT control transfer
+ *
+ *******************************************************************************/
+
+static int stm32_ctrl_recvdata(FAR struct stm32_usbhost_s *priv,
+ FAR uint8_t *buffer, unsigned int buflen)
+{
+ FAR struct stm32_chan_s *chan = &priv->chan[priv->ep0in];
+ int ret;
+
+ /* Save buffer information */
+
+ chan->pid = OTGFS_PID_DATA1;
+ chan->buffer = buffer;
+ chan->buflen = buflen;
+
+ /* Set up for the wait BEFORE starting the transfer */
+
+ ret = stm32_chan_waitsetup(priv, chan);
+ if (ret != OK)
+ {
+ udbg("ERROR: Device disconnected\n");
+ return ret;
+ }
+
+ /* Start the transfer */
+
+ stm32_transfer_start(priv, priv->ep0in);
+
+ /* Wait for the transfer to complete and return the result */
+
+ return stm32_chan_wait(priv, chan);
+}
+
+/*******************************************************************************
+ * Name: stm32_gint_wrpacket
+ *
+ * Description:
+ * Transfer the 'buflen' bytes in 'buffer' to the Tx FIFO associated with
+ * 'chidx' (non-DMA).
+ *
+ *******************************************************************************/
+
+static void stm32_gint_wrpacket(FAR struct stm32_usbhost_s *priv,
+ FAR uint8_t *buffer, int chidx, int buflen)
+{
+ FAR uint32_t *src;
+ uint32_t fifo;
+ int buflen32;
+
+ stm32_pktdump("Sending", buffer, buflen);
+
+ /* Get the number of 32-byte words associated with this byte size */
+
+ buflen32 = (buflen + 3) >> 2;
+
+ /* Get the address of the Tx FIFO associated with this channel */
+
+ fifo = STM32_OTGFS_DFIFO_HCH(chidx);
+
+ /* Transfer all of the data into the Tx FIFO */
+
+ src = (FAR uint32_t *)buffer;
+ for (; buflen32 > 0; buflen32--)
+ {
+ uint32_t data = *src++;
+ stm32_putreg(fifo, data);
+ }
+
+ /* Increment the count of bytes "in-flight" in the Tx FIFO */
+
+ priv->chan[chidx].inflight += buflen;
+}
+
+/*******************************************************************************
+ * Name: stm32_gint_hcinisr
+ *
+ * Description:
+ * USB OTG FS host IN channels interrupt handler
+ *
+ * One the completion of the transfer, the channel result byte may be set as
+ * follows:
+ *
+ * OK - Transfer completed successfully
+ * EAGAIN - If devices NAKs the transfer or NYET occurs
+ * EPERM - If the endpoint stalls
+ * EIO - On a TX or data toggle error
+ * EPIPE - Frame overrun
+ *
+ * EBUSY in the result field indicates that the transfer has not completed.
+ *
+ *******************************************************************************/
+
+static inline void stm32_gint_hcinisr(FAR struct stm32_usbhost_s *priv,
+ int chidx)
+{
+ FAR struct stm32_chan_s *chan = &priv->chan[chidx];
+ uint32_t regval;
+ uint32_t pending;
+
+ /* Read the HCINT register to get the pending HC interrupts. Read the
+ * HCINTMSK register to get the set of enabled HC interrupts.
+ */
+
+ pending = stm32_getreg(STM32_OTGFS_HCINT(chidx));
+ regval = stm32_getreg(STM32_OTGFS_HCINTMSK(chidx));
+
+ /* AND the two to get the set of enabled, pending HC interrupts */
+
+ pending &= regval;
+ ullvdbg("HCINTMSK%d: %08x pending: %08x\n", chidx, regval, pending);
+
+ /* Check for a pending ACK response received/transmitted (ACK) interrupt */
+
+ if ((pending & OTGFS_HCINT_ACK) != 0)
+ {
+ /* Clear the pending the ACK response received/transmitted (ACK) interrupt */
+
+ stm32_putreg(STM32_OTGFS_HCINT(chidx), OTGFS_HCINT_ACK);
+ }
+
+ /* Check for a pending STALL response receive (STALL) interrupt */
+
+ else if ((pending & OTGFS_HCINT_STALL) != 0)
+ {
+ /* Clear the NAK and STALL Conditions. */
+
+ stm32_putreg(STM32_OTGFS_HCINT(chidx), (OTGFS_HCINT_NAK | OTGFS_HCINT_STALL));
+
+ /* Halt the channel when a STALL, TXERR, BBERR or DTERR interrupt is
+ * received on the channel.
+ */
+
+ stm32_chan_halt(priv, chidx, CHREASON_STALL);
+
+ /* When there is a STALL, clear any pending NAK so that it is not
+ * processed below.
+ */
+
+ pending &= ~OTGFS_HCINT_NAK;
+ }
+
+ /* Check for a pending Data Toggle ERRor (DTERR) interrupt */
+
+ else if ((pending & OTGFS_HCINT_DTERR) != 0)
+ {
+ /* Halt the channel when a STALL, TXERR, BBERR or DTERR interrupt is
+ * received on the channel.
+ */
+
+ stm32_chan_halt(priv, chidx, CHREASON_DTERR);
+
+ /* Clear the NAK and data toggle error conditions */
+
+ stm32_putreg(STM32_OTGFS_HCINT(chidx), (OTGFS_HCINT_NAK | OTGFS_HCINT_DTERR));
+ }
+
+ /* Check for a pending FRaMe OverRun (FRMOR) interrupt */
+
+ if ((pending & OTGFS_HCINT_FRMOR) != 0)
+ {
+ /* Halt the channel -- the CHH interrrupt is expected next */
+
+ stm32_chan_halt(priv, chidx, CHREASON_FRMOR);
+
+ /* Clear the FRaMe OverRun (FRMOR) condition */
+
+ stm32_putreg(STM32_OTGFS_HCINT(chidx), OTGFS_HCINT_FRMOR);
+ }
+
+ /* Check for a pending TransFeR Completed (XFRC) interrupt */
+
+ else if ((pending & OTGFS_HCINT_XFRC) != 0)
+ {
+ /* Clear the TransFeR Completed (XFRC) condition */
+
+ stm32_putreg(STM32_OTGFS_HCINT(chidx), OTGFS_HCINT_XFRC);
+
+ /* Then handle the transfer completion event based on the endpoint type */
+
+ if (chan->eptype == OTGFS_EPTYPE_CTRL || chan->eptype == OTGFS_EPTYPE_BULK)
+ {
+ /* Halt the channel -- the CHH interrrupt is expected next */
+
+ stm32_chan_halt(priv, chidx, CHREASON_XFRC);
+
+ /* Clear any pending NAK condition. The 'indata1' data toggle
+ * should have been appropriately updated by the the RxFIFO
+ * logic as each packet was received.
+ */
+
+ stm32_putreg(STM32_OTGFS_HCINT(chidx), OTGFS_HCINT_NAK);
+ }
+ else if (chan->eptype == OTGFS_EPTYPE_INTR)
+ {
+ /* Force the next transfer on an ODD frame */
+
+ regval = stm32_getreg(STM32_OTGFS_HCCHAR(chidx));
+ regval |= OTGFS_HCCHAR_ODDFRM;
+ stm32_putreg(STM32_OTGFS_HCCHAR(chidx), regval);
+
+ /* Set the request done state */
+
+ chan->result = OK;
+ }
+ }
+
+ /* Check for a pending CHannel Halted (CHH) interrupt */
+
+ else if ((pending & OTGFS_HCINT_CHH) != 0)
+ {
+ /* Mask the CHannel Halted (CHH) interrupt */
+
+ regval = stm32_getreg(STM32_OTGFS_HCINTMSK(chidx));
+ regval &= ~OTGFS_HCINT_CHH;
+ stm32_putreg(STM32_OTGFS_HCINTMSK(chidx), regval);
+
+ /* Update the request state based on the host state machine state */
+
+ if (chan->chreason == CHREASON_XFRC)
+ {
+ /* Set the request done reult */
+
+ chan->result = OK;
+ }
+ else if (chan->chreason == CHREASON_STALL)
+ {
+ /* Set the request stall result */
+
+ chan->result = EPERM;
+ }
+ else if ((chan->chreason == CHREASON_TXERR) ||
+ (chan->chreason == CHREASON_DTERR))
+ {
+ /* Set the request I/O error result */
+
+ chan->result = EIO;
+ }
+ else if (chan->chreason == CHREASON_NAK)
+ {
+ /* Halt on NAK only happens on an INTR channel. Fetch the HCCHAR register
+ * and check for an interrupt endpoint.
+ */
+
+ regval = stm32_getreg(STM32_OTGFS_HCCHAR(chidx));
+ if ((regval & OTGFS_HCCHAR_EPTYP_MASK) == OTGFS_HCCHAR_EPTYP_INTR)
+ {
+ /* Toggle the IN data toggle (Used by Bulk and INTR only) */
+
+ chan->indata1 ^= true;
+ }
+
+ /* Set the NAK error result */
+
+ chan->result = EAGAIN;
+ }
+ else /* if (chan->chreason == CHREASON_FRMOR) */
+ {
+ /* Set the frame overrun error result */
+
+ chan->result = EPIPE;
+ }
+
+ /* Clear the CHannel Halted (CHH) condition */
+
+ stm32_putreg(STM32_OTGFS_HCINT(chidx), OTGFS_HCINT_CHH);
+ }
+
+ /* Check for a pending Transaction ERror (TXERR) interrupt */
+
+ else if ((pending & OTGFS_HCINT_TXERR) != 0)
+ {
+ /* Halt the channel when a STALL, TXERR, BBERR or DTERR interrupt is
+ * received on the channel.
+ */
+
+ stm32_chan_halt(priv, chidx, CHREASON_TXERR);
+
+ /* Clear the Transaction ERror (TXERR) condition */
+
+ stm32_putreg(STM32_OTGFS_HCINT(chidx), OTGFS_HCINT_TXERR);
+ }
+
+ /* Check for a pending NAK response received (NAK) interrupt */
+
+ else if ((pending & OTGFS_HCINT_NAK) != 0)
+ {
+ /* For a BULK tranfer, the hardware is capable of retrying
+ * automatically on a NAK. However, this is not always
+ * what we need to do. So we always halt the transfer and
+ * return control to high level logic in the even of a NAK.
+ */
+
+#if 0
+ /* Halt the interrupt channel */
+
+ if (chan->eptype == OTGFS_EPTYPE_CTRL)
+ {
+ /* Halt the channel -- the CHH interrrupt is expected next */
+
+ stm32_chan_halt(priv, chidx, CHREASON_NAK);
+ }
+
+ /* Re-activate CTRL and BULK channels */
+
+ else if (chan->eptype == OTGFS_EPTYPE_CTRL ||
+ chan->eptype == OTGFS_EPTYPE_BULK)
+ {
+ /* Re-activate the channel by clearing CHDIS and assuring that
+ * CHENA is set
+ */
+
+ regval = stm32_getreg(STM32_OTGFS_HCCHAR(chidx));
+ regval |= OTGFS_HCCHAR_CHENA;
+ regval &= ~OTGFS_HCCHAR_CHDIS;
+ stm32_putreg(STM32_OTGFS_HCCHAR(chidx), regval);
+ }
+#else
+ /* Halt all transfers on the NAK -- the CHH interrrupt is expected next */
+
+ stm32_chan_halt(priv, chidx, CHREASON_NAK);
+#endif
+ /* Clear the NAK condition */
+
+ stm32_putreg(STM32_OTGFS_HCINT(chidx), OTGFS_HCINT_NAK);
+ }
+
+ /* Check for a transfer complete event */
+
+ stm32_chan_wakeup(priv, chan);
+}
+
+/*******************************************************************************
+ * Name: stm32_gint_hcoutisr
+ *
+ * Description:
+ * USB OTG FS host OUT channels interrupt handler
+ *
+ * One the completion of the transfer, the channel result byte may be set as
+ * follows:
+ *
+ * OK - Transfer completed successfully
+ * EAGAIN - If devices NAKs the transfer or NYET occurs
+ * EPERM - If the endpoint stalls
+ * EIO - On a TX or data toggle error
+ * EPIPE - Frame overrun
+ *
+ * EBUSY in the result field indicates that the transfer has not completed.
+ *
+ *******************************************************************************/
+
+static inline void stm32_gint_hcoutisr(FAR struct stm32_usbhost_s *priv,
+ int chidx)
+{
+ FAR struct stm32_chan_s *chan = &priv->chan[chidx];
+ uint32_t regval;
+ uint32_t pending;
+
+ /* Read the HCINT register to get the pending HC interrupts. Read the
+ * HCINTMSK register to get the set of enabled HC interrupts.
+ */
+
+ pending = stm32_getreg(STM32_OTGFS_HCINT(chidx));
+ regval = stm32_getreg(STM32_OTGFS_HCINTMSK(chidx));
+
+ /* AND the two to get the set of enabled, pending HC interrupts */
+
+ pending &= regval;
+ ullvdbg("HCINTMSK%d: %08x pending: %08x\n", chidx, regval, pending);
+
+ /* Check for a pending ACK response received/transmitted (ACK) interrupt */
+
+ if ((pending & OTGFS_HCINT_ACK) != 0)
+ {
+ /* Clear the pending the ACK response received/transmitted (ACK) interrupt */
+
+ stm32_putreg(STM32_OTGFS_HCINT(chidx), OTGFS_HCINT_ACK);
+ }
+
+ /* Check for a pending FRaMe OverRun (FRMOR) interrupt */
+
+ else if ((pending & OTGFS_HCINT_FRMOR) != 0)
+ {
+ /* Halt the channel (probably not necessary for FRMOR) */
+
+ stm32_chan_halt(priv, chidx, CHREASON_FRMOR);
+
+ /* Clear the pending the FRaMe OverRun (FRMOR) interrupt */
+
+ stm32_putreg(STM32_OTGFS_HCINT(chidx), OTGFS_HCINT_FRMOR);
+ }
+
+ /* Check for a pending TransFeR Completed (XFRC) interrupt */
+
+ else if ((pending & OTGFS_HCINT_XFRC) != 0)
+ {
+ /* Decrement the number of bytes remaining by the number of
+ * bytes that were "in-flight".
+ */
+
+ priv->chan[chidx].buffer += priv->chan[chidx].inflight;
+ priv->chan[chidx].buflen -= priv->chan[chidx].inflight;
+ priv->chan[chidx].inflight = 0;
+
+ /* Halt the channel -- the CHH interrrupt is expected next */
+
+ stm32_chan_halt(priv, chidx, CHREASON_XFRC);
+
+ /* Clear the pending the TransFeR Completed (XFRC) interrupt */
+
+ stm32_putreg(STM32_OTGFS_HCINT(chidx), OTGFS_HCINT_XFRC);
+ }
+
+ /* Check for a pending STALL response receive (STALL) interrupt */
+
+ else if ((pending & OTGFS_HCINT_STALL) != 0)
+ {
+ /* Clear the pending the STALL response receiv (STALL) interrupt */
+
+ stm32_putreg(STM32_OTGFS_HCINT(chidx), OTGFS_HCINT_STALL);
+
+ /* Halt the channel when a STALL, TXERR, BBERR or DTERR interrupt is
+ * received on the channel.
+ */
+
+ stm32_chan_halt(priv, chidx, CHREASON_STALL);
+ }
+
+ /* Check for a pending NAK response received (NAK) interrupt */
+
+ else if ((pending & OTGFS_HCINT_NAK) != 0)
+ {
+ /* Halt the channel -- the CHH interrrupt is expected next */
+
+ stm32_chan_halt(priv, chidx, CHREASON_NAK);
+
+ /* Clear the pending the NAK response received (NAK) interrupt */
+
+ stm32_putreg(STM32_OTGFS_HCINT(chidx), OTGFS_HCINT_NAK);
+ }
+
+ /* Check for a pending Transaction ERror (TXERR) interrupt */
+
+ else if ((pending & OTGFS_HCINT_TXERR) != 0)
+ {
+ /* Halt the channel when a STALL, TXERR, BBERR or DTERR interrupt is
+ * received on the channel.
+ */
+
+ stm32_chan_halt(priv, chidx, CHREASON_TXERR);
+
+ /* Clear the pending the Transaction ERror (TXERR) interrupt */
+
+ stm32_putreg(STM32_OTGFS_HCINT(chidx), OTGFS_HCINT_TXERR);
+ }
+
+ /* Check for a NYET interrupt */
+
+#if 0 /* NYET is a reserved bit in the HCINT register */
+ else if ((pending & OTGFS_HCINT_NYET) != 0)
+ {
+ /* Halt the channel */
+
+ stm32_chan_halt(priv, chidx, CHREASON_NYET);
+
+ /* Clear the pending the NYET interrupt */
+
+ stm32_putreg(STM32_OTGFS_HCINT(chidx), OTGFS_HCINT_NYET);
+ }
+#endif
+
+ /* Check for a pending Data Toggle ERRor (DTERR) interrupt */
+
+ else if (pending & OTGFS_HCINT_DTERR)
+ {
+ /* Halt the channel when a STALL, TXERR, BBERR or DTERR interrupt is
+ * received on the channel.
+ */
+
+ stm32_chan_halt(priv, chidx, CHREASON_DTERR);
+
+ /* Clear the pending the Data Toggle ERRor (DTERR) and NAK interrupts */
+
+ stm32_putreg(STM32_OTGFS_HCINT(chidx), (OTGFS_HCINT_DTERR | OTGFS_HCINT_NAK));
+ }
+
+ /* Check for a pending CHannel Halted (CHH) interrupt */
+
+ else if ((pending & OTGFS_HCINT_CHH) != 0)
+ {
+ /* Mask the CHannel Halted (CHH) interrupt */
+
+ regval = stm32_getreg(STM32_OTGFS_HCINTMSK(chidx));
+ regval &= ~OTGFS_HCINT_CHH;
+ stm32_putreg(STM32_OTGFS_HCINTMSK(chidx), regval);
+
+ if (chan->chreason == CHREASON_XFRC)
+ {
+ /* Set the request done result */
+
+ chan->result = OK;
+
+ /* Read the HCCHAR register to get the HCCHAR register to get
+ * the endpoint type.
+ */
+
+ regval = stm32_getreg(STM32_OTGFS_HCCHAR(chidx));
+
+ /* Is it a bulk endpoint? Were an odd number of packets
+ * transferred?
+ */
+
+ if ((regval & OTGFS_HCCHAR_EPTYP_MASK) == OTGFS_HCCHAR_EPTYP_BULK &&
+ (chan->npackets & 1) != 0)
+ {
+ /* Yes to both... toggle the data out PID */
+
+ chan->outdata1 ^= true;
+ }
+ }
+ else if (chan->chreason == CHREASON_NAK ||
+ chan->chreason == CHREASON_NYET)
+ {
+ /* Set the try again later result */
+
+ chan->result = EAGAIN;
+ }
+ else if (chan->chreason == CHREASON_STALL)
+ {
+ /* Set the request stall result */
+
+ chan->result = EPERM;
+ }
+ else if ((chan->chreason == CHREASON_TXERR) ||
+ (chan->chreason == CHREASON_DTERR))
+ {
+ /* Set the I/O failure result */
+
+ chan->result = EIO;
+ }
+ else /* if (chan->chreason == CHREASON_FRMOR) */
+ {
+ /* Set the frame error result */
+
+ chan->result = EPIPE;
+ }
+
+ /* Clear the pending the CHannel Halted (CHH) interrupt */
+
+ stm32_putreg(STM32_OTGFS_HCINT(chidx), OTGFS_HCINT_CHH);
+ }
+
+ /* Check for a transfer complete event */
+
+ stm32_chan_wakeup(priv, chan);
+}
+
+/*******************************************************************************
+ * Name: stm32_gint_connected
+ *
+ * Description:
+ * Handle a connection event.
+ *
+ *******************************************************************************/
+
+static void stm32_gint_connected(FAR struct stm32_usbhost_s *priv)
+{
+ /* We we previously disconnected? */
+
+ if (!priv->connected)
+ {
+ /* Yes.. then now we are connected */
+
+ ullvdbg("Connected\n");
+ priv->connected = true;
+ DEBUGASSERT(priv->smstate == SMSTATE_DETACHED);
+
+ /* Notify any waiters */
+
+ priv->smstate = SMSTATE_ATTACHED;
+ if (priv->eventwait)
+ {
+ stm32_givesem(&priv->eventsem);
+ priv->eventwait = false;
+ }
+ }
+}
+
+/*******************************************************************************
+ * Name: stm32_gint_disconnected
+ *
+ * Description:
+ * Handle a disconnection event.
+ *
+ *******************************************************************************/
+
+static void stm32_gint_disconnected(FAR struct stm32_usbhost_s *priv)
+{
+ /* Were we previously connected? */
+
+ if (!priv->connected)
+ {
+ /* Yes.. then we no longer connected */
+
+ ullvdbg("Disconnected\n");
+
+ /* Are we bound to a class driver? */
+
+ if (priv->class)
+ {
+ /* Yes.. Disconnect the class driver */
+
+ CLASS_DISCONNECTED(priv->class);
+ priv->class = NULL;
+ }
+
+ /* Re-Initilaize Host for new Enumeration */
+
+ priv->smstate = SMSTATE_DETACHED;
+ priv->ep0size = STM32_EP0_MAX_PACKET_SIZE;
+ priv->devaddr = STM32_DEF_DEVADDR;
+ priv->connected = false;
+ priv->lowspeed = false;
+ stm32_chan_freeall(priv);
+
+ /* Notify any waiters that there is a change in the connection state */
+
+ if (priv->eventwait)
+ {
+ stm32_givesem(&priv->eventsem);
+ priv->eventwait = false;
+ }
+ }
+}
+
+/*******************************************************************************
+ * Name: stm32_gint_sofisr
+ *
+ * Description:
+ * USB OTG FS start-of-frame interrupt handler
+ *
+ *******************************************************************************/
+
+#ifdef CONFIG_STM32_OTGFS_SOFINTR
+static inline void stm32_gint_sofisr(FAR struct stm32_usbhost_s *priv)
+{
+ /* Handle SOF interrupt */
+#warning "Do what?"
+
+ /* Clear pending SOF interrupt */
+
+ stm32_putreg(STM32_OTGFS_GINTSTS, OTGFS_GINT_SOF);
+}
+#endif
+
+/*******************************************************************************
+ * Name: stm32_gint_rxflvlisr
+ *
+ * Description:
+ * USB OTG FS RxFIFO non-empty interrupt handler
+ *
+ *******************************************************************************/
+
+static inline void stm32_gint_rxflvlisr(FAR struct stm32_usbhost_s *priv)
+{
+ FAR uint32_t *dest;
+ uint32_t grxsts;
+ uint32_t intmsk;
+ uint32_t hcchar;
+ uint32_t hctsiz;
+ uint32_t fifo;
+ int bcnt;
+ int bcnt32;
+ int chidx;
+ int i;
+
+ /* Disable the RxFIFO non-empty interrupt */
+
+ intmsk = stm32_getreg(STM32_OTGFS_GINTMSK);
+ intmsk &= ~OTGFS_GINT_RXFLVL;
+ stm32_putreg(STM32_OTGFS_GINTMSK, intmsk);
+
+ /* Read and pop the next status from the Rx FIFO */
+
+ grxsts = stm32_getreg(STM32_OTGFS_GRXSTSP);
+ ullvdbg("GRXSTS: %08x\n", grxsts);
+
+ /* Isolate the channel number/index in the status word */
+
+ chidx = (grxsts & OTGFS_GRXSTSH_CHNUM_MASK) >> OTGFS_GRXSTSH_CHNUM_SHIFT;
+
+ /* Get the host channel characteristics register (HCCHAR) for this channel */
+
+ hcchar = stm32_getreg(STM32_OTGFS_HCCHAR(chidx));
+
+ /* Then process the interrupt according to the packet status */
+
+ switch (grxsts & OTGFS_GRXSTSH_PKTSTS_MASK)
+ {
+ case OTGFS_GRXSTSH_PKTSTS_INRECVD: /* IN data packet received */
+ {
+ /* Read the data into the host buffer. */
+
+ bcnt = (grxsts & OTGFS_GRXSTSH_BCNT_MASK) >> OTGFS_GRXSTSH_BCNT_SHIFT;
+ if (bcnt > 0 && priv->chan[chidx].buffer != NULL)
+ {
+ /* Transfer the packet from the Rx FIFO into the user buffer */
+
+ dest = (FAR uint32_t *)priv->chan[chidx].buffer;
+ fifo = STM32_OTGFS_DFIFO_HCH(0);
+ bcnt32 = (bcnt + 3) >> 2;
+
+ for (i = 0; i < bcnt32; i++)
+ {
+ *dest++ = stm32_getreg(fifo);
+ }
+
+ stm32_pktdump("Received", priv->chan[chidx].buffer, bcnt);
+
+ /* Toggle the IN data pid (Used by Bulk and INTR only) */
+
+ priv->chan[chidx].indata1 ^= true;
+
+ /* Manage multiple packet transfers */
+
+ priv->chan[chidx].buffer += bcnt;
+ priv->chan[chidx].buflen -= bcnt;
+
+ /* Check if more packets are expected */
+
+ hctsiz = stm32_getreg(STM32_OTGFS_HCTSIZ(chidx));
+ if ((hctsiz & OTGFS_HCTSIZ_PKTCNT_MASK) != 0)
+ {
+ /* Re-activate the channel when more packets are expected */
+
+ hcchar |= OTGFS_HCCHAR_CHENA;
+ hcchar &= ~OTGFS_HCCHAR_CHDIS;
+ stm32_putreg(STM32_OTGFS_HCCHAR(chidx), hcchar);
+ }
+ }
+ }
+ break;
+
+ case OTGFS_GRXSTSH_PKTSTS_INDONE: /* IN transfer completed */
+ case OTGFS_GRXSTSH_PKTSTS_DTOGERR: /* Data toggle error */
+ case OTGFS_GRXSTSH_PKTSTS_HALTED: /* Channel halted */
+ default:
+ break;
+ }
+
+ /* Re-enable the RxFIFO non-empty interrupt */
+
+ intmsk |= OTGFS_GINT_RXFLVL;
+ stm32_putreg(STM32_OTGFS_GINTMSK, intmsk);
+}
+
+/*******************************************************************************
+ * Name: stm32_gint_nptxfeisr
+ *
+ * Description:
+ * USB OTG FS non-periodic TxFIFO empty interrupt handler
+ *
+ *******************************************************************************/
+
+static inline void stm32_gint_nptxfeisr(FAR struct stm32_usbhost_s *priv)
+{
+ FAR struct stm32_chan_s *chan;
+ uint32_t regval;
+ unsigned int wrsize;
+ unsigned int minsize;
+ unsigned int avail;
+ unsigned int chidx;
+
+ /* Recover the index of the channel that is waiting for space in the Tx
+ * FIFO.
+ */
+
+ chidx = priv->chidx;
+ chan = &priv->chan[chidx];
+
+ /* Reduce the buffer size by the number of bytes that were previously placed
+ * in the Tx FIFO.
+ */
+
+ chan->buffer += chan->inflight;
+ chan->buflen -= chan->inflight;
+ chan->inflight = 0;
+
+ /* If we have now transfered the entire buffer, then this transfer is
+ * complete (this case really should never happen because we disable
+ * the NPTXFE interrupt on the final packet).
+ */
+
+ if (chan->buflen <= 0)
+ {
+ /* Disable further Tx FIFO empty interrupts and bail. */
+
+ stm32_modifyreg(STM32_OTGFS_GINTMSK, OTGFS_GINT_NPTXFE, 0);
+ return;
+ }
+
+ /* Read the status from the top of the non-periodic TxFIFO */
+
+ regval = stm32_getreg(STM32_OTGFS_HNPTXSTS);
+
+ /* Extract the number of bytes available in the non-periodic Tx FIFO. */
+
+ avail = ((regval & OTGFS_HNPTXSTS_NPTXFSAV_MASK) >> OTGFS_HNPTXSTS_NPTXFSAV_SHIFT) << 2;
+
+ /* Get minimal size packet that can be sent. Something is serioulsy
+ * configured wrong if one packet will not fit into the empty Tx FIFO.
+ */
+
+ minsize = MIN(chan->buflen, chan->maxpacket);
+ DEBUGASSERT(chan->buflen > 0 && avail >= minsize);
+
+ /* Get the size to put in the Tx FIFO now */
+
+ wrsize = chan->buflen;
+ if (wrsize > avail)
+ {
+ /* Clip the write size to the number of full, max sized packets
+ * that will fit in the Tx FIFO.
+ */
+
+ unsigned int wrpackets = avail / chan->maxpacket;
+ wrsize = wrpackets * chan->maxpacket;
+ }
+
+ /* Otherwise, this will be the last packet to be sent in this transaction.
+ * We now need to disable further NPTXFE interrupts.
+ */
+
+ else
+ {
+ stm32_modifyreg(STM32_OTGFS_GINTMSK, OTGFS_GINT_NPTXFE, 0);
+ }
+
+ /* Write the next group of packets into the Tx FIFO */
+
+ ullvdbg("HNPTXSTS: %08x chidx: %d avail: %d buflen: %d wrsize: %d\n",
+ regval, chidx, avail, chan->buflen, wrsize);
+
+ stm32_gint_wrpacket(priv, chan->buffer, chidx, wrsize);
+}
+
+/*******************************************************************************
+ * Name: stm32_gint_ptxfeisr
+ *
+ * Description:
+ * USB OTG FS periodic TxFIFO empty interrupt handler
+ *
+ *******************************************************************************/
+
+static inline void stm32_gint_ptxfeisr(FAR struct stm32_usbhost_s *priv)
+{
+ FAR struct stm32_chan_s *chan;
+ uint32_t regval;
+ unsigned int wrsize;
+ unsigned int minsize;
+ unsigned int avail;
+ unsigned int chidx;
+
+ /* Recover the index of the channel that is waiting for space in the Tx
+ * FIFO.
+ */
+
+ chidx = priv->chidx;
+ chan = &priv->chan[chidx];
+
+ /* Reduce the buffer size by the number of bytes that were previously placed
+ * in the Tx FIFO.
+ */
+
+ chan->buffer += chan->inflight;
+ chan->buflen -= chan->inflight;
+ chan->inflight = 0;
+
+ /* If we have now transfered the entire buffer, then this transfer is
+ * complete (this case really should never happen because we disable
+ * the PTXFE interrupt on the final packet).
+ */
+
+ if (chan->buflen <= 0)
+ {
+ /* Disable further Tx FIFO empty interrupts and bail. */
+
+ stm32_modifyreg(STM32_OTGFS_GINTMSK, OTGFS_GINT_PTXFE, 0);
+ return;
+ }
+
+ /* Read the status from the top of the periodic TxFIFO */
+
+ regval = stm32_getreg(STM32_OTGFS_HPTXSTS);
+
+ /* Extract the number of bytes available in the periodic Tx FIFO. */
+
+ avail = ((regval & OTGFS_HPTXSTS_PTXFSAVL_MASK) >> OTGFS_HPTXSTS_PTXFSAVL_SHIFT) << 2;
+
+ /* Get minimal size packet that can be sent. Something is serioulsy
+ * configured wrong if one packet will not fit into the empty Tx FIFO.
+ */
+
+ minsize = MIN(chan->buflen, chan->maxpacket);
+ DEBUGASSERT(chan->buflen > 0 && avail >= minsize);
+
+ /* Get the size to put in the Tx FIFO now */
+
+ wrsize = chan->buflen;
+ if (wrsize > avail)
+ {
+ /* Clip the write size to the number of full, max sized packets
+ * that will fit in the Tx FIFO.
+ */
+
+ unsigned int wrpackets = avail / chan->maxpacket;
+ wrsize = wrpackets * chan->maxpacket;
+ }
+
+ /* Otherwise, this will be the last packet to be sent in this transaction.
+ * We now need to disable further PTXFE interrupts.
+ */
+
+ else
+ {
+ stm32_modifyreg(STM32_OTGFS_GINTMSK, OTGFS_GINT_PTXFE, 0);
+ }
+
+ /* Write the next group of packets into the Tx FIFO */
+
+ ullvdbg("HPTXSTS: %08x chidx: %d avail: %d buflen: %d wrsize: %d\n",
+ regval, chidx, avail, chan->buflen, wrsize);
+
+ stm32_gint_wrpacket(priv, chan->buffer, chidx, wrsize);
+}
+
+/*******************************************************************************
+ * Name: stm32_gint_hcisr
+ *
+ * Description:
+ * USB OTG FS host channels interrupt handler
+ *
+ *******************************************************************************/
+
+static inline void stm32_gint_hcisr(FAR struct stm32_usbhost_s *priv)
+{
+ uint32_t haint;
+ uint32_t hcchar;
+ int i = 0;
+
+ /* Read the Host all channels interrupt register and test each bit in the
+ * register. Each bit i, i=0...(STM32_NHOST_CHANNELS-1), corresponds to
+ * a pending interrupt on channel i.
+ */
+
+ haint = stm32_getreg(STM32_OTGFS_HAINT);
+ for (i = 0; i < STM32_NHOST_CHANNELS; i++)
+ {
+ /* Is an interrupt pending on this channel? */
+
+ if ((haint & OTGFS_HAINT(i)) != 0)
+ {
+ /* Yes... read the HCCHAR register to get the direction bit */
+
+ hcchar = stm32_getreg(STM32_OTGFS_HCCHAR(i));
+
+ /* Was this an interrupt on an IN or an OUT channel? */
+
+ if ((hcchar & OTGFS_HCCHAR_EPDIR) != 0)
+ {
+ /* Handle the HC IN channel interrupt */
+
+ stm32_gint_hcinisr(priv, i);
+ }
+ else
+ {
+ /* Handle the HC OUT channel interrupt */
+
+ stm32_gint_hcoutisr(priv, i);
+ }
+ }
+ }
+}
+
+/*******************************************************************************
+ * Name: stm32_gint_hprtisr
+ *
+ * Description:
+ * USB OTG FS host port interrupt handler
+ *
+ *******************************************************************************/
+
+static inline void stm32_gint_hprtisr(FAR struct stm32_usbhost_s *priv)
+{
+ uint32_t hprt;
+ uint32_t newhprt;
+ uint32_t hcfg;
+
+ /* Read the port status and control register (HPRT) */
+
+ hprt = stm32_getreg(STM32_OTGFS_HPRT);
+
+ /* Setup to clear the interrupt bits in GINTSTS by setting the corresponding
+ * bits in the HPRT. The HCINT interrupt bit is cleared when the appropriate
+ * status bits in the HPRT register are cleared.
+ */
+
+ newhprt = hprt & ~(OTGFS_HPRT_PENA | OTGFS_HPRT_PCDET |
+ OTGFS_HPRT_PENCHNG | OTGFS_HPRT_POCCHNG);
+
+ /* Check for Port Overcurrent CHaNGe (POCCHNG) */
+
+ if ((hprt & OTGFS_HPRT_POCCHNG) != 0)
+ {
+ /* Set up to clear the POCCHNG status in the new HPRT contents. */
+
+ newhprt |= OTGFS_HPRT_POCCHNG;
+ }
+
+ /* Check for Port Connect DETected (PCDET). The core sets this bit when a
+ * device connection is detected.
+ */
+
+ if ((hprt & OTGFS_HPRT_PCDET) != 0)
+ {
+ /* Set up to clear the PCDET status in the new HPRT contents. Then
+ * process the new connection event.
+ */
+
+ newhprt |= OTGFS_HPRT_PCDET;
+ stm32_gint_connected(priv);
+ }
+
+ /* Check for Port Enable CHaNGed (PENCHNG) */
+
+ if ((hprt & OTGFS_HPRT_PENCHNG) != 0)
+ {
+ /* Set up to clear the PENCHNG status in the new HPRT contents. */
+
+ newhprt |= OTGFS_HPRT_PENCHNG;
+
+ /* Was the port enabled? */
+
+ if ((hprt & OTGFS_HPRT_PENA) != 0)
+ {
+ /* Yes.. handle the new connection event */
+
+ stm32_gint_connected(priv);
+
+ /* Check the Host ConFiGuration register (HCFG) */
+
+ hcfg = stm32_getreg(STM32_OTGFS_HCFG);
+
+ /* Is this a low speed or full speed connection (OTG FS does not
+ * support high speed)
+ */
+
+ if ((hprt & OTGFS_HPRT_PSPD_MASK) == OTGFS_HPRT_PSPD_LS)
+ {
+ /* Set the Host Frame Interval Register for the 6KHz speed */
+
+ stm32_putreg(STM32_OTGFS_HFIR, 6000);
+
+ /* Are we switching from FS to LS? */
+
+ if ((hcfg & OTGFS_HCFG_FSLSPCS_MASK) != OTGFS_HCFG_FSLSPCS_LS6MHz)
+ {
+ /* Yes... configure for LS */
+
+ hcfg &= ~OTGFS_HCFG_FSLSPCS_MASK;
+ hcfg |= OTGFS_HCFG_FSLSPCS_LS6MHz;
+ stm32_putreg(STM32_OTGFS_HCFG, hcfg);
+
+ /* And reset the port */
+
+ stm32_portreset(priv);
+ }
+ }
+ else /* if ((hprt & OTGFS_HPRT_PSPD_MASK) == OTGFS_HPRT_PSPD_FS) */
+ {
+ stm32_putreg(STM32_OTGFS_HFIR, 48000);
+
+ /* Are we switching from LS to FS? */
+
+ if ((hcfg & OTGFS_HCFG_FSLSPCS_MASK) != OTGFS_HCFG_FSLSPCS_FS48MHz)
+ {
+ /* Yes... configure for FS */
+
+ hcfg &= ~OTGFS_HCFG_FSLSPCS_MASK;
+ hcfg |= OTGFS_HCFG_FSLSPCS_FS48MHz;
+ stm32_putreg(STM32_OTGFS_HCFG, hcfg);
+
+ /* And reset the port */
+
+ stm32_portreset(priv);
+ }
+ }
+ }
+ }
+
+ /* Clear port interrupts by setting bits in the HPRT */
+
+ stm32_putreg(STM32_OTGFS_HPRT, newhprt);
+}
+
+/*******************************************************************************
+ * Name: stm32_gint_discisr
+ *
+ * Description:
+ * USB OTG FS disconnect detected interrupt handler
+ *
+ *******************************************************************************/
+
+static inline void stm32_gint_discisr(FAR struct stm32_usbhost_s *priv)
+{
+ /* Handle the disconnection event */
+
+ stm32_gint_disconnected(priv);
+
+ /* Clear the dicsonnect interrupt */
+
+ stm32_putreg(STM32_OTGFS_GINTSTS, OTGFS_GINT_DISC);
+}
+
+/*******************************************************************************
+ * Name: stm32_gint_iisooxfrisr
+ *
+ * Description:
+ * USB OTG FS incomplete isochronous interrupt handler
+ *
+ *******************************************************************************/
+
+static inline void stm32_gint_iisooxfrisr(FAR struct stm32_usbhost_s *priv)
+{
+ uint32_t regval;
+
+ /* CHENA : Set to enable the channel
+ * CHDIS : Set to stop transmitting/receiving data on a channel
+ */
+
+ regval = stm32_getreg(STM32_OTGFS_HCCHAR(0));
+ regval |= (OTGFS_HCCHAR_CHDIS | OTGFS_HCCHAR_CHENA);
+ stm32_putreg(STM32_OTGFS_HCCHAR(0), regval);
+
+ /* Clear the incomplete isochronous OUT interrupt */
+
+ stm32_putreg(STM32_OTGFS_GINTSTS, OTGFS_GINT_IISOOXFR);
+}
+
+/*******************************************************************************
+ * Name: stm32_gint_isr
+ *
+ * Description:
+ * USB OTG FS global interrupt handler
+ *
+ *******************************************************************************/
+
+static int stm32_gint_isr(int irq, FAR void *context)
+{
+ /* At present, there is only support for a single OTG FS host. Hence it is
+ * pre-allocated as g_usbhost. However, in most code, the private data
+ * structure will be referenced using the 'priv' pointer (rather than the
+ * global data) in order to simplify any future support for multiple devices.
+ */
+
+ FAR struct stm32_usbhost_s *priv = &g_usbhost;
+ uint32_t pending;
+
+ /* If OTG were supported, we would need to check if we are in host or
+ * device mode when the global interrupt occurs. Here we support only
+ * host mode
+ */
+
+ /* Loop while there are pending interrupts to process. This loop may save a
+ * little interrupt handling overhead.
+ */
+
+ for (;;)
+ {
+ /* Get the unmasked bits in the GINT status */
+
+ pending = stm32_getreg(STM32_OTGFS_GINTSTS);
+ pending &= stm32_getreg(STM32_OTGFS_GINTMSK);
+
+ /* Return from the interrupt when there are no furhter pending
+ * interrupts.
+ */
+
+ if (pending == 0)
+ {
+ return OK;
+ }
+
+ /* Otherwise, process each pending, unmasked GINT interrupts */
+
+ ullvdbg("GINTSTS: %08x\n", pending);
+
+ /* Handle the start of frame interrupt */
+
+#ifdef CONFIG_STM32_OTGFS_SOFINTR
+ if ((pending & OTGFS_GINT_SOF) != 0)
+ {
+ stm32_gint_sofisr(priv);
+ }
+#endif
+
+ /* Handle the RxFIFO non-empty interrupt */
+
+ if ((pending & OTGFS_GINT_RXFLVL) != 0)
+ {
+ stm32_gint_rxflvlisr(priv);
+ }
+
+ /* Handle the non-periodic TxFIFO empty interrupt */
+
+ if ((pending & OTGFS_GINT_NPTXFE) != 0)
+ {
+ stm32_gint_nptxfeisr(priv);
+ }
+
+ /* Handle the periodic TxFIFO empty interrupt */
+
+ if ((pending & OTGFS_GINT_PTXFE) != 0)
+ {
+ stm32_gint_ptxfeisr(priv);
+ }
+
+ /* Handle the host channels interrupt */
+
+ if ((pending & OTGFS_GINT_HC) != 0)
+ {
+ stm32_gint_hcisr(priv);
+ }
+
+ /* Handle the host port interrupt */
+
+ if ((pending & OTGFS_GINT_HPRT) != 0)
+ {
+ stm32_gint_hprtisr(priv);
+ }
+
+ /* Handle the disconnect detected interrupt */
+
+ if ((pending & OTGFS_GINT_DISC) != 0)
+ {
+ stm32_gint_discisr(priv);
+ }
+
+ /* Handle the incomplete isochronous OUT transfer */
+
+ if ((pending & OTGFS_GINT_IISOOXFR) != 0)
+ {
+ stm32_gint_iisooxfrisr(priv);
+ }
+ }
+
+ /* We won't get here */
+
+ return OK;
+}
+
+/*******************************************************************************
+ * Name: stm32_gint_enable and stm32_gint_disable
+ *
+ * Description:
+ * Respectively enable or disable the global OTG FS interrupt.
+ *
+ * Input Parameters:
+ * None
+ *
+ * Returned Value:
+ * None
+ *
+ *******************************************************************************/
+
+static void stm32_gint_enable(void)
+{
+ uint32_t regval;
+
+ /* Set the GINTMSK bit to unmask the interrupt */
+
+ regval = stm32_getreg(STM32_OTGFS_GAHBCFG);
+ regval |= OTGFS_GAHBCFG_GINTMSK;
+ stm32_putreg(STM32_OTGFS_GAHBCFG, regval);
+}
+
+static void stm32_gint_disable(void)
+{
+ uint32_t regval;
+
+ /* Clear the GINTMSK bit to mask the interrupt */
+
+ regval = stm32_getreg(STM32_OTGFS_GAHBCFG);
+ regval &= ~OTGFS_GAHBCFG_GINTMSK;
+ stm32_putreg(STM32_OTGFS_GAHBCFG, regval);
+}
+
+/*******************************************************************************
+ * Name: stm32_hostinit_enable
+ *
+ * Description:
+ * Enable host interrupts.
+ *
+ * Input Parameters:
+ * None
+ *
+ * Returned Value:
+ * None
+ *
+ *******************************************************************************/
+
+static inline void stm32_hostinit_enable(void)
+{
+ uint32_t regval;
+
+ /* Disable all interrupts. */
+
+ stm32_putreg(STM32_OTGFS_GINTMSK, 0);
+
+ /* Clear any pending interrupts. */
+
+ stm32_putreg(STM32_OTGFS_GINTSTS, 0xffffffff);
+
+ /* Clear any pending USB OTG Interrupts (should be done elsewhere if OTG is supported) */
+
+ stm32_putreg(STM32_OTGFS_GOTGINT, 0xffffffff);
+
+ /* Clear any pending USB OTG interrupts */
+
+ stm32_putreg(STM32_OTGFS_GINTSTS, 0xbfffffff);
+
+ /* Enable the host interrupts */
+ /* Common interrupts:
+ *
+ * OTGFS_GINT_WKUP : Resume/remote wakeup detected interrupt
+ * OTGFS_GINT_USBSUSP : USB suspend
+ */
+
+ regval = (OTGFS_GINT_WKUP | OTGFS_GINT_USBSUSP);
+
+ /* If OTG were supported, we would need to enable the following as well:
+ *
+ * OTGFS_GINT_OTG : OTG interrupt
+ * OTGFS_GINT_SRQ : Session request/new session detected interrupt
+ * OTGFS_GINT_CIDSCHG : Connector ID status change
+ */
+
+ /* Host-specific interrupts
+ *
+ * OTGFS_GINT_SOF : Start of frame
+ * OTGFS_GINT_RXFLVL : RxFIFO non-empty
+ * OTGFS_GINT_IISOOXFR : Incomplete isochronous OUT transfer
+ * OTGFS_GINT_HPRT : Host port interrupt
+ * OTGFS_GINT_HC : Host channels interrupt
+ * OTGFS_GINT_DISC : Disconnect detected interrupt
+ */
+
+#ifdef CONFIG_STM32_OTGFS_SOFINTR
+ regval |= (OTGFS_GINT_SOF | OTGFS_GINT_RXFLVL | OTGFS_GINT_IISOOXFR |
+ OTGFS_GINT_HPRT | OTGFS_GINT_HC | OTGFS_GINT_DISC);
+#else
+ regval |= (OTGFS_GINT_RXFLVL | OTGFS_GINT_IISOOXFR | OTGFS_GINT_HPRT |
+ OTGFS_GINT_HC | OTGFS_GINT_DISC);
+#endif
+ stm32_putreg(STM32_OTGFS_GINTMSK, regval);
+}
+
+/*******************************************************************************
+ * Name: stm32_txfe_enable
+ *
+ * Description:
+ * Enable Tx FIFO empty interrupts. This is necessary when the entire
+ * transfer will not fit into Tx FIFO. The transfer will then be completed
+ * when the Tx FIFO is empty. NOTE: The Tx FIFO interrupt is disabled
+ * the the fifo empty interrupt handler when the transfer is complete.
+ *
+ * Input Parameters:
+ * priv - Driver state structure reference
+ * chidx - The channel that requires the Tx FIFO empty interrupt
+ *
+ * Returned Value:
+ * None
+ *
+ * Assumptions:
+ * Called from user task context. Interrupts must be disabled to assure
+ * exclusive access to the GINTMSK register.
+ *
+ *******************************************************************************/
+
+static void stm32_txfe_enable(FAR struct stm32_usbhost_s *priv, int chidx)
+{
+ FAR struct stm32_chan_s *chan = &priv->chan[chidx];
+ irqstate_t flags;
+ uint32_t regval;
+
+ /* Disable all interrupts so that we have exclusive access to the GINTMSK
+ * (it would be sufficent just to disable the GINT interrupt).
+ */
+
+ flags = irqsave();
+
+ /* Should we enable the periodic or non-peridic Tx FIFO empty interrupts */
+
+ regval = stm32_getreg(STM32_OTGFS_GINTMSK);
+ switch (chan->eptype)
+ {
+ default:
+ case OTGFS_EPTYPE_CTRL: /* Non periodic transfer */
+ case OTGFS_EPTYPE_BULK:
+ regval |= OTGFS_GINT_NPTXFE;
+ break;
+
+ case OTGFS_EPTYPE_INTR: /* Periodic transfer */
+ case OTGFS_EPTYPE_ISOC:
+ regval |= OTGFS_GINT_PTXFE;
+ break;
+ }
+
+ /* Enable interrupts */
+
+ stm32_putreg(STM32_OTGFS_GINTMSK, regval);
+ irqrestore(flags);
+}
+
+/*******************************************************************************
+ * USB Host Controller Operations
+ *******************************************************************************/
+
+/*******************************************************************************
+ * Name: stm32_wait
+ *
+ * Description:
+ * Wait for a device to be connected or disconneced.
+ *
+ * Input Parameters:
+ * drvr - The USB host driver instance obtained as a parameter from the call to
+ * the class create() method.
+ * connected - TRUE: Wait for device to be connected; FALSE: wait for device
+ * to be disconnected
+ *
+ * Returned Values:
+ * Zero (OK) is returned when a device in connected. This function will not
+ * return until either (1) a device is connected or (2) some failure occurs.
+ * On a failure, a negated errno value is returned indicating the nature of
+ * the failure
+ *
+ * Assumptions:
+ * - Called from a single thread so no mutual exclusion is required.
+ * - Never called from an interrupt handler.
+ *
+ *******************************************************************************/
+
+static int stm32_wait(FAR struct usbhost_driver_s *drvr, bool connected)
+{
+ FAR struct stm32_usbhost_s *priv = (FAR struct stm32_usbhost_s *)drvr;
+ irqstate_t flags;
+
+ /* Are we already connected? */
+
+ flags = irqsave();
+ while (priv->connected == connected)
+ {
+ /* No... wait for the connection/disconnection */
+
+ priv->eventwait = true;
+ stm32_takesem(&priv->eventsem);
+ }
+
+ irqrestore(flags);
+
+ udbg("Connected:%s\n", priv->connected ? "YES" : "NO");
+ return OK;
+}
+
+/*******************************************************************************
+ * Name: stm32_enumerate
+ *
+ * Description:
+ * Enumerate the connected device. As part of this enumeration process,
+ * the driver will (1) get the device's configuration descriptor, (2)
+ * extract the class ID info from the configuration descriptor, (3) call
+ * usbhost_findclass() to find the class that supports this device, (4)
+ * call the create() method on the struct usbhost_registry_s interface
+ * to get a class instance, and finally (5) call the configdesc() method
+ * of the struct usbhost_class_s interface. After that, the class is in
+ * charge of the sequence of operations.
+ *
+ * Input Parameters:
+ * drvr - The USB host driver instance obtained as a parameter from the call to
+ * the class create() method.
+ *
+ * Returned Values:
+ * On success, zero (OK) is returned. On a failure, a negated errno value is
+ * returned indicating the nature of the failure
+ *
+ * Assumptions:
+ * - Only a single class bound to a single device is supported.
+ * - Called from a single thread so no mutual exclusion is required.
+ * - Never called from an interrupt handler.
+ *
+ *******************************************************************************/
+
+static int stm32_enumerate(FAR struct usbhost_driver_s *drvr)
+{
+ struct stm32_usbhost_s *priv = (struct stm32_usbhost_s *)drvr;
+ uint32_t regval;
+ int chidx;
+ int ret;
+
+ /* Are we connected to a device? The caller should have called the wait()
+ * method first to be assured that a device is connected.
+ */
+
+ while (!priv->connected)
+ {
+ /* No, return an error */
+
+ udbg("Not connected\n");
+ return -ENODEV;
+ }
+
+ DEBUGASSERT(priv->smstate == SMSTATE_ATTACHED);
+
+ /* Allocate and initialize the control OUT channel */
+
+ chidx = stm32_chan_alloc(priv);
+ DEBUGASSERT(chidx >= 0);
+
+ priv->ep0out = chidx;
+ priv->chan[chidx].epno = 0;
+ priv->chan[chidx].in = false;
+ priv->chan[chidx].eptype = OTGFS_EPTYPE_CTRL;
+ priv->chan[chidx].maxpacket = STM32_EP0_DEF_PACKET_SIZE;
+ priv->chan[chidx].indata1 = false;
+ priv->chan[chidx].outdata1 = false;
+
+ /* Allocate and initialize the control IN channel */
+
+ chidx = stm32_chan_alloc(priv);
+ DEBUGASSERT(chidx >= 0);
+
+ priv->ep0in = chidx;
+ priv->chan[chidx].epno = 0;
+ priv->chan[chidx].in = true;
+ priv->chan[chidx].eptype = OTGFS_EPTYPE_CTRL;
+ priv->chan[chidx].maxpacket = STM32_EP0_DEF_PACKET_SIZE;
+ priv->chan[chidx].indata1 = false;
+ priv->chan[chidx].outdata1 = false;
+
+ /* USB 2.0 spec says at least 50ms delay before port reset */
+
+ up_mdelay(100);
+
+ /* Reset the host port */
+
+ stm32_portreset(priv);
+
+ /* Get the current device speed */
+
+ regval = stm32_getreg(STM32_OTGFS_HPRT);
+ priv->lowspeed = ((regval & OTGFS_HPRT_PSPD_MASK) == OTGFS_HPRT_PSPD_LS);
+
+ /* Configure control channels */
+
+ stm32_chan_configure(priv, priv->ep0out) ;
+ stm32_chan_configure(priv, priv->ep0in) ;
+
+ /* Let the common usbhost_enumerate do all of the real work. Note that the
+ * FunctionAddress (USB address) is hardcoded to one.
+ */
+
+ uvdbg("Enumerate the device\n");
+ priv->smstate = SMSTATE_ENUM;
+ ret = usbhost_enumerate(drvr, 1, &priv->class);
+
+ /* The enumeration may fail either because of some HCD interfaces failure
+ * or because the device class is not supported. In either case, we just
+ * need to perform the disconnection operation and make ready for a new
+ * enumeration.
+ */
+
+ if (ret < 0)
+ {
+ /* Return to the disconnected state */
+
+ stm32_gint_disconnected(priv);
+ }
+
+ return ret;
+}
+
+/************************************************************************************
+ * Name: stm32_ep0configure
+ *
+ * Description:
+ * Configure endpoint 0. This method is normally used internally by the
+ * enumerate() method but is made available at the interface to support an
+ * external implementation of the enumeration logic.
+ *
+ * Input Parameters:
+ * drvr - The USB host driver instance obtained as a parameter from the call to
+ * the class create() method.
+ * funcaddr - The USB address of the function containing the endpoint that EP0
+ * controls
+ * maxpacketsize - The maximum number of bytes that can be sent to or
+ * received from the endpoint in a single data packet
+ *
+ * Returned Values:
+ * On success, zero (OK) is returned. On a failure, a negated errno value is
+ * returned indicating the nature of the failure
+ *
+ * Assumptions:
+ * This function will *not* be called from an interrupt handler.
+ *
+ ************************************************************************************/
+
+static int stm32_ep0configure(FAR struct usbhost_driver_s *drvr, uint8_t funcaddr,
+ uint16_t maxpacketsize)
+{
+ FAR struct stm32_usbhost_s *priv = (FAR struct stm32_usbhost_s *)drvr;
+
+ DEBUGASSERT(drvr && funcaddr < 128 && maxpacketsize < 2048);
+
+ /* We must have exclusive access to the USB host hardware and state structures */
+
+ stm32_takesem(&priv->exclsem);
+
+ /* Save the device address and EP0 max packet size */
+
+ priv->devaddr = funcaddr;
+ priv->ep0size = maxpacketsize;
+
+ /* Configure the EP0 OUT channel */
+
+ priv->chan[priv->ep0out].maxpacket = maxpacketsize;
+ stm32_chan_configure(priv, priv->ep0out);
+
+ /* Configure the EP0 IN channel */
+
+ priv->chan[priv->ep0in].maxpacket = maxpacketsize;
+ stm32_chan_configure(priv, priv->ep0in);
+
+ stm32_givesem(&priv->exclsem);
+ return OK;
+}
+
+/************************************************************************************
+ * Name: stm32_epalloc
+ *
+ * Description:
+ * Allocate and configure one endpoint.
+ *
+ * Input Parameters:
+ * drvr - The USB host driver instance obtained as a parameter from the call to
+ * the class create() method.
+ * epdesc - Describes the endpoint to be allocated.
+ * ep - A memory location provided by the caller in which to receive the
+ * allocated endpoint desciptor.
+ *
+ * Returned Values:
+ * On success, zero (OK) is returned. On a failure, a negated errno value is
+ * returned indicating the nature of the failure
+ *
+ * Assumptions:
+ * This function will *not* be called from an interrupt handler.
+ *
+ ************************************************************************************/
+
+static int stm32_epalloc(FAR struct usbhost_driver_s *drvr,
+ FAR const struct usbhost_epdesc_s *epdesc,
+ FAR usbhost_ep_t *ep)
+{
+ FAR struct stm32_usbhost_s *priv = (FAR struct stm32_usbhost_s *)drvr;
+ FAR struct stm32_chan_s *chan;
+ int chidx;
+ int ret;
+
+ /* Sanity check. NOTE that this method should only be called if a device is
+ * connected (because we need a valid low speed indication).
+ */
+
+ DEBUGASSERT(priv && epdesc && ep && priv->connected);
+
+ /* We must have exclusive access to the USB host hardware and state structures */
+
+ stm32_takesem(&priv->exclsem);
+
+ /* Allocate a host channel for the endpoint */
+
+ chidx = stm32_chan_alloc(priv);
+ if (chidx < 0)
+ {
+ udbg("Failed to allocate a host channel\n");
+ ret = -ENOMEM;
+ goto errout;
+ }
+
+ /* Decode the endpoint descriptor to initialize the channel data structures.
+ * Note: Here we depend on the fact that the endpoint point type is
+ * encoded in the same way in the endpoint descriptor as it is in the OTG
+ * FS hardware.
+ */
+
+ chan = &priv->chan[chidx];
+ chan->epno = epdesc->addr & USB_EPNO_MASK;
+ chan->in = epdesc->in;
+ chan->eptype = epdesc->xfrtype;
+ chan->maxpacket = epdesc->mxpacketsize;
+ chan->indata1 = false;
+ chan->outdata1 = false;
+
+ /* Then configure the endpoint */
+
+ stm32_chan_configure(priv, chidx) ;
+
+ /* Return the index to the allocated channel as the endpoint "handle" */
+
+ *ep = (usbhost_ep_t)chidx;
+ ret = OK;
+
+errout:
+ stm32_givesem(&priv->exclsem);
+ return ret;
+}
+
+/************************************************************************************
+ * Name: stm32_epfree
+ *
+ * Description:
+ * Free and endpoint previously allocated by DRVR_EPALLOC.
+ *
+ * Input Parameters:
+ * drvr - The USB host driver instance obtained as a parameter from the call to
+ * the class create() method.
+ * ep - The endpint to be freed.
+ *
+ * Returned Values:
+ * On success, zero (OK) is returned. On a failure, a negated errno value is
+ * returned indicating the nature of the failure
+ *
+ * Assumptions:
+ * This function will *not* be called from an interrupt handler.
+ *
+ ************************************************************************************/
+
+static int stm32_epfree(FAR struct usbhost_driver_s *drvr, usbhost_ep_t ep)
+{
+ struct stm32_usbhost_s *priv = (struct stm32_usbhost_s *)drvr;
+ int chidx = (int)ep;
+
+ DEBUGASSERT(priv && chidx < STM32_MAX_TX_FIFOS);
+
+ /* We must have exclusive access to the USB host hardware and state structures */
+
+ stm32_takesem(&priv->exclsem);
+
+ /* Halt the channel and mark the channel avaiable */
+
+ stm32_chan_free(priv, chidx);
+
+ stm32_givesem(&priv->exclsem);
+ return OK;
+}
+
+/*******************************************************************************
+ * Name: stm32_alloc
+ *
+ * Description:
+ * Some hardware supports special memory in which request and descriptor data can
+ * be accessed more efficiently. This method provides a mechanism to allocate
+ * the request/descriptor memory. If the underlying hardware does not support
+ * such "special" memory, this functions may simply map to kmalloc.
+ *
+ * This interface was optimized under a particular assumption. It was assumed
+ * that the driver maintains a pool of small, pre-allocated buffers for descriptor
+ * traffic. NOTE that size is not an input, but an output: The size of the
+ * pre-allocated buffer is returned.
+ *
+ * Input Parameters:
+ * drvr - The USB host driver instance obtained as a parameter from the call to
+ * the class create() method.
+ * buffer - The address of a memory location provided by the caller in which to
+ * return the allocated buffer memory address.
+ * maxlen - The address of a memory location provided by the caller in which to
+ * return the maximum size of the allocated buffer memory.
+ *
+ * Returned Values:
+ * On success, zero (OK) is returned. On a failure, a negated errno value is
+ * returned indicating the nature of the failure
+ *
+ * Assumptions:
+ * - Called from a single thread so no mutual exclusion is required.
+ * - Never called from an interrupt handler.
+ *
+ *******************************************************************************/
+
+static int stm32_alloc(FAR struct usbhost_driver_s *drvr,
+ FAR uint8_t **buffer, FAR size_t *maxlen)
+{
+ FAR uint8_t *alloc;
+
+ DEBUGASSERT(drvr && buffer && maxlen);
+
+ /* There is no special memory requirement for the STM32. */
+
+ alloc = (FAR uint8_t *)kmalloc(CONFIG_STM32_OTGFS_DESCSIZE);
+ if (!alloc)
+ {
+ return -ENOMEM;
+ }
+
+ /* Return the allocated address and size of the descriptor buffer */
+
+ *buffer = alloc;
+ *maxlen = CONFIG_STM32_OTGFS_DESCSIZE;
+ return OK;
+}
+
+/*******************************************************************************
+ * Name: stm32_free
+ *
+ * Description:
+ * Some hardware supports special memory in which request and descriptor data can
+ * be accessed more efficiently. This method provides a mechanism to free that
+ * request/descriptor memory. If the underlying hardware does not support
+ * such "special" memory, this functions may simply map to kfree().
+ *
+ * Input Parameters:
+ * drvr - The USB host driver instance obtained as a parameter from the call to
+ * the class create() method.
+ * buffer - The address of the allocated buffer memory to be freed.
+ *
+ * Returned Values:
+ * On success, zero (OK) is returned. On a failure, a negated errno value is
+ * returned indicating the nature of the failure
+ *
+ * Assumptions:
+ * - Never called from an interrupt handler.
+ *
+ *******************************************************************************/
+
+static int stm32_free(FAR struct usbhost_driver_s *drvr, FAR uint8_t *buffer)
+{
+ /* There is no special memory requirement */
+
+ DEBUGASSERT(drvr && buffer);
+ kfree(buffer);
+ return OK;
+}
+
+/************************************************************************************
+ * Name: stm32_ioalloc
+ *
+ * Description:
+ * Some hardware supports special memory in which larger IO buffers can
+ * be accessed more efficiently. This method provides a mechanism to allocate
+ * the request/descriptor memory. If the underlying hardware does not support
+ * such "special" memory, this functions may simply map to kmalloc.
+ *
+ * This interface differs from DRVR_ALLOC in that the buffers are variable-sized.
+ *
+ * Input Parameters:
+ * drvr - The USB host driver instance obtained as a parameter from the call to
+ * the class create() method.
+ * buffer - The address of a memory location provided by the caller in which to
+ * return the allocated buffer memory address.
+ * buflen - The size of the buffer required.
+ *
+ * Returned Values:
+ * On success, zero (OK) is returned. On a failure, a negated errno value is
+ * returned indicating the nature of the failure
+ *
+ * Assumptions:
+ * This function will *not* be called from an interrupt handler.
+ *
+ ************************************************************************************/
+
+static int stm32_ioalloc(FAR struct usbhost_driver_s *drvr,
+ FAR uint8_t **buffer, size_t buflen)
+{
+ FAR uint8_t *alloc;
+
+ DEBUGASSERT(drvr && buffer && buflen > 0);
+
+ /* There is no special memory requirement */
+
+ alloc = (FAR uint8_t *)kmalloc(buflen);
+ if (!alloc)
+ {
+ return -ENOMEM;
+ }
+
+ /* Return the allocated buffer */
+
+ *buffer = alloc;
+ return OK;
+}
+
+/************************************************************************************
+ * Name: stm32_iofree
+ *
+ * Description:
+ * Some hardware supports special memory in which IO data can be accessed more
+ * efficiently. This method provides a mechanism to free that IO buffer
+ * memory. If the underlying hardware does not support such "special" memory,
+ * this functions may simply map to kfree().
+ *
+ * Input Parameters:
+ * drvr - The USB host driver instance obtained as a parameter from the call to
+ * the class create() method.
+ * buffer - The address of the allocated buffer memory to be freed.
+ *
+ * Returned Values:
+ * On success, zero (OK) is returned. On a failure, a negated errno value is
+ * returned indicating the nature of the failure
+ *
+ * Assumptions:
+ * This function will *not* be called from an interrupt handler.
+ *
+ ************************************************************************************/
+
+static int stm32_iofree(FAR struct usbhost_driver_s *drvr, FAR uint8_t *buffer)
+{
+ /* There is no special memory requirement */
+
+ DEBUGASSERT(drvr && buffer);
+ kfree(buffer);
+ return OK;
+}
+
+/*******************************************************************************
+ * Name: stm32_ctrlin and stm32_ctrlout
+ *
+ * Description:
+ * Process a IN or OUT request on the control endpoint. These methods
+ * will enqueue the request and wait for it to complete. Only one transfer may be
+ * queued; Neither these methods nor the transfer() method can be called again
+ * until the control transfer functions returns.
+ *
+ * These are blocking methods; these functions will not return until the
+ * control transfer has completed.
+ *
+ * Input Parameters:
+ * drvr - The USB host driver instance obtained as a parameter from the call to
+ * the class create() method.
+ * req - Describes the request to be sent. This request must lie in memory
+ * created by DRVR_ALLOC.
+ * buffer - A buffer used for sending the request and for returning any
+ * responses. This buffer must be large enough to hold the length value
+ * in the request description. buffer must have been allocated using DRVR_ALLOC
+ *
+ * NOTE: On an IN transaction, req and buffer may refer to the same allocated
+ * memory.
+ *
+ * Returned Values:
+ * On success, zero (OK) is returned. On a failure, a negated errno value is
+ * returned indicating the nature of the failure
+ *
+ * Assumptions:
+ * - Only a single class bound to a single device is supported.
+ * - Called from a single thread so no mutual exclusion is required.
+ * - Never called from an interrupt handler.
+ *
+ *******************************************************************************/
+
+static int stm32_ctrlin(FAR struct usbhost_driver_s *drvr,
+ FAR const struct usb_ctrlreq_s *req,
+ FAR uint8_t *buffer)
+{
+ struct stm32_usbhost_s *priv = (struct stm32_usbhost_s *)drvr;
+ uint16_t buflen;
+ int retries;
+ int ret;
+
+ DEBUGASSERT(drvr && req);
+ uvdbg("type:%02x req:%02x value:%02x%02x index:%02x%02x len:%02x%02x\n",
+ req->type, req->req, req->value[1], req->value[0],
+ req->index[1], req->index[0], req->len[1], req->len[0]);
+
+ /* Extract values from the request */
+
+ buflen = stm32_getle16(req->len);
+
+ /* We must have exclusive access to the USB host hardware and state structures */
+
+ stm32_takesem(&priv->exclsem);
+
+ /* Loop, retrying until the retry count expires */
+
+ for (retries = 0; retries < STM32_RETRY_COUNT; retries++)
+ {
+ /* Send the SETUP request */
+
+ ret = stm32_ctrl_sendsetup(priv, req);
+ if (ret < 0)
+ {
+ udbg("stm32_ctrl_sendsetup failed: %d\n", ret);
+ return ret;
+ }
+
+ /* Handle the IN data phase (if any) */
+
+ if (buflen > 0)
+ {
+ ret = stm32_ctrl_recvdata(priv, buffer, buflen);
+ if (ret < 0)
+ {
+ udbg("stm32_ctrl_recvdata failed: %d\n", ret);
+ continue;
+ }
+ }
+
+ /* Handle the status OUT phase */
+
+ priv->chan[priv->ep0out].outdata1 ^= true;
+ ret = stm32_ctrl_senddata(priv, NULL, 0);
+ if (ret == OK)
+ {
+ break;
+ }
+
+ udbg("stm32_ctrl_senddata failed: %d\n", ret);
+ ret = -ETIMEDOUT;
+ }
+
+ stm32_givesem(&priv->exclsem);
+ return ret;
+}
+
+static int stm32_ctrlout(FAR struct usbhost_driver_s *drvr,
+ FAR const struct usb_ctrlreq_s *req,
+ FAR const uint8_t *buffer)
+{
+ struct stm32_usbhost_s *priv = (struct stm32_usbhost_s *)drvr;
+ uint16_t buflen;
+ int retries;
+ int ret;
+
+ DEBUGASSERT(drvr && req);
+ uvdbg("type:%02x req:%02x value:%02x%02x index:%02x%02x len:%02x%02x\n",
+ req->type, req->req, req->value[1], req->value[0],
+ req->index[1], req->index[0], req->len[1], req->len[0]);
+
+ /* Extract values from the request */
+
+ buflen = stm32_getle16(req->len);
+
+ /* We must have exclusive access to the USB host hardware and state structures */
+
+ stm32_takesem(&priv->exclsem);
+
+ /* Loop, retrying until the retry count expires */
+
+ for (retries = 0; retries < STM32_RETRY_COUNT; retries++)
+ {
+ /* Send the SETUP request */
+
+ ret = stm32_ctrl_sendsetup(priv, req);
+ if (ret < 0)
+ {
+ udbg("stm32_ctrl_sendsetup failed: %d\n", ret);
+ continue;
+ }
+
+ /* Handle the data OUT phase (if any) */
+
+ if (buflen > 0)
+ {
+ /* Start DATA out transfer (only one DATA packet) */
+
+ priv->chan[priv->ep0out].outdata1 = true;
+ ret = stm32_ctrl_senddata(priv, NULL, 0);
+ if (ret < 0)
+ {
+ udbg("stm32_ctrl_senddata failed: %d\n", ret);
+ continue;
+ }
+ }
+
+ /* Handle the status IN phase */
+
+ ret = stm32_ctrl_recvdata(priv, NULL, 0);
+ if (ret == OK)
+ {
+ break;
+ }
+
+ udbg("stm32_ctrl_recvdata failed: %d\n", ret);
+ ret = -ETIMEDOUT;
+ }
+
+ stm32_givesem(&priv->exclsem);
+ return ret;
+}
+
+/*******************************************************************************
+ * Name: stm32_transfer
+ *
+ * Description:
+ * Process a request to handle a transfer descriptor. This method will
+ * enqueue the transfer request and return immediately. Only one transfer may be
+ * queued; Neither this method nor the ctrlin or ctrlout methods can be called
+ * again until this function returns.
+ *
+ * This is a blocking method; this functions will not return until the
+ * transfer has completed.
+ *
+ * Input Parameters:
+ * drvr - The USB host driver instance obtained as a parameter from the call to
+ * the class create() method.
+ * ep - The IN or OUT endpoint descriptor for the device endpoint on which to
+ * perform the transfer.
+ * buffer - A buffer containing the data to be sent (OUT endpoint) or received
+ * (IN endpoint). buffer must have been allocated using DRVR_ALLOC
+ * buflen - The length of the data to be sent or received.
+ *
+ * Returned Values:
+ * On success, zero (OK) is returned. On a failure, a negated errno value is
+ * returned indicating the nature of the failure:
+ *
+ * EAGAIN - If devices NAKs the transfer (or NYET or other error where
+ * it may be appropriate to restart the entire transaction).
+ * EPERM - If the endpoint stalls
+ * EIO - On a TX or data toggle error
+ * EPIPE - Overrun errors
+ *
+ * Assumptions:
+ * - Only a single class bound to a single device is supported.
+ * - Called from a single thread so no mutual exclusion is required.
+ * - Never called from an interrupt handler.
+ *
+ *******************************************************************************/
+
+static int stm32_transfer(FAR struct usbhost_driver_s *drvr, usbhost_ep_t ep,
+ FAR uint8_t *buffer, size_t buflen)
+{
+ struct stm32_usbhost_s *priv = (struct stm32_usbhost_s *)drvr;
+ FAR struct stm32_chan_s *chan;
+ unsigned int chidx = (unsigned int)ep;
+ int ret = OK;
+
+ uvdbg("chidx: %d buflen: %d\n", (unsigned int)ep, buflen);
+
+ DEBUGASSERT(priv && buffer && chidx < STM32_MAX_TX_FIFOS && buflen > 0);
+ chan = &priv->chan[chidx];
+
+ /* We must have exclusive access to the USB host hardware and state structures */
+
+ stm32_takesem(&priv->exclsem);
+
+ /* Loop until the transfer completes (i.e., buflen is decremented to zero)
+ * or a fatal error occurs (any error other than a simple NAK)
+ */
+
+ chan->buffer = buffer;
+ chan->buflen = buflen;
+
+ while (chan->buflen > 0)
+ {
+ /* Set up for the wait BEFORE starting the transfer */
+
+ ret = stm32_chan_waitsetup(priv, chan);
+ if (ret != OK)
+ {
+ udbg("ERROR: Device disconnected\n");
+ goto errout;
+ }
+
+ /* Set up for the transfer based on the direction and the endpoint type */
+
+ switch (chan->eptype)
+ {
+ default:
+ case OTGFS_EPTYPE_CTRL: /* Control */
+ {
+ /* This kind of transfer on control endpoints other than EP0 are not
+ * currently supported
+ */
+
+ ret = -ENOSYS;
+ goto errout;
+ }
+
+ case OTGFS_EPTYPE_ISOC: /* Isochronous */
+ {
+ /* Set up the IN/OUT data PID */
+
+ chan->pid = OTGFS_PID_DATA0;
+ }
+ break;
+
+ case OTGFS_EPTYPE_BULK: /* Bulk */
+ {
+ /* Handle the bulk transfer based on the direction of the transfer. */
+
+ if (chan->in)
+ {
+ /* Setup the IN data PID */
+
+ chan->pid = chan->indata1 ? OTGFS_PID_DATA1 : OTGFS_PID_DATA0;
+ }
+ else
+ {
+ /* Setup the OUT data PID */
+
+ chan->pid = chan->outdata1 ? OTGFS_PID_DATA1 : OTGFS_PID_DATA0;
+ }
+ }
+ break;
+
+ case OTGFS_EPTYPE_INTR: /* Interrupt */
+ {
+ /* Handle the interrupt transfer based on the direction of the
+ * transfer.
+ */
+
+ if (chan->in)
+ {
+ /* Setup the IN data PID */
+
+ chan->pid = chan->indata1 ? OTGFS_PID_DATA1 : OTGFS_PID_DATA0;
+
+ /* The indata1 data toggle will be updated in the Rx FIFO
+ * interrupt handling logic as each packet is received.
+ */
+ }
+ else
+ {
+ /* Setup the OUT data PID */
+
+ chan->pid = chan->outdata1 ? OTGFS_PID_DATA1 : OTGFS_PID_DATA0;
+
+ /* Toggle the OUT data PID for the next transfer */
+
+ chan->outdata1 ^= true;
+ }
+ }
+ }
+
+ /* Start the transfer */
+
+ stm32_transfer_start(priv, chidx);
+
+ /* Wait for the transfer to complete and get the result */
+
+ ret = stm32_chan_wait(priv, chan);
+
+ /* EAGAIN indicates that the device NAKed the transfer and we need
+ * do try again. Anything else (success or other errors) will
+ * cause use to return
+ */
+
+ if (ret != OK)
+ {
+ udbg("Transfer failed: %d\n", ret);
+ break;
+ }
+ }
+
+errout:
+ stm32_givesem(&priv->exclsem);
+ return ret;
+}
+
+/*******************************************************************************
+ * Name: stm32_disconnect
+ *
+ * Description:
+ * Called by the class when an error occurs and driver has been disconnected.
+ * The USB host driver should discard the handle to the class instance (it is
+ * stale) and not attempt any further interaction with the class driver instance
+ * (until a new instance is received from the create() method). The driver
+ * should not called the class' disconnected() method.
+ *
+ * Input Parameters:
+ * drvr - The USB host driver instance obtained as a parameter from the call to
+ * the class create() method.
+ *
+ * Returned Values:
+ * None
+ *
+ * Assumptions:
+ * - Only a single class bound to a single device is supported.
+ * - Never called from an interrupt handler.
+ *
+ *******************************************************************************/
+
+static void stm32_disconnect(FAR struct usbhost_driver_s *drvr)
+{
+ struct stm32_usbhost_s *priv = (struct stm32_usbhost_s *)drvr;
+ priv->class = NULL;
+}
+
+/*******************************************************************************
+ * Initialization
+ *******************************************************************************/
+/*******************************************************************************
+ * Name: stm32_portreset
+ *
+ * Description:
+ * Reset the USB host port.
+ *
+ * NOTE: "Before starting to drive a USB reset, the application waits for the
+ * OTG interrupt triggered by the debounce done bit (DBCDNE bit in
+ * OTG_FS_GOTGINT), which indicates that the bus is stable again after the
+ * electrical debounce caused by the attachment of a pull-up resistor on DP
+ * (FS) or DM (LS).
+ *
+ * Input Parameters:
+ * priv -- USB host driver private data structure.
+ *
+ * Returned Value:
+ * None
+ *
+ *******************************************************************************/
+
+static void stm32_portreset(FAR struct stm32_usbhost_s *priv)
+{
+ uint32_t regval;
+
+ regval = stm32_getreg(STM32_OTGFS_HPRT);
+ regval &= ~(OTGFS_HPRT_PENA|OTGFS_HPRT_PCDET|OTGFS_HPRT_PENCHNG|OTGFS_HPRT_POCCHNG);
+ regval |= OTGFS_HPRT_PRST;
+ stm32_putreg(STM32_OTGFS_HPRT, regval);
+
+ up_mdelay(10);
+
+ regval &= ~OTGFS_HPRT_PRST;
+ stm32_putreg(STM32_OTGFS_HPRT, regval);
+
+ up_mdelay(20);
+}
+
+/*******************************************************************************
+ * Name: stm32_flush_txfifos
+ *
+ * Description:
+ * Flush the selected Tx FIFO.
+ *
+ * Input Parameters:
+ * priv -- USB host driver private data structure.
+ *
+ * Returned Value:
+ * None.
+ *
+ *******************************************************************************/
+
+static inline void stm32_flush_txfifos(uint32_t txfnum)
+{
+ uint32_t regval;
+ uint32_t timeout;
+
+ /* Initiate the TX FIFO flush operation */
+
+ regval = OTGFS_GRSTCTL_TXFFLSH | txfnum;
+ stm32_putreg(regval, STM32_OTGFS_GRSTCTL);
+
+ /* Wait for the FLUSH to complete */
+
+ for (timeout = 0; timeout < STM32_FLUSH_DELAY; timeout++)
+ {
+ regval = stm32_getreg(STM32_OTGFS_GRSTCTL);
+ if ((regval & OTGFS_GRSTCTL_TXFFLSH) == 0)
+ {
+ break;
+ }
+ }
+
+ /* Wait for 3 PHY Clocks */
+
+ up_udelay(3);
+}
+
+/*******************************************************************************
+ * Name: stm32_flush_rxfifo
+ *
+ * Description:
+ * Flush the Rx FIFO.
+ *
+ * Input Parameters:
+ * priv -- USB host driver private data structure.
+ *
+ * Returned Value:
+ * None.
+ *
+ *******************************************************************************/
+
+static inline void stm32_flush_rxfifo(void)
+{
+ uint32_t regval;
+ uint32_t timeout;
+
+ /* Initiate the RX FIFO flush operation */
+
+ stm32_putreg(OTGFS_GRSTCTL_RXFFLSH, STM32_OTGFS_GRSTCTL);
+
+ /* Wait for the FLUSH to complete */
+
+ for (timeout = 0; timeout < STM32_FLUSH_DELAY; timeout++)
+ {
+ regval = stm32_getreg(STM32_OTGFS_GRSTCTL);
+ if ((regval & OTGFS_GRSTCTL_RXFFLSH) == 0)
+ {
+ break;
+ }
+ }
+
+ /* Wait for 3 PHY Clocks */
+
+ up_udelay(3);
+}
+
+/*******************************************************************************
+ * Name: stm32_vbusdrive
+ *
+ * Description:
+ * Drive the Vbus +5V.
+ *
+ * Input Parameters:
+ * priv - USB host driver private data structure.
+ * state - True: Drive, False: Don't drive
+ *
+ * Returned Value:
+ * None.
+ *
+ *******************************************************************************/
+
+static void stm32_vbusdrive(FAR struct stm32_usbhost_s *priv, bool state)
+{
+ uint32_t regval;
+
+ /* Enable/disable the external charge pump */
+
+ stm32_usbhost_vbusdrive(0, state);
+
+ /* Turn on the Host port power. */
+
+ regval = stm32_getreg(STM32_OTGFS_HPRT);
+ regval &= ~(OTGFS_HPRT_PENA|OTGFS_HPRT_PCDET|OTGFS_HPRT_PENCHNG|OTGFS_HPRT_POCCHNG);
+
+ if (((regval & OTGFS_HPRT_PPWR) == 0) && state)
+ {
+ regval |= OTGFS_HPRT_PPWR;
+ stm32_putreg(STM32_OTGFS_HPRT, regval);
+ }
+
+ if (((regval & OTGFS_HPRT_PPWR) != 0) && !state)
+ {
+ regval &= ~OTGFS_HPRT_PPWR;
+ stm32_putreg(STM32_OTGFS_HPRT, regval);
+ }
+
+ up_mdelay(200);
+}
+
+/*******************************************************************************
+ * Name: stm32_host_initialize
+ *
+ * Description:
+ * Initialize/re-initialize hardware for host mode operation. At present,
+ * this function is called only from stm32_hw_initialize(). But if OTG mode
+ * were supported, this function would also be called to swtich between
+ * host and device modes on a connector ID change interrupt.
+ *
+ * Input Parameters:
+ * priv -- USB host driver private data structure.
+ *
+ * Returned Value:
+ * None.
+ *
+ *******************************************************************************/
+
+static void stm32_host_initialize(FAR struct stm32_usbhost_s *priv)
+{
+ uint32_t regval;
+ uint32_t offset;
+ int i;
+
+ /* Restart the PHY Clock */
+
+ stm32_putreg(STM32_OTGFS_PCGCCTL, 0);
+
+ /* Initialize Host Configuration (HCFG) register */
+
+ regval = stm32_getreg(STM32_OTGFS_HCFG);
+ regval &= ~OTGFS_HCFG_FSLSPCS_MASK;
+ regval |= OTGFS_HCFG_FSLSPCS_FS48MHz;
+ stm32_putreg(STM32_OTGFS_HCFG, regval);
+
+ /* Reset the host port */
+
+ stm32_portreset(priv);
+
+ /* Clear the FS-/LS-only support bit in the HCFG register */
+
+ regval = stm32_getreg(STM32_OTGFS_HCFG);
+ regval &= ~OTGFS_HCFG_FSLSS;
+ stm32_putreg(STM32_OTGFS_HCFG, regval);
+
+ /* Carve up FIFO memory for the Rx FIFO and the periodic and non-periodic Tx FIFOs */
+ /* Configure Rx FIFO size (GRXFSIZ) */
+
+ stm32_putreg(STM32_OTGFS_GRXFSIZ, CONFIG_STM32_OTGFS_RXFIFO_SIZE);
+ offset = CONFIG_STM32_OTGFS_RXFIFO_SIZE;
+
+ /* Setup the host non-periodic Tx FIFO size (HNPTXFSIZ) */
+
+ regval = (offset | (CONFIG_STM32_OTGFS_NPTXFIFO_SIZE << OTGFS_HNPTXFSIZ_NPTXFD_SHIFT));
+ stm32_putreg(STM32_OTGFS_HNPTXFSIZ, regval);
+ offset += CONFIG_STM32_OTGFS_NPTXFIFO_SIZE;
+
+ /* Set up the host periodic Tx fifo size register (HPTXFSIZ) */
+
+ regval = (offset | (CONFIG_STM32_OTGFS_PTXFIFO_SIZE << OTGFS_HPTXFSIZ_PTXFD_SHIFT));
+ stm32_putreg(STM32_OTGFS_HPTXFSIZ, regval);
+
+ /* If OTG were supported, we sould need to clear HNP enable bit in the
+ * USB_OTG control register about here.
+ */
+
+ /* Flush all FIFOs */
+
+ stm32_flush_txfifos(OTGFS_GRSTCTL_TXFNUM_HALL);
+ stm32_flush_rxfifo();
+
+ /* Clear all pending HC Interrupts */
+
+ for (i = 0; i < STM32_NHOST_CHANNELS; i++)
+ {
+ stm32_putreg(STM32_OTGFS_HCINT(i), 0xffffffff);
+ stm32_putreg(STM32_OTGFS_HCINTMSK(i), 0);
+ }
+
+ /* Driver Vbus +5V (the smoke test). Should be done elsewhere in OTG
+ * mode.
+ */
+
+ stm32_vbusdrive(priv, true);
+
+ /* Enable host interrupts */
+
+ stm32_hostinit_enable();
+}
+
+/*******************************************************************************
+ * Name: stm32_sw_initialize
+ *
+ * Description:
+ * One-time setup of the host driver state structure.
+ *
+ * Input Parameters:
+ * priv -- USB host driver private data structure.
+ *
+ * Returned Value:
+ * None.
+ *
+ *******************************************************************************/
+
+static inline void stm32_sw_initialize(FAR struct stm32_usbhost_s *priv)
+{
+ int i;
+
+ /* Initialize the state data structure */
+
+ sem_init(&priv->eventsem, 0, 0);
+ sem_init(&priv->exclsem, 0, 1);
+
+ priv->smstate = SMSTATE_DETACHED;
+ priv->ep0size = STM32_EP0_MAX_PACKET_SIZE;
+ priv->devaddr = STM32_DEF_DEVADDR;
+ priv->connected = false;
+ priv->lowspeed = false;
+
+ /* Put all of the channels back in their initial, allocated state */
+
+ memset(priv->chan, 0, STM32_MAX_TX_FIFOS * sizeof(struct stm32_chan_s));
+
+ /* Initialize each channel */
+
+ for (i = 0; i < STM32_MAX_TX_FIFOS; i++)
+ {
+ FAR struct stm32_chan_s *chan = &priv->chan[i];
+ sem_init(&chan->waitsem, 0, 0);
+ }
+}
+
+/*******************************************************************************
+ * Name: stm32_hw_initialize
+ *
+ * Description:
+ * One-time setup of the host controller harware for normal operations.
+ *
+ * Input Parameters:
+ * priv -- USB host driver private data structure.
+ *
+ * Returned Value:
+ * Zero on success; a negated errno value on failure.
+ *
+ *******************************************************************************/
+
+static inline int stm32_hw_initialize(FAR struct stm32_usbhost_s *priv)
+{
+ uint32_t regval;
+ unsigned long timeout;
+
+ /* Set the PHYSEL bit in the GUSBCFG register to select the OTG FS serial
+ * transceiver: "This bit is always 1 with write-only access"
+ */
+
+ regval = stm32_getreg(STM32_OTGFS_GUSBCFG);;
+ regval |= OTGFS_GUSBCFG_PHYSEL;
+ stm32_putreg(STM32_OTGFS_GUSBCFG, regval);
+
+ /* Reset after a PHY select and set Host mode. First, wait for AHB master
+ * IDLE state.
+ */
+
+ for (timeout = 0; timeout < STM32_READY_DELAY; timeout++)
+ {
+ up_udelay(3);
+ regval = stm32_getreg(STM32_OTGFS_GRSTCTL);
+ if ((regval & OTGFS_GRSTCTL_AHBIDL) != 0)
+ {
+ break;
+ }
+ }
+
+ /* Then perform the core soft reset. */
+
+ stm32_putreg(STM32_OTGFS_GRSTCTL, OTGFS_GRSTCTL_CSRST);
+ for (timeout = 0; timeout < STM32_READY_DELAY; timeout++)
+ {
+ regval = stm32_getreg(STM32_OTGFS_GRSTCTL);
+ if ((regval & OTGFS_GRSTCTL_CSRST) == 0)
+ {
+ break;
+ }
+ }
+
+ /* Wait for 3 PHY Clocks */
+
+ up_udelay(3);
+
+ /* Deactivate the power down */
+
+ regval = (OTGFS_GCCFG_PWRDWN | OTGFS_GCCFG_VBUSASEN | OTGFS_GCCFG_VBUSBSEN);
+#ifndef CONFIG_USBDEV_VBUSSENSING
+ regval |= OTGFS_GCCFG_NOVBUSSENS;
+#endif
+#ifdef CONFIG_STM32_OTGFS_SOFOUTPUT
+ regval |= OTGFS_GCCFG_SOFOUTEN;
+#endif
+ stm32_putreg(STM32_OTGFS_GCCFG, regval);
+ up_mdelay(20);
+
+ /* Initialize OTG features: In order to support OTP, the HNPCAP and SRPCAP
+ * bits would need to be set in the GUSBCFG register about here.
+ */
+
+ /* Force Host Mode */
+
+ regval = stm32_getreg(STM32_OTGFS_GUSBCFG);
+ regval &= ~OTGFS_GUSBCFG_FDMOD;
+ regval |= OTGFS_GUSBCFG_FHMOD;
+ stm32_putreg(STM32_OTGFS_GUSBCFG, regval);
+ up_mdelay(50);
+
+ /* Initialize host mode and return success */
+
+ stm32_host_initialize(priv);
+ return OK;
+}
+
+/*******************************************************************************
+ * Public Functions
+ *******************************************************************************/
+
+/*******************************************************************************
+ * Name: usbhost_initialize
+ *
+ * Description:
+ * Initialize USB host device controller hardware.
+ *
+ * Input Parameters:
+ * controller -- If the device supports more than USB host controller, then
+ * this identifies which controller is being intialized. Normally, this
+ * is just zero.
+ *
+ * Returned Value:
+ * And instance of the USB host interface. The controlling task should
+ * use this interface to (1) call the wait() method to wait for a device
+ * to be connected, and (2) call the enumerate() method to bind the device
+ * to a class driver.
+ *
+ * Assumptions:
+ * - This function should called in the initialization sequence in order
+ * to initialize the USB device functionality.
+ * - Class drivers should be initialized prior to calling this function.
+ * Otherwise, there is a race condition if the device is already connected.
+ *
+ *******************************************************************************/
+
+FAR struct usbhost_driver_s *usbhost_initialize(int controller)
+{
+ /* At present, there is only support for a single OTG FS host. Hence it is
+ * pre-allocated as g_usbhost. However, in most code, the private data
+ * structure will be referenced using the 'priv' pointer (rather than the
+ * global data) in order to simplify any future support for multiple devices.
+ */
+
+ FAR struct stm32_usbhost_s *priv = &g_usbhost;
+
+ /* Sanity checks */
+
+ DEBUGASSERT(controller == 0);
+
+ /* Make sure that interrupts from the OTG FS core are disabled */
+
+ stm32_gint_disable();
+
+ /* Reset the state of the host driver */
+
+ stm32_sw_initialize(priv);
+
+ /* Alternate function pin configuration. Here we assume that:
+ *
+ * 1. GPIOA, SYSCFG, and OTG FS peripheral clocking have already been\
+ * enabled as part of the boot sequence.
+ * 2. Board-specific logic has already enabled other board specific GPIOs
+ * for things like soft pull-up, VBUS sensing, power controls, and over-
+ * current detection.
+ */
+
+ /* Configure OTG FS alternate function pins for DM, DP, ID, and SOF.
+ *
+ * PIN* SIGNAL DIRECTION
+ * ---- ----------- ----------
+ * PA8 OTG_FS_SOF SOF clock output
+ * PA9 OTG_FS_VBUS VBUS input for device, Driven by external regulator by
+ * host (not an alternate function)
+ * PA10 OTG_FS_ID OTG ID pin (only needed in Dual mode)
+ * PA11 OTG_FS_DM D- I/O
+ * PA12 OTG_FS_DP D+ I/O
+ *
+ * *Pins may vary from device-to-device.
+ */
+
+ stm32_configgpio(GPIO_OTGFS_DM);
+ stm32_configgpio(GPIO_OTGFS_DP);
+ stm32_configgpio(GPIO_OTGFS_ID); /* Only needed for OTG */
+
+ /* SOF output pin configuration is configurable */
+
+#ifdef CONFIG_STM32_OTGFS_SOFOUTPUT
+ stm32_configgpio(GPIO_OTGFS_SOF);
+#endif
+
+ /* Initialize the USB OTG FS core */
+
+ stm32_hw_initialize(priv);
+
+ /* Attach USB host controller interrupt handler */
+
+ if (irq_attach(STM32_IRQ_OTGFS, stm32_gint_isr) != 0)
+ {
+ udbg("Failed to attach IRQ\n");
+ return NULL;
+ }
+
+ /* Enable USB OTG FS global interrupts */
+
+ stm32_gint_enable();
+
+ /* Enable interrupts at the interrupt controller */
+
+ up_enable_irq(STM32_IRQ_OTGFS);
+ return &priv->drvr;
+}
+
+#endif /* CONFIG_USBHOST && CONFIG_STM32_OTGFS */
diff --git a/nuttx/arch/arm/src/stm32/stm32_usbhost.c b/nuttx/arch/arm/src/stm32/stm32_usbhost.c
deleted file mode 100644
index 4bf6d646d..000000000
--- a/nuttx/arch/arm/src/stm32/stm32_usbhost.c
+++ /dev/null
@@ -1,2695 +0,0 @@
-/*******************************************************************************
- * arch/arm/src/stm32/stm32_usbhost.c
- *
- * Copyright (C) 2012 Gregory Nutt. All rights reserved.
- * Authors: 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>
-
-#include <sys/types.h>
-#include <stdint.h>
-#include <stdbool.h>
-#include <stdlib.h>
-#include <semaphore.h>
-#include <string.h>
-#include <errno.h>
-#include <debug.h>
-
-#include <nuttx/arch.h>
-#include <nuttx/usb/usb.h>
-#include <nuttx/usb/usbhost.h>
-
-#include <arch/irq.h>
-
-#include "chip.h" /* Includes default GPIO settings */
-#include <arch/board/board.h> /* May redefine GPIO settings */
-
-#include "up_arch.h"
-#include "up_internal.h"
-
-#include "stm32_usbhost.h"
-
-/*******************************************************************************
- * Definitions
- *******************************************************************************/
-
-/* Configuration ***************************************************************/
-
-/* All I/O buffers must lie in AHB SRAM because of the OHCI DMA. It might be
- * okay if no I/O buffers are used *IF* the application can guarantee that all
- * end-user I/O buffers reside in AHB SRAM.
- */
-
-#if STM32_IOBUFFERS < 1
-# warning "No IO buffers allocated"
-#endif
-
-/* OHCI Setup ******************************************************************/
-/* Frame Interval / Periodic Start */
-
-#define BITS_PER_FRAME 12000
-#define FI (BITS_PER_FRAME-1)
-#define FSMPS ((6 * (FI - 210)) / 7)
-#define DEFAULT_FMINTERVAL ((FSMPS << OHCI_FMINT_FSMPS_SHIFT) | FI)
-#define DEFAULT_PERSTART (((9 * BITS_PER_FRAME) / 10) - 1)
-
-/* CLKCTRL enable bits */
-
-#define STM32_CLKCTRL_ENABLES (USBOTG_CLK_HOSTCLK|USBOTG_CLK_PORTSELCLK|USBOTG_CLK_AHBCLK)
-
-/* Interrupt enable bits */
-
-#ifdef CONFIG_DEBUG_USB
-# define STM32_DEBUG_INTS (OHCI_INT_SO|OHCI_INT_RD|OHCI_INT_UE|OHCI_INT_OC)
-#else
-# define STM32_DEBUG_INTS 0
-#endif
-
-#define STM32_NORMAL_INTS (OHCI_INT_WDH|OHCI_INT_RHSC)
-#define STM32_ALL_INTS (STM32_NORMAL_INTS|STM32_DEBUG_INTS)
-
-/* Dump GPIO registers */
-
-#if defined(CONFIG_STM32_USBHOST_REGDEBUG) && defined(CONFIG_DEBUG_GPIO)
-# define usbhost_dumpgpio() \
- do { \
- stm32_dumpgpio(GPIO_USB_DP, "D+ P0.29; D- P0.30"); \
- stm32_dumpgpio(GPIO_USB_UPLED, "LED P1:18; PPWR P1:19 PWRD P1:22 PVRCR P1:27"); \
- } while (0);
-#else
-# define usbhost_dumpgpio()
-#endif
-
-/* USB Host Memory *************************************************************/
-
-/* Helper definitions */
-
-#define HCCA ((struct ohci_hcca_s *)STM32_HCCA_BASE)
-#define TDTAIL ((struct stm32_gtd_s *)STM32_TDTAIL_ADDR)
-#define EDCTRL ((struct stm32_ed_s *)STM32_EDCTRL_ADDR)
-
-/* Periodic intervals 2, 4, 8, 16,and 32 supported */
-
-#define MIN_PERINTERVAL 2
-#define MAX_PERINTERVAL 32
-
-/* Descriptors *****************************************************************/
-
-/* TD delay interrupt value */
-
-#define TD_DELAY(n) (uint32_t)((n) << GTD_STATUS_DI_SHIFT)
-
-/*******************************************************************************
- * Private Types
- *******************************************************************************/
-
-/* This structure retains the state of the USB host controller */
-
-struct stm32_usbhost_s
-{
- /* Common device fields. This must be the first thing defined in the
- * structure so that it is possible to simply cast from struct usbhost_s
- * to structstm32_usbhost_s.
- */
-
- struct usbhost_driver_s drvr;
-
- /* The bound device class driver */
-
- struct usbhost_class_s *class;
-
- /* Driver status */
-
- volatile bool connected; /* Connected to device */
- volatile bool lowspeed; /* Low speed device attached. */
- volatile bool rhswait; /* TRUE: Thread is waiting for Root Hub Status change */
-#ifndef CONFIG_USBHOST_INT_DISABLE
- uint8_t ininterval; /* Minimum periodic IN EP polling interval: 2, 4, 6, 16, or 32 */
- uint8_t outinterval; /* Minimum periodic IN EP polling interval: 2, 4, 6, 16, or 32 */
-#endif
- sem_t exclsem; /* Support mutually exclusive access */
- sem_t rhssem; /* Semaphore to wait Writeback Done Head event */
-};
-
-/* The OCHI expects the size of an endpoint descriptor to be 16 bytes.
- * However, the size allocated for an endpoint descriptor is 32 bytes in
- * stm32_ohciram.h. This extra 16-bytes is used by the OHCI host driver in
- * order to maintain additional endpoint-specific data.
- */
-
-struct stm32_ed_s
-{
- /* Hardware specific fields */
-
- struct ohci_ed_s hw;
-
- /* Software specific fields */
-
- uint8_t xfrtype; /* Transfer type. See SB_EP_ATTR_XFER_* in usb.h */
- uint8_t interval; /* Periodic EP polling interval: 2, 4, 6, 16, or 32 */
- volatile uint8_t tdstatus; /* TD control status bits from last Writeback Done Head event */
- volatile bool wdhwait; /* TRUE: Thread is waiting for WDH interrupt */
- sem_t wdhsem; /* Semaphore used to wait for Writeback Done Head event */
- /* Unused bytes follow, depending on the size of sem_t */
-};
-
-/* The OCHI expects the size of an transfer descriptor to be 16 bytes.
- * However, the size allocated for an endpoint descriptor is 32 bytes in
- * stm32_ohciram.h. This extra 16-bytes is used by the OHCI host driver in
- * order to maintain additional endpoint-specific data.
- */
-
-struct stm32_gtd_s
-{
- /* Hardware specific fields */
-
- struct ohci_gtd_s hw;
-
- /* Software specific fields */
-
- struct stm32_ed_s *ed; /* Pointer to parent ED */
- uint8_t pad[12];
-};
-
-/* The following is used to manage lists of free EDs, TDs, and TD buffers */
-
-struct stm32_list_s
-{
- struct stm32_list_s *flink; /* Link to next buffer in the list */
- /* Variable length buffer data follows */
-};
-
-/*******************************************************************************
- * Private Function Prototypes
- *******************************************************************************/
-
-/* Register operations ********************************************************/
-
-#ifdef CONFIG_STM32_USBHOST_REGDEBUG
-static void stm32_printreg(uint32_t addr, uint32_t val, bool iswrite);
-static void stm32_checkreg(uint32_t addr, uint32_t val, bool iswrite);
-static uint32_t stm32_getreg(uint32_t addr);
-static void stm32_putreg(uint32_t val, uint32_t addr);
-#else
-# define stm32_getreg(addr) getreg32(addr)
-# define stm32_putreg(val,addr) putreg32(val,addr)
-#endif
-
-/* Semaphores ******************************************************************/
-
-static void stm32_takesem(sem_t *sem);
-#define stm32_givesem(s) sem_post(s);
-
-/* Byte stream access helper functions *****************************************/
-
-static inline uint16_t stm32_getle16(const uint8_t *val);
-static void stm32_putle16(uint8_t *dest, uint16_t val);
-
-/* OHCI memory pool helper functions *******************************************/
-
-static inline void stm32_edfree(struct stm32_ed_s *ed);
-static struct stm32_gtd_s *stm32_tdalloc(void);
-static void stm32_tdfree(struct stm32_gtd_s *buffer);
-static uint8_t *stm32_tballoc(void);
-static void stm32_tbfree(uint8_t *buffer);
-#if STM32_IOBUFFERS > 0
-static uint8_t *stm32_allocio(void);
-static void stm32_freeio(uint8_t *buffer);
-#endif
-
-/* ED list helper functions ****************************************************/
-
-static inline int stm32_addbulked(struct stm32_usbhost_s *priv,
- struct stm32_ed_s *ed);
-static inline int stm32_rembulked(struct stm32_usbhost_s *priv,
- struct stm32_ed_s *ed);
-
-#if !defined(CONFIG_USBHOST_INT_DISABLE) || !defined(CONFIG_USBHOST_ISOC_DISABLE)
-static unsigned int stm32_getinterval(uint8_t interval);
-static void stm32_setinttab(uint32_t value, unsigned int interval, unsigned int offset);
-#endif
-
-static inline int stm32_addinted(struct stm32_usbhost_s *priv,
- const FAR struct usbhost_epdesc_s *epdesc,
- struct stm32_ed_s *ed);
-static inline int stm32_reminted(struct stm32_usbhost_s *priv,
- struct stm32_ed_s *ed);
-
-static inline int stm32_addisoced(struct stm32_usbhost_s *priv,
- const FAR struct usbhost_epdesc_s *epdesc,
- struct stm32_ed_s *ed);
-static inline int stm32_remisoced(struct stm32_usbhost_s *priv,
- struct stm32_ed_s *ed);
-
-/* Descriptor helper functions *************************************************/
-
-static int stm32_enqueuetd(struct stm32_usbhost_s *priv,
- struct stm32_ed_s *ed, uint32_t dirpid,
- uint32_t toggle, volatile uint8_t *buffer,
- size_t buflen);
-static int stm32_ctrltd(struct stm32_usbhost_s *priv, uint32_t dirpid,
- uint8_t *buffer, size_t buflen);
-
-/* Interrupt handling **********************************************************/
-
-static int stm32_usbinterrupt(int irq, FAR void *context);
-
-/* USB host controller operations **********************************************/
-
-static int stm32_wait(FAR struct usbhost_driver_s *drvr, bool connected);
-static int stm32_enumerate(FAR struct usbhost_driver_s *drvr);
-static int stm32_ep0configure(FAR struct usbhost_driver_s *drvr, uint8_t funcaddr,
- uint16_t maxpacketsize);
-static int stm32_epalloc(FAR struct usbhost_driver_s *drvr,
- const FAR struct usbhost_epdesc_s *epdesc, usbhost_ep_t *ep);
-static int stm32_epfree(FAR struct usbhost_driver_s *drvr, usbhost_ep_t ep);
-static int stm32_alloc(FAR struct usbhost_driver_s *drvr,
- FAR uint8_t **buffer, FAR size_t *maxlen);
-static int stm32_free(FAR struct usbhost_driver_s *drvr, FAR uint8_t *buffer);
-static int stm32_ioalloc(FAR struct usbhost_driver_s *drvr,
- FAR uint8_t **buffer, size_t buflen);
-static int stm32_iofree(FAR struct usbhost_driver_s *drvr, FAR uint8_t *buffer);
-static int stm32_ctrlin(FAR struct usbhost_driver_s *drvr,
- FAR const struct usb_ctrlreq_s *req,
- FAR uint8_t *buffer);
-static int stm32_ctrlout(FAR struct usbhost_driver_s *drvr,
- FAR const struct usb_ctrlreq_s *req,
- FAR const uint8_t *buffer);
-static int stm32_transfer(FAR struct usbhost_driver_s *drvr, usbhost_ep_t ep,
- FAR uint8_t *buffer, size_t buflen);
-static void stm32_disconnect(FAR struct usbhost_driver_s *drvr);
-
-/* Initialization **************************************************************/
-
-static inline void stm32_ep0init(struct stm32_usbhost_s *priv);
-
-/*******************************************************************************
- * Private Data
- *******************************************************************************/
-
-/* In this driver implementation, support is provided for only a single a single
- * USB device. All status information can be simply retained in a single global
- * instance.
- */
-
-static struct stm32_usbhost_s g_usbhost =
-{
- .drvr =
- {
- .wait = stm32_wait,
- .enumerate = stm32_enumerate,
- .ep0configure = stm32_ep0configure,
- .epalloc = stm32_epalloc,
- .epfree = stm32_epfree,
- .alloc = stm32_alloc,
- .free = stm32_free,
- .ioalloc = stm32_ioalloc,
- .iofree = stm32_iofree,
- .ctrlin = stm32_ctrlin,
- .ctrlout = stm32_ctrlout,
- .transfer = stm32_transfer,
- .disconnect = stm32_disconnect,
- },
- .class = NULL,
-};
-
-/* This is a free list of EDs and TD buffers */
-
-static struct stm32_list_s *g_edfree; /* List of unused EDs */
-static struct stm32_list_s *g_tdfree; /* List of unused TDs */
-static struct stm32_list_s *g_tbfree; /* List of unused transfer buffers */
-#if STM32_IOBUFFERS > 0
-static struct stm32_list_s *g_iofree; /* List of unused I/O buffers */
-#endif
-
-/*******************************************************************************
- * Public Data
- *******************************************************************************/
-
-/*******************************************************************************
- * Private Functions
- *******************************************************************************/
-
-/*******************************************************************************
- * Name: stm32_printreg
- *
- * Description:
- * Print the contents of an STM32xx register operation
- *
- *******************************************************************************/
-
-#ifdef CONFIG_STM32_USBHOST_REGDEBUG
-static void stm32_printreg(uint32_t addr, uint32_t val, bool iswrite)
-{
- lldbg("%08x%s%08x\n", addr, iswrite ? "<-" : "->", val);
-}
-#endif
-
-/*******************************************************************************
- * Name: stm32_checkreg
- *
- * Description:
- * Get the contents of an STM32 register
- *
- *******************************************************************************/
-
-#ifdef CONFIG_STM32_USBHOST_REGDEBUG
-static void stm32_checkreg(uint32_t addr, uint32_t val, bool iswrite)
-{
- static uint32_t prevaddr = 0;
- static uint32_t preval = 0;
- static uint32_t count = 0;
- static bool prevwrite = false;
-
- /* Is this the same value that we read from/wrote to the same register last time?
- * Are we polling the register? If so, suppress the output.
- */
-
- if (addr == prevaddr && val == preval && prevwrite == iswrite)
- {
- /* Yes.. Just increment the count */
-
- count++;
- }
- else
- {
- /* No this is a new address or value or operation. Were there any
- * duplicate accesses before this one?
- */
-
- if (count > 0)
- {
- /* Yes.. Just one? */
-
- if (count == 1)
- {
- /* Yes.. Just one */
-
- stm32_printreg(prevaddr, preval, prevwrite);
- }
- else
- {
- /* No.. More than one. */
-
- lldbg("[repeats %d more times]\n", count);
- }
- }
-
- /* Save the new address, value, count, and operation for next time */
-
- prevaddr = addr;
- preval = val;
- count = 0;
- prevwrite = iswrite;
-
- /* Show the new regisgter access */
-
- stm32_printreg(addr, val, iswrite);
- }
-}
-#endif
-
-/*******************************************************************************
- * Name: stm32_getreg
- *
- * Description:
- * Get the contents of an STM32 register
- *
- *******************************************************************************/
-
-#ifdef CONFIG_STM32_USBHOST_REGDEBUG
-static uint32_t stm32_getreg(uint32_t addr)
-{
- /* Read the value from the register */
-
- uint32_t val = getreg32(addr);
-
- /* Check if we need to print this value */
-
- stm32_checkreg(addr, val, false);
- return val;
-}
-#endif
-
-/*******************************************************************************
- * Name: stm32_putreg
- *
- * Description:
- * Set the contents of an STM32 register to a value
- *
- *******************************************************************************/
-
-#ifdef CONFIG_STM32_USBHOST_REGDEBUG
-static void stm32_putreg(uint32_t val, uint32_t addr)
-{
- /* Check if we need to print this value */
-
- stm32_checkreg(addr, val, true);
-
- /* Write the value */
-
- putreg32(val, addr);
-}
-#endif
-
-/****************************************************************************
- * Name: stm32_takesem
- *
- * Description:
- * This is just a wrapper to handle the annoying behavior of semaphore
- * waits that return due to the receipt of a signal.
- *
- *******************************************************************************/
-
-static void stm32_takesem(sem_t *sem)
-{
- /* Take the semaphore (perhaps waiting) */
-
- while (sem_wait(sem) != 0)
- {
- /* The only case that an error should occr here is if the wait was
- * awakened by a signal.
- */
-
- ASSERT(errno == EINTR);
- }
-}
-
-/****************************************************************************
- * Name: stm32_getle16
- *
- * Description:
- * Get a (possibly unaligned) 16-bit little endian value.
- *
- *******************************************************************************/
-
-static inline uint16_t stm32_getle16(const uint8_t *val)
-{
- return (uint16_t)val[1] << 8 | (uint16_t)val[0];
-}
-
-/****************************************************************************
- * Name: stm32_putle16
- *
- * Description:
- * Put a (possibly unaligned) 16-bit little endian value.
- *
- *******************************************************************************/
-
-static void stm32_putle16(uint8_t *dest, uint16_t val)
-{
- dest[0] = val & 0xff; /* Little endian means LS byte first in byte stream */
- dest[1] = val >> 8;
-}
-
-/*******************************************************************************
- * Name: stm32_edfree
- *
- * Description:
- * Return an endpoint descriptor to the free list
- *
- *******************************************************************************/
-
-static inline void stm32_edfree(struct stm32_ed_s *ed)
-{
- struct stm32_list_s *entry = (struct stm32_list_s *)ed;
-
- /* Put the ED back into the free list */
-
- entry->flink = g_edfree;
- g_edfree = entry;
-}
-
-/*******************************************************************************
- * Name: stm32_tdalloc
- *
- * Description:
- * Allocate an transfer descriptor from the free list
- *
- * Assumptions:
- * - Never called from an interrupt handler.
- * - Protected from conconcurrent access to the TD pool by the interrupt
- * handler
- * - Protection from re-entrance must be assured by the caller
- *
- *******************************************************************************/
-
-static struct stm32_gtd_s *stm32_tdalloc(void)
-{
- struct stm32_gtd_s *ret;
- irqstate_t flags;
-
- /* Disable interrupts momentarily so that stm32_tdfree is not called from the
- * interrupt handler.
- */
-
- flags = irqsave();
- ret = (struct stm32_gtd_s *)g_tdfree;
- if (ret)
- {
- g_tdfree = ((struct stm32_list_s*)ret)->flink;
- }
-
- irqrestore(flags);
- return ret;
-}
-
-/*******************************************************************************
- * Name: stm32_tdfree
- *
- * Description:
- * Return an transfer descriptor to the free list
- *
- * Assumptions:
- * - Only called from the WDH interrupt handler (and during initialization).
- * - Interrupts are disabled in any case.
- *
- *******************************************************************************/
-
-static void stm32_tdfree(struct stm32_gtd_s *td)
-{
- struct stm32_list_s *tdfree = (struct stm32_list_s *)td;
-
- /* This should not happen but just to be safe, don't free the common, pre-
- * allocated tail TD.
- */
-
- if (tdfree != NULL && td != TDTAIL)
- {
- tdfree->flink = g_tdfree;
- g_tdfree = tdfree;
- }
-}
-
-/*******************************************************************************
- * Name: stm32_tballoc
- *
- * Description:
- * Allocate an request/descriptor transfer buffer from the free list
- *
- * Assumptions:
- * - Never called from an interrupt handler.
- * - Protection from re-entrance must be assured by the caller
- *
- *******************************************************************************/
-
-static uint8_t *stm32_tballoc(void)
-{
- uint8_t *ret = (uint8_t *)g_tbfree;
- if (ret)
- {
- g_tbfree = ((struct stm32_list_s*)ret)->flink;
- }
- return ret;
-}
-
-/*******************************************************************************
- * Name: stm32_tbfree
- *
- * Description:
- * Return an request/descriptor transfer buffer to the free list
- *
- *******************************************************************************/
-
-static void stm32_tbfree(uint8_t *buffer)
-{
- struct stm32_list_s *tbfree = (struct stm32_list_s *)buffer;
-
- if (tbfree)
- {
- tbfree->flink = g_tbfree;
- g_tbfree = tbfree;
- }
-}
-
-/*******************************************************************************
- * Name: stm32_allocio
- *
- * Description:
- * Allocate an IO buffer from the free list
- *
- * Assumptions:
- * - Never called from an interrupt handler.
- * - Protection from re-entrance must be assured by the caller
- *
- *******************************************************************************/
-
-#if STM32_IOBUFFERS > 0
-static uint8_t *stm32_allocio(void)
-{
- uint8_t *ret = (uint8_t *)g_iofree;
- if (ret)
- {
- g_iofree = ((struct stm32_list_s*)ret)->flink;
- }
- return ret;
-}
-#endif
-
-/*******************************************************************************
- * Name: stm32_freeio
- *
- * Description:
- * Return an TD buffer to the free list
- *
- *******************************************************************************/
-
-#if STM32_IOBUFFERS > 0
-static void stm32_freeio(uint8_t *buffer)
-{
- struct stm32_list_s *iofree = (struct stm32_list_s *)buffer;
- iofree->flink = g_iofree;
- g_iofree = iofree;
-}
-#endif
-
-/*******************************************************************************
- * Name: stm32_addbulked
- *
- * Description:
- * Helper function to add an ED to the bulk list.
- *
- *******************************************************************************/
-
-static inline int stm32_addbulked(struct stm32_usbhost_s *priv,
- struct stm32_ed_s *ed)
-{
-#ifndef CONFIG_USBHOST_BULK_DISABLE
- uint32_t regval;
-
- /* Add the new bulk ED to the head of the bulk list */
-
- ed->hw.nexted = stm32_getreg(STM32_USBHOST_BULKHEADED);
- stm32_putreg((uint32_t)ed, STM32_USBHOST_BULKHEADED);
-
- /* BulkListEnable. This bit is set to enable the processing of the
- * Bulk list. Note: once enabled, it remains. We really should
- * never modify the bulk list while BLE is set.
- */
-
- regval = stm32_getreg(STM32_USBHOST_CTRL);
- regval |= OHCI_CTRL_BLE;
- stm32_putreg(regval, STM32_USBHOST_CTRL);
- return OK;
-#else
- return -ENOSYS;
-#endif
-}
-
-/*******************************************************************************
- * Name: stm32_rembulked
- *
- * Description:
- * Helper function remove an ED from the bulk list.
- *
- *******************************************************************************/
-
-static inline int stm32_rembulked(struct stm32_usbhost_s *priv,
- struct stm32_ed_s *ed)
-{
-#ifndef CONFIG_USBHOST_BULK_DISABLE
- struct stm32_ed_s *curr;
- struct stm32_ed_s *prev;
- uint32_t regval;
-
- /* Find the ED in the bulk list. NOTE: We really should never be mucking
- * with the bulk list while BLE is set.
- */
-
- for (curr = (struct stm32_ed_s *)stm32_getreg(STM32_USBHOST_BULKHEADED),
- prev = NULL;
- curr && curr != ed;
- prev = curr, curr = (struct stm32_ed_s *)curr->hw.nexted);
-
- /* Hmmm.. It would be a bug if we do not find the ED in the bulk list. */
-
- DEBUGASSERT(curr != NULL);
-
- /* Remove the ED from the bulk list */
-
- if (curr != NULL)
- {
- /* Is this ED the first on in the bulk list? */
-
- if (prev == NULL)
- {
- /* Yes... set the head of the bulk list to skip over this ED */
-
- stm32_putreg(ed->hw.nexted, STM32_USBHOST_BULKHEADED);
-
- /* If the bulk list is now empty, then disable it */
-
- regval = stm32_getreg(STM32_USBHOST_CTRL);
- regval &= ~OHCI_CTRL_BLE;
- stm32_putreg(regval, STM32_USBHOST_CTRL);
- }
- else
- {
- /* No.. set the forward link of the previous ED in the list
- * skip over this ED.
- */
-
- prev->hw.nexted = ed->hw.nexted;
- }
- }
-
- return OK;
-#else
- return -ENOSYS;
-#endif
-}
-
-/*******************************************************************************
- * Name: stm32_getinterval
- *
- * Description:
- * Convert the endpoint polling interval into a HCCA table increment
- *
- *******************************************************************************/
-
-#if !defined(CONFIG_USBHOST_INT_DISABLE) || !defined(CONFIG_USBHOST_ISOC_DISABLE)
-static unsigned int stm32_getinterval(uint8_t interval)
-{
- /* The bInterval field of the endpoint descriptor contains the polling interval
- * for interrupt and isochronous endpoints. For other types of endpoint, this
- * value should be ignored. bInterval is provided in units of 1MS frames.
- */
-
- if (interval < 3)
- {
- return 2;
- }
- else if (interval < 7)
- {
- return 4;
- }
- else if (interval < 15)
- {
- return 8;
- }
- else if (interval < 31)
- {
- return 16;
- }
- else
- {
- return 32;
- }
-}
-#endif
-
-/*******************************************************************************
- * Name: stm32_setinttab
- *
- * Description:
- * Set the interrupt table to the selected value using the provided interval
- * and offset.
- *
- *******************************************************************************/
-
-#if !defined(CONFIG_USBHOST_INT_DISABLE) || !defined(CONFIG_USBHOST_ISOC_DISABLE)
-static void stm32_setinttab(uint32_t value, unsigned int interval, unsigned int offset)
-{
- unsigned int i;
- for (i = offset; i < HCCA_INTTBL_WSIZE; i += interval)
- {
- HCCA->inttbl[i] = value;
- }
-}
-#endif
-
-/*******************************************************************************
- * Name: stm32_addinted
- *
- * Description:
- * Helper function to add an ED to the HCCA interrupt table.
- *
- * To avoid reshuffling the table so much and to keep life simple in general,
- * the following rules are applied:
- *
- * 1. IN EDs get the even entries, OUT EDs get the odd entries.
- * 2. Add IN/OUT EDs are scheduled together at the minimum interval of all
- * IN/OUT EDs.
- *
- * This has the following consequences:
- *
- * 1. The minimum support polling rate is 2MS, and
- * 2. Some devices may get polled at a much higher rate than they request.
- *
- *******************************************************************************/
-
-static inline int stm32_addinted(struct stm32_usbhost_s *priv,
- const FAR struct usbhost_epdesc_s *epdesc,
- struct stm32_ed_s *ed)
-{
-#ifndef CONFIG_USBHOST_INT_DISABLE
- unsigned int interval;
- unsigned int offset;
- uint32_t head;
- uint32_t regval;
-
- /* Disable periodic list processing. Does this take effect immediately? Or
- * at the next SOF... need to check.
- */
-
- regval = stm32_getreg(STM32_USBHOST_CTRL);
- regval &= ~OHCI_CTRL_PLE;
- stm32_putreg(regval, STM32_USBHOST_CTRL);
-
- /* Get the quanitized interval value associated with this ED and save it
- * in the ED.
- */
-
- interval = stm32_getinterval(epdesc->interval);
- ed->interval = interval;
- uvdbg("interval: %d->%d\n", epdesc->interval, interval);
-
- /* Get the offset associated with the ED direction. IN EDs get the even
- * entries, OUT EDs get the odd entries.
- *
- * Get the new, minimum interval. Add IN/OUT EDs are scheduled together
- * at the minimum interval of all IN/OUT EDs.
- */
-
- if (epdesc->in)
- {
- offset = 0;
- if (priv->ininterval > interval)
- {
- priv->ininterval = interval;
- }
- else
- {
- interval = priv->ininterval;
- }
- }
- else
- {
- offset = 1;
- if (priv->outinterval > interval)
- {
- priv->outinterval = interval;
- }
- else
- {
- interval = priv->outinterval;
- }
- }
- uvdbg("min interval: %d offset: %d\n", interval, offset);
-
- /* Get the head of the first of the duplicated entries. The first offset
- * entry is always guaranteed to contain the common ED list head.
- */
-
- head = HCCA->inttbl[offset];
-
- /* Clear all current entries in the interrupt table for this direction */
-
- stm32_setinttab(0, 2, offset);
-
- /* Add the new ED before the old head of the periodic ED list and set the
- * new ED as the head ED in all of the appropriate entries of the HCCA
- * interrupt table.
- */
-
- ed->hw.nexted = head;
- stm32_setinttab((uint32_t)ed, interval, offset);
- uvdbg("head: %08x next: %08x\n", ed, head);
-
- /* Re-enabled periodic list processing */
-
- regval = stm32_getreg(STM32_USBHOST_CTRL);
- regval |= OHCI_CTRL_PLE;
- stm32_putreg(regval, STM32_USBHOST_CTRL);
- return OK;
-#else
- return -ENOSYS;
-#endif
-}
-
-/*******************************************************************************
- * Name: stm32_reminted
- *
- * Description:
- * Helper function to remove an ED from the HCCA interrupt table.
- *
- * To avoid reshuffling the table so much and to keep life simple in general,
- * the following rules are applied:
- *
- * 1. IN EDs get the even entries, OUT EDs get the odd entries.
- * 2. Add IN/OUT EDs are scheduled together at the minimum interval of all
- * IN/OUT EDs.
- *
- * This has the following consequences:
- *
- * 1. The minimum support polling rate is 2MS, and
- * 2. Some devices may get polled at a much higher rate than they request.
- *
- *******************************************************************************/
-
-static inline int stm32_reminted(struct stm32_usbhost_s *priv,
- struct stm32_ed_s *ed)
-{
-#ifndef CONFIG_USBHOST_INT_DISABLE
- struct stm32_ed_s *head;
- struct stm32_ed_s *curr;
- struct stm32_ed_s *prev;
- unsigned int interval;
- unsigned int offset;
- uint32_t regval;
-
- /* Disable periodic list processing. Does this take effect immediately? Or
- * at the next SOF... need to check.
- */
-
- regval = stm32_getreg(STM32_USBHOST_CTRL);
- regval &= ~OHCI_CTRL_PLE;
- stm32_putreg(regval, STM32_USBHOST_CTRL);
-
- /* Get the offset associated with the ED direction. IN EDs get the even
- * entries, OUT EDs get the odd entries.
- */
-
- if ((ed->hw.ctrl & ED_CONTROL_D_MASK) == ED_CONTROL_D_IN)
- {
- offset = 0;
- }
- else
- {
- offset = 1;
- }
-
- /* Get the head of the first of the duplicated entries. The first offset
- * entry is always guaranteed to contain the common ED list head.
- */
-
- head = (struct stm32_ed_s *)HCCA->inttbl[offset];
- uvdbg("ed: %08x head: %08x next: %08x offset: %d\n",
- ed, head, head ? head->hw.nexted : 0, offset);
-
- /* Find the ED to be removed in the ED list */
-
- for (curr = head, prev = NULL;
- curr && curr != ed;
- prev = curr, curr = (struct stm32_ed_s *)curr->hw.nexted);
-
- /* Hmmm.. It would be a bug if we do not find the ED in the bulk list. */
-
- DEBUGASSERT(curr != NULL);
- if (curr != NULL)
- {
- /* Clear all current entries in the interrupt table for this direction */
-
- stm32_setinttab(0, 2, offset);
-
- /* Remove the ED from the list.. Is this ED the first on in the list? */
-
- if (prev == NULL)
- {
- /* Yes... set the head of the bulk list to skip over this ED */
-
- head = (struct stm32_ed_s *)ed->hw.nexted;
- }
- else
- {
- /* No.. set the forward link of the previous ED in the list
- * skip over this ED.
- */
-
- prev->hw.nexted = ed->hw.nexted;
- }
- uvdbg("ed: %08x head: %08x next: %08x\n",
- ed, head, head ? head->hw.nexted : 0);
-
- /* Calculate the new minimum interval for this list */
-
- interval = MAX_PERINTERVAL;
- for (curr = head; curr; curr = (struct stm32_ed_s *)curr->hw.nexted)
- {
- if (curr->interval < interval)
- {
- interval = curr->interval;
- }
- }
- uvdbg("min interval: %d offset: %d\n", interval, offset);
-
- /* Save the new minimum interval */
-
- if ((ed->hw.ctrl && ED_CONTROL_D_MASK) == ED_CONTROL_D_IN)
- {
- priv->ininterval = interval;
- }
- else
- {
- priv->outinterval = interval;
- }
-
- /* Set the head ED in all of the appropriate entries of the HCCA interrupt
- * table (head might be NULL).
- */
-
- stm32_setinttab((uint32_t)head, interval, offset);
- }
-
- /* Re-enabled periodic list processing */
-
- if (head != NULL)
- {
- regval = stm32_getreg(STM32_USBHOST_CTRL);
- regval |= OHCI_CTRL_PLE;
- stm32_putreg(regval, STM32_USBHOST_CTRL);
- }
-
- return OK;
-#else
- return -ENOSYS;
-#endif
-}
-
-/*******************************************************************************
- * Name: stm32_addisoced
- *
- * Description:
- * Helper functions to add an ED to the periodic table.
- *
- *******************************************************************************/
-
-static inline int stm32_addisoced(struct stm32_usbhost_s *priv,
- const FAR struct usbhost_epdesc_s *epdesc,
- struct stm32_ed_s *ed)
-{
-#ifndef CONFIG_USBHOST_ISOC_DISABLE
-# warning "Isochronous endpoints not yet supported"
-#endif
- return -ENOSYS;
-
-}
-
-/*******************************************************************************
- * Name: stm32_remisoced
- *
- * Description:
- * Helper functions to remove an ED from the periodic table.
- *
- *******************************************************************************/
-
-static inline int stm32_remisoced(struct stm32_usbhost_s *priv,
- struct stm32_ed_s *ed)
-{
-#ifndef CONFIG_USBHOST_ISOC_DISABLE
-# warning "Isochronous endpoints not yet supported"
-#endif
- return -ENOSYS;
-}
-
-/*******************************************************************************
- * Name: stm32_enqueuetd
- *
- * Description:
- * Enqueue a transfer descriptor. Notice that this function only supports
- * queue on TD per ED.
- *
- *******************************************************************************/
-
-static int stm32_enqueuetd(struct stm32_usbhost_s *priv,
- struct stm32_ed_s *ed, uint32_t dirpid,
- uint32_t toggle, volatile uint8_t *buffer, size_t buflen)
-{
- struct stm32_gtd_s *td;
- int ret = -ENOMEM;
-
- /* Allocate a TD from the free list */
-
- td = stm32_tdalloc();
- if (td != NULL)
- {
- /* Initialize the allocated TD and link it before the common tail TD. */
-
- td->hw.ctrl = (GTD_STATUS_R | dirpid | TD_DELAY(0) | toggle | GTD_STATUS_CC_MASK);
- TDTAIL->hw.ctrl = 0;
- td->hw.cbp = (uint32_t)buffer;
- TDTAIL->hw.cbp = 0;
- td->hw.nexttd = (uint32_t)TDTAIL;
- TDTAIL->hw.nexttd = 0;
- td->hw.be = (uint32_t)(buffer + (buflen - 1));
- TDTAIL->hw.be = 0;
-
- /* Configure driver-only fields in the extended TD structure */
-
- td->ed = ed;
-
- /* Link the td to the head of the ED's TD list */
-
- ed->hw.headp = (uint32_t)td | ((ed->hw.headp) & ED_HEADP_C);
- ed->hw.tailp = (uint32_t)TDTAIL;
-
- ret = OK;
- }
-
- return ret;
-}
-
-/*******************************************************************************
- * Name: stm32_wdhwait
- *
- * Description:
- * Set the request for the Writeback Done Head event well BEFORE enabling the
- * transfer (as soon as we are absolutely committed to the to avoid transfer).
- * We do this to minimize race conditions. This logic would have to be expanded
- * if we want to have more than one packet in flight at a time!
- *
- *******************************************************************************/
-
-static int stm32_wdhwait(struct stm32_usbhost_s *priv, struct stm32_ed_s *ed)
-{
- irqstate_t flags = irqsave();
- int ret = -ENODEV;
-
- /* Is the device still connected? */
-
- if (priv->connected)
- {
- /* Yes.. then set wdhwait to indicate that we expect to be informed when
- * either (1) the device is disconnected, or (2) the transfer completed.
- */
-
- ed->wdhwait = true;
- ret = OK;
- }
-
- irqrestore(flags);
- return ret;
-}
-
-/*******************************************************************************
- * Name: stm32_ctrltd
- *
- * Description:
- * Process a IN or OUT request on the control endpoint. This function
- * will enqueue the request and wait for it to complete. Only one transfer
- * may be queued; Neither these methods nor the transfer() method can be
- * called again until the control transfer functions returns.
- *
- * These are blocking methods; these functions will not return until the
- * control transfer has completed.
- *
- *******************************************************************************/
-
-static int stm32_ctrltd(struct stm32_usbhost_s *priv, uint32_t dirpid,
- uint8_t *buffer, size_t buflen)
-{
- uint32_t toggle;
- uint32_t regval;
- int ret;
-
- /* Set the request for the Writeback Done Head event well BEFORE enabling the
- * transfer.
- */
-
- ret = stm32_wdhwait(priv, EDCTRL);
- if (ret != OK)
- {
- udbg("ERROR: Device disconnected\n");
- return ret;
- }
-
- /* Configure the toggle field in the TD */
-
- if (dirpid == GTD_STATUS_DP_SETUP)
- {
- toggle = GTD_STATUS_T_DATA0;
- }
- else
- {
- toggle = GTD_STATUS_T_DATA1;
- }
-
- /* Then enqueue the transfer */
-
- EDCTRL->tdstatus = TD_CC_NOERROR;
- ret = stm32_enqueuetd(priv, EDCTRL, dirpid, toggle, buffer, buflen);
- if (ret == OK)
- {
- /* Set ControlListFilled. This bit is used to indicate whether there are
- * TDs on the Control list.
- */
-
- regval = stm32_getreg(STM32_USBHOST_CMDST);
- regval |= OHCI_CMDST_CLF;
- stm32_putreg(regval, STM32_USBHOST_CMDST);
-
- /* Wait for the Writeback Done Head interrupt */
-
- stm32_takesem(&EDCTRL->wdhsem);
-
- /* Check the TD completion status bits */
-
- if (EDCTRL->tdstatus == TD_CC_NOERROR)
- {
- ret = OK;
- }
- else
- {
- uvdbg("Bad TD completion status: %d\n", EDCTRL->tdstatus);
- ret = -EIO;
- }
- }
-
- /* Make sure that there is no outstanding request on this endpoint */
-
- EDCTRL->wdhwait = false;
- return ret;
-}
-
-/*******************************************************************************
- * Name: stm32_usbinterrupt
- *
- * Description:
- * USB interrupt handler
- *
- *******************************************************************************/
-
-static int stm32_usbinterrupt(int irq, FAR void *context)
-{
- struct stm32_usbhost_s *priv = &g_usbhost;
- uint32_t intst;
- uint32_t pending;
- uint32_t regval;
-
- /* Read Interrupt Status and mask out interrupts that are not enabled. */
-
- intst = stm32_getreg(STM32_USBHOST_INTST);
- regval = stm32_getreg(STM32_USBHOST_INTEN);
- ullvdbg("INST: %08x INTEN: %08x\n", intst, regval);
-
- pending = intst & regval;
- if (pending != 0)
- {
- /* Root hub status change interrupt */
-
- if ((pending & OHCI_INT_RHSC) != 0)
- {
- uint32_t rhportst1 = stm32_getreg(STM32_USBHOST_RHPORTST1);
- ullvdbg("Root Hub Status Change, RHPORTST1: %08x\n", rhportst1);
-
- if ((rhportst1 & OHCI_RHPORTST_CSC) != 0)
- {
- uint32_t rhstatus = stm32_getreg(STM32_USBHOST_RHSTATUS);
- ullvdbg("Connect Status Change, RHSTATUS: %08x\n", rhstatus);
-
- /* If DRWE is set, Connect Status Change indicates a remote wake-up event */
-
- if (rhstatus & OHCI_RHSTATUS_DRWE)
- {
- ullvdbg("DRWE: Remote wake-up\n");
- }
-
- /* Otherwise... Not a remote wake-up event */
-
- else
- {
- /* Check current connect status */
-
- if ((rhportst1 & OHCI_RHPORTST_CCS) != 0)
- {
- /* Connected ... Did we just become connected? */
-
- if (!priv->connected)
- {
- /* Yes.. connected. */
-
- ullvdbg("Connected\n");
- priv->connected = true;
-
- /* Notify any waiters */
-
- if (priv->rhswait)
- {
- stm32_givesem(&priv->rhssem);
- priv->rhswait = false;
- }
- }
- else
- {
- ulldbg("Spurious status change (connected)\n");
- }
-
- /* The LSDA (Low speed device attached) bit is valid
- * when CCS == 1.
- */
-
- priv->lowspeed = (rhportst1 & OHCI_RHPORTST_LSDA) != 0;
- ullvdbg("Speed:%s\n", priv->lowspeed ? "LOW" : "FULL");
- }
-
- /* Check if we are now disconnected */
-
- else if (priv->connected)
- {
- /* Yes.. disconnect the device */
-
- ullvdbg("Disconnected\n");
- priv->connected = false;
- priv->lowspeed = false;
-
- /* Are we bound to a class instance? */
-
- if (priv->class)
- {
- /* Yes.. Disconnect the class */
-
- CLASS_DISCONNECTED(priv->class);
- priv->class = NULL;
- }
-
- /* Notify any waiters for the Root Hub Status change event */
-
- if (priv->rhswait)
- {
- stm32_givesem(&priv->rhssem);
- priv->rhswait = false;
- }
- }
- else
- {
- ulldbg("Spurious status change (disconnected)\n");
- }
- }
-
- /* Clear the status change interrupt */
-
- stm32_putreg(OHCI_RHPORTST_CSC, STM32_USBHOST_RHPORTST1);
- }
-
- /* Check for port reset status change */
-
- if ((rhportst1 & OHCI_RHPORTST_PRSC) != 0)
- {
- /* Release the RH port from reset */
-
- stm32_putreg(OHCI_RHPORTST_PRSC, STM32_USBHOST_RHPORTST1);
- }
- }
-
- /* Writeback Done Head interrupt */
-
- if ((pending & OHCI_INT_WDH) != 0)
- {
- struct stm32_gtd_s *td;
- struct stm32_gtd_s *next;
-
- /* The host controller just wrote the list of finished TDs into the HCCA
- * done head. This may include multiple packets that were transferred
- * in the preceding frame.
- *
- * Remove the TD(s) from the Writeback Done Head in the HCCA and return
- * them to the free list. Note that this is safe because the hardware
- * will not modify the writeback done head again until the WDH bit is
- * cleared in the interrupt status register.
- */
-
- td = (struct stm32_gtd_s *)HCCA->donehead;
- HCCA->donehead = 0;
-
- /* Process each TD in the write done list */
-
- for (; td; td = next)
- {
- /* Get the ED in which this TD was enqueued */
-
- struct stm32_ed_s *ed = td->ed;
- DEBUGASSERT(ed != NULL);
-
- /* Save the condition code from the (single) TD status/control
- * word.
- */
-
- ed->tdstatus = (td->hw.ctrl & GTD_STATUS_CC_MASK) >> GTD_STATUS_CC_SHIFT;
-
-#ifdef CONFIG_DEBUG_USB
- if (ed->tdstatus != TD_CC_NOERROR)
- {
- /* The transfer failed for some reason... dump some diagnostic info. */
-
- ulldbg("ERROR: ED xfrtype:%d TD CTRL:%08x/CC:%d RHPORTST1:%08x\n",
- ed->xfrtype, td->hw.ctrl, ed->tdstatus,
- stm32_getreg(STM32_USBHOST_RHPORTST1));
- }
-#endif
-
- /* Return the TD to the free list */
-
- next = (struct stm32_gtd_s *)td->hw.nexttd;
- stm32_tdfree(td);
-
- /* And wake up the thread waiting for the WDH event */
-
- if (ed->wdhwait)
- {
- stm32_givesem(&ed->wdhsem);
- ed->wdhwait = false;
- }
- }
- }
-
-#ifdef CONFIG_DEBUG_USB
- if ((pending & STM32_DEBUG_INTS) != 0)
- {
- ulldbg("ERROR: Unhandled interrupts INTST:%08x\n", intst);
- }
-#endif
-
- /* Clear interrupt status register */
-
- stm32_putreg(intst, STM32_USBHOST_INTST);
- }
-
- return OK;
-}
-
-/*******************************************************************************
- * USB Host Controller Operations
- *******************************************************************************/
-
-/*******************************************************************************
- * Name: stm32_wait
- *
- * Description:
- * Wait for a device to be connected or disconneced.
- *
- * Input Parameters:
- * drvr - The USB host driver instance obtained as a parameter from the call to
- * the class create() method.
- * connected - TRUE: Wait for device to be connected; FALSE: wait for device
- * to be disconnected
- *
- * Returned Values:
- * Zero (OK) is returned when a device in connected. This function will not
- * return until either (1) a device is connected or (2) some failure occurs.
- * On a failure, a negated errno value is returned indicating the nature of
- * the failure
- *
- * Assumptions:
- * - Called from a single thread so no mutual exclusion is required.
- * - Never called from an interrupt handler.
- *
- *******************************************************************************/
-
-static int stm32_wait(FAR struct usbhost_driver_s *drvr, bool connected)
-{
- struct stm32_usbhost_s *priv = (struct stm32_usbhost_s *)drvr;
- irqstate_t flags;
-
- /* Are we already connected? */
-
- flags = irqsave();
- while (priv->connected == connected)
- {
- /* No... wait for the connection/disconnection */
-
- priv->rhswait = true;
- stm32_takesem(&priv->rhssem);
- }
- irqrestore(flags);
-
- udbg("Connected:%s\n", priv->connected ? "YES" : "NO");
- return OK;
-}
-
-/*******************************************************************************
- * Name: stm32_enumerate
- *
- * Description:
- * Enumerate the connected device. As part of this enumeration process,
- * the driver will (1) get the device's configuration descriptor, (2)
- * extract the class ID info from the configuration descriptor, (3) call
- * usbhost_findclass() to find the class that supports this device, (4)
- * call the create() method on the struct usbhost_registry_s interface
- * to get a class instance, and finally (5) call the configdesc() method
- * of the struct usbhost_class_s interface. After that, the class is in
- * charge of the sequence of operations.
- *
- * Input Parameters:
- * drvr - The USB host driver instance obtained as a parameter from the call to
- * the class create() method.
- *
- * Returned Values:
- * On success, zero (OK) is returned. On a failure, a negated errno value is
- * returned indicating the nature of the failure
- *
- * Assumptions:
- * - Only a single class bound to a single device is supported.
- * - Called from a single thread so no mutual exclusion is required.
- * - Never called from an interrupt handler.
- *
- *******************************************************************************/
-
-static int stm32_enumerate(FAR struct usbhost_driver_s *drvr)
-{
- struct stm32_usbhost_s *priv = (struct stm32_usbhost_s *)drvr;
-
- /* Are we connected to a device? The caller should have called the wait()
- * method first to be assured that a device is connected.
- */
-
- while (!priv->connected)
- {
- /* No, return an error */
-
- udbg("Not connected\n");
- return -ENODEV;
- }
-
- /* USB 2.0 spec says at least 50ms delay before port reset */
-
- up_mdelay(100);
-
- /* Put RH port 1 in reset (the STM32 supports only a single downstream port) */
-
- stm32_putreg(OHCI_RHPORTST_PRS, STM32_USBHOST_RHPORTST1);
-
- /* Wait for the port reset to complete */
-
- while ((stm32_getreg(STM32_USBHOST_RHPORTST1) & OHCI_RHPORTST_PRS) != 0);
-
- /* Release RH port 1 from reset and wait a bit */
-
- stm32_putreg(OHCI_RHPORTST_PRSC, STM32_USBHOST_RHPORTST1);
- up_mdelay(200);
-
- /* Let the common usbhost_enumerate do all of the real work. Note that the
- * FunctionAddress (USB address) is hardcoded to one.
- */
-
- uvdbg("Enumerate the device\n");
- return usbhost_enumerate(drvr, 1, &priv->class);
-}
-
-/************************************************************************************
- * Name: stm32_ep0configure
- *
- * Description:
- * Configure endpoint 0. This method is normally used internally by the
- * enumerate() method but is made available at the interface to support
- * an external implementation of the enumeration logic.
- *
- * Input Parameters:
- * drvr - The USB host driver instance obtained as a parameter from the call to
- * the class create() method.
- * funcaddr - The USB address of the function containing the endpoint that EP0
- * controls
- * maxpacketsize - The maximum number of bytes that can be sent to or
- * received from the endpoint in a single data packet
- *
- * Returned Values:
- * On success, zero (OK) is returned. On a failure, a negated errno value is
- * returned indicating the nature of the failure
- *
- * Assumptions:
- * This function will *not* be called from an interrupt handler.
- *
- ************************************************************************************/
-
-static int stm32_ep0configure(FAR struct usbhost_driver_s *drvr, uint8_t funcaddr,
- uint16_t maxpacketsize)
-{
- struct stm32_usbhost_s *priv = (struct stm32_usbhost_s *)drvr;
-
- DEBUGASSERT(drvr && funcaddr < 128 && maxpacketsize < 2048);
-
- /* We must have exclusive access to EP0 and the control list */
-
- stm32_takesem(&priv->exclsem);
-
- /* Set the EP0 ED control word */
-
- EDCTRL->hw.ctrl = (uint32_t)funcaddr << ED_CONTROL_FA_SHIFT |
- (uint32_t)maxpacketsize << ED_CONTROL_MPS_SHIFT;
-
- if (priv->lowspeed)
- {
- EDCTRL->hw.ctrl |= ED_CONTROL_S;
- }
-
- /* Set the transfer type to control */
-
- EDCTRL->xfrtype = USB_EP_ATTR_XFER_CONTROL;
- stm32_givesem(&priv->exclsem);
-
- uvdbg("EP0 CTRL:%08x\n", EDCTRL->hw.ctrl);
- return OK;
-}
-
-/************************************************************************************
- * Name: stm32_epalloc
- *
- * Description:
- * Allocate and configure one endpoint.
- *
- * Input Parameters:
- * drvr - The USB host driver instance obtained as a parameter from the call to
- * the class create() method.
- * epdesc - Describes the endpoint to be allocated.
- * ep - A memory location provided by the caller in which to receive the
- * allocated endpoint desciptor.
- *
- * Returned Values:
- * On success, zero (OK) is returned. On a failure, a negated errno value is
- * returned indicating the nature of the failure
- *
- * Assumptions:
- * This function will *not* be called from an interrupt handler.
- *
- ************************************************************************************/
-
-static int stm32_epalloc(FAR struct usbhost_driver_s *drvr,
- const FAR struct usbhost_epdesc_s *epdesc, usbhost_ep_t *ep)
-{
- struct stm32_usbhost_s *priv = (struct stm32_usbhost_s *)drvr;
- struct stm32_ed_s *ed;
- int ret = -ENOMEM;
-
- /* Sanity check. NOTE that this method should only be called if a device is
- * connected (because we need a valid low speed indication).
- */
-
- DEBUGASSERT(priv && epdesc && ep && priv->connected);
-
- /* We must have exclusive access to the ED pool, the bulk list, the periodic list
- * and the interrupt table.
- */
-
- stm32_takesem(&priv->exclsem);
-
- /* Take the next ED from the beginning of the free list */
-
- ed = (struct stm32_ed_s *)g_edfree;
- if (ed)
- {
- /* Remove the ED from the freelist */
-
- g_edfree = ((struct stm32_list_s*)ed)->flink;
-
- /* Configure the endpoint descriptor. */
-
- memset((void*)ed, 0, sizeof(struct stm32_ed_s));
- ed->hw.ctrl = (uint32_t)(epdesc->funcaddr) << ED_CONTROL_FA_SHIFT |
- (uint32_t)(epdesc->addr) << ED_CONTROL_EN_SHIFT |
- (uint32_t)(epdesc->mxpacketsize) << ED_CONTROL_MPS_SHIFT;
-
- /* Get the direction of the endpoint */
-
- if (epdesc->in)
- {
- ed->hw.ctrl |= ED_CONTROL_D_IN;
- }
- else
- {
- ed->hw.ctrl |= ED_CONTROL_D_OUT;
- }
-
- /* Check for a low-speed device */
-
- if (priv->lowspeed)
- {
- ed->hw.ctrl |= ED_CONTROL_S;
- }
-
- /* Set the transfer type */
-
- ed->xfrtype = epdesc->xfrtype;
-
- /* Special Case isochronous transfer types */
-
-#if 0 /* Isochronous transfers not yet supported */
- if (ed->xfrtype == USB_EP_ATTR_XFER_ISOC)
- {
- ed->hw.ctrl |= ED_CONTROL_F;
- }
-#endif
- uvdbg("EP%d CTRL:%08x\n", epdesc->addr, ed->hw.ctrl);
-
- /* Initialize the semaphore that is used to wait for the endpoint
- * WDH event.
- */
-
- sem_init(&ed->wdhsem, 0, 0);
-
- /* Link the common tail TD to the ED's TD list */
-
- ed->hw.headp = (uint32_t)TDTAIL;
- ed->hw.tailp = (uint32_t)TDTAIL;
-
- /* Now add the endpoint descriptor to the appropriate list */
-
- switch (ed->xfrtype)
- {
- case USB_EP_ATTR_XFER_BULK:
- ret = stm32_addbulked(priv, ed);
- break;
-
- case USB_EP_ATTR_XFER_INT:
- ret = stm32_addinted(priv, epdesc, ed);
- break;
-
- case USB_EP_ATTR_XFER_ISOC:
- ret = stm32_addisoced(priv, epdesc, ed);
- break;
-
- case USB_EP_ATTR_XFER_CONTROL:
- default:
- ret = -EINVAL;
- break;
- }
-
- /* Was the ED successfully added? */
-
- if (ret != OK)
- {
- /* No.. destroy it and report the error */
-
- udbg("ERROR: Failed to queue ED for transfer type: %d\n", ed->xfrtype);
- sem_destroy(&ed->wdhsem);
- stm32_edfree(ed);
- }
- else
- {
- /* Yes.. return an opaque reference to the ED */
-
- *ep = (usbhost_ep_t)ed;
- }
- }
-
- stm32_givesem(&priv->exclsem);
- return ret;
-}
-
-/************************************************************************************
- * Name: stm32_epfree
- *
- * Description:
- * Free and endpoint previously allocated by DRVR_EPALLOC.
- *
- * Input Parameters:
- * drvr - The USB host driver instance obtained as a parameter from the call to
- * the class create() method.
- * ep - The endpint to be freed.
- *
- * Returned Values:
- * On success, zero (OK) is returned. On a failure, a negated errno value is
- * returned indicating the nature of the failure
- *
- * Assumptions:
- * This function will *not* be called from an interrupt handler.
- *
- ************************************************************************************/
-
-static int stm32_epfree(FAR struct usbhost_driver_s *drvr, usbhost_ep_t ep)
-{
- struct stm32_usbhost_s *priv = (struct stm32_usbhost_s *)drvr;
- struct stm32_ed_s *ed = (struct stm32_ed_s *)ep;
- int ret;
-
- /* There should not be any pending, real TDs linked to this ED */
-
- DEBUGASSERT(ed && (ed->hw.headp & ED_HEADP_ADDR_MASK) == STM32_TDTAIL_ADDR);
-
- /* We must have exclusive access to the ED pool, the bulk list, the periodic list
- * and the interrupt table.
- */
-
- stm32_takesem(&priv->exclsem);
-
- /* Remove the ED to the correct list depending on the trasfer type */
-
- switch (ed->xfrtype)
- {
- case USB_EP_ATTR_XFER_BULK:
- ret = stm32_rembulked(priv, ed);
- break;
-
- case USB_EP_ATTR_XFER_INT:
- ret = stm32_reminted(priv, ed);
- break;
-
- case USB_EP_ATTR_XFER_ISOC:
- ret = stm32_remisoced(priv, ed);
- break;
-
- case USB_EP_ATTR_XFER_CONTROL:
- default:
- ret = -EINVAL;
- break;
- }
-
- /* Destroy the semaphore */
-
- sem_destroy(&ed->wdhsem);
-
- /* Put the ED back into the free list */
-
- stm32_edfree(ed);
- stm32_givesem(&priv->exclsem);
- return ret;
-}
-
-/*******************************************************************************
- * Name: stm32_alloc
- *
- * Description:
- * Some hardware supports special memory in which request and descriptor data can
- * be accessed more efficiently. This method provides a mechanism to allocate
- * the request/descriptor memory. If the underlying hardware does not support
- * such "special" memory, this functions may simply map to malloc.
- *
- * This interface was optimized under a particular assumption. It was assumed
- * that the driver maintains a pool of small, pre-allocated buffers for descriptor
- * traffic. NOTE that size is not an input, but an output: The size of the
- * pre-allocated buffer is returned.
- *
- * Input Parameters:
- * drvr - The USB host driver instance obtained as a parameter from the call to
- * the class create() method.
- * buffer - The address of a memory location provided by the caller in which to
- * return the allocated buffer memory address.
- * maxlen - The address of a memory location provided by the caller in which to
- * return the maximum size of the allocated buffer memory.
- *
- * Returned Values:
- * On success, zero (OK) is returned. On a failure, a negated errno value is
- * returned indicating the nature of the failure
- *
- * Assumptions:
- * - Called from a single thread so no mutual exclusion is required.
- * - Never called from an interrupt handler.
- *
- *******************************************************************************/
-
-static int stm32_alloc(FAR struct usbhost_driver_s *drvr,
- FAR uint8_t **buffer, FAR size_t *maxlen)
-{
- struct stm32_usbhost_s *priv = (struct stm32_usbhost_s *)drvr;
- DEBUGASSERT(priv && buffer && maxlen);
- int ret = -ENOMEM;
-
- /* We must have exclusive access to the transfer buffer pool */
-
- stm32_takesem(&priv->exclsem);
-
- *buffer = stm32_tballoc();
- if (*buffer)
- {
- *maxlen = CONFIG_USBHOST_TDBUFSIZE;
- ret = OK;
- }
-
- stm32_givesem(&priv->exclsem);
- return ret;
-}
-
-/*******************************************************************************
- * Name: stm32_free
- *
- * Description:
- * Some hardware supports special memory in which request and descriptor data can
- * be accessed more efficiently. This method provides a mechanism to free that
- * request/descriptor memory. If the underlying hardware does not support
- * such "special" memory, this functions may simply map to free().
- *
- * Input Parameters:
- * drvr - The USB host driver instance obtained as a parameter from the call to
- * the class create() method.
- * buffer - The address of the allocated buffer memory to be freed.
- *
- * Returned Values:
- * On success, zero (OK) is returned. On a failure, a negated errno value is
- * returned indicating the nature of the failure
- *
- * Assumptions:
- * - Never called from an interrupt handler.
- *
- *******************************************************************************/
-
-static int stm32_free(FAR struct usbhost_driver_s *drvr, FAR uint8_t *buffer)
-{
- struct stm32_usbhost_s *priv = (struct stm32_usbhost_s *)drvr;
- DEBUGASSERT(buffer);
-
- /* We must have exclusive access to the transfer buffer pool */
-
- stm32_takesem(&priv->exclsem);
- stm32_tbfree(buffer);
- stm32_givesem(&priv->exclsem);
- return OK;
-}
-
-/************************************************************************************
- * Name: stm32_ioalloc
- *
- * Description:
- * Some hardware supports special memory in which larger IO buffers can
- * be accessed more efficiently. This method provides a mechanism to allocate
- * the request/descriptor memory. If the underlying hardware does not support
- * such "special" memory, this functions may simply map to malloc.
- *
- * This interface differs from DRVR_ALLOC in that the buffers are variable-sized.
- *
- * Input Parameters:
- * drvr - The USB host driver instance obtained as a parameter from the call to
- * the class create() method.
- * buffer - The address of a memory location provided by the caller in which to
- * return the allocated buffer memory address.
- * buflen - The size of the buffer required.
- *
- * Returned Values:
- * On success, zero (OK) is returned. On a failure, a negated errno value is
- * returned indicating the nature of the failure
- *
- * Assumptions:
- * This function will *not* be called from an interrupt handler.
- *
- ************************************************************************************/
-
-static int stm32_ioalloc(FAR struct usbhost_driver_s *drvr,
- FAR uint8_t **buffer, size_t buflen)
-{
- DEBUGASSERT(drvr && buffer);
-
-#if STM32_IOBUFFERS > 0
- if (buflen <= CONFIG_USBHOST_IOBUFSIZE)
- {
- FAR uint8_t *alloc = stm32_allocio();
- if (alloc)
- {
- *buffer = alloc;
- return OK;
- }
- }
- return -ENOMEM;
-#else
- return -ENOSYS;
-#endif
-}
-
-/************************************************************************************
- * Name: stm32_iofree
- *
- * Description:
- * Some hardware supports special memory in which IO data can be accessed more
- * efficiently. This method provides a mechanism to free that IO buffer
- * memory. If the underlying hardware does not support such "special" memory,
- * this functions may simply map to free().
- *
- * Input Parameters:
- * drvr - The USB host driver instance obtained as a parameter from the call to
- * the class create() method.
- * buffer - The address of the allocated buffer memory to be freed.
- *
- * Returned Values:
- * On success, zero (OK) is returned. On a failure, a negated errno value is
- * returned indicating the nature of the failure
- *
- * Assumptions:
- * This function will *not* be called from an interrupt handler.
- *
- ************************************************************************************/
-
-static int stm32_iofree(FAR struct usbhost_driver_s *drvr, FAR uint8_t *buffer)
-{
- DEBUGASSERT(drvr && buffer);
-
-#if STM32_IOBUFFERS > 0
- stm32_freeio(buffer);
- return OK;
-#else
- return -ENOSYS;
-#endif
-}
-
-/*******************************************************************************
- * Name: stm32_ctrlin and stm32_ctrlout
- *
- * Description:
- * Process a IN or OUT request on the control endpoint. These methods
- * will enqueue the request and wait for it to complete. Only one transfer may be
- * queued; Neither these methods nor the transfer() method can be called again
- * until the control transfer functions returns.
- *
- * These are blocking methods; these functions will not return until the
- * control transfer has completed.
- *
- * Input Parameters:
- * drvr - The USB host driver instance obtained as a parameter from the call to
- * the class create() method.
- * req - Describes the request to be sent. This request must lie in memory
- * created by DRVR_ALLOC.
- * buffer - A buffer used for sending the request and for returning any
- * responses. This buffer must be large enough to hold the length value
- * in the request description. buffer must have been allocated using DRVR_ALLOC
- *
- * NOTE: On an IN transaction, req and buffer may refer to the same allocated
- * memory.
- *
- * Returned Values:
- * On success, zero (OK) is returned. On a failure, a negated errno value is
- * returned indicating the nature of the failure
- *
- * Assumptions:
- * - Only a single class bound to a single device is supported.
- * - Called from a single thread so no mutual exclusion is required.
- * - Never called from an interrupt handler.
- *
- *******************************************************************************/
-
-static int stm32_ctrlin(FAR struct usbhost_driver_s *drvr,
- FAR const struct usb_ctrlreq_s *req,
- FAR uint8_t *buffer)
-{
- struct stm32_usbhost_s *priv = (struct stm32_usbhost_s *)drvr;
- uint16_t len;
- int ret;
-
- DEBUGASSERT(drvr && req);
- uvdbg("type:%02x req:%02x value:%02x%02x index:%02x%02x len:%02x%02x\n",
- req->type, req->req, req->value[1], req->value[0],
- req->index[1], req->index[0], req->len[1], req->len[0]);
-
- /* We must have exclusive access to EP0 and the control list */
-
- stm32_takesem(&priv->exclsem);
-
- len = stm32_getle16(req->len);
- ret = stm32_ctrltd(priv, GTD_STATUS_DP_SETUP, (uint8_t*)req, USB_SIZEOF_CTRLREQ);
- if (ret == OK)
- {
- if (len)
- {
- ret = stm32_ctrltd(priv, GTD_STATUS_DP_IN, buffer, len);
- }
-
- if (ret == OK)
- {
- ret = stm32_ctrltd(priv, GTD_STATUS_DP_OUT, NULL, 0);
- }
- }
-
- stm32_givesem(&priv->exclsem);
- return ret;
-}
-
-static int stm32_ctrlout(FAR struct usbhost_driver_s *drvr,
- FAR const struct usb_ctrlreq_s *req,
- FAR const uint8_t *buffer)
-{
- struct stm32_usbhost_s *priv = (struct stm32_usbhost_s *)drvr;
- uint16_t len;
- int ret;
-
- DEBUGASSERT(drvr && req);
- uvdbg("type:%02x req:%02x value:%02x%02x index:%02x%02x len:%02x%02x\n",
- req->type, req->req, req->value[1], req->value[0],
- req->index[1], req->index[0], req->len[1], req->len[0]);
-
- /* We must have exclusive access to EP0 and the control list */
-
- stm32_takesem(&priv->exclsem);
-
- len = stm32_getle16(req->len);
- ret = stm32_ctrltd(priv, GTD_STATUS_DP_SETUP, (uint8_t*)req, USB_SIZEOF_CTRLREQ);
- if (ret == OK)
- {
- if (len)
- {
- ret = stm32_ctrltd(priv, GTD_STATUS_DP_OUT, (uint8_t*)buffer, len);
- }
-
- if (ret == OK)
- {
- ret = stm32_ctrltd(priv, GTD_STATUS_DP_IN, NULL, 0);
- }
- }
-
- stm32_givesem(&priv->exclsem);
- return ret;
-}
-
-/*******************************************************************************
- * Name: stm32_transfer
- *
- * Description:
- * Process a request to handle a transfer descriptor. This method will
- * enqueue the transfer request and return immediately. Only one transfer may be
- * queued; Neither this method nor the ctrlin or ctrlout methods can be called
- * again until this function returns.
- *
- * This is a blocking method; this functions will not return until the
- * transfer has completed.
- *
- * Input Parameters:
- * drvr - The USB host driver instance obtained as a parameter from the call to
- * the class create() method.
- * ep - The IN or OUT endpoint descriptor for the device endpoint on which to
- * perform the transfer.
- * buffer - A buffer containing the data to be sent (OUT endpoint) or received
- * (IN endpoint). buffer must have been allocated using DRVR_ALLOC
- * buflen - The length of the data to be sent or received.
- *
- * Returned Values:
- * On success, zero (OK) is returned. On a failure, a negated errno value is
- * returned indicating the nature of the failure
- *
- * Assumptions:
- * - Only a single class bound to a single device is supported.
- * - Called from a single thread so no mutual exclusion is required.
- * - Never called from an interrupt handler.
- *
- *******************************************************************************/
-
-static int stm32_transfer(FAR struct usbhost_driver_s *drvr, usbhost_ep_t ep,
- FAR uint8_t *buffer, size_t buflen)
-{
- struct stm32_usbhost_s *priv = (struct stm32_usbhost_s *)drvr;
- struct stm32_ed_s *ed = (struct stm32_ed_s *)ep;
- uint32_t dirpid;
- uint32_t regval;
-#if STM32_IOBUFFERS > 0
- uint8_t *origbuf = NULL;
-#endif
- bool in;
- int ret;
-
- DEBUGASSERT(priv && ed && buffer && buflen > 0);
-
- in = (ed->hw.ctrl & ED_CONTROL_D_MASK) == ED_CONTROL_D_IN;
- uvdbg("EP%d %s toggle:%d maxpacket:%d buflen:%d\n",
- (ed->hw.ctrl & ED_CONTROL_EN_MASK) >> ED_CONTROL_EN_SHIFT,
- in ? "IN" : "OUT",
- (ed->hw.headp & ED_HEADP_C) != 0 ? 1 : 0,
- (ed->hw.ctrl & ED_CONTROL_MPS_MASK) >> ED_CONTROL_MPS_SHIFT,
- buflen);
-
- /* We must have exclusive access to the endpoint, the TD pool, the I/O buffer
- * pool, the bulk and interrupt lists, and the HCCA interrupt table.
- */
-
- stm32_takesem(&priv->exclsem);
-
- /* Allocate an IO buffer if the user buffer does not lie in AHB SRAM */
-
-#if STM32_IOBUFFERS > 0
- if ((uintptr_t)buffer < STM32_SRAM_BANK0 ||
- (uintptr_t)buffer >= (STM32_SRAM_BANK0 + STM32_BANK0_SIZE + STM32_BANK1_SIZE))
- {
- /* Will the transfer fit in an IO buffer? */
-
- if (buflen > CONFIG_USBHOST_IOBUFSIZE)
- {
- uvdbg("buflen (%d) > IO buffer size (%d)\n",
- buflen, CONFIG_USBHOST_IOBUFSIZE);
- ret = -ENOMEM;
- goto errout;
- }
-
- /* Allocate an IO buffer in AHB SRAM */
-
- origbuf = buffer;
- buffer = stm32_allocio();
- if (!buffer)
- {
- uvdbg("IO buffer allocation failed\n");
- ret = -ENOMEM;
- goto errout;
- }
-
- /* If this is an OUT transaction, copy the user data into the AHB
- * SRAM IO buffer. Sad... so inefficient. But without exposing
- * the AHB SRAM to the final, end-user client I don't know of any
- * way around this copy.
- */
-
- if (!in)
- {
- memcpy(buffer, origbuf, buflen);
- }
- }
-#endif
-
- /* Set the request for the Writeback Done Head event well BEFORE enabling the
- * transfer.
- */
-
- ret = stm32_wdhwait(priv, ed);
- if (ret != OK)
- {
- udbg("ERROR: Device disconnected\n");
- goto errout;
- }
-
- /* Get the direction of the endpoint */
-
- if (in)
- {
- dirpid = GTD_STATUS_DP_IN;
- }
- else
- {
- dirpid = GTD_STATUS_DP_OUT;
- }
-
- /* Then enqueue the transfer */
-
- ed->tdstatus = TD_CC_NOERROR;
- ret = stm32_enqueuetd(priv, ed, dirpid, GTD_STATUS_T_TOGGLE, buffer, buflen);
- if (ret == OK)
- {
- /* BulkListFilled. This bit is used to indicate whether there are any
- * TDs on the Bulk list.
- */
-
- regval = stm32_getreg(STM32_USBHOST_CMDST);
- regval |= OHCI_CMDST_BLF;
- stm32_putreg(regval, STM32_USBHOST_CMDST);
-
- /* Wait for the Writeback Done Head interrupt */
-
- stm32_takesem(&ed->wdhsem);
-
- /* Check the TD completion status bits */
-
- if (ed->tdstatus == TD_CC_NOERROR)
- {
- ret = OK;
- }
- else
- {
- uvdbg("Bad TD completion status: %d\n", ed->tdstatus);
- ret = -EIO;
- }
- }
-
-errout:
- /* Make sure that there is no outstanding request on this endpoint */
-
- ed->wdhwait = false;
-
- /* Free any temporary IO buffers */
-
-#if STM32_IOBUFFERS > 0
- if (buffer && origbuf)
- {
- /* If this is an IN transaction, get the user data from the AHB
- * SRAM IO buffer. Sad... so inefficient. But without exposing
- * the AHB SRAM to the final, end-user client I don't know of any
- * way around this copy.
- */
-
- if (in && ret == OK)
- {
- memcpy(origbuf, buffer, buflen);
- }
-
- /* Then free the temporary I/O buffer */
-
- stm32_freeio(buffer);
- }
-#endif
-
- stm32_givesem(&priv->exclsem);
- return ret;
-}
-
-/*******************************************************************************
- * Name: stm32_disconnect
- *
- * Description:
- * Called by the class when an error occurs and driver has been disconnected.
- * The USB host driver should discard the handle to the class instance (it is
- * stale) and not attempt any further interaction with the class driver instance
- * (until a new instance is received from the create() method). The driver
- * should not called the class' disconnected() method.
- *
- * Input Parameters:
- * drvr - The USB host driver instance obtained as a parameter from the call to
- * the class create() method.
- *
- * Returned Values:
- * None
- *
- * Assumptions:
- * - Only a single class bound to a single device is supported.
- * - Never called from an interrupt handler.
- *
- *******************************************************************************/
-
-static void stm32_disconnect(FAR struct usbhost_driver_s *drvr)
-{
- struct stm32_usbhost_s *priv = (struct stm32_usbhost_s *)drvr;
- priv->class = NULL;
-}
-
-/*******************************************************************************
- * Initialization
- *******************************************************************************/
-/*******************************************************************************
- * Name: stm32_ep0init
- *
- * Description:
- * Initialize ED for EP0, add it to the control ED list, and enable control
- * transfers.
- *
- * Input Parameters:
- * priv - private driver state instance.
- *
- * Returned Values:
- * None
- *
- *******************************************************************************/
-
-static inline void stm32_ep0init(struct stm32_usbhost_s *priv)
-{
- uint32_t regval;
-
- /* Set up some default values */
-
- (void)stm32_ep0configure(&priv->drvr, 1, 8);
-
- /* Initialize the common tail TD. */
-
- memset(TDTAIL, 0, sizeof(struct stm32_gtd_s));
- TDTAIL->ed = EDCTRL;
-
- /* Link the common tail TD to the ED's TD list */
-
- memset(EDCTRL, 0, sizeof(struct stm32_ed_s));
- EDCTRL->hw.headp = (uint32_t)TDTAIL;
- EDCTRL->hw.tailp = (uint32_t)TDTAIL;
-
- /* Set the head of the control list to the EP0 EDCTRL (this would have to
- * change if we want more than on control EP queued at a time).
- */
-
- stm32_putreg(STM32_EDCTRL_ADDR, STM32_USBHOST_CTRLHEADED);
-
- /* ControlListEnable. This bit is set to enable the processing of the
- * Control list. Note: once enabled, it remains enabled and we may even
- * complete list processing before we get the bit set. We really
- * should never modify the control list while CLE is set.
- */
-
- regval = stm32_getreg(STM32_USBHOST_CTRL);
- regval |= OHCI_CTRL_CLE;
- stm32_putreg(regval, STM32_USBHOST_CTRL);
-}
-
-/*******************************************************************************
- * Public Functions
- *******************************************************************************/
-
-/*******************************************************************************
- * Name: usbhost_initialize
- *
- * Description:
- * Initialize USB host device controller hardware.
- *
- * Input Parameters:
- * controller -- If the device supports more than USB host controller, then
- * this identifies which controller is being intialized. Normally, this
- * is just zero.
- *
- * Returned Value:
- * And instance of the USB host interface. The controlling task should
- * use this interface to (1) call the wait() method to wait for a device
- * to be connected, and (2) call the enumerate() method to bind the device
- * to a class driver.
- *
- * Assumptions:
- * - This function should called in the initialization sequence in order
- * to initialize the USB device functionality.
- * - Class drivers should be initialized prior to calling this function.
- * Otherwise, there is a race condition if the device is already connected.
- *
- *******************************************************************************/
-
-FAR struct usbhost_driver_s *usbhost_initialize(int controller)
-{
- struct stm32_usbhost_s *priv = &g_usbhost;
- uint32_t regval;
- uint8_t *buffer;
- irqstate_t flags;
- int i;
-
- /* Sanity checks. NOTE: If certain OS features are enabled, it may be
- * necessary to increase the size of STM32_ED/TD_SIZE in stm32_ohciram.h
- */
-
- DEBUGASSERT(controller == 0);
- DEBUGASSERT(sizeof(struct stm32_ed_s) <= STM32_ED_SIZE);
- DEBUGASSERT(sizeof(struct stm32_gtd_s) <= STM32_TD_SIZE);
-
- /* Initialize the state data structure */
-
- sem_init(&priv->rhssem, 0, 0);
- sem_init(&priv->exclsem, 0, 1);
-
-#ifndef CONFIG_USBHOST_INT_DISABLE
- priv->ininterval = MAX_PERINTERVAL;
- priv->outinterval = MAX_PERINTERVAL;
-#endif
-
- /* Enable power by setting PCUSB in the PCONP register. Disable interrupts
- * because this register may be shared with other drivers.
- */
-
- flags = irqsave();
- regval = stm32_getreg(STM32_SYSCON_PCONP);
- regval |= SYSCON_PCONP_PCUSB;
- stm32_putreg(regval, STM32_SYSCON_PCONP);
- irqrestore(flags);
-
- /* Enable clocking on USB (USB PLL clocking was initialized in very low-
- * evel clock setup logic (see stm32_clockconfig.c)). We do still need
- * to set up USBOTG CLKCTRL to enable clocking.
- *
- * NOTE: The PORTSEL clock needs to be enabled only when accessing OTGSTCTRL
- */
-
- stm32_putreg(STM32_CLKCTRL_ENABLES, STM32_USBOTG_CLKCTRL);
-
- /* Then wait for the clocks to be reported as "ON" */
-
- do
- {
- regval = stm32_getreg(STM32_USBOTG_CLKST);
- }
- while ((regval & STM32_CLKCTRL_ENABLES) != STM32_CLKCTRL_ENABLES);
-
- /* Set the OTG status and control register. Bits 0:1 apparently mean:
- *
- * 00: U1=device, U2=host
- * 01: U1=host, U2=host
- * 10: reserved
- * 11: U1=host, U2=device
- *
- * We need only select U1=host (Bit 0=1, Bit 1 is not used on STM32);
- * NOTE: The PORTSEL clock needs to be enabled when accessing OTGSTCTRL
- */
-
- stm32_putreg(1, STM32_USBOTG_STCTRL);
-
- /* Now we can turn off the PORTSEL clock */
-
- stm32_putreg((STM32_CLKCTRL_ENABLES & ~USBOTG_CLK_PORTSELCLK), STM32_USBOTG_CLKCTRL);
-
- /* Configure I/O pins */
-
- usbhost_dumpgpio();
- stm32_configgpio(GPIO_USB_DP); /* Positive differential data */
- stm32_configgpio(GPIO_USB_DM); /* Negative differential data */
- stm32_configgpio(GPIO_USB_UPLED); /* GoodLink LED control signal */
- stm32_configgpio(GPIO_USB_PPWR); /* Port Power enable signal for USB port */
- stm32_configgpio(GPIO_USB_PWRD); /* Power Status for USB port (host power switch) */
- stm32_configgpio(GPIO_USB_OVRCR); /* USB port Over-Current status */
- usbhost_dumpgpio();
-
- udbg("Initializing Host Stack\n");
-
- /* Show AHB SRAM memory map */
-
-#if 0 /* Useful if you have doubts about the layout */
- uvdbg("AHB SRAM:\n");
- uvdbg(" HCCA: %08x %d\n", STM32_HCCA_BASE, STM32_HCCA_SIZE);
- uvdbg(" TDTAIL: %08x %d\n", STM32_TDTAIL_ADDR, STM32_TD_SIZE);
- uvdbg(" EDCTRL: %08x %d\n", STM32_EDCTRL_ADDR, STM32_ED_SIZE);
- uvdbg(" EDFREE: %08x %d\n", STM32_EDFREE_BASE, STM32_ED_SIZE);
- uvdbg(" TDFREE: %08x %d\n", STM32_TDFREE_BASE, STM32_EDFREE_SIZE);
- uvdbg(" TBFREE: %08x %d\n", STM32_TBFREE_BASE, STM32_TBFREE_SIZE);
- uvdbg(" IOFREE: %08x %d\n", STM32_IOFREE_BASE, STM32_IOBUFFERS * CONFIG_USBHOST_IOBUFSIZE);
-#endif
-
- /* Initialize all the TDs, EDs and HCCA to 0 */
-
- memset((void*)HCCA, 0, sizeof(struct ohci_hcca_s));
- memset((void*)TDTAIL, 0, sizeof(struct ohci_gtd_s));
- memset((void*)EDCTRL, 0, sizeof(struct stm32_ed_s));
- sem_init(&EDCTRL->wdhsem, 0, 0);
-
- /* Initialize user-configurable EDs */
-
- buffer = (uint8_t *)STM32_EDFREE_BASE;
- for (i = 0; i < CONFIG_USBHOST_NEDS; i++)
- {
- /* Put the ED in a free list */
-
- stm32_edfree((struct stm32_ed_s *)buffer);
- buffer += STM32_ED_SIZE;
- }
-
- /* Initialize user-configurable TDs */
-
- buffer = (uint8_t *)STM32_TDFREE_BASE;
- for (i = 0; i < CONFIG_USBHOST_NTDS; i++)
- {
- /* Put the ED in a free list */
-
- stm32_tdfree((struct stm32_gtd_s *)buffer);
- buffer += STM32_TD_SIZE;
- }
-
- /* Initialize user-configurable request/descriptor transfer buffers */
-
- buffer = (uint8_t *)STM32_TBFREE_BASE;
- for (i = 0; i < CONFIG_USBHOST_TDBUFFERS; i++)
- {
- /* Put the TD buffer in a free list */
-
- stm32_tbfree(buffer);
- buffer += CONFIG_USBHOST_TDBUFSIZE;
- }
-
-#if STM32_IOBUFFERS > 0
- /* Initialize user-configurable IO buffers */
-
- buffer = (uint8_t *)STM32_IOFREE_BASE;
- for (i = 0; i < STM32_IOBUFFERS; i++)
- {
- /* Put the IO buffer in a free list */
-
- stm32_freeio(buffer);
- buffer += CONFIG_USBHOST_IOBUFSIZE;
- }
-#endif
-
- /* Wait 50MS then perform hardware reset */
-
- up_mdelay(50);
-
- stm32_putreg(0, STM32_USBHOST_CTRL); /* Hardware reset */
- stm32_putreg(0, STM32_USBHOST_CTRLHEADED); /* Initialize control list head to Zero */
- stm32_putreg(0, STM32_USBHOST_BULKHEADED); /* Initialize bulk list head to Zero */
-
- /* Software reset */
-
- stm32_putreg(OHCI_CMDST_HCR, STM32_USBHOST_CMDST);
-
- /* Write Fm interval (FI), largest data packet counter (FSMPS), and
- * periodic start.
- */
-
- stm32_putreg(DEFAULT_FMINTERVAL, STM32_USBHOST_FMINT);
- stm32_putreg(DEFAULT_PERSTART, STM32_USBHOST_PERSTART);
-
- /* Put HC in operational state */
-
- regval = stm32_getreg(STM32_USBHOST_CTRL);
- regval &= ~OHCI_CTRL_HCFS_MASK;
- regval |= OHCI_CTRL_HCFS_OPER;
- stm32_putreg(regval, STM32_USBHOST_CTRL);
-
- /* Set global power in HcRhStatus */
-
- stm32_putreg(OHCI_RHSTATUS_SGP, STM32_USBHOST_RHSTATUS);
-
- /* Set HCCA base address */
-
- stm32_putreg((uint32_t)HCCA, STM32_USBHOST_HCCA);
-
- /* Set up EP0 */
-
- stm32_ep0init(priv);
-
- /* Clear pending interrupts */
-
- regval = stm32_getreg(STM32_USBHOST_INTST);
- stm32_putreg(regval, STM32_USBHOST_INTST);
-
- /* Enable OHCI interrupts */
-
- stm32_putreg((STM32_ALL_INTS|OHCI_INT_MIE), STM32_USBHOST_INTEN);
-
- /* Attach USB host controller interrupt handler */
-
- if (irq_attach(STM32_IRQ_USB, stm32_usbinterrupt) != 0)
- {
- udbg("Failed to attach IRQ\n");
- return NULL;
- }
-
- /* Enable USB interrupts at the SYCON controller. Disable interrupts
- * because this register may be shared with other drivers.
- */
-
- flags = irqsave();
- regval = stm32_getreg(STM32_SYSCON_USBINTST);
- regval |= SYSCON_USBINTST_ENINTS;
- stm32_putreg(regval, STM32_SYSCON_USBINTST);
- irqrestore(flags);
-
- /* If there is a USB device in the slot at power up, then we will not
- * get the status change interrupt to signal us that the device is
- * connected. We need to set the initial connected state accordingly.
- */
-
- regval = stm32_getreg(STM32_USBHOST_RHPORTST1);
- priv->connected = ((regval & OHCI_RHPORTST_CCS) != 0);
-
- /* Enable interrupts at the interrupt controller */
-
- up_enable_irq(STM32_IRQ_USB); /* enable USB interrupt */
- udbg("USB host Initialized, Device connected:%s\n",
- priv->connected ? "YES" : "NO");
-
- return &priv->drvr;
-}
diff --git a/nuttx/arch/arm/src/stm32/stm32_usbhost.h b/nuttx/arch/arm/src/stm32/stm32_usbhost.h
index 854c32723..d9bce33f7 100644
--- a/nuttx/arch/arm/src/stm32/stm32_usbhost.h
+++ b/nuttx/arch/arm/src/stm32/stm32_usbhost.h
@@ -47,6 +47,34 @@
#include "chip.h"
#include "chip/stm32_otgfs.h"
+#if defined(CONFIG_STM32_OTGFS) && defined(CONFIG_USBHOST)
+
+/************************************************************************************
+ * Public Functions
+ ************************************************************************************/
+/*
+ * STM32 USB OTG FS Host Driver Support
+ *
+ * Pre-requisites
+ *
+ * CONFIG_USBHOST - Enable general USB host support
+ * CONFIG_STM32_OTGFS - Enable the STM32 USB OTG FS block
+ * CONFIG_STM32_SYSCFG - Needed
+ *
+ * Options:
+ *
+ * CONFIG_STM32_OTGFS_RXFIFO_SIZE - Size of the RX FIFO in 32-bit words.
+ * Default 128 (512 bytes)
+ * CONFIG_STM32_OTGFS_NPTXFIFO_SIZE - Size of the non-periodic Tx FIFO
+ * in 32-bit words. Default 96 (384 bytes)
+ * CONFIG_STM32_OTGFS_PTXFIFO_SIZE - Size of the periodic Tx FIFO in 32-bit
+ * words. Default 96 (384 bytes)
+ * CONFIG_STM32_OTGFS_SOFINTR - Enable SOF interrupts. Why would you ever
+ * want to do that?
+ * CONFIG_STM32_USBHOST_REGDEBUG - Enable very low-level register access
+ * debug. Depends on CONFIG_DEBUG.
+ */
+
/************************************************************************************
* Public Functions
************************************************************************************/
@@ -61,11 +89,40 @@ extern "C" {
#define EXTERN extern
#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
#if defined(__cplusplus)
}
#endif
#endif /* __ASSEMBLY__ */
+#endif /* CONFIG_STM32_OTGFS && CONFIG_USBHOST */
#endif /* __ARCH_ARM_SRC_STM32_STM32_USBHOST_H */
diff --git a/nuttx/arch/arm/src/stm32/stm32f20xxx_rcc.c b/nuttx/arch/arm/src/stm32/stm32f20xxx_rcc.c
index 8cfd405de..335992524 100644
--- a/nuttx/arch/arm/src/stm32/stm32f20xxx_rcc.c
+++ b/nuttx/arch/arm/src/stm32/stm32f20xxx_rcc.c
@@ -616,7 +616,7 @@ static void stm32_stdclockconfig(void)
/* Set the PLL dividers and multiplers to configure the main PLL */
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);
/* Enable the main PLL */
diff --git a/nuttx/arch/arm/src/stm32/stm32f40xxx_rcc.c b/nuttx/arch/arm/src/stm32/stm32f40xxx_rcc.c
index 7ba341b2b..45980f288 100644
--- a/nuttx/arch/arm/src/stm32/stm32f40xxx_rcc.c
+++ b/nuttx/arch/arm/src/stm32/stm32f40xxx_rcc.c
@@ -618,7 +618,7 @@ static void stm32_stdclockconfig(void)
/* Set the PLL dividers and multiplers to configure the main PLL */
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);
/* Enable the main PLL */
diff --git a/nuttx/configs/Kconfig b/nuttx/configs/Kconfig
index 2f6595dbd..b67c11ab3 100644
--- a/nuttx/configs/Kconfig
+++ b/nuttx/configs/Kconfig
@@ -12,703 +12,28 @@ choice
be available for selection. Use ARCH_BOARD_CUSTOM to create a new
board configuration.
-config ARCH_BOARD_AMBER
- bool "Amber Web Server"
- depends on ARCH_CHIP_ATMEGA128
+config ARCH_BOARD_PX4FMU
+ bool "PX4FMU board"
+ depends on ARCH_CHIP_STM32F405RG
---help---
- This is placeholder for the SoC Robotics Amber Web Server that is based
- on the Atmel AVR ATMega128 MCU. There is not much there yet and what is
- there is untested due to tool-related issues.
+ PX4 system Flight Management Unit
-config ARCH_BOARD_AVR32DEV1
- bool "Atmel AVR32DEV1 board"
- depends on ARCH_CHIP_AT32UC3B0256
+config ARCH_BOARD_PX4IO
+ bool "PX4IO board"
+ depends on ARCH_CHIP_STM32F100C8
---help---
- This is a port of NuttX to the Atmel AVR32DEV1 board. That board is
- based on the Atmel AT32UC3B0256 MCU and uses a specially patched
- version of the GNU toolchain: The patches provide support for the
- AVR32 family. That patched GNU toolchain is available only from the
- Atmel website. STATUS: This port is functional but very basic. There
- are configurations for NSH and the OS test.
-
-config ARCH_BOARD_C5471EVM
- bool "Spectrum Digital C5471 evaluation board"
- depends on ARCH_CHIP_C5471
- ---help---
- This is a port to the Spectrum Digital C5471 evaluation board. The
- TMS320C5471 is a dual core processor from TI with an ARM7TDMI general
- purpose processor and a c54 DSP. It is also known as TMS320DA180 or just DA180.
- NuttX runs on the ARM core and is built with a GNU arm-elf toolchain*.
- This port is complete and verified.
-
-config ARCH_BOARD_COMPALE88
- bool "Compal e88 phone"
- depends on ARCH_CHIP_CALYPSO
- ---help---
- These directories contain the board support for compal e88 and e99 phones.
- These ports are based on patches contributed by Denis Carikli for both the
- compal e99 and e88. The patches were made by Alan Carvalho de Assis and
- Denis Carikli using the Stefan Richter's Osmocom-bb patches.
-
-config ARCH_BOARD_COMPALE99
- bool "Compal e99 phone"
- depends on ARCH_CHIP_CALYPSO
- ---help---
- These directories contain the board support for compal e88 and e99 phones.
- These ports are based on patches contributed by Denis Carikli for both the
- compal e99 and e88. The patches were made by Alan Carvalho de Assis and
- Denis Carikli using the Stefan Richter's Osmocom-bb patches.
-
-config ARCH_BOARD_DEMOS92S12NEC64
- bool "Freescale DMO9S12NE64 board"
- depends on ARCH_CHIP_MCS92S12NEC64
- ---help---
- Freescale DMO9S12NE64 board based on the MC9S12NE64 hcs12 cpu. This
- port uses the m9s12x GCC toolchain. STATUS: (Still) under development; it
- is code complete but has not yet been verified.
-
-config ARCH_BOARD_EA3131
- bool "Embedded Artists EA3131 Development board"
- depends on ARCH_CHIP_LPC3131
- ---help---
- Embedded Artists EA3131 Development board. This board is based on the
- an NXP LPC3131 MCU. This OS is built with the arm-elf toolchain*.
- STATUS: This port is complete and mature.
-
-config ARCH_BOARD_EA3152
- bool "Embedded Artists EA3152 Development board"
- depends on ARCH_CHIP_LPC3152
- ---help---
- Embedded Artists EA3152 Development board. This board is based on the
- an NXP LPC3152 MCU. This OS is built with the arm-elf toolchain*.
- STATUS: This port is has not be exercised well, but since it is
- a simple derivative of the ea3131, it should be fully functional.
-
-config ARCH_BOARD_EAGLE100
- bool "Micromint Eagle-100 Development board"
- depends on ARCH_CHIP_LM3S6918
- ---help---
- Micromint Eagle-100 Development board. This board is based on the
- an ARM Cortex-M3 MCU, the Luminary LM3S6918. This OS is built with the
- arm-elf toolchain*. STATUS: This port is complete and mature.
-
-config ARCH_BOARD_EKK_LM3S9B96
- bool "TI/Stellaris EKK-LM3S9B96"
- depends on ARCH_CHIP_LM3S9B96
- ---help---
- TI/Stellaris EKK-LM3S9B96 board. This board is based on the
- an EKK-LM3S9B96 which is a Cortex-M3.
-
-config ARCH_BOARD_EZ80F910200KITG
- bool "ZiLOG ez80f0910200kitg development kit"
- depends on ARCH_CHIP_EZ80F91
- ---help---
- ez80Acclaim! Microcontroller. This port use the ZiLOG ez80f0910200kitg
- development kit, eZ80F091 part, and the Zilog ZDS-II Windows command line
- tools. The development environment is Cygwin under WinXP.
-
-config ARCH_BOARD_EZ80F910200ZCO
- bool "ZiLOG ez80f0910200zco development kit"
- depends on ARCH_CHIP_EZ80F91
- ---help---
- ez80Acclaim! Microcontroller. This port use the Zilog ez80f0910200zco
- development kit, eZ80F091 part, and the Zilog ZDS-II Windows command line
- tools. The development environment is Cygwin under WinXP.
-
-config ARCH_BOARD_HYMINI_STM32V
- bool "HY-Mini STM32v board"
- depends on ARCH_CHIP_STM32F103VCT
- ---help---
- A configuration for the HY-Mini STM32v board. This board is based on the
- STM32F103VCT chip.
-
-config ARCH_BOARD_LINCOLN60
- bool "Micromint Lincoln 60 board"
- depends on ARCH_CHIP_LPC1769
- ---help---
- Micromint Lincoln 60 board using the NXP LPC1769 MCU.
-
-config ARCH_BOARD_KWIKSTIK_K40
- bool "FreeScale KwikStik-K40 development board"
- depends on ARCH_CHIP_MK40X256VLQ100
- ---help---
- Kinetis K40 Cortex-M4 MCU. This port uses the FreeScale KwikStik-K40
- development board.
-
-config ARCH_BOARD_LM3S6432S2E
- bool "Stellaris RDK-S2E Reference Design Kit"
- depends on ARCH_CHIP_LM3S6432
- ---help---
- Stellaris RDK-S2E Reference Design Kit and the MDL-S2E Ethernet to
- Serial module.
-
-config ARCH_BOARD_LM3S6965EK
- bool "Stellaris LM3S6965 Evaluation Kit"
- depends on ARCH_CHIP_LM3S6965
- ---help---
- Stellaris LM3S6965 Evaluation Kit. This board is based on the
- an ARM Cortex-M3 MCU, the Luminary/TI LM3S6965. This OS is built with the
- arm-elf toolchain*. STATUS: This port is complete and mature.
-
-config ARCH_BOARD_LM3S8962EK
- bool "Stellaris LMS38962 Evaluation Kit"
- depends on ARCH_CHIP_LM3S8962
- ---help---
- Stellaris LMS38962 Evaluation Kit.
-
-config ARCH_BOARD_LPCXPRESSO
- bool "NXP LPCExpresso LPC1768"
- depends on ARCH_CHIP_LPC1768
- ---help---
- Embedded Artists base board with NXP LPCExpresso LPC1768. This board
- is based on the NXP LPC1768. The Code Red toolchain is used by default.
-
-config ARCH_BOARD_LPC4330_XPLORER
- bool "NXG LPC4330-Xplorer"
- depends on ARCH_CHIP_LPC4330FET100
- ---help---
- NXG Technologoies LPC4330 Xplorer board. This board is based on the
- LPC4330FET100. The Code Red toolchain is used by default.
-
-config ARCH_BOARD_M68332EVB
- bool "Motoroloa M68332EVB"
- depends on ARCH_M68332
- ---help---
- This is a work in progress for the venerable m68322evb board from
- Motorola. This OS is also built with the arm-elf toolchain. STATUS:
- This port was never completed.
-
-config ARCH_BOARD_MBED
- bool "mbed LCP1768"
- depends on ARCH_CHIP_LPC1768
- ---help---
- The configurations in this directory support the mbed board (http://mbed.org)
- that features the NXP LPC1768 microcontroller. This OS is also built
- with the arm-elf toolchain*. STATUS: Contributed.
-
-config ARCH_BOARD_MCU123
- bool "mcu123.com LPC2148 Development Board"
- depends on ARCH_CHIP_LPC2148
- ---help---
- This port is for the NXP LPC2148 as provided on the mcu123.com
- lpc214x development board. This OS is also built with the arm-elf
- toolchain*. The port supports serial, timer0, spi, and usb.
-
-config ARCH_BOARD_MICROPENDOUS
- bool "Opendous Micropendous 3 board"
- depends on ARCH_CHIP_AT90USB646 || ARCH_CHIP_AT90USB647 || ARCH_CHIP_AT90USB1286 || ARCH_CHIP_AT90USB1287
- ---help---
- This is a port to the Opendous Micropendous 3 board. This board may
- be populated with either an AVR AT90USB646, 647, 1286, or 1287 MCU.
- Support is configured for the AT90USB647.
-
-config ARCH_BOARD_MX1ADS
- bool "Motorola MX1ADS development board"
- depends on ARCH_CHIP_IMX1
- ---help---
- This is a port to the Motorola MX1ADS development board. That board
- is based on the Freescale i.MX1 processor. The i.MX1 is an ARM920T.
- STATUS: This port is nearly code complete but was never fully
- integrated due to tool-related issues.
-
-config ARCH_BOARD_NE64BADGE
- bool "FEG NE64 /PoE Badge board"
- depends on ARCH_CHIP_MCS92S12NEC64
- ---help---
- Future Electronics Group NE64 /PoE Badge board based on the
- MC9S12NE64 hcs12 cpu. This port uses the m9s12x GCC toolchain.
- STATUS: Under development. The port is code-complete but has
- not yet been fully tested.
-
-config ARCH_BOARD_NTOSD_DM320
- bool "Neuros OSD v1.0 Dev Board"
- depends on ARCH_CHIP_DM320
- ---help---
- This port uses the Neuros OSD v1.0 Dev Board with a GNU arm-elf
- toolchain*: see
-
- http://wiki.neurostechnology.com/index.php/OSD_1.0_Developer_Home
-
- There are some differences between the Dev Board and the currently
- available commercial v1.0 Boards. See
-
- http://wiki.neurostechnology.com/index.php/OSD_Developer_Board_v1
-
- NuttX operates on the ARM9EJS of this dual core processor.
- STATUS: This port is code complete, verified, and included in the
- NuttX 0.2.1 release.
-
-config ARCH_BOARD_NUCLEUS2G
- bool "Nucleus 2G board"
- depends on ARCH_CHIP_LPC1768
- ---help---
- This port uses the Nucleus 2G board (with Babel CAN board). This board
- features an NXP LPC1768 processor. See the 2G website (http://www.2g-eng.com/)
- for more information about the Nucleus 2G.
-
-config ARCH_BOARD_LPC1766STK
- bool "Olimex LPC1766-STK board"
- depends on ARCH_CHIP_LPC1766
- ---help---
- This port uses the Olimex LPC1766-STK board and a GNU GCC toolchain* under
- Linux or Cygwin. STATUS: Complete and mature.
-
-config ARCH_BOARD_MIRTOO
- bool "Mirtoo PIC32 Module from Dimitech"
- depends on ARCH_CHIP_PIC32MX250F128D
- ---help---
- This is the port to the DTX1-4000L "Mirtoo" module. This module uses MicroChip
- PIC32MX250F128D. See http://www.dimitech.com/ for further information.
-
-config ARCH_BOARD_OLIMEXLPC2378
- bool "Olimex-lpc2378 board"
- depends on ARCH_CHIP_LPC2378
- ---help---
- This port uses the Olimex-lpc2378 board and a GNU arm-elf toolchain* under
- Linux or Cygwin. STATUS: ostest and NSH configurations available.
- This port for the NXP LPC2378 was contributed by Rommel Marcelo.
-
-config ARCH_BOARD_OLIMEX_STRP711
- bool "Olimex STR-P711 board"
- depends on ARCH_CHIP_STR71X
- ---help---
- This port uses the Olimex STR-P711 board and a GNU arm-elf toolchain* under
- Linux or Cygwin. See the http://www.olimex.com/dev/str-p711.html" for
- further information. STATUS: Configurations for the basic OS test and NSH
- are complete and verified.
-
-config ARCH_BOARD_PCBLOGICPIC32MX
- bool "PIC32MX board from PCB Logic Design Co"
- depends on ARCH_CHIP_PIC32MX460F512L
- ---help---
- This is the port of NuttX to the PIC32MX board from PCB Logic Design Co.
- This board features the MicroChip PIC32MX460F512L.
- The board is a very simple -- little more than a carrier for the PIC32
- MCU plus voltage regulation, debug interface, and an OTG connector.
- STATUS: Code complete but testing has been stalled due to tool related problems
- (PICkit 2 does not work with the PIC32).
-
-config ARCH_BOARD_PIC32_STARTERKIT
- bool "Microchip PIC32 Ethernet Starter Kit (DM320004)"
- depends on ARCH_CHIP_PIC32MX795F512L
- ---help---
- This is the port of NuttX to the Microchip PIC32 Ethernet Starter Kit
- (DM320004) with the Multimedia Expansion Board (MEB, DM320005).
- See www.microchip.com for further information.
-
-config ARCH_BOARD_PIC32_PIC32MX7MMB
- bool "Mikroelektronika PIC32MX7 MMB"
- depends on ARCH_CHIP_PIC32MX795F512L
- ---help---
- This is the port NuttX to the Mikroelektronika PIC32MX7 Multimedia Board
- (MMB). See http://www.mikroe.com/ for further information.
-
-config ARCH_BOARD_PJRC_87C52
- bool "PJRC 87C52 development system"
- depends on ARCH_CHIP_8052
- ---help---
- 8051 Microcontroller. This port uses the PJRC 87C52 development system
- and the SDCC toolchain. This port is not quite ready for prime time.
-
-config ARCH_BOARD_QEMU_I486
- bool "Qemu i486 Mode"
- depends on ARCH_QEMU
- ---help---
- Port of NuttX to QEMU in i486 mode. This port will also run on real i486
- hardwared (Google the Bifferboard).
-
-config ARCH_BOARD_RGMP
- bool "RGMP"
- depends on ARCH_RGMP
- ---help---
- RGMP stands for RTOS and GPOS on Multi-Processor. RGMP is a project for
- running GPOS and RTOS simultaneously on multi-processor platforms. You can
- port your favorite RTOS to RGMP together with an unmodified Linux to form a
- hybrid operating system. This makes your application able to use both RTOS
- and GPOS features.
-
- See http://rgmp.sourceforge.net/wiki/index.php/Main_Page for further information
- about RGMP.
-
-config ARCH_BOARD_SAM3UEK
- bool "Atmel SAM3U-EK development board"
- depends on ARCH_CHIP_AT91SAM3U4E
- ---help---
- The port of NuttX to the Atmel SAM3U-EK development board.
-
-config ARCH_BOARD_SKP16C26
- bool "Renesas SKP16C26 StarterKit"
- depends on ARCH_CHIP_M30262F8
- ---help---
- Renesas M16C processor on the Renesas SKP16C26 StarterKit. This port
- uses the GNU m32c toolchain. STATUS: The port is complete but untested
- due to issues with compiler internal errors.
-
-config ARCH_BOARD_STM3210E_EVAL
- bool "STMicro STM3210E-EVAL development board"
- depends on ARCH_CHIP_STM32F103ZET6
- ---help---
- STMicro STM3210E-EVAL development board based on the STMicro STM32F103ZET6
- microcontroller (ARM Cortex-M3). This port uses the GNU Cortex-M3
- toolchain.
-
-config ARCH_BOARD_STM3220G_EVAL
- bool "STMicro STM3220G-EVAL development board"
- depends on ARCH_CHIP_STM32F207IG
- ---help---
- STMicro STM3220G-EVAL development board based on the STMicro STM32F407IG
- microcontroller (ARM Cortex-M3).
-
-config ARCH_BOARD_STM3240G_EVAL
- bool "STMicro STM3240G-EVAL development board"
- depends on ARCH_CHIP_STM32F407IG
- ---help---
- STMicro STM3240G-EVAL development board based on the STMicro STM32F103ZET6
- microcontroller (ARM Cortex-M4 with FPU). This port uses a GNU Cortex-M4
- toolchain (such as CodeSourcery).
-
-config ARCH_BOARD_STM32F4_DISCOVERY
- bool "STMicro STM32F4-Discovery board"
- depends on ARCH_CHIP_STM32F407VG
- ---help---
- STMicro STM32F4-Discovery board boased on the STMIcro STM32F407VGT6 MCU.
-
-config ARCH_BOARD_SUREPIC32MX
- bool "Sure PIC32MX boards"
- depends on ARCH_CHIP_PIC32MX440F512H
- ---help---
- The "Advanced USB Storage Demo Board," Model DB-DP11215, from Sure
- Electronics (http://www.sureelectronics.net/). This board features
- the MicroChip PIC32MX440F512H. See also
- http://www.sureelectronics.net/goods.php?id=1168 for further
- information about the Sure DB-DP11215 board.
-
-config ARCH_BOARD_TEENSY
- bool "PJRC Teensy++ 2.0 board"
- depends on ARCH_CHIP_AT90USB1286
- ---help---
- This is the port of NuttX to the PJRC Teensy++ 2.0 board. This board is
- developed by http://pjrc.com/teensy/. The Teensy++ 2.0 is based
- on an Atmel AT90USB1286 MCU.
-
-config ARCH_BOARD_TWR_K60N512
- bool "FreeScale TWR-K60N512d evelopment board"
- depends on ARCH_CHIP_MK60N512VMD100
- ---help---
- Kinetis K60 Cortex-M4 MCU. This port uses the FreeScale TWR-K60N512
- development board.
-
-config ARCH_BOARD_UBW32
- bool "UBW32 v2.4 board from Sparkfun"
- depends on ARCH_CHIP_PIC32MX460F512L
- ---help---
- This is the port to the Sparkfun UBW32 board. This port uses the original v2.4
- board which is based on the MicroChip PIC32MX460F512L. See
- http://www.sparkfun.com/products/8971. This older version has been replaced
- with this board http://www.sparkfun.com/products/9713. See also
- http://www.schmalzhaus.com/UBW32/.
-
-config ARCH_BOARD_US7032EVB1
- bool "Hitachi SH-1/US7032EVB1 board"
- depends on ARCH_CHIP_SH7032
- ---help---
- This is a port of the Hitachi SH-1 on the Hitachi SH-1/US7032EVB1 board.
- STATUS: Work has just began on this port.
-
-config ARCH_BOARD_VSN
- bool "SOTEL NetClamps VSN sensor network platform"
- depends on ARCH_CHIP_STM32F103RET6
- ---help---
- ISOTEL NetClamps VSN V1.2 ready2go sensor network platform based on the
- STMicro STM32F103RET6. Contributed by Uros Platise. See
- http://isotel.eu/NetClamps/
-
-config ARCH_BOARD_XTRS
- bool "XTRS TRS80 Model 3 emulation"
- depends on ARCH_CHIP_Z80
- ---help---
- TRS80 Model 3. This port uses a vintage computer based on the Z80.
- An emulator for this computer is available to run TRS80 programs on a
- linux platform (http://www.tim-mann.org/xtrs.html).
-
-config ARCH_BOARD_Z16F2800100ZCOG
- bool "Zilog Z16F2800100ZCOG Development Kit"
- depends on ARCH_CHIP_Z16F281
- ---help---
- z16f Microcontroller. This port use the ZiLIG z16f2800100zcog
- development kit and the Zilog ZDS-II Windows command line tools. The
- development environment is Cygwin under WinXP.
-
-config ARCH_BOARD_Z80SIM
- bool "Z80 Instruction Set Simulator"
- depends on ARCH_CHIP_Z80
- ---help---
- z80 Microcontroller. This port uses a Z80 instruction set simulator.
- That simulator can be found in the NuttX SVN at
- http://nuttx.svn.sourceforge.net/viewvc/nuttx/trunk/misc/sims/z80sim.
- This port also uses the SDCC toolchain (http://sdcc.sourceforge.net/")
- (verified with version 2.6.0).
-
-config ARCH_BOARD_Z8ENCORE000ZCO
- bool "ZiLOG z8encore000zco Development Kit"
- depends on ARCH_CHIP_Z8F6403
- ---help---
- z8Encore! Microcontroller. This port use the ZiLOG z8encore000zco
- development kit, Z8F6403 part, and the Zilog ZDS-II Windows command line
- tools. The development environment is Cygwin under WinXP.
-
-config ARCH_BOARD_Z8F64200100KI
- bool "ZiLOG Z8F64200100KIT Development Kit"
- depends on ARCH_CHIP_Z8F642X
- ---help---
- z8Encore! Microcontroller. This port use the Zilog z8f64200100kit
- development kit, Z8F6423 part, and the Zilog ZDS-II Windows command line
- tools. The development environment is Cygwin under WinXP.
-
-config ARCH_BOARD_SIM
- bool "User mode simulation"
- depends on ARCH_SIM
- ---help---
- A user-mode port of NuttX to the x86 Linux/Cygwin platform is available.
- The purpose of this port is primarily to support OS feature development.
- This port does not support interrupts or a real timer (and hence no
- round robin scheduler) Otherwise, it is complete.
-
-config ARCH_BOARD_CUSTOM
- bool "Custom development board"
- ---help---
- Select this option if there is no directory for the board under configs/.
-
- Don't see the board you want? You must first select the exact MCU part
- number, then the boards supporting that part will be available for selection.
-
+ PX4 system I/O expansion board
endchoice
config ARCH_BOARD
string
- default "amber" if ARCH_BOARD_AMBER
- default "avr32dev1" if ARCH_BOARD_AVR32DEV1
- default "c5471evm" if ARCH_BOARD_C5471EVM
- default "compal_e88" if ARCH_BOARD_COMPALE88
- default "compal_e99" if ARCH_BOARD_COMPALE99
- default "demo9s12ne64" if ARCH_BOARD_DEMOS92S12NEC64
- default "ea3131" if ARCH_BOARD_EA3131
- default "ea3152" if ARCH_BOARD_EA3152
- default "eagle100" if ARCH_BOARD_EAGLE100
- default "ekk-lm3s9b96" if ARCH_BOARD_EKK_LM3S9B96
- default "ez80f0910200kitg" if ARCH_BOARD_EZ80F910200KITG
- default "ez80f0910200zco" if ARCH_BOARD_EZ80F910200ZCO
- default "hymini-stm32v" if ARCH_BOARD_HYMINI_STM32V
- default "kwikstik-k40" if ARCH_BOARD_KWIKSTIK_K40
- default "lincoln60" if ARCH_BOARD_LINCOLN60
- default "lm3s6432-s2e" if ARCH_BOARD_LM3S6432S2E
- default "lm3s6965-ek" if ARCH_BOARD_LM3S6965EK
- default "lm3s8962-ek" if ARCH_BOARD_LM3S8962EK
- default "lpc4330-xplorer" if ARCH_BOARD_LPC4330_XPLORER
- default "lpcxpresso-lpc1768" if ARCH_BOARD_LPCXPRESSO
- default "m68322evb" if ARCH_BOARD_M68332EVB
- default "mbed" if ARCH_BOARD_MBED
- default "mcu123-lpc214x" if ARCH_BOARD_MCU123
- default "micropendous3" if ARCH_BOARD_MICROPENDOUS
- default "mirtoo" if ARCH_BOARD_MIRTOO
- default "mx1ads" if ARCH_BOARD_MX1ADS
- default "ne64badge" if ARCH_BOARD_NE64BADGE
- default "ntosd-dm320" if ARCH_BOARD_NTOSD_DM320
- default "nucleus2g" if ARCH_BOARD_NUCLEUS2G
- default "olimex-lpc1766stk" if ARCH_BOARD_LPC1766STK
- default "olimex-lpc2378" if ARCH_BOARD_OLIMEXLPC2378
- default "olimex-strp711" if ARCH_BOARD_OLIMEX_STRP711
- default "pcblogic-pic32mx" if ARCH_BOARD_PCBLOGICPIC32MX
- default "pic32-starterkit" if ARCH_BOARD_PIC32_STARTERKIT
- default "pic32mx7mmb" if ARCH_BOARD_PIC32_PIC32MX7MMB
- default "pjrc-8051" if ARCH_BOARD_PJRC_87C52
- default "qemu-i486" if ARCH_BOARD_QEMU_I486
- default "rgmp" if ARCH_BOARD_RGMP
- default "sam3u-ek" if ARCH_BOARD_SAM3UEK
- default "skp16c26" if ARCH_BOARD_SKP16C26
- default "stm3210e-eval" if ARCH_BOARD_STM3210E_EVAL
- default "stm3220g-eval" if ARCH_BOARD_STM3220G_EVAL
- default "stm3240g-eval" if ARCH_BOARD_STM3240G_EVAL
- default "stm32f4discovery" if ARCH_BOARD_STM32F4_DISCOVERY
- default "sure-pic32mx" if ARCH_BOARD_SUREPIC32MX
- default "teensy" if ARCH_BOARD_TEENSY
- default "twr-k60n512" if ARCH_BOARD_TWR_K60N512
- default "ubw32" if ARCH_BOARD_UBW32
- default "us7032evb1" if ARCH_BOARD_US7032EVB1
- default "vsn" if ARCH_BOARD_VSN
- default "xtrs" if ARCH_BOARD_XTRS
- default "z16f2800100zcog" if ARCH_BOARD_Z16F2800100ZCOG
- default "z80sim" if ARCH_BOARD_Z80SIM
- default "z8encore000zco" if ARCH_BOARD_Z8ENCORE000ZCO
- default "z8f64200100kit" if ARCH_BOARD_Z8F64200100KI
- default "sim" if ARCH_BOARD_SIM
+ default "px4fmu" if ARCH_BOARD_PX4FMU
+ default "px4io" if ARCH_BOARD_PX4IO
default "" if ARCH_BOARD_CUSTOM
-if ARCH_BOARD_AMBER
-source "configs/amber/Kconfig"
-endif
-if ARCH_BOARD_AVR32DEV1
-source "configs/avr32dev1/Kconfig"
-endif
-if ARCH_BOARD_C5471EVM
-source "configs/c5471evm/Kconfig"
-endif
-if ARCH_BOARD_COMPALE88
-source "configs/compal_e88/Kconfig"
-endif
-if ARCH_BOARD_COMPALE99
-source "configs/compal_e99/Kconfig"
-endif
-if ARCH_BOARD_DEMOS92S12NEC64
-source "configs/demo9s12ne64/Kconfig"
-endif
-if ARCH_BOARD_EA3131
-source "configs/ea3131/Kconfig"
-endif
-if ARCH_BOARD_EA3152
-source "configs/ea3152/Kconfig"
-endif
-if ARCH_BOARD_EAGLE100
-source "configs/eagle100/Kconfig"
-endif
-if ARCH_BOARD_EKK_LM3S9B96
-source "configs/ekk-lm3s9b96/Kconfig"
-endif
-if ARCH_BOARD_EZ80F910200KITG
-source "configs/ez80f910200kitg/Kconfig"
-endif
-if ARCH_BOARD_EZ80F910200ZCO
-source "configs/ez80f910200zco/Kconfig"
-endif
-if ARCH_BOARD_HYMINI_STM32V
-source "configs/hymini-stm32v/Kconfig"
-endif
-if ARCH_BOARD_KWIKSTIK_K40
-source "configs/kwikstik-k40/Kconfig"
-endif
-if ARCH_BOARD_LINCOLN60
-source "configs/lincoln60/Kconfig"
-endif
-if ARCH_BOARD_LM3S6432S2E
-source "configs/lm3s6432-s2e/Kconfig"
-endif
-if ARCH_BOARD_LM3S6965EK
-source "configs/lm3s6965-ek/Kconfig"
-endif
-if ARCH_BOARD_LM3S8962EK
-source "configs/lm3s8962-ek/Kconfig"
-endif
-if ARCH_BOARD_LPC4330_XPLORER
-source "configs/lpc4330-xplorer/Kconfig"
-endif
-if ARCH_BOARD_LPCXPRESSO
-source "configs/lpcxpresso-lpc1768/Kconfig"
-endif
-if ARCH_BOARD_M68332EVB
-source "configs/m68332evb/Kconfig"
-endif
-if ARCH_BOARD_MBED
-source "configs/mbed/Kconfig"
-endif
-if ARCH_BOARD_MCU123
-source "configs/mcu123-lpc214x/Kconfig"
-endif
-if ARCH_BOARD_MICROPENDOUS
-source "configs/micropendous3/Kconfig"
-endif
-if ARCH_BOARD_MIRTOO
-source "configs/mirtoo/Kconfig"
-endif
-if ARCH_BOARD_MX1ADS
-source "configs/mx1ads/Kconfig"
-endif
-if ARCH_BOARD_NE64BADGE
-source "configs/ne64badge/Kconfig"
-endif
-if ARCH_BOARD_NTOSD_DM320
-source "configs/ntosd-dm320/Kconfig"
-endif
-if ARCH_BOARD_NUCLEUS2G
-source "configs/nucleus2g/Kconfig"
-endif
-if ARCH_BOARD_LPC1766STK
-source "configs/olimex-lpc1766stk/Kconfig"
-endif
-if ARCH_BOARD_OLIMEXLPC2378
-source "configs/olimex-lpc2378/Kconfig"
-endif
-if ARCH_BOARD_OLIMEX_STRP711
-source "configs/olimex-strp711/Kconfig"
-endif
-if ARCH_BOARD_PCBLOGICPIC32MX
-source "configs/pcblogic-pic32mx/Kconfig"
-endif
-if ARCH_BOARD_PIC32_STARTERKIT
-source "configs/pic32-starterkit/Kconfig"
-endif
-if ARCH_BOARD_PIC32_PIC32MX7MMB
-source "configs/pic32mx7mmb/Kconfig"
-endif
-if ARCH_BOARD_PJRC_87C52
-source "configs/pjrc-8051/Kconfig"
-endif
-if ARCH_BOARD_QEMU_I486
-source "configs/qemu-i486/Kconfig"
-endif
-if ARCH_BOARD_RGMP
-source "configs/rgmp/Kconfig"
-endif
-if ARCH_BOARD_SAM3UEK
-source "configs/sam3u-ek/Kconfig"
-endif
-if ARCH_BOARD_SKP16C26
-source "configs/skp16c26/Kconfig"
-endif
-if ARCH_BOARD_STM3210E_EVAL
-source "configs/stm3210e-eval/Kconfig"
-endif
-if ARCH_BOARD_STM3220G_EVAL
-source "configs/stm3220g-eval/Kconfig"
-endif
-if ARCH_BOARD_STM3240G_EVAL
-source "configs/stm3240g-eval/Kconfig"
-endif
-if ARCH_BOARD_STM32F4_DISCOVERY
-source "configs/stm32f4discovery/Kconfig"
-endif
-if ARCH_BOARD_SUREPIC32MX
-source "configs/sure-pic32mx/Kconfig"
-endif
-if ARCH_BOARD_TEENSY
-source "configs/teensy/Kconfig"
-endif
-if ARCH_BOARD_TWR_K60N512
-source "configs/twr-k60n512/Kconfig"
-endif
-if ARCH_BOARD_UBW32
-source "configs/ubw32/Kconfig"
-endif
-if ARCH_BOARD_US7032EVB1
-source "configs/us7032evb1/Kconfig"
-endif
-if ARCH_BOARD_VSN
-source "configs/vsn/Kconfig"
-endif
-if ARCH_BOARD_XTRS
-source "configs/xtrs/Kconfig"
-endif
-if ARCH_BOARD_Z16F2800100ZCOG
-source "configs/z16f2800100zcog/Kconfig"
-endif
-if ARCH_BOARD_Z80SIM
-source "configs/z80sim/Kconfig"
-endif
-if ARCH_BOARD_Z8ENCORE000ZCO
-source "configs/z8encore000zco/Kconfig"
-endif
-if ARCH_BOARD_Z8F64200100KI
-source "configs/z8f64200100kit/Kconfig"
+if ARCH_BOARD_PX4FMU
+source "configs/px4fmu/Kconfig"
endif
-if ARCH_BOARD_SIM
-source "configs/sim/Kconfig"
+if ARCH_BOARD_PX4IO
+source "configs/px4io/Kconfig"
endif
diff --git a/nuttx/configs/px4fmu/Kconfig b/nuttx/configs/px4fmu/Kconfig
new file mode 100644
index 000000000..b5e6d5515
--- /dev/null
+++ b/nuttx/configs/px4fmu/Kconfig
@@ -0,0 +1,26 @@
+#
+# For a description of the syntax of this configuration file,
+# see misc/tools/kconfig-language.txt.
+#
+
+if ARCH_BOARD_PX4FMU
+config ARCH_LEDS
+ bool "NuttX LED support"
+ default n
+ ---help---
+ "Support control of board LEDs by NuttX to indicate system state"
+
+config ARCH_BUTTONS
+ bool "Button support"
+ default n
+ ---help---
+ "Support interfaces to use buttons provided by the board."
+
+config ARCH_IRQBUTTONS
+ bool "Button interrupt support"
+ default n
+ depends on ARCH_BUTTONS
+ ---help---
+ "Support EXTI interrupts on button presses and releases."
+
+endif
diff --git a/nuttx/configs/px4fmu/include/board.h b/nuttx/configs/px4fmu/include/board.h
index 60a295f8d..a7dae6552 100755
--- a/nuttx/configs/px4fmu/include/board.h
+++ b/nuttx/configs/px4fmu/include/board.h
@@ -106,7 +106,7 @@
#define STM32_PLLCFG_PLLM RCC_PLLCFG_PLLM(24)
#define STM32_PLLCFG_PLLN RCC_PLLCFG_PLLN(336)
#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
diff --git a/nuttx/configs/px4fmu/nsh/Make.defs b/nuttx/configs/px4fmu/nsh/Make.defs
index 87508e22e..3e6f88bd3 100644
--- a/nuttx/configs/px4fmu/nsh/Make.defs
+++ b/nuttx/configs/px4fmu/nsh/Make.defs
@@ -1,3 +1,3 @@
include ${TOPDIR}/.config
-include $(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/common/Make.defs
+include $(TOPDIR)/configs/px4fmu/common/Make.defs
diff --git a/nuttx/configs/px4fmu/nsh/appconfig b/nuttx/configs/px4fmu/nsh/appconfig
index 834b18165..b5d963e8b 100644
--- a/nuttx/configs/px4fmu/nsh/appconfig
+++ b/nuttx/configs/px4fmu/nsh/appconfig
@@ -63,10 +63,7 @@ CONFIGURED_APPS += systemcmds/eeprom
CONFIGURED_APPS += uORB
-ifeq ($(CONFIG_MAVLINK),y)
CONFIGURED_APPS += mavlink
-endif
-
CONFIGURED_APPS += gps
CONFIGURED_APPS += commander
#CONFIGURED_APPS += sdlog
diff --git a/nuttx/configs/px4fmu/nsh/defconfig b/nuttx/configs/px4fmu/nsh/defconfig
index 5eb3f1f29..b991a68c0 100755
--- a/nuttx/configs/px4fmu/nsh/defconfig
+++ b/nuttx/configs/px4fmu/nsh/defconfig
@@ -1,7 +1,8 @@
############################################################################
# configs/px4fmu/nsh/defconfig
#
-# Copyright (C) 2011 Gregory Nutt. All rights reserved.
+# Copyright (C) 2012 PX4 Development Team. All rights reserved.
+# Copyright (C) 2011-2012 Gregory Nutt. All rights reserved.
# Author: Gregory Nutt <gnutt@nuttx.org>
#
# Redistribution and use in source and binary forms, with or without
@@ -41,7 +42,7 @@
# particular chip family that the architecture is implemented
# in.
# CONFIG_ARCH_architecture - for use in C code. This identifies the
-# specific architecture within the chip familyl.
+# specific architecture within the chip family.
# CONFIG_ARCH_CHIP - Identifies the arch/*/chip subdirectory
# CONFIG_ARCH_CHIP_name - For use in C code
# CONFIG_ARCH_BOARD - identifies the configs subdirectory and, hence,
@@ -51,7 +52,6 @@
# CONFIG_BOARD_LOOPSPERMSEC - for delay loops
# CONFIG_DRAM_SIZE - Describes the installed DRAM.
# CONFIG_DRAM_START - The start address of DRAM (physical)
-# CONFIG_DRAM_END - Last address+1 of installed RAM
# CONFIG_ARCH_IRQPRIO - The STM3240xxx supports interrupt prioritization
# CONFIG_ARCH_FPU - The STM3240xxx supports a floating point unit (FPU).
# CONFIG_ARCH_INTERRUPTSTACK - This architecture supports an interrupt
@@ -70,17 +70,16 @@
# the delay actually is 100 seconds.
# CONFIG_ARCH_DMA - Support DMA initialization
#
-CONFIG_ARCH=arm
+CONFIG_ARCH="arm"
CONFIG_ARCH_ARM=y
CONFIG_ARCH_CORTEXM4=y
-CONFIG_ARCH_CHIP=stm32
+CONFIG_ARCH_CHIP="stm32"
CONFIG_ARCH_CHIP_STM32F405RG=y
-CONFIG_ARCH_BOARD=px4fmu
+CONFIG_ARCH_BOARD="px4fmu"
CONFIG_ARCH_BOARD_PX4FMU=y
CONFIG_BOARD_LOOPSPERMSEC=16717
CONFIG_DRAM_SIZE=0x00030000
CONFIG_DRAM_START=0x20000000
-CONFIG_DRAM_END=(CONFIG_DRAM_START+CONFIG_DRAM_SIZE)
CONFIG_ARCH_IRQPRIO=y
CONFIG_ARCH_FPU=y
CONFIG_ARCH_INTERRUPTSTACK=n
@@ -94,25 +93,8 @@ CONFIG_ARCH_MATH_H=y
CONFIG_ARMV7M_CMNVECTOR=y
-#
-# LIBC printf() options
-#
-# CONFIG_LIBC_FLOATINGPOINT - Enables printf("%f")
-# CONFIG_LIBC_FIXEDPRECISION - Sets 7 digits after dot for printing:
-# 5.1234567
-# CONFIG_HAVE_LONG_LONG - Enabled printf("%llu)
-#
-CONFIG_LIBC_FLOATINGPOINT=y
-CONFIG_HAVE_LONG_LONG=y
-#CONFIG_LIBC_FIXEDPRECISION=7
-#
-# CMSIS options
-#
-# CONFIG_DSPLIB_TARGET - Target for the CMSIS DSP library, one of
-# CortexM0, CortexM3 or CortexM4 (with fpu)
-#
-CONFIG_CMSIS_DSPLIB_TARGET=CortexM4
+
#
# JTAG Enable settings (by default JTAG-DP and SW-DP are enabled):
@@ -132,6 +114,14 @@ CONFIG_STM32_JTAG_NOJNTRST_ENABLE=n
CONFIG_STM32_JTAG_SW_ENABLE=n
#
+# On-chip CCM SRAM configuration
+#
+# CONFIG_STM32_CCMEXCLUDE - Exclude CCM SRAM from the HEAP. You would need
+# to do this if DMA is enabled to prevent non-DMA-able CCM memory from
+# being a part of the stack.
+#
+
+#
# On-board FSMC SRAM configuration
#
# CONFIG_STM32_FSMC - Required. See below
@@ -181,6 +171,7 @@ CONFIG_STM32_TIM12=y
CONFIG_STM32_TIM13=y
CONFIG_STM32_TIM14=y
CONFIG_STM32_WWDG=y
+CONFIG_STM32_IWDG=n
CONFIG_STM32_SPI2=n
CONFIG_STM32_SPI3=y
CONFIG_STM32_USART2=y
@@ -211,40 +202,6 @@ CONFIG_STM32_TIM9=y
CONFIG_STM32_TIM10=y
CONFIG_STM32_TIM11=y
-#
-# Configure the ADC
-#
-CONFIG_ADC=y
-# select trigger timer
-CONFIG_STM32_TIM4_ADC3=y
-# select sample frequency 1^=1.5Msamples/second
-# 65535^=10samples/second 16bit-timer runs at 84/128 MHz
-CONFIG_STM32_ADC3_SAMPLE_FREQUENCY=6000
-# select timer channel 0=CC1,...,3=CC4
-CONFIG_STM32_ADC3_TIMTRIG=3
-CONFIG_ADC_DMA=y
-# only 4 places usable!
-CONFIG_ADC_FIFOSIZE=5
-
-#
-# Timer and I2C devices may need to the following to force power to be applied:
-#
-#CONFIG_STM32_FORCEPOWER=y
-
-#
-# I2C configuration
-#
-CONFIG_I2C=y
-CONFIG_I2C_POLLED=y
-CONFIG_I2C_TRANSFER=y
-CONFIG_I2C_WRITEREAD=y
-CONFIG_I2C_TRACE=n
-# Allow 180 us per byte, a wide margin for the 400 KHz clock we're using
-# e.g. 9.6 ms for an EEPROM page write, 0.9 ms for a MAG update
-CONFIG_STM32_I2CTIMEOUS_PER_BYTE=200
-# Constant overhead for generating I2C start / stop conditions
-CONFIG_STM32_I2CTIMEOUS_START_STOP=700
-CONFIG_DEBUG_I2C=n
#
# Enable the MTD driver for the onboard I2C EEPROM
@@ -368,13 +325,6 @@ CONFIG_PWM_SERVO=n
CONFIG_MULTIPORT=n
#
-# CONFIG_UART2_RTS_CTS_AS_GPIO
-# If set, enables RTS and CTS pins as additional GPIOs 2 and 3
-#
-CONFIG_PX4_UART2_RTS_CTS_AS_GPIO=y
-
-
-#
# STM32F40xxx specific SPI device driver settings
#
CONFIG_SPI_EXCHANGE=y
@@ -386,6 +336,8 @@ CONFIG_SPI_EXCHANGE=y
#
# CONFIG_CAN - Enables CAN support (one or both of CONFIG_STM32_CAN1 or
# CONFIG_STM32_CAN2 must also be defined)
+# CONFIG_CAN_EXTID - Enables support for the 29-bit extended ID. Default
+# Standard 11-bit IDs.
# CONFIG_CAN_FIFOSIZE - The size of the circular buffer of CAN messages.
# Default: 8
# CONFIG_CAN_NPENDINGRTR - The size of the list of pending RTR requests.
@@ -394,8 +346,11 @@ CONFIG_SPI_EXCHANGE=y
# mode for testing. The STM32 CAN driver does support loopback mode.
# CONFIG_CAN1_BAUD - CAN1 BAUD rate. Required if CONFIG_STM32_CAN1 is defined.
# CONFIG_CAN2_BAUD - CAN1 BAUD rate. Required if CONFIG_STM32_CAN2 is defined.
+# CONFIG_CAN_TSEG1 - The number of CAN time quanta in segment 1. Default: 6
+# CONFIG_CAN_TSEG2 - the number of CAN time quanta in segment 2. Default: 7
#
CONFIG_CAN=n
+CONFIG_CAN_EXTID=n
#CONFIG_CAN_FIFOSIZE
#CONFIG_CAN_NPENDINGRTR
CONFIG_CAN_LOOPBACK=n
@@ -403,6 +358,42 @@ CONFIG_CAN1_BAUD=700000
CONFIG_CAN2_BAUD=700000
#
+# I2C configuration
+#
+CONFIG_I2C=y
+CONFIG_I2C_POLLED=y
+CONFIG_I2C_TRANSFER=y
+CONFIG_I2C_TRACE=n
+# Allow 180 us per byte, a wide margin for the 400 KHz clock we're using
+# e.g. 9.6 ms for an EEPROM page write, 0.9 ms for a MAG update
+CONFIG_STM32_I2CTIMEOUS_PER_BYTE=200
+# Constant overhead for generating I2C start / stop conditions
+CONFIG_STM32_I2CTIMEOUS_START_STOP=700
+# XXX this is bad and we want it gone
+CONFIG_I2C_WRITEREAD=y
+
+#
+# ADC configuration
+#
+# Enable ADC driver support.
+#
+# CONFIG_ADC=y : Enable the generic ADC infrastructure
+# CONFIG_STM32_TIM1_ADC=y : Indicate that timer 1 will be used to trigger an ADC
+# CONFIG_STM32_TIM1_ADC3=y : Assign timer 1 to drive ADC3 sampling
+# CONFIG_STM32_ADC3_SAMPLE_FREQUENCY=100 : Select a sampling frequency
+#
+CONFIG_ADC=y
+CONFIG_STM32_TIM4_ADC3=y
+# select sample frequency 1^=1.5Msamples/second
+# 65535^=10samples/second 16bit-timer runs at 84/128 MHz
+CONFIG_STM32_ADC3_SAMPLE_FREQUENCY=6000
+# select timer channel 0=CC1,...,3=CC4
+CONFIG_STM32_ADC3_TIMTRIG=3
+CONFIG_ADC_DMA=y
+# only 4 places usable!
+CONFIG_ADC_FIFOSIZE=5
+
+#
# General build options
#
# CONFIG_RRLOAD_BINARY - make the rrload binary format used with
@@ -419,7 +410,7 @@ CONFIG_CAN2_BAUD=700000
# CONFIG_HAVE_LIBM - toolchain supports libm.a
#
CONFIG_RRLOAD_BINARY=n
-CONFIG_INTELHEX_BINARY=y
+CONFIG_INTELHEX_BINARY=n
CONFIG_MOTOROLA_SREC=n
CONFIG_RAW_BINARY=y
CONFIG_HAVE_LIBM=y
@@ -434,6 +425,9 @@ CONFIG_HAVE_LIBM=y
# CONFIG_DEBUG_SYMBOLS - build without optimization and with
# debug symbols (needed for use with a debugger).
# CONFIG_HAVE_CXX - Enable support for C++
+# CONFIG_HAVE_CXXINITIALIZE - The platform-specific logic includes support
+# for initialization of static C++ instances for this architecture
+# and for the selected toolchain (via up_cxxinitialize()).
# CONFIG_MM_REGIONS - If the architecture includes multiple
# regions of memory to allocate from, this specifies the
# number of memory regions that the memory manager must
@@ -508,7 +502,7 @@ CONFIG_HAVE_LIBM=y
# CONFIG_SCHED_WORKPRIORITY - The execution priority of the worker
# thread. Default: 50
# CONFIG_SCHED_WORKPERIOD - How often the worker thread checks for
-# work in units of microseconds. Default: 50*1000 (50 MS).
+# work in units of microseconds. Default: 50000 (50 MS).
# CONFIG_SCHED_WORKSTACKSIZE - The stack size allocated for the worker
# thread. Default: CONFIG_IDLETHREAD_STACKSIZE.
# CONFIG_SIG_SIGWORK - The signal number that will be used to wake-up
@@ -520,14 +514,20 @@ CONFIG_HAVE_LIBM=y
CONFIG_DEBUG=y
CONFIG_DEBUG_VERBOSE=y
CONFIG_DEBUG_SYMBOLS=y
-CONFIG_DEBUG_ANALOG=n
CONFIG_DEBUG_FS=n
CONFIG_DEBUG_GRAPHICS=n
CONFIG_DEBUG_LCD=n
CONFIG_DEBUG_USB=n
CONFIG_DEBUG_NET=n
CONFIG_DEBUG_RTC=n
+CONFIG_DEBUG_ANALOG=n
+CONFIG_DEBUG_PWM=n
+CONFIG_DEBUG_CAN=n
+CONFIG_DEBUG_I2C=n
+CONFIG_DEBUG_INPUT=n
+
CONFIG_HAVE_CXX=y
+CONFIG_HAVE_CXXINITIALIZE=n
CONFIG_MM_REGIONS=2
CONFIG_ARCH_LOWPUTC=y
CONFIG_MSEC_PER_TICK=1
@@ -549,14 +549,46 @@ CONFIG_FDCLONE_DISABLE=n
CONFIG_FDCLONE_STDIO=y
CONFIG_SDCLONE_DISABLE=y
CONFIG_SCHED_WORKQUEUE=y
-CONFIG_SCHED_WORKPRIORITY=199
-CONFIG_SCHED_WORKPERIOD=(5*1000)
+CONFIG_SCHED_WORKPRIORITY=192
+CONFIG_SCHED_WORKPERIOD=5000
CONFIG_SCHED_WORKSTACKSIZE=2048
CONFIG_SIG_SIGWORK=4
CONFIG_SCHED_WAITPID=y
CONFIG_SCHED_ATEXIT=n
#
+# System Logging
+#
+# CONFIG_SYSLOG - Enables the System Logging feature.
+# CONFIG_RAMLOG - Enables the RAM logging feature
+# CONFIG_RAMLOG_CONSOLE - Use the RAM logging device as a system console.
+# If this feature is enabled (along with CONFIG_DEV_CONSOLE), then all
+# console output will be re-directed to a circular buffer in RAM. This
+# is useful, for example, if the only console is a Telnet console. Then
+# in that case, console output from non-Telnet threads will go to the
+# circular buffer and can be viewed using the NSH 'dmesg' command.
+# CONFIG_RAMLOG_SYSLOG - Use the RAM logging device for the syslogging
+# interface. If this feature is enabled (along with CONFIG_SYSLOG),
+# then all debug output (only) will be re-directed to the circular
+# buffer in RAM. This RAM log can be view from NSH using the 'dmesg'
+# command.
+# CONFIG_RAMLOG_NPOLLWAITERS - The number of threads than can be waiting
+# for this driver on poll(). Default: 4
+#
+# If CONFIG_RAMLOG_CONSOLE or CONFIG_RAMLOG_SYSLOG is selected, then the
+# following may also be provided:
+#
+# CONFIG_RAMLOG_CONSOLE_BUFSIZE - Size of the console RAM log. Default: 1024
+#
+
+CONFIG_SYSLOG=n
+CONFIG_RAMLOG=n
+CONFIG_RAMLOG_CONSOLE=n
+CONFIG_RAMLOG_SYSLOG=n
+#CONFIG_RAMLOG_NPOLLWAITERS
+#CONFIG_RAMLOG_CONSOLE_BUFSIZE
+
+#
# The following can be used to disable categories of
# APIs supported by the OS. If the compiler supports
# weak functions, then it should not be necessary to
@@ -585,8 +617,14 @@ CONFIG_DISABLE_POLL=n
#
# CONFIG_NOPRINTF_FIELDWIDTH - sprintf-related logic is a
# little smaller if we do not support fieldwidthes
+# CONFIG_LIBC_FLOATINGPOINT - Enables printf("%f")
+# CONFIG_LIBC_FIXEDPRECISION - Sets 7 digits after dot for printing:
+# 5.1234567
+# CONFIG_HAVE_LONG_LONG - Enabled printf("%llu)
#
CONFIG_NOPRINTF_FIELDWIDTH=n
+CONFIG_LIBC_FLOATINGPOINT=y
+CONFIG_HAVE_LONG_LONG=y
#
# Allow for architecture optimized implementations
@@ -803,42 +841,6 @@ CONFIG_USBDEV_TRACE=n
CONFIG_USBDEV_TRACE_NRECORDS=512
#
-# USB Serial Device Configuration (Prolifics PL2303 emulation)
-#
-# CONFIG_PL2303
-# Enable compilation of the USB serial driver
-# CONFIG_PL2303_EPINTIN
-# The logical 7-bit address of a hardware endpoint that supports
-# interrupt IN operation
-# CONFIG_PL2303_EPBULKOUT
-# The logical 7-bit address of a hardware endpoint that supports
-# bulk OUT operation
-# CONFIG_PL2303_EPBULKIN
-# The logical 7-bit address of a hardware endpoint that supports
-# bulk IN operation
-# # CONFIG_PL2303_NWRREQS and CONFIG_PL2303_NRDREQS
-# The number of write/read requests that can be in flight
-# CONFIG_PL2303_VENDORID and CONFIG_PL2303_VENDORSTR
-# The vendor ID code/string
-# CONFIG_PL2303_PRODUCTID and CONFIG_PL2303_PRODUCTSTR
-# The product ID code/string
-# CONFIG_PL2303_RXBUFSIZE and CONFIG_PL2303_TXBUFSIZE
-# Size of the serial receive/transmit buffers
-#
-CONFIG_PL2303=n
-CONFIG_PL2303_EPINTIN=1
-CONFIG_PL2303_EPBULKOUT=2
-CONFIG_PL2303_EPBULKIN=3
-CONFIG_PL2303_NWRREQS=4
-CONFIG_PL2303_NRDREQS=4
-CONFIG_PL2303_VENDORID=0x067b
-CONFIG_PL2303_PRODUCTID=0x2303
-CONFIG_PL2303_VENDORSTR="Nuttx"
-CONFIG_PL2303_PRODUCTSTR="USBdev Serial"
-CONFIG_PL2303_RXBUFSIZE=512
-CONFIG_PL2303_TXBUFSIZE=512
-
-#
# USB serial device class driver (Standard CDC ACM class)
#
# CONFIG_CDCACM
@@ -910,44 +912,6 @@ CONFIG_CDCACM_PRODUCTSTR="PX4 FMU v1.6"
#CONFIG_CDCACM_RXBUFSIZE
#CONFIG_CDCACM_TXBUFSIZE
-#
-# USB Storage Device Configuration
-#
-# CONFIG_USBMSC
-# Enable compilation of the USB storage driver
-# CONFIG_USBMSC_EP0MAXPACKET
-# Max packet size for endpoint 0
-# CONFIG_USBMSC_EPBULKOUT and CONFIG_USBMSC_EPBULKIN
-# The logical 7-bit address of a hardware endpoints that support
-# bulk OUT and IN operations
-# CONFIG_USBMSC_NWRREQS and CONFIG_USBMSC_NRDREQS
-# The number of write/read requests that can be in flight
-# CONFIG_USBMSC_BULKINREQLEN and CONFIG_USBMSC_BULKOUTREQLEN
-# The size of the buffer in each write/read request. This
-# value needs to be at least as large as the endpoint
-# maxpacket and ideally as large as a block device sector.
-# CONFIG_USBMSC_VENDORID and CONFIG_USBMSC_VENDORSTR
-# The vendor ID code/string
-# CONFIG_USBMSC_PRODUCTID and CONFIG_USBMSC_PRODUCTSTR
-# The product ID code/string
-# CONFIG_USBMSC_REMOVABLE
-# Select if the media is removable
-#
-CONFIG_USBMSC=n
-CONFIG_USBMSC_EP0MAXPACKET=64
-CONFIG_USBMSC_EPBULKOUT=2
-CONFIG_USBMSC_EPBULKIN=5
-CONFIG_USBMSC_NRDREQS=2
-CONFIG_USBMSC_NWRREQS=2
-CONFIG_USBMSC_BULKINREQLEN=256
-CONFIG_USBMSC_BULKOUTREQLEN=256
-CONFIG_USBMSC_VENDORID=0x584e
-CONFIG_USBMSC_VENDORSTR="NuttX"
-CONFIG_USBMSC_PRODUCTID=0x5342
-CONFIG_USBMSC_PRODUCTSTR="USBdev Storage"
-CONFIG_USBMSC_VERSIONNO=0x0399
-CONFIG_USBMSC_REMOVABLE=y
-
#
# Settings for apps/nshlib
@@ -958,7 +922,6 @@ CONFIG_USBMSC_REMOVABLE=y
# CONFIG_NSH_FILEIOSIZE - Size of a static I/O buffer
# CONFIG_NSH_STRERROR - Use strerror(errno)
# CONFIG_NSH_LINELEN - Maximum length of one command line
-# CONFIG_NSH_STACKSIZE - Stack size to use for new threads.
# CONFIG_NSH_NESTDEPTH - Max number of nested if-then[-else]-fi
# CONFIG_NSH_DISABLESCRIPT - Disable scripting support
# CONFIG_NSH_DISABLEBG - Disable background commands
@@ -1003,9 +966,9 @@ CONFIG_NSH_ARCHINIT=y
CONFIG_NSH_IOBUFFER_SIZE=512
CONFIG_NSH_DHCPC=n
CONFIG_NSH_NOMAC=y
-CONFIG_NSH_IPADDR=(10<<24|0<<16|0<<8|2)
-CONFIG_NSH_DRIPADDR=(10<<24|0<<16|0<<8|1)
-CONFIG_NSH_NETMASK=(255<<24|255<<16|255<<8|0)
+CONFIG_NSH_IPADDR=0x0a000002
+CONFIG_NSH_DRIPADDR=0x0a000001
+CONFIG_NSH_NETMASK=0xffffff00
CONFIG_NSH_ROMFSMOUNTPT="/etc"
CONFIG_NSH_INITSCRIPT="init.d/rcS"
CONFIG_NSH_ROMFSDEVNO=0
@@ -1022,13 +985,6 @@ CONFIG_NSH_MMCSDSPIPORTNO=3
CONFIG_NSH_MMCSDSLOTNO=0
CONFIG_NSH_MMCSDMINOR=0
-#
-# Settings for mavlink
-#
-# CONFIG_MAVLINK - Enable MAVLINK app
-# CONFIG_NSH_BUILTIN_APPS - Build the ADC test as an NSH built-in function.
-# Default: Built as a standalone problem
-CONFIG_MAVLINK=y
#
# Stack and heap information
diff --git a/nuttx/configs/px4io/io/Make.defs b/nuttx/configs/px4io/io/Make.defs
index 87508e22e..369772d03 100644
--- a/nuttx/configs/px4io/io/Make.defs
+++ b/nuttx/configs/px4io/io/Make.defs
@@ -1,3 +1,3 @@
include ${TOPDIR}/.config
-include $(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/common/Make.defs
+include $(TOPDIR)/configs/px4io/common/Make.defs
diff --git a/nuttx/configs/px4io/io/defconfig b/nuttx/configs/px4io/io/defconfig
index 8ae6afe3c..d710f398d 100755
--- a/nuttx/configs/px4io/io/defconfig
+++ b/nuttx/configs/px4io/io/defconfig
@@ -1,7 +1,8 @@
############################################################################
# configs/px4io/nsh/defconfig
#
-# Copyright (C) 2009-2012 Gregory Nutt. All rights reserved.
+# Copyright (C) 2012 PX4 Development Team. All rights reserved.
+# Copyright (C) 2011-2012 Gregory Nutt. All rights reserved.
# Author: Gregory Nutt <gnutt@nuttx.org>
#
# Redistribution and use in source and binary forms, with or without
@@ -41,7 +42,7 @@
# particular chip family that the architecture is implemented
# in.
# CONFIG_ARCH_architecture - for use in C code. This identifies the
-# specific architecture within the chip familyl.
+# specific architecture within the chip family.
# CONFIG_ARCH_CHIP - Identifies the arch/*/chip subdirectory
# CONFIG_ARCH_CHIP_name - For use in C code
# CONFIG_ARCH_BOARD - identifies the configs subdirectory and, hence,
@@ -51,7 +52,6 @@
# CONFIG_BOARD_LOOPSPERMSEC - for delay loops
# CONFIG_DRAM_SIZE - Describes the installed DRAM.
# CONFIG_DRAM_START - The start address of DRAM (physical)
-# CONFIG_DRAM_END - Last address+1 of installed RAM
# CONFIG_ARCH_IRQPRIO - The ST32F100CB supports interrupt prioritization
# CONFIG_ARCH_INTERRUPTSTACK - This architecture supports an interrupt
# stack. If defined, this symbol is the size of the interrupt
@@ -69,17 +69,16 @@
# the delay actually is 100 seconds.
# CONFIG_ARCH_DMA - Support DMA initialization
#
-CONFIG_ARCH=arm
+CONFIG_ARCH="arm"
CONFIG_ARCH_ARM=y
CONFIG_ARCH_CORTEXM3=y
-CONFIG_ARCH_CHIP=stm32
+CONFIG_ARCH_CHIP="stm32"
CONFIG_ARCH_CHIP_STM32F100C8=y
-CONFIG_ARCH_BOARD=px4io
+CONFIG_ARCH_BOARD="px4io"
CONFIG_ARCH_BOARD_PX4IO=y
CONFIG_BOARD_LOOPSPERMSEC=2000
CONFIG_DRAM_SIZE=0x00002000
CONFIG_DRAM_START=0x20000000
-CONFIG_DRAM_END=(CONFIG_DRAM_START+CONFIG_DRAM_SIZE)
CONFIG_ARCH_IRQPRIO=y
CONFIG_ARCH_INTERRUPTSTACK=n
CONFIG_ARCH_STACKDUMP=y
@@ -109,6 +108,7 @@ CONFIG_STM32_JTAG_SW_ENABLE=n
#
# Individual subsystems can be enabled:
+#
# AHB:
CONFIG_STM32_DMA1=n
CONFIG_STM32_DMA2=n
@@ -140,10 +140,6 @@ CONFIG_STM32_TIM8=n
CONFIG_STM32_USART1=y
CONFIG_STM32_ADC3=n
-#
-# Timer and I2C devices may need to the following to force power to be applied:
-#
-#CONFIG_STM32_FORCEPOWER=y
#
# STM32F100 specific serial device driver settings
@@ -306,9 +302,6 @@ CONFIG_HAVE_LIBM=n
# CONFIG_SDCLONE_DISABLE. Disable cloning of all socket
# desciptors by task_create() when a new task is started. If
# set, all sockets will appear to be closed in the new task.
-# CONFIG_NXFLAT. Enable support for the NXFLAT binary format.
-# This format will support execution of NuttX binaries located
-# in a ROMFS filesystem (see examples/nxflat).
# CONFIG_SCHED_WORKQUEUE. Create a dedicated "worker" thread to
# handle delayed processing from interrupt handlers. This feature
# is required for some drivers but, if there are not complaints,
@@ -327,11 +320,25 @@ CONFIG_HAVE_LIBM=n
# thread. Default: CONFIG_IDLETHREAD_STACKSIZE.
# CONFIG_SIG_SIGWORK - The signal number that will be used to wake-up
# the worker thread. Default: 4
+# CONFIG_SCHED_WAITPID - Enable the waitpid() API
+# CONFIG_SCHED_ATEXIT - Enabled the atexit() API
#
#CONFIG_APPS_DIR=
CONFIG_DEBUG=n
CONFIG_DEBUG_VERBOSE=n
CONFIG_DEBUG_SYMBOLS=y
+CONFIG_DEBUG_FS=n
+CONFIG_DEBUG_GRAPHICS=n
+CONFIG_DEBUG_LCD=n
+CONFIG_DEBUG_USB=n
+CONFIG_DEBUG_NET=n
+CONFIG_DEBUG_RTC=n
+CONFIG_DEBUG_ANALOG=n
+CONFIG_DEBUG_PWM=n
+CONFIG_DEBUG_CAN=n
+CONFIG_DEBUG_I2C=n
+CONFIG_DEBUG_INPUT=n
+
CONFIG_HAVE_CXX=n
CONFIG_HAVE_CXXINITIALIZE=n
CONFIG_MM_REGIONS=1
@@ -340,9 +347,9 @@ CONFIG_ARCH_LOWPUTC=y
CONFIG_RR_INTERVAL=200
CONFIG_SCHED_INSTRUMENTATION=n
CONFIG_TASK_NAME_SIZE=0
-CONFIG_START_YEAR=2009
-CONFIG_START_MONTH=9
-CONFIG_START_DAY=21
+CONFIG_START_YEAR=1970
+CONFIG_START_MONTH=1
+CONFIG_START_DAY=1
CONFIG_GREGORIAN_TIME=n
CONFIG_JULIAN_TIME=n
CONFIG_DEV_CONSOLE=y
@@ -354,12 +361,13 @@ CONFIG_SEM_NNESTPRIO=0
CONFIG_FDCLONE_DISABLE=n
CONFIG_FDCLONE_STDIO=y
CONFIG_SDCLONE_DISABLE=y
-CONFIG_NXFLAT=n
CONFIG_SCHED_WORKQUEUE=n
CONFIG_SCHED_WORKPRIORITY=50
-CONFIG_SCHED_WORKPERIOD=(50*1000)
+CONFIG_SCHED_WORKPERIOD=50000
CONFIG_SCHED_WORKSTACKSIZE=1024
CONFIG_SIG_SIGWORK=4
+CONFIG_SCHED_WAITPID=n
+CONFIG_SCHED_ATEXIT=n
#
# The following can be used to disable categories of
@@ -427,6 +435,14 @@ CONFIG_ARCH_BZERO=n
# CONFIG_NAME_MAX - The maximum size of a file name.
# CONFIG_STDIO_BUFFER_SIZE - Size of the buffer to allocate
# on fopen. (Only if CONFIG_NFILE_STREAMS > 0)
+# CONFIG_STDIO_LINEBUFFER - If standard C buffered I/O is enabled
+# (CONFIG_STDIO_BUFFER_SIZE > 0), then this option may be added
+# to force automatic, line-oriented flushing the output buffer
+# for putc(), fputc(), putchar(), puts(), fputs(), printf(),
+# fprintf(), and vfprintf(). When a newline is encountered in
+# the output string, the output buffer will be flushed. This
+# (slightly) increases the NuttX footprint but supports the kind
+# of behavior that people expect for printf().
# CONFIG_NUNGET_CHARS - Number of characters that can be
# buffered by ungetc() (Only if CONFIG_NFILE_STREAMS > 0)
# CONFIG_PREALLOC_MQ_MSGS - The number of pre-allocated message
@@ -452,6 +468,7 @@ CONFIG_NFILE_DESCRIPTORS=8
CONFIG_NFILE_STREAMS=0
CONFIG_NAME_MAX=32
CONFIG_STDIO_BUFFER_SIZE=64
+CONFIG_STDIO_LINEBUFFER=n
CONFIG_NUNGET_CHARS=2
CONFIG_PREALLOC_MQ_MSGS=4
CONFIG_MQ_MAXMSGSIZE=32
diff --git a/nuttx/drivers/Kconfig b/nuttx/drivers/Kconfig
index 6d4c5fc6a..f89862650 100644
--- a/nuttx/drivers/Kconfig
+++ b/nuttx/drivers/Kconfig
@@ -182,6 +182,10 @@ menuconfig LCD
Drivers for parallel and serial LCD and OLED type devices. These
drivers support interfaces as defined in include/nuttx/lcd/lcd.h
+ This selection is necessary to enable support for LCD drivers in
+ drivers/lcd as well as for board-specific LCD drivers in the configs/
+ subdirectories.
+
if LCD
source drivers/lcd/Kconfig
endif
diff --git a/nuttx/drivers/lcd/Kconfig b/nuttx/drivers/lcd/Kconfig
index af94ac16a..081a79c89 100644
--- a/nuttx/drivers/lcd/Kconfig
+++ b/nuttx/drivers/lcd/Kconfig
@@ -173,3 +173,42 @@ config LCD_UG9664HSWAG01
ug-9664hswag01.c. OLED Display Module, UG-9664HSWAG01", Univision
Technology Inc. Used with the LPC Xpresso and Embedded Artists
base board.
+
+choice
+ prompt "LCD Orientation"
+ default LCD_LANDSCAPE
+ depends on LCD
+ ---help---
+ Some LCD drivers may support displays in different orientations.
+ If the LCD driver supports this capability, than these are configuration
+ options to select that display orientation.
+
+config LCD_LANDSCAPE
+ bool "Landscape orientation"
+ ---help---
+ Define for "landscape" orientation support. Landscape mode refers one
+ of two orientations where the the display is wider than it is tall
+ (LCD_RLANDSCAPE is the other). This is the default orientation.
+
+config LCD_PORTRAIT
+ bool "Portrait orientation"
+ ---help---
+ Define for "portrait" orientation support. Portrait mode refers one
+ of two orientations where the the display is taller than it is wide
+ (LCD_RPORTAIT is the other).
+
+config LCD_RPORTRAIT
+ bool "Reverse portrait display"
+ ---help---
+ Define for "reverse portrait" orientation support. Reverse portrait mode
+ refers one of two orientations where the the display is taller than it is
+ wide (LCD_PORTAIT is the other).
+
+config LCD_RLANDSCAPE
+ bool "Reverse landscape orientation"
+ ---help---
+ Define for "reverse landscape" orientation support. Reverse landscape mode
+ refers one of two orientations where the the display is wider than it is
+ tall (LCD_LANDSCAPE is the other).
+
+endchoice
diff --git a/nuttx/drivers/sensors/Make.defs b/nuttx/drivers/sensors/Make.defs
index bd28ba070..d04e7541e 100644
--- a/nuttx/drivers/sensors/Make.defs
+++ b/nuttx/drivers/sensors/Make.defs
@@ -37,7 +37,10 @@
# These drivers depend on I2C support
ifeq ($(CONFIG_I2C),y)
+
+ifeq ($(CONFIG_I2C_TRANSFER),y)
CSRCS += lis331dl.c
+endif
ifeq ($(CONFIG_I2C_LM75),y)
CSRCS += lm75.c
diff --git a/nuttx/drivers/usbhost/usbhost_enumerate.c b/nuttx/drivers/usbhost/usbhost_enumerate.c
index 8e1cd80e7..36bfa20d1 100644
--- a/nuttx/drivers/usbhost/usbhost_enumerate.c
+++ b/nuttx/drivers/usbhost/usbhost_enumerate.c
@@ -1,8 +1,8 @@
/*******************************************************************************
* drivers/usbhost/usbhost_enumerate.c
*
- * Copyright (C) 2011 Gregory Nutt. All rights reserved.
- * Authors: Gregory Nutt <spudmonkey@racsa.co.cr>
+ * Copyright (C) 2011-2012 Gregory Nutt. All rights reserved.
+ * Authors: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@@ -122,8 +122,8 @@ static void usbhost_putle16(uint8_t *dest, uint16_t val)
*
*******************************************************************************/
-static inline int usbhost_devdesc(const struct usb_devdesc_s *devdesc,
- struct usbhost_id_s *id)
+static inline int usbhost_devdesc(FAR const struct usb_devdesc_s *devdesc,
+ FAR struct usbhost_id_s *id)
{
/* Clear the ID info */
@@ -131,7 +131,7 @@ static inline int usbhost_devdesc(const struct usb_devdesc_s *devdesc,
/* Pick off the class ID info */
- id->base = devdesc->class;
+ id->base = devdesc->classid;
id->subclass = devdesc->subclass;
id->proto = devdesc->protocol;
@@ -194,7 +194,7 @@ static inline int usbhost_configdesc(const uint8_t *configdesc, int cfglen,
*/
DEBUGASSERT(remaining >= sizeof(struct usb_ifdesc_s));
- id->base = ifdesc->class;
+ id->base = ifdesc->classid;
id->subclass = ifdesc->subclass;
id->proto = ifdesc->protocol;
uvdbg("class:%d subclass:%d protocol:%d\n",
diff --git a/nuttx/drivers/usbhost/usbhost_hidkbd.c b/nuttx/drivers/usbhost/usbhost_hidkbd.c
index ce951e1e6..73224ff5c 100644
--- a/nuttx/drivers/usbhost/usbhost_hidkbd.c
+++ b/nuttx/drivers/usbhost/usbhost_hidkbd.c
@@ -255,7 +255,9 @@ static inline int usbhost_devinit(FAR struct usbhost_state_s *priv);
static inline uint16_t usbhost_getle16(const uint8_t *val);
static inline void usbhost_putle16(uint8_t *dest, uint16_t val);
static inline uint32_t usbhost_getle32(const uint8_t *val);
+#if 0 /* Not used */
static void usbhost_putle32(uint8_t *dest, uint32_t val);
+#endif
/* Transfer descriptor memory management */
@@ -701,7 +703,7 @@ static int usbhost_kbdpoll(int argc, char *argv[])
#if defined(CONFIG_DEBUG_USB) && defined(CONFIG_DEBUG_VERBOSE)
unsigned int npolls = 0;
#endif
- unsigned int nerrors;
+ unsigned int nerrors = 0;
int ret;
uvdbg("Started\n");
@@ -1381,6 +1383,7 @@ static inline uint32_t usbhost_getle32(const uint8_t *val)
*
****************************************************************************/
+#if 0 /* Not used */
static void usbhost_putle32(uint8_t *dest, uint32_t val)
{
/* Little endian means LS halfword first in byte stream */
@@ -1388,6 +1391,7 @@ static void usbhost_putle32(uint8_t *dest, uint32_t val)
usbhost_putle16(dest, (uint16_t)(val & 0xffff));
usbhost_putle16(dest+2, (uint16_t)(val >> 16));
}
+#endif
/****************************************************************************
* Name: usbhost_tdalloc
diff --git a/nuttx/drivers/usbhost/usbhost_storage.c b/nuttx/drivers/usbhost/usbhost_storage.c
index 2817c2446..853287371 100644
--- a/nuttx/drivers/usbhost/usbhost_storage.c
+++ b/nuttx/drivers/usbhost/usbhost_storage.c
@@ -1,8 +1,8 @@
/****************************************************************************
* drivers/usbhost/usbhost_storage.c
*
- * Copyright (C) 2010-2011 Gregory Nutt. All rights reserved.
- * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ * Copyright (C) 2010-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
@@ -123,7 +123,7 @@ struct usbhost_state_s
struct usbhost_driver_s *drvr;
/* The remainder of the fields are provide to the mass storage class */
-
+
char sdchar; /* Character identifying the /dev/sd[n] device */
volatile bool disconnected; /* TRUE: Device has been disconnected */
uint8_t ifno; /* Interface number */
@@ -217,7 +217,7 @@ static inline int usbhost_tfree(FAR struct usbhost_state_s *priv);
static FAR struct usbmsc_cbw_s *usbhost_cbwalloc(FAR struct usbhost_state_s *priv);
/* struct usbhost_registry_s methods */
-
+
static struct usbhost_class_s *usbhost_create(FAR struct usbhost_driver_s *drvr,
FAR const struct usbhost_id_s *id);
@@ -248,7 +248,7 @@ static int usbhost_ioctl(FAR struct inode *inode, int cmd,
* Private Data
****************************************************************************/
-/* This structure provides the registry entry ID informatino that will be
+/* This structure provides the registry entry ID informatino that will be
* used to associate the USB host mass storage class to a connected USB
* device.
*/
@@ -416,7 +416,7 @@ static inline void usbhost_freeclass(FAR struct usbhost_state_s *class)
flags = irqsave();
class->class.flink = g_freelist;
g_freelist = class;
- irqrestore(flags);
+ irqrestore(flags);
}
#else
static inline void usbhost_freeclass(FAR struct usbhost_state_s *class)
@@ -700,16 +700,16 @@ static inline int usbhost_testunitready(FAR struct usbhost_state_s *priv)
int result;
/* Initialize a CBW (re-using the allocated transfer buffer) */
-
+
cbw = usbhost_cbwalloc(priv);
if (!cbw)
{
udbg("ERROR: Failed to create CBW\n");
return -ENOMEM;
}
-
+
/* Construct and send the CBW */
-
+
usbhost_testunitreadycbw(cbw);
result = DRVR_TRANSFER(priv->drvr, priv->bulkout,
(uint8_t*)cbw, USBMSC_CBW_SIZEOF);
@@ -733,7 +733,7 @@ static inline int usbhost_requestsense(FAR struct usbhost_state_s *priv)
int result;
/* Initialize a CBW (re-using the allocated transfer buffer) */
-
+
cbw = usbhost_cbwalloc(priv);
if (!cbw)
{
@@ -742,7 +742,7 @@ static inline int usbhost_requestsense(FAR struct usbhost_state_s *priv)
}
/* Construct and send the CBW */
-
+
usbhost_requestsensecbw(cbw);
result = DRVR_TRANSFER(priv->drvr, priv->bulkout,
(uint8_t*)cbw, USBMSC_CBW_SIZEOF);
@@ -775,7 +775,7 @@ static inline int usbhost_readcapacity(FAR struct usbhost_state_s *priv)
int result;
/* Initialize a CBW (re-using the allocated transfer buffer) */
-
+
cbw = usbhost_cbwalloc(priv);
if (!cbw)
{
@@ -784,7 +784,7 @@ static inline int usbhost_readcapacity(FAR struct usbhost_state_s *priv)
}
/* Construct and send the CBW */
-
+
usbhost_readcapacitycbw(cbw);
result = DRVR_TRANSFER(priv->drvr, priv->bulkout,
(uint8_t*)cbw, USBMSC_CBW_SIZEOF);
@@ -823,7 +823,7 @@ static inline int usbhost_inquiry(FAR struct usbhost_state_s *priv)
int result;
/* Initialize a CBW (re-using the allocated transfer buffer) */
-
+
cbw = usbhost_cbwalloc(priv);
if (!cbw)
{
@@ -832,7 +832,7 @@ static inline int usbhost_inquiry(FAR struct usbhost_state_s *priv)
}
/* Construct and send the CBW */
-
+
usbhost_inquirycbw(cbw);
result = DRVR_TRANSFER(priv->drvr, priv->bulkout,
(uint8_t*)cbw, USBMSC_CBW_SIZEOF);
@@ -885,7 +885,7 @@ static void usbhost_destroy(FAR void *arg)
DEBUGASSERT(priv != NULL);
uvdbg("crefs: %d\n", priv->crefs);
-
+
/* Unregister the block driver */
usbhost_mkdevname(priv, devname);
@@ -965,10 +965,10 @@ static inline int usbhost_cfgdesc(FAR struct usbhost_state_s *priv,
uint8_t found = 0;
int ret;
- DEBUGASSERT(priv != NULL &&
+ DEBUGASSERT(priv != NULL &&
configdesc != NULL &&
desclen >= sizeof(struct usb_cfgdesc_s));
-
+
/* Verify that we were passed a configuration descriptor */
cfgdesc = (FAR struct usb_cfgdesc_s *)configdesc;
@@ -1004,7 +1004,7 @@ static inline int usbhost_cfgdesc(FAR struct usbhost_state_s *priv,
case USB_DESC_TYPE_INTERFACE:
{
FAR struct usb_ifdesc_s *ifdesc = (FAR struct usb_ifdesc_s *)configdesc;
-
+
uvdbg("Interface descriptor\n");
DEBUGASSERT(remaining >= USB_SIZEOF_IFDESC);
@@ -1078,7 +1078,7 @@ static inline int usbhost_cfgdesc(FAR struct usbhost_state_s *priv,
found |= USBHOST_BINFOUND;
/* Save the bulk IN endpoint information */
-
+
bindesc.addr = epdesc->addr & USB_EP_ADDR_NUMBER_MASK;
bindesc.in = 1;
bindesc.funcaddr = funcaddr;
@@ -1108,7 +1108,7 @@ static inline int usbhost_cfgdesc(FAR struct usbhost_state_s *priv,
}
/* Increment the address of the next descriptor */
-
+
configdesc += desc->len;
remaining -= desc->len;
}
@@ -1116,7 +1116,7 @@ static inline int usbhost_cfgdesc(FAR struct usbhost_state_s *priv,
/* Sanity checking... did we find all of things that we need? Hmmm.. I wonder..
* can we work read-only or write-only if only one bulk endpoint found?
*/
-
+
if (found != USBHOST_ALLFOUND)
{
ulldbg("ERROR: Found IF:%s BIN:%s BOUT:%s\n",
@@ -1202,7 +1202,7 @@ static inline int usbhost_initvolume(FAR struct usbhost_state_s *priv)
uvdbg("Test unit ready, retries=%d\n", retries);
/* Send TESTUNITREADY to see the unit is ready */
-
+
ret = usbhost_testunitready(priv);
if (ret == OK)
{
@@ -1585,7 +1585,7 @@ static FAR struct usbmsc_cbw_s *usbhost_cbwalloc(FAR struct usbhost_state_s *pri
* Name: usbhost_create
*
* Description:
- * This function implements the create() method of struct usbhost_registry_s.
+ * This function implements the create() method of struct usbhost_registry_s.
* The create() method is a callback into the class implementation. It is
* used to (1) create a new instance of the USB host class state and to (2)
* bind a USB host driver "session" to the class instance. Use of this
@@ -1644,9 +1644,9 @@ static FAR struct usbhost_class_s *usbhost_create(FAR struct usbhost_driver_s *d
priv->drvr = drvr;
/* NOTE: We do not yet know the geometry of the USB mass storage device */
-
+
/* Return the instance of the USB mass storage class */
-
+
return &priv->class;
}
}
@@ -1701,7 +1701,7 @@ static int usbhost_connect(FAR struct usbhost_class_s *class,
FAR struct usbhost_state_s *priv = (FAR struct usbhost_state_s *)class;
int ret;
- DEBUGASSERT(priv != NULL &&
+ DEBUGASSERT(priv != NULL &&
configdesc != NULL &&
desclen >= sizeof(struct usb_cfgdesc_s));
@@ -1722,7 +1722,7 @@ static int usbhost_connect(FAR struct usbhost_class_s *class,
udbg("usbhost_initvolume() failed: %d\n", ret);
}
}
-
+
return ret;
}
@@ -1792,7 +1792,7 @@ static int usbhost_disconnected(struct usbhost_class_s *class)
}
}
- irqrestore(flags);
+ irqrestore(flags);
return OK;
}
@@ -1945,45 +1945,52 @@ static ssize_t usbhost_read(FAR struct inode *inode, unsigned char *buffer,
ret = -ENOMEM;
/* Initialize a CBW (re-using the allocated transfer buffer) */
-
+
cbw = usbhost_cbwalloc(priv);
if (cbw)
{
- /* Assume some device failure */
-
- ret = -ENODEV;
+ /* Loop in the event that EAGAIN is returned (mean that the
+ * transaction was NAKed and we should try again.
+ */
- /* Construct and send the CBW */
-
- usbhost_readcbw(startsector, priv->blocksize, nsectors, cbw);
- result = DRVR_TRANSFER(priv->drvr, priv->bulkout,
- (uint8_t*)cbw, USBMSC_CBW_SIZEOF);
- if (result == OK)
+ do
{
- /* Receive the user data */
+ /* Assume some device failure */
+
+ ret = -ENODEV;
- result = DRVR_TRANSFER(priv->drvr, priv->bulkin,
- buffer, priv->blocksize * nsectors);
+ /* Construct and send the CBW */
+
+ usbhost_readcbw(startsector, priv->blocksize, nsectors, cbw);
+ result = DRVR_TRANSFER(priv->drvr, priv->bulkout,
+ (uint8_t*)cbw, USBMSC_CBW_SIZEOF);
if (result == OK)
{
- /* Receive the CSW */
+ /* Receive the user data */
result = DRVR_TRANSFER(priv->drvr, priv->bulkin,
- priv->tbuffer, USBMSC_CSW_SIZEOF);
+ buffer, priv->blocksize * nsectors);
if (result == OK)
{
- FAR struct usbmsc_csw_s *csw;
-
- /* Check the CSW status */
+ /* Receive the CSW */
- csw = (FAR struct usbmsc_csw_s *)priv->tbuffer;
- if (csw->status == 0)
+ result = DRVR_TRANSFER(priv->drvr, priv->bulkin,
+ priv->tbuffer, USBMSC_CSW_SIZEOF);
+ if (result == OK)
{
- ret = nsectors;
+ FAR struct usbmsc_csw_s *csw;
+
+ /* Check the CSW status */
+
+ csw = (FAR struct usbmsc_csw_s *)priv->tbuffer;
+ if (csw->status == 0)
+ {
+ ret = nsectors;
+ }
}
}
}
- }
+ } while (result == -EAGAIN);
}
usbhost_givesem(&priv->exclsem);
@@ -2037,7 +2044,7 @@ static ssize_t usbhost_write(FAR struct inode *inode, const unsigned char *buffe
ret = -ENOMEM;
/* Initialize a CBW (re-using the allocated transfer buffer) */
-
+
cbw = usbhost_cbwalloc(priv);
if (cbw)
{
@@ -2046,7 +2053,7 @@ static ssize_t usbhost_write(FAR struct inode *inode, const unsigned char *buffe
ret = -ENODEV;
/* Construct and send the CBW */
-
+
usbhost_writecbw(startsector, priv->blocksize, nsectors, cbw);
result = DRVR_TRANSFER(priv->drvr, priv->bulkout,
(uint8_t*)cbw, USBMSC_CBW_SIZEOF);
diff --git a/nuttx/include/nuttx/usb/usbhost.h b/nuttx/include/nuttx/usb/usbhost.h
index 133fd4387..acfe9a829 100644
--- a/nuttx/include/nuttx/usb/usbhost.h
+++ b/nuttx/include/nuttx/usb/usbhost.h
@@ -1,7 +1,7 @@
/************************************************************************************
* include/nuttx/usb/usbhost.h
*
- * Copyright (C) 2010-2011 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2010-2012 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* References:
@@ -284,7 +284,7 @@
* Some hardware supports special memory in which request and descriptor data can
* be accessed more efficiently. This method provides a mechanism to allocate
* the request/descriptor memory. If the underlying hardware does not support
- * such "special" memory, this functions may simply map to malloc.
+ * such "special" memory, this functions may simply map to kmalloc.
*
* This interface was optimized under a particular assumption. It was assumed
* that the driver maintains a pool of small, pre-allocated buffers for descriptor
@@ -317,7 +317,7 @@
* Some hardware supports special memory in which request and descriptor data can
* be accessed more efficiently. This method provides a mechanism to free that
* request/descriptor memory. If the underlying hardware does not support
- * such "special" memory, this functions may simply map to free().
+ * such "special" memory, this functions may simply map to kfree().
*
* Input Parameters:
* drvr - The USB host driver instance obtained as a parameter from the call to
@@ -342,7 +342,7 @@
* Some hardware supports special memory in which larger IO buffers can
* be accessed more efficiently. This method provides a mechanism to allocate
* the request/descriptor memory. If the underlying hardware does not support
- * such "special" memory, this functions may simply map to malloc.
+ * such "special" memory, this functions may simply map to kmalloc.
*
* This interface differs from DRVR_ALLOC in that the buffers are variable-sized.
*
@@ -371,7 +371,7 @@
* Some hardware supports special memory in which IO data can be accessed more
* efficiently. This method provides a mechanism to free that IO buffer
* memory. If the underlying hardware does not support such "special" memory,
- * this functions may simply map to free().
+ * this functions may simply map to kfree().
*
* Input Parameters:
* drvr - The USB host driver instance obtained as a parameter from the call to
@@ -448,7 +448,13 @@
*
* Returned Values:
* On success, zero (OK) is returned. On a failure, a negated errno value is
- * returned indicating the nature of the failure
+ * returned indicating the nature of the failure:
+ *
+ * EAGAIN - If devices NAKs the transfer (or NYET or other error where
+ * it may be appropriate to restart the entire transaction).
+ * EPERM - If the endpoint stalls
+ * EIO - On a TX or data toggle error
+ * EPIPE - Overrun errors
*
* Assumptions:
* This function will *not* be called from an interrupt handler.
@@ -553,7 +559,7 @@ struct usbhost_class_s
};
/* This structure describes one endpoint. It is used as an input to the
- * allocep() method. Most of this information comes from the endpoint
+ * epalloc() method. Most of this information comes from the endpoint
* descriptor.
*/
@@ -562,12 +568,12 @@ struct usbhost_epdesc_s
uint8_t addr; /* Endpoint address */
bool in; /* Direction: true->IN */
uint8_t funcaddr; /* USB address of function containing endpoint */
- uint8_t xfrtype; /* Transfer type. See SB_EP_ATTR_XFER_* in usb.h */
+ uint8_t xfrtype; /* Transfer type. See USB_EP_ATTR_XFER_* in usb.h */
uint8_t interval; /* Polling interval */
uint16_t mxpacketsize; /* Max packetsize */
};
-/* This type represents one endpoint configured by the allocep() method.
+/* This type represents one endpoint configured by the epalloc() method.
* The actual form is know only internally to the USB host controller
* (for example, for an OHCI driver, this would probably be a pointer
* to an endpoint descriptor).
@@ -615,7 +621,7 @@ struct usbhost_driver_s
* be accessed more efficiently. The following methods provide a mechanism
* to allocate and free the transfer descriptor memory. If the underlying
* hardware does not support such "special" memory, these functions may
- * simply map to malloc and free.
+ * simply map to kmalloc and kfree.
*
* This interface was optimized under a particular assumption. It was assumed
* that the driver maintains a pool of small, pre-allocated buffers for descriptor
@@ -630,7 +636,7 @@ struct usbhost_driver_s
/* Some hardware supports special memory in which larger IO buffers can
* be accessed more efficiently. This method provides a mechanism to allocate
* the request/descriptor memory. If the underlying hardware does not support
- * such "special" memory, this functions may simply map to malloc.
+ * such "special" memory, this functions may simply map to kmalloc.
*
* This interface differs from DRVR_ALLOC in that the buffers are variable-sized.
*/
diff --git a/nuttx/include/semaphore.h b/nuttx/include/semaphore.h
index 85214b9c2..257a5826f 100644
--- a/nuttx/include/semaphore.h
+++ b/nuttx/include/semaphore.h
@@ -60,16 +60,16 @@ extern "C" {
* Public Type Declarations
****************************************************************************/
-/* This structure contains the holder of a semaphore */
+/* This structure contains information about the holder of a semaphore */
#ifdef CONFIG_PRIORITY_INHERITANCE
struct semholder_s
{
#if CONFIG_SEM_PREALLOCHOLDERS > 0
- struct semholder_s *flink; /* Implements singly linked list */
+ struct semholder_s *flink; /* Implements singly linked list */
#endif
- void *holder; /* Holder TCB (actual type is _TCB) */
- int16_t counts; /* Number of counts owned by this holder */
+ void *htcb; /* Holder TCB (actual type is _TCB) */
+ int16_t counts; /* Number of counts owned by this holder */
};
#if CONFIG_SEM_PREALLOCHOLDERS > 0
@@ -83,12 +83,21 @@ struct semholder_s
struct sem_s
{
- int16_t semcount; /* >0 -> Num counts available */
- /* <0 -> Num tasks waiting for semaphore */
+ int16_t semcount; /* >0 -> Num counts available */
+ /* <0 -> Num tasks waiting for semaphore */
+ /* If priority inheritance is enabled, then we have to keep track of which
+ * tasks hold references to the semaphore.
+ */
+
#ifdef CONFIG_PRIORITY_INHERITANCE
- struct semholder_s hlist; /* List of holders of semaphore counts */
+# if CONFIG_SEM_PREALLOCHOLDERS > 0
+ FAR struct semholder_s *hhead; /* List of holders of semaphore counts */
+# else
+ struct semholder_s holder; /* Single holder */
+# endif
#endif
};
+
typedef struct sem_s sem_t;
/* Initializers */
diff --git a/nuttx/lib/semaphore/sem_init.c b/nuttx/lib/semaphore/sem_init.c
index ea1c6e84e..bc14415f9 100644
--- a/nuttx/lib/semaphore/sem_init.c
+++ b/nuttx/lib/semaphore/sem_init.c
@@ -103,16 +103,17 @@ int sem_init(FAR sem_t *sem, int pshared, unsigned int value)
{
/* Initialize the seamphore count */
- sem->semcount = (int16_t)value;
+ sem->semcount = (int16_t)value;
/* Initialize to support priority inheritance */
#ifdef CONFIG_PRIORITY_INHERITANCE
# if CONFIG_SEM_PREALLOCHOLDERS > 0
- sem->hlist.flink = NULL;
+ sem->hhead = NULL;
+# else
+ sem->holder.htcb = NULL;
+ sem->holder.counts = 0;
# endif
- sem->hlist.holder = NULL;
- sem->hlist.counts = 0;
#endif
return OK;
}
diff --git a/nuttx/sched/Kconfig b/nuttx/sched/Kconfig
index f82273638..9d7a38549 100644
--- a/nuttx/sched/Kconfig
+++ b/nuttx/sched/Kconfig
@@ -204,7 +204,7 @@ config SCHED_ONEXIT_MAX
config DISABLE_OS_API
bool "Disable NuttX interfaces"
- default n
+ default y
---help---
The following can be used to disable categories of
APIs supported by the OS. If the compiler supports
diff --git a/nuttx/sched/os_start.c b/nuttx/sched/os_start.c
index 6cd508b8c..c0b16236d 100644
--- a/nuttx/sched/os_start.c
+++ b/nuttx/sched/os_start.c
@@ -289,6 +289,18 @@ void os_start(void)
g_idletcb.flags = TCB_FLAG_TTYPE_KERNEL;
up_initial_state(&g_idletcb);
+ /* Initialize the semaphore facility(if in link). This has to be done
+ * very early because many subsystems depend upon fully functional
+ * semaphores.
+ */
+
+#ifdef CONFIG_HAVE_WEAKFUNCTIONS
+ if (sem_initialize != NULL)
+#endif
+ {
+ sem_initialize();
+ }
+
/* Initialize the memory manager */
#ifndef CONFIG_HEAP_BASE
@@ -351,15 +363,6 @@ void os_start(void)
}
#endif
- /* Initialize the semaphore facility. (if in link) */
-
-#ifdef CONFIG_HAVE_WEAKFUNCTIONS
- if (sem_initialize != NULL)
-#endif
- {
- sem_initialize();
- }
-
/* Initialize the named message queue facility (if in link) */
#ifndef CONFIG_DISABLE_MQUEUE
diff --git a/nuttx/sched/sched_waitpid.c b/nuttx/sched/sched_waitpid.c
index e8e2f61a2..692ef6410 100644
--- a/nuttx/sched/sched_waitpid.c
+++ b/nuttx/sched/sched_waitpid.c
@@ -178,7 +178,7 @@
pid_t waitpid(pid_t pid, int *stat_loc, int options)
{
- _TCB *tcb = sched_gettcb(pid);
+ _TCB *tcb;
bool mystat;
int err;
int ret;
@@ -186,6 +186,7 @@ pid_t waitpid(pid_t pid, int *stat_loc, int options)
/* Disable pre-emption so that nothing changes in the following tests */
sched_lock();
+ tcb = sched_gettcb(pid);
if (!tcb)
{
err = ECHILD;
diff --git a/nuttx/sched/sem_holder.c b/nuttx/sched/sem_holder.c
index 6003c563d..34f88185a 100644
--- a/nuttx/sched/sem_holder.c
+++ b/nuttx/sched/sem_holder.c
@@ -99,32 +99,31 @@ static inline FAR struct semholder_s *sem_allocholder(sem_t *sem)
* used to implement mutexes.
*/
- if (!sem->hlist.holder)
- {
- pholder = &sem->hlist;
- pholder->counts = 0;
- }
- else
- {
#if CONFIG_SEM_PREALLOCHOLDERS > 0
- pholder = g_freeholders;
- if (pholder)
- {
- /* Remove the holder from the free list an put it into the semaphore's holder list */
+ pholder = g_freeholders;
+ if (pholder)
+ {
+ /* Remove the holder from the free list an put it into the semaphore's holder list */
- g_freeholders = pholder->flink;
- pholder->flink = sem->hlist.flink;
- sem->hlist.flink = pholder;
+ g_freeholders = pholder->flink;
+ pholder->flink = sem->hhead;
+ sem->hhead = pholder;
- /* Make sure the initial count is zero */
+ /* Make sure the initial count is zero */
- pholder->counts = 0;
- }
- else
+ pholder->counts = 0;
+ }
#else
- pholder = NULL;
+ if (!sem->holder.htcb)
+ {
+ pholder = &sem->holder;
+ pholder->counts = 0;
+ }
#endif
+ else
+ {
sdbg("Insufficient pre-allocated holders\n");
+ pholder = NULL;
}
return pholder;
@@ -140,12 +139,13 @@ static FAR struct semholder_s *sem_findholder(sem_t *sem, FAR _TCB *htcb)
/* Try to find the holder in the list of holders associated with this semaphore */
- pholder = &sem->hlist;
#if CONFIG_SEM_PREALLOCHOLDERS > 0
- for (; pholder; pholder = pholder->flink)
+ for (pholder = sem->hhead; pholder; pholder = pholder->flink)
+#else
+ pholder = &sem->holder;
#endif
{
- if (pholder->holder == htcb)
+ if (pholder->htcb == htcb)
{
/* Got it! */
@@ -186,31 +186,33 @@ static inline void sem_freeholder(sem_t *sem, FAR struct semholder_s *pholder)
/* Release the holder and counts */
- pholder->holder = 0;
+ pholder->htcb = NULL;
pholder->counts = 0;
#if CONFIG_SEM_PREALLOCHOLDERS > 0
- /* If this is the holder inside the semaphore, then do nothing more */
+ /* Search the list for the matching holder */
- if (pholder != &sem->hlist)
- {
- /* Otherwise, search the list for the matching holder */
+ for (prev = NULL, curr = sem->hhead;
+ curr && curr != pholder;
+ prev = curr, curr = curr->flink);
- for (prev = &sem->hlist, curr = sem->hlist.flink;
- curr && curr != pholder;
- prev = curr, curr = curr->flink);
+ if (curr)
+ {
+ /* Remove the holder from the list */
- if (curr)
+ if (prev)
{
- /* Remove the holder from the list */
-
prev->flink = pholder->flink;
+ }
+ else
+ {
+ sem->hhead = pholder->flink;
+ }
- /* And put it in the free list */
+ /* And put it in the free list */
- pholder->flink = g_freeholders;
- g_freeholders = pholder;
- }
+ pholder->flink = g_freeholders;
+ g_freeholders = pholder;
}
#endif
}
@@ -221,14 +223,16 @@ static inline void sem_freeholder(sem_t *sem, FAR struct semholder_s *pholder)
static int sem_foreachholder(FAR sem_t *sem, holderhandler_t handler, FAR void *arg)
{
- FAR struct semholder_s *pholder = &sem->hlist;
+ FAR struct semholder_s *pholder;
#if CONFIG_SEM_PREALLOCHOLDERS > 0
FAR struct semholder_s *next;
#endif
int ret = 0;
#if CONFIG_SEM_PREALLOCHOLDERS > 0
- for (; pholder && ret == 0; pholder = next)
+ for (pholder = sem->hhead; pholder && ret == 0; pholder = next)
+#else
+ pholder = &sem->holder;
#endif
{
#if CONFIG_SEM_PREALLOCHOLDERS > 0
@@ -238,7 +242,7 @@ static int sem_foreachholder(FAR sem_t *sem, holderhandler_t handler, FAR void *
#endif
/* The initial "built-in" container may hold a NULL holder */
- if (pholder->holder)
+ if (pholder->htcb)
{
/* Call the handler */
@@ -268,7 +272,7 @@ static int sem_recoverholders(FAR struct semholder_s *pholder, FAR sem_t *sem, F
static int sem_boostholderprio(FAR struct semholder_s *pholder,
FAR sem_t *sem, FAR void *arg)
{
- FAR _TCB *htcb = (FAR _TCB *)pholder->holder;
+ FAR _TCB *htcb = (FAR _TCB *)pholder->htcb;
FAR _TCB *rtcb = (FAR _TCB*)arg;
/* Make sure that the thread is still active. If it exited without releasing
@@ -371,7 +375,7 @@ static int sem_boostholderprio(FAR struct semholder_s *pholder,
static int sem_verifyholder(FAR struct semholder_s *pholder, FAR sem_t *sem, FAR void *arg)
{
#if 0 // Need to revisit this, but these assumptions seem to be untrue -- OR there is a bug???
- FAR _TCB *htcb = (FAR _TCB *)pholder->holder;
+ FAR _TCB *htcb = (FAR _TCB *)pholder->htcb;
/* Called after a semaphore has been released (incremented), the semaphore
* could is non-negative, and there is no thread waiting for the count.
@@ -396,9 +400,9 @@ static int sem_dumpholder(FAR struct semholder_s *pholder, FAR sem_t *sem, FAR v
{
#if CONFIG_SEM_PREALLOCHOLDERS > 0
dbg(" %08x: %08x %08x %04x\n",
- pholder, pholder->flink, pholder->holder, pholder->counts);
+ pholder, pholder->flink, pholder->htcb, pholder->counts);
#else
- dbg(" %08x: %08x %04x\n", pholder, pholder->holder, pholder->counts);
+ dbg(" %08x: %08x %04x\n", pholder, pholder->htcb, pholder->counts);
#endif
return 0;
}
@@ -410,7 +414,7 @@ static int sem_dumpholder(FAR struct semholder_s *pholder, FAR sem_t *sem, FAR v
static int sem_restoreholderprio(FAR struct semholder_s *pholder, FAR sem_t *sem, FAR void *arg)
{
- FAR _TCB *htcb = (FAR _TCB *)pholder->holder;
+ FAR _TCB *htcb = (FAR _TCB *)pholder->htcb;
#if CONFIG_SEM_NNESTPRIO > 0
FAR _TCB *stcb = (FAR _TCB *)arg;
int rpriority;
@@ -510,6 +514,7 @@ static int sem_restoreholderprio(FAR struct semholder_s *pholder, FAR sem_t *sem
{
htcb->pend_reprios[i] = htcb->pend_reprios[j];
}
+
htcb->npend_reprio = j;
break;
}
@@ -534,7 +539,7 @@ static int sem_restoreholderprio(FAR struct semholder_s *pholder, FAR sem_t *sem
static int sem_restoreholderprioA(FAR struct semholder_s *pholder, FAR sem_t *sem, FAR void *arg)
{
FAR _TCB *rtcb = (FAR _TCB*)g_readytorun.head;
- if (pholder->holder != rtcb)
+ if (pholder->htcb != rtcb)
{
return sem_restoreholderprio(pholder, sem, arg);
}
@@ -545,7 +550,7 @@ static int sem_restoreholderprioA(FAR struct semholder_s *pholder, FAR sem_t *se
static int sem_restoreholderprioB(FAR struct semholder_s *pholder, FAR sem_t *sem, FAR void *arg)
{
FAR _TCB *rtcb = (FAR _TCB*)g_readytorun.head;
- if (pholder->holder == rtcb)
+ if (pholder->htcb == rtcb)
{
(void)sem_restoreholderprio(pholder, sem, arg);
return 1;
@@ -586,6 +591,7 @@ void sem_initholders(void)
{
g_holderalloc[i].flink = &g_holderalloc[i+1];
}
+
g_holderalloc[CONFIG_SEM_PREALLOCHOLDERS-1].flink = NULL;
#endif
}
@@ -609,8 +615,8 @@ void sem_initholders(void)
void sem_destroyholder(FAR sem_t *sem)
{
- /* It is an error is a semaphore is destroyed while there are any holders
- * (except perhaps the thread releas the semaphore itself). Hmmm.. but
+ /* It is an error if a semaphore is destroyed while there are any holders
+ * (except perhaps the thread release the semaphore itself). Hmmm.. but
* we actually have to assume that the caller knows what it is doing because
* could have killed another thread that is the actual holder of the semaphore.
* We cannot make any assumptions about the state of the semaphore or the
@@ -621,18 +627,18 @@ void sem_destroyholder(FAR sem_t *sem)
*/
#if CONFIG_SEM_PREALLOCHOLDERS > 0
- if (sem->hlist.holder || sem->hlist.flink)
+ if (sem->hhead)
{
sdbg("Semaphore destroyed with holders\n");
(void)sem_foreachholder(sem, sem_recoverholders, NULL);
}
#else
- if (sem->hlist.holder)
+ if (sem->holder.htcb)
{
sdbg("Semaphore destroyed with holder\n");
}
- sem->hlist.holder = NULL;
+ sem->holder.htcb = NULL;
#endif
}
@@ -664,7 +670,7 @@ void sem_addholder(FAR sem_t *sem)
{
/* Then set the holder and increment the number of counts held by this holder */
- pholder->holder = rtcb;
+ pholder->htcb = rtcb;
pholder->counts++;
}
}
diff --git a/nuttx/tools/mkconfig.c b/nuttx/tools/mkconfig.c
index 97e2a9c34..b3749266c 100644
--- a/nuttx/tools/mkconfig.c
+++ b/nuttx/tools/mkconfig.c
@@ -174,6 +174,12 @@ int main(int argc, char **argv, char **envp)
printf("#ifndef CONFIG_MM_REGIONS\n");
printf("# define CONFIG_MM_REGIONS 1\n");
printf("#endif\n\n");
+ printf("/* If the end of RAM is not specified then it is assumed to be the beginning\n");
+ printf(" * of RAM plus the RAM size.\n");
+ printf(" */\n\n");
+ printf("#ifndef CONFIG_DRAM_END\n");
+ printf("# define CONFIG_DRAM_END (CONFIG_DRAM_START+CONFIG_DRAM_SIZE)\n");
+ printf("#endif\n\n");
printf("/* If no file streams are configured, then make certain that buffered I/O\n");
printf(" * support is disabled\n");
printf(" */\n\n");
@@ -256,6 +262,7 @@ int main(int argc, char **argv, char **envp)
printf("# undef CONFIG_DEBUG_USB\n");
printf("# undef CONFIG_DEBUG_GRAPHICS\n");
printf("# undef CONFIG_DEBUG_GPIO\n");
+ printf("# undef CONFIG_DEBUG_SPI\n");
printf("# undef CONFIG_DEBUG_STACK\n");
printf("#endif\n\n");
printf("#endif /* __INCLUDE_NUTTX_CONFIG_H */\n");