Add LPC32xx CAN header file; Add configuration for the NXP LP4330-Xplorer board

git-svn-id: https://nuttx.svn.sourceforge.net/svnroot/nuttx/trunk@4901 7fd9a85b-ad96-42d3-883c-3090e2eb8679
This commit is contained in:
patacongo 2012-07-03 22:42:27 +00:00
parent b41484839c
commit 05b3e348f4
19 changed files with 3284 additions and 4 deletions

View File

@ -2946,3 +2946,10 @@
board.
* configs/ekk-lm3s3b96: Add a configuration to support the TI/Stellaris
EKK-LM3S3B96 development board. Contributed by Jose Pablo Rojas V.
* arch/arm/src/lpc43xx/chip: Created header files for *all* (really)
lpc43xx registers and all bit-fields.
* configs/lpc4330-xplorer: Added a configuration for the NXP LPC43XX
Xplorer board. This is just to facilitate testing of the LPC43xx
port but will, with any luck, become proper board support for that
board.

View File

@ -58,6 +58,11 @@ config ARCH_CHIP_LPC31XX
---help---
NPX LPC31XX architectures (ARM926EJS).
config ARCH_CHIP_LPC43XX
bool "NXP LPC43XX"
---help---
NPX LPC43XX architectures (ARM Cortex-M4).
config ARCH_CHIP_SAM3U
bool "Atmel AT91SAM3U"
---help---
@ -89,7 +94,7 @@ config ARCH_ARM920T
config ARCH_CORTEXM
bool
default y if ARCH_CHIP_KINETIS || ARCH_CHIP_LM3S || ARCH_CHIP_LPC17XX || ARCH_CHIP_SAM3U || ARCH_CHIP_STM32
default y if ARCH_CHIP_KINETIS || ARCH_CHIP_LM3S || ARCH_CHIP_LPC17XX || ARCH_CHIP_LPC43XX || ARCH_CHIP_SAM3U || ARCH_CHIP_STM32
config ARCH_FAMILY
string
@ -164,6 +169,7 @@ source arch/arm/src/lpc17xx/Kconfig
source arch/arm/src/lpc214x/Kconfig
source arch/arm/src/lpc2378/Kconfig
source arch/arm/src/lpc31xx/Kconfig
source arch/arm/src/lpc43xx/Kconfig
source arch/arm/src/sam3u/Kconfig
source arch/arm/src/stm32/Kconfig
source arch/arm/src/str71x/Kconfig

View File

@ -0,0 +1,95 @@
#
# For a description of the syntax of this configuration file,
# see misc/tools/kconfig-language.txt.
#
choice
prompt "LPC43XX Chip Selection"
default ARCH_CHIP_LPC4330FET100
depends on ARCH_CHIP_LPC43XX
config ARCH_CHIP_LPC4310FBD144
bool "LPC4310FBD144
config ARCH_CHIP_LPC4310FET100
bool "LPC4310FET100
config ARCH_CHIP_LPC4320FBD144
bool "LPC4320FBD144
config ARCH_CHIP_LPC4320FET100
bool "LPC4320FET100
config ARCH_CHIP_LPC4330FBD144
bool "LPC4330FBD144
config ARCH_CHIP_LPC4330FET100
bool "LPC4330FET100
config ARCH_CHIP_LPC4330FET180
bool "LPC4330FET180
config ARCH_CHIP_LPC4330FET256
bool "LPC4330FET256
config ARCH_CHIP_LPC4350FBD208
bool "LPC4350FBD208
config ARCH_CHIP_LPC4350FET180
bool "LPC4350FET180
config ARCH_CHIP_LPC4350FET256
bool "LPC4350FET256
config ARCH_CHIP_LPC4353FBD208
bool "LPC4353FBD208
config ARCH_CHIP_LPC4353FET180
bool "LPC4353FET180
config ARCH_CHIP_LPC4353FET256
bool "LPC4353FET256
config ARCH_CHIP_LPC4357FET180
bool "LPC4357FET180
config ARCH_CHIP_LPC4357FBD208
bool "LPC4357FBD208
config ARCH_CHIP_LPC4357FET256
bool "LPC4357FET256
endchoice
config ARCH_FAMILY_LPC4310
bool
default y if ARCH_CHIP_LPC4310FBD144 || ARCH_CHIP_LPC4310FET100
config ARCH_FAMILY_LPC4320
bool
default y if ARCH_CHIP_LPC4320FBD144 || ARCH_CHIP_LPC4320FET100
config ARCH_FAMILY_LPC4330
bool
default y if ARCH_CHIP_LPC4330FBD144 || ARCH_CHIP_LPC4330FET100 || ARCH_CHIP_LPC4330FET180 || ARCH_CHIP_LPC4330FET256
config ARCH_FAMILY_LPC4350
bool
default y if ARCH_CHIP_LPC4350FBD208 || ARCH_CHIP_LPC4350FET180 || ARCH_CHIP_LPC4350FET256
config ARCH_FAMILY_LPC4353
bool
default y if ARCH_CHIP_LPC4353FBD208 || ARCH_CHIP_LPC4353FET180 || ARCH_CHIP_LPC4353FET256
config ARCH_FAMILY_LPC4357
bool
default y if ARCH_CHIP_LPC4357FET180 || ARCH_CHIP_LPC4357FBD208 || ARCH_CHIP_LPC4357FET256
config ARCH_CORTEXM3
bool
default n if !ARCH_CHIP_LPC43XX
config ARCH_CORTEXM4
bool
default y if ARCH_CHIP_LPC43XX

View File

@ -0,0 +1,458 @@
/************************************************************************************
* arch/arm/src/lpc43xx/chip/lpc43_can.h
*
* Copyright (C) 2012 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name NuttX nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
************************************************************************************/
#ifndef __ARCH_ARM_SRC_LPC43XX_CHIP_LPC43_CAN_H
#define __ARCH_ARM_SRC_LPC43XX_CHIP_LPC43_CAN_H
/************************************************************************************
* Included Files
************************************************************************************/
#include <nuttx/config.h>
/************************************************************************************
* Pre-processor Definitions
************************************************************************************/
/* Register Offsets *****************************************************************/
#define LPC43_CAN_CNTL_OFFSET 0x0000 /* CAN control register */
#define LPC43_CAN_STAT_OFFSET 0x0004 /* Status register */
#define LPC43_CAN_EC_OFFSET 0x0008 /* Error counter register */
#define LPC43_CAN_BT_OFFSET 0x000c /* Bit timing register */
#define LPC43_CAN_INT_OFFSET 0x0010 /* Interrupt register */
#define LPC43_CAN_TEST_OFFSET 0x0014 /* Test register */
#define LPC43_CAN_BRPE_OFFSET 0x0018 /* Baud rate prescaler extension register */
#define LPC43_CAN_IF1_CMDREQ_OFFSET 0x0020 /* Message interface 1 command request */
#define LPC43_CAN_IF1_CMDMSKW_OFFSET 0x0024 /* Message interface 1 command mask (write) */
#define LPC43_CAN_IF1_CMDMSKR_OFFSET 0x0024 /* Message interface 1 command mask (read) */
#define LPC43_CAN_IF1_MSK1_OFFSET 0x0028 /* Message interface 1 mask 1 */
#define LPC43_CAN_IF1_MSK2_OFFSET 0x002c /* Message interface 1 mask 2 */
#define LPC43_CAN_IF1_ARB1_OFFSET 0x0030 /* Message interface 1 arbitration */
#define LPC43_CAN_IF1_ARB2_OFFSET 0x0034 /* Message interface 1 arbitration */
#define LPC43_CAN_IF1_MCTRL_OFFSET 0x0038 /* Message interface 1 message control */
#define LPC43_CAN_IF1_DA1_OFFSET 0x003c /* Message interface 1 data A1 */
#define LPC43_CAN_IF1_DA2_OFFSET 0x0040 /* Message interface 1 data A2 */
#define LPC43_CAN_IF1_DB1_OFFSET 0x0044 /* Message interface 1 data B1 */
#define LPC43_CAN_IF1_DB2_OFFSET 0x0048 /* Message interface 1 data B2 */
#define LPC43_CAN_IF2_CMDREQ_OFFSET 0x0080 /* Message interface 2 command request */
#define LPC43_CAN_IF2_CMDMSKW_OFFSET 0x0084 /* Message interface 2 command mask (write) */
#define LPC43_CAN_IF2_CMDMSKR_OFFSET 0x0084 /* Message interface 2 command mask (read) */
#define LPC43_CAN_IF2_MSK1_OFFSET 0x0088 /* Message interface 2 mask 1 */
#define LPC43_CAN_IF2_MSK2_OFFSET 0x008c /* Message interface 2 mask 2 */
#define LPC43_CAN_IF2_ARB1_OFFSET 0x0090 /* Message interface 2 arbitration 1 */
#define LPC43_CAN_IF2_ARB2_OFFSET 0x0094 /* Message interface 2 arbitration 2 */
#define LPC43_CAN_IF2_MCTRL_OFFSET 0x0098 /* Message interface 2 message control */
#define LPC43_CAN_IF2_DA1_OFFSET 0x009c /* Message interface 2 data A1 */
#define LPC43_CAN_IF2_DA2_OFFSET 0x00a0 /* Message interface 2 data A2 */
#define LPC43_CAN_IF2_DB1_OFFSET 0x00a4 /* Message interface 2 data B1 */
#define LPC43_CAN_IF2_DB2_OFFSET 0x00a8 /* Message interface 2 data B2 */
#define LPC43_CAN_TXREQ1_OFFSET 0x0100 /* Transmission request 1 */
#define LPC43_CAN_TXREQ2_OFFSET 0x0104 /* Transmission request 2 */
#define LPC43_CAN_ND1_OFFSET 0x0120 /* New data 1 */
#define LPC43_CAN_ND2_OFFSET 0x0124 /* New data 2 */
#define LPC43_CAN_IR1_OFFSET 0x0140 /* Interrupt pending 1 */
#define LPC43_CAN_IR2_OFFSET 0x0144 /* Interrupt pending 2 */
#define LPC43_CAN_MSGV1_OFFSET 0x0160 /* Message valid 1 */
#define LPC43_CAN_MSGV2_OFFSET 0x0164 /* Message valid 2 */
#define LPC43_CAN_CLKDIV_OFFSET 0x0180 /* CAN clock divider register */
/* Register Addresses ***************************************************************/
#define LPC43_CAN1_CNTL (LPC43_CAN1_BASE+LPC43_CAN_CNTL_OFFSET)
#define LPC43_CAN1_STAT (LPC43_CAN1_BASE+LPC43_CAN_STAT_OFFSET)
#define LPC43_CAN1_EC (LPC43_CAN1_BASE+LPC43_CAN_EC_OFFSET)
#define LPC43_CAN1_BT (LPC43_CAN1_BASE+LPC43_CAN_BT_OFFSET)
#define LPC43_CAN1_INT (LPC43_CAN1_BASE+LPC43_CAN_INT_OFFSET)
#define LPC43_CAN1_TEST (LPC43_CAN1_BASE+LPC43_CAN_TEST_OFFSET)
#define LPC43_CAN1_BRPE (LPC43_CAN1_BASE+LPC43_CAN_BRPE_OFFSET)
#define LPC43_CAN1_IF1_CMDREQ (LPC43_CAN1_BASE+LPC43_CAN_IF1_CMDREQ_OFFSET)
#define LPC43_CAN1_IF1_CMDMSKW (LPC43_CAN1_BASE+LPC43_CAN_IF1_CMDMSKW_OFFSET)
#define LPC43_CAN1_IF1_CMDMSKR (LPC43_CAN1_BASE+LPC43_CAN_IF1_CMDMSKR_OFFSET)
#define LPC43_CAN1_IF1_MSK1 (LPC43_CAN1_BASE+LPC43_CAN_IF1_MSK1_OFFSET)
#define LPC43_CAN1_IF1_MSK2 (LPC43_CAN1_BASE+LPC43_CAN_IF1_MSK2_OFFSET)
#define LPC43_CAN1_IF1_ARB1 (LPC43_CAN1_BASE+LPC43_CAN_IF1_ARB1_OFFSET)
#define LPC43_CAN1_IF1_ARB2 (LPC43_CAN1_BASE+LPC43_CAN_IF1_ARB2_OFFSET)
#define LPC43_CAN1_IF1_MCTRL (LPC43_CAN1_BASE+LPC43_CAN_IF1_MCTRL_OFFSET)
#define LPC43_CAN1_IF1_DA1 (LPC43_CAN1_BASE+LPC43_CAN_IF1_DA1_OFFSET)
#define LPC43_CAN1_IF1_DA2 (LPC43_CAN1_BASE+LPC43_CAN_IF1_DA2_OFFSET)
#define LPC43_CAN1_IF1_DB1 (LPC43_CAN1_BASE+LPC43_CAN_IF1_DB1_OFFSET)
#define LPC43_CAN1_IF1_DB2 (LPC43_CAN1_BASE+LPC43_CAN_IF1_DB2_OFFSET)
#define LPC43_CAN1_IF2_CMDREQ (LPC43_CAN1_BASE+LPC43_CAN_IF2_CMDREQ_OFFSET)
#define LPC43_CAN1_IF2_CMDMSKW (LPC43_CAN1_BASE+LPC43_CAN_IF2_CMDMSKW_OFFSET)
#define LPC43_CAN1_IF2_CMDMSKR (LPC43_CAN1_BASE+LPC43_CAN_IF2_CMDMSKR_OFFSET)
#define LPC43_CAN1_IF2_MSK1 (LPC43_CAN1_BASE+LPC43_CAN_IF2_MSK1_OFFSET)
#define LPC43_CAN1_IF2_MSK2 (LPC43_CAN1_BASE+LPC43_CAN_IF2_MSK2_OFFSET)
#define LPC43_CAN1_IF2_ARB1 (LPC43_CAN1_BASE+LPC43_CAN_IF2_ARB1_OFFSET)
#define LPC43_CAN1_IF2_ARB2 (LPC43_CAN1_BASE+LPC43_CAN_IF2_ARB2_OFFSET)
#define LPC43_CAN1_IF2_MCTRL (LPC43_CAN1_BASE+LPC43_CAN_IF2_MCTRL_OFFSET)
#define LPC43_CAN1_IF2_DA1 (LPC43_CAN1_BASE+LPC43_CAN_IF2_DA1_OFFSET)
#define LPC43_CAN1_IF2_DA2 (LPC43_CAN1_BASE+LPC43_CAN_IF2_DA2_OFFSET)
#define LPC43_CAN1_IF2_DB1 (LPC43_CAN1_BASE+LPC43_CAN_IF2_DB1_OFFSET)
#define LPC43_CAN1_IF2_DB2 (LPC43_CAN1_BASE+LPC43_CAN_IF2_DB2_OFFSET)
#define LPC43_CAN1_TXREQ1 (LPC43_CAN1_BASE+LPC43_CAN_TXREQ1_OFFSET)
#define LPC43_CAN1_TXREQ2 (LPC43_CAN1_BASE+LPC43_CAN_TXREQ2_OFFSET)
#define LPC43_CAN1_ND1 (LPC43_CAN1_BASE+LPC43_CAN_ND1_OFFSET)
#define LPC43_CAN1_ND2 (LPC43_CAN1_BASE+LPC43_CAN_ND2_OFFSET)
#define LPC43_CAN1_IR1 (LPC43_CAN1_BASE+LPC43_CAN_IR1_OFFSET)
#define LPC43_CAN1_IR2 (LPC43_CAN1_BASE+LPC43_CAN_IR2_OFFSET)
#define LPC43_CAN1_MSGV1 (LPC43_CAN1_BASE+LPC43_CAN_MSGV1_OFFSET)
#define LPC43_CAN1_MSGV2 (LPC43_CAN1_BASE+LPC43_CAN_MSGV2_OFFSET)
#define LPC43_CAN1_CLKDIV (LPC43_CAN1_BASE+LPC43_CAN_CLKDIV_OFFSET)
#define LPC43_CAN2_CNTL (LPC43_CAN2_BASE+LPC43_CAN_CNTL_OFFSET)
#define LPC43_CAN2_STAT (LPC43_CAN2_BASE+LPC43_CAN_STAT_OFFSET)
#define LPC43_CAN2_EC (LPC43_CAN2_BASE+LPC43_CAN_EC_OFFSET)
#define LPC43_CAN2_BT (LPC43_CAN2_BASE+LPC43_CAN_BT_OFFSET)
#define LPC43_CAN2_INT (LPC43_CAN2_BASE+LPC43_CAN_INT_OFFSET)
#define LPC43_CAN2_TEST (LPC43_CAN2_BASE+LPC43_CAN_TEST_OFFSET)
#define LPC43_CAN2_BRPE (LPC43_CAN2_BASE+LPC43_CAN_BRPE_OFFSET)
#define LPC43_CAN2_IF1_CMDREQ (LPC43_CAN2_BASE+LPC43_CAN_IF1_CMDREQ_OFFSET)
#define LPC43_CAN2_IF1_CMDMSKW (LPC43_CAN2_BASE+LPC43_CAN_IF1_CMDMSKW_OFFSET)
#define LPC43_CAN2_IF1_CMDMSKR (LPC43_CAN2_BASE+LPC43_CAN_IF1_CMDMSKR_OFFSET)
#define LPC43_CAN2_IF1_MSK1 (LPC43_CAN2_BASE+LPC43_CAN_IF1_MSK1_OFFSET)
#define LPC43_CAN2_IF1_MSK2 (LPC43_CAN2_BASE+LPC43_CAN_IF1_MSK2_OFFSET)
#define LPC43_CAN2_IF1_ARB1 (LPC43_CAN2_BASE+LPC43_CAN_IF1_ARB1_OFFSET)
#define LPC43_CAN2_IF1_ARB2 (LPC43_CAN2_BASE+LPC43_CAN_IF1_ARB2_OFFSET)
#define LPC43_CAN2_IF1_MCTRL (LPC43_CAN2_BASE+LPC43_CAN_IF1_MCTRL_OFFSET)
#define LPC43_CAN2_IF1_DA1 (LPC43_CAN2_BASE+LPC43_CAN_IF1_DA1_OFFSET)
#define LPC43_CAN2_IF1_DA2 (LPC43_CAN2_BASE+LPC43_CAN_IF1_DA2_OFFSET)
#define LPC43_CAN2_IF1_DB1 (LPC43_CAN2_BASE+LPC43_CAN_IF1_DB1_OFFSET)
#define LPC43_CAN2_IF1_DB2 (LPC43_CAN2_BASE+LPC43_CAN_IF1_DB2_OFFSET)
#define LPC43_CAN2_IF2_CMDREQ (LPC43_CAN2_BASE+LPC43_CAN_IF2_CMDREQ_OFFSET)
#define LPC43_CAN2_IF2_CMDMSKW (LPC43_CAN2_BASE+LPC43_CAN_IF2_CMDMSKW_OFFSET)
#define LPC43_CAN2_IF2_CMDMSKR (LPC43_CAN2_BASE+LPC43_CAN_IF2_CMDMSKR_OFFSET)
#define LPC43_CAN2_IF2_MSK1 (LPC43_CAN2_BASE+LPC43_CAN_IF2_MSK1_OFFSET)
#define LPC43_CAN2_IF2_MSK2 (LPC43_CAN2_BASE+LPC43_CAN_IF2_MSK2_OFFSET)
#define LPC43_CAN2_IF2_ARB1 (LPC43_CAN2_BASE+LPC43_CAN_IF2_ARB1_OFFSET)
#define LPC43_CAN2_IF2_ARB2 (LPC43_CAN2_BASE+LPC43_CAN_IF2_ARB2_OFFSET)
#define LPC43_CAN2_IF2_MCTRL (LPC43_CAN2_BASE+LPC43_CAN_IF2_MCTRL_OFFSET)
#define LPC43_CAN2_IF2_DA1 (LPC43_CAN2_BASE+LPC43_CAN_IF2_DA1_OFFSET)
#define LPC43_CAN2_IF2_DA2 (LPC43_CAN2_BASE+LPC43_CAN_IF2_DA2_OFFSET)
#define LPC43_CAN2_IF2_DB1 (LPC43_CAN2_BASE+LPC43_CAN_IF2_DB1_OFFSET)
#define LPC43_CAN2_IF2_DB2 (LPC43_CAN2_BASE+LPC43_CAN_IF2_DB2_OFFSET)
#define LPC43_CAN2_TXREQ1 (LPC43_CAN2_BASE+LPC43_CAN_TXREQ1_OFFSET)
#define LPC43_CAN2_TXREQ2 (LPC43_CAN2_BASE+LPC43_CAN_TXREQ2_OFFSET)
#define LPC43_CAN2_ND1 (LPC43_CAN2_BASE+LPC43_CAN_ND1_OFFSET)
#define LPC43_CAN2_ND2 (LPC43_CAN2_BASE+LPC43_CAN_ND2_OFFSET)
#define LPC43_CAN2_IR1 (LPC43_CAN2_BASE+LPC43_CAN_IR1_OFFSET)
#define LPC43_CAN2_IR2 (LPC43_CAN2_BASE+LPC43_CAN_IR2_OFFSET)
#define LPC43_CAN2_MSGV1 (LPC43_CAN2_BASE+LPC43_CAN_MSGV1_OFFSET)
#define LPC43_CAN2_MSGV2 (LPC43_CAN2_BASE+LPC43_CAN_MSGV2_OFFSET)
#define LPC43_CAN2_CLKDIV (LPC43_CAN2_BASE+LPC43_CAN_CLKDIV_OFFSET)
/* Register Bit Definitions *********************************************************/
/* CAN control register */
#define CAN_CNTL_INIT (1 << 0) /* Bit 0: Initialization */
#define CAN_CNTL_IE (1 << 1) /* Bit 1: Module interrupt enable */
#define CAN_CNTL_SIE (1 << 2) /* Bit 2: Status change interrupt enable */
#define CAN_CNTL_EIE (1 << 3) /* Bit 3: Error interrupt enable */
/* Bit 4: Reserved */
#define CAN_CNTL_DAR (1 << 5) /* Bit 5: Disable automatic retransmission */
#define CAN_CNTL_CCE (1 << 6) /* Bit 6: Configuration change enable */
#define CAN_CNTL_TEST (1 << 7) /* Bit 7: Test mode enable */
/* Bits 8-31: Reserved */
/* Status register */
#define CAN_STAT_LEC_SHIFT (0) /* Bits 0-2: Last error code */
#define CAN_STAT_LEC_MASK (7 << CAN_STAT_LEC_SHIFT)
#define CAN_STAT_LEC_NOE (0 << CAN_STAT_LEC_SHIFT) /* No error */
#define CAN_STAT_LEC_STUFFE (1 << CAN_STAT_LEC_SHIFT) /* Stuff error */
#define CAN_STAT_LEC_FORME (2 << CAN_STAT_LEC_SHIFT) /* Form error */
#define CAN_STAT_LEC_ACKE (3 << CAN_STAT_LEC_SHIFT) /* AckError */
#define CAN_STAT_LEC_BI1E (4 << CAN_STAT_LEC_SHIFT) /* Bit1Error */
#define CAN_STAT_LEC_BIT0E (5 << CAN_STAT_LEC_SHIFT) /* Bit0Error */
#define CAN_STAT_LEC_CRCE (6 << CAN_STAT_LEC_SHIFT) /* CRCError */
#define CAN_STAT_TXOK (1 << 3) /* Bit 3: Transmitted a message successfully */
#define CAN_STAT_RXOK (1 << 4) /* Bit 4: Received a message successfully */
#define CAN_STAT_EPASS (1 << 5) /* Bit 5: Error passive */
#define CAN_STAT_EWARN (1 << 6) /* Bit 6: Warning status */
#define CAN_STAT_BOFF (1 << 7) /* Bit 7: Busoff status */
/* Bits 8-31: Reserved */
/* Error counter register */
#define CAN_EC_TEC_SHIFT (0) /* Bits 0-7: Transmit error counter */
#define CAN_EC_TEC_MASK (0xff << CAN_EC_TEC_SHIFT)
#define CAN_EC_REC_SHIFT (8) /* Bits 8-14: Receive error counter */
#define CAN_EC_REC_MASK (0x7f << CAN_EC_REC_SHIFT)
#define CAN_EC_RP (1 << 15) /* Bit 15: Receive error passive */
/* Bits 16-31: Reserved */
/* Bit timing register */
#define CAN_BT_BRP_SHIFT (0) /* Bits 0-5: Baud rate prescaler */
#define CAN_BT_BRP_MASK (0x3f << CAN_BT_BRP_SHIFT)
#define CAN_BT_SJW_SHIFT (6) /* Bits 6-7: (Re)synchronization jump width */
#define CAN_BT_SJW_MASK (3 << CAN_BT_SJW_SHIFT)
#define CAN_BT_TSEG1_SHIFT (8) /* Bits 8-11: Time segment after the sample point */
#define CAN_BT_TSEG1_MASK (15 << CAN_BT_TSEG1_SHIFT)
#define CAN_BT_TSEG2_SHIFT (12) /* Bits 12-14: Time segment before the sample point */
#define CAN_BT_TSEG2_MASK (7 << CAN_BT_TSEG2_SHIFT)
/* Bits 15-31: Reserved */
/* Interrupt register */
#define CAN_INT_SHIFT (0) /* Bits 0-15: Interrupt ID */
#define CAN_INT_MASK (0xffff << CAN_INT_SHIFT)
# define CAN_INT_NONE (0 << CAN_INT_SHIFT) /* No interrupt pending */
# define CAN_INT_MSG1 (1 << CAN_INT_SHIFT) /* Message 1 */
# define CAN_INT_MSG2 (2 << CAN_INT_SHIFT) /* Message 2 */
# define CAN_INT_MSG3 (3 << CAN_INT_SHIFT) /* Message 3 */
# define CAN_INT_MSG4 (4 << CAN_INT_SHIFT) /* Message 4 */
# define CAN_INT_MSG5 (5 << CAN_INT_SHIFT) /* Message 5 */
# define CAN_INT_MSG6 (6 << CAN_INT_SHIFT) /* Message 6 */
# define CAN_INT_MSG7 (7 << CAN_INT_SHIFT) /* Message 7 */
# define CAN_INT_MSG8 (8 << CAN_INT_SHIFT) /* Message 8 */
# define CAN_INT_MSG9 (9 << CAN_INT_SHIFT) /* Message 9 */
# define CAN_INT_MSG10 (10 << CAN_INT_SHIFT) /* Message 10 */
# define CAN_INT_MSG11 (11 << CAN_INT_SHIFT) /* Message 11 */
# define CAN_INT_MSG12 (12 << CAN_INT_SHIFT) /* Message 12 */
# define CAN_INT_MSG13 (13 << CAN_INT_SHIFT) /* Message 13 */
# define CAN_INT_MSG14 (14 << CAN_INT_SHIFT) /* Message 14 */
# define CAN_INT_MSG15 (15 << CAN_INT_SHIFT) /* Message 15 */
# define CAN_INT_MSG16 (16 << CAN_INT_SHIFT) /* Message 16 */
# define CAN_INT_MSG17 (17 << CAN_INT_SHIFT) /* Message 17 */
# define CAN_INT_MSG18 (18 << CAN_INT_SHIFT) /* Message 18 */
# define CAN_INT_MSG19 (19 << CAN_INT_SHIFT) /* Message 19 */
# define CAN_INT_MSG20 (20 << CAN_INT_SHIFT) /* Message 20 */
# define CAN_INT_MSG21 (21 << CAN_INT_SHIFT) /* Message 21 */
# define CAN_INT_MSG22 (22 << CAN_INT_SHIFT) /* Message 22 */
# define CAN_INT_MSG23 (23 << CAN_INT_SHIFT) /* Message 23 */
# define CAN_INT_MSG24 (24 << CAN_INT_SHIFT) /* Message 24 */
# define CAN_INT_MSG25 (25 << CAN_INT_SHIFT) /* Message 25 */
# define CAN_INT_MSG26 (26 << CAN_INT_SHIFT) /* Message 26 */
# define CAN_INT_MSG27 (27 << CAN_INT_SHIFT) /* Message 27 */
# define CAN_INT_MSG28 (28 << CAN_INT_SHIFT) /* Message 28 */
# define CAN_INT_MSG29 (29 << CAN_INT_SHIFT) /* Message 29 */
# define CAN_INT_MSG30 (30 << CAN_INT_SHIFT) /* Message 30 */
# define CAN_INT_MSG31 (31 << CAN_INT_SHIFT) /* Message 31 */
# define CAN_INT_MSG32 (32 << CAN_INT_SHIFT) /* Message 32 */
# define CAN_INT_MSG32 (0x8000 << CAN_INT_SHIFT) /* Status interrupt */
/* Bits 16-31: Reserved */
/* Test register */
/* Bits 0-1: Reserved */
#define CAN_TEST_BASIC (1 << 2) /* Bit 2: Basic mode */
#define CAN_TEST_SILENT (1 << 3) /* Bit 3: Silent mode */
#define CAN_TEST_LBACK (1 << 4) /* Bit 4: Loop back mode */
#define CAN_TEST_TX_SHIFT (5) /* Bits 5-6: Control of TD pins */
#define CAN_TEST_TX_MASK (3 << CAN_TEST_TX_SHIFT)
# define CAN_TEST_TX_CAN (0 << CAN_TEST_TX_SHIFT) /* Level controlled CAN controller */
# define CAN_TEST_TX_MONITOR (1 << CAN_TEST_TX_SHIFT) /* Sample point monitored TD pin */
# define CAN_TEST_TX_DOMINANT (2 << CAN_TEST_TX_SHIFT) /* TD pin LOW/dominant */
# define CAN_TEST_TX_RECESSIVE (3 << CAN_TEST_TX_SHIFT) /* TD pin HIGH/recessive */
#define CAN_TEST_RX (1 << 7) /* Bit 7: Monitors actual value of RD Pin */
/* Bits 8-31: Reserved */
/* Baud rate prescaler extension register */
#define CAN_BRPE_SHIFT (0) /* Bits 0-3: Baud rate prescaler extension */
#define CAN_BRPE_MASK (15 << CAN_BRPE_SHIFT)
/* Bits 4-31: Reserved */
/* Message interface 1/2 command request */
#define CAN_CMDREQ_MSGNO_SHIFT (0) /* Bits 0-5: Message number */
#define CAN_CMDREQ_MSGNO_MASK (0x3f << CAN_CMDREQ_MSGNO_SHIFT)
/* Bits 6-14: Reserved */
#define CAN_CMDREQ_BUSY (1 << 15) /* Bit 15: BUSY flag */
/* Bits 16-31: Reserved */
/* Message interface 1/2 command mask (write) */
#define CAN_CMDMSKW_DATAB (1 << 0) /* Bit 0: Access data bytes 4-7 */
#define CAN_CMDMSKW_DATAA (1 << 1) /* Bit 1: Access data bytes 0-3 */
#define CAN_CMDMSKW_TXRQST (1 << 2) /* Bit 2: Access transmission request bit */
#define CAN_CMDMSKW_CLRINTPND (1 << 3) /* Bit 3: Ignored in the write direction */
#define CAN_CMDMSKW_CTRL (1 << 4) /* Bit 4: Access control bits */
#define CAN_CMDMSKW_ARB (1 << 5) /* Bit 5: Access arbitration bits */
#define CAN_CMDMSKW_MASK (1 << 6) /* Bit 6: Access mask bits */
#define CAN_CMDMSKW_WRRD (1 << 7) /* Bit 7: Write transfer (1) */
/* Bits 8-31: Reserved */
/* Message interface 1/2 command mask (read) */
#define CAN_CMDMSKR_DATAB (1 << 0) /* Bit 0: Access data bytes 4-7 */
#define CAN_CMDMSKR_DATAA (1 << 1) /* Bit 1: Access data bytes 0-3 */
#define CAN_CMDMSKR_NEWDAT (1 << 2) /* Bit 2: Access new data bit */
#define CAN_CMDMSKR_CLRINTPND (1 << 3) /* Bit 3: Clear interrupt pending bit */
#define CAN_CMDMSKR_CTRL (1 << 4) /* Bit 4: Access control bits */
#define CAN_CMDMSKR_ARB (1 << 5) /* Bit 5: Access arbitration bits */
#define CAN_CMDMSKR_MASK (1 << 6) /* Bit 6: Access mask bits */
#define CAN_CMDMSKR_WRRD (1 << 7) /* Bit 7: Read transfer (0) */
/* Bits 8-31: Reserved */
/* Message interface 1/2 mask 1 */
#define CAN_MSK1 0xffff /* Bits 0-15: Identifier mask 0-15 */
/* Bits 16-31: Reserved */
/* Message interface 1/2 mask 2 */
#define CAN_MSK2 0x1fff /* Bits 0-12: Identifier mask 16-28 */
/* Bit 13: Reserved */
#define CAN_MSK2_MDIR (1 << 14) /* Bit 14: Mask message direction */
#define CAN_MSK2_MXTD (1 << 15) /* Bit 15: Mask extend identifier */
/* Bits 16-31: Reserved */
/* Message interface 1/2 arbitration */
#define CAN_ARB1 0xffff /* Bits 0-15: Identifier mask 0-15 */
/* Bits 16-31: Reserved */
/* Message interface 1/2 arbitration */
#define CAN_MSK2 0x1fff /* Bits 0-12: Identifier mask 16-28 */
#define CAN_MSK2_DIR (1 << 13) /* Bit 13: Message direction */
#define CAN_MSK2_XTD (1 << 14) /* Bit 14: Extend identifier */
#define CAN_MSK2_MSGVAL (1 << 15) /* Bit 15: Message valid */
/* Bits 16-31: Reserved */
/* Message interface 1 message control */
#define CAN_MCTRL_DLC_SHIFT (0) /* Bits 0-3: Data length code */
#define CAN_MCTRL_DLC_MASK (15 << CAN_MCTRL_DLC_SHIFT)
/* Bits 4-6: Reserved */
#define CAN_MCTRL_EOB (1 << 7) /* Bit 7: End of buffer */
#define CAN_MCTRL_TXRQST (1 << 8) /* Bit 8: Transmit request */
#define CAN_MCTRL_RMTEN (1 << 9) /* Bit 9: Remote enable */
#define CAN_MCTRL_RXIE (1 << 10) /* Bit 10: Receive interrupt enable */
#define CAN_MCTRL_TXIE (1 << 11) /* Bit 11: Transmit interrupt enable */
#define CAN_MCTRL_UMASK (1 << 12) /* Bit 12: Use acceptance mask */
#define CAN_MCTRL_INTPND (1 << 13) /* Bit 13: Interrupt pending */
#define CAN_MCTRL_MSGLST (1 << 14) /* Bit 14: Message lost */
#define CAN_MCTRL_NEWDAT (1 << 15) /* Bit 15: New data */
/* Bits 16-31: Reserved */
/* Message interface 1/2 data A1 */
#define CAN_DA1_DATA0_SHIFT (0) /* Bits 0-7: Data byte 0 */
#define CAN_DA1_DATA0_MASK (0xff << CAN_DA1_DATA0_SHIFT)
#define CAN_DA1_DATA1_SHIFT (8) /* Bits 8-15: Data byte 1 */
#define CAN_DA1_DATA1_MASK (0xff << CAN_DA1_DATA1_SHIFT)
/* Bits 16-31: Reserved */
/* Message interface 1/2 data A2 */
#define CAN_DA2_DATA2_SHIFT (0) /* Bits 0-7: Data byte 2 */
#define CAN_DA2_DATA2_MASK (0xff << CAN_DA2_DATA2_SHIFT)
#define CAN_DA2_DATA3_SHIFT (8) /* Bits 8-15: Data byte 3 */
#define CAN_DA2_DATA3_MASK (0xff << CAN_DA2_DATA3_SHIFT)
/* Bits 16-31: Reserved */
/* Message interface 1/2 data B1 */
#define CAN_DB1_DATA4_SHIFT (0) /* Bits 0-7: Data byte 4 */
#define CAN_DB1_DATA4_MASK (0xff << CAN_DB1_DATA4_SHIFT)
#define CAN_DB1_DATA5_SHIFT (8) /* Bits 8-15: Data byte 5 */
#define CAN_DB1_DATA5_MASK (0xff << CAN_DB1_DATA5_SHIFT)
/* Bits 16-31: Reserved */
/* Message interface 1/2 data B2 */
#define CAN_DB2_DATA6_SHIFT (0) /* Bits 0-7: Data byte 6 */
#define CAN_DB2_DATA6_MASK (0xff << CAN_DB2_DATA6_SHIFT)
#define CAN_DB2_DATA7_SHIFT (8) /* Bits 8-15: Data byte 7 */
#define CAN_DB2_DATA7_MASK (0xff << CAN_DB2_DATA6_SHIFT)
/* Bits 16-31: Reserved */
/* Transmission request 1 */
#define CAN_TXREQ1_MASK 0xffff /* Bits 0-15: TX request bit msg 1-16 */
#define CAN_TXREQ1(n) (1 << ((n)-1)
/* Bits 16-31: Reserved */
/* Transmission request 2 */
#define CAN_TXREQ2_MASK 0xffff /* Bits 0-15: TX request bit msg 17-32 */
#define CAN_TXREQ2(n) (1 << ((n)-17)
/* Bits 16-31: Reserved */
/* New data 1 */
#define CAN_ND1_MASK 0xffff /* Bits 0-15: New data bits msg 1-16 */
#define CAN_ND1(n) (1 << ((n)-1)
/* Bits 16-31: Reserved */
/* New data 2 */
#define CAN_ND2_MASK 0xffff /* Bits 0-15: New data bits msg 17-32 */
#define CAN_ND2(n) (1 << ((n)-17)
/* Bits 16-31: Reserved */
/* Interrupt pending 1 */
#define CAN_IR1_MASK 0xffff /* Bits 0-15: Interrup pending msg 1-16 */
#define CAN_IR1(n) (1 << ((n)-1)
/* Bits 16-31: Reserved */
/* Interrupt pending 2 */
#define CAN_IR2_MASK 0xffff /* Bits 0-15: Interrup pending msg 17-32 */
#define CAN_IR2(n) (1 << ((n)-17)
/* Bits 16-31: Reserved */
/* Message valid 1 */
#define CAN_MSGV1_MASK 0xffff /* Bits 0-15: Interrup pending msg 1-16 */
#define CAN_MSGV1(n) (1 << ((n)-1)
/* Bits 16-31: Reserved */
/* Message valid 2 */
#define CAN_MSGV2_MASK 0xffff /* Bits 0-15: Interrup pending msg 17-32 */
#define CAN_MSGV2(n) (1 << ((n)-17)
/* Bits 16-31: Reserved */
/* CAN clock divider register */
#define CAN_CLKDIV_SHIFT (0) /* Bits 0-3: Clock divider value */
#define CAN_CLKDIV_MASK (15 << CAN_CLKDIV_SHIFT)
# define CAN_CLKDIV_DIV1 (0 << CAN_CLKDIV_SHIFT) /* CAN_CLK = PCLK / 1 */
# define CAN_CLKDIV_DIV2 (1 << CAN_CLKDIV_SHIFT) /* CAN_CLK = PCLK / 2 */
# define CAN_CLKDIV_DIV3 (2 << CAN_CLKDIV_SHIFT) /* CAN_CLK = PCLK / 3 */
# define CAN_CLKDIV_DIV5 (3 << CAN_CLKDIV_SHIFT) /* CAN_CLK = PCLK / 5 */
# define CAN_CLKDIV_DIV9 (4 << CAN_CLKDIV_SHIFT) /* CAN_CLK = PCLK / 9 */
# define CAN_CLKDIV_DIV 17 (5 << CAN_CLKDIV_SHIFT) /* CAN_CLK = PCLK / 17 */
# define CAN_CLKDIV_DIV33 (6 << CAN_CLKDIV_SHIFT) /* CAN_CLK = PCLK / 33 */
# define CAN_CLKDIV_DIV65 (7 << CAN_CLKDIV_SHIFT) /* CAN_CLK = PCLK / 65 */
# define CAN_CLKDIV_DIV129 (8 << CAN_CLKDIV_SHIFT) /* CAN_CLK = PCLK / 129 */
# define CAN_CLKDIV_DIV257 (9 << CAN_CLKDIV_SHIFT) /* CAN_CLK = PCLK / 257 */
# define CAN_CLKDIV_DIV513 (10 << CAN_CLKDIV_SHIFT) /* CAN_CLK = PCLK / 513 */
# define CAN_CLKDIV_DIV1025 (11 << CAN_CLKDIV_SHIFT) /* CAN_CLK = PCLK / 1025 */
# define CAN_CLKDIV_DIV2049 (12 << CAN_CLKDIV_SHIFT) /* CAN_CLK = PCLK / 2049 */
# define CAN_CLKDIV_DIV4097 (13 << CAN_CLKDIV_SHIFT) /* CAN_CLK = PCLK / 4097 */
# define CAN_CLKDIV_DIV8093 (14 << CAN_CLKDIV_SHIFT) /* CAN_CLK = PCLK / 8093 */
# define CAN_CLKDIV_DIV16385 (15 << CAN_CLKDIV_SHIFT) /* CAN_CLK = PCLK / 16385 */
/* Bits 4-31: Reserved */
/************************************************************************************
* Public Types
************************************************************************************/
/************************************************************************************
* Public Data
************************************************************************************/
/************************************************************************************
* Public Functions
************************************************************************************/
#endif /* __ARCH_ARM_SRC_LPC43XX_CHIP_LPC43_CAN_H */

View File

@ -162,7 +162,13 @@ config ARCH_BOARD_LPCXPRESSO
---help---
Embedded Artists base board with NXP LPCExpresso LPC1768. This board
is based on the NXP LPC1768. The Code Red toolchain is used by default.
STATUS: Under development.
config ARCH_BOARD_LPC4330_XPLORER
bool "NXP LPCExpresso LPC1768"
depends on ARCH_CHIP_LPC4330FET100
---help---
NXP LPCExpresso LPC4330 Xplorer board. This board is based on the
LPC4330FET100. The Code Red toolchain is used by default.
config ARCH_BOARD_M68332EVB
bool "Motoroloa M68332EVB"
@ -252,7 +258,7 @@ config ARCH_BOARD_MIRTOO
depends on ARCH_CHIP_PIC32MX250F128D
---help---
This is the port to the DTX1-4000L "Mirtoo" module. This module uses MicroChip
PIC32MX250F128D. See http://www.dimitech.com/ for further information.
PIC32MX250F128D. See http://www.dimitech.com/ for further information.
config ARCH_BOARD_OLIMEXLPC2378
bool "Olimex-lpc2378 board"
@ -497,7 +503,8 @@ config ARCH_BOARD
default "lm3s6965-ek" if ARCH_BOARD_LM3S6965EK
default "lm3s8962-ek" if ARCH_BOARD_LM3S8962EK
default "lpcxpresso-lpc1768" if ARCH_BOARD_LPCXPRESSO
default " m68322evb" if ARCH_BOARD_M68332EVB
default "lpc4330-xplorer" if ARCH_BOARD_LPC4330_XPLORER
default "m68322evb" if ARCH_BOARD_M68332EVB
default "mbed" if ARCH_BOARD_MBED
default "mcu123-lpc214x" if ARCH_BOARD_MCU123
default "micropendous3" if ARCH_BOARD_MICROPENDOUS
@ -551,6 +558,7 @@ source "configs/lm3s6432-s2e/Kconfig"
source "configs/lm3s6965-ek/Kconfig"
source "configs/lm3s8962-ek/Kconfig"
source "configs/lpcxpresso-lpc1768/Kconfig"
source "configs/lpc4330-xplorer/Kconfig"
source "configs/m68332evb/Kconfig"
source "configs/mbed/Kconfig"
source "configs/mcu123-lpc214x/Kconfig"

View File

@ -0,0 +1,19 @@
#
# For a description of the syntax of this configuration file,
# see misc/tools/kconfig-language.txt.
#
if ARCH_BOARD_LPC4330_XPLORER
config ARCH_LEDS
bool "NuttX LED support"
default n
---help---
"Support control of board LEDs by NuttX to indicate system state"
config ARCH_BUTTONS
bool "Button support"
default n
---help---
"Support interfaces to use buttons provided by the board."
endif

View File

@ -0,0 +1,447 @@
README
^^^^^^
README for NuttX port to the NGX LPC4330-Xplorer board
Contents
^^^^^^^^
LPC4330-Xplorer development board
Development Environment
GNU Toolchain Options
IDEs
NuttX buildroot Toolchain
USB Device Controller Functions
LPC4330-Xplorer Configuration Options
USB Host Configuration
Configurations
LPC4330-Xplorer board
^^^^^^^^^^^^^^^^^^^^^
Memory Map
----------
Block Start Length
Name Address
--------------------- ---------- ------
RAM 0x10000000 128K
RAM2 0x10080000 72K
RAMAHB 0x20000000 32K
RAMAHB2 0x20008000 16K
RAMAHB3 0x2000c000 16K
SPIFI flash 0x1e000000 4096K
GPIO Usage:
-----------
GPIO PIN SIGNAL NAME
-------------------------------- ------- --------------
gpio1[12] - LED D2 J10-20 LED1
gpio1[11] - LED D3 J10-17 LED2
gpio0[7] - User Button SW2 J8-25 BTN1
Console
-------
The LPC4330-Xplorer default console is the USB1 virtual COM port (VCOM).
Development Environment
^^^^^^^^^^^^^^^^^^^^^^^
Either Linux or Cygwin on Windows can be used for the development environment.
The source has been built only using the GNU toolchain (see below). Other
toolchains will likely cause problems. Testing was performed using the Cygwin
environment.
GNU Toolchain Options
^^^^^^^^^^^^^^^^^^^^^
The NuttX make system has been modified to support the following different
toolchain options.
1. The CodeSourcery GNU toolchain,
2. The devkitARM GNU toolchain,
3. The NuttX buildroot Toolchain (see below).
All testing has been conducted using the NuttX buildroot toolchain. However,
the make system is setup to default to use the devkitARM toolchain. To use
the CodeSourcery or devkitARM toolchain, you simply need add one of the
following configuration options to your .config (or defconfig) file:
CONFIG_LPC43_CODESOURCERYW=y : CodeSourcery under Windows
CONFIG_LPC43_CODESOURCERYL=y : CodeSourcery under Linux
CONFIG_LPC43_DEVKITARM=y : devkitARM under Windows
CONFIG_LPC43_BUILDROOT=y : NuttX buildroot under Linux or Cygwin (default)
If you are not using CONFIG_LPC43_BUILDROOT, then you may also have to modify
the PATH in the setenv.h file if your make cannot find the tools.
NOTE: the CodeSourcery (for Windows)and devkitARM are Windows native toolchains.
The CodeSourcey (for Linux) and NuttX buildroot toolchains are Cygwin and/or
Linux native toolchains. There are several limitations to using a Windows based
toolchain in a Cygwin environment. The three biggest are:
1. The Windows toolchain cannot follow Cygwin paths. Path conversions are
performed automatically in the Cygwin makefiles using the 'cygpath' utility
but you might easily find some new path problems. If so, check out 'cygpath -w'
2. Windows toolchains cannot follow Cygwin symbolic links. Many symbolic links
are used in Nuttx (e.g., include/arch). The make system works around these
problems for the Windows tools by copying directories instead of linking them.
But this can also cause some confusion for you: For example, you may edit
a file in a "linked" directory and find that your changes had no effect.
That is because you are building the copy of the file in the "fake" symbolic
directory. If you use a Windows toolchain, you should get in the habit of
making like this:
make clean_context all
An alias in your .bashrc file might make that less painful.
3. Dependencies are not made when using Windows versions of the GCC. This is
because the dependencies are generated using Windows pathes which do not
work with the Cygwin make.
Support has been added for making dependencies with the windows-native toolchains.
That support can be enabled by modifying your Make.defs file as follows:
- MKDEP = $(TOPDIR)/tools/mknulldeps.sh
+ MKDEP = $(TOPDIR)/tools/mkdeps.sh --winpaths "$(TOPDIR)"
If you have problems with the dependency build (for example, if you are not
building on C:), then you may need to modify tools/mkdeps.sh
NOTE 1: The CodeSourcery toolchain (2009q1) does not work with default optimization
level of -Os (See Make.defs). It will work with -O0, -O1, or -O2, but not with
-Os.
NOTE 2: The devkitARM toolchain includes a version of MSYS make. Make sure that
the paths to Cygwin's /bin and /usr/bin directories appear BEFORE the devkitARM
path or will get the wrong version of make.
IDEs
^^^^
NuttX is built using command-line make. It can be used with an IDE, but some
effort will be required to create the project (There is a simple RIDE project
in the RIDE subdirectory).
Makefile Build
--------------
Under Eclipse, it is pretty easy to set up an "empty makefile project" and
simply use the NuttX makefile to build the system. That is almost for free
under Linux. Under Windows, you will need to set up the "Cygwin GCC" empty
makefile project in order to work with Windows (Google for "Eclipse Cygwin" -
there is a lot of help on the internet).
Native Build
------------
Here are a few tips before you start that effort:
1) Select the toolchain that you will be using in your .config file
2) Start the NuttX build at least one time from the Cygwin command line
before trying to create your project. This is necessary to create
certain auto-generated files and directories that will be needed.
3) Set up include pathes: You will need include/, arch/arm/src/lpc17xx,
arch/arm/src/common, arch/arm/src/armv7-m, and sched/.
4) All assembly files need to have the definition option -D __ASSEMBLY__
on the command line.
Startup files will probably cause you some headaches. The NuttX startup file
is arch/arm/src/lpc17x/lpc17_vectors.S.
NuttX buildroot Toolchain
^^^^^^^^^^^^^^^^^^^^^^^^^
A GNU GCC-based toolchain is assumed. The files */setenv.sh should
be modified to point to the correct path to the Cortex-M3 GCC toolchain (if
different from the default in your PATH variable).
If you have no Cortex-M3 toolchain, one can be downloaded from the NuttX
SourceForge download site (https://sourceforge.net/project/showfiles.php?group_id=189573).
This GNU toolchain builds and executes in the Linux or Cygwin environment.
1. You must have already configured Nuttx in <some-dir>/nuttx.
cd tools
./configure.sh lpc4330-xplorer/<sub-dir>
2. Download the latest buildroot package into <some-dir>
3. unpack the buildroot tarball. The resulting directory may
have versioning information on it like buildroot-x.y.z. If so,
rename <some-dir>/buildroot-x.y.z to <some-dir>/buildroot.
4. cd <some-dir>/buildroot
5. cp configs/cortexm3-defconfig-4.3.3 .config
6. make oldconfig
7. make
8. Edit setenv.h, if necessary, so that the PATH variable includes
the path to the newly built binaries.
See the file configs/README.txt in the buildroot source tree. That has more
detailed PLUS some special instructions that you will need to follow if you
are building a Cortex-M3 toolchain for Cygwin under Windows.
NOTE: This is an OABI toolchain.
LPC4330-Xplorer Configuration Options
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
CONFIG_ARCH - Identifies the arch/ subdirectory. This should
be set to:
CONFIG_ARCH=arm
CONFIG_ARCH_family - For use in C code:
CONFIG_ARCH_ARM=y
CONFIG_ARCH_architecture - For use in C code:
CONFIG_ARCH_CORTEXM3=y
CONFIG_ARCH_CHIP - Identifies the arch/*/chip subdirectory
CONFIG_ARCH_CHIP=lpc43xx
CONFIG_ARCH_CHIP_name - For use in C code to identify the exact
chip:
CONFIG_ARCH_CHIP_LPC4330=y
CONFIG_ARCH_BOARD - Identifies the configs subdirectory and
hence, the board that supports the particular chip or SoC.
CONFIG_ARCH_BOARD=lpc4330-xplorer (for the LPC4330-Xplorer board)
CONFIG_ARCH_BOARD_name - For use in C code
CONFIG_ARCH_BOARD_LPC4330_XPLORER=y
CONFIG_ARCH_LOOPSPERMSEC - Must be calibrated for correct operation
of delay loops
CONFIG_ENDIAN_BIG - define if big endian (default is little
endian)
CONFIG_DRAM_SIZE - Describes the installed DRAM (CPU SRAM in this case):
CONFIG_DRAM_SIZE=(32*1024) (32Kb)
There is an additional 32Kb of SRAM in AHB SRAM banks 0 and 1.
CONFIG_DRAM_START - The start address of installed DRAM
CONFIG_DRAM_START=0x10000000
CONFIG_DRAM_END - Last address+1 of installed RAM
CONFIG_DRAM_END=(CONFIG_DRAM_START+CONFIG_DRAM_SIZE)
CONFIG_ARCH_IRQPRIO - The LPC43xx supports interrupt prioritization
CONFIG_ARCH_IRQPRIO=y
CONFIG_ARCH_LEDS - Use LEDs to show state. Unique to boards that
have LEDs
CONFIG_ARCH_INTERRUPTSTACK - This architecture supports an interrupt
stack. If defined, this symbol is the size of the interrupt
stack in bytes. If not defined, the user task stacks will be
used during interrupt handling.
CONFIG_ARCH_STACKDUMP - Do stack dumps after assertions
CONFIG_ARCH_LEDS - Use LEDs to show state. Unique to board architecture.
CONFIG_ARCH_CALIBRATION - Enables some build in instrumentation that
cause a 100 second delay during boot-up. This 100 second delay
serves no purpose other than it allows you to calibratre
CONFIG_ARCH_LOOPSPERMSEC. You simply use a stop watch to measure
the 100 second delay then adjust CONFIG_ARCH_LOOPSPERMSEC until
the delay actually is 100 seconds.
Individual subsystems can be enabled:
CONFIG_LPC43_MAINOSC=y
CONFIG_LPC43_PLL0=y
CONFIG_LPC43_PLL1=n
CONFIG_LPC43_ETHERNET=n
CONFIG_LPC43_USBHOST=n
CONFIG_LPC43_USBOTG=n
CONFIG_LPC43_USBDEV=n
CONFIG_LPC43_UART0=y
CONFIG_LPC43_UART1=n
CONFIG_LPC43_UART2=n
CONFIG_LPC43_UART3=n
CONFIG_LPC43_CAN1=n
CONFIG_LPC43_CAN2=n
CONFIG_LPC43_SPI=n
CONFIG_LPC43_SSP0=n
CONFIG_LPC43_SSP1=n
CONFIG_LPC43_I2C0=n
CONFIG_LPC43_I2C1=n
CONFIG_LPC43_I2S=n
CONFIG_LPC43_TMR0=n
CONFIG_LPC43_TMR1=n
CONFIG_LPC43_TMR2=n
CONFIG_LPC43_TMR3=n
CONFIG_LPC43_RIT=n
CONFIG_LPC43_PWM=n
CONFIG_LPC43_MCPWM=n
CONFIG_LPC43_QEI=n
CONFIG_LPC43_RTC=n
CONFIG_LPC43_WDT=n
CONFIG_LPC43_ADC=n
CONFIG_LPC43_DAC=n
CONFIG_LPC43_GPDMA=n
CONFIG_LPC43_FLASH=n
LPC43xx specific device driver settings
CONFIG_UARTn_SERIAL_CONSOLE - selects the UARTn for the
console and ttys0 (default is the UART0).
CONFIG_UARTn_RXBUFSIZE - Characters are buffered as received.
This specific the size of the receive buffer
CONFIG_UARTn_TXBUFSIZE - Characters are buffered before
being sent. This specific the size of the transmit buffer
CONFIG_UARTn_BAUD - The configure BAUD of the UART. Must be
CONFIG_UARTn_BITS - The number of bits. Must be either 7 or 8.
CONFIG_UARTn_PARTIY - 0=no parity, 1=odd parity, 2=even parity
CONFIG_UARTn_2STOP - Two stop bits
LPC43xx specific CAN device driver settings. These settings all
require CONFIG_CAN:
CONFIG_CAN_EXTID - Enables support for the 29-bit extended ID. Default
Standard 11-bit IDs.
CONFIG_CAN1_BAUD - CAN1 BAUD rate. Required if CONFIG_LPC43_CAN1 is defined.
CONFIG_CAN2_BAUD - CAN1 BAUD rate. Required if CONFIG_LPC43_CAN2 is defined.
CONFIG_CAN1_DIVISOR - CAN1 is clocked at CCLK divided by this number.
(the CCLK frequency is divided by this number to get the CAN clock).
Options = {1,2,4,6}. Default: 4.
CONFIG_CAN2_DIVISOR - CAN2 is clocked at CCLK divided by this number.
(the CCLK frequency is divided by this number to get the CAN clock).
Options = {1,2,4,6}. Default: 4.
CONFIG_CAN_TSEG1 - The number of CAN time quanta in segment 1. Default: 6
CONFIG_CAN_TSEG2 = the number of CAN time quanta in segment 2. Default: 7
LPC43xx specific PHY/Ethernet device driver settings. These setting
also require CONFIG_NET and CONFIG_LPC43_ETHERNET.
CONFIG_PHY_KS8721 - Selects Micrel KS8721 PHY
CONFIG_PHY_AUTONEG - Enable auto-negotion
CONFIG_PHY_SPEED100 - Select 100Mbit vs. 10Mbit speed.
CONFIG_PHY_FDUPLEX - Select full (vs. half) duplex
CONFIG_NET_EMACRAM_SIZE - Size of EMAC RAM. Default: 16Kb
CONFIG_NET_NTXDESC - Configured number of Tx descriptors. Default: 18
CONFIG_NET_NRXDESC - Configured number of Rx descriptors. Default: 18
CONFIG_NET_PRIORITY - Ethernet interrupt priority. The is default is
the higest priority.
CONFIG_NET_WOL - Enable Wake-up on Lan (not fully implemented).
CONFIG_NET_REGDEBUG - Enabled low level register debug. Also needs
CONFIG_DEBUG.
CONFIG_NET_DUMPPACKET - Dump all received and transmitted packets.
Also needs CONFIG_DEBUG.
CONFIG_NET_HASH - Enable receipt of near-perfect match frames.
CONFIG_NET_MULTICAST - Enable receipt of multicast (and unicast) frames.
Automatically set if CONFIG_NET_IGMP is selected.
LPC43xx USB Device Configuration
CONFIG_LPC43_USBDEV_FRAME_INTERRUPT
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_LPC43_USBDEV_EPFAST_INTERRUPT
Enable high priority interrupts. I have no idea why you might want to
do that
CONFIG_LPC43_USBDEV_NDMADESCRIPTORS
Number of DMA descriptors to allocate in SRAM.
CONFIG_LPC43_USBDEV_DMA
Enable lpc17xx-specific DMA support
CONFIG_LPC43_USBDEV_NOVBUS
Define if the hardware implementation does not support the VBUS signal
CONFIG_LPC43_USBDEV_NOLED
Define if the hardware implementation does not support the LED output
LPC43xx USB Host Configuration
CONFIG_USBHOST_OHCIRAM_SIZE
Total size of OHCI RAM (in AHB SRAM Bank 1)
CONFIG_USBHOST_NEDS
Number of endpoint descriptors
CONFIG_USBHOST_NTDS
Number of transfer descriptors
CONFIG_USBHOST_TDBUFFERS
Number of transfer descriptor buffers
CONFIG_USBHOST_TDBUFSIZE
Size of one transfer descriptor buffer
CONFIG_USBHOST_IOBUFSIZE
Size of one end-user I/O buffer. This can be zero if the
application can guarantee that all end-user I/O buffers
reside in AHB SRAM.
USB Host Configuration
^^^^^^^^^^^^^^^^^^^^^^
The LPC4330-Xplorer board supports a USB host interface. The hidkbd
example can be used to test this interface.
The NuttShell (NSH) lpc4330-xplorer can also be modified in order to support USB
host operations. To make these modifications, do the following:
1. First configure to build the NSH configuration from the top-level
NuttX directory:
cd tools
./configure lpc4330-xplorer/nsh
cd ..
2. Then edit the top-level .config file to enable USB host. Make the
following changes:
CONFIG_LPC43_USBHOST=n
CONFIG_USBHOST=n
CONFIG_SCHED_WORKQUEUE=y
When this change is made, NSH should be extended to support USB flash
devices. When a FLASH device is inserted, you should see a device
appear in the /dev (psuedo) directory. The device name should be
like /dev/sda, /dev/sdb, etc. The USB mass storage device, is present
it can be mounted from the NSH command line like:
ls /dev
mount -t vfat /dev/sda /mnt/flash
Files on the connect USB flash device should then be accessible under
the mountpoint /mnt/flash.
Configurations
^^^^^^^^^^^^^^
Each LPC4330-Xplorer configuration is maintained in a sudirectory and can be selected
as follow:
cd tools
./configure.sh lpc4330-xplorer/<subdir>
cd -
. ./setenv.sh
Where <subdir> is one of the following:
hidkbd:
This configuration directory, performs a simple test of the USB host
HID keyboard class driver using the test logic in examples/hidkbd.
nsh:
Configures the NuttShell (nsh) located at examples/nsh. The
Configuration enables only the serial NSH interfaces. See notes
above for enabling USB host support in this configuration.

View File

@ -0,0 +1,222 @@
/****************************************************************************
* configs/lpc4330-xplorer/include/board.h
* include/arch/board/board.h
*
* Copyright (C) 2012 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name NuttX nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
#ifndef __ARCH_BOARD_BOARD_H
#define __ARCH_BOARD_BOARD_H
/****************************************************************************
* Included Files
****************************************************************************/
#include <nuttx/config.h>
#include <stdbool.h>
#if defined(CONFIG_ARCH_IRQBUTTONS) && defined(CONFIG_GPIO_IRQ)
# include <nuttx/irq.h>
#endif
/****************************************************************************
* Definitions
****************************************************************************/
/* Clocking ****************************************************************/
/* NOTE: The following definitions require lpc43_syscon.h. It is not included here
* because the including C file may not have that file in its include path.
*/
#define BOARD_XTAL_FREQUENCY (12000000) /* XTAL oscillator frequency */
#define BOARD_OSCCLK_FREQUENCY BOARD_XTAL_FREQUENCY /* Main oscillator frequency */
#define BOARD_RTCCLK_FREQUENCY (32768) /* RTC oscillator frequency */
#define BOARD_INTRCOSC_FREQUENCY (4000000) /* Internal RC oscillator frequency */
/* This is the clock setup we configure for:
*
* SYSCLK = BOARD_OSCCLK_FREQUENCY = 12MHz -> Select Main oscillator for source
* PLL0CLK = (2 * 20 * SYSCLK) / 1 = 480MHz -> PLL0 multipler=20, pre-divider=1
* CCLCK = 480MHz / 6 = 80MHz -> CCLK divider = 6
*/
#define LPC43_CCLK 80000000 /* 80Mhz*/
/* Select the main oscillator as the frequency source. SYSCLK is then the frequency
* of the main oscillator.
*/
#undef CONFIG_LPC43_MAINOSC
#define CONFIG_LPC43_MAINOSC 1
#define BOARD_SCS_VALUE SYSCON_SCS_OSCEN
/* Select the main oscillator and CCLK divider. The output of the divider is CCLK.
* The input to the divider (PLLCLK) will be determined by the PLL output.
*/
#define BOARD_CCLKCFG_DIVIDER 6
#define BOARD_CCLKCFG_VALUE ((BOARD_CCLKCFG_DIVIDER-1) << SYSCON_CCLKCFG_SHIFT)
/* PLL0. PLL0 is used to generate the CPU clock divider input (PLLCLK).
*
* Source clock: Main oscillator
* PLL0 Multiplier value (M): 20
* PLL0 Pre-divider value (N): 1
*
* PLL0CLK = (2 * 20 * SYSCLK) / 1 = 480MHz
*/
#undef CONFIG_LPC43_PLL0
#define CONFIG_LPC43_PLL0 1
#define BOARD_CLKSRCSEL_VALUE SYSCON_CLKSRCSEL_MAIN
#define BOARD_PLL0CFG_MSEL 20
#define BOARD_PLL0CFG_NSEL 1
#define BOARD_PLL0CFG_VALUE \
(((BOARD_PLL0CFG_MSEL-1) << SYSCON_PLL0CFG_MSEL_SHIFT) | \
((BOARD_PLL0CFG_NSEL-1) << SYSCON_PLL0CFG_NSEL_SHIFT))
/* PLL1 -- Not used. */
#undef CONFIG_LPC43_PLL1
#define BOARD_PLL1CFG_MSEL 36
#define BOARD_PLL1CFG_NSEL 1
#define BOARD_PLL1CFG_VALUE \
(((BOARD_PLL1CFG_MSEL-1) << SYSCON_PLL1CFG_MSEL_SHIFT) | \
((BOARD_PLL1CFG_NSEL-1) << SYSCON_PLL1CFG_NSEL_SHIFT))
/* USB divider. This divider is used when PLL1 is not enabled to get the
* USB clock from PLL0:
*
* USBCLK = PLL0CLK / 10 = 48MHz
*/
#define BOARD_USBCLKCFG_VALUE SYSCON_USBCLKCFG_DIV10
/* FLASH Configuration */
#undef CONFIG_LP17_FLASH
#define CONFIG_LP17_FLASH 1
#define BOARD_FLASHCFG_VALUE 0x0000303a
/* LED definitions *********************************************************/
/* The Lincoln 80 has 2 LEDs along the bottom of the board. Green or off.
* If CONFIG_ARCH_LEDS is defined, the LEDs will be controlled as follows
* for NuttX debug functionality (where NC means "No Change").
*
* During the boot phases. LED1 and LED2 will show boot status.
*/
/* LED1 LED2 */
#define LED_STARTED 0 /* OFF OFF */
#define LED_HEAPALLOCATE 1 /* GREEN OFF */
#define LED_IRQSENABLED 2 /* OFF GREEN */
#define LED_STACKCREATED 3 /* OFF OFF */
/* After the system is booted, this logic will no longer use LEDs 1 & 2.
* They are available for use the application software using lpc43_led
* (prototyped below)
*/
/* LED1 LED2 LED3 LED4 */
#define LED_INIRQ 4 /* NC NC NC ON (momentary) */
#define LED_SIGNAL 5 /* NC NC NC ON (momentary) */
#define LED_ASSERTION 6 /* NC NC NC ON (momentary) */
#define LED_PANIC 7 /* NC NC NC ON (1Hz flashing) */
#define GPIO_SSP0_SCK GPIO_SSP0_SCK_1
#define GPIO_SSP0_SSEL GPIO_SSP0_SSEL_1
#define GPIO_SSP0_MISO GPIO_SSP0_MISO_1
#define GPIO_SSP0_MOSI GPIO_SSP0_MOSI_1
/* We need to redefine USB_PWRD as GPIO to get USB Host working
* Also remember to add 2 resistors of 15K to D+ and D- pins.
*/
#ifdef CONFIG_USBHOST
# ifdef GPIO_USB_PWRD
# undef GPIO_USB_PWRD
# define GPIO_USB_PWRD (GPIO_INPUT | GPIO_PORT1 | GPIO_PIN22)
# endif
#endif
/****************************************************************************
* Public Types
****************************************************************************/
#ifndef __ASSEMBLY__
/****************************************************************************
* Public Data
****************************************************************************/
#undef EXTERN
#if defined(__cplusplus)
#define EXTERN extern "C"
extern "C" {
#else
#define EXTERN extern
#endif
/****************************************************************************
* Public Function Prototypes
****************************************************************************/
/****************************************************************************
* Name: lpc43_boardinitialize
*
* Description:
* All LPC43xx architectures must provide the following entry point. This entry point
* is called early in the intitialization -- after all memory has been configured
* and mapped but before any devices have been initialized.
*
****************************************************************************/
EXTERN void lpc43_boardinitialize(void);
/****************************************************************************
* Name: lpc43_led
*
* Description:
* Once the system has booted, these functions can be used to control LEDs 1 & 2
*
************************************************************************************/
#ifdef CONFIG_ARCH_LEDS
EXTERN void lpc43_led(int lednum, int state);
#endif
#undef EXTERN
#if defined(__cplusplus)
}
#endif
#endif /* __ASSEMBLY__ */
#endif /* __ARCH_BOARD_BOARD_H */

View File

@ -0,0 +1,162 @@
############################################################################
# configs/lpc4330-xplorer/nsh/Make.defs
#
# Copyright (C) 2012 Gregory Nutt. All rights reserved.
# Author: Gregory Nutt <gnutt@nuttx.org>
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions
# are met:
#
# 1. Redistributions of source code must retain the above copyright
# notice, this list of conditions and the following disclaimer.
# 2. Redistributions in binary form must reproduce the above copyright
# notice, this list of conditions and the following disclaimer in
# the documentation and/or other materials provided with the
# distribution.
# 3. Neither the name NuttX nor the names of its contributors may be
# used to endorse or promote products derived from this software
# without specific prior written permission.
#
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
# POSSIBILITY OF SUCH DAMAGE.
#
############################################################################
include ${TOPDIR}/.config
# Setup for the selected toolchain
ifeq ($(CONFIG_LPC43_CODESOURCERYW),y)
# CodeSourcery under Windows
CROSSDEV = arm-none-eabi-
WINTOOL = y
ARCHCPUFLAGS = -mcpu=cortex-m4 -mthumb -mfloat-abi=soft
endif
ifeq ($(CONFIG_LPC43_CODESOURCERYL),y)
# CodeSourcery under Linux
CROSSDEV = arm-none-eabi-
ARCHCPUFLAGS = -mcpu=cortex-m4 -mthumb -mfloat-abi=soft
MAXOPTIMIZATION = -O2
endif
ifeq ($(CONFIG_LPC43_DEVKITARM),y)
# devkitARM under Windows
CROSSDEV = arm-eabi-
WINTOOL = y
ARCHCPUFLAGS = -mcpu=cortex-m4 -mthumb -mfloat-abi=soft
endif
ifeq ($(CONFIG_LPC43_BUILDROOT),y)
# NuttX buildroot under Linux or Cygwin
CROSSDEV = arm-elf-
ARCHCPUFLAGS = -mtune=cortex-m4 -march=armv7-m -mfloat-abi=soft
MAXOPTIMIZATION = -Os
endif
ifeq ($(WINTOOL),y)
# Windows-native toolchains
DIRLINK = $(TOPDIR)/tools/winlink.sh
DIRUNLINK = $(TOPDIR)/tools/unlink.sh
MKDEP = $(TOPDIR)/tools/mknulldeps.sh
ARCHINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}"
ARCHXXINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}" -isystem "${shell cygpath -w $(TOPDIR)/include/cxx}"
ARCHSCRIPT = -T "${shell cygpath -w $(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/ld.script}"
MAXOPTIMIZATION = -O2
else
# Linux/Cygwin-native toolchain
MKDEP = $(TOPDIR)/tools/mkdeps.sh
ARCHINCLUDES = -I. -isystem $(TOPDIR)/include
ARCHXXINCLUDES = -I. -isystem $(TOPDIR)/include -isystem $(TOPDIR)/include/cxx
ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/ld.script
endif
CC = $(CROSSDEV)gcc
CXX = $(CROSSDEV)g++
CPP = $(CROSSDEV)gcc -E
LD = $(CROSSDEV)ld
AR = $(CROSSDEV)ar rcs
NM = $(CROSSDEV)nm
OBJCOPY = $(CROSSDEV)objcopy
OBJDUMP = $(CROSSDEV)objdump
ARCHCCVERSION = ${shell $(CC) -v 2>&1 | sed -n '/^gcc version/p' | sed -e 's/^gcc version \([0-9\.]\)/\1/g' -e 's/[-\ ].*//g' -e '1q'}
ARCHCCMAJOR = ${shell echo $(ARCHCCVERSION) | cut -d'.' -f1}
ifeq ("${CONFIG_DEBUG_SYMBOLS}","y")
ARCHOPTIMIZATION = -g
else
ARCHOPTIMIZATION = $(MAXOPTIMIZATION) -fno-strict-aliasing -fno-strength-reduce -fomit-frame-pointer
endif
ARCHCFLAGS = -fno-builtin
ARCHCXXFLAGS = -fno-builtin -fno-exceptions
ARCHWARNINGS = -Wall -Wstrict-prototypes -Wshadow
ARCHWARNINGSXX = -Wall -Wshadow
ARCHDEFINES =
ARCHPICFLAGS = -fpic -msingle-pic-base -mpic-register=r10
CFLAGS = $(ARCHCFLAGS) $(ARCHWARNINGS) $(ARCHOPTIMIZATION) $(ARCHCPUFLAGS) $(ARCHINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) -pipe
CPICFLAGS = $(ARCHPICFLAGS) $(CFLAGS)
CXXFLAGS = $(ARCHCXXFLAGS) $(ARCHWARNINGSXX) $(ARCHOPTIMIZATION) $(ARCHCPUFLAGS) $(ARCHXXINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) -pipe
CXXPICFLAGS = $(ARCHPICFLAGS) $(CXXFLAGS)
CPPFLAGS = $(ARCHINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES)
AFLAGS = $(CFLAGS) -D__ASSEMBLY__
NXFLATLDFLAGS1 = -r -d -warn-common
NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat.ld -no-check-sections
LDNXFLATFLAGS = -e main -s 2048
OBJEXT = .o
LIBEXT = .a
EXEEXT =
ifneq ($(CROSSDEV),arm-elf-)
LDFLAGS += -nostartfiles -nodefaultlibs
endif
ifeq ($(CONFIG_DEBUG_SYMBOLS),y)
LDFLAGS += -g
endif
define PREPROCESS
@echo "CPP: $1->$2"
@$(CPP) $(CPPFLAGS) $1 -o $2
endef
define COMPILE
@echo "CC: $1"
@$(CC) -c $(CFLAGS) $1 -o $2
endef
define COMPILEXX
@echo "CXX: $1"
@$(CXX) -c $(CXXFLAGS) $1 -o $2
endef
define ASSEMBLE
@echo "AS: $1"
@$(CC) -c $(AFLAGS) $1 -o $2
endef
define ARCHIVE
echo "AR: $2"; \
$(AR) $1 $2 || { echo "$(AR) $1 $2 FAILED!" ; exit 1 ; }
endef
define CLEAN
@rm -f *.o *.a
endef
HOSTCC = gcc
HOSTINCLUDES = -I.
HOSTCFLAGS = -Wall -Wstrict-prototypes -Wshadow -g -pipe
HOSTLDFLAGS =

View File

@ -0,0 +1,39 @@
############################################################################
# configs/lpc4330-xplorer/ostest/appconfig
#
# Copyright (C) 2012 Gregory Nutt. All rights reserved.
# Author: Gregory Nutt <gnutt@nuttx.org>
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions
# are met:
#
# 1. Redistributions of source code must retain the above copyright
# notice, this list of conditions and the following disclaimer.
# 2. Redistributions in binary form must reproduce the above copyright
# notice, this list of conditions and the following disclaimer in
# the documentation and/or other materials provided with the
# distribution.
# 3. Neither the name NuttX nor the names of its contributors may be
# used to endorse or promote products derived from this software
# without specific prior written permission.
#
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
# POSSIBILITY OF SUCH DAMAGE.
#
############################################################################
# Path to example in apps/examples containing the user_start entry point
CONFIGURED_APPS += examples/ostest

View File

@ -0,0 +1,821 @@
############################################################################
# configs/lpc4330-xplorer/ostest/defconfig
#
# Copyright (C) 2012 Gregory Nutt. All rights reserved.
# Author: Gregory Nutt <gnutt@nuttx.org>
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions
# are met:
#
# 1. Redistributions of source code must retain the above copyright
# notice, this list of conditions and the following disclaimer.
# 2. Redistributions in binary form must reproduce the above copyright
# notice, this list of conditions and the following disclaimer in
# the documentation and/or other materials provided with the
# distribution.
# 3. Neither the name NuttX nor the names of its contributors may be
# used to endorse or promote products derived from this software
# without specific prior written permission.
#
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
# POSSIBILITY OF SUCH DAMAGE.
#
############################################################################
#
# architecture selection
#
# CONFIG_ARCH - identifies the arch subdirectory and, hence, the
# processor architecture.
# CONFIG_ARCH_family - for use in C code. This identifies the
# particular chip family that the architecture is implemented
# in.
# CONFIG_ARCH_architecture - for use in C code. This identifies the
# specific architecture within the chip familyl.
# CONFIG_ARCH_CHIP - Identifies the arch/*/chip subdirectory
# CONFIG_ARCH_CHIP_name - For use in C code
# CONFIG_ARCH_BOARD - identifies the configs subdirectory and, hence,
# the board that supports the particular chip or SoC.
# CONFIG_ARCH_BOARD_name - for use in C code
# CONFIG_ENDIAN_BIG - define if big endian (default is little endian)
# CONFIG_BOARD_LOOPSPERMSEC - for delay loops
# CONFIG_DRAM_SIZE - Describes the installed DRAM.
# CONFIG_DRAM_START - The start address of DRAM (physical)
# CONFIG_DRAM_END - Last address+1 of installed RAM
# CONFIG_ARCH_IRQPRIO - The ST32F103Z supports interrupt prioritization
# CONFIG_ARCH_INTERRUPTSTACK - This architecture supports an interrupt
# stack. If defined, this symbol is the size of the interrupt
# stack in bytes. If not defined, the user task stacks will be
# used during interrupt handling.
# CONFIG_ARCH_STACKDUMP - Do stack dumps after assertions
# CONFIG_ARCH_BOOTLOADER - Set if you are using a bootloader.
# CONFIG_ARCH_LEDS - Use LEDs to show state. Unique to board architecture.
# CONFIG_ARCH_BUTTONS - Enable support for buttons. Unique to board architecture.
# CONFIG_ARCH_CALIBRATION - Enables some build in instrumentation that
# cause a 100 second delay during boot-up. This 100 second delay
# serves no purpose other than it allows you to calibrate
# CONFIG_BOARD_LOOPSPERMSEC. You simply use a stop watch to measure
# the 100 second delay then adjust CONFIG_BOARD_LOOPSPERMSEC until
# the delay actually is 100 seconds.
# CONFIG_ARCH_DMA - Support DMA initialization
#
CONFIG_ARCH=arm
CONFIG_ARCH_ARM=y
CONFIG_ARCH_CORTEXM4=y
CONFIG_ARCH_CHIP=lpc43xx
CONFIG_ARCH_CHIP_LPC4320=y
CONFIG_ARCH_BOARD=lpc4330-xplorer
CONFIG_ARCH_BOARD_LPC4330_XPLORER=y
CONFIG_BOARD_LOOPSPERMSEC=7982
CONFIG_DRAM_SIZE=(128*1024)
CONFIG_DRAM_START=0x10000000
CONFIG_DRAM_END=(CONFIG_DRAM_START+CONFIG_DRAM_SIZE)
CONFIG_ARCH_IRQPRIO=y
CONFIG_ARCH_INTERRUPTSTACK=n
CONFIG_ARCH_STACKDUMP=y
CONFIG_ARCH_BOOTLOADER=n
CONFIG_ARCH_LEDS=y
CONFIG_ARCH_BUTTONS=n
CONFIG_ARCH_CALIBRATION=n
CONFIG_ARCH_DMA=n
#
# Identify toolchain and linker options
#
CONFIG_LPC43_CODESOURCERYW=n
CONFIG_LPC43_CODESOURCERYL=y
CONFIG_LPC43_DEVKITARM=n
CONFIG_LPC43_BUILDROOT=n
#
# Individual subsystems can be enabled:
#
# Individual subsystems can be enabled:
# (MAINOSC, PLL0, PLL1 and FLASH are controlled in board.h)
CONFIG_LPC43_ETHERNET=n
CONFIG_LPC43_USBHOST=n
CONFIG_LPC43_USBOTG=n
CONFIG_LPC43_USBDEV=n
CONFIG_LPC43_UART0=y
CONFIG_LPC43_UART1=n
CONFIG_LPC43_UART2=n
CONFIG_LPC43_UART3=n
CONFIG_LPC43_CAN1=n
CONFIG_LPC43_CAN2=n
CONFIG_LPC43_SPI=n
CONFIG_LPC43_SSP0=y
CONFIG_LPC43_SSP1=n
CONFIG_LPC43_I2C0=n
CONFIG_LPC43_I2C1=n
CONFIG_LPC43_I2S=n
CONFIG_LPC43_TMR0=n
CONFIG_LPC43_TMR1=n
CONFIG_LPC43_TMR2=n
CONFIG_LPC43_TMR3=n
CONFIG_LPC43_RIT=n
CONFIG_LPC43_PWM=n
CONFIG_LPC43_MCPWM=n
CONFIG_LPC43_QEI=n
CONFIG_LPC43_RTC=n
CONFIG_LPC43_WDT=n
CONFIG_LPC43_ADC=n
CONFIG_LPC43_DAC=n
CONFIG_LPC43_GPDMA=n
#
# LPC43xx specific serial device driver settings
#
# CONFIG_UARTn_SERIAL_CONSOLE - selects the UARTn for the
# console and ttys0 (default is the UART1).
# CONFIG_UARTn_RXBUFSIZE - Characters are buffered as received.
# This specific the size of the receive buffer
# CONFIG_UARTn_TXBUFSIZE - Characters are buffered before
# being sent. This specific the size of the transmit buffer
# CONFIG_UARTn_BAUD - The configure BAUD of the UART. Must be
# CONFIG_UARTn_BITS - The number of bits. Must be either 7 or 8.
# CONFIG_UARTn_PARTIY - 0=no parity, 1=odd parity, 2=even parity
# CONFIG_UARTn_2STOP - Two stop bits
#
CONFIG_UART0_SERIAL_CONSOLE=y
CONFIG_UART1_SERIAL_CONSOLE=n
CONFIG_UART2_SERIAL_CONSOLE=n
CONFIG_UART3_SERIAL_CONSOLE=n
CONFIG_UART0_TXBUFSIZE=256
CONFIG_UART1_TXBUFSIZE=256
CONFIG_UART2_TXBUFSIZE=256
CONFIG_UART3_TXBUFSIZE=256
CONFIG_UART0_RXBUFSIZE=256
CONFIG_UART1_RXBUFSIZE=256
CONFIG_UART2_RXBUFSIZE=256
CONFIG_UART3_RXBUFSIZE=256
CONFIG_UART0_BAUD=115200
CONFIG_UART2_BAUD=115200
CONFIG_UART3_BAUD=115200
CONFIG_UART1_BAUD=115200
CONFIG_UART0_BITS=8
CONFIG_UART1_BITS=8
CONFIG_UART2_BITS=8
CONFIG_UART3_BITS=8
CONFIG_UART0_PARITY=0
CONFIG_UART1_PARITY=0
CONFIG_UART2_PARITY=0
CONFIG_UART3_PARITY=0
CONFIG_UART0_2STOP=0
CONFIG_UART1_2STOP=0
CONFIG_UART2_2STOP=0
CONFIG_UART3_2STOP=0
#
# LPC43xx specific PHY/Ethernet device driver settings
#
# CONFIG_PHY_KS8721 - Selects Micrel KS8721 PHY
# CONFIG_PHY_AUTONEG - Enable auto-negotion
# CONFIG_PHY_SPEED100 - Select 100Mbit vs. 10Mbit speed.
# CONFIG_PHY_FDUPLEX - Select full (vs. half) duplex
# CONFIG_NET_EMACRAM_SIZE - Size of EMAC RAM. Default: 16Kb
# CONFIG_NET_NTXDESC - Configured number of Tx descriptors. Default: 18
# CONFIG_NET_NRXDESC - Configured number of Rx descriptors. Default: 18
# CONFIG_NET_PRIORITY - Ethernet interrupt priority. The is default is
# the higest priority.
# CONFIG_NET_WOL - Enable Wake-up on Lan (not fully implemented).
# CONFIG_NET_REGDEBUG - Enabled low level register debug. Also needs
# CONFIG_DEBUG.
# CONFIG_NET_HASH - Enable receipt of near-perfect match frames.
# CONFIG_NET_MULTICAST - Enable receipt of multicast (and unicast) frames.
# Automatically set if CONFIG_NET_IGMP is selected.
#
CONFIG_PHY_KS8721=y
CONFIG_PHY_AUTONEG=y
CONFIG_PHY_SPEED100=n
CONFIG_PHY_FDUPLEX=y
#
# General build options
#
# CONFIG_RRLOAD_BINARY - make the rrload binary format used with
# BSPs from www.ridgerun.com using the tools/mkimage.sh script
# CONFIG_INTELHEX_BINARY - make the Intel HEX binary format
# used with many different loaders using the GNU objcopy program
# Should not be selected if you are not using the GNU toolchain.
# CONFIG_MOTOROLA_SREC - make the Motorola S-Record binary format
# used with many different loaders using the GNU objcopy program
# Should not be selected if you are not using the GNU toolchain.
# CONFIG_RAW_BINARY - make a raw binary format file used with many
# different loaders using the GNU objcopy program. This option
# should not be selected if you are not using the GNU toolchain.
# CONFIG_HAVE_LIBM - toolchain supports libm.a
#
CONFIG_RRLOAD_BINARY=n
CONFIG_INTELHEX_BINARY=n
CONFIG_MOTOROLA_SREC=n
CONFIG_RAW_BINARY=y
CONFIG_HAVE_LIBM=n
#
# General OS setup
#
# CONFIG_APPS_DIR - Identifies the relative path to the directory
# that builds the application to link with NuttX. Default: ../apps
# CONFIG_DEBUG - enables built-in debug options
# CONFIG_DEBUG_VERBOSE - enables verbose debug output
# CONFIG_DEBUG_SYMBOLS - build without optimization and with
# debug symbols (needed for use with a debugger).
# CONFIG_MM_REGIONS - If the architecture includes multiple
# regions of memory to allocate from, this specifies the
# number of memory regions that the memory manager must
# handle and enables the API mm_addregion(start, end);
# CONFIG_ARCH_LOWPUTC - architecture supports low-level, boot
# time console output
# CONFIG_MSEC_PER_TICK - The default system timer is 100Hz
# or MSEC_PER_TICK=10. This setting may be defined to
# inform NuttX that the processor hardware is providing
# system timer interrupts at some interrupt interval other
# than 10 msec.
# CONFIG_RR_INTERVAL - The round robin timeslice will be set
# this number of milliseconds; Round robin scheduling can
# be disabled by setting this value to zero.
# CONFIG_SCHED_INSTRUMENTATION - enables instrumentation in
# scheduler to monitor system performance
# CONFIG_TASK_NAME_SIZE - Spcifies that maximum size of a
# task name to save in the TCB. Useful if scheduler
# instrumentation is selected. Set to zero to disable.
# CONFIG_START_YEAR, CONFIG_START_MONTH, CONFIG_START_DAY -
# Used to initialize the internal time logic.
# CONFIG_GREGORIAN_TIME - Enables Gregorian time conversions.
# You would only need this if you are concerned about accurate
# time conversions in the past or in the distant future.
# CONFIG_JULIAN_TIME - Enables Julian time conversions. You
# would only need this if you are concerned about accurate
# time conversion in the distand past. You must also define
# CONFIG_GREGORIAN_TIME in order to use Julian time.
# CONFIG_DEV_CONSOLE - Set if architecture-specific logic
# provides /dev/console. Enables stdout, stderr, stdin.
# CONFIG_DEV_LOWCONSOLE - Use the simple, low-level serial console
# driver (minimul support)
# CONFIG_MUTEX_TYPES: Set to enable support for recursive and
# errorcheck mutexes. Enables pthread_mutexattr_settype().
# CONFIG_PRIORITY_INHERITANCE : Set to enable support for priority
# inheritance on mutexes and semaphores.
# CONFIG_SEM_PREALLOCHOLDERS: This setting is only used if priority
# inheritance is enabled. It defines the maximum number of
# different threads (minus one) that can take counts on a
# semaphore with priority inheritance support. This may be
# set to zero if priority inheritance is disabled OR if you
# are only using semaphores as mutexes (only one holder) OR
# if no more than two threads participate using a counting
# semaphore.
# CONFIG_SEM_NNESTPRIO. If priority inheritance is enabled,
# then this setting is the maximum number of higher priority
# threads (minus 1) than can be waiting for another thread
# to release a count on a semaphore. This value may be set
# to zero if no more than one thread is expected to wait for
# a semaphore.
# CONFIG_FDCLONE_DISABLE. Disable cloning of all file descriptors
# by task_create() when a new task is started. If set, all
# files/drivers will appear to be closed in the new task.
# CONFIG_FDCLONE_STDIO. Disable cloning of all but the first
# three file descriptors (stdin, stdout, stderr) by task_create()
# when a new task is started. If set, all files/drivers will
# appear to be closed in the new task except for stdin, stdout,
# and stderr.
# CONFIG_SDCLONE_DISABLE. Disable cloning of all socket
# desciptors by task_create() when a new task is started. If
# set, all sockets will appear to be closed in the new task.
# CONFIG_NXFLAT. Enable support for the NXFLAT binary format.
# This format will support execution of NuttX binaries located
# in a ROMFS filesystem (see examples/nxflat).
# CONFIG_SCHED_WORKQUEUE. Create a dedicated "worker" thread to
# handle delayed processing from interrupt handlers. This feature
# is required for some drivers but, if there are not complaints,
# can be safely disabled. The worker thread also performs
# garbage collection -- completing any delayed memory deallocations
# from interrupt handlers. If the worker thread is disabled,
# then that clean will be performed by the IDLE thread instead
# (which runs at the lowest of priority and may not be appropriate
# if memory reclamation is of high priority). If CONFIG_SCHED_WORKQUEUE
# is enabled, then the following options can also be used:
# CONFIG_SCHED_WORKPRIORITY - The execution priority of the worker
# thread. Default: 50
# CONFIG_SCHED_WORKPERIOD - How often the worker thread checks for
# work in units of microseconds. Default: 50*1000 (50 MS).
# CONFIG_SCHED_WORKSTACKSIZE - The stack size allocated for the worker
# thread. Default: CONFIG_IDLETHREAD_STACKSIZE.
# CONFIG_SIG_SIGWORK - The signal number that will be used to wake-up
# the worker thread. Default: 4
#
#CONFIG_APPS_DIR=
CONFIG_DEBUG=n
CONFIG_DEBUG_VERBOSE=n
CONFIG_DEBUG_SYMBOLS=n
CONFIG_MM_REGIONS=2
CONFIG_ARCH_LOWPUTC=y
CONFIG_RR_INTERVAL=200
CONFIG_SCHED_INSTRUMENTATION=n
CONFIG_TASK_NAME_SIZE=0
CONFIG_START_YEAR=2010
CONFIG_START_MONTH=6
CONFIG_START_DAY=20
CONFIG_GREGORIAN_TIME=n
CONFIG_JULIAN_TIME=n
CONFIG_DEV_CONSOLE=y
CONFIG_DEV_LOWCONSOLE=n
CONFIG_MUTEX_TYPES=n
CONFIG_PRIORITY_INHERITANCE=n
CONFIG_SEM_PREALLOCHOLDERS=0
CONFIG_SEM_NNESTPRIO=0
CONFIG_FDCLONE_DISABLE=n
CONFIG_FDCLONE_STDIO=n
CONFIG_SDCLONE_DISABLE=y
CONFIG_NXFLAT=n
CONFIG_SCHED_WORKQUEUE=n
CONFIG_SCHED_WORKPRIORITY=50
CONFIG_SCHED_WORKPERIOD=(50*1000)
CONFIG_SCHED_WORKSTACKSIZE=1024
CONFIG_SIG_SIGWORK=4
#
# The following can be used to disable categories of
# APIs supported by the OS. If the compiler supports
# weak functions, then it should not be necessary to
# disable functions unless you want to restrict usage
# of those APIs.
#
# There are certain dependency relationships in these
# features.
#
# o mq_notify logic depends on signals to awaken tasks
# waiting for queues to become full or empty.
# o pthread_condtimedwait() depends on signals to wake
# up waiting tasks.
#
CONFIG_DISABLE_CLOCK=n
CONFIG_DISABLE_POSIX_TIMERS=n
CONFIG_DISABLE_PTHREAD=n
CONFIG_DISABLE_SIGNALS=n
CONFIG_DISABLE_MQUEUE=n
CONFIG_DISABLE_MOUNTPOINT=n
CONFIG_DISABLE_ENVIRON=n
CONFIG_DISABLE_POLL=y
#
# Misc libc settings
#
# CONFIG_NOPRINTF_FIELDWIDTH - sprintf-related logic is a
# little smaller if we do not support fieldwidthes
#
CONFIG_NOPRINTF_FIELDWIDTH=n
#
# Allow for architecture optimized implementations
#
# The architecture can provide optimized versions of the
# following to improve system performance
#
CONFIG_ARCH_MEMCPY=n
CONFIG_ARCH_MEMCMP=n
CONFIG_ARCH_MEMMOVE=n
CONFIG_ARCH_MEMSET=n
CONFIG_ARCH_STRCMP=n
CONFIG_ARCH_STRCPY=n
CONFIG_ARCH_STRNCPY=n
CONFIG_ARCH_STRLEN=n
CONFIG_ARCH_STRNLEN=n
CONFIG_ARCH_BZERO=n
#
# Sizes of configurable things (0 disables)
#
# CONFIG_MAX_TASKS - The maximum number of simultaneously
# active tasks. This value must be a power of two.
# CONFIG_MAX_TASK_ARGS - This controls the maximum number of
# of parameters that a task may receive (i.e., maxmum value
# of 'argc')
# CONFIG_NPTHREAD_KEYS - The number of items of thread-
# specific data that can be retained
# CONFIG_NFILE_DESCRIPTORS - The maximum number of file
# descriptors (one for each open)
# CONFIG_NFILE_STREAMS - The maximum number of streams that
# can be fopen'ed
# CONFIG_NAME_MAX - The maximum size of a file name.
# CONFIG_STDIO_BUFFER_SIZE - Size of the buffer to allocate
# on fopen. (Only if CONFIG_NFILE_STREAMS > 0)
# CONFIG_NUNGET_CHARS - Number of characters that can be
# buffered by ungetc() (Only if CONFIG_NFILE_STREAMS > 0)
# CONFIG_PREALLOC_MQ_MSGS - The number of pre-allocated message
# structures. The system manages a pool of preallocated
# message structures to minimize dynamic allocations
# CONFIG_MQ_MAXMSGSIZE - Message structures are allocated with
# a fixed payload size given by this settin (does not include
# other message structure overhead.
# CONFIG_MAX_WDOGPARMS - Maximum number of parameters that
# can be passed to a watchdog handler
# CONFIG_PREALLOC_WDOGS - The number of pre-allocated watchdog
# structures. The system manages a pool of preallocated
# watchdog structures to minimize dynamic allocations
# CONFIG_PREALLOC_TIMERS - The number of pre-allocated POSIX
# timer structures. The system manages a pool of preallocated
# timer structures to minimize dynamic allocations. Set to
# zero for all dynamic allocations.
#
CONFIG_MAX_TASKS=16
CONFIG_MAX_TASK_ARGS=4
CONFIG_NPTHREAD_KEYS=4
CONFIG_NFILE_DESCRIPTORS=8
CONFIG_NFILE_STREAMS=8
CONFIG_NAME_MAX=32
CONFIG_STDIO_BUFFER_SIZE=256
CONFIG_NUNGET_CHARS=2
CONFIG_PREALLOC_MQ_MSGS=4
CONFIG_MQ_MAXMSGSIZE=32
CONFIG_MAX_WDOGPARMS=2
CONFIG_PREALLOC_WDOGS=4
CONFIG_PREALLOC_TIMERS=4
#
# Filesystem configuration
#
# CONFIG_FS_FAT - Enable FAT filesystem support
# CONFIG_FAT_SECTORSIZE - Max supported sector size
# CONFIG_FS_ROMFS - Enable ROMFS filesystem support
CONFIG_FS_FAT=y
CONFIG_FS_ROMFS=n
#
# SPI-based MMC/SD driver
#
# CONFIG_MMCSD_NSLOTS
# Number of MMC/SD slots supported by the driver
# CONFIG_MMCSD_READONLY
# Provide read-only access (default is read/write)
# CONFIG_MMCSD_SPICLOCK - Maximum SPI clock to drive MMC/SD card.
# Default is 20MHz.
#
CONFIG_MMCSD_NSLOTS=1
CONFIG_MMCSD_READONLY=n
CONFIG_MMCSD_SPICLOCK=12500000
#
# Block driver buffering
#
# CONFIG_FS_READAHEAD
# Enable read-ahead buffering
# CONFIG_FS_WRITEBUFFER
# Enable write buffering
#
CONFIG_FS_READAHEAD=n
CONFIG_FS_WRITEBUFFER=n
#
# SDIO-based MMC/SD driver
#
# CONFIG_SDIO_DMA
# SDIO driver supports DMA
# CONFIG_MMCSD_MMCSUPPORT
# Enable support for MMC cards
# CONFIG_MMCSD_HAVECARDDETECT
# SDIO driver card detection is 100% accurate
#
CONFIG_SDIO_DMA=n
CONFIG_MMCSD_MMCSUPPORT=n
CONFIG_MMCSD_HAVECARDDETECT=n
#
# TCP/IP and UDP support via uIP
# CONFIG_NET - Enable or disable all network features
# CONFIG_NET_IPv6 - Build in support for IPv6
# CONFIG_NSOCKET_DESCRIPTORS - Maximum number of socket descriptors per task/thread.
# CONFIG_NET_SOCKOPTS - Enable or disable support for socket options
# CONFIG_NET_BUFSIZE - uIP buffer size
# CONFIG_NET_TCP - TCP support on or off
# CONFIG_NET_TCP_CONNS - Maximum number of TCP connections (all tasks)
# CONFIG_NET_TCP_READAHEAD_BUFSIZE - Size of TCP read-ahead buffers
# CONFIG_NET_NTCP_READAHEAD_BUFFERS - Number of TCP read-ahead buffers (may be zero)
# CONFIG_NET_TCPBACKLOG - Incoming connections pend in a backlog until
# accept() is called. The size of the backlog is selected when listen() is called.
# CONFIG_NET_MAX_LISTENPORTS - Maximum number of listening TCP ports (all tasks)
# CONFIG_NET_UDP - UDP support on or off
# CONFIG_NET_UDP_CHECKSUMS - UDP checksums on or off
# CONFIG_NET_UDP_CONNS - The maximum amount of concurrent UDP connections
# CONFIG_NET_ICMP - ICMP ping response support on or off
# CONFIG_NET_ICMP_PING - ICMP ping request support on or off
# CONFIG_NET_PINGADDRCONF - Use "ping" packet for setting IP address
# CONFIG_NET_STATISTICS - uIP statistics on or off
# CONFIG_NET_RECEIVE_WINDOW - The size of the advertised receiver's window
# CONFIG_NET_ARPTAB_SIZE - The size of the ARP table
# CONFIG_NET_BROADCAST - Broadcast support
# CONFIG_NET_FWCACHE_SIZE - number of packets to remember when looking for duplicates
#
CONFIG_NET=n
CONFIG_NET_IPv6=n
CONFIG_NSOCKET_DESCRIPTORS=0
CONFIG_NET_SOCKOPTS=y
CONFIG_NET_BUFSIZE=420
CONFIG_NET_TCP=n
CONFIG_NET_TCP_CONNS=40
CONFIG_NET_MAX_LISTENPORTS=40
CONFIG_NET_UDP=n
CONFIG_NET_UDP_CHECKSUMS=y
#CONFIG_NET_UDP_CONNS=10
CONFIG_NET_ICMP=n
CONFIG_NET_ICMP_PING=n
#CONFIG_NET_PINGADDRCONF=0
CONFIG_NET_STATISTICS=y
#CONFIG_NET_RECEIVE_WINDOW=
#CONFIG_NET_ARPTAB_SIZE=8
CONFIG_NET_BROADCAST=n
#CONFIG_NET_FWCACHE_SIZE=2
#
# UIP Network Utilities
# CONFIG_NET_DHCP_LIGHT - Reduces size of DHCP
# CONFIG_NET_RESOLV_ENTRIES - Number of resolver entries
#
CONFIG_NET_DHCP_LIGHT=n
CONFIG_NET_RESOLV_ENTRIES=4
#
# USB Device Configuration
#
# CONFIG_USBDEV
# Enables USB device support
# CONFIG_USBDEV_ISOCHRONOUS
# Build in extra support for isochronous endpoints
# CONFIG_USBDEV_DUALSPEED
# Hardware handles high and full speed operation (USB 2.0)
# CONFIG_USBDEV_SELFPOWERED
# Will cause USB features to indicate that the device is
# self-powered
# CONFIG_USBDEV_MAXPOWER
# Maximum power consumption in mA
# CONFIG_USBDEV_TRACE
# Enables USB tracing for debug
# CONFIG_USBDEV_TRACE_NRECORDS
# Number of trace entries to remember
#
CONFIG_USBDEV=n
CONFIG_USBDEV_ISOCHRONOUS=n
CONFIG_USBDEV_DUALSPEED=n
CONFIG_USBDEV_SELFPOWERED=y
CONFIG_USBDEV_REMOTEWAKEUP=n
CONFIG_USBDEV_MAXPOWER=100
CONFIG_USBDEV_TRACE=n
CONFIG_USBDEV_TRACE_NRECORDS=128
#
# LPC43xx USB Configuration
#
# CONFIG_LPC43_USBDEV_FRAME_INTERRUPT
# 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_LPC43_USBDEV_EPFAST_INTERRUPT
# Enable high priority interrupts. I have no idea why you might want to
# do that
# CONFIG_LPC43_USBDEV_NDMADESCRIPTORS
# Number of DMA descriptors to allocate in SRAM.
# CONFIG_LPC43_USBDEV_DMA
# Enable lpc43xx-specific DMA support
#
CONFIG_LPC43_USBDEV_FRAME_INTERRUPT=n
CONFIG_LPC43_USBDEV_EPFAST_INTERRUPT=n
CONFIG_LPC43_USBDEV_DMA=n
CONFIG_LPC43_USBDEV_NDMADESCRIPTORS=0
CONFIG_LPC43_USBDEV_DMAINTMASK=0
#
# USB Serial Device Configuration
#
# CONFIG_PL2303
# Enable compilation of the USB serial driver
# CONFIG_PL2303_EPINTIN
# The logical 7-bit address of a hardware endpoint that supports
# interrupt IN operation
# CONFIG_PL2303_EPBULKOUT
# The logical 7-bit address of a hardware endpoint that supports
# bulk OUT operation
# CONFIG_PL2303_EPBULKIN
# The logical 7-bit address of a hardware endpoint that supports
# bulk IN operation
# # CONFIG_PL2303_NWRREQS and CONFIG_PL2303_NRDREQS
# The number of write/read requests that can be in flight
# CONFIG_PL2303_VENDORID and CONFIG_PL2303_VENDORSTR
# The vendor ID code/string
# CONFIG_PL2303_PRODUCTID and CONFIG_PL2303_PRODUCTSTR
# The product ID code/string
# CONFIG_PL2303_RXBUFSIZE and CONFIG_PL2303_TXBUFSIZE
# Size of the serial receive/transmit buffers
#
CONFIG_PL2303=n
CONFIG_PL2303_EPINTIN=1
CONFIG_PL2303_EPBULKOUT=2
CONFIG_PL2303_EPBULKIN=5
CONFIG_PL2303_NWRREQS=4
CONFIG_PL2303_NRDREQS=4
CONFIG_PL2303_VENDORID=0x067b
CONFIG_PL2303_PRODUCTID=0x2303
CONFIG_PL2303_VENDORSTR="Nuttx"
CONFIG_PL2303_PRODUCTSTR="USBdev Serial"
CONFIG_PL2303_RXBUFSIZE=512
CONFIG_PL2303_TXBUFSIZE=512
#
# USB Storage Device Configuration
#
# CONFIG_USBMSC
# Enable compilation of the USB storage driver
# CONFIG_USBMSC_EP0MAXPACKET
# Max packet size for endpoint 0
# CONFIG_USBMSC_EPBULKOUT and CONFIG_USBMSC_EPBULKIN
# The logical 7-bit address of a hardware endpoints that support
# bulk OUT and IN operations
# CONFIG_USBMSC_NWRREQS and CONFIG_USBMSC_NRDREQS
# The number of write/read requests that can be in flight
# CONFIG_USBMSC_BULKINREQLEN and CONFIG_USBMSC_BULKOUTREQLEN
# The size of the buffer in each write/read request. This
# value needs to be at least as large as the endpoint
# maxpacket and ideally as large as a block device sector.
# CONFIG_USBMSC_VENDORID and CONFIG_USBMSC_VENDORSTR
# The vendor ID code/string
# CONFIG_USBMSC_PRODUCTID and CONFIG_USBMSC_PRODUCTSTR
# The product ID code/string
# CONFIG_USBMSC_REMOVABLE
# Select if the media is removable
#
CONFIG_USBMSC=n
CONFIG_USBMSC_EP0MAXPACKET=64
CONFIG_USBMSC_EPBULKOUT=2
CONFIG_USBMSC_EPBULKIN=5
CONFIG_USBMSC_NRDREQS=2
CONFIG_USBMSC_NWRREQS=2
CONFIG_USBMSC_BULKINREQLEN=256
CONFIG_USBMSC_BULKOUTREQLEN=256
CONFIG_USBMSC_VENDORID=0x584e
CONFIG_USBMSC_VENDORSTR="NuttX"
CONFIG_USBMSC_PRODUCTID=0x5342
CONFIG_USBMSC_PRODUCTSTR="USBdev Storage"
CONFIG_USBMSC_VERSIONNO=0x0399
CONFIG_USBMSC_REMOVABLE=y
#
# Settings for examples/uip
#
CONFIG_EXAMPLE_UIP_IPADDR=(10<<24|0<<16|0<<8|2)
CONFIG_EXAMPLE_UIP_DRIPADDR=(10<<24|0<<16|0<<8|1)
CONFIG_EXAMPLE_UIP_NETMASK=(255<<24|255<<16|255<<8|0)
CONFIG_EXAMPLE_UIP_DHCPC=n
#
# Settings for examples/nettest
CONFIG_EXAMPLE_NETTEST_SERVER=n
CONFIG_EXAMPLE_NETTEST_PERFORMANCE=n
CONFIG_EXAMPLE_NETTEST_NOMAC=n
CONFIG_EXAMPLE_NETTEST_IPADDR=(10<<24|0<<16|0<<8|2)
CONFIG_EXAMPLE_NETTEST_DRIPADDR=(10<<24|0<<16|0<<8|1)
CONFIG_EXAMPLE_NETTEST_NETMASK=(255<<24|255<<16|255<<8|0)
CONFIG_EXAMPLE_NETTEST_CLIENTIP=(10<<24|0<<16|0<<8|1)
#
# Settings for examples/ostest
#
CONFIG_EXAMPLES_OSTEST_LOOPS=1
CONFIG_EXAMPLES_OSTEST_STACKSIZE=2048
CONFIG_EXAMPLES_OSTEST_NBARRIER_THREADS=3
#
# Settings for apps/nshlib
#
# CONFIG_NSH_FILEIOSIZE - Size of a static I/O buffer
# CONFIG_NSH_STRERROR - Use strerror(errno)
# CONFIG_NSH_LINELEN - Maximum length of one command line
# CONFIG_NSH_NESTDEPTH - Max number of nested if-then[-else]-fi
# CONFIG_NSH_DISABLESCRIPT - Disable scripting support
# CONFIG_NSH_DISABLEBG - Disable background commands
# CONFIG_NSH_ROMFSETC - Use startup script in /etc
# CONFIG_NSH_CONSOLE - Use serial console front end
# CONFIG_NSH_TELNET - Use telnetd console front end
# CONFIG_NSH_ARCHINIT - Platform provides architecture
# specific initialization (nsh_archinitialize()).
#
# If CONFIG_NSH_TELNET is selected:
# CONFIG_NSH_IOBUFFER_SIZE -- Telnetd I/O buffer size
# CONFIG_NSH_DHCPC - Obtain address using DHCP
# CONFIG_NSH_IPADDR - Provides static IP address
# CONFIG_NSH_DRIPADDR - Provides static router IP address
# CONFIG_NSH_NETMASK - Provides static network mask
# CONFIG_NSH_NOMAC - Use a bogus MAC address
#
# If CONFIG_NSH_ROMFSETC is selected:
# CONFIG_NSH_ROMFSMOUNTPT - ROMFS mountpoint
# CONFIG_NSH_INITSCRIPT - Relative path to init script
# CONFIG_NSH_ROMFSDEVNO - ROMFS RAM device minor
# CONFIG_NSH_ROMFSSECTSIZE - ROMF sector size
# CONFIG_NSH_FATDEVNO - FAT FS RAM device minor
# CONFIG_NSH_FATSECTSIZE - FAT FS sector size
# CONFIG_NSH_FATNSECTORS - FAT FS number of sectors
# CONFIG_NSH_FATMOUNTPT - FAT FS mountpoint
#
CONFIG_NSH_FILEIOSIZE=512
CONFIG_NSH_STRERROR=n
CONFIG_NSH_LINELEN=64
CONFIG_NSH_NESTDEPTH=3
CONFIG_NSH_DISABLESCRIPT=n
CONFIG_NSH_DISABLEBG=n
CONFIG_NSH_ROMFSETC=n
CONFIG_NSH_CONSOLE=y
CONFIG_NSH_TELNET=n
CONFIG_NSH_ARCHINIT=y
CONFIG_NSH_IOBUFFER_SIZE=512
CONFIG_NSH_DHCPC=n
CONFIG_NSH_NOMAC=n
CONFIG_NSH_IPADDR=(10<<24|0<<16|0<<8|2)
CONFIG_NSH_DRIPADDR=(10<<24|0<<16|0<<8|1)
CONFIG_NSH_NETMASK=(255<<24|255<<16|255<<8|0)
CONFIG_NSH_ROMFSMOUNTPT="/etc"
CONFIG_NSH_INITSCRIPT="init.d/rcS"
CONFIG_NSH_ROMFSDEVNO=0
CONFIG_NSH_ROMFSSECTSIZE=64
CONFIG_NSH_FATDEVNO=1
CONFIG_NSH_FATSECTSIZE=512
CONFIG_NSH_FATNSECTORS=1024
CONFIG_NSH_FATMOUNTPT=/tmp
#
# Architecture-specific NSH options
#
CONFIG_NSH_MMCSDSPIPORTNO=0
CONFIG_NSH_MMCSDSLOTNO=0
CONFIG_NSH_MMCSDMINOR=0
#
# Settings for examples/usbserial
#
# CONFIG_EXAMPLES_USBSERIAL_INONLY
# Only verify IN (device-to-host) data transfers. Default: both
# CONFIG_EXAMPLES_USBSERIAL_OUTONLY
# Only verify OUT (host-to-device) data transfers. Default: both
# CONFIG_EXAMPLES_USBSERIAL_ONLYSMALL
# Send only small, single packet messages. Default: Send large and small.
# CONFIG_EXAMPLES_USBSERIAL_ONLYBIG
# Send only large, multi-packet messages. Default: Send large and small.
#
CONFIG_EXAMPLES_USBSERIAL_INONLY=n
CONFIG_EXAMPLES_USBSERIAL_OUTONLY=n
CONFIG_EXAMPLES_USBSERIAL_ONLYSMALL=n
CONFIG_EXAMPLES_USBSERIAL_ONLYBIG=n
CONFIG_EXAMPLES_USBSERIAL_TRACEINIT=n
CONFIG_EXAMPLES_USBSERIAL_TRACECLASS=n
CONFIG_EXAMPLES_USBSERIAL_TRACETRANSFERS=n
CONFIG_EXAMPLES_USBSERIAL_TRACECONTROLLER=n
CONFIG_EXAMPLES_USBSERIAL_TRACEINTERRUPTS=n
#
# Stack and heap information
#
# CONFIG_BOOT_RUNFROMFLASH - Some configurations support XIP
# operation from FLASH but must copy initialized .data sections to RAM.
# (should also be =n for the LPC43xx which always runs from flash)
# CONFIG_BOOT_COPYTORAM - Some configurations boot in FLASH
# but copy themselves entirely into RAM for better performance.
# CONFIG_CUSTOM_STACK - The up_ implementation will handle
# all stack operations outside of the nuttx model.
# CONFIG_STACK_POINTER - The initial stack pointer (arm7tdmi only)
# CONFIG_IDLETHREAD_STACKSIZE - The size of the initial stack.
# This is the thread that (1) performs the inital boot of the system up
# to the point where user_start() is spawned, and (2) there after is the
# IDLE thread that executes only when there is no other thread ready to
# run.
# CONFIG_USERMAIN_STACKSIZE - The size of the stack to allocate
# for the main user thread that begins at the user_start() entry point.
# CONFIG_PTHREAD_STACK_MIN - Minimum pthread stack size
# CONFIG_PTHREAD_STACK_DEFAULT - Default pthread stack size
# CONFIG_HEAP_BASE - The beginning of the heap
# CONFIG_HEAP_SIZE - The size of the heap
#
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=

View File

@ -0,0 +1,58 @@
#!/bin/bash
# configs/lpc4330-xplorer/ostest/setenv.sh
#
# Copyright (C) 2010 Gregory Nutt. All rights reserved.
# Author: Gregory Nutt <spudmonkey@racsa.co.cr>
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions
# are met:
#
# 1. Redistributions of source code must retain the above copyright
# notice, this list of conditions and the following disclaimer.
# 2. Redistributions in binary form must reproduce the above copyright
# notice, this list of conditions and the following disclaimer in
# the documentation and/or other materials provided with the
# distribution.
# 3. Neither the name NuttX nor the names of its contributors may be
# used to endorse or promote products derived from this software
# without specific prior written permission.
#
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
# POSSIBILITY OF SUCH DAMAGE.
#
if [ "$_" = "$0" ] ; then
echo "You must source this script, not run it!" 1>&2
exit 1
fi
WD=`pwd`
if [ ! -x "setenv.sh" ]; then
echo "This script must be executed from the top-level NuttX build directory"
exit 1
fi
if [ -z "${PATH_ORIG}" ]; then
export PATH_ORIG="${PATH}"
fi
# TOOLCHAIN_BIN must be defined to the full path to the location where you
# have installed the toolchain of your choice. Modify the following:
export TOOLCHAIN_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
# Andd add the toolchain path to the PATH variable
export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
echo "PATH : ${PATH}"

View File

@ -0,0 +1,110 @@
/****************************************************************************
* configs/lpc4330-xplorer/scripts/ld.script
*
* Copyright (C) 2012 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name NuttX nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
/* The LPC4330 on the LPC4330-Xplorer has 4096Kb of SPIFI FLASH beginning at
* address 0x1400:0000 and 264K of total SRAM: 128Kb of SRAM in the CPU block
* beginning at address 0x1000:0000, 72Kb beginning at address 0x1008:0000 and
* 64Kb of AHB SRAM in three banks beginning at addresses 0x2000:0000,
* 0x2000:8000 and 0x2000:C000. Here we assume that .data and .bss will all
* fit into the 128Kb CPU SRAM address range.
*/
MEMORY
{
flash (rx) : ORIGIN = 0x1c000000, LENGTH = 1024K
sram (rwx) : ORIGIN = 0x10000000, LENGTH = 96K
}
OUTPUT_ARCH(arm)
ENTRY(_stext)
SECTIONS
{
.text : {
_stext = ABSOLUTE(.);
*(.vectors)
*(.text .text.*)
*(.fixup)
*(.gnu.warning)
*(.rodata .rodata.*)
*(.gnu.linkonce.t.*)
*(.glue_7)
*(.glue_7t)
*(.got)
*(.gcc_except_table)
*(.gnu.linkonce.r.*)
_etext = ABSOLUTE(.);
} > flash
_eronly = ABSOLUTE(.); /* See below */
.data : {
_sdata = ABSOLUTE(.);
*(.data .data.*)
*(.gnu.linkonce.d.*)
CONSTRUCTORS
_edata = ABSOLUTE(.);
} > sram AT > flash
.ARM.extab : {
*(.ARM.extab*)
} >sram
.ARM.exidx : {
__exidx_start = ABSOLUTE(.);
*(.ARM.exidx*)
__exidx_end = ABSOLUTE(.);
} >sram
.bss : { /* BSS */
_sbss = ABSOLUTE(.);
*(.bss .bss.*)
*(.gnu.linkonce.b.*)
*(COMMON)
_ebss = ABSOLUTE(.);
} > sram
/* Stabs debugging sections. */
.stab 0 : { *(.stab) }
.stabstr 0 : { *(.stabstr) }
.stab.excl 0 : { *(.stab.excl) }
.stab.exclstr 0 : { *(.stab.exclstr) }
.stab.index 0 : { *(.stab.index) }
.stab.indexstr 0 : { *(.stab.indexstr) }
.comment 0 : { *(.comment) }
.debug_abbrev 0 : { *(.debug_abbrev) }
.debug_info 0 : { *(.debug_info) }
.debug_line 0 : { *(.debug_line) }
.debug_pubnames 0 : { *(.debug_pubnames) }
.debug_aranges 0 : { *(.debug_aranges) }
}

View File

@ -0,0 +1,96 @@
############################################################################
# configs/lpc4330-xplorer/src/Makefile
#
# Copyright (C) 2012 Gregory Nutt. All rights reserved.
# Author: Gregory Nutt <gnutt@nuttx.org>
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions
# are met:
#
# 1. Redistributions of source code must retain the above copyright
# notice, this list of conditions and the following disclaimer.
# 2. Redistributions in binary form must reproduce the above copyright
# notice, this list of conditions and the following disclaimer in
# the documentation and/or other materials provided with the
# distribution.
# 3. Neither the name NuttX nor the names of its contributors may be
# used to endorse or promote products derived from this software
# without specific prior written permission.
#
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
# POSSIBILITY OF SUCH DAMAGE.
#
############################################################################
-include $(TOPDIR)/Make.defs
CFLAGS += -I$(TOPDIR)/sched
ASRCS =
CSRCS = up_boot.c up_leds.c
ifeq ($(CONFIG_NSH_ARCHINIT),y)
CSRCS += up_nsh.c
endif
ifeq ($(CONFIG_USBMSC),y)
CSRCS += up_usbmsc.c
endif
ifeq ($(CONFIG_ARCH_BUTTONS),y)
CSRCS += up_buttons.c
endif
AOBJS = $(ASRCS:.S=$(OBJEXT))
COBJS = $(CSRCS:.c=$(OBJEXT))
SRCS = $(ASRCS) $(CSRCS)
OBJS = $(AOBJS) $(COBJS)
ARCH_SRCDIR = $(TOPDIR)/arch/$(CONFIG_ARCH)/src
ifeq ($(WINTOOL),y)
CFLAGS += -I "${shell cygpath -w $(ARCH_SRCDIR)/chip}" \
-I "${shell cygpath -w $(ARCH_SRCDIR)/common}" \
-I "${shell cygpath -w $(ARCH_SRCDIR)/armv7-m}"
else
CFLAGS += -I$(ARCH_SRCDIR)/chip -I$(ARCH_SRCDIR)/common -I$(ARCH_SRCDIR)/armv7-m
endif
all: libboard$(LIBEXT)
$(AOBJS): %$(OBJEXT): %.S
$(call ASSEMBLE, $<, $@)
$(COBJS) $(LINKOBJS): %$(OBJEXT): %.c
$(call COMPILE, $<, $@)
libboard$(LIBEXT): $(OBJS)
@( for obj in $(OBJS) ; do \
$(call ARCHIVE, $@, $${obj}); \
done ; )
.depend: Makefile $(SRCS)
@$(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
@touch $@
depend: .depend
clean:
@rm -f libboard$(LIBEXT) *~ .*.swp
$(call CLEAN)
distclean: clean
@rm -f Make.dep .depend
-include Make.dep

View File

@ -0,0 +1,104 @@
/****************************************************************************
* configs/lpc4330-xplorer/src/lpc4330_xplorer_internal.h
* arch/arm/src/board/lpc4330-xplorer_internal.n
*
* Copyright (C) 2012 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name NuttX nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
#ifndef _CONFIGS_LPC4330_XPLORER_SRC_LPC4330_XPLORER_INTERNAL_H
#define _CONFIGS_LPC4330_XPLORER_SRC_LPC4330_XPLORER_INTERNAL_H
/****************************************************************************
* Included Files
****************************************************************************/
#include <nuttx/config.h>
#include <nuttx/compiler.h>
/****************************************************************************
* Definitions
****************************************************************************/
/****************************************************************************
* LEDs GPIO PIN SIGNAL NAME
* -------------------------------- ------- --------------
* gpio1[12] - LED D2 J10-20 LED1
* gpio1[11] - LED D3 J10-17 LED2
****************************************************************************/
#define LPC4330_XPLORER_LED1 (GPIO_OUTPUT | GPIO_PORT1 | GPIO_PIN12)
#define LPC4330_XPLORER_LED1_OFF LPC4330_XPLORER_LED1
#define LPC4330_XPLORER_LED1_ON (LPC4330_XPLORER_LED1 | GPIO_VALUE_ONE)
#define LPC4330_XPLORER_LED2 (GPIO_OUTPUT | GPIO_PORT1 | GPIO_PIN11)
#define LPC4330_XPLORER_LED2_OFF LPC4330_XPLORER_LED2
#define LPC4330_XPLORER_LED2_ON (LPC4330_XPLORER_LED2 | GPIO_VALUE_ONE)
#define LPC4330_XPLORER_HEARTBEAT LPC4330_XPLORER_LED2
/****************************************************************************
* Buttons GPIO PIN SIGNAL NAME
* -------------------------------- ------- --------------
* gpio0[7] - User Button SW2 J8-25 BTN1
****************************************************************************/
#define LPC4330_XPLORER_BUT1 (GPIO_INTBOTH | GPIO_FLOAT | GPIO_PORT0 | GPIO_PIN7)
/* Button IRQ numbers */
#define LPC4330_XPLORER_BUT1_IRQ LPC43_IRQ_P0p23
/****************************************************************************
* Public Types
****************************************************************************/
/****************************************************************************
* Public data
****************************************************************************/
#ifndef __ASSEMBLY__
/****************************************************************************
* Public Functions
****************************************************************************/
/****************************************************************************
* Name: lpc43_sspinitialize
*
* Description:
* Called to configure SPI chip select GPIO pins for the Lincoln 80 board.
*
****************************************************************************/
extern void weak_function lpc43_sspinitialize(void);
#endif /* __ASSEMBLY__ */
#endif /* _CONFIGS_LPC4330_XPLORER_SRC_LPC4330_XPLORER_INTERNAL_H */

View File

@ -0,0 +1,82 @@
/************************************************************************************
* configs/lpc4330-xplorer/src/up_boot.c
* arch/arm/src/board/up_boot.c
*
* Copyright (C) 2012 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name NuttX nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
************************************************************************************/
/************************************************************************************
* Included Files
************************************************************************************/
#include <nuttx/config.h>
#include <debug.h>
#include <arch/board/board.h>
#include "up_arch.h"
#include "up_internal.h"
#include "lpc43_internal.h"
#include "lpc4330_xplorer_internal.h"
/************************************************************************************
* Definitions
************************************************************************************/
/************************************************************************************
* Private Functions
************************************************************************************/
/************************************************************************************
* Public Functions
************************************************************************************/
/************************************************************************************
* Name: lpc43_boardinitialize
*
* Description:
* All LPC43xx architectures must provide the following entry point. This entry point
* is called early in the intitialization -- after all memory has been configured
* and mapped but before any devices have been initialized.
*
************************************************************************************/
void lpc43_boardinitialize(void)
{
/* Configure on-board LEDs if LED support has been selected. */
#ifdef CONFIG_ARCH_LEDS
up_ledinit();
#endif
}

View File

@ -0,0 +1,225 @@
/****************************************************************************
* configs/lpc4330-xplorer/src/up_buttons.c
*
* Copyright (C) 2012 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name NuttX nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
/****************************************************************************
* Included Files
****************************************************************************/
#include <nuttx/config.h>
#include <stdint.h>
#include <stdbool.h>
#include <nuttx/arch.h>
#include <nuttx/irq.h>
#include <arch/board/board.h>
#include "lpc43_internal.h"
#include "lpc4330_xplorer_internal.h"
#ifdef CONFIG_ARCH_BUTTONS
/****************************************************************************
* Definitions
****************************************************************************/
/****************************************************************************
* Private Data
****************************************************************************/
/* Pin configuration for each STM3210E-EVAL button. This array is indexed by
* the BUTTON_* and JOYSTICK_* definitions in board.h
*/
static const uint16_t g_buttoncfg[BOARD_NUM_BUTTONS] =
{
LPC4330_XPLORER_BUT1
};
/* This array defines all of the interupt handlers current attached to
* button events.
*/
#if defined(CONFIG_ARCH_IRQBUTTONS) && defined(CONFIG_GPIO_IRQ)
static xcpt_t g_buttonisr[BOARD_NUM_BUTTONS];
/* This array provides the mapping from button ID numbers to button IRQ
* numbers.
*/
static uint8_t g_buttonirq[BOARD_NUM_BUTTONS] =
{
LPC4330_XPLORER_BUT1_IRQ
};
#endif
/****************************************************************************
* Private Functions
****************************************************************************/
/****************************************************************************
* Public Functions
****************************************************************************/
/****************************************************************************
* Name: up_buttoninit
*
* Description:
* up_buttoninit() must be called to initialize button resources. After
* that, up_buttons() may be called to collect the current state of all
* buttons or up_irqbutton() may be called to register button interrupt
* handlers.
*
****************************************************************************/
void up_buttoninit(void)
{
int i;
/* Configure the GPIO pins as interrupting inputs. */
for (i = 0; i < BOARD_NUM_BUTTONS; i++)
{
lpc43_configgpio(g_buttoncfg[i]);
}
}
/****************************************************************************
* Name: up_buttons
*
* Description:
* up_buttoninit() must be called to initialize button resources. After
* that, up_buttons() may be called to collect the current state of all
* buttons.
*
* up_buttons() may be called at any time to harvest the state of every
* button. The state of the buttons is returned as a bitset with one
* bit corresponding to each button: If the bit is set, then the button
* is pressed. See the BOARD_BUTTON_*_BIT and BOARD_JOYSTICK_*_BIT
* definitions in board.h for the meaning of each bit.
*
****************************************************************************/
uint8_t up_buttons(void)
{
uint8_t ret = 0;
int i;
/* Check that state of each key */
for (i = 0; i < BOARD_NUM_BUTTONS; i++)
{
/* A LOW value means that the key is pressed. */
bool released = lpc43_gpioread(g_buttoncfg[i]);
/* Accumulate the set of depressed (not released) keys */
if (!released)
{
ret |= (1 << i);
}
}
return ret;
}
/****************************************************************************
* Button support.
*
* Description:
* up_buttoninit() must be called to initialize button resources. After
* that, up_irqbutton() may be called to register button interrupt handlers.
*
* up_irqbutton() may be called to register an interrupt handler that will
* be called when a button is depressed or released. The ID value is a
* button enumeration value that uniquely identifies a button resource. See the
* BOARD_BUTTON_* and BOARD_JOYSTICK_* definitions in board.h for the meaning
* of enumeration values. The previous interrupt handler address is returned
* (so that it may restored, if so desired).
*
* Note that up_irqbutton() also enables button interrupts. Button
* interrupts will remain enabled after the interrupt handler is attached.
* Interrupts may be disabled (and detached) by calling up_irqbutton with
* irqhandler equal to NULL.
*
****************************************************************************/
#if defined(CONFIG_ARCH_IRQBUTTONS) && defined(CONFIG_GPIO_IRQ)
xcpt_t up_irqbutton(int id, xcpt_t irqhandler)
{
xcpt_t oldhandler = NULL;
irqstate_t flags;
int irq;
/* Verify that the button ID is within range */
if ((unsigned)id < BOARD_NUM_BUTTONS)
{
/* Return the current button handler and set the new interrupt handler */
oldhandler = g_buttonisr[id];
g_buttonisr[id] = irqhandler;
/* Disable interrupts until we are done */
flags = irqsave();
/* Configure the interrupt. Either attach and enable the new
* interrupt or disable and detach the old interrupt handler.
*/
irq = g_buttonirq[id];
if (irqhandler)
{
/* Attach then enable the new interrupt handler */
(void)irq_attach(irq, irqhandler);
up_enable_irq(irq);
}
else
{
/* Disable then then detach the the old interrupt handler */
up_disable_irq(irq);
(void)irq_detach(irq);
}
irqrestore(flags);
}
return oldhandler;
}
#endif
#endif /* CONFIG_ARCH_BUTTONS */

View File

@ -0,0 +1,219 @@
/****************************************************************************
* configs/lpc4330-xplorer/src/up_leds.c
* arch/arm/src/board/up_leds.c
*
* Copyright (C) 2012 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name NuttX nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
/****************************************************************************
* Included Files
****************************************************************************/
#include <nuttx/config.h>
#include <stdint.h>
#include <stdbool.h>
#include <debug.h>
#include <arch/board/board.h>
#include "chip.h"
#include "up_arch.h"
#include "up_internal.h"
#include "lpc43_internal.h"
#include "lpc4330_xplorer_internal.h"
#ifdef CONFIG_ARCH_LEDS
/****************************************************************************
* Definitions
****************************************************************************/
/* Enables debug output from this file (needs CONFIG_DEBUG with
* CONFIG_DEBUG_VERBOSE too)
*/
#undef LED_DEBUG /* Define to enable debug */
#undef LED_VERBOSE /* Define to enable verbose debug */
#ifdef LED_DEBUG
# define leddbg lldbg
# ifdef LED_VERBOSE
# define ledvdbg lldbg
# else
# define ledvdbg(x...)
# endif
#else
# undef LED_VERBOSE
# define leddbg(x...)
# define ledvdbg(x...)
#endif
/* Dump GPIO registers */
#ifdef LED_VERBOSE
# define led_dumpgpio(m) lpc43_dumpgpio(LPC4330_XPLORER_LED2, m)
#else
# define led_dumpgpio(m)
#endif
/****************************************************************************
* Private Data
****************************************************************************/
/* LED definitions ******************************************************************
The LPC4330-Xplorer has 2 LEDs along the bottom of the board. Green or off.
If CONFIG_ARCH_LEDS is defined, the LEDs will be controlled as follows for NuttX
debug functionality (where NC means "No Change").
During the boot phases. LED1 and LED2 will show boot status.
LED1 LED2
STARTED OFF OFF
HEAPALLOCATE BLUE OFF
IRQSENABLED OFF BLUE
STACKCREATED OFF OFF
After the system is booted, this logic will no longer use LEDs 1 & 2. They
are available for use by applications using lpc43_led (prototyped below)
*/
static bool g_initialized;
static int g_nestcount;
/****************************************************************************
* Private Functions
****************************************************************************/
/****************************************************************************
* Public Functions
****************************************************************************/
/****************************************************************************
* Name: up_ledinit
****************************************************************************/
void up_ledinit(void)
{
/* Configure all LED GPIO lines */
led_dumpgpio("up_ledinit() Entry)");
lpc43_configgpio(LPC4330_XPLORER_LED1);
lpc43_configgpio(LPC4330_XPLORER_LED2);
led_dumpgpio("up_ledinit() Exit");
}
/****************************************************************************
* Name: up_ledon
****************************************************************************/
void up_ledon(int led)
{
/* We will control LED1 and LED2 not yet completed the boot sequence. */
if (!g_initialized)
{
int led1 = 0;
int led2 = 0;
switch (led)
{
case LED_STACKCREATED:
g_initialized = true;
case LED_STARTED:
default:
break;
case LED_HEAPALLOCATE:
led1 = 1;
break;
case LED_IRQSENABLED:
led2 = 1;
}
lpc43_led(LPC4330_XPLORER_LED1,led1);
lpc43_led(LPC4330_XPLORER_LED2,led2);
}
/* We will always control the HB LED */
switch (led)
{
case LED_INIRQ:
case LED_SIGNAL:
case LED_ASSERTION:
case LED_PANIC:
lpc43_gpiowrite(LPC4330_XPLORER_HEARTBEAT, false);
g_nestcount++;
default:
break;
}
}
/****************************************************************************
* Name: up_ledoff
****************************************************************************/
void up_ledoff(int led)
{
/* In all states, OFF can only mean turning off the HB LED */
if (g_nestcount <= 1)
{
lpc43_led(LPC4330_XPLORER_HEARTBEAT, true);
g_nestcount = 0;
}
else
{
g_nestcount--;
}
}
/************************************************************************************
* Name: lpc43_led
*
* Description:
* Once the system has booted, these functions can be used to control the LEDs
*
************************************************************************************/
void lpc43_led(int lednum, int state)
{
lpc43_gpiowrite(lednum, state);
}
#endif /* CONFIG_ARCH_LEDS */

View File

@ -0,0 +1,102 @@
/****************************************************************************
* config/lpc4330-xplorer/src/up_nsh.c
* arch/arm/src/board/up_nsh.c
*
* Copyright (C) 2012 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name NuttX nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
/****************************************************************************
* Included Files
****************************************************************************/
#include <nuttx/config.h>
#include <stdio.h>
#include <debug.h>
#include <errno.h>
#include <nuttx/spi.h>
#include <nuttx/mmcsd.h>
/****************************************************************************
* Pre-Processor Definitions
****************************************************************************/
/* Configuration ************************************************************/
/* PORT and SLOT number probably depend on the board configuration */
#ifdef CONFIG_ARCH_BOARD_LPC4330_XPLORER
# define CONFIG_NSH_HAVEUSBDEV 1
#else
# error "Unrecognized board"
# undef CONFIG_NSH_HAVEUSBDEV
#endif
/* Can't support USB features if USB is not enabled */
#ifndef CONFIG_USBDEV
# undef CONFIG_NSH_HAVEUSBDEV
#endif
/* Debug ********************************************************************/
#ifdef CONFIG_CPP_HAVE_VARARGS
# ifdef CONFIG_DEBUG
# define message(...) lib_lowprintf(__VA_ARGS__)
# else
# define message(...) printf(__VA_ARGS__)
# endif
#else
# ifdef CONFIG_DEBUG
# define message lib_lowprintf
# else
# define message printf
# endif
#endif
/****************************************************************************
* Public Functions
****************************************************************************/
/****************************************************************************
* Name: nsh_archinitialize
*
* Description:
* Perform architecture specific initialization
*
****************************************************************************/
int nsh_archinitialize(void)
{
return OK;
}