From c7f31bf28f105ba361108b8a29fbac35ddcccc87 Mon Sep 17 00:00:00 2001 From: patacongo Date: Fri, 16 Jul 2010 03:01:05 +0000 Subject: LPC17xx USBDEV driver now compiles (still untested) git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@2805 42af7a65-404d-4744-a932-0658087f49c3 --- nuttx/ChangeLog | 5 + nuttx/Documentation/NuttX.html | 7 +- nuttx/arch/arm/src/cortexm3/up_assert.c | 35 +++---- nuttx/arch/arm/src/lpc17xx/lpc17_usbdev.c | 35 ++++--- nuttx/configs/nucleus2g/src/Makefile | 3 + nuttx/configs/nucleus2g/src/up_usbstrg.c | 143 +++++++++++++++++++++++++++ nuttx/configs/nucleus2g/usbserial/defconfig | 2 +- nuttx/configs/nucleus2g/usbstorage/defconfig | 4 +- nuttx/drivers/mmcsd/mmcsd_spi.c | 14 +-- 9 files changed, 203 insertions(+), 45 deletions(-) create mode 100755 nuttx/configs/nucleus2g/src/up_usbstrg.c (limited to 'nuttx') diff --git a/nuttx/ChangeLog b/nuttx/ChangeLog index e617abe04..eeb9bec02 100644 --- a/nuttx/ChangeLog +++ b/nuttx/ChangeLog @@ -1176,3 +1176,8 @@ * net/uip/uip_igmp*.c - Add IGMP support (untested on initial checkin). * examples/igmp - Add a trivial test for IGMP (much more is needed) + * configs/nucleus2g/usbserial and usbstorage - Add USB configurations + for testing purposes. + * arch/arm/src/common/up_internal.h, cortexm3/up_assert.c, + */*_vectors.S - Correct compilations errors when CONFIG_ARCH_INTERRUPTSTACK + is enabled (feature still not tested) diff --git a/nuttx/Documentation/NuttX.html b/nuttx/Documentation/NuttX.html index 6b2a545d9..d42fbb8e3 100644 --- a/nuttx/Documentation/NuttX.html +++ b/nuttx/Documentation/NuttX.html @@ -8,7 +8,7 @@

NuttX RTOS

-

Last Updated: July 11, 2010

+

Last Updated: July 15, 2010

@@ -1851,6 +1851,11 @@ nuttx-5.8 2010-xx-xx Gregory Nutt <spudmonkey@racsa.co.cr> * net/uip/uip_igmp*.c - Add IGMP support (untested on initial checkin). * examples/igmp - Add a trivial test for IGMP (much more is needed) + * configs/nucleus2g/usbserial and usbstorage - Add USB configurations + for testing purposes. + * arch/arm/src/common/up_internal.h, cortexm3/up_assert.c, + */*_vectors.S - Correct compilations errors when CONFIG_ARCH_INTERRUPTSTACK + is enabled (feature still not tested) pascal-2.1 2010-xx-xx Gregory Nutt <spudmonkey@racsa.co.cr> diff --git a/nuttx/arch/arm/src/cortexm3/up_assert.c b/nuttx/arch/arm/src/cortexm3/up_assert.c index 55ab0df05..416d763cd 100644 --- a/nuttx/arch/arm/src/cortexm3/up_assert.c +++ b/nuttx/arch/arm/src/cortexm3/up_assert.c @@ -208,33 +208,28 @@ static void up_dumpstate(void) up_stackdump(sp, istackbase); } - /* Extract the user stack pointer. */ + /* Extract the user stack pointer if we are in an interrupt handler. + * If we are not in an interrupt handler. Then sp is the user stack + * pointer (and the above range check should have failed). + */ if (current_regs) { sp = current_regs[REG_R13]; lldbg("sp: %08x\n", sp); + } - /* Show user stack info */ - - lldbg("User stack:\n"); - lldbg(" base: %08x\n", ustackbase); - lldbg(" size: %08x\n", ustacksize); + lldbg("User stack:\n"); + lldbg(" base: %08x\n", ustackbase); + lldbg(" size: %08x\n", ustacksize); - /* Dump the user stack if the stack pointer lies within the allocated user - * stack memory. - */ + /* Dump the user stack if the stack pointer lies within the allocated user + * stack memory. + */ - if (sp > ustackbase || sp <= ustackbase - ustacksize) - { -#if !defined(CONFIG_ARCH_INTERRUPTSTACK) || CONFIG_ARCH_INTERRUPTSTACK < 4 - lldbg("ERROR: Stack pointer is not within allocated stack\n"); -#endif - } - else - { - up_stackdump(sp, ustackbase); - } + if (sp <= ustackbase && sp > ustackbase - ustacksize) + { + up_stackdump(sp, ustackbase); } #else lldbg("sp: %08x\n", sp); @@ -247,9 +242,7 @@ static void up_dumpstate(void) if (sp > ustackbase || sp <= ustackbase - ustacksize) { -#if !defined(CONFIG_ARCH_INTERRUPTSTACK) || CONFIG_ARCH_INTERRUPTSTACK < 4 lldbg("ERROR: Stack pointer is not within allocated stack\n"); -#endif } else { diff --git a/nuttx/arch/arm/src/lpc17xx/lpc17_usbdev.c b/nuttx/arch/arm/src/lpc17xx/lpc17_usbdev.c index 29a5490e6..6c584d513 100755 --- a/nuttx/arch/arm/src/lpc17xx/lpc17_usbdev.c +++ b/nuttx/arch/arm/src/lpc17xx/lpc17_usbdev.c @@ -59,6 +59,7 @@ #include "up_arch.h" #include "up_internal.h" +#include "lpc17_internal.h" #include "lpc17_usb.h" #include "lpc17_syscon.h" @@ -103,7 +104,7 @@ #endif #ifdef CONFIG_DEBUG -# define USB_ERROR_INT USBDEV_INT_EPRINT +# define USB_ERROR_INT USBDEV_INT_ERRINT #else # define USB_ERROR_INT 0 #endif @@ -178,7 +179,7 @@ #define LPC17_TRACEINTID_EPOUT 0x0013 #define LPC17_TRACEINTID_EPOUTQEMPTY 0x0014 #define LPC17_TRACEINTID_EP0SETUPSETADDRESS 0x0015 -#define LPC17_TRACEINTID_EPRINT 0x0016 +#define LPC17_TRACEINTID_ERRINT 0x0016 #define LPC17_TRACEINTID_EPSLOW 0x0017 #define LPC17_TRACEINTID_FRAME 0x0018 #define LPC17_TRACEINTID_GETCONFIG 0x0019 @@ -2021,18 +2022,18 @@ static int lpc17_usbinterrupt(int irq, FAR void *context) #if CONFIG_DEBUG /* USB engine error interrupt */ - if ((devintstatus & USBDEV_INT_EPRINT)) + if ((devintstatus & USBDEV_INT_ERRINT)) { uint8_t errcode; /* Clear the error interrupt */ - lpc17_putreg(USBDEV_INT_EPRINT, LPC17_USBDEV_INTCLR); + lpc17_putreg(USBDEV_INT_ERRINT, LPC17_USBDEV_INTCLR); /* And show what error occurred */ errcode = (uint8_t)lpc17_usbcmd(CMD_USBDEV_READERRORSTATUS, 0) & 0x0f; - usbtrace(TRACE_INTDECODE(LPC17_TRACEINTID_EPRINT), (uint16_t)errcode); + usbtrace(TRACE_INTDECODE(LPC17_TRACEINTID_ERRINT), (uint16_t)errcode); } #endif @@ -3106,7 +3107,9 @@ void up_usbinitialize(void) /* Disable USB interrupts */ - lpc17_putreg(0, LPC17_USBDEV_INTST); + regval = lpc17_getreg(LPC17_SYSCON_USBINTST); + regval &= ~SYSCON_USBINTST_ENINTS; + lpc17_putreg(regval, LPC17_SYSCON_USBINTST); irqrestore(flags); /* Initialize the device state structure */ @@ -3166,9 +3169,11 @@ void up_usbinitialize(void) /* Turn on USB power and clocking */ - reg = lpc17_getreg(LPC17_PCON_PCONP); - reg |= LPC17_PCONP_PCUSB; - lpc17_putreg(reg, LPC17_PCON_PCONP); + flags = irqsave(); + reg = lpc17_getreg(LPC17_SYSCON_PCONP); + reg |= SYSCON_PCONP_PCUSB; + lpc17_putreg(reg, LPC17_SYSCON_PCONP); + irqrestore(flags); /* Attach USB controller interrupt handler */ @@ -3184,7 +3189,11 @@ void up_usbinitialize(void) * driver */ - lpc17_putreg(USBDEV_INTST_ENUSBINTS, LPC17_USBDEV_INTST); + flags = irqsave(); + reg = lpc17_getreg(LPC17_SYSCON_USBINTST); + reg |= SYSCON_USBINTST_ENINTS; + lpc17_putreg(regval, LPC17_SYSCON_USBINTST); + irqrestore(flags); /* Disconnect device */ @@ -3240,9 +3249,9 @@ void up_usbuninitialize(void) /* Turn off USB power and clocking */ - reg = lpc17_getreg(LPC17_PCON_PCONP); - reg &= ~LPC17_PCONP_PCUSB; - lpc17_putreg(reg, LPC17_PCON_PCONP); + reg = lpc17_getreg(LPC17_SYSCON_PCONP); + reg &= ~SYSCON_PCONP_PCUSB; + lpc17_putreg(reg, LPC17_SYSCON_PCONP); irqrestore(flags); } diff --git a/nuttx/configs/nucleus2g/src/Makefile b/nuttx/configs/nucleus2g/src/Makefile index 78a58d25b..de5a3c76c 100755 --- a/nuttx/configs/nucleus2g/src/Makefile +++ b/nuttx/configs/nucleus2g/src/Makefile @@ -42,6 +42,9 @@ CSRCS = up_boot.c up_leds.c up_ssp.c ifeq ($(CONFIG_EXAMPLES_NSH_ARCHINIT),y) CSRCS += up_nsh.c endif +ifeq ($(CONFIG_EXAMPLE),usbstorage) +CSRCS += up_usbstrg.c +endif AOBJS = $(ASRCS:.S=$(OBJEXT)) COBJS = $(CSRCS:.c=$(OBJEXT)) diff --git a/nuttx/configs/nucleus2g/src/up_usbstrg.c b/nuttx/configs/nucleus2g/src/up_usbstrg.c new file mode 100755 index 000000000..2db8eddf3 --- /dev/null +++ b/nuttx/configs/nucleus2g/src/up_usbstrg.c @@ -0,0 +1,143 @@ +/**************************************************************************** + * configs/nucleus2g/src/up_usbstrg.c + * + * Copyright (C) 2010 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * Configure and register the LPC17xx MMC/SD SPI block driver. + * + * 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 + +#include +#include +#include + +#include +#include + +/**************************************************************************** + * Pre-Processor Definitions + ****************************************************************************/ + +/* Configuration ************************************************************/ + +#ifndef CONFIG_EXAMPLES_USBSTRG_DEVMINOR1 +# define CONFIG_EXAMPLES_USBSTRG_DEVMINOR1 0 +#endif + +/* PORT and SLOT number probably depend on the board configuration */ + +#ifdef CONFIG_ARCH_BOARD_NUCLEUS2G +# undef LPC17XX_MMCSDSPIPORTNO +# define LPC17XX_MMCSDSPIPORTNO 1 +# undef LPC17XX_MMCSDSLOTNO +# define LPC17XX_MMCSDSLOTNO 0 +#else + /* Add configuration for new LPC17xx boards here */ +# error "Unrecognized LPC17xx board" +#endif + +/* Debug ********************************************************************/ + +#ifdef CONFIG_CPP_HAVE_VARARGS +# ifdef CONFIG_DEBUG +# define message(...) lib_lowprintf(__VA_ARGS__) +# define msgflush() +# else +# define message(...) printf(__VA_ARGS__) +# define msgflush() fflush(stdout) +# endif +#else +# ifdef CONFIG_DEBUG +# define message lib_lowprintf +# define msgflush() +# else +# define message printf +# define msgflush() fflush(stdout) +# endif +#endif + + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: usbstrg_archinitialize + * + * Description: + * Perform architecture specific initialization + * + ****************************************************************************/ + +int usbstrg_archinitialize(void) +{ + FAR struct spi_dev_s *spi; + int ret; + + /* Get the SPI port */ + + message("usbstrg_archinitialize: Initializing SPI port %d\n", + LPC17XX_MMCSDSPIPORTNO); + + spi = up_spiinitialize(1); + if (!spi) + { + message("usbstrg_archinitialize: Failed to initialize SPI port %d\n", + LPC17XX_MMCSDSPIPORTNO); + return -ENODEV; + } + + message("usbstrg_archinitialize: Successfully initialized SPI port %d\n", + LPC17XX_MMCSDSPIPORTNO); + + /* Bind the SPI port to the slot */ + + message("usbstrg_archinitialize: Binding SPI port %d to MMC/SD slot %d\n", + LPC17XX_MMCSDSPIPORTNO, LPC17XX_MMCSDSLOTNO); + + ret = mmcsd_spislotinitialize(CONFIG_EXAMPLES_USBSTRG_DEVMINOR1, LPC17XX_MMCSDSLOTNO, spi); + if (ret < 0) + { + message("usbstrg_archinitialize: Failed to bind SPI port %d to MMC/SD slot %d: %d\n", + LPC17XX_MMCSDSPIPORTNO, LPC17XX_MMCSDSLOTNO, ret); + return ret; + } + + message("usbstrg_archinitialize: Successfuly bound SPI port %d to MMC/SD slot %d\n", + LPC17XX_MMCSDSPIPORTNO, LPC17XX_MMCSDSLOTNO); + return OK; +} diff --git a/nuttx/configs/nucleus2g/usbserial/defconfig b/nuttx/configs/nucleus2g/usbserial/defconfig index cb9501277..aba7874d5 100755 --- a/nuttx/configs/nucleus2g/usbserial/defconfig +++ b/nuttx/configs/nucleus2g/usbserial/defconfig @@ -81,7 +81,7 @@ CONFIG_DRAM_SIZE=(32*1024) CONFIG_DRAM_START=0x10000000 CONFIG_DRAM_END=(CONFIG_DRAM_START+CONFIG_DRAM_SIZE) CONFIG_ARCH_IRQPRIO=y -CONFIG_ARCH_INTERRUPTSTACK=1024 +CONFIG_ARCH_INTERRUPTSTACK=n CONFIG_ARCH_STACKDUMP=y CONFIG_ARCH_BOOTLOADER=n CONFIG_ARCH_LEDS=y diff --git a/nuttx/configs/nucleus2g/usbstorage/defconfig b/nuttx/configs/nucleus2g/usbstorage/defconfig index 477a8b1ab..7141c8e9e 100755 --- a/nuttx/configs/nucleus2g/usbstorage/defconfig +++ b/nuttx/configs/nucleus2g/usbstorage/defconfig @@ -81,7 +81,7 @@ CONFIG_DRAM_SIZE=(32*1024) CONFIG_DRAM_START=0x10000000 CONFIG_DRAM_END=(CONFIG_DRAM_START+CONFIG_DRAM_SIZE) CONFIG_ARCH_IRQPRIO=y -CONFIG_ARCH_INTERRUPTSTACK=1024 +CONFIG_ARCH_INTERRUPTSTACK=n CONFIG_ARCH_STACKDUMP=y CONFIG_ARCH_BOOTLOADER=n CONFIG_ARCH_LEDS=y @@ -113,7 +113,7 @@ CONFIG_LPC17_UART3=n CONFIG_LPC17_CAN1=n CONFIG_LPC17_CAN2=n CONFIG_LPC17_SPI=n -CONFIG_LPC17_SSP0=n +CONFIG_LPC17_SSP0=y CONFIG_LPC17_SSP1=n CONFIG_LPC17_I2C0=n CONFIG_LPC17_I2C1=n diff --git a/nuttx/drivers/mmcsd/mmcsd_spi.c b/nuttx/drivers/mmcsd/mmcsd_spi.c index f1c2f9a7f..93fd5dcab 100644 --- a/nuttx/drivers/mmcsd/mmcsd_spi.c +++ b/nuttx/drivers/mmcsd/mmcsd_spi.c @@ -1,7 +1,7 @@ /**************************************************************************** * drivers/mmcsd/mmcsd_spi.c * - * Copyright (C) 2008-2009 Gregory Nutt. All rights reserved. + * Copyright (C) 2008-2010 Gregory Nutt. All rights reserved. * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without @@ -114,12 +114,12 @@ * ticks per second. */ -#define MMCSD_DELAY_10MS (CLK_TCK/100 + 1) -#define MMCSD_DELAY_50MS (CLK_TCK/20 + 1) -#define MMCSD_DELAY_100MS (CLK_TCK/10 + 1) -#define MMCSD_DELAY_250MS (CLK_TCK/4 + 1) -#define MMCSD_DELAY_500MS (CLK_TCK/2 + 1) -#define MMCSD_DELAY_1SEC (CLK_TCK + 1) +#define MMCSD_DELAY_10MS (CLK_TCK/100 + 1) +#define MMCSD_DELAY_50MS (CLK_TCK/20 + 1) +#define MMCSD_DELAY_100MS (CLK_TCK/10 + 1) +#define MMCSD_DELAY_250MS (CLK_TCK/4 + 1) +#define MMCSD_DELAY_500MS (CLK_TCK/2 + 1) +#define MMCSD_DELAY_1SEC (CLK_TCK + 1) #define MMCSD_DELAY_10SEC (10 * CLK_TCK + 1) #define ELAPSED_TIME(t) (g_system_timer-(t)) -- cgit v1.2.3