From 80f9004741771691132a0f43ae1d9d5c42a2e4c6 Mon Sep 17 00:00:00 2001 From: patacongo Date: Thu, 6 Sep 2012 20:08:25 +0000 Subject: Add LPC31 Kconfig git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@5104 42af7a65-404d-4744-a932-0658087f49c3 --- nuttx/arch/arm/Kconfig | 107 ++++++++++---- nuttx/arch/arm/src/lpc17xx/Kconfig | 2 +- nuttx/arch/arm/src/lpc17xx/lpc17_usbdev.c | 12 +- nuttx/arch/arm/src/lpc31xx/Kconfig | 180 ++++++++++++++++++++++++ nuttx/arch/arm/src/lpc31xx/Make.defs | 2 +- nuttx/arch/arm/src/lpc31xx/chip.h | 5 +- nuttx/arch/arm/src/lpc31xx/lpc31_adc.h | 2 +- nuttx/arch/arm/src/lpc31xx/lpc31_allocateheap.c | 2 +- nuttx/arch/arm/src/lpc31xx/lpc31_analogdie.h | 2 +- nuttx/arch/arm/src/lpc31xx/lpc31_bcrndx.c | 2 +- nuttx/arch/arm/src/lpc31xx/lpc31_cgu.h | 2 +- nuttx/arch/arm/src/lpc31xx/lpc31_cgudrvr.h | 2 +- nuttx/arch/arm/src/lpc31xx/lpc31_clkdomain.c | 2 +- nuttx/arch/arm/src/lpc31xx/lpc31_clkexten.c | 2 +- nuttx/arch/arm/src/lpc31xx/lpc31_clkfreq.c | 2 +- nuttx/arch/arm/src/lpc31xx/lpc31_clkinit.c | 2 +- nuttx/arch/arm/src/lpc31xx/lpc31_decodeirq.c | 2 +- nuttx/arch/arm/src/lpc31xx/lpc31_defclk.c | 2 +- nuttx/arch/arm/src/lpc31xx/lpc31_dma.h | 2 +- nuttx/arch/arm/src/lpc31xx/lpc31_esrndx.c | 2 +- nuttx/arch/arm/src/lpc31xx/lpc31_evntrtr.h | 2 +- nuttx/arch/arm/src/lpc31xx/lpc31_fdcndx.c | 2 +- nuttx/arch/arm/src/lpc31xx/lpc31_fdivinit.c | 2 +- nuttx/arch/arm/src/lpc31xx/lpc31_freqin.c | 2 +- nuttx/arch/arm/src/lpc31xx/lpc31_i2c.c | 2 +- nuttx/arch/arm/src/lpc31xx/lpc31_i2c.h | 2 +- nuttx/arch/arm/src/lpc31xx/lpc31_i2s.h | 2 +- nuttx/arch/arm/src/lpc31xx/lpc31_intc.h | 2 +- nuttx/arch/arm/src/lpc31xx/lpc31_internal.h | 2 +- nuttx/arch/arm/src/lpc31xx/lpc31_ioconfig.h | 2 +- nuttx/arch/arm/src/lpc31xx/lpc31_irq.c | 2 +- nuttx/arch/arm/src/lpc31xx/lpc31_lcd.h | 2 +- nuttx/arch/arm/src/lpc31xx/lpc31_mci.h | 2 +- nuttx/arch/arm/src/lpc31xx/lpc31_memorymap.h | 2 +- nuttx/arch/arm/src/lpc31xx/lpc31_mpmc.h | 2 +- nuttx/arch/arm/src/lpc31xx/lpc31_nand.h | 2 +- nuttx/arch/arm/src/lpc31xx/lpc31_otp.h | 2 +- nuttx/arch/arm/src/lpc31xx/lpc31_pcm.h | 2 +- nuttx/arch/arm/src/lpc31xx/lpc31_pllconfig.c | 2 +- nuttx/arch/arm/src/lpc31xx/lpc31_pwm.h | 2 +- nuttx/arch/arm/src/lpc31xx/lpc31_resetclks.c | 2 +- nuttx/arch/arm/src/lpc31xx/lpc31_rng.h | 2 +- nuttx/arch/arm/src/lpc31xx/lpc31_setfdiv.c | 2 +- nuttx/arch/arm/src/lpc31xx/lpc31_setfreqin.c | 2 +- nuttx/arch/arm/src/lpc31xx/lpc31_softreset.c | 2 +- nuttx/arch/arm/src/lpc31xx/lpc31_spi.c | 26 ++-- nuttx/arch/arm/src/lpc31xx/lpc31_spi.h | 2 +- nuttx/arch/arm/src/lpc31xx/lpc31_syscreg.h | 2 +- nuttx/arch/arm/src/lpc31xx/lpc31_timer.h | 2 +- nuttx/arch/arm/src/lpc31xx/lpc31_timerisr.c | 2 +- nuttx/arch/arm/src/lpc31xx/lpc31_uart.h | 2 +- nuttx/arch/arm/src/lpc31xx/lpc31_usbdev.c | 18 +-- nuttx/arch/arm/src/lpc31xx/lpc31_usbotg.h | 2 +- nuttx/arch/arm/src/lpc31xx/lpc31_wdt.h | 2 +- 54 files changed, 340 insertions(+), 104 deletions(-) (limited to 'nuttx/arch/arm') diff --git a/nuttx/arch/arm/Kconfig b/nuttx/arch/arm/Kconfig index 79462b6f5..3343d7c47 100644 --- a/nuttx/arch/arm/Kconfig +++ b/nuttx/arch/arm/Kconfig @@ -11,6 +11,7 @@ choice config ARCH_CHIP_C5471 bool "TMS320 C5471" select ARCH_ARM7TDMI + select ARCH_HAVE_LOWVECTORS ---help--- TI TMS320 C5471, A180, or DA180 (ARM7TDMI) @@ -18,12 +19,15 @@ config ARCH_CHIP_CALYPSO bool "Calypso" select ARCH_ARM7TDMI select ARCH_HAVE_HEAP2 + select ARCH_HAVE_LOWVECTORS ---help--- TI Calypso-based cell phones (ARM7TDMI) config ARCH_CHIP_DM320 bool "TMS320 DM320" select ARCH_ARM926EJS + select ARCH_HAVE_LOWVECTORS + select ARCH_HAVE_MMU ---help--- TI DMS320 DM320 (ARM926EJS) @@ -31,70 +35,81 @@ config ARCH_CHIP_IMX bool "Freescale iMX" select ARCH_ARM920T select ARCH_HAVE_HEAP2 + select ARCH_HAVE_LOWVECTORS + select ARCH_HAVE_MMU ---help--- Freescale iMX architectures (ARM920T) config ARCH_CHIP_KINETIS bool "Freescale Kinetis" - select ARCH_CORTEXM select ARCH_CORTEXM4 + select ARCH_HAVE_MPU ---help--- Freescale Kinetis Architectures (ARM Cortex-M4) config ARCH_CHIP_LM3S bool "TI Stellaris" - select ARCH_CORTEXM select ARCH_CORTEXM3 + select ARCH_HAVE_MPU ---help--- TI Stellaris LMS3 architecutres (ARM Cortex-M3) config ARCH_CHIP_LPC17XX bool "NXP LPC17xx" - select ARCH_CORTEXM select ARCH_CORTEXM3 + select ARCH_HAVE_MPU ---help--- NXP LPC17xx architectures (ARM Cortex-M3) config ARCH_CHIP_LPC214X bool "NXP LPC214x" select ARCH_ARM7TDMI + select ARCH_HAVE_LOWVECTORS ---help--- NXP LPC2145x architectures (ARM7TDMI) config ARCH_CHIP_LPC2378 bool "NXP LPC2378" select ARCH_ARM7TDMI + select ARCH_HAVE_LOWVECTORS ---help--- NXP LPC2145x architectures (ARM7TDMI) config ARCH_CHIP_LPC31XX bool "NXP LPC31XX" select ARCH_ARM926EJS + select ARCH_HAVE_LOWVECTORS + select ARCH_HAVE_MMU ---help--- NPX LPC31XX architectures (ARM926EJS). config ARCH_CHIP_LPC43XX bool "NXP LPC43XX" select ARCH_CORTEXM4 + select ARCH_HAVE_CMNVECTOR select ARMV7M_CMNVECTOR + select ARCH_HAVE_MPU ---help--- NPX LPC43XX architectures (ARM Cortex-M4). config ARCH_CHIP_SAM3U bool "Atmel AT91SAM3U" - select ARCH_CORTEXM select ARCH_CORTEXM3 + select ARCH_HAVE_MPU ---help--- Atmel AT91SAM3U architectures (ARM Cortex-M3) config ARCH_CHIP_STM32 bool "STMicro STM32" + select ARCH_HAVE_CMNVECTOR + select ARCH_HAVE_MPU ---help--- STMicro STM32 architectures (ARM Cortex-M3/4). config ARCH_CHIP_STR71X bool "STMicro STR71x" select ARCH_ARM7TDMI + select ARCH_HAVE_LOWVECTORS ---help--- STMicro STR71x architectures (ARM7TDMI). @@ -115,26 +130,6 @@ config ARCH_CORTEXM3 config ARCH_CORTEXM4 bool -config ARMV7M_CMNVECTOR - bool - default n - -config ARCH_FPU - bool "FPU support" - default y - depends on ARCH_CORTEXM4 - ---help--- - Build in support for the ARM Cortex-M4 Floating Point Unit (FPU). - Check your chip specifications first; not all Cortex-M4 chips support the FPU. - -config ARMV7M_MPU - bool "MPU support" - default n - depends on ARCH_CORTEXM3 || ARCH_CORTEXM4 - ---help--- - Build in support for the ARM Cortex-M3/4 Memory Protection Unit (MPU). - Check your chip specifications first; not all Cortex-M3/4 chips support the MPU. - config ARCH_FAMILY string default "arm" if ARCH_ARM7TDMI || ARCH_ARM926EJS || ARCH_ARM920T @@ -157,6 +152,70 @@ config ARCH_CHIP default "stm32" if ARCH_CHIP_STM32 default "str71x" if ARCH_CHIP_STR71X +config ARMV7M_CMNVECTOR + bool "Use common ARMv7-M vectors" + default n + depends on ARCH_HAVE_CMNVECTOR + ---help--- + Some architectures use their own, built-in vector logic. Some use only + the common vector logic. Some can use either their own built-in vector + logic or the common vector logic. This applies only to ARMv7-M + architectures. + +config ARCH_FPU + bool "FPU support" + default y + depends on ARCH_CORTEXM4 + ---help--- + Build in support for the ARM Cortex-M4 Floating Point Unit (FPU). + Check your chip specifications first; not all Cortex-M4 chips support the FPU. + +config ARCH_HAVE_MPU + bool + +config ARMV7M_MPU + bool "MPU support" + default n + depends on ARCH_HAVE_MPU + ---help--- + Build in support for the ARM Cortex-M3/4 Memory Protection Unit (MPU). + Check your chip specifications first; not all Cortex-M3/4 chips support the MPU. + +config ARCH_HAVE_LOWVECTORS + bool + +config ARCH_LOWVECTORS + bool "Vectors in low memory" + default n + depends on ARCH_HAVE_LOWVECTORS + ---help--- + Support ARM vectors in low memory. + +config ARCH_HAVE_MMU + bool + +config PGTABLE_VADDR + hex "Page table virtual address" + depends on ARCH_HAVE_MMU + ---help--- + Page table virtual address (might be defined in the board.h file). Not + applicable to all architectures. + +config ARCH_ROMPGTABLE + bool "ROM page table" + default n + depends on ARCH_HAVE_MMU + ---help--- + Support a fixed memory mapping use a (read-only) page table in ROM/FLASH. + +config PAGING + bool "On-demand paging" + default n + depends on ARCH_HAVE_MMU && !ARCH_ROMPGTABLE + ---help--- + If set =y in your configation file, this setting will enable the on-demand + paging feature as described in http://www.nuttx.org/NuttXDemandPaging.html. + config ARCH_LEDS bool "Use board LEDs to show state" default y diff --git a/nuttx/arch/arm/src/lpc17xx/Kconfig b/nuttx/arch/arm/src/lpc17xx/Kconfig index 108579b3e..f22f67344 100644 --- a/nuttx/arch/arm/src/lpc17xx/Kconfig +++ b/nuttx/arch/arm/src/lpc17xx/Kconfig @@ -484,7 +484,7 @@ endmenu menu "USB device driver options" -config USBDEV_EP0_MAXSIZE +config LPC17_USBDEV_EP0_MAXSIZE int "EP0 Max packet size" depends on LPC17_USBDEV default 64 diff --git a/nuttx/arch/arm/src/lpc17xx/lpc17_usbdev.c b/nuttx/arch/arm/src/lpc17xx/lpc17_usbdev.c index 4d6be083e..ccaa3528a 100644 --- a/nuttx/arch/arm/src/lpc17xx/lpc17_usbdev.c +++ b/nuttx/arch/arm/src/lpc17xx/lpc17_usbdev.c @@ -69,8 +69,8 @@ /* Configuration ***************************************************************/ -#ifndef CONFIG_USBDEV_EP0_MAXSIZE -# define CONFIG_USBDEV_EP0_MAXSIZE 64 +#ifndef CONFIG_LPC17_USBDEV_EP0_MAXSIZE +# define CONFIG_LPC17_USBDEV_EP0_MAXSIZE 64 #endif #ifndef CONFIG_USBDEV_MAXPOWER @@ -1369,8 +1369,8 @@ static inline void lpc17_ep0configure(struct lpc17_usbdev_s *priv) /* EndPoint 0 initialization */ - lpc17_eprealize(&priv->eplist[LPC17_CTRLEP_OUT], 0, CONFIG_USBDEV_EP0_MAXSIZE); - lpc17_eprealize(&priv->eplist[LPC17_CTRLEP_IN], 1, CONFIG_USBDEV_EP0_MAXSIZE); + lpc17_eprealize(&priv->eplist[LPC17_CTRLEP_OUT], 0, CONFIG_LPC17_USBDEV_EP0_MAXSIZE); + lpc17_eprealize(&priv->eplist[LPC17_CTRLEP_IN], 1, CONFIG_LPC17_USBDEV_EP0_MAXSIZE); /* Enable EP0 interrupts (not DMA) */ @@ -1930,7 +1930,7 @@ static inline void lpc17_ep0dataoutinterrupt(struct lpc17_usbdev_s *priv) case LPC17_EP0SHORTWRITE: { priv->ep0state = LPC17_EP0STATUSOUT; - pktlen = lpc17_epread(LPC17_EP0_OUT, NULL, CONFIG_USBDEV_EP0_MAXSIZE); + pktlen = lpc17_epread(LPC17_EP0_OUT, NULL, CONFIG_LPC17_USBDEV_EP0_MAXSIZE); if (LPC17_READOVERRUN(pktlen)) { lpc17_ep0setup(priv); @@ -1941,7 +1941,7 @@ static inline void lpc17_ep0dataoutinterrupt(struct lpc17_usbdev_s *priv) case LPC17_EP0SHORTWRSENT: { priv->ep0state = LPC17_EP0REQUEST; - pktlen = lpc17_epread(LPC17_EP0_OUT, NULL, CONFIG_USBDEV_EP0_MAXSIZE); + pktlen = lpc17_epread(LPC17_EP0_OUT, NULL, CONFIG_LPC17_USBDEV_EP0_MAXSIZE); if (LPC17_READOVERRUN(pktlen)) { lpc17_ep0setup(priv); diff --git a/nuttx/arch/arm/src/lpc31xx/Kconfig b/nuttx/arch/arm/src/lpc31xx/Kconfig index ae2bf3130..51c087998 100644 --- a/nuttx/arch/arm/src/lpc31xx/Kconfig +++ b/nuttx/arch/arm/src/lpc31xx/Kconfig @@ -2,3 +2,183 @@ # For a description of the syntax of this configuration file, # see misc/tools/kconfig-language.txt. # + +choice + prompt "LPC31 Chip Selection" + default ARCH_CHIP_LPC3131 + depends on ARCH_CHIP_LPC31XX + +config ARCH_CHIP_LPC3130 + bool "LPC3130" + +config ARCH_CHIP_LPC3131 + bool "LPC3131" + +config ARCH_CHIP_LPC3152 + bool "LPC3152" + +config ARCH_CHIP_LPC3154 + bool "LPC3154" + +endchoice + +choice + prompt "Toolchain Selection" + default LPC31_CODESOURCERYW + depends on ARCH_CHIP_LPC31XX + +config LPC31_CODESOURCERYW + bool "CodeSourcery for Windows" + +config LPC31_CODESOURCERYL + bool "CodeSourcery for Linux" + +config LPC31_DEVKITARM + bool "DevkitARM (Windows)" + +config LPC31_BUILDROOT + bool "NuttX buildroot (Cygwin or Linux)" + +endchoice + +menu "LPC31xx Memory Mapping" + +config LPC31_EXTNAND + bool "Map external NAND" + default n + ---help--- + Map external NAND into the memory map. + +config LPC31_EXTSDRAM + bool "Map external SDRAM" + default n + ---help--- + Map external SDRAM into the memory map. + +config LPC31_EXTSDRAMHEAP + bool "Add external SDRAM to the heap" + default y + depends on LPC31_EXTSDRAM + ---help--- + Add external SDRAM into the heap. + +config LPC31_EXTSDRAMSIZE + int "External SDRAM size" + depends on LPC31_EXTSDRAM + ---help--- + Size of the external SDRAM. + +config LPC31_EXTSRAM0 + bool "Map external SRAM0" + default n + ---help--- + Map external SRAM0 into the memory map. + +config LPC31_EXTSRAM0HEAP + bool "Add external SRAM0 to the heap" + default y + depends on LPC31_EXTSRAM0 + ---help--- + Add external SRAM0 into the heap. + +config LPC31_EXTSRAM0SIZE + int "External SRAM size" + depends on LPC31_EXTSRAM0 + ---help--- + Size of the external SRAM. + +config LPC31_EXTSRAM1 + bool "Map external SRAM0" + default n + ---help--- + Map external SRAM1 into the memory map. + +config LPC31_EXTSRAM1HEAP + bool "Add external SRAM1 to the heap" + default y + depends on LPC31_EXTSRAM1 + ---help--- + Add external SRAM1 into the heap. + +config LPC31_EXTSRAM1SIZE + int "External SRAM1 size" + depends on LPC31_EXTSRAM1 + ---help--- + Size of the external SRAM1. + +endmenu + +menu "LPC31xx Peripheral Support" + +config LPC31_UART + bool "UART" + default n + select ARCH_HAS_UART + +endmenu + +menu "LPC31xx UART Configuration" + depends on LPC31_UART + +config LPC31_UART_DIVADDVAL + int "BAUD pre-scaler divisor" + ---help--- + BAUD pre-scaler divisor + +config LPC31_UART_DIVISOR + int "BAUD divisor" + ---help--- + BAUD divisor + +config LPC31_UART_MULVAL + int "BAUD multiplier" + ---help--- + BAUD multiplier + +endmenu + +menu "USB device driver options" + +config LPC31_USBDEV_EP0_MAXSIZE + int "EP0 Max packet size" + depends on USBDEV + default 64 + ---help--- + Endpoint 0 maximum packet size. Default: 64 + +config LPC31_USBDEV_FRAME_INTERRUPT + bool "USB frame interrupt" + depends on USBDEV + default n + ---help--- + Handle USB Start-Of-Frame events. Enable reading SOF from interrupt + handler vs. simply reading on demand. Probably a bad idea... Unless + there is some issue with sampling the SOF from hardware asynchronously. + +config LPC31_USBDEV_DMA + bool "Enable USB device DMA" + depends on USBDEV + default n + ---help--- + Enable lpc31xx-specific DMA support + +config LPC31_USBDEV_REGDEBUG + bool "Register level debug" + depends on USBDEV && DEBUG + default n + ---help--- + Output detailed register-level USB device debug information. Requires also DEBUG. + +endmenu + +menu "SPI device driver options" + +config LPC31_SPI_REGDEBUG + bool "Register level debug" + depends on DEBUG + default n + ---help--- + Output detailed register-level SPI device debug information. Requires also DEBUG. + +endmenu + diff --git a/nuttx/arch/arm/src/lpc31xx/Make.defs b/nuttx/arch/arm/src/lpc31xx/Make.defs index 69af7726f..83dadc8c0 100755 --- a/nuttx/arch/arm/src/lpc31xx/Make.defs +++ b/nuttx/arch/arm/src/lpc31xx/Make.defs @@ -2,7 +2,7 @@ # arch/arm/lpc31xx/Make.defs # # Copyright (C) 2009-2011 Gregory Nutt. All rights reserved. -# Author: Gregory Nutt +# Author: Gregory Nutt # # Redistribution and use in source and binary forms, with or without # modification, are permitted provided that the following conditions diff --git a/nuttx/arch/arm/src/lpc31xx/chip.h b/nuttx/arch/arm/src/lpc31xx/chip.h index ba62730f7..4ffcf2fbf 100755 --- a/nuttx/arch/arm/src/lpc31xx/chip.h +++ b/nuttx/arch/arm/src/lpc31xx/chip.h @@ -2,7 +2,7 @@ * arch/arm/src/lpc31xx/chip.h * * Copyright (C) 2009, 2011 Gregory Nutt. All rights reserved. - * Author: Gregory Nutt + * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions @@ -59,11 +59,10 @@ # define HAVE_INTSRAM1 1 /* 192Kb internal SRAM */ # define LPC31_NDMACH 12 /* 12 DMA channels */ # undef HAVE_AESENGINE /* No AES engine */ -#elif defined(CONFIG_ARCH_CHIP_LPC3152) +#elif defined(CONFIG_ARCH_CHIP_LPC3154) # define HAVE_INTSRAM1 1 /* 192Kb internal SRAM */ # define LPC31_NDMACH 12 /* 12 DMA channels */ # define HAVE_AESENGINE 1 /* AES engine */ -# undef HAVE_AESENGINE /* No AES engine */ #else # error "Unsupported LPC31XX architecture" # undef HAVE_INTSRAM1 /* No INTSRAM1 */ diff --git a/nuttx/arch/arm/src/lpc31xx/lpc31_adc.h b/nuttx/arch/arm/src/lpc31xx/lpc31_adc.h index f0231e255..c5edeef78 100755 --- a/nuttx/arch/arm/src/lpc31xx/lpc31_adc.h +++ b/nuttx/arch/arm/src/lpc31xx/lpc31_adc.h @@ -2,7 +2,7 @@ * arch/arm/src/lpc31xx/lpc31_adc.h * * Copyright (C) 2009-2010 Gregory Nutt. All rights reserved. - * Author: Gregory Nutt + * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions diff --git a/nuttx/arch/arm/src/lpc31xx/lpc31_allocateheap.c b/nuttx/arch/arm/src/lpc31xx/lpc31_allocateheap.c index 0f68dcc0c..df3c897e1 100755 --- a/nuttx/arch/arm/src/lpc31xx/lpc31_allocateheap.c +++ b/nuttx/arch/arm/src/lpc31xx/lpc31_allocateheap.c @@ -2,7 +2,7 @@ * arch/arm/src/lpc31xx/lpc31_allocateheap.c * * Copyright (C) 2009-2010 Gregory Nutt. All rights reserved. - * Author: Gregory Nutt + * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions diff --git a/nuttx/arch/arm/src/lpc31xx/lpc31_analogdie.h b/nuttx/arch/arm/src/lpc31xx/lpc31_analogdie.h index 7a8904deb..9daf5c34f 100755 --- a/nuttx/arch/arm/src/lpc31xx/lpc31_analogdie.h +++ b/nuttx/arch/arm/src/lpc31xx/lpc31_analogdie.h @@ -2,7 +2,7 @@ * arch/arm/src/lpc31xx/lpc31_analogdie.h * * Copyright (C) 2011 Gregory Nutt. All rights reserved. - * Author: Gregory Nutt + * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions diff --git a/nuttx/arch/arm/src/lpc31xx/lpc31_bcrndx.c b/nuttx/arch/arm/src/lpc31xx/lpc31_bcrndx.c index 6da6aa55d..f2bcf7276 100755 --- a/nuttx/arch/arm/src/lpc31xx/lpc31_bcrndx.c +++ b/nuttx/arch/arm/src/lpc31xx/lpc31_bcrndx.c @@ -2,7 +2,7 @@ * arch/arm/src/lpc31xx/lpc31_bcrndx.c * * Copyright (C) 2009-2010 Gregory Nutt. All rights reserved. - * Author: Gregory Nutt + * Author: Gregory Nutt * * References: * - UM10314 LPC3130/31 User manual Rev. 1.01 — 9 September 2009 diff --git a/nuttx/arch/arm/src/lpc31xx/lpc31_cgu.h b/nuttx/arch/arm/src/lpc31xx/lpc31_cgu.h index e6c4befe7..0d1d7b7fb 100755 --- a/nuttx/arch/arm/src/lpc31xx/lpc31_cgu.h +++ b/nuttx/arch/arm/src/lpc31xx/lpc31_cgu.h @@ -2,7 +2,7 @@ * arch/arm/src/lpc31xx/lpc31_cgu.h * * Copyright (C) 2009-2011 Gregory Nutt. All rights reserved. - * Author: Gregory Nutt + * Author: Gregory Nutt * * References: * - UM10314 LPC3130/31 User manual Rev. 1.01 — 9 September 2009 diff --git a/nuttx/arch/arm/src/lpc31xx/lpc31_cgudrvr.h b/nuttx/arch/arm/src/lpc31xx/lpc31_cgudrvr.h index fc589c893..a408f56b2 100755 --- a/nuttx/arch/arm/src/lpc31xx/lpc31_cgudrvr.h +++ b/nuttx/arch/arm/src/lpc31xx/lpc31_cgudrvr.h @@ -2,7 +2,7 @@ * arch/arm/src/lpc31xx/lpc31_cgudrvr.h * * Copyright (C) 2009-2010 Gregory Nutt. All rights reserved. - * Author: Gregory Nutt + * Author: Gregory Nutt * * References: * - NXP UM10314 LPC3130/31 User manual Rev. 1.01 — 9 September 2009 diff --git a/nuttx/arch/arm/src/lpc31xx/lpc31_clkdomain.c b/nuttx/arch/arm/src/lpc31xx/lpc31_clkdomain.c index 98014bb28..e07f86e52 100755 --- a/nuttx/arch/arm/src/lpc31xx/lpc31_clkdomain.c +++ b/nuttx/arch/arm/src/lpc31xx/lpc31_clkdomain.c @@ -2,7 +2,7 @@ * arch/arm/src/lpc31xx/lpc31_clkdomain.c * * Copyright (C) 2009 Gregory Nutt. All rights reserved. - * Author: Gregory Nutt + * Author: Gregory Nutt * * References: * - UM10314 LPC3130/31 User manual Rev. 1.01 — 9 September 2009 diff --git a/nuttx/arch/arm/src/lpc31xx/lpc31_clkexten.c b/nuttx/arch/arm/src/lpc31xx/lpc31_clkexten.c index 1024c1035..20bd0c776 100755 --- a/nuttx/arch/arm/src/lpc31xx/lpc31_clkexten.c +++ b/nuttx/arch/arm/src/lpc31xx/lpc31_clkexten.c @@ -2,7 +2,7 @@ * arch/arm/src/lpc31xx/lpc31_exten.c * * Copyright (C) 2009 Gregory Nutt. All rights reserved. - * Author: Gregory Nutt + * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions diff --git a/nuttx/arch/arm/src/lpc31xx/lpc31_clkfreq.c b/nuttx/arch/arm/src/lpc31xx/lpc31_clkfreq.c index 845dc5602..e78b95086 100755 --- a/nuttx/arch/arm/src/lpc31xx/lpc31_clkfreq.c +++ b/nuttx/arch/arm/src/lpc31xx/lpc31_clkfreq.c @@ -2,7 +2,7 @@ * arch/arm/src/lpc31xx/lpc31_clkfreq.c * * Copyright (C) 2009-2010 Gregory Nutt. All rights reserved. - * Author: Gregory Nutt + * Author: Gregory Nutt * * References: * - UM10314 LPC3130/31 User manual Rev. 1.01 — 9 September 2009 diff --git a/nuttx/arch/arm/src/lpc31xx/lpc31_clkinit.c b/nuttx/arch/arm/src/lpc31xx/lpc31_clkinit.c index 5e3e8ae4c..b0e032281 100755 --- a/nuttx/arch/arm/src/lpc31xx/lpc31_clkinit.c +++ b/nuttx/arch/arm/src/lpc31xx/lpc31_clkinit.c @@ -2,7 +2,7 @@ * arch/arm/src/lpc31xx/lpc31_clkinit.c * * Copyright (C) 2009-2010 Gregory Nutt. All rights reserved. - * Author: Gregory Nutt + * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions diff --git a/nuttx/arch/arm/src/lpc31xx/lpc31_decodeirq.c b/nuttx/arch/arm/src/lpc31xx/lpc31_decodeirq.c index 9a417f9eb..41e1d3e13 100755 --- a/nuttx/arch/arm/src/lpc31xx/lpc31_decodeirq.c +++ b/nuttx/arch/arm/src/lpc31xx/lpc31_decodeirq.c @@ -3,7 +3,7 @@ * arch/arm/src/chip/lpc31_decodeirq.c * * Copyright (C) 2009 Gregory Nutt. All rights reserved. - * Author: Gregory Nutt + * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions diff --git a/nuttx/arch/arm/src/lpc31xx/lpc31_defclk.c b/nuttx/arch/arm/src/lpc31xx/lpc31_defclk.c index 8e13df20d..1f0ec194b 100755 --- a/nuttx/arch/arm/src/lpc31xx/lpc31_defclk.c +++ b/nuttx/arch/arm/src/lpc31xx/lpc31_defclk.c @@ -2,7 +2,7 @@ * arch/arm/src/lpc31xx/lpc31_defclk.c * * Copyright (C) 2009 Gregory Nutt. All rights reserved. - * Author: Gregory Nutt + * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions diff --git a/nuttx/arch/arm/src/lpc31xx/lpc31_dma.h b/nuttx/arch/arm/src/lpc31xx/lpc31_dma.h index f88258be0..8bfac39d3 100755 --- a/nuttx/arch/arm/src/lpc31xx/lpc31_dma.h +++ b/nuttx/arch/arm/src/lpc31xx/lpc31_dma.h @@ -2,7 +2,7 @@ * arch/arm/src/lpc31xx/lpc31_dma.h * * Copyright (C) 2009, 2011 Gregory Nutt. All rights reserved. - * Author: Gregory Nutt + * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions diff --git a/nuttx/arch/arm/src/lpc31xx/lpc31_esrndx.c b/nuttx/arch/arm/src/lpc31xx/lpc31_esrndx.c index 802b63f33..e29fe937d 100755 --- a/nuttx/arch/arm/src/lpc31xx/lpc31_esrndx.c +++ b/nuttx/arch/arm/src/lpc31xx/lpc31_esrndx.c @@ -2,7 +2,7 @@ * arch/arm/src/lpc31xx/lpc31_esrndx.c * * Copyright (C) 2009-2010 Gregory Nutt. All rights reserved. - * Author: Gregory Nutt + * Author: Gregory Nutt * * References: * - UM10314 LPC3130/31 User manual Rev. 1.01 — 9 September 2009 diff --git a/nuttx/arch/arm/src/lpc31xx/lpc31_evntrtr.h b/nuttx/arch/arm/src/lpc31xx/lpc31_evntrtr.h index b35c35a8a..6ebc46e3b 100755 --- a/nuttx/arch/arm/src/lpc31xx/lpc31_evntrtr.h +++ b/nuttx/arch/arm/src/lpc31xx/lpc31_evntrtr.h @@ -2,7 +2,7 @@ * arch/arm/src/lpc31xx/lpc31_evntrtr.h * * Copyright (C) 2009-2010 Gregory Nutt. All rights reserved. - * Author: Gregory Nutt + * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions diff --git a/nuttx/arch/arm/src/lpc31xx/lpc31_fdcndx.c b/nuttx/arch/arm/src/lpc31xx/lpc31_fdcndx.c index 546705eec..7d678b370 100755 --- a/nuttx/arch/arm/src/lpc31xx/lpc31_fdcndx.c +++ b/nuttx/arch/arm/src/lpc31xx/lpc31_fdcndx.c @@ -2,7 +2,7 @@ * arch/arm/src/lpc31xx/lpc31_fdcndx.c * * Copyright (C) 2009-2010 Gregory Nutt. All rights reserved. - * Author: Gregory Nutt + * Author: Gregory Nutt * * References: * - UM10314 LPC3130/31 User manual Rev. 1.01 — 9 September 2009 diff --git a/nuttx/arch/arm/src/lpc31xx/lpc31_fdivinit.c b/nuttx/arch/arm/src/lpc31xx/lpc31_fdivinit.c index 27a31152d..f8ecb00f3 100755 --- a/nuttx/arch/arm/src/lpc31xx/lpc31_fdivinit.c +++ b/nuttx/arch/arm/src/lpc31xx/lpc31_fdivinit.c @@ -2,7 +2,7 @@ * arch/arm/src/lpc31xx/lpc31_fdivinit.c * * Copyright (C) 2009 Gregory Nutt. All rights reserved. - * Author: Gregory Nutt + * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions diff --git a/nuttx/arch/arm/src/lpc31xx/lpc31_freqin.c b/nuttx/arch/arm/src/lpc31xx/lpc31_freqin.c index 7e6bd3b3d..3540592ac 100755 --- a/nuttx/arch/arm/src/lpc31xx/lpc31_freqin.c +++ b/nuttx/arch/arm/src/lpc31xx/lpc31_freqin.c @@ -2,7 +2,7 @@ * arch/arm/src/lpc31xx/lpc31_freqin.c * * Copyright (C) 2009 Gregory Nutt. All rights reserved. - * Author: Gregory Nutt + * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions diff --git a/nuttx/arch/arm/src/lpc31xx/lpc31_i2c.c b/nuttx/arch/arm/src/lpc31xx/lpc31_i2c.c index 52777dbb6..3d65c302d 100644 --- a/nuttx/arch/arm/src/lpc31xx/lpc31_i2c.c +++ b/nuttx/arch/arm/src/lpc31xx/lpc31_i2c.c @@ -4,7 +4,7 @@ * Author: David Hewson * * Copyright (C) 2010-2011 Gregory Nutt. All rights reserved. - * Author: Gregory Nutt + * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions diff --git a/nuttx/arch/arm/src/lpc31xx/lpc31_i2c.h b/nuttx/arch/arm/src/lpc31xx/lpc31_i2c.h index d2425db3a..e7574c702 100755 --- a/nuttx/arch/arm/src/lpc31xx/lpc31_i2c.h +++ b/nuttx/arch/arm/src/lpc31xx/lpc31_i2c.h @@ -2,7 +2,7 @@ * arch/arm/src/lpc31xx/lpc31_i2c.h * * Copyright (C) 2009-2010 Gregory Nutt. All rights reserved. - * Author: Gregory Nutt + * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions diff --git a/nuttx/arch/arm/src/lpc31xx/lpc31_i2s.h b/nuttx/arch/arm/src/lpc31xx/lpc31_i2s.h index 4d07dcc8f..5ad4413f0 100755 --- a/nuttx/arch/arm/src/lpc31xx/lpc31_i2s.h +++ b/nuttx/arch/arm/src/lpc31xx/lpc31_i2s.h @@ -2,7 +2,7 @@ * arch/arm/src/lpc31xx/lpc31_i2s.h * * Copyright (C) 2009 Gregory Nutt. All rights reserved. - * Author: Gregory Nutt + * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions diff --git a/nuttx/arch/arm/src/lpc31xx/lpc31_intc.h b/nuttx/arch/arm/src/lpc31xx/lpc31_intc.h index 204ff7555..e6dabded8 100755 --- a/nuttx/arch/arm/src/lpc31xx/lpc31_intc.h +++ b/nuttx/arch/arm/src/lpc31xx/lpc31_intc.h @@ -2,7 +2,7 @@ * arch/arm/src/lpc31xx/lpc31_intc.h * * Copyright (C) 2009-2010 Gregory Nutt. All rights reserved. - * Author: Gregory Nutt + * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions diff --git a/nuttx/arch/arm/src/lpc31xx/lpc31_internal.h b/nuttx/arch/arm/src/lpc31xx/lpc31_internal.h index d91f3a2e1..f68384b7e 100755 --- a/nuttx/arch/arm/src/lpc31xx/lpc31_internal.h +++ b/nuttx/arch/arm/src/lpc31xx/lpc31_internal.h @@ -2,7 +2,7 @@ * arch/arm/src/lpc31xx/lpc31_internal.h * * Copyright (C) 2009-2011 Gregory Nutt. All rights reserved. - * Author: Gregory Nutt + * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions diff --git a/nuttx/arch/arm/src/lpc31xx/lpc31_ioconfig.h b/nuttx/arch/arm/src/lpc31xx/lpc31_ioconfig.h index 491943fd6..2cf5e0c90 100755 --- a/nuttx/arch/arm/src/lpc31xx/lpc31_ioconfig.h +++ b/nuttx/arch/arm/src/lpc31xx/lpc31_ioconfig.h @@ -2,7 +2,7 @@ * arch/arm/src/lpc31xx/lpc31_ioconfig.h * * Copyright (C) 2009-2010 Gregory Nutt. All rights reserved. - * Author: Gregory Nutt + * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions diff --git a/nuttx/arch/arm/src/lpc31xx/lpc31_irq.c b/nuttx/arch/arm/src/lpc31xx/lpc31_irq.c index 69cddda6e..4418ebc08 100755 --- a/nuttx/arch/arm/src/lpc31xx/lpc31_irq.c +++ b/nuttx/arch/arm/src/lpc31xx/lpc31_irq.c @@ -3,7 +3,7 @@ * arch/arm/src/chip/lpc31_irq.c * * Copyright (C) 2009-2011 Gregory Nutt. All rights reserved. - * Author: Gregory Nutt + * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions diff --git a/nuttx/arch/arm/src/lpc31xx/lpc31_lcd.h b/nuttx/arch/arm/src/lpc31xx/lpc31_lcd.h index 2f659827a..34aa6fc6e 100755 --- a/nuttx/arch/arm/src/lpc31xx/lpc31_lcd.h +++ b/nuttx/arch/arm/src/lpc31xx/lpc31_lcd.h @@ -2,7 +2,7 @@ * arch/arm/src/lpc31xx/lpc31_lcd.h * * Copyright (C) 2009 Gregory Nutt. All rights reserved. - * Author: Gregory Nutt + * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions diff --git a/nuttx/arch/arm/src/lpc31xx/lpc31_mci.h b/nuttx/arch/arm/src/lpc31xx/lpc31_mci.h index 252061826..8314db414 100755 --- a/nuttx/arch/arm/src/lpc31xx/lpc31_mci.h +++ b/nuttx/arch/arm/src/lpc31xx/lpc31_mci.h @@ -2,7 +2,7 @@ * arch/arm/src/lpc31xx/lpc31_mci.h * * Copyright (C) 2009 Gregory Nutt. All rights reserved. - * Author: Gregory Nutt + * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions diff --git a/nuttx/arch/arm/src/lpc31xx/lpc31_memorymap.h b/nuttx/arch/arm/src/lpc31xx/lpc31_memorymap.h index 493551181..b5155df89 100755 --- a/nuttx/arch/arm/src/lpc31xx/lpc31_memorymap.h +++ b/nuttx/arch/arm/src/lpc31xx/lpc31_memorymap.h @@ -2,7 +2,7 @@ * arch/arm/src/lpc31xx/lpc31_memorymap.h * * Copyright (C) 2009-2010 Gregory Nutt. All rights reserved. - * Author: Gregory Nutt + * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions diff --git a/nuttx/arch/arm/src/lpc31xx/lpc31_mpmc.h b/nuttx/arch/arm/src/lpc31xx/lpc31_mpmc.h index 5e927159d..5c2b8761a 100755 --- a/nuttx/arch/arm/src/lpc31xx/lpc31_mpmc.h +++ b/nuttx/arch/arm/src/lpc31xx/lpc31_mpmc.h @@ -2,7 +2,7 @@ * arch/arm/src/lpc31xx/lpc31_mpmc.h * * Copyright (C) 2009 Gregory Nutt. All rights reserved. - * Author: Gregory Nutt + * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions diff --git a/nuttx/arch/arm/src/lpc31xx/lpc31_nand.h b/nuttx/arch/arm/src/lpc31xx/lpc31_nand.h index ec429c0dd..52f22bdc2 100755 --- a/nuttx/arch/arm/src/lpc31xx/lpc31_nand.h +++ b/nuttx/arch/arm/src/lpc31xx/lpc31_nand.h @@ -2,7 +2,7 @@ * arch/arm/src/lpc31xx/lpc31_nand.h * * Copyright (C) 2009, 2011 Gregory Nutt. All rights reserved. - * Author: Gregory Nutt + * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions diff --git a/nuttx/arch/arm/src/lpc31xx/lpc31_otp.h b/nuttx/arch/arm/src/lpc31xx/lpc31_otp.h index f66605e5f..349fe2154 100755 --- a/nuttx/arch/arm/src/lpc31xx/lpc31_otp.h +++ b/nuttx/arch/arm/src/lpc31xx/lpc31_otp.h @@ -2,7 +2,7 @@ * arch/arm/src/lpc31xx/lpc31_otp.h * * Copyright (C) 2011 Gregory Nutt. All rights reserved. - * Author: Gregory Nutt + * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions diff --git a/nuttx/arch/arm/src/lpc31xx/lpc31_pcm.h b/nuttx/arch/arm/src/lpc31xx/lpc31_pcm.h index c3815a865..0be577aef 100755 --- a/nuttx/arch/arm/src/lpc31xx/lpc31_pcm.h +++ b/nuttx/arch/arm/src/lpc31xx/lpc31_pcm.h @@ -2,7 +2,7 @@ * arch/arm/src/lpc31xx/lpc31_pcm.h * * Copyright (C) 2009 Gregory Nutt. All rights reserved. - * Author: Gregory Nutt + * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions diff --git a/nuttx/arch/arm/src/lpc31xx/lpc31_pllconfig.c b/nuttx/arch/arm/src/lpc31xx/lpc31_pllconfig.c index dba4d25b6..fc6d4dc3b 100755 --- a/nuttx/arch/arm/src/lpc31xx/lpc31_pllconfig.c +++ b/nuttx/arch/arm/src/lpc31xx/lpc31_pllconfig.c @@ -2,7 +2,7 @@ * arch/arm/src/lpc31xx/lpc31_pllconfig.c * * Copyright (C) 2009-2010 Gregory Nutt. All rights reserved. - * Author: Gregory Nutt + * Author: Gregory Nutt * * References: * - NXP UM10314 LPC3130/31 User manual Rev. 1.01 — 9 September 2009 diff --git a/nuttx/arch/arm/src/lpc31xx/lpc31_pwm.h b/nuttx/arch/arm/src/lpc31xx/lpc31_pwm.h index 9263c99d3..042cd79d9 100755 --- a/nuttx/arch/arm/src/lpc31xx/lpc31_pwm.h +++ b/nuttx/arch/arm/src/lpc31xx/lpc31_pwm.h @@ -2,7 +2,7 @@ * arch/arm/src/lpc31xx/lpc31_pwm.h * * Copyright (C) 2009-2010 Gregory Nutt. All rights reserved. - * Author: Gregory Nutt + * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions diff --git a/nuttx/arch/arm/src/lpc31xx/lpc31_resetclks.c b/nuttx/arch/arm/src/lpc31xx/lpc31_resetclks.c index 0f24957f0..fe3287940 100755 --- a/nuttx/arch/arm/src/lpc31xx/lpc31_resetclks.c +++ b/nuttx/arch/arm/src/lpc31xx/lpc31_resetclks.c @@ -2,7 +2,7 @@ * arch/arm/src/lpc31xx/lpc31_resetclks.c * * Copyright (C) 2009 Gregory Nutt. All rights reserved. - * Author: Gregory Nutt + * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions diff --git a/nuttx/arch/arm/src/lpc31xx/lpc31_rng.h b/nuttx/arch/arm/src/lpc31xx/lpc31_rng.h index 585a4b497..e0539f96a 100755 --- a/nuttx/arch/arm/src/lpc31xx/lpc31_rng.h +++ b/nuttx/arch/arm/src/lpc31xx/lpc31_rng.h @@ -2,7 +2,7 @@ * arch/arm/src/lpc31xx/lpc31_rng.h * * Copyright (C) 2009-2010 Gregory Nutt. All rights reserved. - * Author: Gregory Nutt + * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions diff --git a/nuttx/arch/arm/src/lpc31xx/lpc31_setfdiv.c b/nuttx/arch/arm/src/lpc31xx/lpc31_setfdiv.c index 4ed1d855a..196118b18 100755 --- a/nuttx/arch/arm/src/lpc31xx/lpc31_setfdiv.c +++ b/nuttx/arch/arm/src/lpc31xx/lpc31_setfdiv.c @@ -2,7 +2,7 @@ * arch/arm/src/lpc31xx/lpc31_setfdiv.c * * Copyright (C) 2009-2010 Gregory Nutt. All rights reserved. - * Author: Gregory Nutt + * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions diff --git a/nuttx/arch/arm/src/lpc31xx/lpc31_setfreqin.c b/nuttx/arch/arm/src/lpc31xx/lpc31_setfreqin.c index b247af403..bbac38240 100755 --- a/nuttx/arch/arm/src/lpc31xx/lpc31_setfreqin.c +++ b/nuttx/arch/arm/src/lpc31xx/lpc31_setfreqin.c @@ -2,7 +2,7 @@ * arch/arm/src/lpc31xx/lpc31_setfreqin.c * * Copyright (C) 2009-2010 Gregory Nutt. All rights reserved. - * Author: Gregory Nutt + * Author: Gregory Nutt * * References: * - NXP UM10314 LPC3130/31 User manual Rev. 1.01 — 9 September 2009 diff --git a/nuttx/arch/arm/src/lpc31xx/lpc31_softreset.c b/nuttx/arch/arm/src/lpc31xx/lpc31_softreset.c index 8bf9ef12a..fcade115a 100755 --- a/nuttx/arch/arm/src/lpc31xx/lpc31_softreset.c +++ b/nuttx/arch/arm/src/lpc31xx/lpc31_softreset.c @@ -2,7 +2,7 @@ * arch/arm/src/lpc31xx/lpc31_softreset.c * * Copyright (C) 2009 Gregory Nutt. All rights reserved. - * Author: Gregory Nutt + * Author: Gregory Nutt * * References: * - UM10314 LPC3130/31 User manual Rev. 1.01 — 9 September 2009 diff --git a/nuttx/arch/arm/src/lpc31xx/lpc31_spi.c b/nuttx/arch/arm/src/lpc31xx/lpc31_spi.c index 5667ba95d..6f04af303 100644 --- a/nuttx/arch/arm/src/lpc31xx/lpc31_spi.c +++ b/nuttx/arch/arm/src/lpc31xx/lpc31_spi.c @@ -1,9 +1,9 @@ /************************************************************************************ * arm/arm/src/lpc31xx/lpc31_spi.c * - * Copyright (C) 2009-2010 Gregory Nutt. All rights reserved. + * Copyright (C) 2009-2010, 2012 Gregory Nutt. All rights reserved. * Author: David Hewson, deriving in part from other SPI drivers originally by - * Gregory Nutt + * Gregory Nutt * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions @@ -62,14 +62,12 @@ /* Configuration ********************************************************************/ /* Debug ****************************************************************************/ -/* Define the following to enable extremely detailed register debug */ - -#undef CONFIG_DEBUG_SPIREGS - -/* CONFIG_DEBUG must also be defined */ +/* CONFIG_LPC31_SPI_REGDEBUG enabled very low, register-level debug output. + * CONFIG_DEBUG must also be defined + */ #ifndef CONFIG_DEBUG -# undef CONFIG_DEBUG_SPIREGS +# undef CONFIG_LPC31_SPI_REGDEBUG #endif /* FIFOs ****************************************************************************/ @@ -102,7 +100,7 @@ struct lpc31_spidev_s * Private Function Prototypes ************************************************************************************/ -#ifdef CONFIG_DEBUG_SPIREGS +#ifdef CONFIG_LPC31_SPI_REGDEBUG static bool spi_checkreg(bool wr, uint32_t value, uint32_t address); static void spi_putreg(uint32_t value, uint32_t address); static uint32_t spi_getreg(uint32_t address); @@ -163,7 +161,7 @@ static struct lpc31_spidev_s g_spidev = .spidev = { &g_spiops }, }; -#ifdef CONFIG_DEBUG_SPIREGS +#ifdef CONFIG_LPC31_SPI_REGDEBUG static bool g_wrlast; static uint32_t g_addresslast; static uint32_t g_valuelast; @@ -194,7 +192,7 @@ static int g_ntimes; * ****************************************************************************/ -#ifdef CONFIG_DEBUG_SPIREGS +#ifdef CONFIG_LPC31_SPI_REGDEBUG static bool spi_checkreg(bool wr, uint32_t value, uint32_t address) { if (wr == g_wrlast && value == g_valuelast && address == g_addresslast) @@ -233,7 +231,7 @@ static bool spi_checkreg(bool wr, uint32_t value, uint32_t address) * ****************************************************************************/ -#ifdef CONFIG_DEBUG_SPIREGS +#ifdef CONFIG_LPC31_SPI_REGDEBUG static void spi_putreg(uint32_t value, uint32_t address) { if (spi_checkreg(true, value, address)) @@ -258,7 +256,7 @@ static void spi_putreg(uint32_t value, uint32_t address) * ****************************************************************************/ -#ifdef CONFIG_DEBUG_SPIREGS +#ifdef CONFIG_LPC31_SPI_REGDEBUG static uint32_t spi_getreg(uint32_t address) { uint32_t value = getreg32(address); @@ -920,7 +918,7 @@ FAR struct spi_dev_s *up_spiinitialize(int port) * default to "driven-by-IP" on reset. */ -#ifdef CONFIG_DEBUG_SPIREGS +#ifdef CONFIG_LPC31_SPI_REGDEBUG lldbg("PINS: %08x MODE0: %08x MODE1: %08x\n", spi_getreg(LPC31_IOCONFIG_SPI_PINS), spi_getreg(LPC31_IOCONFIG_SPI_MODE0), diff --git a/nuttx/arch/arm/src/lpc31xx/lpc31_spi.h b/nuttx/arch/arm/src/lpc31xx/lpc31_spi.h index 819dae5ae..6d63fe65d 100755 --- a/nuttx/arch/arm/src/lpc31xx/lpc31_spi.h +++ b/nuttx/arch/arm/src/lpc31xx/lpc31_spi.h @@ -2,7 +2,7 @@ * arch/arm/src/lpc31xx/lpc31_spi.h * * Copyright (C) 2009-2010 Gregory Nutt. All rights reserved. - * Author: Gregory Nutt + * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions diff --git a/nuttx/arch/arm/src/lpc31xx/lpc31_syscreg.h b/nuttx/arch/arm/src/lpc31xx/lpc31_syscreg.h index 3a031a13c..c14c7267c 100755 --- a/nuttx/arch/arm/src/lpc31xx/lpc31_syscreg.h +++ b/nuttx/arch/arm/src/lpc31xx/lpc31_syscreg.h @@ -2,7 +2,7 @@ * arch/arm/src/lpc31xx/lpc31_syscreg.h * * Copyright (C) 2009-2010 Gregory Nutt. All rights reserved. - * Author: Gregory Nutt + * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions diff --git a/nuttx/arch/arm/src/lpc31xx/lpc31_timer.h b/nuttx/arch/arm/src/lpc31xx/lpc31_timer.h index 88deb1756..b3d580ab6 100755 --- a/nuttx/arch/arm/src/lpc31xx/lpc31_timer.h +++ b/nuttx/arch/arm/src/lpc31xx/lpc31_timer.h @@ -2,7 +2,7 @@ * arch/arm/src/lpc31xx/lpc31_timer.h * * Copyright (C) 2009-2010 Gregory Nutt. All rights reserved. - * Author: Gregory Nutt + * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions diff --git a/nuttx/arch/arm/src/lpc31xx/lpc31_timerisr.c b/nuttx/arch/arm/src/lpc31xx/lpc31_timerisr.c index 1a484477e..ab9912c19 100755 --- a/nuttx/arch/arm/src/lpc31xx/lpc31_timerisr.c +++ b/nuttx/arch/arm/src/lpc31xx/lpc31_timerisr.c @@ -2,7 +2,7 @@ * arch/arm/src/lpc31xx/lpc31_timerisr.c * * Copyright (C) 2009 Gregory Nutt. All rights reserved. - * Author: Gregory Nutt + * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions diff --git a/nuttx/arch/arm/src/lpc31xx/lpc31_uart.h b/nuttx/arch/arm/src/lpc31xx/lpc31_uart.h index f80fe4d92..d612e0308 100755 --- a/nuttx/arch/arm/src/lpc31xx/lpc31_uart.h +++ b/nuttx/arch/arm/src/lpc31xx/lpc31_uart.h @@ -2,7 +2,7 @@ * arch/arm/src/lpc31xx/lpc31_uart.h * * Copyright (C) 2009 Gregory Nutt. All rights reserved. - * Author: Gregory Nutt + * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions diff --git a/nuttx/arch/arm/src/lpc31xx/lpc31_usbdev.c b/nuttx/arch/arm/src/lpc31xx/lpc31_usbdev.c index 5584937cc..0e8fcf17c 100755 --- a/nuttx/arch/arm/src/lpc31xx/lpc31_usbdev.c +++ b/nuttx/arch/arm/src/lpc31xx/lpc31_usbdev.c @@ -2,7 +2,7 @@ * arch/arm/src/lpc31xx/lpc31_usbdev.c * * Authors: David Hewson - * Gregory Nutt + * Gregory Nutt * * Part of the NuttX OS and based, in part, on the LPC2148 USB driver: * @@ -74,8 +74,8 @@ /* Configuration ***************************************************************/ -#ifndef CONFIG_USBDEV_EP0_MAXSIZE -# define CONFIG_USBDEV_EP0_MAXSIZE 64 +#ifndef CONFIG_LPC31_USBDEV_EP0_MAXSIZE +# define CONFIG_LPC31_LPC31_USBDEV_EP0_MAXSIZE 64 #endif #ifndef CONFIG_USBDEV_MAXPOWER @@ -401,7 +401,7 @@ static int lpc31_epdisable(FAR struct usbdev_ep_s *ep); static FAR struct usbdev_req_s *lpc31_epallocreq(FAR struct usbdev_ep_s *ep); static void lpc31_epfreereq(FAR struct usbdev_ep_s *ep, FAR struct usbdev_req_s *); -#ifdef CONFIG_ARCH_USBDEV_DMA +#ifdef CONFIG_LPC31_USBDEV_DMA static void *lpc31_epallocbuffer(FAR struct usbdev_ep_s *ep, unsigned bytes); static void lpc31_epfreebuffer(FAR struct usbdev_ep_s *ep, FAR void *buf); #endif @@ -438,7 +438,7 @@ static const struct usbdev_epops_s g_epops = .disable = lpc31_epdisable, .allocreq = lpc31_epallocreq, .freereq = lpc31_epfreereq, -#ifdef CONFIG_ARCH_USBDEV_DMA +#ifdef CONFIG_LPC31_USBDEV_DMA .allocbuffer = lpc31_epallocbuffer, .freebuffer = lpc31_epfreebuffer, #endif @@ -1003,11 +1003,11 @@ static void lpc31_dispatchrequest(struct lpc31_usbdev_s *priv, static void lpc31_ep0configure(struct lpc31_usbdev_s *priv) { /* Enable ep0 IN and ep0 OUT */ - g_qh[LPC31_EP0_OUT].capability = (DQH_CAPABILITY_MAX_PACKET(CONFIG_USBDEV_EP0_MAXSIZE) | + g_qh[LPC31_EP0_OUT].capability = (DQH_CAPABILITY_MAX_PACKET(CONFIG_LPC31_USBDEV_EP0_MAXSIZE) | DQH_CAPABILITY_IOS | DQH_CAPABILITY_ZLT); - g_qh[LPC31_EP0_IN ].capability = (DQH_CAPABILITY_MAX_PACKET(CONFIG_USBDEV_EP0_MAXSIZE) | + g_qh[LPC31_EP0_IN ].capability = (DQH_CAPABILITY_MAX_PACKET(CONFIG_LPC31_USBDEV_EP0_MAXSIZE) | DQH_CAPABILITY_IOS | DQH_CAPABILITY_ZLT); @@ -1955,7 +1955,7 @@ static void lpc31_epfreereq(FAR struct usbdev_ep_s *ep, FAR struct usbdev_req_s * *******************************************************************************/ -#ifdef CONFIG_ARCH_USBDEV_DMA +#ifdef CONFIG_LPC31_USBDEV_DMA static void *lpc31_epallocbuffer(FAR struct usbdev_ep_s *ep, unsigned bytes) { usbtrace(TRACE_EPALLOCBUFFER, privep->epphy); @@ -1971,7 +1971,7 @@ static void *lpc31_epallocbuffer(FAR struct usbdev_ep_s *ep, unsigned bytes) * *******************************************************************************/ -#ifdef CONFIG_LPC313x_USBDEV_DMA +#ifdef CONFIG_LPC31_USBDEV_DMA static void lpc31_epfreebuffer(FAR struct usbdev_ep_s *ep, FAR void *buf) { usbtrace(TRACE_EPFREEBUFFER, privep->epphy); diff --git a/nuttx/arch/arm/src/lpc31xx/lpc31_usbotg.h b/nuttx/arch/arm/src/lpc31xx/lpc31_usbotg.h index 557695280..b98706dfb 100755 --- a/nuttx/arch/arm/src/lpc31xx/lpc31_usbotg.h +++ b/nuttx/arch/arm/src/lpc31xx/lpc31_usbotg.h @@ -2,7 +2,7 @@ * arch/arm/src/lpc31xx/lpc31_usbotg.h * * Copyright (C) 2009-2011 Gregory Nutt. All rights reserved. - * Author: Gregory Nutt + * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions diff --git a/nuttx/arch/arm/src/lpc31xx/lpc31_wdt.h b/nuttx/arch/arm/src/lpc31xx/lpc31_wdt.h index ac063472d..2840b67e4 100755 --- a/nuttx/arch/arm/src/lpc31xx/lpc31_wdt.h +++ b/nuttx/arch/arm/src/lpc31xx/lpc31_wdt.h @@ -2,7 +2,7 @@ * arch/arm/src/lpc31xx/lpc31_wdt.h * * Copyright (C) 2009-2010 Gregory Nutt. All rights reserved. - * Author: Gregory Nutt + * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions -- cgit v1.2.3