lpc2378 port contributed by Rommel Marcelo
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@2579 42af7a65-404d-4744-a932-0658087f49c3
This commit is contained in:
parent
5e32ac3abd
commit
75ed1a4ff6
63
arch/arm/src/lpc2378/Make.defs
Executable file
63
arch/arm/src/lpc2378/Make.defs
Executable file
@ -0,0 +1,63 @@
|
||||
##############################################################################
|
||||
# lpc23xx/Make.defs
|
||||
#
|
||||
# Copyright (C) 2010 Rommel Marcelo. All rights reserved.
|
||||
# Author: Rommel Marcelo
|
||||
#
|
||||
# This file is part of the NuttX RTOS and based on the lpc2148 port:
|
||||
#
|
||||
# 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.
|
||||
#
|
||||
##############################################################################
|
||||
|
||||
HEAD_ASRC = lpc23xx_head.S
|
||||
|
||||
CMN_ASRCS = up_saveusercontext.S up_fullcontextrestore.S up_vectors.S
|
||||
CMN_CSRCS = up_allocateheap.c up_assert.c up_blocktask.c up_copystate.c \
|
||||
up_createstack.c up_dataabort.c up_mdelay.c up_udelay.c \
|
||||
up_exit.c up_idle.c up_initialize.c up_initialstate.c \
|
||||
up_interruptcontext.c up_prefetchabort.c up_releasepending.c \
|
||||
up_releasestack.c up_reprioritizertr.c up_syscall.c up_unblocktask.c \
|
||||
up_undefinedinsn.c up_usestack.c up_lowputs.c
|
||||
|
||||
ifneq ($(CONFIG_DISABLE_SIGNALS),y)
|
||||
CMN_CSRCS += up_schedulesigaction.c up_sigdeliver.c
|
||||
endif
|
||||
|
||||
CHIP_ASRCS = lpc23xx_lowputc.S
|
||||
CHIP_CSRCS = lpc23xx_pllsetup.c lpc23xx_decodeirq.c lpc23xx_irq.c lpc23xx_timerisr.c \
|
||||
lpc23xx_serial.c lpc23xx_io.c
|
||||
|
||||
|
||||
ifeq ($(CONFIG_USBDEV),y)
|
||||
#CHIP_CSRCS += lpc23xx_usbdev.c
|
||||
endif
|
||||
|
959
arch/arm/src/lpc2378/chip.h
Executable file
959
arch/arm/src/lpc2378/chip.h
Executable file
@ -0,0 +1,959 @@
|
||||
/****************************************************************************************************
|
||||
* arch/arm/src/lpc2378/chip.h
|
||||
*
|
||||
* Copyright (C) 2010 Rommel Marcelo. All rights reserved.
|
||||
* Author: Rommel Marcelo
|
||||
*
|
||||
* This file is part of the NuttX RTOS and based on the lpc2148 port:
|
||||
*
|
||||
* 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.
|
||||
*
|
||||
****************************************************************************************************/
|
||||
|
||||
#ifndef _ARCH_ARM_SRC_LPC2378_CHIP_H
|
||||
#define _ARCH_ARM_SRC_LPC2378_CHIP_H
|
||||
|
||||
/****************************************************************************************************
|
||||
* Included Files
|
||||
****************************************************************************************************/
|
||||
|
||||
#include <sys/types.h>
|
||||
|
||||
/****************************************************************************************************
|
||||
* Pre-processor Definitions
|
||||
****************************************************************************************************/
|
||||
|
||||
/* Memory Map ***************************************************************************************/
|
||||
|
||||
#define LPC23XX_FLASH_BASE 0x00000000
|
||||
#define LPC23XX_FIO_BASE 0x3fffc000
|
||||
#define LPC23XX_ONCHIP_RAM_BASE 0x40000000
|
||||
#define LPC23XX_USBDMA_RAM_BASE 0x7fd00000
|
||||
#define LPC23XX_ETHERNET_RAM_BASE 0x7fe00000
|
||||
#define LPC23XX_BOOT_BLOCK 0x7fffd000
|
||||
#define LPC23XX_EXTMEM_BASE 0x80000000
|
||||
#define LPC23XX_APB_BASE 0xe0000000
|
||||
#define LPC23XX_AHB_BASE 0xf0000000
|
||||
|
||||
/* Peripheral Registers ****************************************************************************/
|
||||
|
||||
/* APB Register block base addresses */
|
||||
|
||||
#define LPC23XX_WD_BASE 0xe0000000 /* Watchdog base address */
|
||||
#define LPC23XX_TMR0_BASE 0xE0004000 /* Timer 0 base address*/
|
||||
#define LPC23XX_TMR1_BASE 0xe0008000 /* Timer 1 base address */
|
||||
#define LPC23XX_UART0_BASE 0xe000c000 /* UART0 base address */
|
||||
#define LPC23XX_UART1_BASE 0xe0010000 /* UART1 base address */
|
||||
#define LPC23XX_PWM_BASE 0xe0018000 /* Pulse width modulator (PWM) base address */
|
||||
#define LPC23XX_I2C0_BASE 0xe001c000 /* I2C0 base address */
|
||||
#define LPC23XX_SPI0_BASE 0xe0020000 /* Serial Peripheral Interface 0 (SPI0) base */
|
||||
#define LPC23XX_RTC_BASE 0xe0024000 /* Real Time Clock (RTC) base address */
|
||||
#define LPC23XX_GPIO0_BASE 0xe0028000 /* General Purpose I/O (GPIO) 0 base address */
|
||||
#define LPC23XX_GPIO1_BASE 0xe0028010 /* General Purpose I/O (GPIO) 1 base address */
|
||||
#define LPC23XX_PINSEL_BASE 0xe002c000 /* Pin function select registers */
|
||||
#define LPC23XX_SSP1_BASE 0xe0030000 /* Synchronous Serial Port 1 base address */
|
||||
#define LPC23XX_AD0_BASE 0xe0034000 /* Analog to Digital Converter 0 base address*/
|
||||
//~ #define LPC23XX_CAN_ACCEPT_RAM_BASE 0xe0038000 /* CAN Acceptance Filter RAM base address*/
|
||||
#define LPC23XX_CAN_ACCEPT_BASE 0xE003C000 /* CAN Acceptance Filter Register base address*/
|
||||
#define LPC23XX_CAN_COMMON_BASE 0xe0040000 /* CAN Common Register base address*/
|
||||
#define LPC23XX_CAN1_BASE 0xe0044000 /* CAN 1 Controller base address*/
|
||||
#define LPC23XX_CAN2_BASE 0xe0048000 /* CAN 2 Controller base address*/
|
||||
#define LPC23XX_I2C1_BASE 0xe005c000 /* I2C1 base address */
|
||||
#define LPC23XX_SSP0_BASE 0xE0068000 /* Synchronous Serial Port 0 base address */
|
||||
#define LPC23XX_DAC_BASE 0xE006C000 /* DAC base address */
|
||||
#define LPC23XX_TMR2_BASE 0xE0070000 /* Timer 2 base address */
|
||||
#define LPC23XX_TMR3_BASE 0xE0074000 /* Timer 3 base address */
|
||||
#define LPC23XX_UART2_BASE 0xE0078000 /* UART2 base address */
|
||||
#define LPC23XX_UART3_BASE 0xE007C000 /* UART3 base address */
|
||||
#define LPC23XX_I2C2_BASE 0xE0080000 /* I2C2 base address */
|
||||
#define LPC23XX_BATT_RAM_BASE 0xE0084000 /* Battery RAM base address */
|
||||
#define LPC23XX_I2S_BASE 0xE0088000 /* I2S base address */
|
||||
#define LPC23XX_MCI_BASE 0xE008C000 /* SD/MMC Card Interface base address */
|
||||
//~ #define LPC23XX_SPI1_BASE 0xe0068000 /* Serial Peripheral Interface 1 (SPI1) base */
|
||||
#define LPC23XX_EMAC_BASE 0xFFE00000 /* Ethernet MAC base address */
|
||||
#define LPC23XX_USB_BASE 0xFFE0C200 /* USB base address */
|
||||
#define LPC23XX_SCB_BASE 0xE01FC000 /* System Control Block (SBC) base address */
|
||||
#define LPC23XX_EXT_BASE 0xe01fc140 /* External Interrupt base address */
|
||||
|
||||
/* AHB Register block base addresses */
|
||||
|
||||
#define LPC23XX_EMC_BASE 0xFFE08000 /* External Memory Controller (EMC) base address */
|
||||
#define LPC23XX_VIC_BASE 0xFFFFF000 /* Vectored Interrupt Controller (VIC) Base */
|
||||
#define LPC23XX_GPDMA_BASE 0xFFE04000 /* General Purpose DMA */
|
||||
|
||||
|
||||
/* Watchdog Register Offsets */
|
||||
#define WD_MOD_OFFSET 0x00 /* Watchdog Mode Register */
|
||||
#define WD_TC_OFFSET 0x04 /* Watchdog Time Constant Register */
|
||||
#define WD_FEED_OFFSET 0x08 /* Watchdog Feed Register */
|
||||
#define WD_TV_OFFSET 0x0C /* Watchdog Time Value Register */
|
||||
|
||||
/* Timers Base Addresses */
|
||||
#define TMR0_BASE_ADDR 0xE0004000
|
||||
#define TMR1_BASE_ADDR 0xE0008000
|
||||
#define TMR2_BASE_ADDR 0xE0070000
|
||||
#define TMR3_BASE_ADDR 0xE0074000
|
||||
/* Timer 0/1/2/3 register offsets */
|
||||
#define TMR_IR_OFFSET 0x00 /* RW:Interrupt Register */
|
||||
#define TMR_TCR_OFFSET 0x04 /* RW: Timer Control Register */
|
||||
#define TMR_TC_OFFSET 0x08 /* RW: Timer Counter */
|
||||
#define TMR_PR_OFFSET 0x0c /* RW: Prescale Register */
|
||||
#define TMR_PC_OFFSET 0x10 /* RW: Prescale Counter Register */
|
||||
#define TMR_MCR_OFFSET 0x14 /* RW: Match Control Register */
|
||||
#define TMR_MR0_OFFSET 0x18 /* RW: Match Register 0 */
|
||||
#define TMR_MR1_OFFSET 0x1c /* RW: Match Register 1 */
|
||||
#define TMR_MR2_OFFSET 0x20 /* RW: Match Register 2 */
|
||||
#define TMR_MR3_OFFSET 0x24 /* RW: Match Register 3 */
|
||||
#define TMR_CCR_OFFSET 0x28 /* RW: Capture Control Register */
|
||||
#define TMR_CR0_OFFSET 0x2c /* R: Capture Register 0 */
|
||||
#define TMR_CR1_OFFSET 0x30 /* R: Capture Register 1 */
|
||||
#define TMR_CR2_OFFSET 0x34 /* R: Capture Register 2 */
|
||||
#define TMR_CR3_OFFSET 0x38 /* RW: Capture Register 3 */
|
||||
#define TMR_EMR_OFFSET 0x3c /* RW: External Match Register */
|
||||
#define TMR_CTCR_OFFSET 0x70 /* RW: Count Control Register */
|
||||
|
||||
/* Universal Asynchronous Receiver Transmitter Base Addresses */
|
||||
#define UART0_BASE_ADDR 0xE000C000
|
||||
#define UART1_BASE_ADDR 0xE0010000
|
||||
#define UART2_BASE_ADDR 0xE0078000
|
||||
#define UART3_BASE_ADDR 0xE007C000
|
||||
/* UART 0/1/2/3 Register Offsets */
|
||||
#define UART_RBR_OFFSET 0x00 /* R: Receive Buffer Register (DLAB=0) */
|
||||
#define UART_THR_OFFSET 0x00 /* W: Transmit Holding Register (DLAB=0) */
|
||||
#define UART_DLL_OFFSET 0x00 /* W: Divisor Latch Register (LSB, DLAB=1) */
|
||||
#define UART_IER_OFFSET 0x04 /* W: Interrupt Enable Register (DLAB=0) */
|
||||
#define UART_DLM_OFFSET 0x04 /* RW: Divisor Latch Register (MSB, DLAB=1) */
|
||||
#define UART_IIR_OFFSET 0x08 /* R: Interrupt ID Register */
|
||||
#define UART_FCR_OFFSET 0x08 /* W: FIFO Control Register */
|
||||
#define UART_LCR_OFFSET 0x0c /* RW: Line Control Register */
|
||||
#define UART_MCR_OFFSET 0x10 /* RW: Modem Control REgister (2146/6/8 UART1 Only) */
|
||||
#define UART_LSR_OFFSET 0x14 /* R: Scratch Pad Register */
|
||||
#define UART_MSR_OFFSET 0x18 /* RW: MODEM Status Register (2146/6/8 UART1 Only) */
|
||||
#define UART_SCR_OFFSET 0x1c /* RW: Line Status Register */
|
||||
#define UART_ACR_OFFSET 0x20 /* RW: Autobaud Control Register */
|
||||
#define UART_FDR_OFFSET 0x28 /* RW: Fractional Divider Register */
|
||||
#define UART_TER_OFFSET 0x30 /* RW: Transmit Enable Register */
|
||||
|
||||
|
||||
/* Pulse Width Modulation Base Address */
|
||||
#define PWM1_BASE_ADDR 0xE0018000
|
||||
/* PWM register offsets */
|
||||
#define PWM_IR_OFFSET 0x00 /* Interrupt Register */
|
||||
#define PWM_TCR_OFFSET 0x04 /* Timer Control Register */
|
||||
#define PWM_TC_OFFSET 0x08 /* Timer Counter */
|
||||
#define PWM_PR_OFFSET 0x0c /* Prescale Register */
|
||||
#define PWM_PC_OFFSET 0x10 /* Prescale Counter Register */
|
||||
#define PWM_MCR_OFFSET 0x14 /* Match Control Register */
|
||||
#define PWM_MR0_OFFSET 0x18 /* Match Register 0 */
|
||||
#define PWM_MR1_OFFSET 0x1c /* Match Register 1 */
|
||||
#define PWM_MR2_OFFSET 0x20 /* Match Register 2 */
|
||||
#define PWM_MR3_OFFSET 0x24 /* Match Register 3 */
|
||||
#define PWM_CCR_OFFSET 0x28 /* Capture Control Register*/
|
||||
#define PWM_CCR0_OFFSET 0x2C /* Capture Register 0 */
|
||||
#define PWM_CCR1_OFFSET 0x30 /* Capture Register 1 */
|
||||
#define PWM_CCR2_OFFSET 0x34 /* Capture Register 2 */
|
||||
#define PWM_CCR3_OFFSET 0x38 /* Capture Register 3 */
|
||||
#define PWM_EMR_OFFSET 0x3C /* */
|
||||
#define PWM_MR4_OFFSET 0x40 /* Match Register 4 */
|
||||
#define PWM_MR5_OFFSET 0x44 /* Match Register 5 */
|
||||
#define PWM_MR6_OFFSET 0x48 /* Match Register 6 */
|
||||
#define PWM_PCR_OFFSET 0x4c /* Control Register */
|
||||
#define PWM_LER_OFFSET 0x50 /* Latch Enable Register */
|
||||
#define PWM_CTCR_OFFSET 0x70
|
||||
|
||||
/* I2C Base Addresses */
|
||||
#define I2C0_BASE_ADDR 0xE001C000
|
||||
#define I2C1_BASE_ADDR 0xE005C000
|
||||
#define I2C2_BASE_ADDR 0xE0080000
|
||||
/* I2C 0/1/2 register offsets */
|
||||
#define I2C_CONSET_OFFSET 0x00 /* Control Set Register */
|
||||
#define I2C_STAT_OFFSET 0x04 /* Status Register */
|
||||
#define I2C_DAT_OFFSET 0x08 /* Data Register */
|
||||
#define I2C_ADR_OFFSET 0x0c /* Slave Address Register */
|
||||
#define I2C_SCLH_OFFSET 0x10 /* SCL Duty Cycle Register (high half word) */
|
||||
#define I2C_SCLL_OFFSET 0x14 /* SCL Duty Cycle Register (low half word) */
|
||||
#define I2C_CONCLR_OFFSET 0x18 /* Control Clear Register */
|
||||
|
||||
/* Pin function select register offsets */
|
||||
|
||||
#define PINSEL0_OFFSET 0x00 /* Pin function select register 0 */
|
||||
#define PINSEL1_OFFSET 0x04 /* Pin function select register 1 */
|
||||
#define PINSEL2_OFFSET 0x08 /* Pin function select register 2 */
|
||||
#define PINSEL3_OFFSET 0x0C /* Pin function select register 3 */
|
||||
#define PINSEL4_OFFSET 0x10 /* Pin function select register 4 */
|
||||
#define PINSEL5_OFFSET 0x14 /* Pin function select register 5 */
|
||||
#define PINSEL6_OFFSET 0x18 /* Pin function select register 6 */
|
||||
#define PINSEL7_OFFSET 0x1C /* Pin function select register 7 */
|
||||
#define PINSEL8_OFFSET 0x20 /* Pin function select register 8 */
|
||||
#define PINSEL9_OFFSET 0x24 /* Pin function select register 9 */
|
||||
#define PINSEL10_OFFSET 0x28 /* Pin function select register 10 */
|
||||
|
||||
|
||||
/* Analog to Digital (AD) Base Address */
|
||||
|
||||
#define ADC0_BASE_ADDR 0xE0034000
|
||||
|
||||
/* Analog to Digital (AD) Converter registger offsets */
|
||||
|
||||
#define AD_ADCR_OFFSET 0x00 /* A/D Control Register */
|
||||
#define AD_ADGDR_OFFSET 0x04 /* A/D Global Data Register (only one common register!) */
|
||||
//~ #define AD_ADGSR_OFFSET 0x08 /* A/D Global Start Register */
|
||||
#define AD_ADINTEN_OFFSET 0x0c /* A/D Interrupt Enable Register */
|
||||
#define AD_ADDR0_OFFSET 0x10 /* A/D Chanel 0 Data Register */
|
||||
#define AD_ADDR1_OFFSET 0x14 /* A/D Chanel 0 Data Register */
|
||||
#define AD_ADDR2_OFFSET 0x18 /* A/D Chanel 0 Data Register */
|
||||
#define AD_ADDR3_OFFSET 0x1c /* A/D Chanel 0 Data Register */
|
||||
#define AD_ADDR4_OFFSET 0x20 /* A/D Chanel 0 Data Register */
|
||||
#define AD_ADDR5_OFFSET 0x24 /* A/D Chanel 0 Data Register */
|
||||
#define AD_ADDR6_OFFSET 0x28 /* A/D Chanel 0 Data Register */
|
||||
#define AD_ADDR7_OFFSET 0x2c /* A/D Chanel 0 Data Register */
|
||||
#define AD_ADSTAT_OFFSET 0x30 /* A/D Status Register */
|
||||
|
||||
/* Digital to Analog (DAC) Base Address */
|
||||
|
||||
#define DAC_BASE_ADDR 0xE006C000
|
||||
|
||||
/* Digital to Analog (DAC) reister offset */
|
||||
//#define DACR_OFFSET 0x00
|
||||
|
||||
/* SPI0 register offsets */
|
||||
|
||||
#define SPI0_BASE_ADDR 0xE0020000
|
||||
|
||||
#define SPI0_CR_OFFSET 0x00 /* Control Register */
|
||||
#define SPI0_SR_OFFSET 0x04 /* Status Register */
|
||||
#define SPI0_DR_OFFSET 0x08 /* Data Register */
|
||||
#define SPI0_CCR_OFFSET 0x0c /* Clock Counter Register */
|
||||
#define SPI0_INTF_OFFSET 0x1c /* Interrupt Flag Register */
|
||||
|
||||
/* SPI1 register offsets */
|
||||
|
||||
//~ #define SPI1_CR0_OFFSET 0x00 /* Control Register 0 */
|
||||
//~ #define SPI1_CR1_OFFSET 0x04 /* Control Register 1 */
|
||||
//~ #define SPI1_DR_OFFSET 0x08 /* Data Register */
|
||||
//~ #define SPI1_SR_OFFSET 0x0c /* Status Register */
|
||||
//~ #define SPI1_CPSR_OFFSET 0x10 /* Clock Pre-Scale Regisrer */
|
||||
//~ #define SPI1_IMSC_OFFSET 0x14 /* Interrupt Mask Set and Clear Register */
|
||||
//~ #define SPI1_RIS_OFFSET 0x18 /* Raw Interrupt Status Register */
|
||||
//~ #define SPI1_MIS_OFFSET 0x1c /* Masked Interrupt Status Register */
|
||||
//~ #define SPI1_ICR_OFFSET 0x20 /* Interrupt Clear Register */
|
||||
|
||||
/* SSP Base Addresses */
|
||||
#define SSP0_BASE_ADDR 0xE0068000
|
||||
#define SSP1_BASE_ADDR 0xE0030000
|
||||
/* SSP 0/1 register offsets */
|
||||
#define SSP_CR0_OFFSET 0x00 /* Control Register 0 */
|
||||
#define SSP_CR1_OFFSET 0x04 /* Control Register 1 */
|
||||
#define SSP_DR_OFFSET 0x08 /* Data Register */
|
||||
#define SSP_SR_OFFSET 0x0C /* Status Register*/
|
||||
#define SSP_CPSR_OFFSET 0x10 /* Clock Prescale Register */
|
||||
#define SSP_IMSC_OFFSET 0x14 /* Interrupt Mask Set/Clear Register */
|
||||
#define SSP_RIS_OFFSET 0x18 /* Raw Interrupt Register */
|
||||
#define SSP_MIS_OFFSET 0x1C /* Masked Interrupt Status Register */
|
||||
#define SSP_ICR_OFFSET 0x20 /* Interrupt Clear Register */
|
||||
#define SSP_DMACR_OFFSET 0x24 /* DMA Control Register */
|
||||
|
||||
/* Real Time Clock Base Address */
|
||||
#define RTC_BASE_ADDR 0xE0024000
|
||||
/* RTC register offsets */
|
||||
#define RTC_ILR_OFFSET 0x00 /* Interrupt Location Register */
|
||||
#define RTC_CTC_OFFSET 0x04 /* Clock Tick Counter */
|
||||
#define RTC_CCR_OFFSET 0x08 /* Clock Control Register */
|
||||
#define RTC_CIIR_OFFSET 0x0c /* Counter Increment Interrupt Register */
|
||||
#define RTC_AMR_OFFSET 0x10 /* Alarm Mask Register */
|
||||
#define RTC_CTIME0_OFFSET 0x14 /* Consolidated Time Register 0 */
|
||||
#define RTC_CTIME1_OFFSET 0x18 /* Consolidated Time Register 1 */
|
||||
#define RTC_CTIME2_OFFSET 0x1c /* Consolidated Time Register 2 */
|
||||
#define RTC_SEC_OFFSET 0x20 /* Seconds Register */
|
||||
#define RTC_MIN_OFFSET 0x24 /* Minutes Register */
|
||||
#define RTC_HOUR_OFFSET 0x28 /* Hours Register */
|
||||
#define RTC_DOM_OFFSET 0x2c /* Day Of Month Register */
|
||||
#define RTC_DOW_OFFSET 0x30 /* Day Of Week Register */
|
||||
#define RTC_DOY_OFFSET 0x34 /* Day Of Year Register */
|
||||
#define RTC_MONTH_OFFSET 0x38 /* Months Register */
|
||||
#define RTC_YEAR_OFFSET 0x3c /* Years Register */
|
||||
|
||||
#define RTC_ALSEC_OFFSET 0x60 /* Alarm Seconds Register */
|
||||
#define RTC_ALMIN_OFFSET 0x64 /* Alarm Minutes Register */
|
||||
#define RTC_ALHOUR_OFFSET 0x68 /* Alarm Hours Register */
|
||||
#define RTC_ALDOM_OFFSET 0x6c /* Alarm Day Of Month Register */
|
||||
#define RTC_ALDOW_OFFSET 0x70 /* Alarm Day Of Week Register */
|
||||
#define RTC_ALDOY_OFFSET 0x74 /* Alarm Day Of Year Register */
|
||||
#define RTC_ALMON_OFFSET 0x78 /* Alarm Months Register */
|
||||
#define RTC_ALYEAR_OFFSET 0x7c /* Alarm Years Register */
|
||||
#define RTC_PREINT_OFFSET 0x80 /* Prescale Value Register (integer) */
|
||||
#define RTC_PREFRAC_OFFSET 0x84 /* Prescale Value Register (fraction) */
|
||||
|
||||
|
||||
/* Watchdog */
|
||||
//~ WDG_BASE_ADDR 0xE0000000
|
||||
#define WDMOD_OFFSET 0x00
|
||||
#define WDTC_OFFSET 0x04
|
||||
#define WDFEED_OFFSET 0x08
|
||||
#define WDTV_OFFSET 0x0C
|
||||
#define WDCLKSEL_OFFSET 0x10
|
||||
|
||||
/* CAN CONTROLLERS AND ACCEPTANCE FILTER */
|
||||
//~ CAN_ACCEPT_BASE_ADDR 0xE003C000
|
||||
#define CAN_AFMR_OFFSET 0x00
|
||||
#define CAN_SFF_SA_OFFSET 0x04
|
||||
#define CAN_SFF_GRP_SA_OFFSET 0x08
|
||||
#define CAN_EFF_SA_OFFSET 0x0C
|
||||
#define CAN_EFF_GRP_SA_OFFSET 0x10
|
||||
#define CAN_EOT_OFFSET 0x14
|
||||
#define CAN_LUT_ERR_ADR_OFFSET 0x18
|
||||
#define CAN_LUT_ERR_OFFSET 0x1C
|
||||
|
||||
//~ CAN_COMMON_BASE_ADDR 0xE0040000
|
||||
#define CAN_TX_SR_OFFSET 0x00
|
||||
#define CAN_RX_SR_OFFSET 0x04
|
||||
#define CAN_MSR_OFFSET 0x08
|
||||
|
||||
//~ CAN1_BASE_ADDR 0xE0044000
|
||||
#define CAN1MOD_OFFSET 0x00
|
||||
#define CAN1CMR_OFFSET 0x04
|
||||
#define CAN1GSR_OFFSET 0x08
|
||||
#define CAN1ICR_OFFSET 0x0C
|
||||
#define CAN1IER_OFFSET 0x10
|
||||
#define CAN1BTR_OFFSET 0x14
|
||||
#define CAN1EWL_OFFSET 0x18
|
||||
#define CAN1SR_OFFSET 0x1C
|
||||
#define CAN1RFS_OFFSET 0x20
|
||||
#define CAN1RID_OFFSET 0x24
|
||||
#define CAN1RDA_OFFSET 0x28
|
||||
#define CAN1RDB_OFFSET 0x2C
|
||||
|
||||
#define CAN1TFI1_OFFSET 0x30
|
||||
#define CAN1TID1_OFFSET 0x34
|
||||
#define CAN1TDA1_OFFSET 0x38
|
||||
#define CAN1TDB1_OFFSET 0x3C
|
||||
#define CAN1TFI2_OFFSET 0x40
|
||||
#define CAN1TID2_OFFSET 0x44
|
||||
#define CAN1TDA2_OFFSET 0x48
|
||||
#define CAN1TDB2_OFFSET 0x4C
|
||||
#define CAN1TFI3_OFFSET 0x50
|
||||
#define CAN1TID3_OFFSET 0x54
|
||||
#define CAN1TDA3_OFFSET 0x58
|
||||
#define CAN1TDB3_OFFSET 0x5C
|
||||
|
||||
//~ CAN2_BASE_ADDR 0xE0048000
|
||||
#define CAN2MOD_OFFSET 0x00
|
||||
#define CAN2CMR_OFFSET 0x04
|
||||
#define CAN2GSR_OFFSET 0x08
|
||||
#define CAN2ICR_OFFSET 0x0C
|
||||
#define CAN2IER_OFFSET 0x10
|
||||
#define CAN2BTR_OFFSET 0x14
|
||||
#define CAN2EWL_OFFSET 0x18
|
||||
#define CAN2SR_OFFSET 0x1C
|
||||
#define CAN2RFS_OFFSET 0x20
|
||||
#define CAN2RID_OFFSET 0x24
|
||||
#define CAN2RDA_OFFSET 0x28
|
||||
#define CAN2RDB_OFFSET 0x2C
|
||||
|
||||
#define CAN2TFI1_OFFSET 0x30
|
||||
#define CAN2TID1_OFFSET 0x34
|
||||
#define CAN2TDA1_OFFSET 0x38
|
||||
#define CAN2TDB1_OFFSET 0x3C
|
||||
#define CAN2TFI2_OFFSET 0x40
|
||||
#define CAN2TID2_OFFSET 0x44
|
||||
#define CAN2TDA2_OFFSET 0x48
|
||||
#define CAN2TDB2_OFFSET 0x4C
|
||||
#define CAN2TFI3_OFFSET 0x50
|
||||
#define CAN2TID3_OFFSET 0x54
|
||||
#define CAN2TDA3_OFFSET 0x58
|
||||
#define CAN2TDB3_OFFSET 0x5C
|
||||
|
||||
|
||||
/* MultiMedia Card Interface(MCI) Controller */
|
||||
//~ MCI_BASE_ADDR 0xE008C000
|
||||
#define MCI_POWER_OFFSET 0x00
|
||||
#define MCI_CLOCK_OFFSET 0x04
|
||||
#define MCI_ARGUMENT_OFFSET 0x08
|
||||
#define MCI_COMMAND_OFFSET 0x0C
|
||||
#define MCI_RESP_CMD_OFFSET 0x10
|
||||
#define MCI_RESP0_OFFSET 0x14
|
||||
#define MCI_RESP1_OFFSET 0x18
|
||||
#define MCI_RESP2_OFFSET 0x1C
|
||||
#define MCI_RESP3_OFFSET 0x20
|
||||
#define MCI_DATA_TMR_OFFSET 0x24
|
||||
#define MCI_DATA_LEN_OFFSET 0x28
|
||||
#define MCI_DATA_CTRL_OFFSET 0x2C
|
||||
#define MCI_DATA_CNT_OFFSET 0x30
|
||||
#define MCI_STATUS_OFFSET 0x34
|
||||
#define MCI_CLEAR_OFFSET 0x38
|
||||
#define MCI_MASK0_OFFSET 0x3C
|
||||
#define MCI_MASK1_OFFSET 0x40
|
||||
#define MCI_FIFO_CNT_OFFSET 0x48
|
||||
#define MCI_FIFO_OFFSET 0x80
|
||||
|
||||
|
||||
/* I2S Interface Controller (I2S) */
|
||||
//~ I2S_BASE_ADDR 0xE0088000
|
||||
#define I2S_DAO_OFFSET 0x00
|
||||
#define I2S_DAI_OFFSET 0x04
|
||||
#define I2S_TX_FIFO_OFFSET 0x08
|
||||
#define I2S_RX_FIFO_OFFSET 0x0C
|
||||
#define I2S_STATE_OFFSET 0x10
|
||||
#define I2S_DMA1_OFFSET 0x14
|
||||
#define I2S_DMA2_OFFSET 0x18
|
||||
#define I2S_IRQ_OFFSET 0x1C
|
||||
#define I2S_TXRATE_OFFSET 0x20
|
||||
#define I2S_RXRATE_OFFSET 0x24
|
||||
|
||||
/* General-purpose DMA Controller */
|
||||
/* DMA_BASE_ADDR 0xFFE04000 */
|
||||
#define GPDMA_INT_STAT_OFFSET 0x4000
|
||||
#define GPDMA_INT_TCSTAT_OFFSET 0x4004
|
||||
#define GPDMA_INT_TCCLR_OFFSET 0x4008
|
||||
#define GPDMA_INT_ERR_STAT_OFFSET 0x400C
|
||||
#define GPDMA_INT_ERR_CLR_OFFSET 0x4010
|
||||
#define GPDMA_RAW_INT_TCSTAT_OFFSET 0x4014
|
||||
#define GPDMA_RAW_INT_ERR_STAT_OFFSET 0x4018
|
||||
#define GPDMA_ENABLED_CHNS_OFFSET 0x401C
|
||||
#define GPDMA_SOFT_BREQ_OFFSET 0x4020
|
||||
#define GPDMA_SOFT_SREQ_OFFSET 0x4024
|
||||
#define GPDMA_SOFT_LBREQ_OFFSET 0x4028
|
||||
#define GPDMA_SOFT_LSREQ_OFFSET 0x402C
|
||||
#define GPDMA_CONFIG_OFFSET 0x4030
|
||||
#define GPDMA_SYNC_OFFSET 0x4034
|
||||
/* DMA channel 0 registers */
|
||||
#define GPDMA_CH0_SRC_OFFSET 0x4100
|
||||
#define GPDMA_CH0_DEST_OFFSET 0x4104
|
||||
#define GPDMA_CH0_LLI_OFFSET 0x4108
|
||||
#define GPDMA_CH0_CTRL_OFFSET 0x410C
|
||||
#define GPDMA_CH0_CFG_OFFSET 0x4110
|
||||
/* DMA channel 1 registers */
|
||||
#define GPDMA_CH1_SRC_OFFSET 0x4120
|
||||
#define GPDMA_CH1_DEST_OFFSET 0x4124
|
||||
#define GPDMA_CH1_LLI_OFFSET 0x4128
|
||||
#define GPDMA_CH1_CTRL_OFFSET 0x412C
|
||||
#define GPDMA_CH1_CFG_OFFSET 0x4130
|
||||
|
||||
|
||||
/* USB Controller */
|
||||
#define USB_INT_BASE_ADDR 0xE01FC1C0
|
||||
#define USB_BASE_ADDR 0xFFE0C200 /* USB Base Address */
|
||||
|
||||
/* USB Device Interrupt Registers */
|
||||
#define USB_INT_STAT_OFFSET 0x00
|
||||
#define USB_INT_EN_OFFSET 0x04
|
||||
#define USB_INT_CLR_OFFSET 0x08
|
||||
#define USB_INT_SET_OFFSET 0x0C
|
||||
#define USB_INT_PRIO_OFFSET 0x2C
|
||||
|
||||
/* USB Device Endpoint Interrupt Registers */
|
||||
#define USB_EP_INT_STAT_OFFSET 0x30
|
||||
#define USB_EP_INT_EN_OFFSET 0x34
|
||||
#define USB_EP_INT_CLR_OFFSET 0x38
|
||||
#define USB_EP_INT_SET_OFFSET 0x3C
|
||||
#define USB_EP_INT_PRIO_OFFSET 0x40
|
||||
|
||||
/* USB Device Endpoint Realization Registers */
|
||||
#define USB_REALIZE_EP_OFFSET 0x44
|
||||
#define USB_EP_INDEX_OFFSET 0x48
|
||||
#define USB_MAXPACKET_SIZE_OFFSET 0x4C
|
||||
|
||||
/* USB Device Command Reagisters */
|
||||
#define USB_CMD_CODE_OFFSET 0x10
|
||||
#define USB_CMD_DATA_OFFSET 0x14
|
||||
|
||||
/* USB Device Data Transfer Registers */
|
||||
#define USB_RX_DATA_OFFSET 0x18
|
||||
#define USB_TX_DATA_OFFSET 0x1C
|
||||
#define USB_RX_PLENGTH_OFFSET 0x20
|
||||
#define USB_TX_PLENGTH_OFFSET 0x24
|
||||
#define USB_USB_CTRL_OFFSET 0x28
|
||||
|
||||
/* USB Device DMA Registers */
|
||||
#define USB_DMA_REQ_STAT_OFFSET 0x50
|
||||
#define USB_DMA_REQ_CLR_OFFSET 0x54
|
||||
#define USB_DMA_REQ_SET_OFFSET 0x58
|
||||
#define USB_UDCA_HEAD_OFFSET 0x80
|
||||
#define USB_EP_DMA_STAT_OFFSET 0x84
|
||||
#define USB_EP_DMA_EN_OFFSET 0x88
|
||||
#define USB_EP_DMA_DIS_OFFSET 0x8C
|
||||
#define USB_DMA_INT_STAT_OFFSET 0x90
|
||||
#define USB_DMA_INT_EN_OFFSET 0x94
|
||||
#define USB_EOT_INT_STAT_OFFSET 0xA0
|
||||
#define USB_EOT_INT_CLR_OFFSET 0xA4
|
||||
#define USB_EOT_INT_SET_OFFSET 0xA8
|
||||
#define USB_NDD_REQ_INT_STAT_OFFSET 0xAC
|
||||
#define USB_NDD_REQ_INT_CLR_OFFSET 0xB0
|
||||
#define USB_NDD_REQ_INT_SET_OFFSET 0xB4
|
||||
#define USB_SYS_ERR_INT_STAT_OFFSET 0xB8
|
||||
#define USB_SYS_ERR_INT_CLR_OFFSET 0xBC
|
||||
#define USB_SYS_ERR_INT_SET_OFFSET 0xC0
|
||||
|
||||
/* System Control Block(SCB) modules include Memory Accelerator Module,
|
||||
Phase Locked Loop, VPB divider, Power Control, External Interrupt,
|
||||
Reset, and Code Security/Debugging */
|
||||
|
||||
#define SCB_BASE_ADDR 0xE01FC000
|
||||
/* Memory Accelerator Module (MAM) Regiser */
|
||||
#define SCB_MAMCR (*(volatile uint32_t*)(0xE01FC000))
|
||||
#define SCB_MAMTIM (*(volatile uint32_t*)(0xE01FC004))
|
||||
#define SCB_MEMMAP (*(volatile uint32_t*)(0xE01FC040))
|
||||
/* Phase Locked Loop (PLL) Register */
|
||||
#define SCB_PLLCON (*(volatile uint32_t*)(0xE01FC080))
|
||||
#define SCB_PLLCFG (*(volatile uint32_t*)(0xE01FC084))
|
||||
#define SCB_PLLSTAT (*(volatile uint32_t*)(0xE01FC088))
|
||||
#define SCB_PLLFEED (*(volatile uint32_t*)(0xE01FC08C))
|
||||
/* Power Control register */
|
||||
#define SCB_PCON (*(volatile uint32_t*)(0xE01FC0C0))
|
||||
#define SCB_PCONP (*(volatile uint32_t*)(0xE01FC0C4))
|
||||
#define SCB_PCONP_OFFSET 0x0C4
|
||||
/* Clock Divider Register */
|
||||
#define SCB_CCLKCFG (*(volatile uint32_t*)(0xE01FC104))
|
||||
#define SCB_USBCLKCFG (*(volatile uint32_t*)(0xE01FC108))
|
||||
#define SCB_CLKSRCSEL (*(volatile uint32_t*)(0xE01FC10C))
|
||||
#define SCB_PCLKSEL0 (*(volatile uint32_t*)(0xE01FC1A8))
|
||||
#define SCB_PCLKSEL1 (*(volatile uint32_t*)(0xE01FC1AC))
|
||||
#define SCB_PCLKSEL0_OFFSET (0x1A8)
|
||||
#define SCB_PCLKSEL1_OFFSET (0x1AC)
|
||||
/* External Interrupt register */
|
||||
#define SCB_EXTINT (*(volatile uint32_t*)(0xE01FC140))
|
||||
#define SCB_INTWAKE (*(volatile uint32_t*)(0xE01FC144))
|
||||
#define SCB_EXTMODE (*(volatile uint32_t*)(0xE01FC148))
|
||||
#define SCB_EXTPOLAR (*(volatile uint32_t*)(0xE01FC14C))
|
||||
/* Reser Source Indentification register */
|
||||
#define SCB_RSIR (*(volatile uint32_t*)(0xE01FC180))
|
||||
/* RSID, code security protection */
|
||||
#define SCB_CSPR (*(volatile uint32_t*)(0xE01FC184))
|
||||
|
||||
#define SCB_AHBCFG1 (*(volatile uint32_t*)(0xE01FC188))
|
||||
#define SCB_AHBCFG2 (*(volatile uint32_t*)(0xE01FC18C))
|
||||
/* System Controls and Status Register */
|
||||
#define SCB_SCS (*(volatile uint32_t*)(0xE01FC1A0))
|
||||
|
||||
//~ /* External Memory Controller (EMC) definitions */
|
||||
|
||||
|
||||
/* MPMC(EMC) registers, note: all the external memory controller(EMC) registers
|
||||
are for LPC24xx only. */
|
||||
#define STATIC_MEM0_BASE 0x80000000
|
||||
#define STATIC_MEM1_BASE 0x81000000
|
||||
#define STATIC_MEM2_BASE 0x82000000
|
||||
#define STATIC_MEM3_BASE 0x83000000
|
||||
|
||||
#define DYNAMIC_MEM0_BASE 0xA0000000
|
||||
#define DYNAMIC_MEM1_BASE 0xB0000000
|
||||
#define DYNAMIC_MEM2_BASE 0xC0000000
|
||||
#define DYNAMIC_MEM3_BASE 0xD0000000
|
||||
|
||||
/* External Memory Controller (EMC) */
|
||||
//~ #define EMC_BASE_ADDR 0xFFE08000
|
||||
#define EMC_CTRL_OFFSET 0x000
|
||||
#define EMC_STAT_OFFSET 0x004
|
||||
#define EMC_CONFIG_OFFSET 0x008
|
||||
|
||||
/* Dynamic RAM access registers */
|
||||
#define EMC_DYN_CTRL_OFFSET 0x020
|
||||
#define EMC_DYN_RFSH_OFFSET 0x024
|
||||
#define EMC_DYN_RD_CFG_OFFSET 0x028
|
||||
#define EMC_DYN_RP_OFFSET 0x030
|
||||
#define EMC_DYN_RAS_OFFSET 0x034
|
||||
#define EMC_DYN_SREX_OFFSET 0x038
|
||||
#define EMC_DYN_APR_OFFSET 0x03C
|
||||
#define EMC_DYN_DAL_OFFSET 0x040
|
||||
#define EMC_DYN_WR_OFFSET 0x044
|
||||
#define EMC_DYN_RC_OFFSET 0x048
|
||||
#define EMC_DYN_RFC_OFFSET 0x04C
|
||||
#define EMC_DYN_XSR_OFFSET 0x050
|
||||
#define EMC_DYN_RRD_OFFSET 0x054
|
||||
#define EMC_DYN_MRD_OFFSET 0x058
|
||||
|
||||
#define EMC_DYN_CFG0_OFFSET 0x100
|
||||
#define EMC_DYN_RASCAS0_OFFSET 0x104
|
||||
#define EMC_DYN_CFG1_OFFSET 0x140
|
||||
#define EMC_DYN_RASCAS1_OFFSET 0x144
|
||||
#define EMC_DYN_CFG2_OFFSET 0x160
|
||||
#define EMC_DYN_RASCAS2_OFFSET 0x164
|
||||
#define EMC_DYN_CFG3_OFFSET 0x180
|
||||
#define EMC_DYN_RASCAS3_OFFSET 0x184
|
||||
|
||||
/* static RAM access registers */
|
||||
#define EMC_STA_CFG0_OFFSET 0x200
|
||||
#define EMC_STA_WAITWEN0_OFFSET 0x204
|
||||
#define EMC_STA_WAITOEN0_OFFSET 0x208
|
||||
#define EMC_STA_WAITRD0_OFFSET 0x20C
|
||||
#define EMC_STA_WAITPAGE0_OFFSET 0x210
|
||||
#define EMC_STA_WAITWR0_OFFSET 0x214
|
||||
#define EMC_STA_WAITTURN0_OFFSET 0x218
|
||||
|
||||
#define EMC_STA_CFG1_OFFSET 0x220
|
||||
#define EMC_STA_WAITWEN1_OFFSET 0x224
|
||||
#define EMC_STA_WAITOEN1_OFFSET 0x228
|
||||
#define EMC_STA_WAITRD1_OFFSET 0x22C
|
||||
#define EMC_STA_WAITPAGE1_OFFSET 0x230
|
||||
#define EMC_STA_WAITWR1_OFFSET 0x234
|
||||
#define EMC_STA_WAITTURN1_OFFSET 0x238
|
||||
|
||||
#define EMC_STA_CFG2_OFFSET 0x240
|
||||
#define EMC_STA_WAITWEN2_OFFSET 0x244
|
||||
#define EMC_STA_WAITOEN2_OFFSET 0x248
|
||||
#define EMC_STA_WAITRD2_OFFSET 0x24C
|
||||
#define EMC_STA_WAITPAGE2_OFFSET 0x250
|
||||
#define EMC_STA_WAITWR2_OFFSET 0x254
|
||||
#define EMC_STA_WAITTURN2_OFFSET 0x258
|
||||
|
||||
#define EMC_STA_CFG3 0x260
|
||||
#define EMC_STA_WAITWEN3_OFFSET 0x264
|
||||
#define EMC_STA_WAITOEN3_OFFSET 0x268
|
||||
#define EMC_STA_WAITRD3_OFFSET 0x26C
|
||||
#define EMC_STA_WAITPAGE3_OFFSET 0x270
|
||||
#define EMC_STA_WAITWR3_OFFSET 0x274
|
||||
#define EMC_STA_WAITTURN3_OFFSET 0x278
|
||||
|
||||
#define EMC_STA_EXT_WAIT_OFFSET 0x880
|
||||
|
||||
/* GPIO register offsets WORD access */
|
||||
#define GPIO0_PIN_OFFSET 0x00 /* Pin Value Register */
|
||||
#define GPIO0_SET_OFFSET 0x04 /* Pin Output Set Register */
|
||||
#define GPIO0_DIR_OFFSET 0x08 /* Pin Direction Register */
|
||||
#define GPIO0_CLR_OFFSET 0x0c /* Pin Output Clear Register */
|
||||
#define GPIO1_PIN_OFFSET 0x10 /* Pin Value Register */
|
||||
#define GPIO1_SET_OFFSET 0x14 /* Pin Output Set Register */
|
||||
#define GPIO1_DIR_OFFSET 0x18 /* Pin Direction Register */
|
||||
#define GPIO1_CLR_OFFSET 0x1c /* Pin Output Clear Register */
|
||||
|
||||
/* Fast I0 Base Address */
|
||||
#define FIO_BASE_ADDR 0x3FFFC000
|
||||
/* FIO register offsets WORD access */
|
||||
#define FIO0_DIR_OFFSET 0x00 /* Fast GPIO Port Direction Register */
|
||||
#define FIO0_MASK_OFFSET 0x10 /* Fast GPIO Mask Register */
|
||||
#define FIO0_PIN_OFFSET 0x14 /* Fast GPIO Pin Value Register */
|
||||
#define FIO0_SET_OFFSET 0x18 /* Fast GPIO Port Output Set Register */
|
||||
#define FIO0_CLR_OFFSET 0x1c /* Fast GPIO Port Output Clear Register */
|
||||
|
||||
#define FIO1_DIR_OFFSET 0x20 /* Fast GPIO Port Direction Register */
|
||||
#define FIO1_MASK_OFFSET 0x30 /* Fast GPIO Mask Register */
|
||||
#define FIO1_PIN_OFFSET 0x34 /* Fast GPIO Pin Value Register */
|
||||
#define FIO1_SET_OFFSET 0x38 /* Fast GPIO Port Output Set Register */
|
||||
#define FIO1_CLR_OFFSET 0x3c /* Fast GPIO Port Output Clear Register */
|
||||
|
||||
#define FIO2_DIR_OFFSET 0x40 /* Fast GPIO Port Direction Register */
|
||||
#define FIO2_MASK_OFFSET 0x50 /* Fast GPIO Mask Register */
|
||||
#define FIO2_PIN_OFFSET 0x54 /* Fast GPIO Pin Value Register */
|
||||
#define FIO2_SET_OFFSET 0x58 /* Fast GPIO Port Output Set Register */
|
||||
#define FIO2_CLR_OFFSET 0x5c /* Fast GPIO Port Output Clear Register */
|
||||
|
||||
#define FIO3_DIR_OFFSET 0x60 /* Fast GPIO Port Direction Register */
|
||||
#define FIO3_MASK_OFFSET 0x70 /* Fast GPIO Mask Register */
|
||||
#define FIO3_PIN_OFFSET 0x74 /* Fast GPIO Pin Value Register */
|
||||
#define FIO3_SET_OFFSET 0x78 /* Fast GPIO Port Output Set Register */
|
||||
#define FIO3_CLR_OFFSET 0x7c /* Fast GPIO Port Output Clear Register */
|
||||
|
||||
#define FIO4_DIR_OFFSET 0x80 /* Fast GPIO Port Direction Register */
|
||||
#define FIO4_MASK_OFFSET 0x90 /* Fast GPIO Mask Register */
|
||||
#define FIO4_PIN_OFFSET 0x94 /* Fast GPIO Pin Value Register */
|
||||
#define FIO4_SET_OFFSET 0x98 /* Fast GPIO Port Output Set Register */
|
||||
#define FIO4_CLR_OFFSET 0x9c /* Fast GPIO Port Output Clear Register */
|
||||
|
||||
|
||||
/* FIO register offsets HALF-WORD access */
|
||||
|
||||
#define FIO0MASKL_OFFSET 0x10 /* Fast IO Mask Lower HALF-WORD */
|
||||
#define FIO1MASKL_OFFSET 0x30
|
||||
#define FIO2MASKL_OFFSET 0x50
|
||||
#define FIO3MASKL_OFFSET 0x70
|
||||
#define FIO4MASKL_OFFSET 0x90
|
||||
|
||||
#define FIO0MASKU_OFFSET 0x12 /* Fast IO Mask Upper HALF-WORD */
|
||||
#define FIO1MASKU_OFFSET 0x32
|
||||
#define FIO2MASKU_OFFSET 0x52
|
||||
#define FIO3MASKU_OFFSET 0x72
|
||||
#define FIO4MASKU_OFFSET 0x92
|
||||
|
||||
#define FIO0PINL_OFFSET 0x14 /* Fast IOPIN Lower HALF-WORD */
|
||||
#define FIO1PINL_OFFSET 0x34
|
||||
#define FIO2PINL_OFFSET 0x54
|
||||
#define FIO3PINL_OFFSET 0x74
|
||||
#define FIO4PINL_OFFSET 0x94
|
||||
|
||||
#define FIO0PINU_OFFSET 0x16 /* Fast IOPIN Upper HALF-WORD */
|
||||
#define FIO1PINU_OFFSET 0x36
|
||||
#define FIO2PINU_OFFSET 0x56
|
||||
#define FIO3PINU_OFFSET 0x76
|
||||
#define FIO4PINU_OFFSET 0x96
|
||||
|
||||
#define FIO0SETL_OFFSET 0x18 /* Fast IOSET Lower HALF-WORD */
|
||||
#define FIO1SETL_OFFSET 0x38
|
||||
#define FIO2SETL_OFFSET 0x58
|
||||
#define FIO3SETL_OFFSET 0x78
|
||||
#define FIO4SETL_OFFSET 0x98
|
||||
|
||||
#define FIO0SETU_OFFSET 0x1A /* Fast IOSET Upper HALF-WORD */
|
||||
#define FIO1SETU_OFFSET 0x3A
|
||||
#define FIO2SETU_OFFSET 0x5A
|
||||
#define FIO3SETU_OFFSET 0x7A
|
||||
#define FIO4SETU_OFFSET 0x9A
|
||||
|
||||
#define FIO0CLRL_OFFSET 0x1C /* Fast IOCLR Lower HALF-WORD */
|
||||
#define FIO1CLRL_OFFSET 0x3C
|
||||
#define FIO2CLRL_OFFSET 0x5C
|
||||
#define FIO3CLRL_OFFSET 0x7C
|
||||
#define FIO4CLRL_OFFSET 0x9C
|
||||
|
||||
#define FIO0CLRU_OFFSET 0x1E /* Fast IOCLR Upper HALF-WORD */
|
||||
#define FIO1CLRU_OFFSET 0x3E
|
||||
#define FIO2CLRU_OFFSET 0x5E
|
||||
#define FIO3CLRU_OFFSET 0x7E
|
||||
#define FIO4CLRU_OFFSET 0x9E
|
||||
|
||||
#define FIO0DIRL_OFFSET 0x00 /* Fast IODIR Lower HALF-WORD */
|
||||
#define FIO1DIRL_OFFSET 0x20
|
||||
#define FIO2DIRL_OFFSET 0x40
|
||||
#define FIO3DIRL_OFFSET 0x60
|
||||
#define FIO4DIRL_OFFSET 0x80
|
||||
|
||||
#define FIO0DIRU_OFFSET 0x02 /* Fast IODIR Upper HALF-WORD */
|
||||
#define FIO1DIRU_OFFSET 0x22
|
||||
#define FIO2DIRU_OFFSET 0x42
|
||||
#define FIO3DIRU_OFFSET 0x62
|
||||
#define FIO4DIRU_OFFSET 0x82
|
||||
|
||||
|
||||
/* FIO register offsets BYTE access */
|
||||
|
||||
#define FIO0DIR0_OFFSET 0x00
|
||||
#define FIO1DIR0_OFFSET 0x20
|
||||
#define FIO2DIR0_OFFSET 0x40
|
||||
#define FIO3DIR0_OFFSET 0x60
|
||||
#define FIO4DIR0_OFFSET 0x80
|
||||
|
||||
#define FIO0DIR1_OFFSET 0x01
|
||||
#define FIO1DIR1_OFFSET 0x21
|
||||
#define FIO2DIR1_OFFSET 0x41
|
||||
#define FIO3DIR1_OFFSET 0x61
|
||||
#define FIO4DIR1_OFFSET 0x81
|
||||
|
||||
#define FIO0DIR2_OFFSET 0x02
|
||||
#define FIO1DIR2_OFFSET 0x22
|
||||
#define FIO2DIR2_OFFSET 0x42
|
||||
#define FIO3DIR2_OFFSET 0x62
|
||||
#define FIO4DIR2_OFFSET 0x82
|
||||
|
||||
#define FIO0DIR3_OFFSET 0x03
|
||||
#define FIO1DIR3_OFFSET 0x23
|
||||
#define FIO2DIR3_OFFSET 0x43
|
||||
#define FIO3DIR3_OFFSET 0x63
|
||||
#define FIO4DIR3_OFFSET 0x83
|
||||
|
||||
#define FIO0MASK0_OFFSET 0x10
|
||||
#define FIO1MASK0_OFFSET 0x30
|
||||
#define FIO2MASK0_OFFSET 0x50
|
||||
#define FIO3MASK0_OFFSET 0x70
|
||||
#define FIO4MASK0_OFFSET 0x90
|
||||
|
||||
#define FIO0MASK1_OFFSET 0x11
|
||||
#define FIO1MASK1_OFFSET 0x21
|
||||
#define FIO2MASK1_OFFSET 0x51
|
||||
#define FIO3MASK1_OFFSET 0x71
|
||||
#define FIO4MASK1_OFFSET 0x91
|
||||
|
||||
#define FIO0MASK2_OFFSET 0x12
|
||||
#define FIO1MASK2_OFFSET 0x32
|
||||
#define FIO2MASK2_OFFSET 0x52
|
||||
#define FIO3MASK2_OFFSET 0x72
|
||||
#define FIO4MASK2_OFFSET 0x92
|
||||
|
||||
#define FIO0MASK3_OFFSET 0x13
|
||||
#define FIO1MASK3_OFFSET 0x33
|
||||
#define FIO2MASK3_OFFSET 0x53
|
||||
#define FIO3MASK3_OFFSET 0x73
|
||||
#define FIO4MASK3_OFFSET 0x93
|
||||
|
||||
#define FIO0PIN0_OFFSET 0x14
|
||||
#define FIO1PIN0_OFFSET 0x34
|
||||
#define FIO2PIN0_OFFSET 0x54
|
||||
#define FIO3PIN0_OFFSET 0x74
|
||||
#define FIO4PIN0_OFFSET 0x94
|
||||
|
||||
#define FIO0PIN1_OFFSET 0x15
|
||||
#define FIO1PIN1_OFFSET 0x25
|
||||
#define FIO2PIN1_OFFSET 0x55
|
||||
#define FIO3PIN1_OFFSET 0x75
|
||||
#define FIO4PIN1_OFFSET 0x95
|
||||
|
||||
#define FIO0PIN2_OFFSET 0x16
|
||||
#define FIO1PIN2_OFFSET 0x36
|
||||
#define FIO2PIN2_OFFSET 0x56
|
||||
#define FIO3PIN2_OFFSET 0x76
|
||||
#define FIO4PIN2_OFFSET 0x96
|
||||
|
||||
#define FIO0PIN3_OFFSET 0x17
|
||||
#define FIO1PIN3_OFFSET 0x37
|
||||
#define FIO2PIN3_OFFSET 0x57
|
||||
#define FIO3PIN3_OFFSET 0x77
|
||||
#define FIO4PIN3_OFFSET 0x97
|
||||
|
||||
#define FIO0SET0_OFFSET 0x18
|
||||
#define FIO1SET0_OFFSET 0x38
|
||||
#define FIO2SET0_OFFSET 0x58
|
||||
#define FIO3SET0_OFFSET 0x78
|
||||
#define FIO4SET0_OFFSET 0x98
|
||||
|
||||
#define FIO0SET1_OFFSET 0x19
|
||||
#define FIO1SET1_OFFSET 0x29
|
||||
#define FIO2SET1_OFFSET 0x59
|
||||
#define FIO3SET1_OFFSET 0x79
|
||||
#define FIO4SET1_OFFSET 0x99
|
||||
|
||||
#define FIO0SET2_OFFSET 0x1A
|
||||
#define FIO1SET2_OFFSET 0x3A
|
||||
#define FIO2SET2_OFFSET 0x5A
|
||||
#define FIO3SET2_OFFSET 0x7A
|
||||
#define FIO4SET2_OFFSET 0x9A
|
||||
|
||||
#define FIO0SET3_OFFSET 0x1B
|
||||
#define FIO1SET3_OFFSET 0x3B
|
||||
#define FIO2SET3_OFFSET 0x5B
|
||||
#define FIO3SET3_OFFSET 0x7B
|
||||
#define FIO4SET3_OFFSET 0x9B
|
||||
|
||||
#define FIO0CLR0_OFFSET 0x1C
|
||||
#define FIO1CLR0_OFFSET 0x3C
|
||||
#define FIO2CLR0_OFFSET 0x5C
|
||||
#define FIO3CLR0_OFFSET 0x7C
|
||||
#define FIO4CLR0_OFFSET 0x9C
|
||||
|
||||
#define FIO0CLR1_OFFSET 0x1D
|
||||
#define FIO1CLR1_OFFSET 0x2D
|
||||
#define FIO2CLR1_OFFSET 0x5D
|
||||
#define FIO3CLR1_OFFSET 0x7D
|
||||
#define FIO4CLR1_OFFSET 0x9D
|
||||
|
||||
#define FIO0CLR2_OFFSET 0x1E
|
||||
#define FIO1CLR2_OFFSET 0x3E
|
||||
#define FIO2CLR2_OFFSET 0x5E
|
||||
#define FIO3CLR2_OFFSET 0x7E
|
||||
#define FIO4CLR2_OFFSET 0x9E
|
||||
|
||||
#define FIO0CLR3_OFFSET 0x1F
|
||||
#define FIO1CLR3_OFFSET 0x3F
|
||||
#define FIO2CLR3_OFFSET 0x5F
|
||||
#define FIO3CLR3_OFFSET 0x7F
|
||||
#define FIO4CLR3_OFFSET 0x9F
|
||||
|
||||
/* Vectored Interrupt Controller (VIC) register offsets */
|
||||
|
||||
#define VIC_IRQSTATUS_OFFSET 0x000 /* R: IRQ Status Register */
|
||||
#define VIC_FIQSTATUS_OFFSET 0x004 /* R: FIQ Status Register */
|
||||
#define VIC_RAWINTR_OFFSET 0x008 /* R: Raw Interrupt Status Register */
|
||||
#define VIC_INTSELECT_OFFSET 0x00c /* RW: Interrupt Select Register */
|
||||
#define VIC_INTENABLE_OFFSET 0x010 /* RW: Interrupt Enable Register */
|
||||
#define VIC_INTENCLEAR_OFFSET 0x014 /* W: Interrupt Enable Clear Register */
|
||||
#define VIC_SOFTINT_OFFSET 0x018 /* RW: Software Interrupt Register */
|
||||
#define VIC_SOFTINTCLEAR_OFFSET 0x01c /* W: Software Interrupt Clear Register */
|
||||
#define VIC_PROTECTION_OFFSET 0x020 /* Protection Enable Register */
|
||||
#define VIC_PRIORITY_MASK_OFFSET 0x024 /* Priority Mask Register */
|
||||
|
||||
|
||||
//~ #define LPC23XX_VIC_BASE 0xfffff000 /* Vectored Interrupt Controller (VIC) Base */
|
||||
#define VIC_ADDRESS_OFFSET 0xF00 /* RW: Vector Address Register */
|
||||
|
||||
#define VIC_VECTADDR0_OFFSET 0x100 /* RW: Vector Address 0 Register */
|
||||
#define VIC_VECTADDR1_OFFSET 0x104 /* RW: Vector Address 1 Register */
|
||||
#define VIC_VECTADDR2_OFFSET 0x108 /* RW: Vector Address 2 Register */
|
||||
#define VIC_VECTADDR3_OFFSET 0x10c /* RW: Vector Address 3 Register */
|
||||
#define VIC_VECTADDR4_OFFSET 0x110 /* RW: Vector Address 4 Register */
|
||||
#define VIC_VECTADDR5_OFFSET 0x114 /* RW: Vector Address 5 Register */
|
||||
#define VIC_VECTADDR6_OFFSET 0x118 /* RW: Vector Address 6 Register */
|
||||
#define VIC_VECTADDR7_OFFSET 0x11c /* RW: Vector Address 7 Register */
|
||||
#define VIC_VECTADDR8_OFFSET 0x120 /* RW: Vector Address 8 Register */
|
||||
#define VIC_VECTADDR9_OFFSET 0x124 /* RW: Vector Address 9 Register */
|
||||
#define VIC_VECTADDR10_OFFSET 0x128 /* RW: Vector Address 10 Register */
|
||||
#define VIC_VECTADDR11_OFFSET 0x12c /* RW: Vector Address 11 Register */
|
||||
#define VIC_VECTADDR12_OFFSET 0x130 /* RW: Vector Address 12 Register */
|
||||
#define VIC_VECTADDR13_OFFSET 0x134 /* RW: Vector Address 13 Register */
|
||||
#define VIC_VECTADDR14_OFFSET 0x138 /* RW: Vector Address 14 Register */
|
||||
#define VIC_VECTADDR15_OFFSET 0x13c /* RW: Vector Address 15 Register */
|
||||
#define VIC_VECTADDR16_OFFSET 0x140 /* RW: Vector Address 16 Register */
|
||||
#define VIC_VECTADDR17_OFFSET 0x144 /* RW: Vector Address 17 Register */
|
||||
#define VIC_VECTADDR18_OFFSET 0x148 /* RW: Vector Address 18 Register */
|
||||
#define VIC_VECTADDR19_OFFSET 0x14c /* RW: Vector Address 19 Register */
|
||||
#define VIC_VECTADDR20_OFFSET 0x150 /* RW: Vector Address 20 Register */
|
||||
#define VIC_VECTADDR21_OFFSET 0x154 /* RW: Vector Address 21 Register */
|
||||
#define VIC_VECTADDR22_OFFSET 0x158 /* RW: Vector Address 22 Register */
|
||||
#define VIC_VECTADDR23_OFFSET 0x15c /* RW: Vector Address 23 Register */
|
||||
#define VIC_VECTADDR24_OFFSET 0x160 /* RW: Vector Address 24 Register */
|
||||
#define VIC_VECTADDR25_OFFSET 0x164 /* RW: Vector Address 25 Register */
|
||||
#define VIC_VECTADDR26_OFFSET 0x168 /* RW: Vector Address 26 Register */
|
||||
#define VIC_VECTADDR27_OFFSET 0x16c /* RW: Vector Address 27 Register */
|
||||
#define VIC_VECTADDR28_OFFSET 0x170 /* RW: Vector Address 28 Register */
|
||||
#define VIC_VECTADDR29_OFFSET 0x174 /* RW: Vector Address 29 Register */
|
||||
#define VIC_VECTADDR30_OFFSET 0x178 /* RW: Vector Address 30 Register */
|
||||
#define VIC_VECTADDR31_OFFSET 0x17c /* RW: Vector Address 31 Register */
|
||||
|
||||
|
||||
/*VICVectPriority */
|
||||
#define VIC_VECTPRIORITY0_OFFSET 0x200 /* RW: Vector Control 0 Register */
|
||||
#define VIC_VECTPRIORITY1_OFFSET 0x204 /* RW: Vector Control 1 Register */
|
||||
#define VIC_VECTPRIORITY2_OFFSET 0x208 /* RW: Vector Control 2 Register */
|
||||
#define VIC_VECTPRIORITY3_OFFSET 0x20c /* RW: Vector Control 3 Register */
|
||||
#define VIC_VECTPRIORITY4_OFFSET 0x210 /* RW: Vector Control 4 Register */
|
||||
#define VIC_VECTPRIORITY5_OFFSET 0x214 /* RW: Vector Control 5 Register */
|
||||
#define VIC_VECTPRIORITY6_OFFSET 0x218 /* RW: Vector Control 6 Register */
|
||||
#define VIC_VECTPRIORITY7_OFFSET 0x21c /* RW: Vector Control 7 Register */
|
||||
#define VIC_VECTPRIORITY8_OFFSET 0x220 /* RW: Vector Control 8 Register */
|
||||
#define VIC_VECTPRIORITY9_OFFSET 0x224 /* RW: Vector Control 9 Register */
|
||||
#define VIC_VECTPRIORITY10_OFFSET 0x228 /* RW: Vector Control 10 Register */
|
||||
#define VIC_VECTPRIORITY11_OFFSET 0x22c /* RW: Vector Control 11 Register */
|
||||
#define VIC_VECTPRIORITY12_OFFSET 0x230 /* RW: Vector Control 12 Register */
|
||||
#define VIC_VECTPRIORITY13_OFFSET 0x234 /* RW: Vector Control 13 Register */
|
||||
#define VIC_VECTPRIORITY14_OFFSET 0x238 /* RW: Vector Control 14 Register */
|
||||
#define VIC_VECTPRIORITY15_OFFSET 0x23c /* RW: Vector Control 15 Register */
|
||||
#define VIC_VECTPRIORITY16_OFFSET 0x240 /* RW: Vector Control 16 Register */
|
||||
#define VIC_VECTPRIORITY17_OFFSET 0x244 /* RW: Vector Control 17 Register */
|
||||
#define VIC_VECTPRIORITY18_OFFSET 0x248 /* RW: Vector Control 18 Register */
|
||||
#define VIC_VECTPRIORITY19_OFFSET 0x24c /* RW: Vector Control 19 Register */
|
||||
#define VIC_VECTPRIORITY20_OFFSET 0x250 /* RW: Vector Control 20 Register */
|
||||
#define VIC_VECTPRIORITY21_OFFSET 0x254 /* RW: Vector Control 21 Register */
|
||||
#define VIC_VECTPRIORITY22_OFFSET 0x258 /* RW: Vector Control 22 Register */
|
||||
#define VIC_VECTPRIORITY23_OFFSET 0x25c /* RW: Vector Control 23 Register */
|
||||
#define VIC_VECTPRIORITY24_OFFSET 0x260 /* RW: Vector Control 24 Register */
|
||||
#define VIC_VECTPRIORITY25_OFFSET 0x264 /* RW: Vector Control 25 Register */
|
||||
#define VIC_VECTPRIORITY26_OFFSET 0x268 /* RW: Vector Control 26 Register */
|
||||
#define VIC_VECTPRIORITY27_OFFSET 0x26c /* RW: Vector Control 27 Register */
|
||||
#define VIC_VECTPRIORITY28_OFFSET 0x270 /* RW: Vector Control 28 Register */
|
||||
#define VIC_VECTPRIORITY29_OFFSET 0x274 /* RW: Vector Control 29 Register */
|
||||
#define VIC_VECTPRIORITY30_OFFSET 0x278 /* RW: Vector Control 30 Register */
|
||||
#define VIC_VECTPRIORITY31_OFFSET 0x27c /* RW: Vector Control 31 Register */
|
||||
|
||||
/****************************************************************************************************
|
||||
* Inline Functions
|
||||
****************************************************************************************************/
|
||||
|
||||
/****************************************************************************************************
|
||||
* Global Function Prototypes
|
||||
****************************************************************************************************/
|
||||
|
||||
#endif /* _ARCH_ARM_SRC_LPC2378_CHIP_H */
|
70
arch/arm/src/lpc2378/internal.h
Executable file
70
arch/arm/src/lpc2378/internal.h
Executable file
@ -0,0 +1,70 @@
|
||||
/****************************************************************************************************
|
||||
* arch/arm/src/lpc2378/chip.h
|
||||
*
|
||||
* Copyright (C) 2010 Rommel Marcelo. All rights reserved.
|
||||
* Author: Rommel Marcelo
|
||||
*
|
||||
* This file is part of the NuttX RTOS and based on the lpc2148 port:
|
||||
*
|
||||
* 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.
|
||||
*
|
||||
****************************************************************************************************/
|
||||
|
||||
#ifndef _ARCH_ARM_SRC_LPC2378_INTERNAL_H
|
||||
#define _ARCH_ARM_SRC_LPC2378_INTERNAL_H
|
||||
|
||||
/****************************************************************************************************
|
||||
* Included Files
|
||||
****************************************************************************************************/
|
||||
|
||||
#include "up_internal.h"
|
||||
#include "chip.h"
|
||||
|
||||
/****************************************************************************************************
|
||||
* Pre-processor Definitions
|
||||
****************************************************************************************************/
|
||||
|
||||
//~ #define CONFIG_VECTORED_INTERRUPTS
|
||||
|
||||
/****************************************************************************************************
|
||||
* Global Function Prototypes
|
||||
****************************************************************************************************/
|
||||
|
||||
#ifndef __ASSEMBLY__
|
||||
|
||||
#ifdef CONFIG_ARCH_LEDS
|
||||
extern void up_statledoff(void);
|
||||
extern void up_statledon(void);
|
||||
#endif
|
||||
|
||||
#endif
|
||||
|
||||
#endif /* _ARCH_ARM_SRC_LPC2378_INTERNAL_H */
|
168
arch/arm/src/lpc2378/lpc23xx_decodeirq.c
Executable file
168
arch/arm/src/lpc2378/lpc23xx_decodeirq.c
Executable file
@ -0,0 +1,168 @@
|
||||
/********************************************************************************
|
||||
* arch/arm/src/lpc2378/lpc23xx_decodeirq.c
|
||||
*
|
||||
* Copyright (C) 2010 Rommel Marcelo. All rights reserved.
|
||||
* Author: Rommel Marcelo
|
||||
*
|
||||
* This file is part of the NuttX RTOS and based on the lpc2148 port:
|
||||
*
|
||||
* 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.
|
||||
*
|
||||
********************************************************************************/
|
||||
|
||||
/********************************************************************************
|
||||
* Included Files
|
||||
********************************************************************************/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
|
||||
#include <sys/types.h>
|
||||
#include <stdint.h>
|
||||
#include <nuttx/irq.h>
|
||||
#include <nuttx/arch.h>
|
||||
#include <assert.h>
|
||||
#include <debug.h>
|
||||
|
||||
#include <arch/board/board.h>
|
||||
|
||||
#include "up_arch.h"
|
||||
#include "os_internal.h"
|
||||
#include "internal.h"
|
||||
#include "lpc23xx_vic.h"
|
||||
|
||||
/********************************************************************************
|
||||
* Definitions
|
||||
********************************************************************************/
|
||||
|
||||
/********************************************************************************
|
||||
* Private Types
|
||||
********************************************************************************/
|
||||
|
||||
/********************************************************************************
|
||||
* Public Data
|
||||
********************************************************************************/
|
||||
|
||||
/********************************************************************************
|
||||
* Private Data
|
||||
********************************************************************************/
|
||||
|
||||
/********************************************************************************
|
||||
* Private Functions
|
||||
********************************************************************************/
|
||||
|
||||
/********************************************************************************
|
||||
* Public Funstions
|
||||
********************************************************************************/
|
||||
|
||||
/********************************************************************************
|
||||
* up_decodeirq() and/or lpc23xx_decodeirq()
|
||||
*
|
||||
* Description:
|
||||
* The vectored interrupt controller (VIC) takes 32 interrupt request inputs
|
||||
* and programmatically assigns them into 2 categories: FIQ, vectored IRQ.
|
||||
*
|
||||
* - FIQs have the highest priority. There is a single FIQ vector, but multiple
|
||||
* interrupt sources can be ORed to this FIQ vector.
|
||||
*
|
||||
* - Vectored IRQs have the middle priority. Any of the 32 interrupt sources
|
||||
* can be assigned to vectored IRQs.
|
||||
*
|
||||
* - Non-vectored IRQs have the lowest priority.
|
||||
*
|
||||
* The general flow of IRQ processing is to simply read the VICAddress
|
||||
* and jump to the address of the vector provided in the register. The VIC will
|
||||
* provide the address of the highest priority vectored IRQ. If a non-vectored
|
||||
* IRQ is requesting, the address of a default handler is provided.
|
||||
*
|
||||
********************************************************************************/
|
||||
|
||||
#ifndef CONFIG_VECTORED_INTERRUPTS
|
||||
void up_decodeirq(uint32_t *regs)
|
||||
#else
|
||||
static void lpc23xx_decodeirq( uint32_t *regs)
|
||||
#endif
|
||||
{
|
||||
#ifdef CONFIG_SUPPRESS_INTERRUPTS
|
||||
lib_lowprintf("Unexpected IRQ\n");
|
||||
current_regs = regs;
|
||||
PANIC(OSERR_ERREXCEPTION);
|
||||
#else
|
||||
|
||||
/* Check which IRQ fires */
|
||||
|
||||
uint32_t irqbits = vic_getreg(VIC_IRQSTATUS_OFFSET) & 0xFFFFFFFF;
|
||||
unsigned int irq;
|
||||
|
||||
for (irq = 0; irq < NR_IRQS; irq++)
|
||||
{
|
||||
if( irqbits & (uint32_t)(1<<irq) ) break;
|
||||
}
|
||||
|
||||
/* Verify that the resulting IRQ number is valid */
|
||||
|
||||
if (irq < NR_IRQS) /* redundant check ?? */
|
||||
{
|
||||
/* Current regs non-zero indicates that we are processing an interrupt;
|
||||
* current_regs is also used to manage interrupt level context switches.
|
||||
*/
|
||||
DEBUGASSERT(current_regs == NULL);
|
||||
current_regs = regs;
|
||||
|
||||
/* Mask and acknowledge the interrupt */
|
||||
|
||||
up_maskack_irq(irq);
|
||||
|
||||
/* Deliver the IRQ */
|
||||
|
||||
irq_dispatch(irq, regs);
|
||||
|
||||
/* Indicate that we are no longer in an interrupt handler */
|
||||
|
||||
current_regs = NULL;
|
||||
}
|
||||
|
||||
#endif
|
||||
}
|
||||
|
||||
#ifdef CONFIG_VECTORED_INTERRUPTS
|
||||
void up_decodeirq(uint32_t *regs)
|
||||
{
|
||||
vic_vector_t vector = (vic_vector_t)vic_getreg(VIC_ADDRESS_OFFSET);
|
||||
|
||||
/* Mask and acknowledge the interrupt */
|
||||
|
||||
up_maskack_irq(irq);
|
||||
|
||||
/* Valid Interrupt */
|
||||
if(vector != NULL)
|
||||
(vector)(regs);
|
||||
}
|
||||
#endif
|
71
arch/arm/src/lpc2378/lpc23xx_gpio.h
Executable file
71
arch/arm/src/lpc2378/lpc23xx_gpio.h
Executable file
@ -0,0 +1,71 @@
|
||||
/************************************************************************************
|
||||
* arch/arm/src/lpc2378/lpc231x_gpio.h
|
||||
*
|
||||
* Copyright (C) 2010 Rommel Marcelo. All rights reserved.
|
||||
* Author: Rommel Marcelo
|
||||
*
|
||||
* This file is part of the NuttX RTOS and based on the lpc2148 port:
|
||||
*
|
||||
* 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.
|
||||
*
|
||||
************************************************************************************/
|
||||
|
||||
#ifndef _ARCH_ARM_SRC_LPC2378_LPC23XX_GPIO_H
|
||||
#define _ARCH_ARM_SRC_LPC2378_LPC23XX_GPIO_H
|
||||
|
||||
/************************************************************************************
|
||||
* Included Files
|
||||
************************************************************************************/
|
||||
#include "chip.h"
|
||||
/************************************************************************************
|
||||
* Definitions
|
||||
************************************************************************************/
|
||||
#define io_getreg8(o) getreg8(LPC23XX_FIO_BASE+(o))
|
||||
#define io_getreg(r) getreg32(LPC23XX_FIO_BASE+ (r))
|
||||
#define dir_getreg8(o) getreg8(LPC23XX_FIO_BASE+(o))
|
||||
#define dir_getreg(r) getreg32(LPC23XX_FIO_BASE+ (r))
|
||||
#define dir_putreg8(v,o) putreg8((v), LPC23XX_FIO_BASE+(o))
|
||||
#define dir_putreg(v,r) putreg32((v),LPC23XX_FIO_BASE+ (r))
|
||||
#define fio_putreg8(v,o) putreg8((v), LPC23XX_FIO_BASE+(o))
|
||||
#define fio_getreg8(o) getreg8(LPC23XX_FIO_BASE+(o))
|
||||
/************************************************************************************
|
||||
* Public Types
|
||||
************************************************************************************/
|
||||
|
||||
/************************************************************************************
|
||||
* Inline Functions
|
||||
************************************************************************************/
|
||||
|
||||
/************************************************************************************
|
||||
* Public Function Prototypes
|
||||
************************************************************************************/
|
||||
|
||||
#endif /* _ARCH_ARM_SRC_LPC2378_LPC23XX_GPIO_H */
|
235
arch/arm/src/lpc2378/lpc23xx_head.S
Executable file
235
arch/arm/src/lpc2378/lpc23xx_head.S
Executable file
@ -0,0 +1,235 @@
|
||||
/****************************************************************************
|
||||
* arch/arm/src/arm/lpc2378/lpc23xx_head.S
|
||||
*
|
||||
* Copyright (C) 2010 Rommel Marcelo. All rights reserved.
|
||||
* Author: Rommel Marcelo
|
||||
*
|
||||
* This file is part of the NuttX RTOS and based on the lpc2148 port:
|
||||
*
|
||||
* 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.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Included Files
|
||||
****************************************************************************/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
#include <arch/board/board.h>
|
||||
|
||||
#include "arm.h"
|
||||
#include "internal.h"
|
||||
#include "up_arch.h"
|
||||
#include "lpc23xx_uart.h"
|
||||
#include "lpc23xx_scb.h"
|
||||
#include "lpc23xx_pinsel.h"
|
||||
|
||||
/****************************************************************************
|
||||
* Macros
|
||||
****************************************************************************/
|
||||
|
||||
/* Print a character on the UART to show boot status. This macro will
|
||||
* modify r0, r1, r2 and r14
|
||||
*/
|
||||
#ifdef CONFIG_DEBUG
|
||||
.macro showprogress, code
|
||||
mov r0, #\code
|
||||
bl up_lowputc
|
||||
.endm
|
||||
#else
|
||||
.macro showprogress, code
|
||||
.endm
|
||||
#endif
|
||||
|
||||
/*****************************************************************************
|
||||
* Text
|
||||
*****************************************************************************/
|
||||
|
||||
.text
|
||||
|
||||
/*****************************************************************************
|
||||
* Name: _vector_table
|
||||
*
|
||||
* Description:
|
||||
* Interrrupt vector table. This must be located at the beginning
|
||||
* of the memory space (at CONFIG_CODE_BASE). The first entry in
|
||||
* the vector table is the reset vector and this is the code that
|
||||
* will execute whn the processor is reset.
|
||||
*
|
||||
*****************************************************************************/
|
||||
|
||||
.globl _vector_table
|
||||
.type _vector_table, %function
|
||||
_vector_table:
|
||||
ldr pc, .Lresethandler /* 0x00: Reset */
|
||||
ldr pc, .Lundefinedhandler /* 0x04: Undefined instruction */
|
||||
ldr pc, .Lswihandler /* 0x08: Software interrupt */
|
||||
ldr pc, .Lprefetchaborthandler /* 0x0c: Prefetch abort */
|
||||
ldr pc, .Ldataaborthandler /* 0x10: Data abort */
|
||||
.long 0xB8A06F58 /* 0x14: Vector checksum */
|
||||
ldr pc, .Lirqhandler /* 0x18: IRQ */
|
||||
ldr pc, .Lfiqhandler /* 0x1c: FIQ */
|
||||
|
||||
.globl __start
|
||||
.globl up_vectorundefinsn
|
||||
.globl up_vectorswi
|
||||
.globl up_vectorprefetch
|
||||
.globl up_vectordata
|
||||
.globl up_vectorirq
|
||||
.globl up_vectorfiq
|
||||
|
||||
.Lresethandler:
|
||||
.long __start
|
||||
.Lundefinedhandler:
|
||||
.long up_vectorundefinsn
|
||||
.Lswihandler:
|
||||
.long up_vectorswi
|
||||
.Lprefetchaborthandler:
|
||||
.long up_vectorprefetch
|
||||
.Ldataaborthandler:
|
||||
.long up_vectordata
|
||||
.Lirqhandler:
|
||||
.long up_vectorirq
|
||||
.Lfiqhandler:
|
||||
.long up_vectorfiq
|
||||
.size _vector_table, . - _vector_table
|
||||
|
||||
|
||||
/****************************************************************************
|
||||
* OS Entry Point
|
||||
****************************************************************************/
|
||||
|
||||
/* We assume the bootloader has already initialized most of the h/w for
|
||||
* us and that only leaves us having to do some os specific things
|
||||
* below.
|
||||
*/
|
||||
.text
|
||||
.globl __start
|
||||
.type __start, #function
|
||||
__start:
|
||||
|
||||
/* Call lowlevel init C-function */
|
||||
.extern ConfigurePLL
|
||||
ldr r0, =ConfigurePLL
|
||||
mov lr, pc
|
||||
bx r0
|
||||
|
||||
/* First, setup initial processor mode */
|
||||
|
||||
mov r0, #(SVC_MODE | PSR_I_BIT | PSR_F_BIT )
|
||||
msr cpsr, r0
|
||||
|
||||
/* Configure the uart so that we can get debug output as soon
|
||||
* as possible. Modifies r0, r1, r2, and r14.
|
||||
*/
|
||||
bl up_lowsetup
|
||||
|
||||
showprogress 'A'
|
||||
|
||||
|
||||
/* Setup system stack (and get the BSS range) */
|
||||
|
||||
adr r0, LC0
|
||||
ldmia r0, {r4, r5, sp}
|
||||
|
||||
/* Clear system BSS section (Initialize with 0) */
|
||||
|
||||
mov r0, #0
|
||||
1: cmp r4, r5
|
||||
strcc r0, [r4], #4
|
||||
bcc 1b
|
||||
|
||||
showprogress 'B'
|
||||
|
||||
/* Copy system .data sections to new home in RAM. */
|
||||
|
||||
adr r3, LC2
|
||||
ldmia r3, {r0, r1, r2}
|
||||
|
||||
2: ldmia r0!, {r3 - r10}
|
||||
stmia r1!, {r3 - r10}
|
||||
cmp r1, r2
|
||||
blt 2b
|
||||
|
||||
/* Perform early serial initialization */
|
||||
|
||||
mov fp, #0
|
||||
#ifdef CONFIG_USE_EARLYSERIALINIT
|
||||
bl up_earlyserialinit
|
||||
showprogress 'S'
|
||||
#endif
|
||||
|
||||
showprogress 'C'
|
||||
showprogress '\n'
|
||||
|
||||
/* Initialize onboard LEDs */
|
||||
|
||||
#ifdef CONFIG_ARCH_LEDS
|
||||
bl up_ledinit
|
||||
#endif
|
||||
|
||||
/* Then jump to OS entry */
|
||||
|
||||
b os_start
|
||||
|
||||
/* Variables:
|
||||
* _sbss is the start of the BSS region (see ld.script)
|
||||
* _ebss is the end of the BSS regsion (see ld.script)
|
||||
* The idle task stack starts at the end of BSS and is
|
||||
* of size CONFIG_IDLETHREAD_STACKSIZE. The heap continues
|
||||
* from there until the end of memory. See g_heapbase
|
||||
* below.
|
||||
*/
|
||||
|
||||
LC0: .long _sbss
|
||||
.long _ebss
|
||||
.long _ebss+CONFIG_IDLETHREAD_STACKSIZE-4
|
||||
|
||||
LC2: .long _eronly /* Where .data defaults are stored in FLASH */
|
||||
.long _sdata /* Where .data needs to reside in SDRAM */
|
||||
.long _edata
|
||||
.size __start, .-__start
|
||||
|
||||
/* This global variable is unsigned long g_heapbase and is
|
||||
* exported from here only because of its coupling to LCO
|
||||
* above.
|
||||
*/
|
||||
|
||||
.data
|
||||
.align 4
|
||||
.globl g_heapbase
|
||||
.type g_heapbase, object
|
||||
g_heapbase:
|
||||
.long _ebss+CONFIG_IDLETHREAD_STACKSIZE
|
||||
.size g_heapbase, .-g_heapbase
|
||||
|
||||
.end
|
||||
|
93
arch/arm/src/lpc2378/lpc23xx_io.c
Executable file
93
arch/arm/src/lpc2378/lpc23xx_io.c
Executable file
@ -0,0 +1,93 @@
|
||||
/***********************************************************************
|
||||
* arch/arm/src/arm/lpc2378/lpc23xx_head.S
|
||||
*
|
||||
* Copyright (C) 2010 Rommel Marcelo. All rights reserved.
|
||||
* Author: Rommel Marcelo
|
||||
*
|
||||
* This file is part of the NuttX RTOS:
|
||||
*
|
||||
* Copyright (C) 2010 Gregory Nutt. All rights reserved.
|
||||
*
|
||||
* 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 "up_arch.h"
|
||||
#include <sys/types.h>
|
||||
#include "lpc23xx_scb.h"
|
||||
#include "lpc23xx_pinsel.h"
|
||||
#include "lpc23xx_uart.h"
|
||||
#include "lpc23xx_gpio.h"
|
||||
|
||||
/***********************************************************************
|
||||
* Definitions
|
||||
***********************************************************************/
|
||||
|
||||
/******************************************************************************
|
||||
* Name: IO_Init()
|
||||
*
|
||||
* Descriptions: Initialize the target board before running the main()
|
||||
*
|
||||
******************************************************************************/
|
||||
void IO_Init( void )
|
||||
{
|
||||
uint32_t regval;
|
||||
/* Reset all GPIO pins to default */
|
||||
pinsel_putreg(0, PINSEL0_OFFSET);
|
||||
pinsel_putreg(0, PINSEL1_OFFSET);
|
||||
pinsel_putreg(0, PINSEL2_OFFSET);
|
||||
pinsel_putreg(0, PINSEL3_OFFSET);
|
||||
pinsel_putreg(0, PINSEL4_OFFSET);
|
||||
pinsel_putreg(0, PINSEL5_OFFSET);
|
||||
pinsel_putreg(0, PINSEL6_OFFSET);
|
||||
pinsel_putreg(0, PINSEL7_OFFSET);
|
||||
pinsel_putreg(0, PINSEL8_OFFSET);
|
||||
pinsel_putreg(0, PINSEL9_OFFSET);
|
||||
pinsel_putreg(0, PINSEL10_OFFSET);
|
||||
/*
|
||||
regval = scb_getreg(SCB_PCONP_OFFSET) & \
|
||||
~(PCSDC | PCUART1 | PCI2C0 | PCSSP1 | PCEMC | );
|
||||
scb_getreg( regval, SCB_PCONP_OFFSET );
|
||||
*/
|
||||
/* Turn off all peripheral power */
|
||||
scb_putreg( 0, SCB_PCONP_OFFSET );
|
||||
|
||||
/* Turn on UART0/2 / Timer0 */
|
||||
//~ regval = PCUART0 | PCUART2 | PCTIM0 | PCRTC ;
|
||||
regval = PCUART0 | PCUART2 | PCTIM0 ;
|
||||
scb_putreg( regval , SCB_PCONP_OFFSET );
|
||||
|
||||
/* Status LED P1.19 */
|
||||
dir_putreg8((1 << 3), FIO1DIR2_OFFSET);
|
||||
/* other io setup here */
|
||||
return;
|
||||
}
|
291
arch/arm/src/lpc2378/lpc23xx_irq.c
Executable file
291
arch/arm/src/lpc2378/lpc23xx_irq.c
Executable file
@ -0,0 +1,291 @@
|
||||
/****************************************************************************
|
||||
* arch/arm/src/lpc2378/lpc23xx_irq.c
|
||||
*
|
||||
* Copyright (C) 2010 Rommel Marcelo. All rights reserved.
|
||||
* Author: Rommel Marcelo
|
||||
*
|
||||
* This file is part of the NuttX RTOS and based on the lpc2148 port:
|
||||
*
|
||||
* 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.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Included Files
|
||||
****************************************************************************/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
|
||||
#include <stdint.h>
|
||||
#include <errno.h>
|
||||
#include <debug.h>
|
||||
#include <nuttx/irq.h>
|
||||
|
||||
#include "arm.h"
|
||||
#include "chip.h"
|
||||
#include "up_arch.h"
|
||||
#include "os_internal.h"
|
||||
|
||||
#include "internal.h"
|
||||
#include "lpc23xx_vic.h"
|
||||
|
||||
/****************************************************************************
|
||||
* Definitions
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Public Data
|
||||
****************************************************************************/
|
||||
|
||||
uint32_t *current_regs;
|
||||
|
||||
/****************************************************************************
|
||||
* Private Data
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Private Functions
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Public Functions
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Name: up_irqinitialize
|
||||
****************************************************************************/
|
||||
|
||||
void up_irqinitialize(void)
|
||||
{
|
||||
int reg;
|
||||
|
||||
/* Disable all interrupts. We do this by writing ones to the IntClearEnable
|
||||
* register.
|
||||
*/
|
||||
vic_putreg(0xffffffff, VIC_INTENCLEAR_OFFSET);
|
||||
|
||||
/* Select all IRQs, FIQs are not used */
|
||||
vic_putreg(0, VIC_INTSELECT_OFFSET);
|
||||
|
||||
/* Clear priority interrupts */
|
||||
|
||||
for (reg = 0; reg < NR_IRQS; reg++)
|
||||
{
|
||||
vic_putreg(0, VIC_VECTADDR0_OFFSET + (reg << 2));
|
||||
vic_putreg(0x0F, VIC_VECTPRIORITY0_OFFSET + (reg << 2));
|
||||
}
|
||||
|
||||
/* currents_regs is non-NULL only while processing an interrupt */
|
||||
|
||||
current_regs = NULL;
|
||||
|
||||
/* Enable global ARM interrupts */
|
||||
|
||||
#ifndef CONFIG_SUPPRESS_INTERRUPTS
|
||||
irqrestore(SVC_MODE | PSR_F_BIT);
|
||||
#endif
|
||||
}
|
||||
/***********************************************************************
|
||||
* Name: up_enable_irq_protect
|
||||
* VIC registers can be accessed in User or privileged mode
|
||||
***********************************************************************/
|
||||
static void up_enable_irq_protect(void)
|
||||
{
|
||||
//~ uint32_t reg32 = vic_getreg(VIC_PROTECTION_OFFSET);
|
||||
//~ reg32 &= ~(0xFFFFFFFF);
|
||||
vic_putreg(0x01, VIC_PROTECTION_OFFSET);
|
||||
}
|
||||
|
||||
/***********************************************************************
|
||||
* Name: up_disable_irq_protect
|
||||
* VIC registers can only be accessed in privileged mode
|
||||
***********************************************************************/
|
||||
static void up_disable_irq_protect(void)
|
||||
{
|
||||
vic_putreg(0, VIC_PROTECTION_OFFSET);
|
||||
}
|
||||
/***********************************************************************
|
||||
* Name: up_disable_irq
|
||||
*
|
||||
* Description:
|
||||
* Disable the IRQ specified by 'irq'
|
||||
*
|
||||
***********************************************************************/
|
||||
|
||||
void up_disable_irq(int irq)
|
||||
{
|
||||
/* Verify that the IRQ number is within range */
|
||||
|
||||
if (irq < NR_IRQS)
|
||||
{
|
||||
/* Disable the irq by setting the corresponding bit in the VIC
|
||||
* Interrupt Enable Clear register.
|
||||
*/
|
||||
|
||||
vic_putreg((1 << irq), VIC_INTENCLEAR_OFFSET);
|
||||
}
|
||||
}
|
||||
|
||||
/***********************************************************************
|
||||
* Name: up_enable_irq
|
||||
*
|
||||
* Description:
|
||||
* Enable the IRQ specified by 'irq'
|
||||
*
|
||||
***********************************************************************/
|
||||
|
||||
void up_enable_irq(int irq)
|
||||
{
|
||||
/* Verify that the IRQ number is within range */
|
||||
|
||||
if (irq < NR_IRQS)
|
||||
{
|
||||
/* Disable all interrupts */
|
||||
|
||||
irqstate_t flags = irqsave();
|
||||
|
||||
/* Enable the irq by setting the corresponding bit in the VIC
|
||||
* Interrupt Enable register.
|
||||
*/
|
||||
|
||||
uint32_t val = vic_getreg(VIC_INTENABLE_OFFSET);
|
||||
vic_putreg(val | (1 << irq), VIC_INTENABLE_OFFSET);
|
||||
irqrestore(flags);
|
||||
}
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
* Name: up_maskack_irq
|
||||
*
|
||||
* Description:
|
||||
* Mask the IRQ and acknowledge it
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
void up_maskack_irq(int irq)
|
||||
{
|
||||
uint32_t reg32;
|
||||
|
||||
if ((unsigned)irq < NR_IRQS)
|
||||
{
|
||||
/* Mask the IRQ by clearing the associated bit in Software Priority Mask register */
|
||||
reg32 = vic_getreg(VIC_PRIORITY_MASK_OFFSET);
|
||||
reg32 &= ~(1 << irq);
|
||||
vic_putreg(reg32, VIC_PRIORITY_MASK_OFFSET);
|
||||
}
|
||||
/* Clear interrupt */
|
||||
vic_putreg((1<<irq), VIC_SOFTINTCLEAR_OFFSET);
|
||||
#ifdef CONFIG_VECTORED_INTERRUPTS
|
||||
vic_putreg(0, VIC_ADDRESS_OFFSET); /* dummy write to clear VICADDRESS */
|
||||
#endif
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
* Name: up_prioritize_irq
|
||||
*
|
||||
* Description:
|
||||
* set interrupt priority
|
||||
* MOD
|
||||
****************************************************************************/
|
||||
|
||||
int up_prioritize_irq(int irq, int priority)
|
||||
{
|
||||
/* The default priority on reset is 16 */
|
||||
if (irq < NR_IRQS && priority > 0 && priority < 16)
|
||||
{
|
||||
int offset = irq << 2;
|
||||
vic_putreg( priority, VIC_VECTPRIORITY0_OFFSET + offset );
|
||||
return OK;
|
||||
}
|
||||
return -EINVAL;
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
* Name: up_attach_vector
|
||||
*
|
||||
* Description:
|
||||
* Attach a user-supplied handler to a vectored interrupt
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
#ifndef CONFIG_VECTORED_INTERRUPTS
|
||||
void up_attach_vector(int irq, int vector, vic_vector_t handler)
|
||||
{
|
||||
/* Verify that the IRQ number and vector number are within range */
|
||||
|
||||
if (irq < NR_IRQS && vector < 32 && handler)
|
||||
{
|
||||
int offset = vector << 2;
|
||||
|
||||
/* Disable all interrupts */
|
||||
|
||||
irqstate_t flags = irqsave();
|
||||
|
||||
/* Save the vector address */
|
||||
|
||||
vic_putreg((uint32_t)handler, VIC_VECTADDR0_OFFSET + offset);
|
||||
|
||||
/* Set the interrupt priority */
|
||||
|
||||
up_prioritize_irq(irq, vector);
|
||||
|
||||
/* Enable the vectored interrupt */
|
||||
|
||||
uint32_t val = vic_getreg(VIC_INTENABLE_OFFSET);
|
||||
vic_putreg(val | (1 << irq), VIC_INTENABLE_OFFSET);
|
||||
|
||||
irqrestore(flags);
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
||||
/****************************************************************************
|
||||
* Name: up_detach_vector
|
||||
*
|
||||
* Description:
|
||||
* Detach a user-supplied handler from a vectored interrupt
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
#ifdef CONFIG_VECTORED_INTERRUPTS
|
||||
void up_detach_vector(int vector)
|
||||
{
|
||||
/* Verify that the vector number is within range */
|
||||
|
||||
if (vector < 32)
|
||||
{
|
||||
/* Disable the vectored interrupt */
|
||||
|
||||
int offset = vector << 2;
|
||||
vic_putreg(0, (VIC_VECTADDR0_OFFSET + offset));
|
||||
}
|
||||
}
|
||||
#endif
|
262
arch/arm/src/lpc2378/lpc23xx_lowputc.S
Executable file
262
arch/arm/src/lpc2378/lpc23xx_lowputc.S
Executable file
@ -0,0 +1,262 @@
|
||||
/**************************************************************************
|
||||
* arch/arm/src/lpc2378/lpc23xx_lowputc.S
|
||||
*
|
||||
* Copyright (C) 2010 Rommel Marcelo. All rights reserved.
|
||||
* Author: Rommel Marcelo
|
||||
*
|
||||
* This file is part of the NuttX RTOS and based on the lpc2148 port:
|
||||
*
|
||||
* 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.
|
||||
*
|
||||
**************************************************************************/
|
||||
|
||||
/**************************************************************************
|
||||
* Included Files
|
||||
**************************************************************************/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
#include "up_internal.h"
|
||||
#include "up_arch.h"
|
||||
#include "lpc23xx_pinsel.h"
|
||||
#include "lpc23xx_scb.h"
|
||||
#include "lpc23xx_uart.h"
|
||||
|
||||
/**************************************************************************
|
||||
* Private Definitions
|
||||
**************************************************************************/
|
||||
@ //-- Pins
|
||||
@ PINSEL0 |= (0x01<<4) | //-- P0.2 TXD0
|
||||
@ (0x01<<6); //-- P0.3 RXD0
|
||||
@PCLKSEL0 |= (0x01 << 6); //-- bit 7:6 =01-> Clock div = 1 for UART0
|
||||
|
||||
#if defined(CONFIG_UART0_SERIAL_CONSOLE)
|
||||
# define UARTxBASE UART0_BASE_ADDR
|
||||
# define PINSELECT LPC23XX_PINSEL0
|
||||
# define UARTxPCLKSEL 0xE01FC1A8
|
||||
# define PCLKSEL_MASK U0_PCLKSEL_MASK
|
||||
# define UARTxPINSEL UART0_PINSEL
|
||||
# define UARTxPINMASK UART0_PINMASK
|
||||
# define UARTxBAUD CONFIG_UART0_BAUD
|
||||
# define UARTxBITS CONFIG_UART0_BITS
|
||||
# define UARTxPARITY CONFIG_UART0_PARITY
|
||||
# define UARTx2STOP CONFIG_UART0_2STOP
|
||||
#elif defined(CONFIG_UART1_SERIAL_CONSOLE)
|
||||
# define UARTxBASE UART1_BASE_ADDR
|
||||
/* # define PINSELECT LPC23XX_PINSEL1 only Uart0/Uart2 share same Pinsel */
|
||||
# define UARTxPCLKSEL 0xE01FC1A8
|
||||
# define PCLKSEL_MASK U1_PCLKSEL_MASK
|
||||
# define UARTxPINSEL UART1_PINSEL
|
||||
# define UARTxPINMASK UART1_PINMASK
|
||||
# define UARTxBAUD CONFIG_UART1_BAUD
|
||||
# define UARTxBITS CONFIG_UART1_BITS
|
||||
# define UARTxPARITY CONFIG_UART1_PARITY
|
||||
# define UARTx2STOP CONFIG_UART1_2STOP
|
||||
#elif defined(CONFIG_UART2_SERIAL_CONSOLE)
|
||||
# define UARTxBASE UART2_BASE_ADDR
|
||||
# define PINSELECT LPC23XX_PINSEL0
|
||||
# define UARTxPCLKSEL 0xE01FC1AC
|
||||
# define PCLKSEL_MASK U2_PCLKSEL_MASK
|
||||
# define UARTxPINSEL UART2_PINSEL
|
||||
# define UARTxPINMASK UART2_PINMASK
|
||||
# define UARTxBAUD CONFIG_UART2_BAUD
|
||||
# define UARTxBITS CONFIG_UART2_BITS
|
||||
# define UARTxPARITY CONFIG_UART2_PARITY
|
||||
# define UARTx2STOP CONFIG_UART2_2STOP
|
||||
#elif defined(CONFIG_UART3_SERIAL_CONSOLE)
|
||||
# define PINSELECT LPC23XX_PINSEL0
|
||||
# define UARTxBASE UART3_BASE_ADDR
|
||||
# define UARTxPCLKSEL 0xE01FC1AC
|
||||
# define PCLKSEL_MASK U2_PCLKSEL_MASK
|
||||
# define UARTxPINSEL UART3_PINSEL
|
||||
# define UARTxPINMASK UART3_PINMASK
|
||||
# define UARTxBAUD CONFIG_UART3_BAUD
|
||||
# define UARTxBITS CONFIG_UART3_BITS
|
||||
# define UARTxPARITY CONFIG_UART3_PARITY
|
||||
# define UARTx2STOP CONFIG_UART3_2STOP
|
||||
#else
|
||||
# error "No CONFIG_UARTn_SERIAL_CONSOLE Setting"
|
||||
#endif
|
||||
|
||||
#if UARTxBITS == 5
|
||||
# define LCR_CHAR LCR_CHAR_5
|
||||
#elif UARTxBITS == 6
|
||||
# define LCR_CHAR LCR_CHAR_6
|
||||
#elif UARTxBITS == 7
|
||||
# define LCR_CHAR LCR_CHAR_7
|
||||
#elif UARTxBITS == 8
|
||||
# define LCR_CHAR LCR_CHAR_8
|
||||
#else
|
||||
# error "No CONFIG_UARTn_BITS Setting"
|
||||
#endif
|
||||
|
||||
#if UARTxPARITY == 0
|
||||
# define LCR_PAR LCR_PAR_NONE
|
||||
#elif UARTxPARITY == 1
|
||||
# define LCR_PAR LCR_PAR_ODD
|
||||
#elif UARTxPARITY == 2
|
||||
# define LCR_PAR LCR_PAR_EVEN
|
||||
#elif UARTxPARITY == 3
|
||||
# define LCR_PAR LCR_PAR_MARK
|
||||
#elif UARTxPARITY == 4
|
||||
# define LCR_PAR LCR_PAR_SPACE
|
||||
#else
|
||||
# error "No CONFIG_UARTn_PARITY Setting"
|
||||
#endif
|
||||
|
||||
#if UARTx2STOP != 0
|
||||
# define LCR_STOP LCR_STOP_2
|
||||
#else
|
||||
# define LCR_STOP LCR_STOP_1
|
||||
#endif
|
||||
|
||||
#define LCR_VALUE (LCR_CHAR | LCR_PAR | LCR_STOP)
|
||||
#define FCR_VALUE (FCR_FIFO_TRIG8 | FCR_TX_FIFO_RESET | \
|
||||
FCR_RX_FIFO_RESET | FCR_FIFO_ENABLE)
|
||||
@#define MULVAL (12 << 4)
|
||||
@#define DIVADDVAL 3
|
||||
/**************************************************************************
|
||||
* Private Types
|
||||
**************************************************************************/
|
||||
|
||||
/**************************************************************************
|
||||
* Private Function Prototypes
|
||||
**************************************************************************/
|
||||
|
||||
/**************************************************************************
|
||||
* Global Variables
|
||||
**************************************************************************/
|
||||
|
||||
/**************************************************************************
|
||||
* Private Variables
|
||||
**************************************************************************/
|
||||
|
||||
/**************************************************************************
|
||||
* Private Functions
|
||||
**************************************************************************/
|
||||
|
||||
/**************************************************************************
|
||||
* Public Functions
|
||||
**************************************************************************/
|
||||
|
||||
/**************************************************************************
|
||||
* Name: up_lowputc
|
||||
**************************************************************************/
|
||||
|
||||
/* This assembly language version has the advantage that it does not
|
||||
* require a C stack and uses only r0-r1. Hence it can be used during
|
||||
* early boot phases.
|
||||
*/
|
||||
|
||||
.text
|
||||
.global up_lowputc
|
||||
.type up_lowputc, function
|
||||
up_lowputc:
|
||||
/* On entry, r0 holds the character to be printed */
|
||||
|
||||
ldr r1, =UARTxBASE
|
||||
strb r0, [r1, #UART_THR_OFFSET]
|
||||
|
||||
/* Wait for the byte to be transferred */
|
||||
|
||||
1: ldr r0, [r1, #UART_LSR_OFFSET]
|
||||
ands r0, #LSR_TEMT /* Transmitter empty */
|
||||
beq 1b
|
||||
|
||||
/* And return */
|
||||
|
||||
mov pc, lr
|
||||
.size up_lowputc, . - up_lowputc
|
||||
|
||||
/* This performs basic initialization of the UART. This can be called very
|
||||
* early in initialization because it does not depend on having a stack. It
|
||||
* modifies r0-r2 and r14.
|
||||
*/
|
||||
|
||||
.text
|
||||
.globl up_lowsetup
|
||||
.type up_lowsetup, function
|
||||
up_lowsetup:
|
||||
/* Configure PINSEL0 */
|
||||
|
||||
ldr r0, =PINSELECT /* TODO: generalize this for different uart pins */
|
||||
ldr r1, [r0]
|
||||
ldr r2, =(~UARTxPINMASK)
|
||||
and r1, r2
|
||||
|
||||
ldr r2, =(UARTxPINSEL)
|
||||
orr r1, r2
|
||||
str r1, [r0]
|
||||
|
||||
/* Power Up Uart0 */
|
||||
ldr r0, =UARTxPCLKSEL /* PCLKSEL0 address */
|
||||
ldr r1, [r0]
|
||||
ldr r2, =(~PCLKSEL_MASK)
|
||||
and r1, r2
|
||||
|
||||
ldr r2, =(U0_PCLKSEL)
|
||||
orr r1, r2
|
||||
str r1, [r0]
|
||||
|
||||
/* Configure parity, data bits, stop bits and set DLAB=1 */
|
||||
|
||||
ldr r0, =UARTxBASE
|
||||
mov r1, #(LCR_VALUE | LCR_DLAB_ENABLE)
|
||||
strb r1, [r0, #UART_LCR_OFFSET]
|
||||
|
||||
/* Set the BAUD divisor */
|
||||
|
||||
mov r1, #((MULVAL << 4) | DIVADDVAL)
|
||||
strb r1, [r0, #UART_FDR_OFFSET]
|
||||
|
||||
mov r1, #DLMVAL
|
||||
strb r1, [r0, #UART_DLM_OFFSET]
|
||||
|
||||
mov r1, #DLLVAL
|
||||
strb r1, [r0, #UART_DLL_OFFSET]
|
||||
|
||||
/* Clear DLAB and Set format 8N1 */
|
||||
|
||||
mov r1, #LCR_VALUE
|
||||
strb r1, [r0, #UART_LCR_OFFSET]
|
||||
|
||||
/* Configure the FIFOs */
|
||||
|
||||
mov r1, #FCR_VALUE
|
||||
strb r1, [r0, #UART_FCR_OFFSET]
|
||||
|
||||
mov r1, #LCR_VALUE
|
||||
strb r1, [r0, #UART_LCR_OFFSET]
|
||||
|
||||
/* And return */
|
||||
|
||||
mov pc, lr
|
||||
.size up_lowsetup, . - up_lowsetup
|
||||
.end
|
792
arch/arm/src/lpc2378/lpc23xx_pinsel.h
Executable file
792
arch/arm/src/lpc2378/lpc23xx_pinsel.h
Executable file
@ -0,0 +1,792 @@
|
||||
/************************************************************************************
|
||||
* arch/arm/src/lpc2378/lpc23xx_pinsel.h
|
||||
*
|
||||
* Copyright (C) 2010 Rommel Marcelo. All rights reserved.
|
||||
* Author: Rommel Marcelo
|
||||
*
|
||||
* This file is part of the NuttX RTOS and based on the lpc2148 port:
|
||||
*
|
||||
* 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.
|
||||
*
|
||||
************************************************************************************/
|
||||
|
||||
#ifndef _ARCH_ARM_SRC_LPC23XX_PINSEL_H
|
||||
#define _ARCH_ARM_SRC_LPC23XX_PINSEL_H
|
||||
|
||||
/************************************************************************************
|
||||
* Included Files
|
||||
************************************************************************************/
|
||||
#include "chip.h"
|
||||
/************************************************************************************
|
||||
* Definitions
|
||||
************************************************************************************/
|
||||
|
||||
#define PINSEL_BASE 0xE002C000
|
||||
|
||||
#define pinsel_putreg8(v,o) putreg8( (v), LPC23XX_PINSEL_BASE+(o) )
|
||||
#define pinsel_putreg(v,r) putreg32( (v),LPC23XX_PINSEL_BASE+ (r) )
|
||||
#define pinsel_getreg(o) getreg32( PINSEL_BASE+(o) )
|
||||
|
||||
/* Register address definitions *****************************************************/
|
||||
#define LPC23XX_PINSEL0 (PINSEL_BASE + PINSEL0_OFFSET)
|
||||
#define LPC23XX_PINSEL1 (PINSEL_BASE + PINSEL1_OFFSET)
|
||||
#define LPC23XX_PINSEL2 (PINSEL_BASE + PINSEL2_OFFSET)
|
||||
#define LPC23XX_PINSEL3 (PINSEL_BASE + PINSEL3_OFFSET)
|
||||
#define LPC23XX_PINSEL4 (PINSEL_BASE + PINSEL4_OFFSET)
|
||||
#define LPC23XX_PINSEL5 (PINSEL_BASE + PINSEL5_OFFSET)
|
||||
#define LPC23XX_PINSEL6 (PINSEL_BASE + PINSEL6_OFFSET)
|
||||
#define LPC23XX_PINSEL7 (PINSEL_BASE + PINSEL7_OFFSET)
|
||||
#define LPC23XX_PINSEL8 (PINSEL_BASE + PINSEL8_OFFSET)
|
||||
#define LPC23XX_PINSEL9 (PINSEL_BASE + PINSEL9_OFFSET)
|
||||
#define LPC23XX_PINSEL10 (PINSEL_BASE + PINSEL10_OFFSET)
|
||||
|
||||
/* PINSEL 0 */
|
||||
#define PSEL0_P00_GPIO (0x00000000)
|
||||
#define PSEL0_P00_RD1 (0x00000001)
|
||||
#define PSEL0_P00_TXD3 (0x00000002)
|
||||
#define PSEL0_P00_SDA1 (0x00000003)
|
||||
#define PSEL0_P00_MASK (0x00000003)
|
||||
|
||||
#define PSEL0_P0_1_GPIO (0x00000000)
|
||||
#define PSEL0_P0_1_TD1 (0x00000004)
|
||||
#define PSEL0_P0_1_RXD3 (0x00000008)
|
||||
#define PSEL0_P0_1_SCL1 (0x0000000c)
|
||||
#define PSEL0_P0_1_MASK (0x0000000c)
|
||||
|
||||
#define PSEL0_P0_2_GPIO (0x00000000)
|
||||
#define PSEL0_P0_2_TXD0 (0x00000010)
|
||||
#define PSEL0_P0_2_RSVD2 (0x00000020)
|
||||
#define PSEL0_P0_2_RSVD3 (0x00000030)
|
||||
#define PSEL0_P0_2_MASK (0x00000030)
|
||||
|
||||
#define PSEL0_P0_3_GPIO (0x00000000)
|
||||
#define PSEL0_P0_3_RXD0 (0x00000040)
|
||||
#define PSEL0_P0_3_RSVD2 (0x00000080)
|
||||
#define PSEL0_P0_3_RSVD3 (0x000000c0)
|
||||
#define PSEL0_P0_3_MASK (0x000000c0)
|
||||
|
||||
#define PSEL0_P0_4_GPIO (0x00000000)
|
||||
#define PSEL0_P0_4_I2SRX_CLK (0x00000100)
|
||||
#define PSEL0_P0_4_RD2 (0x00000200)
|
||||
#define PSEL0_P0_4_CAP20 (0x00000300)
|
||||
#define PSEL0_P0_4_MASK (0x00000400)
|
||||
|
||||
#define PSEL0_P0_5_GPIO (0x00000000)
|
||||
#define PSEL0_P0_5_I2SRX_WS (0x00000400)
|
||||
#define PSEL0_P0_5_TD2 (0x00000800)
|
||||
#define PSEL0_P0_5_CAP21 (0x00000c00)
|
||||
#define PSEL0_P0_5_MASK (0x00000c00)
|
||||
|
||||
#define PSEL0_P0_6_GPIO (0x00000000)
|
||||
#define PSEL0_P0_6_I2SRX_SDA (0x00001000)
|
||||
#define PSEL0_P0_6_SSEL1 (0x00002000)
|
||||
#define PSEL0_P0_6_MAT20 (0x00003000)
|
||||
#define PSEL0_P0_6_MASK (0x00003000)
|
||||
|
||||
#define PSEL0_P0_7_GPIO (0x00000000)
|
||||
#define PSEL0_P0_7_I2STX_CLK (0x00004000)
|
||||
#define PSEL0_P0_7_SCK1 (0x00008000)
|
||||
#define PSEL0_P0_7_MAT21 (0x0000c000)
|
||||
#define PSEL0_P0_7_MASK (0x0000c000)
|
||||
|
||||
#define PSEL0_P0_8_GPIO (0x00000000)
|
||||
#define PSEL0_P0_8_I2STX_WS (0x00010000)
|
||||
#define PSEL0_P0_8_MISO1 (0x00020000)
|
||||
#define PSEL0_P0_8_MAT22 (0x00030000)
|
||||
#define PSEL0_P0_8_MASK (0x00030000)
|
||||
|
||||
#define PSEL0_P0_9_GPIO (0x00000000)
|
||||
#define PSEL0_P0_9_I2STX_SDA (0x00040000)
|
||||
#define PSEL0_P0_9_MOSI1 (0x00080000)
|
||||
#define PSEL0_P0_9_MAT23 (0x000c0000)
|
||||
#define PSEL0_P0_9_MASK (0x000c0000)
|
||||
|
||||
#define PSEL0_P0_10_GPIO (0x00000000)
|
||||
#define PSEL0_P0_10_TXD2 (0x00100000)
|
||||
#define PSEL0_P0_10_SDA2 (0x00200000)
|
||||
#define PSEL0_P0_10_MAT30 (0x00300000)
|
||||
#define PSEL0_P0_10_MASK (0x00300000)
|
||||
|
||||
#define PSEL0_P0_11_GPIO (0x00000000)
|
||||
#define PSEL0_P0_11_RXD2 (0x00400000)
|
||||
#define PSEL0_P0_11_SCL2 (0x00800000)
|
||||
#define PSEL0_P0_11_MAT31 (0x00c00000)
|
||||
#define PSEL0_P0_11_MASK (0x00c00000)
|
||||
|
||||
#define PSEL0_P0_12_GPIO (0x00000000)
|
||||
#define PSEL0_P0_12_RSVD1 (0x01000000)
|
||||
#define PSEL0_P0_12_MISO1 (0x02000000)
|
||||
#define PSEL0_P0_12_AD06 (0x03000000)
|
||||
#define PSEL0_P0_12_MASK (0x03000000)
|
||||
|
||||
#define PSEL0_P0_13_GPIO (0x00000000)
|
||||
#define PSEL0_P0_13_USB_UPLED2 (0x04000000)
|
||||
#define PSEL0_P0_13_MOSI1 (0x08000000)
|
||||
#define PSEL0_P0_13_AD07 (0x0c000000)
|
||||
#define PSEL0_P0_13_MASK (0x0c000000)
|
||||
|
||||
#define PSEL0_P0_14_GPIO (0x00000000)
|
||||
#define PSEL0_P0_14_RSVD1 (0x10000000)
|
||||
#define PSEL0_P0_14_USB_CONNECT2 (0x20000000)
|
||||
#define PSEL0_P0_14_SSEL1 (0x30000000)
|
||||
#define PSEL0_P0_14_MASK (0x30000000)
|
||||
|
||||
#define PSEL0_P0_15_GPIO (0x00000000)
|
||||
#define PSEL0_P0_15_TXD1 (0x40000000)
|
||||
#define PSEL0_P0_15_SCK0 (0x80000000)
|
||||
#define PSEL0_P0_15_SCK (0xc0000000)
|
||||
#define PSEL0_P0_15_MASK (0xc0000000)
|
||||
|
||||
/* PINSEL 1 */
|
||||
#define PSEL1_P0_16_GPIO (0x00000000)
|
||||
#define PSEL1_P0_16_RXD1 (0x00000001)
|
||||
#define PSEL1_P0_16_SSEL0 (0x00000002)
|
||||
#define PSEL1_P0_16_SSEL (0x00000003)
|
||||
#define PSEL1_P0_16_MASK (0x00000003)
|
||||
|
||||
#define PSEL1_P0_17_GPIO (0x00000000)
|
||||
#define PSEL1_P0_17_CTS1 (0x00000004)
|
||||
#define PSEL1_P0_17_MISO0 (0x00000008)
|
||||
#define PSEL1_P0_17_MISO (0x0000000c)
|
||||
#define PSEL1_P0_17_MASK (0x0000000c)
|
||||
|
||||
#define PSEL1_P0_18_GPIO (0x00000000)
|
||||
#define PSEL1_P0_18_DCD1 (0x00000010)
|
||||
#define PSEL1_P0_18_MOSI0 (0x00000020)
|
||||
#define PSEL1_P0_18_MOSI (0x00000030)
|
||||
#define PSEL1_P0_18_MASK (0x00000030)
|
||||
|
||||
#define PSEL1_P0_19_GPIO (0x00000000)
|
||||
#define PSEL1_P0_19_DSR1 (0x00000040)
|
||||
#define PSEL1_P0_19_MCICLK (0x00000080)
|
||||
#define PSEL1_P0_19_SDA1 (0x000000c0)
|
||||
#define PSEL1_P0_19_MASK (0x000000c0)
|
||||
|
||||
#define PSEL1_P0_20_GPIO (0x00000000)
|
||||
#define PSEL1_P0_20_DTR1 (0x00000100)
|
||||
#define PSEL1_P0_20_MCICMD (0x00000200)
|
||||
#define PSEL1_P0_20_SCL1 (0x00000300)
|
||||
#define PSEL1_P0_20_MASK (0x00000300)
|
||||
|
||||
#define PSEL1_P0_21_GPIO (0x00000000)
|
||||
#define PSEL1_P0_21_RI1 (0x00000400)
|
||||
#define PSEL1_P0_21_MCIPWR (0x00000800)
|
||||
#define PSEL1_P0_21_RD1 (0x00000c00)
|
||||
#define PSEL1_P0_21_MASK (0x00000c00)
|
||||
|
||||
#define PSEL1_P0_22_GPIO (0x00000000)
|
||||
#define PSEL1_P0_22_RTS1 (0x00001000)
|
||||
#define PSEL1_P0_22_MCIDA0 (0x00002000)
|
||||
#define PSEL1_P0_22_TD1 (0x00003000)
|
||||
#define PSEL1_P0_22_MASK (0x00003000)
|
||||
|
||||
#define PSEL1_P0_23_GPIO (0x00000000)
|
||||
#define PSEL1_P0_23_AD00 (0x00004000)
|
||||
#define PSEL1_P0_23_I2SRX_CLK (0x00008000)
|
||||
#define PSEL1_P0_23_CAP30 (0x0000c000)
|
||||
#define PSEL1_P0_23_MASK (0x0000c000)
|
||||
|
||||
#define PSEL1_P0_24_GPIO (0x00000000)
|
||||
#define PSEL1_P0_24_AD01 (0x00010000)
|
||||
#define PSEL1_P0_24_I2SRX_WS (0x00020000)
|
||||
#define PSEL1_P0_24_CAP31 (0x00030000)
|
||||
#define PSEL1_P0_24_MASK (0x00030000)
|
||||
|
||||
#define PSEL1_P0_25_GPIO (0x00000000)
|
||||
#define PSEL1_P0_25_AD02 (0x00040000)
|
||||
#define PSEL1_P0_25_I2SRX_SDA (0x00080000)
|
||||
#define PSEL1_P0_25_TXD3 (0x000c0000)
|
||||
#define PSEL1_P0_25_MASK (0x000c0000)
|
||||
|
||||
#define PSEL1_P0_26_GPI0 (0x00000000)
|
||||
#define PSEL1_P0_26_AD031 (0x00100000)
|
||||
#define PSEL1_P0_26_AOUT (0x00200000)
|
||||
#define PSEL1_P0_26_RXD3 (0x00300000)
|
||||
#define PSEL1_P0_26_MASK (0x00300000)
|
||||
|
||||
#define PSEL1_P0_27_GPI0 (0x00000000)
|
||||
#define PSEL1_P0_27_SDA0 (0x00400000)
|
||||
#define PSEL1_P0_27_RSVD2 (0x00800000)
|
||||
#define PSEL1_P0_27_RSVD3 (0x00c00000)
|
||||
#define PSEL1_P0_27_MASK (0x00c00000)
|
||||
|
||||
#define PSEL1_P0_28_GPIO (0x00000000)
|
||||
#define PSEL1_P0_28_SCL0 (0x01000000)
|
||||
#define PSEL1_P0_28_RSVD2 (0x02000000)
|
||||
#define PSEL1_P0_28_RSVD3 (0x03000000)
|
||||
#define PSEL1_P0_28_MASK (0x03000000)
|
||||
|
||||
#define PSEL1_P0_29_GPIO (0x00000000)
|
||||
#define PSEL1_P0_29_USB_DPOS1 (0x04000000)
|
||||
#define PSEL1_P0_29_RSVD2 (0x08000000)
|
||||
#define PSEL1_P0_29_RSVD3 (0x0c000000)
|
||||
#define PSEL1_P0_29_MASK (0x0c000000)
|
||||
|
||||
#define PSEL1_P0_30_GPIO (0x00000000)
|
||||
#define PSEL1_P0_30_USB_DNEG1 (0x10000000)
|
||||
#define PSEL1_P0_30_RSVD2 (0x20000000)
|
||||
#define PSEL1_P0_30_RSVD3 (0x30000000)
|
||||
#define PSEL1_P0_30_MASK (0x30000000)
|
||||
|
||||
#define PSEL1_P0_31_GPIO (0x00000000)
|
||||
#define PSEL1_P0_31_USB_DPOS2 (0x40000000)
|
||||
#define PSEL1_P0_31_RSVD2 (0x80000000)
|
||||
#define PSEL1_P0_31_RSVD3 (0xc0000000)
|
||||
#define PSEL1_P0_31_MASK (0xc0000000)
|
||||
|
||||
|
||||
/* PINSEL 2 */
|
||||
#define PSEL2_P1_0_GPIO (0x00000000)
|
||||
#define PSEL2_P1_0_ENET_TXD0 (0x00000001)
|
||||
#define PSEL2_P1_0_RSVD2 (0x00000002)
|
||||
#define PSEL2_P1_0_RSVD3 (0x00000003)
|
||||
#define PSEL2_P1_0_MASK (0x00000003)
|
||||
|
||||
#define PSEL2_P1_1_GPIO (0x00000000)
|
||||
#define PSEL2_P1_1_ENET_TXD1 (0x00000004)
|
||||
#define PSEL2_P1_1_RSVD2 (0x00000008)
|
||||
#define PSEL2_P1_1_RSVD3 (0x0000000c)
|
||||
#define PSEL2_P1_1_MASK (0x0000000c)
|
||||
|
||||
#define PSEL2_P1_2_RSVD0 (0x00000000)
|
||||
#define PSEL2_P1_2_RSVD1 (0x00000010)
|
||||
#define PSEL2_P1_2_RSVD2 (0x00000020)
|
||||
#define PSEL2_P1_2_RSVD3 (0x00000030)
|
||||
#define PSEL2_P1_2_MASK (0x00000030)
|
||||
|
||||
#define PSEL2_P1_3_RSVD0 (0x00000000)
|
||||
#define PSEL2_P1_3_RSVD1 (0x00000040)
|
||||
#define PSEL2_P1_3_RSVD2 (0x00000080)
|
||||
#define PSEL2_P1_3_RSVD3 (0x000000c0)
|
||||
#define PSEL2_P1_3_MASK (0x000000c0)
|
||||
|
||||
#define PSEL2_P1_4_GPIO (0x00000000)
|
||||
#define PSEL2_P1_4_ENET_TX_EN (0x00000100)
|
||||
#define PSEL2_P1_4_RSVD2 (0x00000200)
|
||||
#define PSEL2_P1_4_RSVD3 (0x00000300)
|
||||
#define PSEL2_P1_4_MASK (0x00000300)
|
||||
|
||||
#define PSEL2_P1_5_RSVDO (0x00000000)
|
||||
#define PSEL2_P1_5_RSVD1 (0x00000400)
|
||||
#define PSEL2_P1_5_RSVD2 (0x00000800)
|
||||
#define PSEL2_P1_5_RSVD3 (0x00000c00)
|
||||
#define PSEL2_P1_5_MASK (0x00000c00)
|
||||
|
||||
#define PSEL2_P1_6_RSVD0 (0x00000000)
|
||||
#define PSEL2_P1_6_RSVD1 (0x00001000)
|
||||
#define PSEL2_P1_6_RSVD2 (0x00002000)
|
||||
#define PSEL2_P1_6_RSVD3 (0x00003000)
|
||||
#define PSEL2_P1_6_MASK (0x00003000)
|
||||
|
||||
#define PSEL2_P1_7_RSVD0 (0x00000000)
|
||||
#define PSEL2_P1_7_RSVD1 (0x00004000)
|
||||
#define PSEL2_P1_7_RSVD2 (0x00008000)
|
||||
#define PSEL2_P1_7_RSVD3 (0x0000c000)
|
||||
#define PSEL2_P1_7_MASK (0x0000c000)
|
||||
|
||||
#define PSEL2_P1_8_GPIO (0x00000000)
|
||||
#define PSEL2_P1_8_ENET_CRS (0x00010000)
|
||||
#define PSEL2_P1_8_RSVD2 (0x00020000)
|
||||
#define PSEL2_P1_8_RSVD3 (0x00030000)
|
||||
#define PSEL2_P1_8_MASK (0x00030000)
|
||||
|
||||
#define PSEL2_P1_9_GPIO (0x00000000)
|
||||
#define PSEL2_P1_9_ENET_RXD0 (0x00040000)
|
||||
#define PSEL2_P1_9_RSVD2 (0x00080000)
|
||||
#define PSEL2_P1_9_RSVD3 (0x000c0000)
|
||||
#define PSEL2_P1_9_MASK (0x000c0000)
|
||||
|
||||
#define PSEL2_P1_10_GPI0 (0x00000000)
|
||||
#define PSEL2_P1_10_ENET_RXD1 (0x00100000)
|
||||
#define PSEL2_P1_10_RSVD2 (0x00200000)
|
||||
#define PSEL2_P1_10_RSVD3 (0x00300000)
|
||||
#define PSEL2_P1_10_MASK (0x00300000)
|
||||
|
||||
#define PSEL2_P1_11_RSVD0 (0x00000000)
|
||||
#define PSEL2_P1_11_RSVD1 (0x00400000)
|
||||
#define PSEL2_P1_11_RSVD2 (0x00800000)
|
||||
#define PSEL2_P1_11_RSVD3 (0x00c00000)
|
||||
#define PSEL2_P1_11_MASK (0x00c00000)
|
||||
|
||||
#define PSEL2_P1_12_RSVD0 (0x00000000)
|
||||
#define PSEL2_P1_12_RSVD1 (0x01000000)
|
||||
#define PSEL2_P1_12_RSVD2 (0x02000000)
|
||||
#define PSEL2_P1_12_RSVD3 (0x03000000)
|
||||
#define PSEL2_P1_12_MASK (0x03000000)
|
||||
|
||||
#define PSEL2_P1_13_RSVD0 (0x00000000)
|
||||
#define PSEL2_P1_13_RSVD1 (0x04000000)
|
||||
#define PSEL2_P1_13_RSVD2 (0x08000000)
|
||||
#define PSEL2_P1_13_RSVD3 (0x0c000000)
|
||||
#define PSEL2_P1_13_MASK (0x0c000000)
|
||||
|
||||
#define PSEL2_P1_14_GPIO (0x00000000)
|
||||
#define PSEL2_P1_14_ENET_RX_ER (0x10000000)
|
||||
#define PSEL2_P1_14_RSVD2 (0x20000000)
|
||||
#define PSEL2_P1_14_RSVD3 (0x30000000)
|
||||
#define PSEL2_P1_14_MASK (0x30000000)
|
||||
|
||||
#define PSEL2_P1_15_GPIO (0x00000000)
|
||||
#define PSEL2_P1_15_ENET_REF_CLK (0x40000000)
|
||||
#define PSEL2_P1_15_RSVD2 (0x80000000)
|
||||
#define PSEL2_P1_15_RSVD3 (0xc0000000)
|
||||
#define PSEL2_P1_15_MASK (0xc0000000)
|
||||
|
||||
|
||||
/* PINSEL 3 */
|
||||
#define PSEL3_P1_16_GPIO (0x00000000)
|
||||
#define PSEL3_P1_16_ENET_MDC (0x00000001)
|
||||
#define PSEL3_P1_16_RSVD2 (0x00000002)
|
||||
#define PSEL3_P1_16_RSVD3 (0x00000003)
|
||||
#define PSEL3_P1_16_MASK (0x00000003)
|
||||
|
||||
#define PSEL3_P1_17_GPIO (0x00000000)
|
||||
#define PSEL3_P1_17_ENET_MDIO (0x00000004)
|
||||
#define PSEL3_P1_17_RSVD2 (0x00000008)
|
||||
#define PSEL3_P1_17_RSVD3 (0x0000000c)
|
||||
#define PSEL3_P1_17_MASK (0x0000000c)
|
||||
|
||||
#define PSEL3_P1_18_GPIO (0x00000000)
|
||||
#define PSEL3_P1_18_USB_UP_LED1 (0x00000010)
|
||||
#define PSEL3_P1_18_PWM1_1 (0x00000020)
|
||||
#define PSEL3_P1_18_CAP1_0 (0x00000030)
|
||||
#define PSEL3_P1_18_MASK (0x00000030)
|
||||
|
||||
#define PSEL3_P1_19_GPIO (0x00000000)
|
||||
#define PSEL3_P1_19_USB_TX_E1 (0x00000040) /* 2388 only Reserved on 2377/78 */
|
||||
#define PSEL3_P1_19_USB_PPWR1 (0x00000080) /* 2388 only Reserved on 2377/78 */
|
||||
#define PSEL3_P1_19_CAP1_1 (0x000000c0)
|
||||
#define PSEL3_P1_19_MASK (0x000000c0)
|
||||
|
||||
#define PSEL3_P1_20_GPIO (0x00000000)
|
||||
#define PSEL3_P1_20_USB_TX_DP1 (0x00000100)/* 2388 only Reserved on 2377/78 */
|
||||
#define PSEL3_P1_20_PWM1_2 (0x00000200)
|
||||
#define PSEL3_P1_20_SCK0 (0x00000300)
|
||||
#define PSEL3_P1_20_MASK (0x00000300)
|
||||
|
||||
#define PSEL3_P1_21_GPIO (0x00000000)
|
||||
#define PSEL3_P1_21_USB_TX_DM1 (0x00000400)/* 2388 only Reserved on 2377/78 */
|
||||
#define PSEL3_P1_21_PWM1_3 (0x00000800)
|
||||
#define PSEL3_P1_21_SSEL0 (0x00000c00)
|
||||
#define PSEL3_P1_21_MASK (0x00000c00)
|
||||
|
||||
#define PSEL3_P1_22_GPIO (0x00000000)
|
||||
#define PSEL3_P1_22_USB_RCV1 (0x00001000) /* 2388 only Reserved on 2377/78 */
|
||||
#define PSEL3_P1_22_USB_PWRD1 (0x00002000)/* 2388 only Reserved on 2377/78 */
|
||||
#define PSEL3_P1_22_MAT1_0 (0x00003000)
|
||||
#define PSEL3_P1_22_MASK (0x00003000)
|
||||
|
||||
#define PSEL3_P1_23_GPIO (0x00000000)
|
||||
#define PSEL3_P1_23_USB_RX_DP1 (0x00004000)/* 2388 only Reserved on 2377/78 */
|
||||
#define PSEL3_P1_23_PWM1_4 (0x00008000)
|
||||
#define PSEL3_P1_23_MISO0 (0x0000c000)
|
||||
#define PSEL3_P1_23_MASK (0x0000c000)
|
||||
|
||||
#define PSEL3_P1_24_GPIO (0x00000000)
|
||||
#define PSEL3_P1_24_USB_RX_DM1 (0x00010000)/* 2388 only Reserved on 2377/78 */
|
||||
#define PSEL3_P1_24_PWM1_5 (0x00020000)
|
||||
#define PSEL3_P1_24_MOSI0 (0x00030000)
|
||||
#define PSEL3_P1_24_MASK (0x00030000)
|
||||
|
||||
#define PSEL3_P1_25_GPIO (0x00000000)
|
||||
#define PSEL3_P1_25_USB_LS1 (0x00040000)/* 2388 only Reserved on 2377/78 */
|
||||
#define PSEL3_P1_25_USB_HSTEN1 (0x00080000)/* 2388 only Reserved on 2377/78 */
|
||||
#define PSEL3_P1_25_MAT1_1 (0x000c0000)
|
||||
#define PSEL3_P1_25_MASK (0x000c0000)
|
||||
|
||||
#define PSEL3_P1_26_GPI0 (0x00000000)
|
||||
#define PSEL3_P1_26_USB_SSPND1 (0x00100000)/* 2388 only Reserved on 2377/78 */
|
||||
#define PSEL3_P1_26_PWM1_6 (0x00200000)
|
||||
#define PSEL3_P1_26_CAP0_0 (0x00300000)
|
||||
#define PSEL3_P1_26_MASK (0x00300000)
|
||||
|
||||
#define PSEL3_P1_27_GPIO (0x00000000)
|
||||
#define PSEL3_P1_27_USB_INT1 (0x00400000)/* 2388 only Reserved on 2377/78 */
|
||||
#define PSEL3_P1_27_USB_OVRCR1 (0x00800000)/* 2388 only Reserved on 2377/78 */
|
||||
#define PSEL3_P1_27_CAP0_1 (0x00c00000)
|
||||
#define PSEL3_P1_27_MASK (0x00c00000)
|
||||
|
||||
#define PSEL3_P1_28_GPIO (0x00000000)
|
||||
#define PSEL3_P1_28_USB_SCL1 (0x01000000)/* 2388 only Reserved on 2377/78 */
|
||||
#define PSEL3_P1_28_PCAP1_0 (0x02000000)
|
||||
#define PSEL3_P1_28_MAT0_0 (0x03000000)
|
||||
#define PSEL3_P1_28_MASK (0x03000000)
|
||||
|
||||
#define PSEL3_P1_29_GPIO (0x00000000)
|
||||
#define PSEL3_P1_29_USB_SDA1 (0x04000000)/* 2388 only Reserved on 2377/78 */
|
||||
#define PSEL3_P1_29_PCAP1_1 (0x08000000)
|
||||
#define PSEL3_P1_29_MAT0_1 (0x0c000000)
|
||||
#define PSEL3_P1_29_MASK (0x0c000000)
|
||||
|
||||
#define PSEL3_P1_30_GPIO (0x00000000)
|
||||
#define PSEL3_P1_30_USB_PWRD2 (0x10000000)
|
||||
#define PSEL3_P1_30_VBUS (0x20000000)
|
||||
#define PSEL3_P1_30_AD0_4 (0x30000000)
|
||||
#define PSEL3_P1_30_MASK (0x30000000)
|
||||
|
||||
#define PSEL3_P1_31_GPIO (0x00000000)
|
||||
#define PSEL3_P1_31_USB_OVRCR2 (0x40000000)/* 2388 only Reserved on 2377/78 */
|
||||
#define PSEL3_P1_31_SCK1 (0x80000000)
|
||||
#define PSEL3_P1_31_AD0_5 (0xc0000000)
|
||||
#define PSEL3_P1_31_MASK (0xc0000000)
|
||||
|
||||
/* PINSEL 4 */
|
||||
#define PSEL4_P2_0_GPIO (0x00000000)
|
||||
#define PSEL4_P2_0_PWM1_1 (0x00000001)
|
||||
#define PSEL4_P2_0_TXD1 (0x00000002)
|
||||
#define PSEL4_P2_0_TRACECLK (0x00000003)
|
||||
#define PSEL4_P2_0_MASK (0x00000003)
|
||||
|
||||
#define PSEL4_P2_1_GPIO (0x00000000)
|
||||
#define PSEL4_P2_1_PWM1_2 (0x00000004)
|
||||
#define PSEL4_P2_1_RXD1 (0x00000008)
|
||||
#define PSEL4_P2_1_PIPESTAT0 (0x0000000c)
|
||||
#define PSEL4_P2_1_MASK (0x0000000c)
|
||||
|
||||
#define PSEL4_P2_2_GPIO (0x00000000)
|
||||
#define PSEL4_P2_2_PWM1_3 (0x00000010)
|
||||
#define PSEL4_P2_2_CTS1 (0x00000020)
|
||||
#define PSEL4_P2_2_PIPESTAT1 (0x00000030)
|
||||
#define PSEL4_P2_2_MASK (0x00000030)
|
||||
|
||||
#define PSEL4_P2_3_GPIO (0x00000000)
|
||||
#define PSEL4_P2_3_PWM1_4 (0x00000040)
|
||||
#define PSEL4_P2_3_DCD1 (0x00000080)
|
||||
#define PSEL4_P2_3_PIPESTAT2 (0x000000c0)
|
||||
#define PSEL4_P2_3_MASK (0x000000c0)
|
||||
|
||||
#define PSEL4_P2_4_GPIO (0x00000000)
|
||||
#define PSEL4_P2_4_PWM1_5 (0x00000100)
|
||||
#define PSEL4_P2_4_DSR1 (0x00000200)
|
||||
#define PSEL4_P2_4_TRACESYNC (0x00000300)
|
||||
#define PSEL4_P2_4_MASK (0x00000300)
|
||||
|
||||
#define PSEL4_P2_5_GPIO (0x00000000)
|
||||
#define PSEL4_P2_5_PWM1_6 (0x00000400)
|
||||
#define PSEL4_P2_5_DTR1 (0x00000800)
|
||||
#define PSEL4_P2_5_TRACEPKT0 (0x00000c00)
|
||||
#define PSEL4_P2_5_MASK (0x00000c00)
|
||||
|
||||
#define PSEL4_P2_6_GPIO (0x00000000)
|
||||
#define PSEL4_P2_6_PCAP1_0 (0x00001000)
|
||||
#define PSEL4_P2_6_RI1 (0x00002000)
|
||||
#define PSEL4_P2_6_TRACEPKT1 (0x00003000)
|
||||
#define PSEL4_P2_6_MASK (0x00003000)
|
||||
|
||||
#define PSEL4_P2_7_GPIO (0x00000000)
|
||||
#define PSEL4_P2_7_RD2 (0x00004000)
|
||||
#define PSEL4_P2_7_RTS1 (0x00008000)
|
||||
#define PSEL4_P2_7_TRACEPKT2 (0x0000c000)
|
||||
#define PSEL4_P2_7_MASK (0x0000c000)
|
||||
|
||||
#define PSEL4_P2_8_GPIO (0x00000000)
|
||||
#define PSEL4_P2_8_TD2 (0x00010000)
|
||||
#define PSEL4_P2_8_TXD2 (0x00020000)
|
||||
#define PSEL4_P2_8_TRACEPKT3 (0x00030000)
|
||||
#define PSEL4_P2_8_MASK (0x00030000)
|
||||
|
||||
#define PSEL4_P2_9_GPIO (0x00000000)
|
||||
#define PSEL4_P2_9_USB_CONNECT1 (0x00040000)
|
||||
#define PSEL4_P2_9_RXD2 (0x00080000)
|
||||
#define PSEL4_P2_9_EXTIN0 (0x000c0000)
|
||||
#define PSEL4_P2_9_MASK (0x000c0000)
|
||||
|
||||
#define PSEL4_P2_10_GPI0 (0x00000000)
|
||||
#define PSEL4_P2_10_EINT0 (0x00100000)
|
||||
#define PSEL4_P2_10_RSVD2 (0x00200000)
|
||||
#define PSEL4_P2_10_RSVD3 (0x00300000)
|
||||
#define PSEL4_P2_10_MASK (0x00300000)
|
||||
|
||||
#define PSEL4_P2_11_GPIO (0x00000000)
|
||||
#define PSEL4_P2_11_EINT1 (0x00400000)
|
||||
#define PSEL4_P2_11_MCIDAT1 (0x00800000)
|
||||
#define PSEL4_P2_11_I2STX_CLK (0x00c00000)
|
||||
#define PSEL4_P2_11_MASK (0x00c00000)
|
||||
|
||||
#define PSEL4_P2_12_GPIO (0x00000000)
|
||||
#define PSEL4_P2_12_EINT2 (0x01000000)
|
||||
#define PSEL4_P2_12_MCIDAT2 (0x02000000)
|
||||
#define PSEL4_P2_12_I2STX_WS (0x03000000)
|
||||
#define PSEL4_P2_12_MASK (0x03000000)
|
||||
|
||||
#define PSEL4_P2_13_GPIO (0x00000000)
|
||||
#define PSEL4_P2_13_EINT3 (0x04000000)
|
||||
#define PSEL4_P2_13_MCIDAT3 (0x08000000)
|
||||
#define PSEL4_P2_13_I2STX_SDA (0x0c000000)
|
||||
#define PSEL4_P2_13_MASK (0x0c000000)
|
||||
|
||||
#define PSEL4_P2_14_RSVD0 (0x00000000)
|
||||
#define PSEL4_P2_14_RSVD1 (0x10000000)
|
||||
#define PSEL4_P2_14_RSVD2 (0x20000000)
|
||||
#define PSEL4_P2_14_RSVD3 (0x30000000)
|
||||
#define PSEL4_P2_14_MASK (0x30000000)
|
||||
|
||||
#define PSEL4_P2_15_RSVD0 (0x00000000)
|
||||
#define PSEL4_P2_15_RSVD1 (0x40000000)
|
||||
#define PSEL4_P2_15_RSVD2 (0x80000000)
|
||||
#define PSEL4_P2_15_RSVD3 (0xc0000000)
|
||||
#define PSEL4_P2_15_MASK (0xc0000000)
|
||||
|
||||
/* PINSEL 5 All reserved */
|
||||
|
||||
|
||||
/* PINSEL 6 */
|
||||
#define PSEL6_P3_0_GPIO (0x00000000)
|
||||
#define PSEL6_P3_0_D0 (0x00000001)
|
||||
#define PSEL6_P3_0_RSVD2 (0x00000002)
|
||||
#define PSEL6_P3_0_RSVD3 (0x00000003)
|
||||
#define PSEL6_P3_0_MASK (0x00000003)
|
||||
|
||||
#define PSEL6_P3_1_GPIO (0x00000000)
|
||||
#define PSEL6_P3_1_D1 (0x00000004)
|
||||
#define PSEL6_P3_1_RSVD2 (0x00000008)
|
||||
#define PSEL6_P3_1_RSVD3 (0x0000000c)
|
||||
#define PSEL6_P3_1_MASK (0x0000000c)
|
||||
|
||||
#define PSEL6_P3_2_GPIO (0x00000000)
|
||||
#define PSEL6_P3_2_D2 (0x00000010)
|
||||
#define PSEL6_P3_2_RSVD2 (0x00000020)
|
||||
#define PSEL6_P3_2_RSVD3 (0x00000030)
|
||||
#define PSEL6_P3_2_MASK (0x00000030)
|
||||
|
||||
#define PSEL6_P3_3_GPIO (0x00000000)
|
||||
#define PSEL6_P3_3_D3 (0x00000040)
|
||||
#define PSEL6_P3_3_RSVD2 (0x00000080)
|
||||
#define PSEL6_P3_3_RSVD3 (0x000000c0)
|
||||
#define PSEL6_P3_3_MASK (0x000000c0)
|
||||
|
||||
#define PSEL6_P3_4_GPIO (0x00000000)
|
||||
#define PSEL6_P3_4_D4 (0x00000100)
|
||||
#define PSEL6_P3_4_RSVD2 (0x00000200)
|
||||
#define PSEL6_P3_4_RSVD3 (0x00000300)
|
||||
#define PSEL6_P3_4_MASK (0x00000400)
|
||||
|
||||
#define PSEL6_P3_5_GPIO (0x00000000)
|
||||
#define PSEL6_P3_5_D5 (0x00000400)
|
||||
#define PSEL6_P3_5_RSVD2 (0x00000800)
|
||||
#define PSEL6_P3_5_RSVD3 (0x00000c00)
|
||||
#define PSEL6_P3_5_MASK (0x00000c00)
|
||||
|
||||
#define PSEL6_P3_6_GPIO (0x00000000)
|
||||
#define PSEL6_P3_6_D6 (0x00001000)
|
||||
#define PSEL6_P3_6_RSVD2 (0x00002000)
|
||||
#define PSEL6_P3_6_RSVD3 (0x00003000)
|
||||
#define PSEL6_P3_6_MASK (0x00003000)
|
||||
|
||||
#define PSEL6_P3_7_GPIO (0x00000000)
|
||||
#define PSEL6_P3_7_D7 (0x00004000)
|
||||
#define PSEL6_P3_7_RSVD2 (0x00008000)
|
||||
#define PSEL6_P3_7_RSVD3 (0x0000c000)
|
||||
#define PSEL6_P3_7_MASK (0x0000c000)
|
||||
/* Rest of PSEL 6 are reserved */
|
||||
|
||||
/* PINSEL 7 */
|
||||
/* PINSEL 7 bit 0:13 are reserved */
|
||||
#define PSEL7_P3_23_GPIO (0x00000000)
|
||||
#define PSEL7_P3_23_RSVD1 (0x00004000)
|
||||
#define PSEL7_P3_23_CAP0_0 (0x00008000)
|
||||
#define PSEL7_P3_23_PCAP1_0 (0x0000c000)
|
||||
#define PSEL7_P3_23_MASK (0x0000c000)
|
||||
|
||||
#define PSEL7_P3_24_GPIO (0x00000000)
|
||||
#define PSEL7_P3_24_RSVD1 (0x00010000)
|
||||
#define PSEL7_P3_24_CAP0_1 (0x00020000)
|
||||
#define PSEL7_P3_24_PWM1_1 (0x00030000)
|
||||
#define PSEL7_P3_24_MASK (0x00030000)
|
||||
|
||||
#define PSEL7_P3_25_GPIO (0x00000000)
|
||||
#define PSEL7_P3_25_RSVD1 (0x00040000)
|
||||
#define PSEL7_P3_25_MAT0_0 (0x00080000)
|
||||
#define PSEL7_P3_25_PWM1_2 (0x000c0000)
|
||||
#define PSEL7_P3_25_MASK (0x000c0000)
|
||||
|
||||
#define PSEL7_P3_26_GPI0 (0x00000000)
|
||||
#define PSEL7_P3_26_RSVD1 (0x00100000)
|
||||
#define PSEL7_P3_26_MAT0_1 (0x00200000)
|
||||
#define PSEL7_P3_26_PWM1_3 (0x00300000)
|
||||
#define PSEL7_P3_26_MASK (0x00300000)
|
||||
/* PINSEL 7 rest are reserved */
|
||||
|
||||
|
||||
/* PINSEL 8 */
|
||||
#define PSEL8_P4_0_GPIO (0x00000000)
|
||||
#define PSEL8_P4_0_A0 (0x00000001)
|
||||
#define PSEL8_P4_0_RSVD2 (0x00000002)
|
||||
#define PSEL8_P4_0_RSVD3 (0x00000003)
|
||||
#define PSEL8_P4_0_MASK (0x00000003)
|
||||
|
||||
#define PSEL8_P4_1_GPIO (0x00000000)
|
||||
#define PSEL8_P4_1_A1 (0x00000004)
|
||||
#define PSEL8_P4_1_RXD3 (0x00000008)
|
||||
#define PSEL8_P4_1_SCL1 (0x0000000c)
|
||||
#define PSEL8_P4_1_MASK (0x0000000c)
|
||||
|
||||
#define PSEL8_P4_2_GPIO (0x00000000)
|
||||
#define PSEL8_P4_2_A2 (0x00000010)
|
||||
#define PSEL8_P4_2_RSVD2 (0x00000020)
|
||||
#define PSEL8_P4_2_RSVD3 (0x00000030)
|
||||
#define PSEL8_P4_2_MASK (0x00000030)
|
||||
|
||||
#define PSEL8_P4_3_GPIO (0x00000000)
|
||||
#define PSEL8_P4_3_A3 (0x00000040)
|
||||
#define PSEL8_P4_3_RSVD2 (0x00000080)
|
||||
#define PSEL8_P4_3_RSVD3 (0x000000c0)
|
||||
#define PSEL8_P4_3_MASK (0x000000c0)
|
||||
|
||||
#define PSEL8_P4_4_GPIO (0x00000000)
|
||||
#define PSEL8_P4_4_A4 (0x00000100)
|
||||
#define PSEL8_P4_4_RSVD2 (0x00000200)
|
||||
#define PSEL8_P4_4_RSVD3 (0x00000300)
|
||||
#define PSEL8_P4_4_MASK (0x00000400)
|
||||
|
||||
#define PSEL8_P4_5_GPIO (0x00000000)
|
||||
#define PSEL8_P4_5_A5 (0x00000400)
|
||||
#define PSEL8_P4_5_RSVD2 (0x00000800)
|
||||
#define PSEL8_P4_5_RSVD3 (0x00000c00)
|
||||
#define PSEL8_P4_5_MASK (0x00000c00)
|
||||
|
||||
#define PSEL8_P4_6_GPIO (0x00000000)
|
||||
#define PSEL8_P4_6_A6 (0x00001000)
|
||||
#define PSEL8_P4_6_RSVD2 (0x00002000)
|
||||
#define PSEL8_P4_6_RSVD3 (0x00003000)
|
||||
#define PSEL8_P4_6_MASK (0x00003000)
|
||||
|
||||
#define PSEL8_P4_7_GPIO (0x00000000)
|
||||
#define PSEL8_P4_7_A7 (0x00004000)
|
||||
#define PSEL8_P4_7_RSVD2 (0x00008000)
|
||||
#define PSEL8_P4_7_RSVD3 (0x0000c000)
|
||||
#define PSEL8_P4_7_MASK (0x0000c000)
|
||||
|
||||
#define PSEL8_P4_8_GPIO (0x00000000)
|
||||
#define PSEL8_P4_8_A8 (0x00010000)
|
||||
#define PSEL8_P4_8_RSVD2 (0x00020000)
|
||||
#define PSEL8_P4_8_RSVD3 (0x00030000)
|
||||
#define PSEL8_P4_8_MASK (0x00030000)
|
||||
|
||||
#define PSEL8_P4_9_GPIO (0x00000000)
|
||||
#define PSEL8_P4_9_A9 (0x00040000)
|
||||
#define PSEL8_P4_9_RSVD2 (0x00080000)
|
||||
#define PSEL8_P4_9_RSVD3 (0x000c0000)
|
||||
#define PSEL8_P4_9_MASK (0x000c0000)
|
||||
|
||||
#define PSEL8_P4_10_GPIO (0x00000000)
|
||||
#define PSEL8_P4_10_A10 (0x00100000)
|
||||
#define PSEL8_P4_10_RSVD2 (0x00200000)
|
||||
#define PSEL8_P4_10_RSVD3 (0x00300000)
|
||||
#define PSEL8_P4_10_MASK (0x00300000)
|
||||
|
||||
#define PSEL8_P4_11_GPIO (0x00000000)
|
||||
#define PSEL8_P4_11_A11 (0x00400000)
|
||||
#define PSEL8_P4_11_RSVD2 (0x00800000)
|
||||
#define PSEL8_P4_11_RSVD3 (0x00c00000)
|
||||
#define PSEL8_P4_11_MASK (0x00c00000)
|
||||
|
||||
#define PSEL8_P4_12_GPIO (0x00000000)
|
||||
#define PSEL8_P4_12_A12 (0x01000000)
|
||||
#define PSEL8_P4_12_RSVD2 (0x02000000)
|
||||
#define PSEL8_P4_12_RSVD3 (0x03000000)
|
||||
#define PSEL8_P4_12_MASK (0x03000000)
|
||||
|
||||
#define PSEL8_P4_13_GPIO (0x00000000)
|
||||
#define PSEL8_P4_13_A13 (0x04000000)
|
||||
#define PSEL8_P4_13_RSVD2 (0x08000000)
|
||||
#define PSEL8_P4_13_RSVD3 (0x0c000000)
|
||||
#define PSEL8_P4_13_MASK (0x0c000000)
|
||||
|
||||
#define PSEL8_P4_14_GPIO (0x00000000)
|
||||
#define PSEL8_P4_14_A14 (0x10000000)
|
||||
#define PSEL8_P4_14_RSVD2 (0x20000000)
|
||||
#define PSEL8_P4_14_RSVD3 (0x30000000)
|
||||
#define PSEL8_P4_14_MASK (0x30000000)
|
||||
|
||||
#define PSEL8_P4_15_GPIO (0x00000000)
|
||||
#define PSEL8_P4_15_A15 (0x40000000)
|
||||
#define PSEL8_P4_15_RSVD2 (0x80000000)
|
||||
#define PSEL8_P4_15_RSVD3 (0xc0000000)
|
||||
#define PSEL8_P4_15_MASK (0xc0000000)
|
||||
|
||||
/* PINSEL 9 */
|
||||
/* PINSEL 9 bit 0:15 are reserved */
|
||||
#define PSEL9_P4_24_GPIO (0x00000000)
|
||||
#define PSEL9_P4_24_OE (0x00010000)
|
||||
#define PSEL9_P4_24_RSVD2 (0x00020000)
|
||||
#define PSEL9_P4_24_RSVD3 (0x00030000)
|
||||
#define PSEL9_P4_24_MASK (0x00030000)
|
||||
|
||||
#define PSEL9_P4_25_GPIO (0x00000000)
|
||||
#define PSEL9_P4_25_ (0x00040000)
|
||||
#define PSEL9_P4_25_BLS0 (0x00080000)
|
||||
#define PSEL9_P4_25_RSVD3 (0x000c0000)
|
||||
#define PSEL9_P4_25_MASK (0x000c0000)
|
||||
|
||||
/* PINSEL 9 bit 26:27 are reserved */
|
||||
|
||||
#define PSEL9_P4_28_GPIO (0x00000000)
|
||||
#define PSEL9_P4_28_RSVD1 (0x01000000)
|
||||
#define PSEL9_P4_28_MAT2_0 (0x02000000)
|
||||
#define PSEL9_P4_28_TXD3 (0x03000000)
|
||||
#define PSEL9_P4_28_MASK (0x03000000)
|
||||
|
||||
#define PSEL9_P4_29_GPIO (0x00000000)
|
||||
#define PSEL9_P4_29_RSVD1 (0x04000000)
|
||||
#define PSEL9_P4_29_MAT2_1 (0x08000000)
|
||||
#define PSEL9_P4_29_RXD3 (0x0c000000)
|
||||
#define PSEL9_P4_29_MASK (0x0c000000)
|
||||
|
||||
#define PSEL9_P4_30_GPIO (0x00000000)
|
||||
#define PSEL9_P4_30_CS0 (0x10000000)
|
||||
#define PSEL9_P4_30_RSVD2 (0x20000000)
|
||||
#define PSEL9_P4_30_RSVD3 (0x30000000)
|
||||
#define PSEL9_P4_30_MASK (0x30000000)
|
||||
|
||||
#define PSEL9_P4_31_GPIO (0x00000000)
|
||||
#define PSEL9_P4_31_CS1 (0x40000000)
|
||||
#define PSEL9_P4_31_RSVD2 (0x80000000)
|
||||
#define PSEL9_P4_31_RSVD3 (0xc0000000)
|
||||
#define PSEL9_P4_31_MASK (0xc0000000)
|
||||
|
||||
/* PINSEL 10 */
|
||||
#define PSEL10_ETM (0x00000002)
|
||||
|
||||
/* TODO PINMODE pullup/pulldown resistor configuration */
|
||||
/************************************************************************************
|
||||
* Public Types
|
||||
************************************************************************************/
|
||||
|
||||
/************************************************************************************
|
||||
* Inline Functions
|
||||
************************************************************************************/
|
||||
|
||||
/************************************************************************************
|
||||
* Public Function Prototypes
|
||||
************************************************************************************/
|
||||
|
||||
#endif /* _ARCH_ARM_SRC_LPC23XX_PINSEL_H */
|
238
arch/arm/src/lpc2378/lpc23xx_pllsetup.c
Executable file
238
arch/arm/src/lpc2378/lpc23xx_pllsetup.c
Executable file
@ -0,0 +1,238 @@
|
||||
/****************************************************************************
|
||||
* arch/arm/src/lpc2378/lpc23xx_irq.c
|
||||
*
|
||||
* Copyright (C) 2010 Rommel Marcelo. All rights reserved.
|
||||
* Author: Rommel Marcelo
|
||||
*
|
||||
* This file is part of the NuttX RTOS:
|
||||
*
|
||||
* Copyright (C) 2010 Gregory Nutt. All rights reserved.
|
||||
*
|
||||
* 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.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
/* This file holds the NuttX start logic that runs when the LPC2378
|
||||
* is reset. This logic must be located at address 0x0000:0000 in
|
||||
* flash but may be linked to run at different locations based on
|
||||
* the selected mode:
|
||||
*
|
||||
* default: Executes from 0x0000:0000. In non-default modes, the
|
||||
* MEMAP register is set override the settings of the CPU configuration
|
||||
* pins.
|
||||
*
|
||||
* CONFIG_EXTMEM_MODE: Code executes from external memory starting at
|
||||
* address 0x8000:0000.
|
||||
*
|
||||
* CONFIG_RAM_MODE: Code executes from on-chip RAM at address
|
||||
* 0x4000:0000.
|
||||
*
|
||||
* Starupt Code must be linked to run at the correct address
|
||||
* corresponding to the selected mode.
|
||||
*/
|
||||
|
||||
/***********************************************************************
|
||||
* Included Files
|
||||
**********************************************************************/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
#include <arch/board/board.h>
|
||||
#include <sys/types.h>
|
||||
|
||||
#include "arm.h"
|
||||
#include "up_arch.h"
|
||||
#include "internal.h"
|
||||
#include "lpc23xx_pinsel.h"
|
||||
#include "lpc23xx_scb.h"
|
||||
|
||||
extern void IO_Init(void);
|
||||
/***********************************************************************
|
||||
* Definitions
|
||||
**********************************************************************/
|
||||
#if ((FOSC < 32000) || (FOSC > 50000000))
|
||||
# error Fosc out of range (32KHz-50MHz)
|
||||
# error correct and recompile
|
||||
#endif
|
||||
|
||||
#if ((CCLK < 10000000) || (CCLK > 72000000))
|
||||
# error cclk out of range (10MHz-72MHz)
|
||||
# error correct PLL MULTIPLIER and recompile
|
||||
#endif
|
||||
|
||||
#if ((FCCO < 275000000) || (FCCO > 550000000))
|
||||
# error Fcco out of range (275MHz-550MHz)
|
||||
# error internal algorithm error
|
||||
#endif
|
||||
|
||||
/* Phase Locked Loop (PLL) initialization values
|
||||
*
|
||||
* Bit 0:14 MSEL: PLL Multiplier "M" Value
|
||||
* CCLK = 57 600 000 Hz
|
||||
* Bit 16:23 NSEL: PLL Divider "N" Value
|
||||
* Fcco = (2 * M * F_in) / N
|
||||
* 275MHz <= Fcco <= 550MHz
|
||||
*
|
||||
* PLL clock sources:
|
||||
* Internal RC 0 default on reset
|
||||
* Main Oscillator 1
|
||||
* RTC 2
|
||||
*/
|
||||
#ifdef CONFIG_PLL_CLKSRC
|
||||
# if ( (CONFIG_PLL_CLKSRC < 0) || (CONFIG_PLL_CLKSRC > 2) )
|
||||
# error "PLL clock source not valid, check configuration "
|
||||
# endif
|
||||
#else
|
||||
# error "PLL clock source not defined, check configuration file"
|
||||
#endif
|
||||
|
||||
/* PLL provides CCLK and must always be configured */
|
||||
#define PLL ( PLL_M | (PLL_N << 16) )
|
||||
|
||||
/* Memory Accelerator Module (MAM) initialization values
|
||||
*
|
||||
* MAM Control Register
|
||||
* Bit 0:1 Mode
|
||||
* 0 = Disabled
|
||||
* 1 = Partially Enabled
|
||||
* 2 = Fully Enabled
|
||||
* MAM Timing Register
|
||||
* Bit 0:2 Fetch Cycles
|
||||
* 0 = Reserved
|
||||
* 1 = 1 CCLK
|
||||
* 2 = 2 CCLK
|
||||
* 3 = 3 CCLK
|
||||
* 4 = 4 CCLK
|
||||
* 5 = 5 CCLK
|
||||
* 6 = 6 CCLK
|
||||
* 7 = 7 CCLK
|
||||
*/
|
||||
/* LPC2378 Rev. '-' errata MAM may not work if fully enabled */
|
||||
#ifdef CONFIG_MAM_SETUP
|
||||
# ifndef CONFIG_MAMCR_VALUE /* Can be selected from config file */
|
||||
# define CONFIG_MAMCR_VALUE (MAMCR_PART)
|
||||
# endif
|
||||
|
||||
# ifndef CONFIG_MAMTIM_VALUE /* Can be selected from config file */
|
||||
# define CONFIG_MAMTIM_VALUE (0x00000003)
|
||||
# endif
|
||||
#endif
|
||||
|
||||
/****************************************************************************
|
||||
* Private Functions
|
||||
****************************************************************************/
|
||||
|
||||
|
||||
/****************************************************************************
|
||||
* Name: up_scbpllfeed
|
||||
****************************************************************************/
|
||||
static inline void up_scbpllfeed(void)
|
||||
{
|
||||
SCB_PLLFEED = 0xAA;
|
||||
SCB_PLLFEED = 0x55;
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
* Name: ConfigurePLL
|
||||
****************************************************************************/
|
||||
void ConfigurePLL ( void )
|
||||
{
|
||||
uint32_t MSel, NSel;
|
||||
|
||||
/* LPC2378 Rev.'-' errata Enable the Ethernet block to enable 16k EnetRAM */
|
||||
SCB_PCONP |= PCENET;
|
||||
|
||||
/* Vectors are remapped to Flash */
|
||||
SCB_MEMMAP = MEMMAP2FLASH;
|
||||
|
||||
/* Enable PLL, disconnected */
|
||||
if(SCB_PLLSTAT & (1 << 25))
|
||||
{
|
||||
SCB_PLLCON = 0x01;
|
||||
up_scbpllfeed();
|
||||
}
|
||||
|
||||
/* Disable PLL, disconnected */
|
||||
SCB_PLLCON = 0;
|
||||
up_scbpllfeed();
|
||||
|
||||
/* Enable main OSC */
|
||||
SCB_SCS |= 0x20;
|
||||
|
||||
/* Wait until main OSC is usable */
|
||||
while( !(SCB_SCS & 0x40) );
|
||||
|
||||
|
||||
/* select main OSC, 12MHz, as the PLL clock source */
|
||||
SCB_CLKSRCSEL = CONFIG_PLL_CLKSRC;
|
||||
|
||||
/* Reconfigure PLL */
|
||||
SCB_PLLCFG = PLL;
|
||||
up_scbpllfeed();
|
||||
|
||||
|
||||
/* Enable PLL */
|
||||
SCB_PLLCON = 0x01;
|
||||
up_scbpllfeed();
|
||||
|
||||
/* Set clock divider */
|
||||
SCB_CCLKCFG = CCLK_DIV;
|
||||
|
||||
|
||||
#ifdef CONFIG_USBDEV
|
||||
/* usbclk = 288 MHz/6 = 48 MHz */
|
||||
SCB_USBCLKCFG = USBCLK_DIV;
|
||||
/* Turn On USB PCLK */
|
||||
SCB_PCONP |= PCUSB;
|
||||
#endif
|
||||
|
||||
/* Wait for PLL to lock */
|
||||
while( ( SCB_PLLSTAT & (1 << 26) ) == 0);
|
||||
|
||||
MSel = SCB_PLLSTAT & 0x00007FFF;
|
||||
NSel = ( SCB_PLLSTAT & 0x00FF0000 ) >> 16;
|
||||
while( (MSel != PLL_M) && (NSel != PLL_N) );
|
||||
|
||||
/* Enable and connect */
|
||||
SCB_PLLCON = 0x03;
|
||||
up_scbpllfeed();
|
||||
|
||||
/* Check connect bit status */
|
||||
while( ( SCB_PLLSTAT & ( 1 << 25 ) ) == 0 );
|
||||
|
||||
/* Set memory accelerater module*/
|
||||
SCB_MAMCR = 0;
|
||||
SCB_MAMTIM = CONFIG_MAMTIM_VALUE;
|
||||
SCB_MAMCR = CONFIG_MAMCR_VALUE;
|
||||
|
||||
/* Enable FastIO on P0:P1 */
|
||||
SCB_SCS |= 0x01;
|
||||
|
||||
IO_Init();
|
||||
|
||||
return;
|
||||
}
|
131
arch/arm/src/lpc2378/lpc23xx_scb.h
Executable file
131
arch/arm/src/lpc2378/lpc23xx_scb.h
Executable file
@ -0,0 +1,131 @@
|
||||
/****************************************************************************************************
|
||||
* arch/arm/src/lpc2378/lpc23xx_scb.h
|
||||
*
|
||||
* Copyright (C) 2010 Rommel Marcelo. All rights reserved.
|
||||
* Author: Rommel Marcelo
|
||||
*
|
||||
* This file is part of the NuttX RTOS and based on the lpc2148 port:
|
||||
*
|
||||
* 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.
|
||||
*
|
||||
****************************************************************************************************/
|
||||
|
||||
#ifndef __ARCH_ARM_SRC_LPC2378_LPC23XX_SCB_H
|
||||
#define __ARCH_ARM_SRC_LPC2378_LPC23XX_SCB_H
|
||||
|
||||
/****************************************************************************************************
|
||||
* Included Files
|
||||
****************************************************************************************************/
|
||||
|
||||
#include <chip.h>
|
||||
#include "lpc23xx_vic.h"
|
||||
|
||||
/****************************************************************************************************
|
||||
* Definitions
|
||||
****************************************************************************************************/
|
||||
#define scb_getreg(o) getreg32(LPC23XX_SCB_BASE + (o))
|
||||
#define scb_putreg(v,o) putreg32((v),LPC23XX_SCB_BASE + (o))
|
||||
|
||||
/* Memory Accelerator Mode */
|
||||
#define MAMCR_OFF 0
|
||||
#define MAMCR_PART 1
|
||||
#define MAMCR_FULL 2
|
||||
|
||||
/* Memory Mapping */
|
||||
#define MEMMAP2BBLK 0 /* Interrupt Vectors in Boot Block */
|
||||
#define MEMMAP2FLASH 1 /* Interrupt Vectors in FLASH */
|
||||
#define MEMMAP2SRAM 2 /* Interrupt Vectors in RAM */
|
||||
|
||||
/* Register bit settings */
|
||||
|
||||
/* PLL Control Register Bit Settings */
|
||||
|
||||
#define PLLCON_PLLE (1 << 0) /* PLL Enable */
|
||||
#define PLLCON_PLLC (1 << 1) /* PLL Connect */
|
||||
|
||||
/* PLL Configuration Register Bit Settings */
|
||||
|
||||
#define PLLCFG_MSEL (0x0000FFFF << 0) /* PLL Multiplier (minus 1) */
|
||||
#define PLLCFG_NSEL (0x000000FF << 16) /* PLL Divider */
|
||||
|
||||
|
||||
/* PLL Status Register Bit Settings */
|
||||
|
||||
#define PLLSTAT_MSEL (0x7FFF << 0) /* PLL Multiplier Readback */
|
||||
#define PLLSTAT_NSEL (0xFF << 16) /* PLL Divider Readback */
|
||||
#define PLLSTAT_PLLE (1 << 24) /* PLL Enable Readback */
|
||||
#define PLLSTAT_PLLC (1 << 25) /* PLL Connect Readback */
|
||||
#define PLLSTAT_PLOCK (1 << 26) /* PLL Lock Status */
|
||||
|
||||
/* PLL Feed Register values */
|
||||
|
||||
#define PLLFEED1 0xaa
|
||||
#define PLLFEED2 0x55
|
||||
|
||||
|
||||
/* Peripheral Power Control (PCONP) Register 0xE01FC0C4 */
|
||||
|
||||
#define PCTIM0 (1 << 1) /* Timer/Counter 0 */
|
||||
#define PCTIM1 (1 << 2) /* Timer/Counter 1 */
|
||||
#define PCUART0 (1 << 3) /* UART0 power/clock */
|
||||
#define PCUART1 (1 << 4) /* UART1 power/clock */
|
||||
#define PCPWM1 (1 << 5) /* Unused, always 0 */
|
||||
#define PWM1 (1 << 6) /* Pulse Width Modulation 1 */
|
||||
#define PCI2C0 (1 << 7) /* I2C0 interface */
|
||||
#define PCSPI (1 << 8) /* SPI */
|
||||
#define PCRTC (1 << 9) /* Real Time Clock*/
|
||||
#define PCSSP1 (1 << 10) /* SSP1 */
|
||||
#define PCEMC (1 << 11) /* External Memory Controller */
|
||||
#define PCAD (1 << 12) /* A/D converter (ADC) Note: Clear the PDN bit in the AD0CR before
|
||||
clearing this bit, and set this bit before setting PDN */
|
||||
#define PCAN1 (1 << 13) /* CAN Controller 1 */
|
||||
#define PCAN2 (1 << 14) /* CAN Controller 2 */
|
||||
#define PCI2C1 (1 << 19) /* The I2C1 interface power/clock control bit */
|
||||
#define PCSSP0 (1 << 21) /* The SSP0 interface power/clock control bit */
|
||||
#define PCTIM2 (1 << 22) /* Timer 2 */
|
||||
#define PCTIM3 (1 << 23) /* Timer 3 */
|
||||
#define PCUART2 (1 << 24) /* UART 2 */
|
||||
#define PCUART3 (1 << 25) /* UART 3 */
|
||||
#define PCI2C2 (1 << 26) /* I2C interface 2 */
|
||||
#define PCI2S (1 << 27) /* I2S interface */
|
||||
#define PCSDC (1 << 28) /* SD card interface */
|
||||
#define PCGPDMA (1 << 29) /* GP DMA function */
|
||||
#define PCENET (1 << 30) /* Ethernet block */
|
||||
#define PCUSB (1 << 31) /* USB interface */
|
||||
/****************************************************************************************************
|
||||
* Inline Functions
|
||||
****************************************************************************************************/
|
||||
|
||||
/****************************************************************************************************
|
||||
* Global Function Prototypes
|
||||
****************************************************************************************************/
|
||||
|
||||
#endif /* __ARCH_ARM_SRC_LPC2378_LPC23XX_SCB_H */
|
976
arch/arm/src/lpc2378/lpc23xx_serial.c
Executable file
976
arch/arm/src/lpc2378/lpc23xx_serial.c
Executable file
@ -0,0 +1,976 @@
|
||||
/****************************************************************************
|
||||
* arch/arm/src/lpc2378/lpc23xx_serial.c
|
||||
*
|
||||
* Copyright (C) 2010 Rommel Marcelo. All rights reserved.
|
||||
* Author: Rommel Marcelo
|
||||
*
|
||||
* This file is part of the NuttX RTOS and based on the lpc2148 port:
|
||||
*
|
||||
* 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.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Included Files
|
||||
****************************************************************************/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
|
||||
#include <sys/types.h>
|
||||
#include <stdint.h>
|
||||
#include <stdbool.h>
|
||||
#include <unistd.h>
|
||||
#include <semaphore.h>
|
||||
#include <string.h>
|
||||
#include <errno.h>
|
||||
#include <debug.h>
|
||||
#include <nuttx/irq.h>
|
||||
#include <nuttx/arch.h>
|
||||
#include <nuttx/serial.h>
|
||||
#include <arch/serial.h>
|
||||
|
||||
#include "chip.h"
|
||||
#include "up_arch.h"
|
||||
#include "os_internal.h"
|
||||
|
||||
#include "internal.h"
|
||||
#include "lpc23xx_scb.h"
|
||||
#include "lpc23xx_pinsel.h"
|
||||
#include "lpc23xx_uart.h"
|
||||
#include "lpc23xx_vic.h"
|
||||
|
||||
#ifdef CONFIG_USE_SERIALDRIVER
|
||||
|
||||
/****************************************************************************
|
||||
* Definitions
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Private Types
|
||||
****************************************************************************/
|
||||
|
||||
struct up_dev_s
|
||||
{
|
||||
uint32_t uartbase; /* Base address of UART registers */
|
||||
uint32_t baud; /* Configured baud */
|
||||
uint8_t ier; /* Saved IER value */
|
||||
uint8_t irq; /* IRQ associated with this UART */
|
||||
uint8_t parity; /* 0=none, 1=odd, 2=even */
|
||||
uint8_t bits; /* Number of bits (7 or 8) */
|
||||
bool stopbits2; /* true: Configure with 2 stop bits instead of 1 */
|
||||
};
|
||||
|
||||
/****************************************************************************
|
||||
* Private Function Prototypes
|
||||
****************************************************************************/
|
||||
|
||||
static int up_setup(struct uart_dev_s *dev);
|
||||
static void up_shutdown(struct uart_dev_s *dev);
|
||||
static int up_attach(struct uart_dev_s *dev);
|
||||
static void up_detach(struct uart_dev_s *dev);
|
||||
static int up_interrupt(int irq, void *context);
|
||||
static int up_ioctl(struct file *filep, int cmd, unsigned long arg);
|
||||
static int up_receive(struct uart_dev_s *dev, uint32_t *status);
|
||||
static void up_rxint(struct uart_dev_s *dev, bool enable);
|
||||
static bool up_rxavailable(struct uart_dev_s *dev);
|
||||
static void up_send(struct uart_dev_s *dev, int ch);
|
||||
static void up_txint(struct uart_dev_s *dev, bool enable);
|
||||
static bool up_txready(struct uart_dev_s *dev);
|
||||
static bool up_txempty(struct uart_dev_s *dev);
|
||||
|
||||
/****************************************************************************
|
||||
* Private Variables
|
||||
****************************************************************************/
|
||||
|
||||
struct uart_ops_s g_uart_ops =
|
||||
{
|
||||
.setup = up_setup,
|
||||
.shutdown = up_shutdown,
|
||||
.attach = up_attach,
|
||||
.detach = up_detach,
|
||||
.ioctl = up_ioctl,
|
||||
.receive = up_receive,
|
||||
.rxint = up_rxint,
|
||||
.rxavailable = up_rxavailable,
|
||||
.send = up_send,
|
||||
.txint = up_txint,
|
||||
.txready = up_txready,
|
||||
.txempty = up_txempty,
|
||||
};
|
||||
|
||||
/* I/O buffers */
|
||||
|
||||
static char g_uart0rxbuffer[CONFIG_UART0_RXBUFSIZE];
|
||||
static char g_uart0txbuffer[CONFIG_UART0_TXBUFSIZE];
|
||||
static char g_uart2rxbuffer[CONFIG_UART2_RXBUFSIZE];
|
||||
static char g_uart2txbuffer[CONFIG_UART2_TXBUFSIZE];
|
||||
|
||||
/* This describes the state of the LPC214X uart0 port. */
|
||||
#ifdef CONFIG_UART0
|
||||
static struct up_dev_s g_uart0priv =
|
||||
{
|
||||
.uartbase = UART0_BASE_ADDR,
|
||||
.baud = CONFIG_UART0_BAUD,
|
||||
.irq = UART0_IRQ,
|
||||
.parity = CONFIG_UART0_PARITY,
|
||||
.bits = CONFIG_UART0_BITS,
|
||||
.stopbits2 = CONFIG_UART0_2STOP,
|
||||
};
|
||||
|
||||
static uart_dev_t g_uart0port =
|
||||
{
|
||||
.recv =
|
||||
{
|
||||
.size = CONFIG_UART0_RXBUFSIZE,
|
||||
.buffer = g_uart0rxbuffer,
|
||||
},
|
||||
.xmit =
|
||||
{
|
||||
.size = CONFIG_UART0_TXBUFSIZE,
|
||||
.buffer = g_uart0txbuffer,
|
||||
},
|
||||
.ops = &g_uart_ops,
|
||||
.priv = &g_uart0priv,
|
||||
};
|
||||
#endif
|
||||
|
||||
#ifdef CONFIG_UART2
|
||||
/* This describes the state of the LPC23XX uart2 port. */
|
||||
|
||||
static struct up_dev_s g_uart2priv =
|
||||
{
|
||||
.uartbase = UART2_BASE_ADDR,
|
||||
.baud = CONFIG_UART2_BAUD,
|
||||
.irq = UART2_IRQ,
|
||||
.parity = CONFIG_UART2_PARITY,
|
||||
.bits = CONFIG_UART2_BITS,
|
||||
.stopbits2 = CONFIG_UART2_2STOP,
|
||||
|
||||
};
|
||||
|
||||
static uart_dev_t g_uart2port =
|
||||
{
|
||||
.recv =
|
||||
{
|
||||
.size = CONFIG_UART2_RXBUFSIZE,
|
||||
.buffer = g_uart2rxbuffer,
|
||||
},
|
||||
.xmit =
|
||||
{
|
||||
.size = CONFIG_UART2_TXBUFSIZE,
|
||||
.buffer = g_uart2txbuffer,
|
||||
},
|
||||
.ops = &g_uart_ops,
|
||||
.priv = &g_uart2priv,
|
||||
};
|
||||
|
||||
#endif
|
||||
/* Now, which one with be tty0/console and which tty1? */
|
||||
|
||||
#if defined(CONFIG_UART0_SERIAL_CONSOLE)
|
||||
# define CONSOLE_DEV g_uart0port
|
||||
# define TTYS0_DEV g_uart0port
|
||||
# define TTYS1_DEV g_uart2port
|
||||
#elif defined(CONFIG_UART1_SERIAL_CONSOLE)
|
||||
# define CONSOLE_DEV g_uart2port
|
||||
# define TTYS0_DEV g_uart2port
|
||||
# define TTYS1_DEV g_uart0port
|
||||
#else
|
||||
# error "No CONFIG_UARTn_SERIAL_CONSOLE Setting"
|
||||
#endif
|
||||
|
||||
/****************************************************************************
|
||||
* Private Functions
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Name: up_serialin
|
||||
****************************************************************************/
|
||||
|
||||
static inline uint8_t up_serialin(struct up_dev_s *priv, int offset)
|
||||
{
|
||||
return getreg8(priv->uartbase + offset);
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
* Name: up_serialout
|
||||
****************************************************************************/
|
||||
|
||||
static inline void up_serialout(struct up_dev_s *priv, int offset, uint8_t value)
|
||||
{
|
||||
putreg8(value, priv->uartbase + offset);
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
* Name: up_disableuartint
|
||||
****************************************************************************/
|
||||
|
||||
static inline void up_disableuartint(struct up_dev_s *priv, uint8_t *ier)
|
||||
{
|
||||
if (ier)
|
||||
{
|
||||
*ier = priv->ier & IER_ALLIE;
|
||||
}
|
||||
|
||||
priv->ier &= ~IER_ALLIE;
|
||||
up_serialout(priv, UART_IER_OFFSET, priv->ier);
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
* Name: up_restoreuartint
|
||||
****************************************************************************/
|
||||
|
||||
static inline void up_restoreuartint(struct up_dev_s *priv, uint8_t ier)
|
||||
{
|
||||
priv->ier |= ier & IER_ALLIE;
|
||||
up_serialout(priv, UART_IER_OFFSET, priv->ier);
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
* Name: up_waittxready
|
||||
****************************************************************************/
|
||||
|
||||
static inline void up_waittxready(struct up_dev_s *priv)
|
||||
{
|
||||
int tmp;
|
||||
|
||||
/* Limit how long we will wait for the TX available condition */
|
||||
for (tmp = 1000 ; tmp > 0 ; tmp--)
|
||||
{
|
||||
/* Check if the tranmitter holding register (THR) is empty */
|
||||
if ((up_serialin(priv, UART_LSR_OFFSET) & LSR_THRE) != 0)
|
||||
{
|
||||
/* The THR is empty, return */
|
||||
break;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
* Name: up_enablebreaks
|
||||
****************************************************************************/
|
||||
|
||||
static inline void up_enablebreaks(struct up_dev_s *priv, bool enable)
|
||||
{
|
||||
uint8_t lcr = up_serialin(priv, UART_LCR_OFFSET);
|
||||
if (enable)
|
||||
{
|
||||
lcr |= LCR_BREAK_ENABLE;
|
||||
}
|
||||
else
|
||||
{
|
||||
lcr &= ~LCR_BREAK_ENABLE;
|
||||
}
|
||||
up_serialout(priv, UART_LCR_OFFSET, lcr);
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
* Name: up_configbaud
|
||||
****************************************************************************/
|
||||
static inline void up_configbaud(struct up_dev_s *priv)
|
||||
{
|
||||
|
||||
/* In a buckled-up, embedded system, there is no reason to constantly
|
||||
* calculate the following. The calculation can be skipped if the
|
||||
* MULVAL, DIVADDVAL, and DIVISOR values are provided in the configuration
|
||||
* file.
|
||||
*/
|
||||
|
||||
#ifndef CONFIG_UART_MULVAL
|
||||
uint32_t qtrclk;
|
||||
|
||||
/* Test values calculated for every multiplier/divisor combination */
|
||||
|
||||
uint32_t tdiv;
|
||||
uint32_t terr;
|
||||
int tmulval;
|
||||
int tdivaddval;
|
||||
|
||||
/* Optimal multiplier/divider values */
|
||||
|
||||
uint32_t div = 0;
|
||||
uint32_t err = 100000;
|
||||
int mulval = 1;
|
||||
int divaddval = 0;
|
||||
|
||||
/* Baud is generated using FDR and DLL-DLM registers
|
||||
*
|
||||
* baud = clock * (mulval/(mulval+divaddval) / (16 * div)
|
||||
*
|
||||
* Or
|
||||
*
|
||||
* div = (clock/16) * (mulval/(mulval+divaddval) / baud
|
||||
*
|
||||
* Where mulval = Fractional divider multiplier
|
||||
* divaddval = Fractional divider pre-scale div
|
||||
* div = DLL-DLM divisor
|
||||
*/
|
||||
|
||||
/* Get UART block clock divided by 16 */
|
||||
|
||||
qtrclk = U0_PCLK >> 4; /* TODO: Different Uart port with different clocking */
|
||||
|
||||
/* Try every valid multiplier, tmulval (or until a perfect
|
||||
* match is found).
|
||||
*/
|
||||
|
||||
for (tmulval = 1 ; tmulval <= 15 && err > 0; tmulval++)
|
||||
{
|
||||
/* Try every valid pre-scale div, tdivaddval (or until a perfect
|
||||
* match is found).
|
||||
*/
|
||||
|
||||
for (tdivaddval = 0 ; tdivaddval <= 15 && err > 0; tdivaddval++)
|
||||
{
|
||||
/* Calculate the divisor with these fractional divider settings */
|
||||
|
||||
uint32_t tmp = (tmulval * qtrclk) / ((tmulval + tdivaddval));
|
||||
tdiv = (tmp + (priv->baud >>1)) / priv->baud;
|
||||
|
||||
/* Check if this candidate divisor is within a valid range */
|
||||
|
||||
if (tdiv > 2 && tdiv < 0x10000)
|
||||
{
|
||||
/* Calculate the actual baud and the error */
|
||||
|
||||
uint32_t actualbaud = tmp / tdiv;
|
||||
|
||||
if (actualbaud <= priv->baud)
|
||||
{
|
||||
terr = priv->baud - actualbaud;
|
||||
}
|
||||
else
|
||||
{
|
||||
terr = actualbaud - priv->baud;
|
||||
}
|
||||
|
||||
/* Is this the smallest error we have encountered? */
|
||||
|
||||
if (terr < err)
|
||||
{
|
||||
/* Yes, save these settings as the new, candidate optimal settings */
|
||||
|
||||
mulval = tmulval ;
|
||||
divaddval = tdivaddval;
|
||||
div = tdiv;
|
||||
err = terr;
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
/* Configure the MS and LS DLAB registers */
|
||||
|
||||
up_serialout(priv, UART_DLM_OFFSET, div >> 8);
|
||||
up_serialout(priv, UART_DLL_OFFSET, div & 0xff);
|
||||
|
||||
/* Configure the Fractional Divider Register (FDR) */
|
||||
|
||||
up_serialout(priv, UART_FDR_OFFSET, ((mulval << 4) | divaddval) );
|
||||
|
||||
#else
|
||||
|
||||
/* Configure the MS and LS DLAB registers */
|
||||
up_serialout(priv, UART_DLM_OFFSET, DLMVAL >> 8);
|
||||
up_serialout(priv, UART_DLL_OFFSET, DLLVAL & 0xff);
|
||||
|
||||
/* Configure the Fractional Divider Register (FDR) */
|
||||
|
||||
up_serialout(priv, UART_FDR_OFFSET, ((MULVAL << 4) | DIVADDVAL) );
|
||||
|
||||
#endif
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
* Name: up_setup
|
||||
*
|
||||
* Description:
|
||||
* Configure the UART baud, bits, parity, fifos, etc. This
|
||||
* method is called the first time that the serial port is
|
||||
* opened.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
static int up_setup(struct uart_dev_s *dev)
|
||||
{
|
||||
#ifndef CONFIG_SUPPRESS_LPC214X_UART_CONFIG
|
||||
struct up_dev_s *priv = (struct up_dev_s*)dev->priv;
|
||||
uint8_t lcr;
|
||||
|
||||
/* Clear fifos */
|
||||
|
||||
up_serialout(priv, UART_FCR_OFFSET,
|
||||
(FCR_RX_FIFO_RESET|FCR_TX_FIFO_RESET));
|
||||
|
||||
/* Set trigger */
|
||||
|
||||
up_serialout(priv, UART_FCR_OFFSET,
|
||||
(FCR_FIFO_ENABLE|FCR_FIFO_TRIG14));
|
||||
|
||||
/* Set up the IER */
|
||||
|
||||
priv->ier = up_serialin(priv, UART_IER_OFFSET);
|
||||
|
||||
/* Set up the Line Control Register */
|
||||
|
||||
lcr = 0;
|
||||
|
||||
lcr |= (priv->bits == 7) ? LCR_CHAR_7 : LCR_CHAR_8;
|
||||
|
||||
if (priv->stopbits2)
|
||||
{
|
||||
lcr |= LCR_STOP_2;
|
||||
}
|
||||
|
||||
if (priv->parity == 1)
|
||||
{
|
||||
lcr |= LCR_PAR_ODD;
|
||||
}
|
||||
else if (priv->parity == 2)
|
||||
{
|
||||
lcr |= LCR_PAR_EVEN;
|
||||
}
|
||||
|
||||
/* Enable access to latch divisor DLAB=1 */
|
||||
|
||||
up_serialout( priv, UART_LCR_OFFSET, (lcr | LCR_DLAB_ENABLE) );
|
||||
|
||||
/* find values for DLL, DLM, DIVADDVAL, MULVAL */
|
||||
|
||||
up_configbaud(priv);
|
||||
|
||||
/* Disable access to latch divisor Clear DLAB */
|
||||
|
||||
up_serialout(priv, UART_LCR_OFFSET, lcr);
|
||||
|
||||
/* Configure the FIFOs */
|
||||
|
||||
up_serialout(priv, UART_FCR_OFFSET,
|
||||
(FCR_FIFO_TRIG8 | FCR_TX_FIFO_RESET | \
|
||||
FCR_RX_FIFO_RESET | FCR_FIFO_ENABLE));
|
||||
|
||||
/* The NuttX serial driver waits for the first THRE interrrupt before
|
||||
* sending serial data... However, it appears that the LPC2378 hardware too
|
||||
* does not generate that interrupt until a transition from not-empty
|
||||
* to empty. So, the current kludge here is to send one NULL at
|
||||
* startup to kick things off.
|
||||
*/
|
||||
up_serialout(priv, UART_THR_OFFSET, '\0');
|
||||
#endif
|
||||
return OK;
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
* Name: up_shutdown
|
||||
*
|
||||
* Description:
|
||||
* Disable the UART. This method is called when the serial
|
||||
* port is closed
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
static void up_shutdown(struct uart_dev_s *dev)
|
||||
{
|
||||
struct up_dev_s *priv = (struct up_dev_s*)dev->priv;
|
||||
up_disableuartint(priv, NULL);
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
* Name: up_attach
|
||||
*
|
||||
* Description:
|
||||
* Configure the UART to operation in interrupt driven mode. This method is
|
||||
* called when the serial port is opened. Normally, this is just after the
|
||||
* the setup() method is called, however, the serial console may operate in
|
||||
* a non-interrupt driven mode during the boot phase.
|
||||
*
|
||||
* RX and TX interrupts are not enabled when by the attach method (unless the
|
||||
* hardware supports multiple levels of interrupt enabling). The RX and TX
|
||||
* interrupts are not enabled until the txint() and rxint() methods are called.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
static int up_attach(struct uart_dev_s *dev)
|
||||
{
|
||||
struct up_dev_s *priv = (struct up_dev_s*)dev->priv;
|
||||
int ret;
|
||||
|
||||
/* Attach and enable the IRQ */
|
||||
|
||||
ret = irq_attach(priv->irq, up_interrupt);
|
||||
if (ret == OK)
|
||||
{
|
||||
/* Enable the interrupt (RX and TX interrupts are still disabled
|
||||
* in the UART
|
||||
*/
|
||||
|
||||
up_enable_irq(priv->irq);
|
||||
|
||||
/* Set the uart interrupt priority (the default value is one) */
|
||||
if (priv->uartbase == UART0_BASE_ADDR)
|
||||
{
|
||||
up_prioritize_irq(priv->irq, PRIORITY_LOWEST);
|
||||
}
|
||||
else if (priv->uartbase == UART2_BASE_ADDR)
|
||||
{
|
||||
up_prioritize_irq(priv->irq, 10);
|
||||
}
|
||||
|
||||
}
|
||||
return ret;
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
* Name: up_detach
|
||||
*
|
||||
* Description:
|
||||
* Detach UART interrupts. This method is called when the serial port is
|
||||
* closed normally just before the shutdown method is called. The exception is
|
||||
* the serial console which is never shutdown.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
static void up_detach(struct uart_dev_s *dev)
|
||||
{
|
||||
struct up_dev_s *priv = (struct up_dev_s*)dev->priv;
|
||||
up_disable_irq(priv->irq);
|
||||
irq_detach(priv->irq);
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
* Name: up_interrupt
|
||||
*
|
||||
* Description:
|
||||
* This is the UART interrupt handler. It will be invoked
|
||||
* when an interrupt received on the 'irq' It should call
|
||||
* uart_transmitchars or uart_receivechar to perform the
|
||||
* appropriate data transfers. The interrupt handling logic\
|
||||
* must be able to map the 'irq' number into the approprite
|
||||
* uart_dev_s structure in order to call these functions.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
static int up_interrupt(int irq, void *context)
|
||||
{
|
||||
struct uart_dev_s *dev = NULL;
|
||||
struct up_dev_s *priv;
|
||||
uint8_t status;
|
||||
int passes;
|
||||
|
||||
if (g_uart0priv.irq == irq)
|
||||
{
|
||||
dev = &g_uart0port;
|
||||
}
|
||||
else if (g_uart2priv.irq == irq)
|
||||
{
|
||||
dev = &g_uart2port;
|
||||
}
|
||||
else
|
||||
{
|
||||
PANIC(OSERR_INTERNAL);
|
||||
}
|
||||
priv = (struct up_dev_s*)dev->priv;
|
||||
|
||||
/* Loop until there are no characters to be transferred or,
|
||||
* until we have been looping for a long time.
|
||||
*/
|
||||
|
||||
for (passes = 0; passes < 256; passes++)
|
||||
{
|
||||
/* Get the current UART status and check for loop
|
||||
* termination conditions
|
||||
*/
|
||||
|
||||
status = up_serialin(priv, UART_IIR_OFFSET);
|
||||
|
||||
/* The NO INTERRUPT should be zero if there are pending
|
||||
* interrupts
|
||||
*/
|
||||
|
||||
if ((status & IIR_NO_INT) != 0)
|
||||
{
|
||||
/* Break out of the loop when there is no longer a
|
||||
* pending interrupt
|
||||
*/
|
||||
|
||||
break;
|
||||
}
|
||||
|
||||
/* Handle the interrupt by its interrupt ID field */
|
||||
|
||||
switch (status & IIR_MASK)
|
||||
{
|
||||
/* Handle incoming, receive bytes (with or without timeout) */
|
||||
|
||||
case IIR_RDA_INT:
|
||||
case IIR_CTI_INT:
|
||||
{
|
||||
uart_recvchars(dev);
|
||||
break;
|
||||
}
|
||||
|
||||
/* Handle outgoing, transmit bytes */
|
||||
|
||||
case IIR_THRE_INT:
|
||||
{
|
||||
uart_xmitchars(dev);
|
||||
break;
|
||||
}
|
||||
|
||||
/* Just clear modem status interrupts (UART1 only) */
|
||||
|
||||
case IIR_MS_INT:
|
||||
{
|
||||
/* Read the modem status register (MSR) to clear */
|
||||
|
||||
status = up_serialin(priv, UART_MSR_OFFSET);
|
||||
vdbg("MSR: %02x\n", status);
|
||||
break;
|
||||
}
|
||||
|
||||
/* Just clear any line status interrupts */
|
||||
|
||||
case IIR_RLS_INT:
|
||||
{
|
||||
/* Read the line status register (LSR) to clear */
|
||||
|
||||
status = up_serialin(priv, UART_LSR_OFFSET);
|
||||
vdbg("LSR: %02x\n", status);
|
||||
break;
|
||||
}
|
||||
|
||||
/* There should be no other values */
|
||||
|
||||
default:
|
||||
{
|
||||
dbg("Unexpected IIR: %02x\n", status);
|
||||
break;
|
||||
}
|
||||
}
|
||||
}
|
||||
return OK;
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
* Name: up_ioctl
|
||||
*
|
||||
* Description:
|
||||
* All ioctl calls will be routed through this method
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
static int up_ioctl(struct file *filep, int cmd, unsigned long arg)
|
||||
{
|
||||
struct inode *inode = filep->f_inode;
|
||||
struct uart_dev_s *dev = inode->i_private;
|
||||
struct up_dev_s *priv = (struct up_dev_s*)dev->priv;
|
||||
int ret = OK;
|
||||
|
||||
switch (cmd)
|
||||
{
|
||||
case TIOCSERGSTRUCT:
|
||||
{
|
||||
struct up_dev_s *user = (struct up_dev_s*)arg;
|
||||
if (!user)
|
||||
{
|
||||
*get_errno_ptr() = EINVAL;
|
||||
ret = ERROR;
|
||||
}
|
||||
else
|
||||
{
|
||||
memcpy(user, dev, sizeof(struct up_dev_s));
|
||||
}
|
||||
}
|
||||
break;
|
||||
|
||||
case TIOCSBRK: /* BSD compatibility: Turn break on, unconditionally */
|
||||
{
|
||||
irqstate_t flags = irqsave();
|
||||
up_enablebreaks(priv, true);
|
||||
irqrestore(flags);
|
||||
}
|
||||
break;
|
||||
|
||||
case TIOCCBRK: /* BSD compatibility: Turn break off, unconditionally */
|
||||
{
|
||||
irqstate_t flags;
|
||||
flags = irqsave();
|
||||
up_enablebreaks(priv, false);
|
||||
irqrestore(flags);
|
||||
}
|
||||
break;
|
||||
|
||||
default:
|
||||
*get_errno_ptr() = ENOTTY;
|
||||
ret = ERROR;
|
||||
break;
|
||||
}
|
||||
|
||||
return ret;
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
* Name: up_receive
|
||||
*
|
||||
* Description:
|
||||
* Called (usually) from the interrupt level to receive one
|
||||
* character from the UART. Error bits associated with the
|
||||
* receipt are provided in the return 'status'.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
static int up_receive(struct uart_dev_s *dev, uint32_t *status)
|
||||
{
|
||||
struct up_dev_s *priv = (struct up_dev_s*)dev->priv;
|
||||
uint8_t rbr;
|
||||
|
||||
*status = up_serialin(priv, UART_LSR_OFFSET);
|
||||
rbr = up_serialin(priv, UART_RBR_OFFSET);
|
||||
return rbr;
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
* Name: up_rxint
|
||||
*
|
||||
* Description:
|
||||
* Call to enable or disable RX interrupts
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
static void up_rxint(struct uart_dev_s *dev, bool enable)
|
||||
{
|
||||
struct up_dev_s *priv = (struct up_dev_s*)dev->priv;
|
||||
if (enable)
|
||||
{
|
||||
#ifndef CONFIG_SUPPRESS_SERIAL_INTS
|
||||
priv->ier |= IER_ERBFI;
|
||||
#endif
|
||||
}
|
||||
else
|
||||
{
|
||||
priv->ier &= ~IER_ERBFI;
|
||||
}
|
||||
up_serialout(priv, UART_IER_OFFSET, priv->ier);
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
* Name: up_rxavailable
|
||||
*
|
||||
* Description:
|
||||
* Return true if the receive fifo is not empty
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
static bool up_rxavailable(struct uart_dev_s *dev)
|
||||
{
|
||||
struct up_dev_s *priv = (struct up_dev_s*)dev->priv;
|
||||
return ((up_serialin(priv, UART_LSR_OFFSET) & LSR_RDR) != 0);
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
* Name: up_send
|
||||
*
|
||||
* Description:
|
||||
* This method will send one byte on the UART
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
static void up_send(struct uart_dev_s *dev, int ch)
|
||||
{
|
||||
struct up_dev_s *priv = (struct up_dev_s*)dev->priv;
|
||||
up_serialout(priv, UART_THR_OFFSET, (uint8_t)ch);
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
* Name: up_txint
|
||||
*
|
||||
* Description:
|
||||
* Call to enable or disable TX interrupts
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
static void up_txint(struct uart_dev_s *dev, bool enable)
|
||||
{
|
||||
struct up_dev_s *priv = (struct up_dev_s*)dev->priv;
|
||||
if (enable)
|
||||
{
|
||||
#ifndef CONFIG_SUPPRESS_SERIAL_INTS
|
||||
priv->ier |= IER_ETBEI;
|
||||
#endif
|
||||
}
|
||||
else
|
||||
{
|
||||
priv->ier &= ~IER_ETBEI;
|
||||
}
|
||||
up_serialout(priv, UART_IER_OFFSET, priv->ier);
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
* Name: up_txready
|
||||
*
|
||||
* Description:
|
||||
* Return true if the tranmsit fifo is not full
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
static bool up_txready(struct uart_dev_s *dev)
|
||||
{
|
||||
struct up_dev_s *priv = (struct up_dev_s*)dev->priv;
|
||||
return ((up_serialin(priv, UART_LSR_OFFSET) & LSR_THRE) != 0);
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
* Name: up_txempty
|
||||
*
|
||||
* Description:
|
||||
* Return true if the transmit fifo is empty
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
static bool up_txempty(struct uart_dev_s *dev)
|
||||
{
|
||||
struct up_dev_s *priv = (struct up_dev_s*)dev->priv;
|
||||
return ((up_serialin(priv, UART_LSR_OFFSET) & LSR_THRE) != 0);
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
* Public Funtions
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Name: up_serialinit
|
||||
*
|
||||
* Description:
|
||||
* Performs the low level UART initialization early in
|
||||
* debug so that the serial console will be available
|
||||
* during bootup. This must be called before up_serialinit.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
void up_earlyserialinit(void)
|
||||
{
|
||||
/* Enable UART0 and 2 */
|
||||
uint32_t pinsel = getreg32(LPC23XX_PINSEL0);
|
||||
|
||||
pinsel &= ~( UART0_PINMASK | UART2_PINMASK );
|
||||
pinsel |= ( UART0_PINSEL | UART2_PINSEL );
|
||||
|
||||
putreg32(pinsel, LPC23XX_PINSEL0);
|
||||
|
||||
/* Set Uart PCLK divider */
|
||||
SCB_PCLKSEL0 = (SCB_PCLKSEL0 & ~U0_PCLKSEL_MASK) | U0_PCLKSEL;
|
||||
SCB_PCLKSEL1 = (SCB_PCLKSEL1 & ~U2_PCLKSEL_MASK) | U2_PCLKSEL;
|
||||
|
||||
/* Disable both UARTS */
|
||||
|
||||
up_disableuartint(TTYS0_DEV.priv, NULL);
|
||||
up_disableuartint(TTYS1_DEV.priv, NULL);
|
||||
|
||||
/* Configuration whichever one is the console */
|
||||
|
||||
CONSOLE_DEV.isconsole = true;
|
||||
up_setup(&CONSOLE_DEV);
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
* Name: up_serialinit
|
||||
*
|
||||
* Description:
|
||||
* Register serial console and serial ports. This assumes
|
||||
* that up_earlyserialinit was called previously.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
void up_serialinit(void)
|
||||
{
|
||||
(void)uart_register("/dev/console", &CONSOLE_DEV);
|
||||
(void)uart_register("/dev/ttyS0", &TTYS0_DEV);
|
||||
(void)uart_register("/dev/ttyS1", &TTYS1_DEV);
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
* Name: up_putc
|
||||
*
|
||||
* Description:
|
||||
* Provide priority, low-level access to support OS debug writes
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
int up_putc(int ch)
|
||||
{
|
||||
struct up_dev_s *priv = (struct up_dev_s*)CONSOLE_DEV.priv;
|
||||
uint8_t ier;
|
||||
|
||||
up_disableuartint(priv, &ier);
|
||||
up_waittxready(priv);
|
||||
up_serialout(priv, UART_THR_OFFSET, (uint8_t)ch);
|
||||
|
||||
/* Check for LF */
|
||||
|
||||
if (ch == '\n')
|
||||
{
|
||||
/* Add CR */
|
||||
|
||||
up_waittxready(priv);
|
||||
up_serialout(priv, UART_THR_OFFSET, '\r');
|
||||
}
|
||||
|
||||
up_waittxready(priv);
|
||||
up_restoreuartint(priv, ier);
|
||||
return ch;
|
||||
}
|
||||
|
||||
#else /* CONFIG_USE_SERIALDRIVER */
|
||||
|
||||
/****************************************************************************
|
||||
* Name: up_putc
|
||||
*
|
||||
* Description:
|
||||
* Provide priority, low-level access to support OS debug writes
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
int up_putc(int ch)
|
||||
{
|
||||
/* Check for LF */
|
||||
|
||||
if (ch == '\n')
|
||||
{
|
||||
/* Add CR */
|
||||
|
||||
up_lowputc('\r');
|
||||
}
|
||||
|
||||
up_lowputc(ch);
|
||||
return ch;
|
||||
}
|
||||
|
||||
#endif /* CONFIG_USE_SERIALDRIVER */
|
163
arch/arm/src/lpc2378/lpc23xx_timer.h
Executable file
163
arch/arm/src/lpc2378/lpc23xx_timer.h
Executable file
@ -0,0 +1,163 @@
|
||||
/************************************************************************************
|
||||
* arch/arm/src/lpc2378/lpc23xx_timer.h
|
||||
*
|
||||
* Copyright (C) 2010 Rommel Marcelo. All rights reserved.
|
||||
* Author: Rommel Marcelo
|
||||
*
|
||||
* This file is part of the NuttX RTOS and based on the lpc2148 port:
|
||||
*
|
||||
* 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.
|
||||
*
|
||||
************************************************************************************/
|
||||
|
||||
#ifndef __ARCH_ARM_SRC_LPC2378_LPC23XX_TIMER_H
|
||||
#define __ARCH_ARM_SRC_LPC2378_LPC23XX_TIMER_H
|
||||
|
||||
/************************************************************************************
|
||||
* Included Files
|
||||
************************************************************************************/
|
||||
|
||||
/************************************************************************************
|
||||
* Definitions
|
||||
************************************************************************************/
|
||||
|
||||
#define tmr_getreg8(o) getreg8(LPC23XX_TMR0_BASE+(o))
|
||||
#define tmr_getreg16(o) getreg16(LPC23XX_TMR0_BASE+(o))
|
||||
#define tmr_getreg32(o) getreg32(LPC23XX_TMR0_BASE+(o))
|
||||
|
||||
#define tmr_putreg8(v,o) putreg8((v), LPC23XX_TMR0_BASE+(o))
|
||||
#define tmr_putreg16(v,o) putreg16((v), LPC23XX_TMR0_BASE+(o))
|
||||
#define tmr_putreg32(v,o) putreg32((v), LPC23XX_TMR0_BASE+(o))
|
||||
/* Timer registers are 8, 16-bit and 32-bits wide */
|
||||
|
||||
/* Timer Interrupt Register Bit Definitions (8-bit) */
|
||||
|
||||
#define TMR_IR_MR0I (1 << 0) /* Interrupt flag for match channel 0 */
|
||||
#define TMR_IR_MR1I (1 << 1) /* Interrupt flag for match channel 1 */
|
||||
#define TMR_IR_MR2I (1 << 2) /* Interrupt flag for match channel 2 */
|
||||
#define TMR_IR_MR3I (1 << 3) /* Interrupt flag for match channel 3 */
|
||||
#define TMR_IR_CR0I (1 << 4) /* Interrupt flag for capture channel 0 event */
|
||||
#define TMR_IR_CR1I (1 << 5) /* Interrupt flag for capture channel 1 event */
|
||||
#define TMR_IR_CR2I (1 << 6) /* Interrupt flag for capture channel 2 event */
|
||||
#define TMR_IR_CR3I (1 << 7) /* Interrupt flag for capture channel 3 event */
|
||||
#define TMR_IR_ALLI (0xff) /* All timer interrupts */
|
||||
|
||||
/* Timer Control Register Bit Definitions (8-bits) */
|
||||
|
||||
#define TMR_CR_ENABLE (1 << 0) /* Counter Enable */
|
||||
#define TMR_CR_RESET (1 << 1) /* Countger Reset */
|
||||
|
||||
/* Timer Counter (32-bits, no bit fields) */
|
||||
|
||||
/* Timer Prescale Register Bit Definitions (32-bits, no bit fields) */
|
||||
|
||||
/* Timer Prescale Counter Register Bit Definitions */
|
||||
|
||||
/* Timer Match Control Register Bit Definitions (16-bit) */
|
||||
|
||||
#define TMR_MCR_MR0I (1 << 0) /* Enable Interrupt when MR0 matches TC */
|
||||
#define TMR_MCR_MR0R (1 << 1) /* Enable Reset of TC upon MR0 match */
|
||||
#define TMR_MCR_MR0S (1 << 2) /* Enable Stop of TC upon MR0 match */
|
||||
#define TMR_MCR_MR1I (1 << 3) /* Enable Interrupt when MR1 matches TC */
|
||||
#define TMR_MCR_MR1R (1 << 4) /* Enable Reset of TC upon MR1 match */
|
||||
#define TMR_MCR_MR1S (1 << 5) /* Enable Stop of TC upon MR1 match */
|
||||
#define TMR_MCR_MR2I (1 << 6) /* Enable Interrupt when MR2 matches TC */
|
||||
#define TMR_MCR_MR2R (1 << 7) /* Enable Reset of TC upon MR2 match */
|
||||
#define TMR_MCR_MR2S (1 << 8) /* Enable Stop of TC upon MR2 match */
|
||||
#define TMR_MCR_MR3I (1 << 9) /* Enable Interrupt when MR3 matches TC */
|
||||
#define TMR_MCR_MR3R (1 << 10) /* Enable Reset of TC upon MR3 match */
|
||||
#define TMR_MCR_MR3S (1 << 11) /* Enable Stop of TC upon MR3 match */
|
||||
|
||||
/* Timer Match Register 0/1/2/3 (32-bits, no bit fields) */
|
||||
|
||||
/* Timer Capture Control Register Bit Definitions */
|
||||
|
||||
#define TMR_CCR_CAP0RE (1 << 0) /* Enable Rising edge on CAPn.0 will load TC to CR0 */
|
||||
#define TMR_CCR_CAP0FE (1 << 1) /* Enable Falling edge on CAPn.0 will load TC to CR0 */
|
||||
#define TMR_CCR_CAP0I (1 << 2) /* Enable Interrupt on load of CR0 */
|
||||
#define TMR_CCR_CAP1RE (1 << 3) /* Enable Rising edge on CAPn.1 will load TC to CR1 */
|
||||
#define TMR_CCR_CAP1FE (1 << 4) /* Enable Falling edge on CAPn.1 will load TC to CR1 */
|
||||
#define TMR_CCR_CAP1I (1 << 5) /* Enable Interrupt on load of CR1 */
|
||||
//~ #define TMR_CCR_CAP2RE (1 << 6) /* Enable Rising edge on CAPn.2 will load TC to CR2 */
|
||||
//~ #define TMR_CCR_CAP2FE (1 << 7) /* Enable Falling edge on CAPn.2 will load TC to CR2 */
|
||||
//~ #define TMR_CCR_CAP2I (1 << 8) /* Enable Interrupt on load of CR2 */
|
||||
//~ #define TMR_CCR_CAP3RE (1 << 9) /* Enable Rising edge on CAPn.3 will load TC to CR3 */
|
||||
//~ #define TMR_CCR_CAP3FE (1 << 10) /* Enable Falling edge on CAPn.3 will load TC to CR3 */
|
||||
//~ #define TMR_CCR_CAP3I (1 << 11) /* Enable Interrupt on load of CR3 */
|
||||
|
||||
/* Timer Capture Register 0/1/2/3 (32-bits, no bit fields) */
|
||||
|
||||
/* Timer External Match Register Bit Definitions */
|
||||
|
||||
#define TMR_EMR_EM0 (1 << 0) /* External Match 0 */
|
||||
#define TMR_EMR_EM1 (1 << 1) /* External Match 1 */
|
||||
#define TMR_EMR_EM2 (1 << 2) /* External Match 2 */
|
||||
#define TMR_EMR_EM3 (1 << 3) /* External Match 3 */
|
||||
|
||||
#define TMR_EMR_EMC0(b) ((b) << 4) /* External match control 0 (see below) */
|
||||
#define TMR_EMR_EMC1(b) ((b) << 6) /* External match control 1 (see below) */
|
||||
#define TMR_EMR_EMC2(b) ((b) << 8) /* External match control 2 (see below) */
|
||||
#define TMR_EMR_EMC3(b) ((b) << 10) /* External match control 3 (see below) */
|
||||
|
||||
/* EMR External Match Control (EMCn) Field Falues */
|
||||
|
||||
#define TMR_EMR_MASK (3) /* Mask for all bits */
|
||||
#define TMR_EMR_NOOP (0) /* Do nothing */
|
||||
#define TMR_EMR_CLEAR (1) /* Clear corresponding EMn bit/output to 0 */
|
||||
#define TMR_EMR_SET (2) /* Set corresponding EMn bit/output to 1 */
|
||||
#define TMR_EMR_TOGGLE (3) /* Toggle corresponding EMn bit/output */
|
||||
|
||||
/* Timer Count Control Register Bit Definitions (8-bit) */
|
||||
|
||||
#define TMR_CTCR_MODE_MASK (3 << 0) /* Counter/Timer Mode */
|
||||
#define TMR_CTCR_PCLK (0 << 0) /* Rising edge of PCLK */
|
||||
#define TMR_CTCR_RISING (1 << 0) /* Rising edge of CAP input */
|
||||
#define TMR_CTDR_FALLING (2 << 0) /* Failing edge of CAP input */
|
||||
#define TMR_CTCR_BOTH (3 << 0) /* Both edges of CAP input */
|
||||
#define TMR_CTCR_INPUT_MASK (3 << 2) /* Counter Input Select */
|
||||
#define TMR_CTCR_CR0 (0 << 2) /* CAPn.0 */
|
||||
#define TMR_CTCR_CR1 (1 << 2) /* CAPn.1 */
|
||||
#define TMR_CTCR_CR2 (2 << 2) /* CAPn.2 */
|
||||
#define TMR_CTCR_CR3 (3 << 2) /* CAPn.3 */
|
||||
|
||||
/************************************************************************************
|
||||
* Public Types
|
||||
************************************************************************************/
|
||||
|
||||
/************************************************************************************
|
||||
* Inline Functions
|
||||
************************************************************************************/
|
||||
|
||||
/************************************************************************************
|
||||
* Public Function Prototypes
|
||||
************************************************************************************/
|
||||
|
||||
#endif /* __ARCH_ARM_SRC_LPC2378_LPC23XX_TIMER_H */
|
193
arch/arm/src/lpc2378/lpc23xx_timerisr.c
Executable file
193
arch/arm/src/lpc2378/lpc23xx_timerisr.c
Executable file
@ -0,0 +1,193 @@
|
||||
/****************************************************************************
|
||||
* arch/arm/src/lpc2378/lpc23xx_timerisr.c
|
||||
*
|
||||
* Copyright (C) 2010 Rommel Marcelo. All rights reserved.
|
||||
* Author: Rommel Marcelo
|
||||
*
|
||||
* This file is part of the NuttX RTOS and based on the lpc2148 port:
|
||||
*
|
||||
* 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.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Included Files
|
||||
****************************************************************************/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
#include <sys/types.h>
|
||||
#include <debug.h>
|
||||
#include <nuttx/arch.h>
|
||||
#include <arch/board/board.h>
|
||||
|
||||
#include "clock_internal.h"
|
||||
#include "internal.h"
|
||||
#include "up_arch.h"
|
||||
|
||||
#include "lpc23xx_scb.h"
|
||||
#include "lpc23xx_vic.h"
|
||||
#include "lpc23xx_timer.h"
|
||||
|
||||
|
||||
/****************************************************************************
|
||||
* Definitions
|
||||
****************************************************************************/
|
||||
/* T0_PCLKDIV valid values are 1,2,4 */
|
||||
#define T0_PCLK_DIV 1
|
||||
|
||||
/* PCKLSEL0 bits 3:2, 00=CCLK/4, 01=CCLK/1 , 10=CCLK/2 */
|
||||
|
||||
#ifdef T0_PCLK_DIV
|
||||
# if T0_PCLK_DIV == 1
|
||||
# define TIMER0_PCLKSEL (0x00000004)
|
||||
# elif T0_PCLK_DIV == 2
|
||||
# define TIMER0_PCLKSEL (0x00000008)
|
||||
# elif T0_PCLK_DIV == 4
|
||||
# define TIMER0_PCLKSEL (0x00000000)
|
||||
# endif
|
||||
#endif
|
||||
|
||||
#define T0_PCLKSEL_MASK (0x0000000C)
|
||||
|
||||
#define T0_TICKS_COUNT ( (CCLK / T0_PCLK_DIV ) / TICK_PER_SEC )
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
/****************************************************************************
|
||||
* Private Types
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Private Function Prototypes
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Global Functions
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Function: up_timerisr
|
||||
*
|
||||
* Description:
|
||||
* The timer ISR will perform a variety of services for
|
||||
* various portions of the systems.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
#ifdef CONFIG_VECTORED_INTERRUPTS
|
||||
int up_timerisr(uint32_t *regs)
|
||||
#else
|
||||
int up_timerisr(int irq, uint32_t *regs)
|
||||
#endif
|
||||
{
|
||||
static uint32_t tick;
|
||||
|
||||
/* Process timer interrupt */
|
||||
|
||||
sched_process_timer();
|
||||
|
||||
/* Clear the MR0 match interrupt */
|
||||
|
||||
tmr_putreg8(TMR_IR_MR0I, TMR_IR_OFFSET);
|
||||
|
||||
/* Reset the VIC as well */
|
||||
|
||||
#ifdef CONFIG_VECTORED_INTERRUPTS
|
||||
/* write any value to VICAddress to acknowledge the interrupt */
|
||||
vic_putreg(0, VIC_ADDRESS_OFFSET);
|
||||
#endif
|
||||
|
||||
if(tick++ > 100){
|
||||
tick =0;
|
||||
up_statledoff();
|
||||
}else up_statledon();
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
* Function: up_timerinit
|
||||
*
|
||||
* Description:
|
||||
* This function is called during start-up to initialize
|
||||
* the system timer interrupt.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
void up_timerinit(void)
|
||||
{
|
||||
uint16_t mcr;
|
||||
|
||||
/* Power up Timer0 */
|
||||
SCB_PCONP |= PCTIM0;
|
||||
|
||||
/* Timer0 clock input frequency = CCLK / TO_PCLKDIV */
|
||||
SCB_PCLKSEL0 = (SCB_PCLKSEL0 & ~T0_PCLKSEL_MASK) | TIMER0_PCLKSEL;
|
||||
|
||||
/* Clear all match and capture event interrupts */
|
||||
tmr_putreg8(TMR_IR_ALLI, TMR_IR_OFFSET);
|
||||
|
||||
/* Clear the timer counter */
|
||||
tmr_putreg32(0, TMR_TC_OFFSET);
|
||||
|
||||
/* No pre-scaler */
|
||||
tmr_putreg32(0, TMR_PR_OFFSET);
|
||||
tmr_putreg32(0, TMR_PC_OFFSET);
|
||||
|
||||
/* Set timer match registger to get a TICK_PER_SEC rate
|
||||
* See arch/board.h and sched/os_internal.h
|
||||
*/
|
||||
tmr_putreg32( T0_TICKS_COUNT, TMR_MR0_OFFSET ); /* 10ms Intterrupt */
|
||||
|
||||
/* Reset timer counter register and interrupt on match */
|
||||
mcr = tmr_getreg16(TMR_MCR_OFFSET);
|
||||
mcr &= ~TMR_MCR_MR1I;
|
||||
mcr |= (TMR_MCR_MR0I | TMR_MCR_MR0R);
|
||||
tmr_putreg16(mcr, TMR_MCR_OFFSET);//-- bit 0=1 -int on MR0, bit 1=1 - Reset on MR0
|
||||
|
||||
/* Enable counting */
|
||||
//~ tmr_putreg32(1, TMR_TCR_OFFSET);
|
||||
tmr_putreg8(TMR_CR_ENABLE, TMR_TCR_OFFSET);
|
||||
|
||||
/* Attach the timer interrupt vector */
|
||||
|
||||
#ifdef CONFIG_VECTORED_INTERRUPTS
|
||||
up_attach_vector(IRQ_SYSTIMER, PRIORITY_HIGHEST, (vic_vector_t)up_timerisr);
|
||||
#else
|
||||
(void)irq_attach(IRQ_SYSTIMER, (xcpt_t)up_timerisr);
|
||||
up_prioritize_irq(IRQ_SYSTIMER, PRIORITY_HIGHEST);
|
||||
#endif
|
||||
/* And enable the system timer interrupt */
|
||||
|
||||
up_enable_irq(IRQ_SYSTIMER);
|
||||
}
|
231
arch/arm/src/lpc2378/lpc23xx_uart.h
Executable file
231
arch/arm/src/lpc2378/lpc23xx_uart.h
Executable file
@ -0,0 +1,231 @@
|
||||
/************************************************************************************
|
||||
* arch/arm/src/lpc2378/lpc2378/uart.h
|
||||
*
|
||||
* Copyright (C) 2010 Rommel Marcelo. All rights reserved.
|
||||
* Author: Rommel Marcelo
|
||||
*
|
||||
* This file is part of the NuttX RTOS and based on the lpc2148 port:
|
||||
*
|
||||
* 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.
|
||||
*
|
||||
************************************************************************************/
|
||||
|
||||
#ifndef __ARCH_ARM_SRC_LPC2378_LPC23XX_UART_H
|
||||
#define __ARCH_ARM_SRC_LPC2378_LPC23XX_UART_H
|
||||
|
||||
/************************************************************************************
|
||||
* Included Files
|
||||
************************************************************************************/
|
||||
|
||||
#include <arch/board/board.h> /* For clock settings */
|
||||
|
||||
/************************************************************************************
|
||||
* Definitions
|
||||
************************************************************************************/
|
||||
/* Derive baud divisor setting from clock settings (see board.h) */
|
||||
//--F_in = 57 600 000 Hz U0DLM=0, U0DLL=25, DIVADDVAL=3, MULVAL=12, baudrate=115200, err = 0.000000 %
|
||||
//--F_in = 57 600 000 Hz U0DLM=1, U0DLL=119, DIVADDVAL=0, MULVAL=1, baudrate=9600, err = 0.000000 %
|
||||
/* Used only if CONFIG_UART_MULVAL is not defined */
|
||||
#define DIVADDVAL 0
|
||||
#define MULVAL 1
|
||||
#define DLMVAL 1
|
||||
#define DLLVAL 119
|
||||
|
||||
/* UARTx PCLK divider valid values are 1,2,4 */
|
||||
#define U0_PCLKDIV 1
|
||||
//~ #define U1_PCLKDIV 1
|
||||
#define U2_PCLKDIV 1
|
||||
//~ #define U3_PCLKDIV 1
|
||||
|
||||
|
||||
#define U0_PCLK (CCLK / U0_PCLKDIV)
|
||||
//~ #define U1_PCLK (CCLK / U1_PCLKDIV)
|
||||
#define U2_PCLK (CCLK / U2_PCLKDIV)
|
||||
//~ #define U3_PCLK (CCLK / U3_PCLKDIV)
|
||||
|
||||
#define U0_PCLKSEL_MASK (0x000000C0)
|
||||
#define U2_PCLKSEL_MASK (0x00030000)
|
||||
|
||||
/* PCKLSEL0 bits 7:6, 00=CCLK/4, 01=CCLK/1 , 10=CCLK/2 */
|
||||
#ifdef U0_PCLKDIV
|
||||
# if U0_PCLKDIV == 1
|
||||
# define U0_PCLKSEL (0x00000040)
|
||||
# elif U0_PCLKDIV == 2
|
||||
# define U0_PCLKSEL (0x00000080)
|
||||
# elif U0_PCLKDIV == 4
|
||||
# define U0_PCLKSEL (0x00000000)
|
||||
# endif
|
||||
#else
|
||||
# error "UART0 PCLK divider not set"
|
||||
#endif
|
||||
|
||||
/* PCKLSEL1 bits 17:16, 00=CCLK/4, 01=CCLK/1 , 10=CCLK/2 */
|
||||
#ifdef U2_PCLKDIV
|
||||
# if U2_PCLKDIV == 1
|
||||
# define U2_PCLKSEL (0x00010000)
|
||||
# elif U2_PCLKDIV == 2
|
||||
# define U2_PCLKSEL (0x00020000)
|
||||
# elif U2_PCLKDIV == 4
|
||||
# define U2_PCLKSEL (0x00000000)
|
||||
# endif
|
||||
#else
|
||||
# error "UART2 PCLK divider not set"
|
||||
#endif
|
||||
|
||||
|
||||
|
||||
|
||||
/* Universal Asynchronous Receiver Transmitter Base Addresses */
|
||||
#define UART0_BASE_ADDR 0xE000C000
|
||||
#define UART1_BASE_ADDR 0xE0010000
|
||||
#define UART2_BASE_ADDR 0xE0078000
|
||||
#define UART3_BASE_ADDR 0xE007C000
|
||||
|
||||
/* UART 0/1/2/3 Register Offsets */
|
||||
#define UART_RBR_OFFSET 0x00 /* R: Receive Buffer Register (DLAB=0) */
|
||||
#define UART_THR_OFFSET 0x00 /* W: Transmit Holding Register (DLAB=0) */
|
||||
#define UART_DLL_OFFSET 0x00 /* W: Divisor Latch Register (LSB, DLAB=1) */
|
||||
#define UART_IER_OFFSET 0x04 /* W: Interrupt Enable Register (DLAB=0) */
|
||||
#define UART_DLM_OFFSET 0x04 /* RW: Divisor Latch Register (MSB, DLAB=1) */
|
||||
#define UART_IIR_OFFSET 0x08 /* R: Interrupt ID Register */
|
||||
#define UART_FCR_OFFSET 0x08 /* W: FIFO Control Register */
|
||||
#define UART_LCR_OFFSET 0x0c /* RW: Line Control Register */
|
||||
#define UART_MCR_OFFSET 0x10 /* RW: Modem Control REgister (2146/6/8 UART1 Only) */
|
||||
#define UART_LSR_OFFSET 0x14 /* R: Scratch Pad Register */
|
||||
#define UART_MSR_OFFSET 0x18 /* RW: MODEM Status Register (2146/6/8 UART1 Only) */
|
||||
#define UART_SCR_OFFSET 0x1c /* RW: Line Status Register */
|
||||
#define UART_ACR_OFFSET 0x20 /* RW: Autobaud Control Register */
|
||||
#define UART_FDR_OFFSET 0x28 /* RW: Fractional Divider Register */
|
||||
#define UART_TER_OFFSET 0x30 /* RW: Transmit Enable Register */
|
||||
|
||||
/* PINSEL0 bit definitions for UART0/2 */
|
||||
|
||||
#define UART0_PINSEL 0x00000050 /* PINSEL0 value for UART0 */
|
||||
#define UART0_PINMASK 0x000000F0 /* PINSEL0 mask for UART0 */
|
||||
|
||||
#define UART1_TX_PINSEL 0x40000000 /* PINSEL0 value for UART1 Tx */
|
||||
#define UART1_TXPINMASK 0xC0000000 /* PINSEL0 mask for UART1 Tx */
|
||||
#define UART1_RX_PINSEL 0x00000001 /* PINSEL1 value for UART1 Rx */
|
||||
#define UART1_RX_PINMASK 0x00000003 /* PINSEL1 mask for UART1 Rx */
|
||||
#define UART1_MODEM_PINSEL 0x00001555 /* PINSEL1 mask for UART1 Modem Interface */
|
||||
#define UART1_CTS_PINMASK 0x00003FFF /* PINSEL1 mask for UART1 Modem Interface */
|
||||
//~ #define UART1_CTS_PINSEL 0x00000004 /* PINSEL1 mask for UART1 CTS */
|
||||
//~ #define UART1_CTS_PINMASK 0x0000000C /* PINSEL1 mask for UART1 CTS */
|
||||
//~ #define UART1_CTS_PINSEL 0x00000010 /* PINSEL1 mask for UART1 Rx */
|
||||
//~ #define UART1_CTS_PINMASK 0x00000030 /* PINSEL1 mask for UART1 Rx */
|
||||
#define UART2_PINSEL 0x00500000 /* PINSEL0 value for UART2 */
|
||||
#define UART2_PINMASK 0x00F00000 /* PINSEL0 mask for UART2 */
|
||||
|
||||
#define UART3_PINSEL 0x0F000000 /* PINSEL9 value for UART3 */
|
||||
#define UART3_PINMASK 0x0F000000 /* PINSEL9 mask for UART3 */
|
||||
|
||||
/* Interrupt Enable Register (IER) bit definitions */
|
||||
|
||||
#define IER_ERBFI (1 << 0) /* Enable receive data available int */
|
||||
#define IER_ETBEI (1 << 1) /* Enable THR empty Interrupt */
|
||||
#define IER_ELSI (1 << 2) /* Enable receive line status int */
|
||||
#define IER_EDSSI (1 << 3) /* Enable MODEM atatus interrupt (2146/6/8 UART1 Only) */
|
||||
#define IER_ALLIE 0x0f /* All interrupts */
|
||||
|
||||
/* Interrupt ID Register(IIR) bit definitions */
|
||||
|
||||
#define IIR_NO_INT (1 << 0) /* No interrupts pending */
|
||||
#define IIR_MS_INT (0 << 1) /* MODEM Status (UART1 only) */
|
||||
#define IIR_THRE_INT (1 << 1) /* Transmit Holding Register Empty */
|
||||
#define IIR_RDA_INT (2 << 1) /* Receive Data Available */
|
||||
#define IIR_RLS_INT (3 << 1) /* Receive Line Status */
|
||||
#define IIR_CTI_INT (6 << 1) /* Character Timeout Indicator */
|
||||
#define IIR_MASK 0x0e
|
||||
|
||||
/* FIFO Control Register (FCR) bit definitions */
|
||||
|
||||
#define FCR_FIFO_ENABLE (1 << 0) /* FIFO enable */
|
||||
#define FCR_RX_FIFO_RESET (1 << 1) /* Reset receive FIFO */
|
||||
#define FCR_TX_FIFO_RESET (1 << 2) /* Reset transmit FIFO */
|
||||
#define FCR_FIFO_TRIG1 (0 << 6) /* Trigger @1 character in FIFO */
|
||||
#define FCR_FIFO_TRIG4 (1 << 6) /* Trigger @4 characters in FIFO */
|
||||
#define FCR_FIFO_TRIG8 (2 << 6) /* Trigger @8 characters in FIFO */
|
||||
#define FCR_FIFO_TRIG14 (3 << 6) /* Trigger @14 characters in FIFO */
|
||||
|
||||
/* Line Control Register (LCR) bit definitions */
|
||||
|
||||
#define LCR_CHAR_5 (0 << 0) /* 5-bit character length */
|
||||
#define LCR_CHAR_6 (1 << 0) /* 6-bit character length */
|
||||
#define LCR_CHAR_7 (2 << 0) /* 7-bit character length */
|
||||
#define LCR_CHAR_8 (3 << 0) /* 8-bit character length */
|
||||
#define LCR_STOP_1 (0 << 2) /* 1 stop bit */
|
||||
#define LCR_STOP_2 (1 << 2) /* 2 stop bits */
|
||||
#define LCR_PAR_NONE (0 << 3) /* No parity */
|
||||
#define LCR_PAR_ODD (1 << 3) /* Odd parity */
|
||||
#define LCR_PAR_EVEN (3 << 3) /* Even parity */
|
||||
#define LCR_PAR_MARK (5 << 3) /* Mark "1" parity */
|
||||
#define LCR_PAR_SPACE (7 << 3) /* Space "0" parity */
|
||||
#define LCR_BREAK_ENABLE (1 << 6) /* Output BREAK */
|
||||
#define LCR_DLAB_ENABLE (1 << 7) /* Enable divisor latch access */
|
||||
|
||||
/* Modem Control Register (MCR) bit definitions */
|
||||
|
||||
#define MCR_DTR (1 << 0) /* Data terminal ready */
|
||||
#define MCR_RTS (1 << 1) /* Request to send */
|
||||
#define MCR_LB (1 << 4) /* Loopback */
|
||||
|
||||
/* Line Status Register (LSR) bit definitions */
|
||||
|
||||
#define LSR_RDR (1 << 0) /* Receive data ready */
|
||||
#define LSR_OE (1 << 1) /* Overrun error */
|
||||
#define LSR_PE (1 << 2) /* Parity error */
|
||||
#define LSR_FE (1 << 3) /* Framing error */
|
||||
#define LSR_BI (1 << 4) /* Break interrupt */
|
||||
#define LSR_THRE (1 << 5) /* THR empty */
|
||||
#define LSR_TEMT (1 << 6) /* Transmitter empty */
|
||||
#define LSR_RXFE (1 << 7) /* Error in receive FIFO */
|
||||
#define LSR_ERR_MASK 0x1e
|
||||
|
||||
/* Modem Status Register (MSR) bit definitions */
|
||||
|
||||
#define MSR_DCTS (1 << 0) /* Delta clear to send */
|
||||
#define MSR_DDSR (1 << 1) /* Delta data set ready */
|
||||
#define MSR_TERI (1 << 2) /* Trailing edge ring indicator */
|
||||
#define MSR_DDCD (1 << 3) /* Delta data carrier detect */
|
||||
#define MSR_CTS (1 << 4) /* Clear to send */
|
||||
#define MSR_DSR (1 << 5) /* Data set ready */
|
||||
#define MSR_RI (1 << 6) /* Ring indicator */
|
||||
#define MSR_DCD (1 << 7) /* Data carrier detect */
|
||||
|
||||
/************************************************************************************
|
||||
* Inline Functions
|
||||
************************************************************************************/
|
||||
|
||||
/************************************************************************************
|
||||
* Global Function Prototypes
|
||||
************************************************************************************/
|
||||
|
||||
#endif /* __ARCH_ARM_SRC_LPC2378_LPC23XX_UART_H */
|
76
arch/arm/src/lpc2378/lpc23xx_vic.h
Executable file
76
arch/arm/src/lpc2378/lpc23xx_vic.h
Executable file
@ -0,0 +1,76 @@
|
||||
/************************************************************************************
|
||||
* arch/arm/src/lpc2378/lpc23xx_vic.h
|
||||
*
|
||||
* Copyright (C) 2010 Rommel Marcelo. All rights reserved.
|
||||
* Author: Rommel Marcelo
|
||||
*
|
||||
* This file is part of the NuttX RTOS and based on the lpc2148 port:
|
||||
*
|
||||
* 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.
|
||||
*
|
||||
************************************************************************************/
|
||||
|
||||
#ifndef __ARCH_ARM_SRC_LPC2378_LPC23XX_VIC_H
|
||||
#define __ARCH_ARM_SRC_LPC2378_LPC23XX_VIC_H
|
||||
|
||||
/************************************************************************************
|
||||
* Included Files
|
||||
************************************************************************************/
|
||||
|
||||
/************************************************************************************
|
||||
* Definitions
|
||||
************************************************************************************/
|
||||
|
||||
/* All VIC registers are 32-bits wide */
|
||||
|
||||
#define vic_getreg(o) getreg32(LPC23XX_VIC_BASE + (o))
|
||||
#define vic_putreg(v,o) putreg32((v),LPC23XX_VIC_BASE + (o))
|
||||
|
||||
/* Vector Control Register bit definitions */
|
||||
|
||||
//~ #define LPC23XX_VECTPRIORITY_IRQMASK (0x0000001f)
|
||||
//~ #define VECTPRIORITY_IRQMASK (0x0000FFFF)
|
||||
//~ #define LPC23XX_VECTPRIORITY_IRQSHIFT (0)
|
||||
//~ #define LPC23XX_VECTPRIORITY_ENABLE (1 << 5)
|
||||
|
||||
/************************************************************************************
|
||||
* Public Types
|
||||
************************************************************************************/
|
||||
|
||||
/************************************************************************************
|
||||
* Inline Functions
|
||||
************************************************************************************/
|
||||
|
||||
/************************************************************************************
|
||||
* Public Function Prototypes
|
||||
************************************************************************************/
|
||||
|
||||
#endif /* __ARCH_ARM_SRC_LPC2378_LPC23XX_VIC_H */
|
Loading…
Reference in New Issue
Block a user