forked from Archive/PX4-Autopilot
Add LPC31 Kconfig
git-svn-id: https://nuttx.svn.sourceforge.net/svnroot/nuttx/trunk@5104 7fd9a85b-ad96-42d3-883c-3090e2eb8679
This commit is contained in:
parent
dcd68236b1
commit
941daa511e
|
@ -3271,7 +3271,7 @@
|
|||
if the correct setting is already in defined in the defconfig file.
|
||||
* fs/fat/fs_utils.c: Improper constructed bool expression. This
|
||||
would cause many unnecessary writes to FLASH (Thanks Ronen Vainish).
|
||||
* Kconfig: Verify configuration settings for the LPC432xx. This includes
|
||||
* Kconfig: Verify configuration settings for the LPC43xx. This includes
|
||||
some corrections to configuration variable names and defconfig settings.
|
||||
|
||||
* Kconfig: Add and verify configuration settings for the LPC31xx.
|
||||
|
||||
|
|
|
@ -119,11 +119,58 @@ config BOARD_LOOPSPERMSEC
|
|||
is 100 seconds.
|
||||
|
||||
config DRAM_START
|
||||
hex "DRAM start address"
|
||||
hex "DRAM start physical address"
|
||||
help
|
||||
The physical start address of installed RAM.
|
||||
The physical start address of installed RAM. Despite the naming,
|
||||
this may be SDRAM or SRAM or any other RAM technology that support
|
||||
program execution.
|
||||
|
||||
config DRAM_VSTART
|
||||
hex "DRAM start virtual address"
|
||||
depends on ARCH_HAVE_MMU
|
||||
help
|
||||
The virtual start address of installed RAM. Despite the naming,
|
||||
this may be SDRAM or SRAM or any other RAM technology that support
|
||||
program execution.
|
||||
|
||||
config DRAM_SIZE
|
||||
int "DRAM size"
|
||||
help
|
||||
The size in bytes of the installed RAM.
|
||||
The size in bytes of the installed RAM. Despite the naming,
|
||||
this may be SDRAM or SRAM or any other RAM technology that support
|
||||
program execution.
|
||||
|
||||
comment "Boot options"
|
||||
|
||||
choice
|
||||
prompt "LPC31xx Boot Mode"
|
||||
default BOOT_RUNFROMFLASH
|
||||
|
||||
config BOOT_RUNFROMEXTSRAM
|
||||
bool "Run from external SRAM"
|
||||
---help---
|
||||
Some configuration support booting and running from external SRAM.
|
||||
|
||||
config BOOT_RUNFROMFLASH
|
||||
bool "Boot and run from flash"
|
||||
---help---
|
||||
Most configurations support XIP operation from FLASH but must copy
|
||||
initialized .data sections to RAM. (This is the default).
|
||||
|
||||
config BOOT_RUNFROMISRAM
|
||||
bool "Boot and run from internal SRAM"
|
||||
---help---
|
||||
Some configuration support booting and running from internal SRAM.
|
||||
|
||||
config BOOT_RUNFROMSDRAM
|
||||
bool "Boot and run from external SDRAM"
|
||||
---help---
|
||||
Some configuration support booting and running from external SDRAM.
|
||||
|
||||
config BOOT_COPYTORAM
|
||||
bool "Boot from FLASH but copy to ram"
|
||||
---help---
|
||||
Some configurations boot in FLASH but copy themselves entirely into
|
||||
RAM for better performance.
|
||||
|
||||
endchoice
|
||||
|
|
|
@ -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
|
||||
|
|
|
@ -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
|
||||
|
|
|
@ -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);
|
||||
|
|
|
@ -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
|
||||
|
||||
|
|
|
@ -2,7 +2,7 @@
|
|||
# arch/arm/lpc31xx/Make.defs
|
||||
#
|
||||
# Copyright (C) 2009-2011 Gregory Nutt. All rights reserved.
|
||||
# Author: Gregory Nutt <spudmonkey@racsa.co.cr>
|
||||
# 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
|
||||
|
|
|
@ -2,7 +2,7 @@
|
|||
* arch/arm/src/lpc31xx/chip.h
|
||||
*
|
||||
* Copyright (C) 2009, 2011 Gregory Nutt. All rights reserved.
|
||||
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
|
||||
* 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
|
||||
|
@ -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 */
|
||||
|
|
|
@ -2,7 +2,7 @@
|
|||
* arch/arm/src/lpc31xx/lpc31_adc.h
|
||||
*
|
||||
* Copyright (C) 2009-2010 Gregory Nutt. All rights reserved.
|
||||
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
|
||||
* 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
|
||||
|
|
|
@ -2,7 +2,7 @@
|
|||
* arch/arm/src/lpc31xx/lpc31_allocateheap.c
|
||||
*
|
||||
* Copyright (C) 2009-2010 Gregory Nutt. All rights reserved.
|
||||
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
|
||||
* 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
|
||||
|
|
|
@ -2,7 +2,7 @@
|
|||
* arch/arm/src/lpc31xx/lpc31_analogdie.h
|
||||
*
|
||||
* Copyright (C) 2011 Gregory Nutt. All rights reserved.
|
||||
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
|
||||
* 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
|
||||
|
|
|
@ -2,7 +2,7 @@
|
|||
* arch/arm/src/lpc31xx/lpc31_bcrndx.c
|
||||
*
|
||||
* Copyright (C) 2009-2010 Gregory Nutt. All rights reserved.
|
||||
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
|
||||
* Author: Gregory Nutt <gnutt@nuttx.org>
|
||||
*
|
||||
* References:
|
||||
* - UM10314 LPC3130/31 User manual Rev. 1.01 — 9 September 2009
|
||||
|
|
|
@ -2,7 +2,7 @@
|
|||
* arch/arm/src/lpc31xx/lpc31_cgu.h
|
||||
*
|
||||
* Copyright (C) 2009-2011 Gregory Nutt. All rights reserved.
|
||||
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
|
||||
* Author: Gregory Nutt <gnutt@nuttx.org>
|
||||
*
|
||||
* References:
|
||||
* - UM10314 LPC3130/31 User manual Rev. 1.01 — 9 September 2009
|
||||
|
|
|
@ -2,7 +2,7 @@
|
|||
* arch/arm/src/lpc31xx/lpc31_cgudrvr.h
|
||||
*
|
||||
* Copyright (C) 2009-2010 Gregory Nutt. All rights reserved.
|
||||
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
|
||||
* Author: Gregory Nutt <gnutt@nuttx.org>
|
||||
*
|
||||
* References:
|
||||
* - NXP UM10314 LPC3130/31 User manual Rev. 1.01 — 9 September 2009
|
||||
|
|
|
@ -2,7 +2,7 @@
|
|||
* arch/arm/src/lpc31xx/lpc31_clkdomain.c
|
||||
*
|
||||
* Copyright (C) 2009 Gregory Nutt. All rights reserved.
|
||||
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
|
||||
* Author: Gregory Nutt <gnutt@nuttx.org>
|
||||
*
|
||||
* References:
|
||||
* - UM10314 LPC3130/31 User manual Rev. 1.01 — 9 September 2009
|
||||
|
|
|
@ -2,7 +2,7 @@
|
|||
* arch/arm/src/lpc31xx/lpc31_exten.c
|
||||
*
|
||||
* Copyright (C) 2009 Gregory Nutt. All rights reserved.
|
||||
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
|
||||
* 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
|
||||
|
|
|
@ -2,7 +2,7 @@
|
|||
* arch/arm/src/lpc31xx/lpc31_clkfreq.c
|
||||
*
|
||||
* Copyright (C) 2009-2010 Gregory Nutt. All rights reserved.
|
||||
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
|
||||
* Author: Gregory Nutt <gnutt@nuttx.org>
|
||||
*
|
||||
* References:
|
||||
* - UM10314 LPC3130/31 User manual Rev. 1.01 — 9 September 2009
|
||||
|
|
|
@ -2,7 +2,7 @@
|
|||
* arch/arm/src/lpc31xx/lpc31_clkinit.c
|
||||
*
|
||||
* Copyright (C) 2009-2010 Gregory Nutt. All rights reserved.
|
||||
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
|
||||
* 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
|
||||
|
|
|
@ -3,7 +3,7 @@
|
|||
* arch/arm/src/chip/lpc31_decodeirq.c
|
||||
*
|
||||
* Copyright (C) 2009 Gregory Nutt. All rights reserved.
|
||||
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
|
||||
* 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
|
||||
|
|
|
@ -2,7 +2,7 @@
|
|||
* arch/arm/src/lpc31xx/lpc31_defclk.c
|
||||
*
|
||||
* Copyright (C) 2009 Gregory Nutt. All rights reserved.
|
||||
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
|
||||
* 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
|
||||
|
|
|
@ -2,7 +2,7 @@
|
|||
* arch/arm/src/lpc31xx/lpc31_dma.h
|
||||
*
|
||||
* Copyright (C) 2009, 2011 Gregory Nutt. All rights reserved.
|
||||
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
|
||||
* 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
|
||||
|
|
|
@ -2,7 +2,7 @@
|
|||
* arch/arm/src/lpc31xx/lpc31_esrndx.c
|
||||
*
|
||||
* Copyright (C) 2009-2010 Gregory Nutt. All rights reserved.
|
||||
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
|
||||
* Author: Gregory Nutt <gnutt@nuttx.org>
|
||||
*
|
||||
* References:
|
||||
* - UM10314 LPC3130/31 User manual Rev. 1.01 — 9 September 2009
|
||||
|
|
|
@ -2,7 +2,7 @@
|
|||
* arch/arm/src/lpc31xx/lpc31_evntrtr.h
|
||||
*
|
||||
* Copyright (C) 2009-2010 Gregory Nutt. All rights reserved.
|
||||
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
|
||||
* 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
|
||||
|
|
|
@ -2,7 +2,7 @@
|
|||
* arch/arm/src/lpc31xx/lpc31_fdcndx.c
|
||||
*
|
||||
* Copyright (C) 2009-2010 Gregory Nutt. All rights reserved.
|
||||
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
|
||||
* Author: Gregory Nutt <gnutt@nuttx.org>
|
||||
*
|
||||
* References:
|
||||
* - UM10314 LPC3130/31 User manual Rev. 1.01 — 9 September 2009
|
||||
|
|
|
@ -2,7 +2,7 @@
|
|||
* arch/arm/src/lpc31xx/lpc31_fdivinit.c
|
||||
*
|
||||
* Copyright (C) 2009 Gregory Nutt. All rights reserved.
|
||||
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
|
||||
* 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
|
||||
|
|
|
@ -2,7 +2,7 @@
|
|||
* arch/arm/src/lpc31xx/lpc31_freqin.c
|
||||
*
|
||||
* Copyright (C) 2009 Gregory Nutt. All rights reserved.
|
||||
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
|
||||
* 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
|
||||
|
|
|
@ -4,7 +4,7 @@
|
|||
* Author: David Hewson
|
||||
*
|
||||
* Copyright (C) 2010-2011 Gregory Nutt. All rights reserved.
|
||||
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
|
||||
* 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
|
||||
|
|
|
@ -2,7 +2,7 @@
|
|||
* arch/arm/src/lpc31xx/lpc31_i2c.h
|
||||
*
|
||||
* Copyright (C) 2009-2010 Gregory Nutt. All rights reserved.
|
||||
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
|
||||
* 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
|
||||
|
|
|
@ -2,7 +2,7 @@
|
|||
* arch/arm/src/lpc31xx/lpc31_i2s.h
|
||||
*
|
||||
* Copyright (C) 2009 Gregory Nutt. All rights reserved.
|
||||
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
|
||||
* 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
|
||||
|
|
|
@ -2,7 +2,7 @@
|
|||
* arch/arm/src/lpc31xx/lpc31_intc.h
|
||||
*
|
||||
* Copyright (C) 2009-2010 Gregory Nutt. All rights reserved.
|
||||
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
|
||||
* 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
|
||||
|
|
|
@ -2,7 +2,7 @@
|
|||
* arch/arm/src/lpc31xx/lpc31_internal.h
|
||||
*
|
||||
* Copyright (C) 2009-2011 Gregory Nutt. All rights reserved.
|
||||
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
|
||||
* 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
|
||||
|
|
|
@ -2,7 +2,7 @@
|
|||
* arch/arm/src/lpc31xx/lpc31_ioconfig.h
|
||||
*
|
||||
* Copyright (C) 2009-2010 Gregory Nutt. All rights reserved.
|
||||
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
|
||||
* 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
|
||||
|
|
|
@ -3,7 +3,7 @@
|
|||
* arch/arm/src/chip/lpc31_irq.c
|
||||
*
|
||||
* Copyright (C) 2009-2011 Gregory Nutt. All rights reserved.
|
||||
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
|
||||
* 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
|
||||
|
|
|
@ -2,7 +2,7 @@
|
|||
* arch/arm/src/lpc31xx/lpc31_lcd.h
|
||||
*
|
||||
* Copyright (C) 2009 Gregory Nutt. All rights reserved.
|
||||
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
|
||||
* 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
|
||||
|
|
|
@ -2,7 +2,7 @@
|
|||
* arch/arm/src/lpc31xx/lpc31_mci.h
|
||||
*
|
||||
* Copyright (C) 2009 Gregory Nutt. All rights reserved.
|
||||
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
|
||||
* 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
|
||||
|
|
|
@ -2,7 +2,7 @@
|
|||
* arch/arm/src/lpc31xx/lpc31_memorymap.h
|
||||
*
|
||||
* Copyright (C) 2009-2010 Gregory Nutt. All rights reserved.
|
||||
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
|
||||
* 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
|
||||
|
|
|
@ -2,7 +2,7 @@
|
|||
* arch/arm/src/lpc31xx/lpc31_mpmc.h
|
||||
*
|
||||
* Copyright (C) 2009 Gregory Nutt. All rights reserved.
|
||||
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
|
||||
* 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
|
||||
|
|
|
@ -2,7 +2,7 @@
|
|||
* arch/arm/src/lpc31xx/lpc31_nand.h
|
||||
*
|
||||
* Copyright (C) 2009, 2011 Gregory Nutt. All rights reserved.
|
||||
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
|
||||
* 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
|
||||
|
|
|
@ -2,7 +2,7 @@
|
|||
* arch/arm/src/lpc31xx/lpc31_otp.h
|
||||
*
|
||||
* Copyright (C) 2011 Gregory Nutt. All rights reserved.
|
||||
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
|
||||
* 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
|
||||
|
|
|
@ -2,7 +2,7 @@
|
|||
* arch/arm/src/lpc31xx/lpc31_pcm.h
|
||||
*
|
||||
* Copyright (C) 2009 Gregory Nutt. All rights reserved.
|
||||
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
|
||||
* 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
|
||||
|
|
|
@ -2,7 +2,7 @@
|
|||
* arch/arm/src/lpc31xx/lpc31_pllconfig.c
|
||||
*
|
||||
* Copyright (C) 2009-2010 Gregory Nutt. All rights reserved.
|
||||
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
|
||||
* Author: Gregory Nutt <gnutt@nuttx.org>
|
||||
*
|
||||
* References:
|
||||
* - NXP UM10314 LPC3130/31 User manual Rev. 1.01 — 9 September 2009
|
||||
|
|
|
@ -2,7 +2,7 @@
|
|||
* arch/arm/src/lpc31xx/lpc31_pwm.h
|
||||
*
|
||||
* Copyright (C) 2009-2010 Gregory Nutt. All rights reserved.
|
||||
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
|
||||
* 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
|
||||
|
|
|
@ -2,7 +2,7 @@
|
|||
* arch/arm/src/lpc31xx/lpc31_resetclks.c
|
||||
*
|
||||
* Copyright (C) 2009 Gregory Nutt. All rights reserved.
|
||||
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
|
||||
* 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
|
||||
|
|
|
@ -2,7 +2,7 @@
|
|||
* arch/arm/src/lpc31xx/lpc31_rng.h
|
||||
*
|
||||
* Copyright (C) 2009-2010 Gregory Nutt. All rights reserved.
|
||||
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
|
||||
* 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
|
||||
|
|
|
@ -2,7 +2,7 @@
|
|||
* arch/arm/src/lpc31xx/lpc31_setfdiv.c
|
||||
*
|
||||
* Copyright (C) 2009-2010 Gregory Nutt. All rights reserved.
|
||||
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
|
||||
* 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
|
||||
|
|
|
@ -2,7 +2,7 @@
|
|||
* arch/arm/src/lpc31xx/lpc31_setfreqin.c
|
||||
*
|
||||
* Copyright (C) 2009-2010 Gregory Nutt. All rights reserved.
|
||||
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
|
||||
* Author: Gregory Nutt <gnutt@nuttx.org>
|
||||
*
|
||||
* References:
|
||||
* - NXP UM10314 LPC3130/31 User manual Rev. 1.01 — 9 September 2009
|
||||
|
|
|
@ -2,7 +2,7 @@
|
|||
* arch/arm/src/lpc31xx/lpc31_softreset.c
|
||||
*
|
||||
* Copyright (C) 2009 Gregory Nutt. All rights reserved.
|
||||
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
|
||||
* Author: Gregory Nutt <gnutt@nuttx.org>
|
||||
*
|
||||
* References:
|
||||
* - UM10314 LPC3130/31 User manual Rev. 1.01 — 9 September 2009
|
||||
|
|
|
@ -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 <spudmonkey@racsa.co.cr>
|
||||
* Gregory Nutt <gnutt@nuttx.org>
|
||||
*
|
||||
* 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),
|
||||
|
|
|
@ -2,7 +2,7 @@
|
|||
* arch/arm/src/lpc31xx/lpc31_spi.h
|
||||
*
|
||||
* Copyright (C) 2009-2010 Gregory Nutt. All rights reserved.
|
||||
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
|
||||
* 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
|
||||
|
|
|
@ -2,7 +2,7 @@
|
|||
* arch/arm/src/lpc31xx/lpc31_syscreg.h
|
||||
*
|
||||
* Copyright (C) 2009-2010 Gregory Nutt. All rights reserved.
|
||||
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
|
||||
* 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
|
||||
|
|
|
@ -2,7 +2,7 @@
|
|||
* arch/arm/src/lpc31xx/lpc31_timer.h
|
||||
*
|
||||
* Copyright (C) 2009-2010 Gregory Nutt. All rights reserved.
|
||||
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
|
||||
* 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
|
||||
|
|
|
@ -2,7 +2,7 @@
|
|||
* arch/arm/src/lpc31xx/lpc31_timerisr.c
|
||||
*
|
||||
* Copyright (C) 2009 Gregory Nutt. All rights reserved.
|
||||
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
|
||||
* 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
|
||||
|
|
|
@ -2,7 +2,7 @@
|
|||
* arch/arm/src/lpc31xx/lpc31_uart.h
|
||||
*
|
||||
* Copyright (C) 2009 Gregory Nutt. All rights reserved.
|
||||
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
|
||||
* 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
|
||||
|
|
|
@ -2,7 +2,7 @@
|
|||
* arch/arm/src/lpc31xx/lpc31_usbdev.c
|
||||
*
|
||||
* Authors: David Hewson
|
||||
* Gregory Nutt <spudmonkey@racsa.co.cr>
|
||||
* Gregory Nutt <gnutt@nuttx.org>
|
||||
*
|
||||
* 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);
|
||||
|
|
|
@ -2,7 +2,7 @@
|
|||
* arch/arm/src/lpc31xx/lpc31_usbotg.h
|
||||
*
|
||||
* Copyright (C) 2009-2011 Gregory Nutt. All rights reserved.
|
||||
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
|
||||
* 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
|
||||
|
|
|
@ -2,7 +2,7 @@
|
|||
* arch/arm/src/lpc31xx/lpc31_wdt.h
|
||||
*
|
||||
* Copyright (C) 2009-2010 Gregory Nutt. All rights reserved.
|
||||
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
|
||||
* 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
|
||||
|
|
|
@ -1,7 +1,7 @@
|
|||
############################################################################
|
||||
# configs/ea3131/nsh/defconfig
|
||||
#
|
||||
# Copyright (C) 2010 Gregory Nutt. All rights reserved.
|
||||
# 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
|
||||
|
@ -39,6 +39,7 @@ CONFIG_ARCH="arm"
|
|||
CONFIG_ARCH_ARM=y
|
||||
CONFIG_ARCH_ARM926EJS=y
|
||||
CONFIG_ARCH_CHIP="lpc31xx"
|
||||
CONFIG_ARCH_CHIP_LPC31XX=y
|
||||
CONFIG_ARCH_CHIP_LPC3131=y
|
||||
CONFIG_ARCH_BOARD="ea3131"
|
||||
CONFIG_ARCH_BOARD_EA3131=y
|
||||
|
@ -63,32 +64,32 @@ CONFIG_ARCH_ROMPGTABLE=y
|
|||
|
||||
# Identify toolchain and linker options
|
||||
#
|
||||
CONFIG_LPC31XX_CODESOURCERYW=n
|
||||
CONFIG_LPC31XX_CODESOURCERYL=n
|
||||
CONFIG_LPC31XX_DEVKITARM=n
|
||||
CONFIG_LPC31XX_BUILDROOT=y
|
||||
CONFIG_LPC31_CODESOURCERYW=n
|
||||
CONFIG_LPC31_CODESOURCERYL=n
|
||||
CONFIG_LPC31_DEVKITARM=n
|
||||
CONFIG_LPC31_BUILDROOT=y
|
||||
|
||||
#
|
||||
# Individual subsystems can be enabled:
|
||||
#
|
||||
CONFIG_LPC31XX_MCI=n
|
||||
CONFIG_LPC31XX_SPI=n
|
||||
CONFIG_LPC31XX_UART=y
|
||||
CONFIG_LPC31_MCI=n
|
||||
CONFIG_LPC31_SPI=n
|
||||
CONFIG_LPC31_UART=y
|
||||
|
||||
#
|
||||
# Exernal memory available on the board (see also CONFIG_MM_REGIONS)
|
||||
#
|
||||
CONFIG_LPC31XX_EXTSRAM0=n
|
||||
CONFIG_LPC31XX_EXTSRAM0HEAP=n
|
||||
CONFIG_LPC31XX_EXTSRAM0SIZE=131072
|
||||
CONFIG_LPC31XX_EXTSRAM1=n
|
||||
CONFIG_LPC31XX_EXTSRAM1HEAP=n
|
||||
CONFIG_LPC31XX_EXTSRAM1SIZE=131072
|
||||
CONFIG_LPC31XX_EXTSDRAM=n
|
||||
CONFIG_LPC31XX_EXTSDRAMHEAP=n
|
||||
CONFIG_LPC31XX_EXTSDRAMSIZE=67108864
|
||||
CONFIG_LPC31XX_EXTNAND=n
|
||||
CONFIG_LPC31XX_EXTNANDSIZE=67108864
|
||||
CONFIG_LPC31_EXTSRAM0=n
|
||||
CONFIG_LPC31_EXTSRAM0HEAP=n
|
||||
CONFIG_LPC31_EXTSRAM0SIZE=131072
|
||||
CONFIG_LPC31_EXTSRAM1=n
|
||||
CONFIG_LPC31_EXTSRAM1HEAP=n
|
||||
CONFIG_LPC31_EXTSRAM1SIZE=131072
|
||||
CONFIG_LPC31_EXTSDRAM=n
|
||||
CONFIG_LPC31_EXTSDRAMHEAP=n
|
||||
CONFIG_LPC31_EXTSDRAMSIZE=67108864
|
||||
CONFIG_LPC31_EXTNAND=n
|
||||
CONFIG_LPC31_EXTNANDSIZE=67108864
|
||||
|
||||
#
|
||||
# LPC31XX specific device driver settings
|
||||
|
@ -269,11 +270,11 @@ CONFIG_USBDEV_TRACE_NRECORDS=128
|
|||
#
|
||||
# LPC31XX USB Configuration
|
||||
#
|
||||
CONFIG_LPC31XX_GIO_USBATTACH=6
|
||||
CONFIG_LPC31XX_GIO_USBDPPULLUP=17
|
||||
CONFIG_LPC31XX_VENDORID=0xd320
|
||||
CONFIG_LPC31XX_PRODUCTID=0x3211
|
||||
CONFIG_LPC31XX_USBDEV_DMA=n
|
||||
CONFIG_LPC31_GIO_USBATTACH=6
|
||||
CONFIG_LPC31_GIO_USBDPPULLUP=17
|
||||
CONFIG_LPC31_VENDORID=0xd320
|
||||
CONFIG_LPC31_PRODUCTID=0x3211
|
||||
CONFIG_LPC31_USBDEV_DMA=n
|
||||
|
||||
#
|
||||
# USB Serial Device Configuration
|
||||
|
@ -388,12 +389,7 @@ CONFIG_EXAMPLES_USBSERIAL_TRACEINTERRUPTS=n
|
|||
# Stack and heap information
|
||||
#
|
||||
CONFIG_BOOT_RUNFROMFLASH=n
|
||||
CONFIG_BOOT_COPYTORAM=n
|
||||
CONFIG_CUSTOM_STACK=n
|
||||
#CONFIG_STACK_POINTER
|
||||
CONFIG_IDLETHREAD_STACKSIZE=1024
|
||||
CONFIG_USERMAIN_STACKSIZE=2048
|
||||
CONFIG_PTHREAD_STACK_MIN=256
|
||||
CONFIG_PTHREAD_STACK_DEFAULT=2048
|
||||
CONFIG_HEAP_BASE=
|
||||
CONFIG_HEAP_SIZE=
|
||||
|
|
|
@ -1,7 +1,7 @@
|
|||
############################################################################
|
||||
# configs/ea3131/ostest/defconfig
|
||||
#
|
||||
# Copyright (C) 2009-2010 Gregory Nutt. All rights reserved.
|
||||
# Copyright (C) 2009-2010,2012 Gregory Nutt. All rights reserved.
|
||||
# Author: Gregory Nutt <gnutt@nuttx.org>
|
||||
#
|
||||
# Redistribution and use in source and binary forms, with or without
|
||||
|
@ -39,6 +39,7 @@ CONFIG_ARCH="arm"
|
|||
CONFIG_ARCH_ARM=y
|
||||
CONFIG_ARCH_ARM926EJS=y
|
||||
CONFIG_ARCH_CHIP="lpc31xx"
|
||||
CONFIG_ARCH_CHIP_LPC31XX=y
|
||||
CONFIG_ARCH_CHIP_LPC3131=y
|
||||
CONFIG_ARCH_BOARD="ea3131"
|
||||
CONFIG_ARCH_BOARD_EA3131=y
|
||||
|
@ -63,32 +64,32 @@ CONFIG_ARCH_ROMPGTABLE=y
|
|||
|
||||
# Identify toolchain and linker options
|
||||
#
|
||||
CONFIG_LPC31XX_CODESOURCERYW=n
|
||||
CONFIG_LPC31XX_CODESOURCERYL=n
|
||||
CONFIG_LPC31XX_DEVKITARM=n
|
||||
CONFIG_LPC31XX_BUILDROOT=y
|
||||
CONFIG_LPC31_CODESOURCERYW=n
|
||||
CONFIG_LPC31_CODESOURCERYL=n
|
||||
CONFIG_LPC31_DEVKITARM=n
|
||||
CONFIG_LPC31_BUILDROOT=y
|
||||
|
||||
#
|
||||
# Individual subsystems can be enabled:
|
||||
#
|
||||
CONFIG_LPC31XX_MCI=n
|
||||
CONFIG_LPC31XX_SPI=n
|
||||
CONFIG_LPC31XX_UART=y
|
||||
CONFIG_LPC31_MCI=n
|
||||
CONFIG_LPC31_SPI=n
|
||||
CONFIG_LPC31_UART=y
|
||||
|
||||
#
|
||||
# Exernal memory available on the board (see also CONFIG_MM_REGIONS)
|
||||
#
|
||||
CONFIG_LPC31XX_EXTSRAM0=n
|
||||
CONFIG_LPC31XX_EXTSRAM0HEAP=n
|
||||
CONFIG_LPC31XX_EXTSRAM0SIZE=131072
|
||||
CONFIG_LPC31XX_EXTSRAM1=n
|
||||
CONFIG_LPC31XX_EXTSRAM1HEAP=n
|
||||
CONFIG_LPC31XX_EXTSRAM1SIZE=131072
|
||||
CONFIG_LPC31XX_EXTSDRAM=n
|
||||
CONFIG_LPC31XX_EXTSDRAMHEAP=n
|
||||
CONFIG_LPC31XX_EXTSDRAMSIZE=67108864
|
||||
CONFIG_LPC31XX_EXTNAND=n
|
||||
CONFIG_LPC31XX_EXTNANDSIZE=67108864
|
||||
CONFIG_LPC31_EXTSRAM0=n
|
||||
CONFIG_LPC31_EXTSRAM0HEAP=n
|
||||
CONFIG_LPC31_EXTSRAM0SIZE=131072
|
||||
CONFIG_LPC31_EXTSRAM1=n
|
||||
CONFIG_LPC31_EXTSRAM1HEAP=n
|
||||
CONFIG_LPC31_EXTSRAM1SIZE=131072
|
||||
CONFIG_LPC31_EXTSDRAM=n
|
||||
CONFIG_LPC31_EXTSDRAMHEAP=n
|
||||
CONFIG_LPC31_EXTSDRAMSIZE=67108864
|
||||
CONFIG_LPC31_EXTNAND=n
|
||||
CONFIG_LPC31_EXTNANDSIZE=67108864
|
||||
|
||||
#
|
||||
# LPC31XX specific device driver settings
|
||||
|
@ -269,11 +270,11 @@ CONFIG_USBDEV_TRACE_NRECORDS=128
|
|||
#
|
||||
# LPC31XX USB Configuration
|
||||
#
|
||||
CONFIG_LPC31XX_GIO_USBATTACH=6
|
||||
CONFIG_LPC31XX_GIO_USBDPPULLUP=17
|
||||
CONFIG_LPC31XX_VENDORID=0xd320
|
||||
CONFIG_LPC31XX_PRODUCTID=0x3211
|
||||
CONFIG_LPC31XX_USBDEV_DMA=n
|
||||
CONFIG_LPC31_GIO_USBATTACH=6
|
||||
CONFIG_LPC31_GIO_USBDPPULLUP=17
|
||||
CONFIG_LPC31_VENDORID=0xd320
|
||||
CONFIG_LPC31_PRODUCTID=0x3211
|
||||
CONFIG_LPC31_USBDEV_DMA=n
|
||||
|
||||
#
|
||||
# USB Serial Device Configuration
|
||||
|
@ -387,13 +388,8 @@ CONFIG_EXAMPLES_USBSERIAL_TRACEINTERRUPTS=n
|
|||
#
|
||||
# Stack and heap information
|
||||
#
|
||||
CONFIG_BOOT_RUNFROMFLASH=n
|
||||
CONFIG_BOOT_COPYTORAM=n
|
||||
CONFIG_CUSTOM_STACK=n
|
||||
#CONFIG_STACK_POINTER
|
||||
CONFIG_BOOT_RUNFROMISRAM=y
|
||||
CONFIG_IDLETHREAD_STACKSIZE=1024
|
||||
CONFIG_USERMAIN_STACKSIZE=2048
|
||||
CONFIG_PTHREAD_STACK_MIN=256
|
||||
CONFIG_PTHREAD_STACK_DEFAULT=2048
|
||||
CONFIG_HEAP_BASE=
|
||||
CONFIG_HEAP_SIZE=
|
||||
|
|
|
@ -1,7 +1,7 @@
|
|||
############################################################################
|
||||
# configs/ea3131/pgnsh/defconfig
|
||||
#
|
||||
# Copyright (C) 2010 Gregory Nutt. All rights reserved.
|
||||
# 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
|
||||
|
@ -39,6 +39,7 @@ CONFIG_ARCH="arm"
|
|||
CONFIG_ARCH_ARM=y
|
||||
CONFIG_ARCH_ARM926EJS=y
|
||||
CONFIG_ARCH_CHIP="lpc31xx"
|
||||
CONFIG_ARCH_CHIP_LPC31XX=y
|
||||
CONFIG_ARCH_CHIP_LPC3131=y
|
||||
CONFIG_ARCH_BOARD="ea3131"
|
||||
CONFIG_ARCH_BOARD_EA3131=y
|
||||
|
@ -63,32 +64,32 @@ CONFIG_ARCH_ROMPGTABLE=n
|
|||
|
||||
# Identify toolchain and linker options
|
||||
#
|
||||
CONFIG_LPC31XX_CODESOURCERYW=n
|
||||
CONFIG_LPC31XX_CODESOURCERYL=n
|
||||
CONFIG_LPC31XX_DEVKITARM=n
|
||||
CONFIG_LPC31XX_BUILDROOT=y
|
||||
CONFIG_LPC31_CODESOURCERYW=n
|
||||
CONFIG_LPC31_CODESOURCERYL=n
|
||||
CONFIG_LPC31_DEVKITARM=n
|
||||
CONFIG_LPC31_BUILDROOT=y
|
||||
|
||||
#
|
||||
# Individual subsystems can be enabled:
|
||||
#
|
||||
CONFIG_LPC31XX_MCI=n
|
||||
CONFIG_LPC31XX_SPI=y
|
||||
CONFIG_LPC31XX_UART=y
|
||||
CONFIG_LPC31_MCI=n
|
||||
CONFIG_LPC31_SPI=y
|
||||
CONFIG_LPC31_UART=y
|
||||
|
||||
#
|
||||
# Exernal memory available on the board (see also CONFIG_MM_REGIONS)
|
||||
#
|
||||
CONFIG_LPC31XX_EXTSRAM0=n
|
||||
CONFIG_LPC31XX_EXTSRAM0HEAP=n
|
||||
CONFIG_LPC31XX_EXTSRAM0SIZE=131072
|
||||
CONFIG_LPC31XX_EXTSRAM1=n
|
||||
CONFIG_LPC31XX_EXTSRAM1HEAP=n
|
||||
CONFIG_LPC31XX_EXTSRAM1SIZE=131072
|
||||
CONFIG_LPC31XX_EXTSDRAM=n
|
||||
CONFIG_LPC31XX_EXTSDRAMHEAP=n
|
||||
CONFIG_LPC31XX_EXTSDRAMSIZE=67108864
|
||||
CONFIG_LPC31XX_EXTNAND=n
|
||||
CONFIG_LPC31XX_EXTNANDSIZE=67108864
|
||||
CONFIG_LPC31_EXTSRAM0=n
|
||||
CONFIG_LPC31_EXTSRAM0HEAP=n
|
||||
CONFIG_LPC31_EXTSRAM0SIZE=131072
|
||||
CONFIG_LPC31_EXTSRAM1=n
|
||||
CONFIG_LPC31_EXTSRAM1HEAP=n
|
||||
CONFIG_LPC31_EXTSRAM1SIZE=131072
|
||||
CONFIG_LPC31_EXTSDRAM=n
|
||||
CONFIG_LPC31_EXTSDRAMHEAP=n
|
||||
CONFIG_LPC31_EXTSDRAMSIZE=67108864
|
||||
CONFIG_LPC31_EXTNAND=n
|
||||
CONFIG_LPC31_EXTNANDSIZE=67108864
|
||||
|
||||
#
|
||||
# LPC31XX specific device driver settings
|
||||
|
@ -312,11 +313,11 @@ CONFIG_USBDEV_TRACE_NRECORDS=128
|
|||
#
|
||||
# LPC31XX USB Configuration
|
||||
#
|
||||
CONFIG_LPC31XX_GIO_USBATTACH=6
|
||||
CONFIG_LPC31XX_GIO_USBDPPULLUP=17
|
||||
CONFIG_LPC31XX_VENDORID=0xd320
|
||||
CONFIG_LPC31XX_PRODUCTID=0x3211
|
||||
CONFIG_LPC31XX_USBDEV_DMA=n
|
||||
CONFIG_LPC31_GIO_USBATTACH=6
|
||||
CONFIG_LPC31_GIO_USBDPPULLUP=17
|
||||
CONFIG_LPC31_VENDORID=0xd320
|
||||
CONFIG_LPC31_PRODUCTID=0x3211
|
||||
CONFIG_LPC31_USBDEV_DMA=n
|
||||
|
||||
#
|
||||
# USB Serial Device Configuration
|
||||
|
@ -430,13 +431,8 @@ CONFIG_EXAMPLES_USBSERIAL_TRACEINTERRUPTS=n
|
|||
#
|
||||
# Stack and heap information
|
||||
#
|
||||
CONFIG_BOOT_RUNFROMFLASH=n
|
||||
CONFIG_BOOT_COPYTORAM=n
|
||||
CONFIG_CUSTOM_STACK=n
|
||||
#CONFIG_STACK_POINTER
|
||||
CONFIG_BOOT_RUNFROMISRAM=y
|
||||
CONFIG_IDLETHREAD_STACKSIZE=1024
|
||||
CONFIG_USERMAIN_STACKSIZE=2048
|
||||
CONFIG_PTHREAD_STACK_MIN=256
|
||||
CONFIG_PTHREAD_STACK_DEFAULT=2048
|
||||
CONFIG_HEAP_BASE=
|
||||
CONFIG_HEAP_SIZE=
|
||||
|
|
|
@ -1,7 +1,7 @@
|
|||
############################################################################
|
||||
# configs/ea3131/usbserial/defconfig
|
||||
#
|
||||
# Copyright (C) 2010-2011 Gregory Nutt. All rights reserved.
|
||||
# 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
|
||||
|
@ -39,6 +39,7 @@ CONFIG_ARCH="arm"
|
|||
CONFIG_ARCH_ARM=y
|
||||
CONFIG_ARCH_ARM926EJS=y
|
||||
CONFIG_ARCH_CHIP="lpc31xx"
|
||||
CONFIG_ARCH_CHIP_LPC31XX=y
|
||||
CONFIG_ARCH_CHIP_LPC3131=y
|
||||
CONFIG_ARCH_BOARD="ea3131"
|
||||
CONFIG_ARCH_BOARD_EA3131=y
|
||||
|
@ -63,32 +64,32 @@ CONFIG_ARCH_ROMPGTABLE=y
|
|||
|
||||
# Identify toolchain and linker options
|
||||
#
|
||||
CONFIG_LPC31XX_CODESOURCERYW=n
|
||||
CONFIG_LPC31XX_CODESOURCERYL=y
|
||||
CONFIG_LPC31XX_DEVKITARM=n
|
||||
CONFIG_LPC31XX_BUILDROOT=n
|
||||
CONFIG_LPC31_CODESOURCERYW=n
|
||||
CONFIG_LPC31_CODESOURCERYL=y
|
||||
CONFIG_LPC31_DEVKITARM=n
|
||||
CONFIG_LPC31_BUILDROOT=n
|
||||
|
||||
#
|
||||
# Individual subsystems can be enabled:
|
||||
#
|
||||
CONFIG_LPC31XX_MCI=n
|
||||
CONFIG_LPC31XX_SPI=n
|
||||
CONFIG_LPC31XX_UART=y
|
||||
CONFIG_LPC31_MCI=n
|
||||
CONFIG_LPC31_SPI=n
|
||||
CONFIG_LPC31_UART=y
|
||||
|
||||
#
|
||||
# Exernal memory available on the board (see also CONFIG_MM_REGIONS)
|
||||
#
|
||||
CONFIG_LPC31XX_EXTSRAM0=n
|
||||
CONFIG_LPC31XX_EXTSRAM0HEAP=n
|
||||
CONFIG_LPC31XX_EXTSRAM0SIZE=131072
|
||||
CONFIG_LPC31XX_EXTSRAM1=n
|
||||
CONFIG_LPC31XX_EXTSRAM1HEAP=n
|
||||
CONFIG_LPC31XX_EXTSRAM1SIZE=131072
|
||||
CONFIG_LPC31XX_EXTSDRAM=n
|
||||
CONFIG_LPC31XX_EXTSDRAMHEAP=n
|
||||
CONFIG_LPC31XX_EXTSDRAMSIZE=67108864
|
||||
CONFIG_LPC31XX_EXTNAND=n
|
||||
CONFIG_LPC31XX_EXTNANDSIZE=67108864
|
||||
CONFIG_LPC31_EXTSRAM0=n
|
||||
CONFIG_LPC31_EXTSRAM0HEAP=n
|
||||
CONFIG_LPC31_EXTSRAM0SIZE=131072
|
||||
CONFIG_LPC31_EXTSRAM1=n
|
||||
CONFIG_LPC31_EXTSRAM1HEAP=n
|
||||
CONFIG_LPC31_EXTSRAM1SIZE=131072
|
||||
CONFIG_LPC31_EXTSDRAM=n
|
||||
CONFIG_LPC31_EXTSDRAMHEAP=n
|
||||
CONFIG_LPC31_EXTSDRAMSIZE=67108864
|
||||
CONFIG_LPC31_EXTNAND=n
|
||||
CONFIG_LPC31_EXTNANDSIZE=67108864
|
||||
|
||||
#
|
||||
# LPC31XX specific device driver settings
|
||||
|
@ -272,11 +273,11 @@ CONFIG_USBDEV_TRACE_NRECORDS=128
|
|||
#
|
||||
# LPC31XX USB Configuration
|
||||
#
|
||||
CONFIG_LPC31XX_GIO_USBATTACH=6
|
||||
CONFIG_LPC31XX_GIO_USBDPPULLUP=17
|
||||
CONFIG_LPC31XX_VENDORID=0xd320
|
||||
CONFIG_LPC31XX_PRODUCTID=0x3211
|
||||
CONFIG_LPC31XX_USBDEV_DMA=n
|
||||
CONFIG_LPC31_GIO_USBATTACH=6
|
||||
CONFIG_LPC31_GIO_USBDPPULLUP=17
|
||||
CONFIG_LPC31_VENDORID=0xd320
|
||||
CONFIG_LPC31_PRODUCTID=0x3211
|
||||
CONFIG_LPC31_USBDEV_DMA=n
|
||||
|
||||
#
|
||||
# USB Serial Device Configuration
|
||||
|
@ -402,13 +403,8 @@ CONFIG_EXAMPLES_USBMSC_TRACEINTERRUPTS=n
|
|||
#
|
||||
# Stack and heap information
|
||||
#
|
||||
CONFIG_BOOT_RUNFROMFLASH=n
|
||||
CONFIG_BOOT_COPYTORAM=n
|
||||
CONFIG_CUSTOM_STACK=n
|
||||
#CONFIG_STACK_POINTER
|
||||
CONFIG_BOOT_RUNFROMISRAM=y
|
||||
CONFIG_IDLETHREAD_STACKSIZE=1024
|
||||
CONFIG_USERMAIN_STACKSIZE=2048
|
||||
CONFIG_PTHREAD_STACK_MIN=256
|
||||
CONFIG_PTHREAD_STACK_DEFAULT=2048
|
||||
CONFIG_HEAP_BASE=
|
||||
CONFIG_HEAP_SIZE=
|
||||
|
|
|
@ -1,7 +1,7 @@
|
|||
############################################################################
|
||||
# configs/ea3131/usbstorage/defconfig
|
||||
#
|
||||
# Copyright (C) 2010-2011 Gregory Nutt. All rights reserved.
|
||||
# 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
|
||||
|
@ -39,6 +39,7 @@ CONFIG_ARCH="arm"
|
|||
CONFIG_ARCH_ARM=y
|
||||
CONFIG_ARCH_ARM926EJS=y
|
||||
CONFIG_ARCH_CHIP="lpc31xx"
|
||||
CONFIG_ARCH_CHIP_LPC31XX=y
|
||||
CONFIG_ARCH_CHIP_LPC3131=y
|
||||
CONFIG_ARCH_BOARD="ea3131"
|
||||
CONFIG_ARCH_BOARD_EA3131=y
|
||||
|
@ -63,32 +64,32 @@ CONFIG_ARCH_ROMPGTABLE=y
|
|||
|
||||
# Identify toolchain and linker options
|
||||
#
|
||||
CONFIG_LPC31XX_CODESOURCERYW=n
|
||||
CONFIG_LPC31XX_CODESOURCERYL=y
|
||||
CONFIG_LPC31XX_DEVKITARM=n
|
||||
CONFIG_LPC31XX_BUILDROOT=n
|
||||
CONFIG_LPC31_CODESOURCERYW=n
|
||||
CONFIG_LPC31_CODESOURCERYL=y
|
||||
CONFIG_LPC31_DEVKITARM=n
|
||||
CONFIG_LPC31_BUILDROOT=n
|
||||
|
||||
#
|
||||
# Individual subsystems can be enabled:
|
||||
#
|
||||
CONFIG_LPC31XX_MCI=n
|
||||
CONFIG_LPC31XX_SPI=n
|
||||
CONFIG_LPC31XX_UART=y
|
||||
CONFIG_LPC31_MCI=n
|
||||
CONFIG_LPC31_SPI=n
|
||||
CONFIG_LPC31_UART=y
|
||||
|
||||
#
|
||||
# Exernal memory available on the board (see also CONFIG_MM_REGIONS)
|
||||
#
|
||||
CONFIG_LPC31XX_EXTSRAM0=n
|
||||
CONFIG_LPC31XX_EXTSRAM0HEAP=n
|
||||
CONFIG_LPC31XX_EXTSRAM0SIZE=131072
|
||||
CONFIG_LPC31XX_EXTSRAM1=n
|
||||
CONFIG_LPC31XX_EXTSRAM1HEAP=n
|
||||
CONFIG_LPC31XX_EXTSRAM1SIZE=131072
|
||||
CONFIG_LPC31XX_EXTSDRAM=n
|
||||
CONFIG_LPC31XX_EXTSDRAMHEAP=n
|
||||
CONFIG_LPC31XX_EXTSDRAMSIZE=67108864
|
||||
CONFIG_LPC31XX_EXTNAND=n
|
||||
CONFIG_LPC31XX_EXTNANDSIZE=67108864
|
||||
CONFIG_LPC31_EXTSRAM0=n
|
||||
CONFIG_LPC31_EXTSRAM0HEAP=n
|
||||
CONFIG_LPC31_EXTSRAM0SIZE=131072
|
||||
CONFIG_LPC31_EXTSRAM1=n
|
||||
CONFIG_LPC31_EXTSRAM1HEAP=n
|
||||
CONFIG_LPC31_EXTSRAM1SIZE=131072
|
||||
CONFIG_LPC31_EXTSDRAM=n
|
||||
CONFIG_LPC31_EXTSDRAMHEAP=n
|
||||
CONFIG_LPC31_EXTSDRAMSIZE=67108864
|
||||
CONFIG_LPC31_EXTNAND=n
|
||||
CONFIG_LPC31_EXTNANDSIZE=67108864
|
||||
|
||||
#
|
||||
# LPC31XX specific device driver settings
|
||||
|
@ -273,11 +274,11 @@ CONFIG_USBDEV_TRACE_NRECORDS=128
|
|||
#
|
||||
# LPC31XX USB Configuration
|
||||
#
|
||||
CONFIG_LPC31XX_GIO_USBATTACH=6
|
||||
CONFIG_LPC31XX_GIO_USBDPPULLUP=17
|
||||
CONFIG_LPC31XX_VENDORID=0xd320
|
||||
CONFIG_LPC31XX_PRODUCTID=0x3211
|
||||
CONFIG_LPC31XX_USBDEV_DMA=n
|
||||
CONFIG_LPC31_GIO_USBATTACH=6
|
||||
CONFIG_LPC31_GIO_USBDPPULLUP=17
|
||||
CONFIG_LPC31_VENDORID=0xd320
|
||||
CONFIG_LPC31_PRODUCTID=0x3211
|
||||
CONFIG_LPC31_USBDEV_DMA=n
|
||||
|
||||
#
|
||||
# USB Serial Device Configuration
|
||||
|
@ -403,13 +404,8 @@ CONFIG_EXAMPLES_USBMSC_TRACEINTERRUPTS=n
|
|||
#
|
||||
# Stack and heap information
|
||||
#
|
||||
CONFIG_BOOT_RUNFROMFLASH=n
|
||||
CONFIG_BOOT_COPYTORAM=n
|
||||
CONFIG_CUSTOM_STACK=n
|
||||
#CONFIG_STACK_POINTER
|
||||
CONFIG_BOOT_RUNFROMISRAM=y
|
||||
CONFIG_IDLETHREAD_STACKSIZE=1024
|
||||
CONFIG_USERMAIN_STACKSIZE=2048
|
||||
CONFIG_PTHREAD_STACK_MIN=256
|
||||
CONFIG_PTHREAD_STACK_DEFAULT=2048
|
||||
CONFIG_HEAP_BASE=
|
||||
CONFIG_HEAP_SIZE=
|
||||
|
|
|
@ -1,7 +1,7 @@
|
|||
############################################################################
|
||||
# configs/ea3152/ostest/defconfig
|
||||
#
|
||||
# Copyright (C) 2011 Gregory Nutt. 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
|
||||
|
@ -39,6 +39,7 @@ CONFIG_ARCH="arm"
|
|||
CONFIG_ARCH_ARM=y
|
||||
CONFIG_ARCH_ARM926EJS=y
|
||||
CONFIG_ARCH_CHIP="lpc31xx"
|
||||
CONFIG_ARCH_CHIP_LPC31XX=y
|
||||
CONFIG_ARCH_CHIP_LPC3152=y
|
||||
CONFIG_ARCH_BOARD="ea3152"
|
||||
CONFIG_ARCH_BOARD_EA3152=y
|
||||
|
@ -63,32 +64,32 @@ CONFIG_ARCH_ROMPGTABLE=y
|
|||
|
||||
# Identify toolchain and linker options
|
||||
#
|
||||
CONFIG_LPC31XX_CODESOURCERYW=n
|
||||
CONFIG_LPC31XX_CODESOURCERYL=n
|
||||
CONFIG_LPC31XX_DEVKITARM=n
|
||||
CONFIG_LPC31XX_BUILDROOT=y
|
||||
CONFIG_LPC31_CODESOURCERYW=n
|
||||
CONFIG_LPC31_CODESOURCERYL=n
|
||||
CONFIG_LPC31_DEVKITARM=n
|
||||
CONFIG_LPC31_BUILDROOT=y
|
||||
|
||||
#
|
||||
# Individual subsystems can be enabled:
|
||||
#
|
||||
CONFIG_LPC31XX_MCI=n
|
||||
CONFIG_LPC31XX_SPI=n
|
||||
CONFIG_LPC31XX_UART=y
|
||||
CONFIG_LPC31_MCI=n
|
||||
CONFIG_LPC31_SPI=n
|
||||
CONFIG_LPC31_UART=y
|
||||
|
||||
#
|
||||
# Exernal memory available on the board (see also CONFIG_MM_REGIONS)
|
||||
#
|
||||
CONFIG_LPC31XX_EXTSRAM0=n
|
||||
CONFIG_LPC31XX_EXTSRAM0HEAP=n
|
||||
CONFIG_LPC31XX_EXTSRAM0SIZE=131072
|
||||
CONFIG_LPC31XX_EXTSRAM1=n
|
||||
CONFIG_LPC31XX_EXTSRAM1HEAP=n
|
||||
CONFIG_LPC31XX_EXTSRAM1SIZE=131072
|
||||
CONFIG_LPC31XX_EXTSDRAM=n
|
||||
CONFIG_LPC31XX_EXTSDRAMHEAP=n
|
||||
CONFIG_LPC31XX_EXTSDRAMSIZE=67108864
|
||||
CONFIG_LPC31XX_EXTNAND=n
|
||||
CONFIG_LPC31XX_EXTNANDSIZE=67108864
|
||||
CONFIG_LPC31_EXTSRAM0=n
|
||||
CONFIG_LPC31_EXTSRAM0HEAP=n
|
||||
CONFIG_LPC31_EXTSRAM0SIZE=131072
|
||||
CONFIG_LPC31_EXTSRAM1=n
|
||||
CONFIG_LPC31_EXTSRAM1HEAP=n
|
||||
CONFIG_LPC31_EXTSRAM1SIZE=131072
|
||||
CONFIG_LPC31_EXTSDRAM=n
|
||||
CONFIG_LPC31_EXTSDRAMHEAP=n
|
||||
CONFIG_LPC31_EXTSDRAMSIZE=67108864
|
||||
CONFIG_LPC31_EXTNAND=n
|
||||
CONFIG_LPC31_EXTNANDSIZE=67108864
|
||||
|
||||
#
|
||||
# LPC31XX specific device driver settings
|
||||
|
@ -270,11 +271,11 @@ CONFIG_USBDEV_TRACE_NRECORDS=128
|
|||
#
|
||||
# LPC31XX USB Configuration
|
||||
#
|
||||
CONFIG_LPC31XX_GIO_USBATTACH=6
|
||||
CONFIG_LPC31XX_GIO_USBDPPULLUP=17
|
||||
CONFIG_LPC31XX_VENDORID=0xd320
|
||||
CONFIG_LPC31XX_PRODUCTID=0x3211
|
||||
CONFIG_LPC31XX_USBDEV_DMA=n
|
||||
CONFIG_LPC31_GIO_USBATTACH=6
|
||||
CONFIG_LPC31_GIO_USBDPPULLUP=17
|
||||
CONFIG_LPC31_VENDORID=0xd320
|
||||
CONFIG_LPC31_PRODUCTID=0x3211
|
||||
CONFIG_LPC31_USBDEV_DMA=n
|
||||
|
||||
#
|
||||
# USB Serial Device Configuration
|
||||
|
@ -388,13 +389,8 @@ CONFIG_EXAMPLES_USBSERIAL_TRACEINTERRUPTS=n
|
|||
#
|
||||
# Stack and heap information
|
||||
#
|
||||
CONFIG_BOOT_RUNFROMFLASH=n
|
||||
CONFIG_BOOT_COPYTORAM=n
|
||||
CONFIG_CUSTOM_STACK=n
|
||||
#CONFIG_STACK_POINTER
|
||||
CONFIG_BOOT_RUNFROMISRAM=y
|
||||
CONFIG_IDLETHREAD_STACKSIZE=1024
|
||||
CONFIG_USERMAIN_STACKSIZE=2048
|
||||
CONFIG_PTHREAD_STACK_MIN=256
|
||||
CONFIG_PTHREAD_STACK_DEFAULT=2048
|
||||
CONFIG_HEAP_BASE=
|
||||
CONFIG_HEAP_SIZE=
|
||||
|
|
|
@ -2,12 +2,15 @@
|
|||
# For a description of the syntax of this configuration file,
|
||||
# see misc/tools/kconfig-language.txt.
|
||||
#
|
||||
|
||||
menuconfig USBDEV_COMPOSITE
|
||||
bool "USB composite device support"
|
||||
default n
|
||||
---help---
|
||||
Enables USB composite device support
|
||||
|
||||
if USBDEV_COMPOSITE
|
||||
|
||||
#config COMPOSITE_IAD
|
||||
# bool ""
|
||||
# default n
|
||||
|
@ -89,7 +92,9 @@ config USBDEV_BUSPOWERED
|
|||
---help---
|
||||
Will cause USB features to indicate
|
||||
that the device is self-powered
|
||||
|
||||
endchoice
|
||||
|
||||
config USBDEV_MAXPOWER
|
||||
int "Maximum power consumption in mA"
|
||||
default 100
|
||||
|
@ -115,6 +120,7 @@ menuconfig PL2303
|
|||
default n
|
||||
---help---
|
||||
This logic emulates the Prolific PL2303 serial/USB converter
|
||||
|
||||
if PL2303
|
||||
config PL2303_EPINTIN
|
||||
int "Logical endpoint numbers"
|
||||
|
@ -178,6 +184,7 @@ menuconfig CDCACM
|
|||
default n
|
||||
---help---
|
||||
Enables USB Modem (CDC ACM) support
|
||||
|
||||
if CDCACM
|
||||
config CDCACM_COMPOSITE
|
||||
bool "CDCACM composite support"
|
||||
|
|
|
@ -381,20 +381,6 @@ config PREALLOC_TIMERS
|
|||
|
||||
comment "Stack and heap information"
|
||||
|
||||
config BOOT_RUNFROMFLASH
|
||||
bool "boot run from flash"
|
||||
default n
|
||||
---help---
|
||||
Some configurations support XIP operation from FLASH but must copy
|
||||
initialized .data sections to RAM
|
||||
|
||||
config BOOT_COPYTORAM
|
||||
bool "boot copy to ram"
|
||||
default n
|
||||
---help---
|
||||
Some configurations boot in FLASH
|
||||
but copy themselves entirely into RAM for better performance.
|
||||
|
||||
config CUSTOM_STACK
|
||||
bool "Enable custom stack"
|
||||
default n
|
||||
|
|
Loading…
Reference in New Issue