From be85acd0f71ce088b4e1584e6ce485015288f63c Mon Sep 17 00:00:00 2001 From: patacongo Date: Fri, 27 May 2011 15:26:52 +0000 Subject: Rename all lpc313x to lpc31xx git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@3644 42af7a65-404d-4744-a932-0658087f49c3 --- nuttx/ChangeLog | 4 +- nuttx/arch/arm/include/lpc313x/irq.h | 118 - nuttx/arch/arm/include/lpc31xx/irq.h | 118 + nuttx/arch/arm/src/lpc313x/Make.defs | 67 - nuttx/arch/arm/src/lpc313x/chip.h | 62 - nuttx/arch/arm/src/lpc313x/lpc313x_adc.h | 132 - nuttx/arch/arm/src/lpc313x/lpc313x_allocateheap.c | 206 -- nuttx/arch/arm/src/lpc313x/lpc313x_bcrndx.c | 100 - nuttx/arch/arm/src/lpc313x/lpc313x_boot.c | 397 --- nuttx/arch/arm/src/lpc313x/lpc313x_cgu.h | 1626 ------------- nuttx/arch/arm/src/lpc313x/lpc313x_cgudrvr.h | 819 ------- nuttx/arch/arm/src/lpc313x/lpc313x_clkdomain.c | 125 - nuttx/arch/arm/src/lpc313x/lpc313x_clkexten.c | 152 -- nuttx/arch/arm/src/lpc313x/lpc313x_clkfreq.c | 177 -- nuttx/arch/arm/src/lpc313x/lpc313x_clkinit.c | 298 --- nuttx/arch/arm/src/lpc313x/lpc313x_decodeirq.c | 137 -- nuttx/arch/arm/src/lpc313x/lpc313x_defclk.c | 119 - nuttx/arch/arm/src/lpc313x/lpc313x_dma.h | 423 ---- nuttx/arch/arm/src/lpc313x/lpc313x_esrndx.c | 134 -- nuttx/arch/arm/src/lpc313x/lpc313x_evntrtr.h | 264 -- nuttx/arch/arm/src/lpc313x/lpc313x_fdcndx.c | 127 - nuttx/arch/arm/src/lpc313x/lpc313x_fdivinit.c | 204 -- nuttx/arch/arm/src/lpc313x/lpc313x_freqin.c | 82 - nuttx/arch/arm/src/lpc313x/lpc313x_i2c.c | 608 ----- nuttx/arch/arm/src/lpc313x/lpc313x_i2c.h | 207 -- nuttx/arch/arm/src/lpc313x/lpc313x_i2s.h | 315 --- nuttx/arch/arm/src/lpc313x/lpc313x_intc.h | 198 -- nuttx/arch/arm/src/lpc313x/lpc313x_internal.h | 300 --- nuttx/arch/arm/src/lpc313x/lpc313x_ioconfig.h | 357 --- nuttx/arch/arm/src/lpc313x/lpc313x_irq.c | 218 -- nuttx/arch/arm/src/lpc313x/lpc313x_lcd.h | 161 -- nuttx/arch/arm/src/lpc313x/lpc313x_lowputc.c | 356 --- nuttx/arch/arm/src/lpc313x/lpc313x_mci.h | 270 --- nuttx/arch/arm/src/lpc313x/lpc313x_memorymap.h | 414 ---- nuttx/arch/arm/src/lpc313x/lpc313x_mpmc.h | 340 --- nuttx/arch/arm/src/lpc313x/lpc313x_nand.h | 378 --- nuttx/arch/arm/src/lpc313x/lpc313x_pcm.h | 174 -- nuttx/arch/arm/src/lpc313x/lpc313x_pllconfig.c | 267 --- nuttx/arch/arm/src/lpc313x/lpc313x_pwm.h | 97 - nuttx/arch/arm/src/lpc313x/lpc313x_resetclks.c | 151 -- nuttx/arch/arm/src/lpc313x/lpc313x_rng.h | 85 - nuttx/arch/arm/src/lpc313x/lpc313x_serial.c | 856 ------- nuttx/arch/arm/src/lpc313x/lpc313x_setfdiv.c | 135 -- nuttx/arch/arm/src/lpc313x/lpc313x_setfreqin.c | 119 - nuttx/arch/arm/src/lpc313x/lpc313x_softreset.c | 90 - nuttx/arch/arm/src/lpc313x/lpc313x_spi.c | 971 -------- nuttx/arch/arm/src/lpc313x/lpc313x_spi.h | 252 -- nuttx/arch/arm/src/lpc313x/lpc313x_syscreg.h | 611 ----- nuttx/arch/arm/src/lpc313x/lpc313x_timer.h | 119 - nuttx/arch/arm/src/lpc313x/lpc313x_timerisr.c | 162 -- nuttx/arch/arm/src/lpc313x/lpc313x_uart.h | 263 -- nuttx/arch/arm/src/lpc313x/lpc313x_usbdev.c | 2653 --------------------- nuttx/arch/arm/src/lpc313x/lpc313x_usbotg.h | 654 ----- nuttx/arch/arm/src/lpc313x/lpc313x_wdt.h | 130 - nuttx/arch/arm/src/lpc31xx/Make.defs | 67 + nuttx/arch/arm/src/lpc31xx/chip.h | 62 + nuttx/arch/arm/src/lpc31xx/lpc31_adc.h | 132 + nuttx/arch/arm/src/lpc31xx/lpc31_allocateheap.c | 206 ++ nuttx/arch/arm/src/lpc31xx/lpc31_bcrndx.c | 100 + nuttx/arch/arm/src/lpc31xx/lpc31_boot.c | 397 +++ nuttx/arch/arm/src/lpc31xx/lpc31_cgu.h | 1626 +++++++++++++ nuttx/arch/arm/src/lpc31xx/lpc31_cgudrvr.h | 819 +++++++ nuttx/arch/arm/src/lpc31xx/lpc31_clkdomain.c | 125 + nuttx/arch/arm/src/lpc31xx/lpc31_clkexten.c | 152 ++ nuttx/arch/arm/src/lpc31xx/lpc31_clkfreq.c | 177 ++ nuttx/arch/arm/src/lpc31xx/lpc31_clkinit.c | 298 +++ nuttx/arch/arm/src/lpc31xx/lpc31_decodeirq.c | 137 ++ nuttx/arch/arm/src/lpc31xx/lpc31_defclk.c | 119 + nuttx/arch/arm/src/lpc31xx/lpc31_dma.h | 423 ++++ nuttx/arch/arm/src/lpc31xx/lpc31_esrndx.c | 134 ++ nuttx/arch/arm/src/lpc31xx/lpc31_evntrtr.h | 264 ++ nuttx/arch/arm/src/lpc31xx/lpc31_fdcndx.c | 127 + nuttx/arch/arm/src/lpc31xx/lpc31_fdivinit.c | 204 ++ nuttx/arch/arm/src/lpc31xx/lpc31_freqin.c | 82 + nuttx/arch/arm/src/lpc31xx/lpc31_i2c.c | 608 +++++ nuttx/arch/arm/src/lpc31xx/lpc31_i2c.h | 207 ++ nuttx/arch/arm/src/lpc31xx/lpc31_i2s.h | 315 +++ nuttx/arch/arm/src/lpc31xx/lpc31_intc.h | 198 ++ nuttx/arch/arm/src/lpc31xx/lpc31_internal.h | 300 +++ nuttx/arch/arm/src/lpc31xx/lpc31_ioconfig.h | 357 +++ nuttx/arch/arm/src/lpc31xx/lpc31_irq.c | 218 ++ nuttx/arch/arm/src/lpc31xx/lpc31_lcd.h | 161 ++ nuttx/arch/arm/src/lpc31xx/lpc31_lowputc.c | 356 +++ nuttx/arch/arm/src/lpc31xx/lpc31_mci.h | 270 +++ nuttx/arch/arm/src/lpc31xx/lpc31_memorymap.h | 414 ++++ nuttx/arch/arm/src/lpc31xx/lpc31_mpmc.h | 340 +++ nuttx/arch/arm/src/lpc31xx/lpc31_nand.h | 378 +++ nuttx/arch/arm/src/lpc31xx/lpc31_pcm.h | 174 ++ nuttx/arch/arm/src/lpc31xx/lpc31_pllconfig.c | 267 +++ nuttx/arch/arm/src/lpc31xx/lpc31_pwm.h | 97 + nuttx/arch/arm/src/lpc31xx/lpc31_resetclks.c | 151 ++ nuttx/arch/arm/src/lpc31xx/lpc31_rng.h | 85 + nuttx/arch/arm/src/lpc31xx/lpc31_serial.c | 856 +++++++ nuttx/arch/arm/src/lpc31xx/lpc31_setfdiv.c | 135 ++ nuttx/arch/arm/src/lpc31xx/lpc31_setfreqin.c | 119 + nuttx/arch/arm/src/lpc31xx/lpc31_softreset.c | 90 + nuttx/arch/arm/src/lpc31xx/lpc31_spi.c | 971 ++++++++ nuttx/arch/arm/src/lpc31xx/lpc31_spi.h | 252 ++ nuttx/arch/arm/src/lpc31xx/lpc31_syscreg.h | 611 +++++ nuttx/arch/arm/src/lpc31xx/lpc31_timer.h | 119 + nuttx/arch/arm/src/lpc31xx/lpc31_timerisr.c | 162 ++ nuttx/arch/arm/src/lpc31xx/lpc31_uart.h | 263 ++ nuttx/arch/arm/src/lpc31xx/lpc31_usbdev.c | 2653 +++++++++++++++++++++ nuttx/arch/arm/src/lpc31xx/lpc31_usbotg.h | 654 +++++ nuttx/arch/arm/src/lpc31xx/lpc31_wdt.h | 130 + nuttx/configs/ea3131/README.txt | 40 +- nuttx/configs/ea3131/include/board.h | 8 +- nuttx/configs/ea3131/include/board_memorymap.h | 58 +- nuttx/configs/ea3131/locked/mklocked.sh | 2 +- nuttx/configs/ea3131/nsh/Make.defs | 10 +- nuttx/configs/ea3131/nsh/defconfig | 84 +- nuttx/configs/ea3131/nsh/ld.script | 2 +- nuttx/configs/ea3131/ostest/Make.defs | 10 +- nuttx/configs/ea3131/ostest/defconfig | 84 +- nuttx/configs/ea3131/ostest/ld.script | 2 +- nuttx/configs/ea3131/pgnsh/Make.defs | 10 +- nuttx/configs/ea3131/pgnsh/defconfig | 84 +- nuttx/configs/ea3131/pgnsh/ld.script | 2 +- nuttx/configs/ea3131/src/Makefile | 4 +- nuttx/configs/ea3131/src/ea3131_internal.h | 254 +- nuttx/configs/ea3131/src/up_boot.c | 238 +- nuttx/configs/ea3131/src/up_clkinit.c | 6 +- nuttx/configs/ea3131/src/up_fillpage.c | 28 +- nuttx/configs/ea3131/src/up_leds.c | 2 +- nuttx/configs/ea3131/src/up_mem.c | 96 +- nuttx/configs/ea3131/src/up_nsh.c | 11 +- nuttx/configs/ea3131/src/up_spi.c | 30 +- nuttx/configs/ea3131/tools/armusbocd.cfg | 68 +- nuttx/configs/ea3131/tools/lpchdr.c | 594 ++--- nuttx/configs/ea3131/tools/lpchdr.h | 210 +- nuttx/configs/ea3131/usbserial/Make.defs | 10 +- nuttx/configs/ea3131/usbserial/defconfig | 84 +- nuttx/configs/ea3131/usbserial/ld.script | 2 +- nuttx/configs/ea3131/usbstorage/Make.defs | 10 +- nuttx/configs/ea3131/usbstorage/defconfig | 84 +- nuttx/configs/ea3131/usbstorage/ld.script | 2 +- 136 files changed, 18748 insertions(+), 18745 deletions(-) delete mode 100755 nuttx/arch/arm/include/lpc313x/irq.h create mode 100755 nuttx/arch/arm/include/lpc31xx/irq.h delete mode 100755 nuttx/arch/arm/src/lpc313x/Make.defs delete mode 100755 nuttx/arch/arm/src/lpc313x/chip.h delete mode 100755 nuttx/arch/arm/src/lpc313x/lpc313x_adc.h delete mode 100755 nuttx/arch/arm/src/lpc313x/lpc313x_allocateheap.c delete mode 100755 nuttx/arch/arm/src/lpc313x/lpc313x_bcrndx.c delete mode 100755 nuttx/arch/arm/src/lpc313x/lpc313x_boot.c delete mode 100755 nuttx/arch/arm/src/lpc313x/lpc313x_cgu.h delete mode 100755 nuttx/arch/arm/src/lpc313x/lpc313x_cgudrvr.h delete mode 100755 nuttx/arch/arm/src/lpc313x/lpc313x_clkdomain.c delete mode 100755 nuttx/arch/arm/src/lpc313x/lpc313x_clkexten.c delete mode 100755 nuttx/arch/arm/src/lpc313x/lpc313x_clkfreq.c delete mode 100755 nuttx/arch/arm/src/lpc313x/lpc313x_clkinit.c delete mode 100755 nuttx/arch/arm/src/lpc313x/lpc313x_decodeirq.c delete mode 100755 nuttx/arch/arm/src/lpc313x/lpc313x_defclk.c delete mode 100755 nuttx/arch/arm/src/lpc313x/lpc313x_dma.h delete mode 100755 nuttx/arch/arm/src/lpc313x/lpc313x_esrndx.c delete mode 100755 nuttx/arch/arm/src/lpc313x/lpc313x_evntrtr.h delete mode 100755 nuttx/arch/arm/src/lpc313x/lpc313x_fdcndx.c delete mode 100755 nuttx/arch/arm/src/lpc313x/lpc313x_fdivinit.c delete mode 100755 nuttx/arch/arm/src/lpc313x/lpc313x_freqin.c delete mode 100644 nuttx/arch/arm/src/lpc313x/lpc313x_i2c.c delete mode 100755 nuttx/arch/arm/src/lpc313x/lpc313x_i2c.h delete mode 100755 nuttx/arch/arm/src/lpc313x/lpc313x_i2s.h delete mode 100755 nuttx/arch/arm/src/lpc313x/lpc313x_intc.h delete mode 100755 nuttx/arch/arm/src/lpc313x/lpc313x_internal.h delete mode 100755 nuttx/arch/arm/src/lpc313x/lpc313x_ioconfig.h delete mode 100755 nuttx/arch/arm/src/lpc313x/lpc313x_irq.c delete mode 100755 nuttx/arch/arm/src/lpc313x/lpc313x_lcd.h delete mode 100755 nuttx/arch/arm/src/lpc313x/lpc313x_lowputc.c delete mode 100755 nuttx/arch/arm/src/lpc313x/lpc313x_mci.h delete mode 100755 nuttx/arch/arm/src/lpc313x/lpc313x_memorymap.h delete mode 100755 nuttx/arch/arm/src/lpc313x/lpc313x_mpmc.h delete mode 100755 nuttx/arch/arm/src/lpc313x/lpc313x_nand.h delete mode 100755 nuttx/arch/arm/src/lpc313x/lpc313x_pcm.h delete mode 100755 nuttx/arch/arm/src/lpc313x/lpc313x_pllconfig.c delete mode 100755 nuttx/arch/arm/src/lpc313x/lpc313x_pwm.h delete mode 100755 nuttx/arch/arm/src/lpc313x/lpc313x_resetclks.c delete mode 100755 nuttx/arch/arm/src/lpc313x/lpc313x_rng.h delete mode 100755 nuttx/arch/arm/src/lpc313x/lpc313x_serial.c delete mode 100755 nuttx/arch/arm/src/lpc313x/lpc313x_setfdiv.c delete mode 100755 nuttx/arch/arm/src/lpc313x/lpc313x_setfreqin.c delete mode 100755 nuttx/arch/arm/src/lpc313x/lpc313x_softreset.c delete mode 100644 nuttx/arch/arm/src/lpc313x/lpc313x_spi.c delete mode 100755 nuttx/arch/arm/src/lpc313x/lpc313x_spi.h delete mode 100755 nuttx/arch/arm/src/lpc313x/lpc313x_syscreg.h delete mode 100755 nuttx/arch/arm/src/lpc313x/lpc313x_timer.h delete mode 100755 nuttx/arch/arm/src/lpc313x/lpc313x_timerisr.c delete mode 100755 nuttx/arch/arm/src/lpc313x/lpc313x_uart.h delete mode 100755 nuttx/arch/arm/src/lpc313x/lpc313x_usbdev.c delete mode 100755 nuttx/arch/arm/src/lpc313x/lpc313x_usbotg.h delete mode 100755 nuttx/arch/arm/src/lpc313x/lpc313x_wdt.h create mode 100755 nuttx/arch/arm/src/lpc31xx/Make.defs create mode 100755 nuttx/arch/arm/src/lpc31xx/chip.h create mode 100755 nuttx/arch/arm/src/lpc31xx/lpc31_adc.h create mode 100755 nuttx/arch/arm/src/lpc31xx/lpc31_allocateheap.c create mode 100755 nuttx/arch/arm/src/lpc31xx/lpc31_bcrndx.c create mode 100755 nuttx/arch/arm/src/lpc31xx/lpc31_boot.c create mode 100755 nuttx/arch/arm/src/lpc31xx/lpc31_cgu.h create mode 100755 nuttx/arch/arm/src/lpc31xx/lpc31_cgudrvr.h create mode 100755 nuttx/arch/arm/src/lpc31xx/lpc31_clkdomain.c create mode 100755 nuttx/arch/arm/src/lpc31xx/lpc31_clkexten.c create mode 100755 nuttx/arch/arm/src/lpc31xx/lpc31_clkfreq.c create mode 100755 nuttx/arch/arm/src/lpc31xx/lpc31_clkinit.c create mode 100755 nuttx/arch/arm/src/lpc31xx/lpc31_decodeirq.c create mode 100755 nuttx/arch/arm/src/lpc31xx/lpc31_defclk.c create mode 100755 nuttx/arch/arm/src/lpc31xx/lpc31_dma.h create mode 100755 nuttx/arch/arm/src/lpc31xx/lpc31_esrndx.c create mode 100755 nuttx/arch/arm/src/lpc31xx/lpc31_evntrtr.h create mode 100755 nuttx/arch/arm/src/lpc31xx/lpc31_fdcndx.c create mode 100755 nuttx/arch/arm/src/lpc31xx/lpc31_fdivinit.c create mode 100755 nuttx/arch/arm/src/lpc31xx/lpc31_freqin.c create mode 100644 nuttx/arch/arm/src/lpc31xx/lpc31_i2c.c create mode 100755 nuttx/arch/arm/src/lpc31xx/lpc31_i2c.h create mode 100755 nuttx/arch/arm/src/lpc31xx/lpc31_i2s.h create mode 100755 nuttx/arch/arm/src/lpc31xx/lpc31_intc.h create mode 100755 nuttx/arch/arm/src/lpc31xx/lpc31_internal.h create mode 100755 nuttx/arch/arm/src/lpc31xx/lpc31_ioconfig.h create mode 100755 nuttx/arch/arm/src/lpc31xx/lpc31_irq.c create mode 100755 nuttx/arch/arm/src/lpc31xx/lpc31_lcd.h create mode 100755 nuttx/arch/arm/src/lpc31xx/lpc31_lowputc.c create mode 100755 nuttx/arch/arm/src/lpc31xx/lpc31_mci.h create mode 100755 nuttx/arch/arm/src/lpc31xx/lpc31_memorymap.h create mode 100755 nuttx/arch/arm/src/lpc31xx/lpc31_mpmc.h create mode 100755 nuttx/arch/arm/src/lpc31xx/lpc31_nand.h create mode 100755 nuttx/arch/arm/src/lpc31xx/lpc31_pcm.h create mode 100755 nuttx/arch/arm/src/lpc31xx/lpc31_pllconfig.c create mode 100755 nuttx/arch/arm/src/lpc31xx/lpc31_pwm.h create mode 100755 nuttx/arch/arm/src/lpc31xx/lpc31_resetclks.c create mode 100755 nuttx/arch/arm/src/lpc31xx/lpc31_rng.h create mode 100755 nuttx/arch/arm/src/lpc31xx/lpc31_serial.c create mode 100755 nuttx/arch/arm/src/lpc31xx/lpc31_setfdiv.c create mode 100755 nuttx/arch/arm/src/lpc31xx/lpc31_setfreqin.c create mode 100755 nuttx/arch/arm/src/lpc31xx/lpc31_softreset.c create mode 100644 nuttx/arch/arm/src/lpc31xx/lpc31_spi.c create mode 100755 nuttx/arch/arm/src/lpc31xx/lpc31_spi.h create mode 100755 nuttx/arch/arm/src/lpc31xx/lpc31_syscreg.h create mode 100755 nuttx/arch/arm/src/lpc31xx/lpc31_timer.h create mode 100755 nuttx/arch/arm/src/lpc31xx/lpc31_timerisr.c create mode 100755 nuttx/arch/arm/src/lpc31xx/lpc31_uart.h create mode 100755 nuttx/arch/arm/src/lpc31xx/lpc31_usbdev.c create mode 100755 nuttx/arch/arm/src/lpc31xx/lpc31_usbotg.h create mode 100755 nuttx/arch/arm/src/lpc31xx/lpc31_wdt.h (limited to 'nuttx') diff --git a/nuttx/ChangeLog b/nuttx/ChangeLog index d43911d17..76f4f2c97 100644 --- a/nuttx/ChangeLog +++ b/nuttx/ChangeLog @@ -1771,4 +1771,6 @@ * drivers/net/e1000.c/h: A PCI-based E1000 ethernet driver submitted by Yu Qiang. * lib/net/lib_inetaddr.c: An implementatino of the inet_addr() function - submitted y Yu Qiang. \ No newline at end of file + submitted y Yu Qiang. + * arch/arm/src/lpc31xx and arch/arm/include/lpc31xx: Renamed from lpc313x + to make name space for other famiy members. diff --git a/nuttx/arch/arm/include/lpc313x/irq.h b/nuttx/arch/arm/include/lpc313x/irq.h deleted file mode 100755 index d3879e1d2..000000000 --- a/nuttx/arch/arm/include/lpc313x/irq.h +++ /dev/null @@ -1,118 +0,0 @@ -/**************************************************************************** - * arch/arm/include/lpc313x/irq.h - * - * Copyright (C) 2009-2010 Gregory Nutt. All rights reserved. - * Author: Gregory Nutt - * - * 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 should never be included directed but, rather, - * only indirectly through nuttx/irq.h - */ - -#ifndef __ARCH_ARM_INCLUDE_LPC313X_IRQ_H -#define __ARCH_ARM_INCLUDE_LPC313X_IRQ_H - -/**************************************************************************** - * Included Files - ****************************************************************************/ - -/**************************************************************************** - * Definitions - ****************************************************************************/ - -/* LPC313X Interrupts */ - - /* IRQ0: Reserved */ -#define LPC313X_IRQ_IRQ0 0 /* IRQ1: Event router cascaded IRQ0 */ -#define LPC313X_IRQ_IRQ1 1 /* IRQ2: Event router cascaded IRQ1 */ -#define LPC313X_IRQ_IRQ2 2 /* IRQ3: Event router cascaded IRQ2 */ -#define LPC313X_IRQ_IRQ3 3 /* IRQ4: Event router cascaded IRQ3 */ -#define LPC313X_IRQ_TMR0 4 /* IRQ5: Timer 0 Interrupt */ -#define LPC313X_IRQ_TMR1 5 /* IRQ6: Timer 1 Interrupt */ -#define LPC313X_IRQ_TMR2 6 /* IRQ7: Timer 2 Interrupt */ -#define LPC313X_IRQ_TMR3 7 /* IRQ8: Timer 3 Interrupt */ -#define LPC313X_IRQ_ADC 8 /* IRQ9: ADC 10-bit */ -#define LPC313X_IRQ_UART 9 /* IRQ10: UART */ -#define LPC313X_IRQ_I2C0 10 /* IRQ11: I2C0 */ -#define LPC313X_IRQ_I2C1 11 /* IRQ12: I2C1 */ -#define LPC313X_IRQ_I2STX0 12 /* IRQ13: I2S0 Transmit */ -#define LPC313X_IRQ_I2STX1 13 /* IRQ14: I2S1 Transmit */ -#define LPC313X_IRQ_I2SRX0 14 /* IRQ15: I2S0 Receive */ -#define LPC313X_IRQ_I2SRX1 15 /* IRQ16: I2S1 Receive */ - /* IRQ17: Reserved */ -#define LPC313X_IRQ_LCD 17 /* IRQ18: LCD Interface */ -#define LPC313X_IRQ_SPISMS 18 /* IRQ19: SPI SMS */ -#define LPC313X_IRQ_SPITX 19 /* IRQ20: SPI Transmit */ -#define LPC313X_IRQ_SPIRX 20 /* IRQ21: SPI Receive */ -#define LPC313X_IRQ_SPIOVF 21 /* IRQ22: SPI Overflow */ -#define LPC313X_IRQ_SPI 22 /* IRQ23: SPI */ -#define LPC313X_IRQ_DMA 23 /* IRQ24: DMA */ -#define LPC313X_IRQ_NAND 24 /* IRQ25: NAND FLASH Controller */ -#define LPC313X_IRQ_MCI 25 /* IRQ26: MCI */ -#define LPC313X_IRQ_USBOTG 26 /* IRQ27: USB OTG */ -#define LPC313X_IRQ_ISRAM0 27 /* IRQ28: ISRAM0 MRC Finished */ -#define LPC313X_IRQ_ISRAM1 28 /* IRQ29: ISRAM1 MRC Finished */ - -#define LPC313X_IRQ_SYSTIMER LPC313X_IRQ_TMR0 -#define NR_IRQS (LPC313X_IRQ_ISRAM1+1) - -/**************************************************************************** - * Public Types - ****************************************************************************/ - -/**************************************************************************** - * Inline functions - ****************************************************************************/ - -/**************************************************************************** - * Public Variables - ****************************************************************************/ - -/**************************************************************************** - * Public Function Prototypes - ****************************************************************************/ - -#ifndef __ASSEMBLY__ -#ifdef __cplusplus -#define EXTERN extern "C" -extern "C" { -#else -#define EXTERN extern -#endif - -#undef EXTERN -#ifdef __cplusplus -} -#endif -#endif - -#endif /* __ARCH_ARM_INCLUDE_LPC313X_IRQ_H */ - diff --git a/nuttx/arch/arm/include/lpc31xx/irq.h b/nuttx/arch/arm/include/lpc31xx/irq.h new file mode 100755 index 000000000..7e11025bb --- /dev/null +++ b/nuttx/arch/arm/include/lpc31xx/irq.h @@ -0,0 +1,118 @@ +/**************************************************************************** + * arch/arm/include/lpc31xx/irq.h + * + * Copyright (C) 2009-2011 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * 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 should never be included directed but, rather, + * only indirectly through nuttx/irq.h + */ + +#ifndef __ARCH_ARM_INCLUDE_LPC31XX_IRQ_H +#define __ARCH_ARM_INCLUDE_LPC31XX_IRQ_H + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +/**************************************************************************** + * Definitions + ****************************************************************************/ + +/* LPC31XX Interrupts */ + + /* IRQ0: Reserved */ +#define LPC31_IRQ_IRQ0 0 /* IRQ1: Event router cascaded IRQ0 */ +#define LPC31_IRQ_IRQ1 1 /* IRQ2: Event router cascaded IRQ1 */ +#define LPC31_IRQ_IRQ2 2 /* IRQ3: Event router cascaded IRQ2 */ +#define LPC31_IRQ_IRQ3 3 /* IRQ4: Event router cascaded IRQ3 */ +#define LPC31_IRQ_TMR0 4 /* IRQ5: Timer 0 Interrupt */ +#define LPC31_IRQ_TMR1 5 /* IRQ6: Timer 1 Interrupt */ +#define LPC31_IRQ_TMR2 6 /* IRQ7: Timer 2 Interrupt */ +#define LPC31_IRQ_TMR3 7 /* IRQ8: Timer 3 Interrupt */ +#define LPC31_IRQ_ADC 8 /* IRQ9: ADC 10-bit */ +#define LPC31_IRQ_UART 9 /* IRQ10: UART */ +#define LPC31_IRQ_I2C0 10 /* IRQ11: I2C0 */ +#define LPC31_IRQ_I2C1 11 /* IRQ12: I2C1 */ +#define LPC31_IRQ_I2STX0 12 /* IRQ13: I2S0 Transmit */ +#define LPC31_IRQ_I2STX1 13 /* IRQ14: I2S1 Transmit */ +#define LPC31_IRQ_I2SRX0 14 /* IRQ15: I2S0 Receive */ +#define LPC31_IRQ_I2SRX1 15 /* IRQ16: I2S1 Receive */ + /* IRQ17: Reserved */ +#define LPC31_IRQ_LCD 17 /* IRQ18: LCD Interface */ +#define LPC31_IRQ_SPISMS 18 /* IRQ19: SPI SMS */ +#define LPC31_IRQ_SPITX 19 /* IRQ20: SPI Transmit */ +#define LPC31_IRQ_SPIRX 20 /* IRQ21: SPI Receive */ +#define LPC31_IRQ_SPIOVF 21 /* IRQ22: SPI Overflow */ +#define LPC31_IRQ_SPI 22 /* IRQ23: SPI */ +#define LPC31_IRQ_DMA 23 /* IRQ24: DMA */ +#define LPC31_IRQ_NAND 24 /* IRQ25: NAND FLASH Controller */ +#define LPC31_IRQ_MCI 25 /* IRQ26: MCI */ +#define LPC31_IRQ_USBOTG 26 /* IRQ27: USB OTG */ +#define LPC31_IRQ_ISRAM0 27 /* IRQ28: ISRAM0 MRC Finished */ +#define LPC31_IRQ_ISRAM1 28 /* IRQ29: ISRAM1 MRC Finished */ + +#define LPC31_IRQ_SYSTIMER LPC31_IRQ_TMR0 +#define NR_IRQS (LPC31_IRQ_ISRAM1+1) + +/**************************************************************************** + * Public Types + ****************************************************************************/ + +/**************************************************************************** + * Inline functions + ****************************************************************************/ + +/**************************************************************************** + * Public Variables + ****************************************************************************/ + +/**************************************************************************** + * Public Function Prototypes + ****************************************************************************/ + +#ifndef __ASSEMBLY__ +#ifdef __cplusplus +#define EXTERN extern "C" +extern "C" { +#else +#define EXTERN extern +#endif + +#undef EXTERN +#ifdef __cplusplus +} +#endif +#endif + +#endif /* __ARCH_ARM_INCLUDE_LPC31XX_IRQ_H */ + diff --git a/nuttx/arch/arm/src/lpc313x/Make.defs b/nuttx/arch/arm/src/lpc313x/Make.defs deleted file mode 100755 index 464c5bf31..000000000 --- a/nuttx/arch/arm/src/lpc313x/Make.defs +++ /dev/null @@ -1,67 +0,0 @@ -############################################################################ -# arch/arm/lpc313x/Make.defs -# -# Copyright (C) 2009-2010 Gregory Nutt. All rights reserved. -# Author: Gregory Nutt -# -# 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 Gregory Nutt 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 = up_head.S - -CMN_ASRCS = up_cache.S up_fullcontextrestore.S up_saveusercontext.S \ - up_vectors.S up_vectoraddrexcptn.S up_vectortab.S -CMN_CSRCS = 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_modifyreg8.c up_modifyreg16.c up_modifyreg32.c \ - up_prefetchabort.c up_releasepending.c up_releasestack.c \ - up_reprioritizertr.c up_schedulesigaction.c \ - up_sigdeliver.c up_syscall.c up_unblocktask.c \ - up_undefinedinsn.c up_usestack.c - -ifeq ($(CONFIG_PAGING),y) -CMN_CSRCS += up_pginitialize.c up_checkmapping.c up_allocpage.c up_va2pte.c -endif - -CGU_ASRCS = -CGU_CSRCS = lpc313x_bcrndx.c lpc313x_clkdomain.c lpc313x_clkexten.c \ - lpc313x_clkfreq.c lpc313x_clkinit.c lpc313x_defclk.c \ - lpc313x_esrndx.c lpc313x_fdcndx.c lpc313x_fdivinit.c \ - lpc313x_freqin.c lpc313x_pllconfig.c lpc313x_resetclks.c \ - lpc313x_setfreqin.c lpc313x_setfdiv.c lpc313x_softreset.c - -CHIP_ASRCS = $(CGU_ASRCS) -CHIP_CSRCS = lpc313x_allocateheap.c lpc313x_boot.c lpc313x_decodeirq.c \ - lpc313x_irq.c lpc313x_lowputc.c lpc313x_serial.c lpc313x_i2c.c \ - lpc313x_spi.c lpc313x_timerisr.c $(CGU_CSRCS) - -ifeq ($(CONFIG_USBDEV),y) -CHIP_CSRCS += lpc313x_usbdev.c -endif diff --git a/nuttx/arch/arm/src/lpc313x/chip.h b/nuttx/arch/arm/src/lpc313x/chip.h deleted file mode 100755 index 35cf83eaa..000000000 --- a/nuttx/arch/arm/src/lpc313x/chip.h +++ /dev/null @@ -1,62 +0,0 @@ -/************************************************************************************ - * arch/arm/src/lpc313x/chip.h - * - * Copyright (C) 2009 Gregory Nutt. All rights reserved. - * Author: Gregory Nutt - * - * 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_LPC313X_CHIP_H -#define __ARCH_ARM_SRC_LPC313X_CHIP_H - -/************************************************************************************ - * Included Files - ************************************************************************************/ - -#include -#include "lpc313x_memorymap.h" - -/************************************************************************************ - * Pre-processor Definitions - ************************************************************************************/ - -/************************************************************************************ - * Public Types - ************************************************************************************/ - -/************************************************************************************ - * Public Data - ************************************************************************************/ - -/************************************************************************************ - * Public Functions - ************************************************************************************/ - -#endif /* __ARCH_ARM_SRC_LPC313X_CHIP_H */ diff --git a/nuttx/arch/arm/src/lpc313x/lpc313x_adc.h b/nuttx/arch/arm/src/lpc313x/lpc313x_adc.h deleted file mode 100755 index 4cbbbee10..000000000 --- a/nuttx/arch/arm/src/lpc313x/lpc313x_adc.h +++ /dev/null @@ -1,132 +0,0 @@ -/************************************************************************************************ - * arch/arm/src/lpc313x/lpc313x_adc.h - * - * Copyright (C) 2009-2010 Gregory Nutt. All rights reserved. - * Author: Gregory Nutt - * - * 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_LPC313X_ADC_H -#define __ARCH_ARM_SRC_LPC313X_ADC_H - -/************************************************************************************************ - * Included Files - ************************************************************************************************/ - -#include -#include "lpc313x_memorymap.h" - -/************************************************************************************************ - * Pre-processor Definitions - ************************************************************************************************/ - -/* ADC register base address offset into the APB0 domain ****************************************/ - -#define LPC313X_ADC_VBASE (LPC313X_APB0_VADDR+LPC313X_APB0_ADC_OFFSET) -#define LPC313X_ADC_PBASE (LPC313X_APB0_PADDR+LPC313X_APB0_ADC_OFFSET) - -/* ADC register offsets (with respect to the ADC base) ******************************************/ - -#define LPC313X_ADC_R0_OFFSET 0x000 /* Data for analog input channel 0 */ -#define LPC313X_ADC_R1_OFFSET 0x004 /* Data for analog input channel 1 */ -#define LPC313X_ADC_R2_OFFSET 0x008 /* Data for analog input channel 2 */ -#define LPC313X_ADC_R3_OFFSET 0x00c /* Data for analog input channel 3 */ - /* 0x010-0x01c: Reserved */ -#define LPC313X_ADC_CON_OFFSET 0x020 /* ADC control register */ -#define LPC313X_ADC_CSEL_OFFSET 0x024 /* Configure and select analog input channels */ -#define LPC313X_ADC_INTEN_OFFSET 0x028 /* Enable ADC interrupts */ -#define LPC313X_ADC_INTST_OFFSET 0x02C /* ADC interrupt status */ -#define LPC313X_ADC_INTCLR_OFFSET 0x030 /* Clear ADC interrupt status */ - /* 0x034-: Reserved */ - -/* ADC register (virtual) addresses *************************************************************/ - -#define LPC313X_ADC_R0 (LPC313X_ADC_VBASE+LPC313X_ADC_R0_OFFSET) -#define LPC313X_ADC_R1 (LPC313X_ADC_VBASE+LPC313X_ADC_R1_OFFSET) -#define LPC313X_ADC_R2 (LPC313X_ADC_VBASE+LPC313X_ADC_R2_OFFSET) -#define LPC313X_ADC_R3 (LPC313X_ADC_VBASE+LPC313X_ADC_R3_OFFSET) -#define LPC313X_ADC_CON (LPC313X_ADC_VBASE+LPC313X_ADC_CON_OFFSET) -#define LPC313X_ADC_CSEL (LPC313X_ADC_VBASE+LPC313X_ADC_CSEL_OFFSET) -#define LPC313X_ADC_INTEN (LPC313X_ADC_VBASE+LPC313X_ADC_INTEN_OFFSET) -#define LPC313X_ADC_INTST (LPC313X_ADC_VBASE+LPC313X_ADC_INTST_OFFSET) -#define LPC313X_ADC_INTCLR (LPC313X_ADC_VBASE+LPC313X_ADC_INTCLR_OFFSET) - -/* ADC register bit definitions *****************************************************************/ - -/* ADC_Rx (ADC_R0, address 0x13002000; ADC_R1, address 0x13002004, ADC_R2, address 0x13002008; - * ADC_R3, address 0x1300200c) - */ - -#define ADC_RX_SHIFT (0) /* Bits 0-9: Digital conversion data */ -#define ADC_RX_MASK (0x3ff << ADC_RX_SHIFT) - -/* ADC_CON, address 0x13002020 */ - -#define ADC_CON_STATUS (1 << 4) /* Bit 4: ADC Status */ -#define ADC_CON_START (1 << 3) /* Bit 3: Start command */ -#define ADC_CON_CSCAN (1 << 2) /* Bit 2: Continuous scan */ -#define ADC_CON_ENABLE (1 << 1) /* Bit 1: ADC enable */ - -/* ADC_CSEL, address 0x13002024 */ - -#define ADC_CSEL_CHAN3_SHIFT (12) /* Bits 12-15: Select and configure channel 3*/ -#define ADC_CSEL_CHAN3_MASK (15 << ADC_CSEL_CHAN3_SHIFT) -#define ADC_CSEL_CHAN2_SHIFT (8) /* Bits 8-10: Select and configure channel 2*/ -#define ADC_CSEL_CHAN2_MASK (15 << ADC_CSEL_CHAN2_SHIFT) -#define ADC_CSEL_CHAN1_SHIFT (4) /* Bits 4-7: Select and configure channel 1*/ -#define ADC_CSEL_CHAN1_MASK (15 << ADC_CSEL_CHAN1_SHIFT) -#define ADC_CSEL_CHAN0_SHIFT (0) /* Bits 0-3: Select and configure channel 0*/ -#define ADC_CSEL_CHAN0_MASK (15 << ADC_CSEL_CHAN0_SHIFT) - -/* ADC_INTEN, address 0x13002028 */ - -#define ADC_INTEN_ENABLE (1 << 0) - -/* ADC_INTST, address 0x1300202c */ - -#define ADC_INTST_PENDING (1 << 0) - -/* ADC_INTCLR, address 0x13002030 */ - -#define ADC_INTCLR_CLEAR (1 << 0) - -/************************************************************************************************ - * Public Types - ************************************************************************************************/ - -/************************************************************************************************ - * Public Data - ************************************************************************************************/ - -/************************************************************************************************ - * Public Functions - ************************************************************************************************/ - -#endif /* __ARCH_ARM_SRC_LPC313X_ADC_H */ diff --git a/nuttx/arch/arm/src/lpc313x/lpc313x_allocateheap.c b/nuttx/arch/arm/src/lpc313x/lpc313x_allocateheap.c deleted file mode 100755 index 79ba8464e..000000000 --- a/nuttx/arch/arm/src/lpc313x/lpc313x_allocateheap.c +++ /dev/null @@ -1,206 +0,0 @@ -/************************************************************************ - * arch/arm/src/lpc313x/lpc313x_allocateheap.c - * - * Copyright (C) 2009-2010 Gregory Nutt. All rights reserved. - * Author: Gregory Nutt - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name NuttX nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - ************************************************************************/ - -/************************************************************************ - * Included Files - ************************************************************************/ - -#include - -#include -#include - -#include -#include - -#include "arm.h" -#include "chip.h" -#include "up_arch.h" -#include "up_internal.h" -#include "lpc313x_memorymap.h" - -#ifdef CONFIG_PAGING -# include -# include "pg_macros.h" -#endif - -/************************************************************************ - * Pre-processor Definitions - ************************************************************************/ - -/* Configuration ********************************************************/ - -/* Some sanity checking. If external memory regions are defined, verify - * that CONFIG_MM_REGIONS is set to match, exactly, the number of external - * memory regions that we have been asked to add to the heap. - */ - -#if defined(CONFIG_LPC313X_EXTSRAM0) && defined(CONFIG_LPC313X_EXTSRAM0HEAP) -# if defined(CONFIG_LPC313X_EXTSRAM1) && defined(CONFIG_LPC313X_EXTSRAM1HEAP) -# if defined(CONFIG_LPC313X_EXTSDRAM) && defined(CONFIG_LPC313X_EXTSDRAMHEAP) -# /* SRAM+EXTSRAM0+EXTSRAM1+EXTSDRAM */ -# define LPC313X_NEXT_REGIONS 4 -# else -# /* SRAM+EXTSRAM0+EXTSRAM1 */ -# define LPC313X_NEXT_REGIONS 3 -# endif -# elif defined(CONFIG_LPC313X_EXTSDRAM) && defined(CONFIG_LPC313X_EXTSDRAMHEAP) -# /* SRAM+EXTSRAM0+EXTSDRAM */ -# define LPC313X_NEXT_REGIONS 3 -# else -# /* SRAM+EXTSRAM0 */ -# define LPC313X_NEXT_REGIONS 2 -# endif -#elif defined(CONFIG_LPC313X_EXTSRAM1) && defined(CONFIG_LPC313X_EXTSRAM1HEAP) -# if defined(CONFIG_LPC313X_EXTSDRAM) && defined(CONFIG_LPC313X_EXTSDRAMHEAP) -# /* SRAM+EXTSRAM1+EXTSDRAM */ -# define LPC313X_NEXT_REGIONS 3 -# else -# /* SRAM+EXTSRAM1 */ -# define LPC313X_NEXT_REGIONS 2 -# endif -#elif defined(CONFIG_LPC313X_EXTSDRAM) && defined(CONFIG_LPC313X_EXTSDRAMHEAP) -# /* SRAM+EXTSDRAM */ -# define LPC313X_NEXT_REGIONS 2 -#else -# /* SRAM */ -# define LPC313X_NEXT_REGIONS 1 -#endif - -#if CONFIG_MM_REGIONS != LPC313X_NEXT_REGIONS -# if CONFIG_MM_REGIONS < LPC313X_NEXT_REGIONS -# error "CONFIG_MM_REGIONS is large enough for the selected memory regions" -# else -# error "CONFIG_MM_REGIONS is too large for the selected memory regions" -# endif -# if defined(CONFIG_LPC313X_EXTSRAM0) && defined(CONFIG_LPC313X_EXTSRAM0HEAP) -# error "External SRAM0 is selected for heap" -# endif -# if defined(CONFIG_LPC313X_EXTSRAM1) && defined(CONFIG_LPC313X_EXTSRAM1HEAP) -# error "External SRAM1 is selected for heap" -# endif -# if defined(CONFIG_LPC313X_EXTSDRAM) && defined(CONFIG_LPC313X_EXTSDRAMHEAP) -# error "External SRAM1 is selected for heap" -# endif -#endif - -/* The following determines the end+1 address the heap (in SRAM0 or SRAM1) - * and that, in turn, determines the size of the heap. Specifically, this - * logic it checks if a page table has been allocated at the end of SRAM - * and, if so, subtracts that the size of the page table from the end+1 - * address of heap. - * - * If the page table was not allocated at the end of SRAM, then this logic - * will let the heap run all the way to the end of SRAM. - */ - -#ifdef CONFIG_PAGING -# ifdef PGTABLE_IN_HIGHSRAM -# define LPC313X_HEAP_VEND (PG_LOCKED_VBASE + PG_TOTAL_VSIZE - PGTABLE_SIZE) -# else -# define LPC313X_HEAP_VEND (PG_LOCKED_VBASE + PG_TOTAL_VSIZE) -# endif -#else -# ifdef PGTABLE_IN_HIGHSRAM -# define LPC313X_HEAP_VEND (LPC313X_INTSRAM_VSECTION + LPC313X_ISRAM_SIZE - PGTABLE_SIZE) -# else -# define LPC313X_HEAP_VEND (LPC313X_INTSRAM_VSECTION + LPC313X_ISRAM_SIZE) -# endif -#endif - -/************************************************************************ - * Private Data - ************************************************************************/ - -/************************************************************************ - * Private Functions - ************************************************************************/ - -/************************************************************************ - * Public Functions - ************************************************************************/ - -/************************************************************************ - * Name: up_allocate_heap - * - * Description: - * The heap may be statically allocated by defining CONFIG_HEAP_BASE - * and CONFIG_HEAP_SIZE. If these are not defined, then this function - * will be called to dynamically set aside the heap region to the end - * of SRAM. - * - * SRAM layout: - * Start of SRAM: .data - * .bss - * IDLE thread stack - * End of SRAm: heap - * - * NOTE: Ignore the erroneous nomenclature DRAM and SDRAM. That names - * date back to an earlier platform that had SDRAM. - * - ************************************************************************/ - -void up_allocate_heap(FAR void **heap_start, size_t *heap_size) -{ - up_ledon(LED_HEAPALLOCATE); - *heap_start = (FAR void*)g_heapbase; - *heap_size = LPC313X_HEAP_VEND - g_heapbase; -} - -/************************************************************************ - * Name: up_addregion - * - * Description: - * Memory may be added in non-contiguous chunks. Additional chunks are - * added by calling this function. - * - ************************************************************************/ - -#if CONFIG_MM_REGIONS > 1 -void up_addregion(void) -{ -#if defined(CONFIG_LPC313X_EXTSRAM0) && defined(CONFIG_LPC313X_EXTSRAM0HEAP) - mm_addregion((FAR void*)LPC313X_EXTSRAM0_VSECTION, CONFIG_LPC313X_EXTSRAM0SIZE); -#endif - -#if defined(CONFIG_LPC313X_EXTSRAM1) && defined(CONFIG_LPC313X_EXTSRAM1HEAP) - mm_addregion((FAR void*)LPC313X_EXTSRAM1_VSECTION, CONFIG_LPC313X_EXTSRAM1SIZE); -#endif - -#if defined(CONFIG_LPC313X_EXTSDRAM) && defined(CONFIG_LPC313X_EXTSDRAMHEAP) - mm_addregion((FAR void*)LPC313X_EXTSDRAM_VSECTION, CONFIG_LPC313X_EXTSDRAMSIZE); -#endif -} -#endif diff --git a/nuttx/arch/arm/src/lpc313x/lpc313x_bcrndx.c b/nuttx/arch/arm/src/lpc313x/lpc313x_bcrndx.c deleted file mode 100755 index 99935387d..000000000 --- a/nuttx/arch/arm/src/lpc313x/lpc313x_bcrndx.c +++ /dev/null @@ -1,100 +0,0 @@ -/************************************************************************ - * arch/arm/src/lpc313x/lpc313x_bcrndx.c - * - * Copyright (C) 2009-2010 Gregory Nutt. All rights reserved. - * Author: Gregory Nutt - * - * References: - * - UM10314 LPC3130/31 User manual Rev. 1.01 — 9 September 2009 - * - lpc313x.cdl.drivers.zip example driver code - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name NuttX nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - ************************************************************************/ - -/************************************************************************ - * Included Files - ************************************************************************/ - -#include -#include - -#include "up_arch.h" -#include "lpc313x_cgudrvr.h" - -/************************************************************************ - * Pre-processor Definitions - ************************************************************************/ - -/************************************************************************ - * Private Data - ************************************************************************/ - -/************************************************************************ - * Private Functions - ************************************************************************/ - -/************************************************************************ - * Public Functions - ************************************************************************/ - -/************************************************************************ - * Name: lpc313x_bcrndx - * - * Description: - * Only 5 of the 12 domains have an associated BCR register. This - * function returns the index to the associated BCR register (if any) - * or BCRNDX_INVALID otherwise. - * - ************************************************************************/ - -int lpc313x_bcrndx(enum lpc313x_domainid_e dmnid) -{ - switch (dmnid) - { - /* BCR0-3 correspond directly to domains 0-3 */ - - case DOMAINID_SYS: /* Domain 0: SYS_BASE */ - case DOMAINID_AHB0APB0: /* Domain 1: AHB0APB0_BASE */ - case DOMAINID_AHB0APB1: /* Domain 2: AHB0APB1_BASE */ - case DOMAINID_AHB0APB2: /* Domain 3: AHB0APB2_BASE */ - return (int)dmnid; - - /* There is a BCR register corresponding to domain 7, but it is at - * index 4 - */ - - case DOMAINID_CLK1024FS: /* Domain 7: CLK1024FS_BASE */ - return 4; - - default: /* There is no BCR register for the other - * domains. */ - break; - } - return BCRNDX_INVALID; -} diff --git a/nuttx/arch/arm/src/lpc313x/lpc313x_boot.c b/nuttx/arch/arm/src/lpc313x/lpc313x_boot.c deleted file mode 100755 index 6f9934b87..000000000 --- a/nuttx/arch/arm/src/lpc313x/lpc313x_boot.c +++ /dev/null @@ -1,397 +0,0 @@ -/************************************************************************************ - * arch/arm/src/lpc313x/lpc313x_boot.c - * - * Copyright (C) 2009-2010 Gregory Nutt. All rights reserved. - * Author: Gregory Nutt - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name NuttX nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - ************************************************************************************/ - -/************************************************************************************ - * Included Files - ************************************************************************************/ - -#include -#include - -#include - -#include "chip.h" -#include "arm.h" -#include "up_internal.h" -#include "up_arch.h" - -#include "lpc313x_syscreg.h" -#include "lpc313x_cgudrvr.h" -#include "lpc313x_internal.h" - -#ifdef CONFIG_PAGING -# include -# include "pg_macros.h" -#endif - -/************************************************************************************ - * Private Types - ************************************************************************************/ - -/************************************************************************************ - * Private Types - ************************************************************************************/ - -struct section_mapping_s -{ - uint32_t physbase; /* Physical address of the region to be mapped */ - uint32_t virtbase; /* Virtual address of the region to be mapped */ - uint32_t mmuflags; /* MMU settings for the region (e.g., cache-able) */ - uint32_t nsections; /* Number of mappings in the region */ -}; - -/************************************************************************************ - * Public Variables - ************************************************************************************/ - -extern uint32_t _vector_start; /* Beginning of vector block */ -extern uint32_t _vector_end; /* End+1 of vector block */ - -/************************************************************************************ - * Private Variables - ************************************************************************************/ - -/* This table describes how to map a set of 1Mb pages to space the physical address - * space of the LPCD313x. - */ - -#ifndef CONFIG_ARCH_ROMPGTABLE -static const struct section_mapping_s section_mapping[] = -{ - { LPC313X_SHADOWSPACE_PSECTION, LPC313X_SHADOWSPACE_VSECTION, - LPC313X_SHADOWSPACE_MMUFLAGS, LPC313X_SHADOWSPACE_NSECTIONS}, -#ifndef CONFIG_PAGING /* SRAM is already fully mapped */ - { LPC313X_INTSRAM_PSECTION, LPC313X_INTSRAM_VSECTION, - LPC313X_INTSRAM_MMUFLAGS, LPC313X_INTSRAM_NSECTIONS}, -#endif -#ifdef CONFIG_ARCH_ROMPGTABLE - { LPC313X_INTSROM0_PSECTION, LPC313X_INTSROM0_VSECTION, - LPC313X_INTSROM_MMUFLAGS, LPC313X_INTSROM0_NSECTIONS}, -#endif - { LPC313X_APB01_PSECTION, LPC313X_APB01_VSECTION, - LPC313X_APB01_MMUFLAGS, LPC313X_APB01_NSECTIONS}, - { LPC313X_APB2_PSECTION, LPC313X_APB2_VSECTION, - LPC313X_APB2_MMUFLAGS, LPC313X_APB2_NSECTIONS}, - { LPC313X_APB3_PSECTION, LPC313X_APB3_VSECTION, - LPC313X_APB3_MMUFLAGS, LPC313X_APB3_NSECTIONS}, - { LPC313X_APB4MPMC_PSECTION, LPC313X_APB4MPMC_VSECTION, - LPC313X_APB4MPMC_MMUFLAGS, LPC313X_APB4MPMC_NSECTIONS}, - { LPC313X_MCI_PSECTION, LPC313X_MCI_VSECTION, - LPC313X_MCI_MMUFLAGS, LPC313X_MCI_NSECTIONS}, - { LPC313X_USBOTG_PSECTION, LPC313X_USBOTG_VSECTION, - LPC313X_USBOTG_MMUFLAGS, LPC313X_USBOTG_NSECTIONS}, -#if defined(CONFIG_LPC313X_EXTSRAM0) && CONFIG_LPC313X_EXTSRAM0SIZE > 0 - { LPC313X_EXTSRAM_PSECTION, LPC313X_EXTSRAM_VSECTION, - LPC313X_EXTSDRAM_MMUFLAGS, LPC313X_EXTSRAM_NSECTIONS}, -#endif -#if defined(CONFIG_LPC313X_EXTSDRAM) && CONFIG_LPC313X_EXTSDRAMSIZE > 0 - { LPC313X_EXTSDRAM0_PSECTION, LPC313X_EXTSDRAM0_VSECTION, - LPC313X_EXTSDRAM_MMUFLAGS, LPC313X_EXTSDRAM0_NSECTIONS}, -#endif - { LPC313X_INTC_PSECTION, LPC313X_INTC_VSECTION, - LPC313X_INTC_MMUFLAGS, LPC313X_INTC_NSECTIONS}, -#ifdef CONFIG_LPC313X_EXTNAND - { LPC313X_NAND_PSECTION, LPC313X_NAND_VSECTION - LPC313X_NAND_MMUFLAGS, LPC313X_NAND_NSECTIONS}, -#endif -}; -#define NMAPPINGS (sizeof(section_mapping) / sizeof(struct section_mapping_s)) -#endif - -/************************************************************************************ - * Private Functions - ************************************************************************************/ - -/************************************************************************************ - * Name: up_setlevel1entry - ************************************************************************************/ - -#ifndef CONFIG_ARCH_ROMPGTABLE -static inline void up_setlevel1entry(uint32_t paddr, uint32_t vaddr, uint32_t mmuflags) -{ - uint32_t *pgtable = (uint32_t*)PGTABLE_BASE_VADDR; - uint32_t index = vaddr >> 20; - - /* Save the page table entry */ - - pgtable[index] = (paddr | mmuflags); -} -#endif - -/************************************************************************************ - * Name: up_setlevel2coarseentry - ************************************************************************************/ - -static inline void up_setlevel2coarseentry(uint32_t ctabvaddr, uint32_t paddr, - uint32_t vaddr, uint32_t mmuflags) -{ - uint32_t *ctable = (uint32_t*)ctabvaddr; - uint32_t index; - - /* The coarse table divides a 1Mb address space up into 256 entries, each - * corresponding to 4Kb of address space. The coarse page table index is - * related to the offset from the beginning of 1Mb region. - */ - - index = (vaddr & 0x000ff000) >> 12; - - /* Save the coarse table entry */ - - ctable[index] = (paddr | mmuflags); -} - -/************************************************************************************ - * Name: up_setupmappings - ************************************************************************************/ - -#ifndef CONFIG_ARCH_ROMPGTABLE -static void up_setupmappings(void) -{ - int i, j; - - for (i = 0; i < NMAPPINGS; i++) - { - uint32_t sect_paddr = section_mapping[i].physbase; - uint32_t sect_vaddr = section_mapping[i].virtbase; - uint32_t mmuflags = section_mapping[i].mmuflags; - - for (j = 0; j < section_mapping[i].nsections; j++) - { - up_setlevel1entry(sect_paddr, sect_vaddr, mmuflags); - sect_paddr += SECTION_SIZE; - sect_vaddr += SECTION_SIZE; - } - } -} -#endif - -/************************************************************************************ - * Name: up_vectorpermissions - * - * Description: - * Set permissions on the vector mapping. - * - ************************************************************************************/ - -#if !defined(CONFIG_ARCH_ROMPGTABLE) && defined(CONFIG_ARCH_LOWVECTORS) && defined(CONFIG_PAGING) -static void up_vectorpermissions(uint32_t mmuflags) -{ - /* The PTE for the beginning of ISRAM is at the base of the L2 page table */ - - uint32_t *ptr = (uint32_t*)PG_L2_VECT_VADDR; - uint32_t pte; - - /* The pte might be zero the first time this function is called. */ - - pte = *ptr; - if (pte == 0) - { - pte = PG_VECT_PBASE; - } - else - { - pte &= PG_L1_PADDRMASK; - } - - /* Update the MMU flags and save */ - - *ptr = pte | mmuflags; - - /* Invalid the TLB for this address */ - - tlb_invalidate_single(PG_L2_VECT_VADDR); -} -#endif - -/************************************************************************************ - * Name: up_vectormapping - * - * Description: - * Setup a special mapping for the interrupt vectors when (1) the interrupt - * vectors are not positioned in ROM, and when (2) the interrupt vectors are - * located at the high address, 0xffff0000. When the interrupt vectors are located - * in ROM, we just have to assume that they were set up correctly; When vectors - * are located in low memory, 0x00000000, the shadow memory region will be mapped - * to support them. - * - ************************************************************************************/ - -#if !defined(CONFIG_ARCH_ROMPGTABLE) && !defined(CONFIG_ARCH_LOWVECTORS) -static void up_vectormapping(void) -{ - uint32_t vector_paddr = LPC313X_VECTOR_PADDR; - uint32_t vector_vaddr = LPC313X_VECTOR_VADDR; - uint32_t end_paddr = vector_paddr + VECTOR_TABLE_SIZE; - - /* We want to keep our interrupt vectors and interrupt-related logic in zero-wait - * state internal RAM (IRAM). The DM320 has 16Kb of IRAM positioned at physical - * address 0x0000:0000; we need to map this to 0xffff:0000. - */ - - while (vector_paddr < end_paddr) - { - up_setlevel2coarseentry(PGTABLE_L2_COARSE_VBASE, vector_paddr, - vector_vaddr, MMU_L2_VECTORFLAGS); - vector_paddr += 4096; - vector_vaddr += 4096; - } - - /* Now set the level 1 descriptor to refer to the level 2 coarse page table. */ - - up_setlevel1entry(PGTABLE_L2_COARSE_PBASE, LPC313X_VECTOR_VCOARSE, - MMU_L1_VECTORFLAGS); -} -#endif - -/************************************************************************************ - * Name: up_copyvectorblock - * - * Description: - * Copy the interrupt block to its final destination. - * - ************************************************************************************/ - -static void up_copyvectorblock(void) -{ - uint32_t *src; - uint32_t *end; - uint32_t *dest; - - /* If we are using vectors in low memory but RAM in that area has been marked - * read only, then temparily mark the mapping write-able (non-buffered). - */ - -#if !defined(CONFIG_ARCH_ROMPGTABLE) && defined(CONFIG_ARCH_LOWVECTORS) && defined(CONFIG_PAGING) - up_vectorpermissions(MMU_L2_VECTRWFLAGS); -#endif - - /* Copy the vectors into ISRAM at the address that will be mapped to the vector - * address: - * - * LPC313X_VECTOR_PADDR - Unmapped, physical address of vector table in SRAM - * LPC313X_VECTOR_VSRAM - Virtual address of vector table in SRAM - * LPC313X_VECTOR_VADDR - Virtual address of vector table (0x00000000 or 0xffff0000) - */ - - src = (uint32_t*)&_vector_start; - end = (uint32_t*)&_vector_end; - dest = (uint32_t*)LPC313X_VECTOR_VSRAM; - - while (src < end) - { - *dest++ = *src++; - } - - /* Make the vectors read-only, cacheable again */ - -#if !defined(CONFIG_ARCH_ROMPGTABLE) && defined(CONFIG_ARCH_LOWVECTORS) && defined(CONFIG_PAGING) - up_vectorpermissions(MMU_L2_VECTROFLAGS); -#endif - - /* Then set the LPC313x shadow register, LPC313X_SYSCREG_ARM926SHADOWPTR, so that - * the vector table is mapped to address 0x0000:0000 - NOTE: that there is not yet - * full support for the vector table at address 0xffff0000. - */ - - putreg32(LPC313X_VECTOR_PADDR, LPC313X_SYSCREG_ARM926SHADOWPTR); -} - -/************************************************************************************ - * Public Functions - ************************************************************************************/ - -/************************************************************************************ - * Name: up_boot - * - * Description: - * Complete boot operations started in up_head.S - * - ************************************************************************************/ - -void up_boot(void) -{ - /* __start provided the basic MMU mappings for SRAM. Now provide mappings for all - * IO regions (Including the vector region). - */ - -#ifndef CONFIG_ARCH_ROMPGTABLE - up_setupmappings(); - - /* Provide a special mapping for the IRAM interrupt vector positioned in high - * memory. - */ - -#ifndef CONFIG_ARCH_LOWVECTORS - up_vectormapping(); -#endif -#endif /* CONFIG_ARCH_ROMPGTABLE */ - - /* Setup up vector block. _vector_start and _vector_end are exported from - * up_vector.S - */ - - up_copyvectorblock(); - - /* Reset all clocks */ - - lpc313x_resetclks(); - - /* Initialize the PLLs */ - - lpc313x_hp1pllconfig(); - lpc313x_hp0pllconfig(); - - /* Initialize clocking to settings provided by board-specific logic */ - - lpc313x_clkinit(&g_boardclks); - - /* Map first 4KB of ARM space to ISRAM area */ - - putreg32(LPC313X_INTSRAM0_PADDR, LPC313X_SYSCREG_ARM926SHADOWPTR); - - /* Perform common, low-level chip initialization (might do nothing) */ - - lpc313x_lowsetup(); - - /* Perform early serial initialization if we are going to use the serial driver */ - -#ifdef CONFIG_USE_EARLYSERIALINIT - up_earlyserialinit(); -#endif - - /* Perform board-specific initialization */ - - lpc313x_boardinitialize(); -} diff --git a/nuttx/arch/arm/src/lpc313x/lpc313x_cgu.h b/nuttx/arch/arm/src/lpc313x/lpc313x_cgu.h deleted file mode 100755 index 961258e39..000000000 --- a/nuttx/arch/arm/src/lpc313x/lpc313x_cgu.h +++ /dev/null @@ -1,1626 +0,0 @@ -/************************************************************************************************ - * arch/arm/src/lpc313x/lpc313x_cgu.h - * - * Copyright (C) 2009-2010 Gregory Nutt. All rights reserved. - * Author: Gregory Nutt - * - * References: - * - UM10314 LPC3130/31 User manual Rev. 1.01 — 9 September 2009 - * - * 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_LPC313X_CGU_H -#define __ARCH_ARM_SRC_LPC313X_CGU_H - -/************************************************************************************************ - * Included Files - ************************************************************************************************/ - -#include -#include "lpc313x_memorymap.h" - -/************************************************************************************************ - * Pre-processor Definitions - ************************************************************************************************/ - -/* CGU register base address offset into the APB0 domain ****************************************/ - -/* APB0 offsets to Clock Switch Box (CSB) and CGU Configuration (CFG) register groups */ - -#define LPC313X_APB0_GCU_CSB_OFFSET (LPC313X_APB0_GCU_OFFSET) -#define LPC313X_APB0_GCU_CFG_OFFSET (LPC313X_APB0_GCU_OFFSET+0x0c00) - -/* Virtual and physical base address of the CGU block and CSB and CFG register groups */ - -#define LPC313X_CGU_VBASE (LPC313X_APB0_VADDR+LPC313X_APB0_CGU_OFFSET) -#define LPC313X_CGU_PBASE (LPC313X_APB0_PADDR+LPC313X_APB0_CGU_OFFSET) - -#define LPC313X_CGU_CSB_VBASE (LPC313X_APB0_VADDR+LPC313X_APB0_GCU_CSB_OFFSET) -#define LPC313X_CGU_CSB_PBASE (LPC313X_APB0_PADDR+LPC313X_APB0_GCU_CSB_OFFSET) - -#define LPC313X_CGU_CFG_VBASE (LPC313X_APB0_VADDR+LPC313X_APB0_GCU_CFG_OFFSET) -#define LPC313X_CGU_CFG_PBASE (LPC313X_APB0_PADDR+LPC313X_APB0_GCU_CFG_OFFSET) - -/* CGU register offsets *************************************************************************/ -/* CGU clock switchbox register offsets (with respect to the CGU CSB register base) *************/ -/* Switch configuration registers (SCR) for base clocks */ - -#define LPC313X_CGU_SCR_OFFSET(n) (0x000+((n)<<2)) -#define LPC313X_CGU_SCR0_OFFSET 0x000 /* SYS base */ -#define LPC313X_CGU_SCR1_OFFSET 0x004 /* AHB0_APB0 base */ -#define LPC313X_CGU_SCR2_OFFSET 0x008 /* AHB0_APB1 base */ -#define LPC313X_CGU_SCR3_OFFSET 0x00c /* AHB0_APB2 base */ -#define LPC313X_CGU_SCR4_OFFSET 0x010 /* AHB0_APB3 base */ -#define LPC313X_CGU_SCR5_OFFSET 0x014 /* PCM base */ -#define LPC313X_CGU_SCR6_OFFSET 0x018 /* UART base */ -#define LPC313X_CGU_SCR7_OFFSET 0x01c /* CLK1024FS base */ -#define LPC313X_CGU_SCR8_OFFSET 0x020 /* I2SRX_BCK0 base */ -#define LPC313X_CGU_SCR9_OFFSET 0x024 /* I2SRX_BCK1 base */ -#define LPC313X_CGU_SCR10_OFFSET 0x028 /* SPI_CLK base */ -#define LPC313X_CGU_SCR11_OFFSET 0x02c /* SYSCLK_O base */ - -/* Frequency select (FS) registers 1 for base clocks */ - -#define LPC313X_CGU_FS1_OFFSET(n) (0x030+((n)<<2)) -#define LPC313X_CGU_FS1_0_OFFSET 0x030 /* SYS base */ -#define LPC313X_CGU_FS1_1_OFFSET 0x034 /* AHB0_APB0 base */ -#define LPC313X_CGU_FS1_2_OFFSET 0x038 /* AHB0_APB1 base */ -#define LPC313X_CGU_FS1_3_OFFSET 0x03c /* AHB0_APB2 base */ -#define LPC313X_CGU_FS1_4_OFFSET 0x040 /* AHB0_APB3 base */ -#define LPC313X_CGU_FS1_5_OFFSET 0x044 /* PCM base */ -#define LPC313X_CGU_FS1_6_OFFSET 0x048 /* UART base */ -#define LPC313X_CGU_FS1_7_OFFSET 0x04c /* CLK1024FS base */ -#define LPC313X_CGU_FS1_8_OFFSET 0x050 /* I2SRX_BCK0 base */ -#define LPC313X_CGU_FS1_9_OFFSET 0x054 /* I2SRX_BCK1 base */ -#define LPC313X_CGU_FS1_10_OFFSET 0x058 /* SPI_CLK base */ -#define LPC313X_CGU_FS1_11_OFFSET 0x05c /* SYSCLK_O base */ - -/* Frequency select (FS) registers 2 for base clocks */ - -#define LPC313X_CGU_FS2_OFFSET(n) (0x060+((n)<<2)) -#define LPC313X_CGU_FS2_0_OFFSET 0x060 /* SYS base */ -#define LPC313X_CGU_FS2_1_OFFSET 0x064 /* AHB0_APB0 base */ -#define LPC313X_CGU_FS2_2_OFFSET 0x068 /* AHB0_APB1 base */ -#define LPC313X_CGU_FS2_3_OFFSET 0x06c /* AHB0_APB2 base */ -#define LPC313X_CGU_FS2_4_OFFSET 0x070 /* AHB0_APB3 base */ -#define LPC313X_CGU_FS2_5_OFFSET 0x074 /* PCM base */ -#define LPC313X_CGU_FS2_6_OFFSET 0x078 /* UART base */ -#define LPC313X_CGU_FS2_7_OFFSET 0x07c /* CLK1024FS base */ -#define LPC313X_CGU_FS2_8_OFFSET 0x080 /* I2SRX_BCK0 base */ -#define LPC313X_CGU_FS2_9_OFFSET 0x084 /* I2SRX_BCK1 base */ -#define LPC313X_CGU_FS2_10_OFFSET 0x088 /* SPI_CLK base */ -#define LPC313X_CGU_FS2_11_OFFSET 0x08c /* SYSCLK_O base */ - -/* Switch status registers (SSR) for base clocks */ - -#define LPC313X_CGU_SSR_OFFSET(n) (0x090+((n)<<2)) -#define LPC313X_CGU_SSR0_OFFSET 0x090 /* SYS base */ -#define LPC313X_CGU_SSR1_OFFSET 0x094 /* AHB0_APB0 base */ -#define LPC313X_CGU_SSR2_OFFSET 0x098 /* AHB0_APB1 base */ -#define LPC313X_CGU_SSR3_OFFSET 0x09c /* AHB0_APB2 base */ -#define LPC313X_CGU_SSR4_OFFSET 0x0a0 /* AHB0_APB3 base */ -#define LPC313X_CGU_SSR5_OFFSET 0x0a4 /* PCM base */ -#define LPC313X_CGU_SSR6_OFFSET 0x0a8 /* UART base */ -#define LPC313X_CGU_SSR7_OFFSET 0x0ac /* CLK1024FS base */ -#define LPC313X_CGU_SSR8_OFFSET 0x0b0 /* I2SRX_BCK0 base */ -#define LPC313X_CGU_SSR9_OFFSET 0x0b4 /* I2SRX_BCK1 base */ -#define LPC313X_CGU_SSR10_OFFSET 0x0b8 /* SPI_CLK base */ -#define LPC313X_CGU_SSR11_OFFSET 0x0bc /* SYSCLK_O base */ - -/* Power control registers (PCR), spreading stage */ - -#define LPC313X_CGU_PCR_OFFSET(n) (0x0c0+((n)<<2)) -#define LPC313X_CGU_PCR0_OFFSET 0x0c0 /* APB0_CLK */ -#define LPC313X_CGU_PCR1_OFFSET 0x0c4 /* APB1_CLK */ -#define LPC313X_CGU_PCR2_OFFSET 0x0c8 /* APB2_CLK */ -#define LPC313X_CGU_PCR3_OFFSET 0x0cc /* APB3_CLK */ -#define LPC313X_CGU_PCR4_OFFSET 0x0d0 /* APB4_CLK */ -#define LPC313X_CGU_PCR5_OFFSET 0x0d4 /* AHB_TO_INTC_CLK */ -#define LPC313X_CGU_PCR6_OFFSET 0x0d8 /* AHB0_CLK */ -#define LPC313X_CGU_PCR7_OFFSET 0x0dc /* EBI_CLK */ -#define LPC313X_CGU_PCR8_OFFSET 0x0e0 /* DMA_PCLK */ -#define LPC313X_CGU_PCR9_OFFSET 0x0e4 /* DMA_CLK_GATED */ -#define LPC313X_CGU_PCR10_OFFSET 0x0e8 /* NANDFLASH_S0_CLK */ -#define LPC313X_CGU_PCR11_OFFSET 0x0ec /* NANDFLASH_ECC_CLK */ -#define LPC313X_CGU_PCR12_OFFSET 0x0f0 /* Reserved */ -#define LPC313X_CGU_PCR13_OFFSET 0x0f4 /* NANDFLASH_NAND_CLK */ -#define LPC313X_CGU_PCR14_OFFSET 0x0f8 /* NANDFLASH_PCLK */ -#define LPC313X_CGU_PCR15_OFFSET 0x0fc /* CLOCK_OUT */ -#define LPC313X_CGU_PCR16_OFFSET 0x100 /* ARM926_CORE_CLK */ -#define LPC313X_CGU_PCR17_OFFSET 0x104 /* ARM926_BUSIF_CLK */ -#define LPC313X_CGU_PCR18_OFFSET 0x108 /* ARM926_RETIME_CLK */ -#define LPC313X_CGU_PCR19_OFFSET 0x10c /* SD_MMC_HCLK */ -#define LPC313X_CGU_PCR20_OFFSET 0x110 /* SD_MMC_CCLK_IN */ -#define LPC313X_CGU_PCR21_OFFSET 0x114 /* USB_OTG_AHB_CLK */ -#define LPC313X_CGU_PCR22_OFFSET 0x118 /* ISRAM0_CLK */ -#define LPC313X_CGU_PCR23_OFFSET 0x11c /* RED_CTL_RSCLK */ -#define LPC313X_CGU_PCR24_OFFSET 0x120 /* ISRAM1_CLK (LPC313x only) */ -#define LPC313X_CGU_PCR25_OFFSET 0x124 /* ISROM_CLK */ -#define LPC313X_CGU_PCR26_OFFSET 0x128 /* MPMC_CFG_CLK */ -#define LPC313X_CGU_PCR27_OFFSET 0x12c /* MPMC_CFG_CLK2 */ -#define LPC313X_CGU_PCR28_OFFSET 0x130 /* MPMC_CFG_CLK3 */ -#define LPC313X_CGU_PCR29_OFFSET 0x134 /* INTC_CLK */ -#define LPC313X_CGU_PCR30_OFFSET 0x138 /* AHB_TO_APB0_PCLK */ -#define LPC313X_CGU_PCR31_OFFSET 0x13c /* EVENT_ROUTER_PCLK */ -#define LPC313X_CGU_PCR32_OFFSET 0x140 /* ADC_PCLK */ -#define LPC313X_CGU_PCR33_OFFSET 0x144 /* ADC_CLK */ -#define LPC313X_CGU_PCR34_OFFSET 0x148 /* WDOG_PCLK */ -#define LPC313X_CGU_PCR35_OFFSET 0x14c /* IOCONF_PCLK */ -#define LPC313X_CGU_PCR36_OFFSET 0x150 /* CGU_PCLK */ -#define LPC313X_CGU_PCR37_OFFSET 0x154 /* SYSCREG_PCLK */ -#define LPC313X_CGU_PCR38_OFFSET 0x158 /* Reserved */ -#define LPC313X_CGU_PCR39_OFFSET 0x15c /* RNG_PCLK */ -#define LPC313X_CGU_PCR40_OFFSET 0x160 /* AHB_TO_APB1_PCLK */ -#define LPC313X_CGU_PCR41_OFFSET 0x164 /* TIMER0_PCLK */ -#define LPC313X_CGU_PCR42_OFFSET 0x168 /* TIMER1_PCLK */ -#define LPC313X_CGU_PCR43_OFFSET 0x16c /* TIMER2_PCLK */ -#define LPC313X_CGU_PCR44_OFFSET 0x170 /* TIMER3_PCLK */ -#define LPC313X_CGU_PCR45_OFFSET 0x174 /* PWM_PCLK */ -#define LPC313X_CGU_PCR46_OFFSET 0x178 /* PWM_PCLK_REGS */ -#define LPC313X_CGU_PCR47_OFFSET 0x17c /* PWM_CLK */ -#define LPC313X_CGU_PCR48_OFFSET 0x180 /* I2C0_PCLK */ -#define LPC313X_CGU_PCR49_OFFSET 0x184 /* I2C1_PCLK */ -#define LPC313X_CGU_PCR50_OFFSET 0x188 /* AHB_TO_APB2_PCLK */ -#define LPC313X_CGU_PCR51_OFFSET 0x18c /* PCM_PCLK */ -#define LPC313X_CGU_PCR52_OFFSET 0x190 /* PCM_APB_PCLK */ -#define LPC313X_CGU_PCR53_OFFSET 0x194 /* UART_APB_CLK */ -#define LPC313X_CGU_PCR54_OFFSET 0x198 /* LCD_PCLK */ -#define LPC313X_CGU_PCR55_OFFSET 0x19c /* LCD_CLK */ -#define LPC313X_CGU_PCR56_OFFSET 0x1a0 /* SPI_PCLK */ -#define LPC313X_CGU_PCR57_OFFSET 0x1a4 /* SPI_PCLK_GATED */ -#define LPC313X_CGU_PCR58_OFFSET 0x1a8 /* AHB_TO_APB3_PCLK */ -#define LPC313X_CGU_PCR59_OFFSET 0x1ac /* I2S_CFG_PCLK */ -#define LPC313X_CGU_PCR60_OFFSET 0x1b0 /* EDGE_DET_PCLK */ -#define LPC313X_CGU_PCR61_OFFSET 0x1b4 /* I2STX_FIFO_0_PCLK */ -#define LPC313X_CGU_PCR62_OFFSET 0x1b8 /* I2STX_IF_0_PCLK */ -#define LPC313X_CGU_PCR63_OFFSET 0x1bc /* I2STX_FIFO_1_PCLK */ -#define LPC313X_CGU_PCR64_OFFSET 0x1c0 /* I2STX_IF_1_PCLK */ -#define LPC313X_CGU_PCR65_OFFSET 0x1c4 /* I2SRX_FIFO_0_PCLK */ -#define LPC313X_CGU_PCR66_OFFSET 0x1c8 /* I2SRX_IF_0_PCLK */ -#define LPC313X_CGU_PCR67_OFFSET 0x1cc /* I2SRX_FIFO_1_PCLK */ -#define LPC313X_CGU_PCR68_OFFSET 0x1d0 /* I2SRX_IF_1_PCLK */ -#define LPC313X_CGU_PCR69_OFFSET 0x1d4 /* Reserved */ -#define LPC313X_CGU_PCR70_OFFSET 0x1d8 /* Reserved */ -#define LPC313X_CGU_PCR71_OFFSET 0x1dc /* PCM_CLK_IP */ -#define LPC313X_CGU_PCR72_OFFSET 0x1e0 /* UART_U_CLK */ -#define LPC313X_CGU_PCR73_OFFSET 0x1e4 /* I2S_EDGE_DETECT_CLK */ -#define LPC313X_CGU_PCR74_OFFSET 0x1e8 /* I2STX_BCK0_N */ -#define LPC313X_CGU_PCR75_OFFSET 0x1ec /* I2STX_WS0 */ -#define LPC313X_CGU_PCR76_OFFSET 0x1f0 /* I2STX_CLK0 */ -#define LPC313X_CGU_PCR77_OFFSET 0x1f4 /* I2STX_BCK1_N */ -#define LPC313X_CGU_PCR78_OFFSET 0x1f8 /* I2STX_WS1 */ -#define LPC313X_CGU_PCR79_OFFSET 0x1fc /* CLK_256FS */ -#define LPC313X_CGU_PCR80_OFFSET 0x200 /* I2SRX_BCK0_N */ -#define LPC313X_CGU_PCR81_OFFSET 0x204 /* I2SRX_WS0 */ -#define LPC313X_CGU_PCR82_OFFSET 0x208 /* I2SRX_BCK1_N */ -#define LPC313X_CGU_PCR83_OFFSET 0x20c /* I2SRX_WS1 */ -#define LPC313X_CGU_PCR84_OFFSET 0x210 /* Reserved */ -#define LPC313X_CGU_PCR85_OFFSET 0x214 /* Reserved */ -#define LPC313X_CGU_PCR86_OFFSET 0x218 /* Reserved */ -#define LPC313X_CGU_PCR87_OFFSET 0x21c /* I2SRX_BCK0 */ -#define LPC313X_CGU_PCR88_OFFSET 0x220 /* I2SRX_BCK1 */ -#define LPC313X_CGU_PCR89_OFFSET 0x224 /* SPI_CLK */ -#define LPC313X_CGU_PCR90_OFFSET 0x228 /* SPI_CLK_GATED */ -#define LPC313X_CGU_PCR91_OFFSET 0x22c /* SYSCLK_O */ - -/* Power status registers (PSR), spreading stage */ - -#define LPC313X_CGU_PSR_OFFSET(n) (0x230+((n)<<2)) -#define LPC313X_CGU_PSR0_OFFSET 0x230 /* PB0_CLK */ -#define LPC313X_CGU_PSR1_OFFSET 0x234 /* PB1_CLK */ -#define LPC313X_CGU_PSR2_OFFSET 0x238 /* PB2_CLK */ -#define LPC313X_CGU_PSR3_OFFSET 0x23c /* PB3_CLK */ -#define LPC313X_CGU_PSR4_OFFSET 0x240 /* PB4_CLK */ -#define LPC313X_CGU_PSR5_OFFSET 0x244 /* HB_TO_INTC_CLK */ -#define LPC313X_CGU_PSR6_OFFSET 0x248 /* HB0_CLK */ -#define LPC313X_CGU_PSR7_OFFSET 0x24c /* EBI_CLK */ -#define LPC313X_CGU_PSR8_OFFSET 0x250 /* DMA_PCLK */ -#define LPC313X_CGU_PSR9_OFFSET 0x254 /* DMA_CLK_GATED */ -#define LPC313X_CGU_PSR10_OFFSET 0x258 /* NANDFLASH_S0_CLK */ -#define LPC313X_CGU_PSR11_OFFSET 0x25c /* NANDFLASH_ECC_CLK */ -#define LPC313X_CGU_PSR12_OFFSET 0x260 /* Reserved */ -#define LPC313X_CGU_PSR13_OFFSET 0x264 /* NANDFLASH_NAND_CLK */ -#define LPC313X_CGU_PSR14_OFFSET 0x268 /* NANDFLASH_PCLK */ -#define LPC313X_CGU_PSR15_OFFSET 0x26c /* CLOCK_OUT */ -#define LPC313X_CGU_PSR16_OFFSET 0x270 /* RM926_CORE_CLK */ -#define LPC313X_CGU_PSR17_OFFSET 0x274 /* RM926_BUSIF_CLK */ -#define LPC313X_CGU_PSR18_OFFSET 0x278 /* RM926_RETIME_CLK */ -#define LPC313X_CGU_PSR19_OFFSET 0x27c /* SD_MMC_HCLK */ -#define LPC313X_CGU_PSR20_OFFSET 0x280 /* SD_MMC_CCLK_IN */ -#define LPC313X_CGU_PSR21_OFFSET 0x284 /* USB_OTG_AHB_CLK */ -#define LPC313X_CGU_PSR22_OFFSET 0x288 /* ISRAM0_CLK */ -#define LPC313X_CGU_PSR23_OFFSET 0x28c /* RED_CTL_RSCLK */ -#define LPC313X_CGU_PSR24_OFFSET 0x290 /* ISRAM1_CLK */ -#define LPC313X_CGU_PSR25_OFFSET 0x294 /* ISROM_CLK */ -#define LPC313X_CGU_PSR26_OFFSET 0x298 /* MPMC_CFG_CLK */ -#define LPC313X_CGU_PSR27_OFFSET 0x29c /* MPMC_CFG_CLK2 */ -#define LPC313X_CGU_PSR28_OFFSET 0x2a0 /* MPMC_CFG_CLK3 */ -#define LPC313X_CGU_PSR29_OFFSET 0x2a4 /* INTC_CLK */ -#define LPC313X_CGU_PSR30_OFFSET 0x2a8 /* HB_TO_APB0_PCLK */ -#define LPC313X_CGU_PSR31_OFFSET 0x2ac /* EVENT_ROUTER_PCLK */ -#define LPC313X_CGU_PSR32_OFFSET 0x2b0 /* DC_PCLK */ -#define LPC313X_CGU_PSR33_OFFSET 0x2b4 /* DC_CLK */ -#define LPC313X_CGU_PSR34_OFFSET 0x2b8 /* WDOG_PCLK */ -#define LPC313X_CGU_PSR35_OFFSET 0x2bc /* IOCONF_PCLK */ -#define LPC313X_CGU_PSR36_OFFSET 0x2c0 /* CGU_PCLK */ -#define LPC313X_CGU_PSR37_OFFSET 0x2c4 /* SYSCREG_PCLK */ -#define LPC313X_CGU_PSR38_OFFSET 0x2c8 /* Reserved */ -#define LPC313X_CGU_PSR39_OFFSET 0x2cc /* RNG_PCLK */ -#define LPC313X_CGU_PSR40_OFFSET 0x2d0 /* HB_TO_APB1_PCLK */ -#define LPC313X_CGU_PSR41_OFFSET 0x2d4 /* TIMER0_PCLK */ -#define LPC313X_CGU_PSR42_OFFSET 0x2d8 /* TIMER1_PCLK */ -#define LPC313X_CGU_PSR43_OFFSET 0x2dc /* TIMER2_PCLK */ -#define LPC313X_CGU_PSR44_OFFSET 0x2e0 /* TIMER3_PCLK */ -#define LPC313X_CGU_PSR45_OFFSET 0x2e4 /* PWM_PCLK */ -#define LPC313X_CGU_PSR46_OFFSET 0x2e8 /* PWM_PCLK_REGS */ -#define LPC313X_CGU_PSR47_OFFSET 0x2ec /* PWM_CLK */ -#define LPC313X_CGU_PSR48_OFFSET 0x2f0 /* I2C0_PCLK */ -#define LPC313X_CGU_PSR49_OFFSET 0x2f4 /* I2C1_PCLK */ -#define LPC313X_CGU_PSR50_OFFSET 0x2f8 /* HB_TO_APB2_PCLK */ -#define LPC313X_CGU_PSR51_OFFSET 0x2fc /* PCM_PCLK */ -#define LPC313X_CGU_PSR52_OFFSET 0x300 /* PCM_APB_PCLK */ -#define LPC313X_CGU_PSR53_OFFSET 0x304 /* UART_APB_CLK */ -#define LPC313X_CGU_PSR54_OFFSET 0x308 /* LCD_PCLK */ -#define LPC313X_CGU_PSR55_OFFSET 0x30c /* LCD_CLK */ -#define LPC313X_CGU_PSR56_OFFSET 0x310 /* SPI_PCLK */ -#define LPC313X_CGU_PSR57_OFFSET 0x314 /* SPI_PCLK_GATED */ -#define LPC313X_CGU_PSR58_OFFSET 0x318 /* HB_TO_APB3_PCLK */ -#define LPC313X_CGU_PSR59_OFFSET 0x31c /* I2S_CFG_PCLK */ -#define LPC313X_CGU_PSR60_OFFSET 0x320 /* EDGE_DET_PCLK */ -#define LPC313X_CGU_PSR61_OFFSET 0x324 /* I2STX_FIFO_0_PCLK */ -#define LPC313X_CGU_PSR62_OFFSET 0x328 /* I2STX_IF_0_PCLK */ -#define LPC313X_CGU_PSR63_OFFSET 0x32c /* I2STX_FIFO_1_PCLK */ -#define LPC313X_CGU_PSR64_OFFSET 0x330 /* I2STX_IF_1_PCLK */ -#define LPC313X_CGU_PSR65_OFFSET 0x334 /* I2SRX_FIFO_0_PCLK */ -#define LPC313X_CGU_PSR66_OFFSET 0x338 /* I2SRX_IF_0_PCLK */ -#define LPC313X_CGU_PSR67_OFFSET 0x33c /* I2SRX_FIFO_1_PCLK */ -#define LPC313X_CGU_PSR68_OFFSET 0x340 /* I2SRX_IF_1_PCLK */ -#define LPC313X_CGU_PSR69_OFFSET 0x344 /* Reserved */ -#define LPC313X_CGU_PSR70_OFFSET 0x348 /* Reserved */ -#define LPC313X_CGU_PSR71_OFFSET 0x34c /* PCM_CLK_IP */ -#define LPC313X_CGU_PSR72_OFFSET 0x350 /* UART_U_CLK */ -#define LPC313X_CGU_PSR73_OFFSET 0x354 /* I2S_EDGE_DETECT_CLK */ -#define LPC313X_CGU_PSR74_OFFSET 0x358 /* I2STX_BCK0_N */ -#define LPC313X_CGU_PSR75_OFFSET 0x35c /* I2STX_WS0 */ -#define LPC313X_CGU_PSR76_OFFSET 0x360 /* I2STX_CLK0 */ -#define LPC313X_CGU_PSR77_OFFSET 0x364 /* I2STX_BCK1_N */ -#define LPC313X_CGU_PSR78_OFFSET 0x368 /* I2STX_WS1 */ -#define LPC313X_CGU_PSR79_OFFSET 0x36c /* CLK_256FS */ -#define LPC313X_CGU_PSR80_OFFSET 0x370 /* I2SRX_BCK0_N */ -#define LPC313X_CGU_PSR81_OFFSET 0x374 /* I2SRX_WS0 */ -#define LPC313X_CGU_PSR82_OFFSET 0x378 /* I2SRX_BCK1_N */ -#define LPC313X_CGU_PSR83_OFFSET 0x37c /* I2SRX_WS1 */ -#define LPC313X_CGU_PSR84_OFFSET 0x380 /* Reserved */ -#define LPC313X_CGU_PSR85_OFFSET 0x384 /* Reserved */ -#define LPC313X_CGU_PSR86_OFFSET 0x388 /* Reserved */ -#define LPC313X_CGU_PSR87_OFFSET 0x38c /* I2SRX_BCK0 */ -#define LPC313X_CGU_PSR88_OFFSET 0x390 /* I2SRX_BCK1 */ -#define LPC313X_CGU_PSR89_OFFSET 0x394 /* SPI_CLK */ -#define LPC313X_CGU_PSR90_OFFSET 0x398 /* SPI_CLK_GATED */ -#define LPC313X_CGU_PSR91_OFFSET 0x39c /* SYSCLK_O */ - -/* Enable select registers (ESR), spreading stage */ - -#define LPC313X_CGU_ESR_OFFSET(n) (0x3a0+((n)<<2)) -#define LPC313X_CGU_ESR0_OFFSET 0x3a0 /* APB0_CLK */ -#define LPC313X_CGU_ESR1_OFFSET 0x3a4 /* APB1_CLK */ -#define LPC313X_CGU_ESR2_OFFSET 0x3A8 /* APB2_CLK */ -#define LPC313X_CGU_ESR3_OFFSET 0x3ac /* APB3_CLK */ -#define LPC313X_CGU_ESR4_OFFSET 0x3b0 /* APB4_CLK */ -#define LPC313X_CGU_ESR5_OFFSET 0x3b4 /* AHB_TO_INTC_CLK */ -#define LPC313X_CGU_ESR6_OFFSET 0x3b8 /* AHB0_CLK */ -#define LPC313X_CGU_ESR7_OFFSET 0x3bc /* EBI_CLK */ -#define LPC313X_CGU_ESR8_OFFSET 0x3c0 /* DMA_PCLK */ -#define LPC313X_CGU_ESR9_OFFSET 0x3c4 /* DMA_CLK_GATED */ -#define LPC313X_CGU_ESR10_OFFSET 0x3c8 /* NANDFLASH_S0_CLK */ -#define LPC313X_CGU_ESR11_OFFSET 0x3cc /* NANDFLASH_ECC_CLK */ -#define LPC313X_CGU_ESR12_OFFSET 0x3d0 /* Reserved */ -#define LPC313X_CGU_ESR13_OFFSET 0x3d4 /* NANDFLASH_NAND_CLK */ -#define LPC313X_CGU_ESR14_OFFSET 0x3d8 /* NANDFLASH_PCLK */ -#define LPC313X_CGU_ESR15_OFFSET 0x3dc /* CLOCK_OUT */ -#define LPC313X_CGU_ESR16_OFFSET 0x3e0 /* ARM926_CORE_CLK */ -#define LPC313X_CGU_ESR17_OFFSET 0x3e4 /* ARM926_BUSIF_CLK */ -#define LPC313X_CGU_ESR18_OFFSET 0x3e8 /* ARM926_RETIME_CLK */ -#define LPC313X_CGU_ESR19_OFFSET 0x3ec /* SD_MMC_HCLK */ -#define LPC313X_CGU_ESR20_OFFSET 0x3f0 /* SD_MMC_CCLK_IN */ -#define LPC313X_CGU_ESR21_OFFSET 0x3f4 /* USB_OTG_AHB_CLK */ -#define LPC313X_CGU_ESR22_OFFSET 0x3f8 /* ISRAM0_CLK */ -#define LPC313X_CGU_ESR23_OFFSET 0x3fc /* RED_CTL_RSCLK */ -#define LPC313X_CGU_ESR24_OFFSET 0x400 /* ISRAM1_CLK */ -#define LPC313X_CGU_ESR25_OFFSET 0x404 /* ISROM_CLK */ -#define LPC313X_CGU_ESR26_OFFSET 0x408 /* MPMC_CFG_CLK */ -#define LPC313X_CGU_ESR27_OFFSET 0x40c /* MPMC_CFG_CLK2 */ -#define LPC313X_CGU_ESR28_OFFSET 0x410 /* MPMC_CFG_CLK3 */ -#define LPC313X_CGU_ESR29_OFFSET 0x414 /* INTC_CLK */ -#define LPC313X_CGU_ESR30_OFFSET 0x418 /* AHB_TO_APB0_PCLK */ -#define LPC313X_CGU_ESR31_OFFSET 0x41c /* EVENT_ROUTER_PCLK */ -#define LPC313X_CGU_ESR32_OFFSET 0x420 /* ADC_PCLK */ -#define LPC313X_CGU_ESR33_OFFSET 0x424 /* ADC_CLK */ -#define LPC313X_CGU_ESR34_OFFSET 0x428 /* WDOG_PCLK */ -#define LPC313X_CGU_ESR35_OFFSET 0x42c /* IOCONF_PCLK */ -#define LPC313X_CGU_ESR36_OFFSET 0x430 /* CGU_PCLK */ -#define LPC313X_CGU_ESR37_OFFSET 0x434 /* SYSCREG_PCLK */ -#define LPC313X_CGU_ESR38_OFFSET 0x438 /* Reserved */ -#define LPC313X_CGU_ESR39_OFFSET 0x43c /* RNG_PCLK */ -#define LPC313X_CGU_ESR40_OFFSET 0x440 /* AHB_TO_APB1_PCLK */ -#define LPC313X_CGU_ESR41_OFFSET 0x444 /* TIMER0_PCLK */ -#define LPC313X_CGU_ESR42_OFFSET 0x448 /* TIMER1_PCLK */ -#define LPC313X_CGU_ESR43_OFFSET 0x44c /* TIMER2_PCLK */ -#define LPC313X_CGU_ESR44_OFFSET 0x450 /* TIMER3_PCLK */ -#define LPC313X_CGU_ESR45_OFFSET 0x454 /* PWM_PCLK */ -#define LPC313X_CGU_ESR46_OFFSET 0x458 /* PWM_PCLK_REGS */ -#define LPC313X_CGU_ESR47_OFFSET 0x45c /* PWM_CLK */ -#define LPC313X_CGU_ESR48_OFFSET 0x460 /* I2C0_PCLK */ -#define LPC313X_CGU_ESR49_OFFSET 0x464 /* I2C1_PCLK */ -#define LPC313X_CGU_ESR50_OFFSET 0x468 /* AHB_TO_APB2_PCLK */ -#define LPC313X_CGU_ESR51_OFFSET 0x46c /* PCM_PCLK */ -#define LPC313X_CGU_ESR52_OFFSET 0x470 /* PCM_APB_PCLK */ -#define LPC313X_CGU_ESR53_OFFSET 0x474 /* UART_APB_CLK */ -#define LPC313X_CGU_ESR54_OFFSET 0x478 /* LCD_PCLK */ -#define LPC313X_CGU_ESR55_OFFSET 0x47c /* LCD_CLK */ -#define LPC313X_CGU_ESR56_OFFSET 0x480 /* SPI_PCLK */ -#define LPC313X_CGU_ESR57_OFFSET 0x484 /* SPI_PCLK_GATED */ -#define LPC313X_CGU_ESR58_OFFSET 0x488 /* AHB_TO_APB3_PCLK */ -#define LPC313X_CGU_ESR59_OFFSET 0x48c /* I2S_CFG_PCLK */ -#define LPC313X_CGU_ESR60_OFFSET 0x490 /* EDGE_DET_PCLK */ -#define LPC313X_CGU_ESR61_OFFSET 0x494 /* I2STX_FIFO_0_PCLK */ -#define LPC313X_CGU_ESR62_OFFSET 0x498 /* I2STX_IF_0_PCLK */ -#define LPC313X_CGU_ESR63_OFFSET 0x49c /* I2STX_FIFO_1_PCLK */ -#define LPC313X_CGU_ESR64_OFFSET 0x4a0 /* I2STX_IF_1_PCLK */ -#define LPC313X_CGU_ESR65_OFFSET 0x4a4 /* I2SRX_FIFO_0_PCLK */ -#define LPC313X_CGU_ESR66_OFFSET 0x4a8 /* I2SRX_IF_0_PCLK */ -#define LPC313X_CGU_ESR67_OFFSET 0x4ac /* I2SRX_FIFO_1_PCLK */ -#define LPC313X_CGU_ESR68_OFFSET 0x4b0 /* I2SRX_IF_1_PCLK */ -#define LPC313X_CGU_ESR69_OFFSET 0x4b4 /* Reserved */ -#define LPC313X_CGU_ESR70_OFFSET 0x4b8 /* Reserved */ -#define LPC313X_CGU_ESR71_OFFSET 0x4bc /* PCM_CLK_IP */ -#define LPC313X_CGU_ESR72_OFFSET 0x4c0 /* UART_U_CLK */ -#define LPC313X_CGU_ESR73_OFFSET 0x4c4 /* I2S_EDGE_DETECT_CLK */ -#define LPC313X_CGU_ESR74_OFFSET 0x4c8 /* R_I2STX_BCK0_N */ -#define LPC313X_CGU_ESR75_OFFSET 0x4cc /* I2STX_WS0 */ -#define LPC313X_CGU_ESR76_OFFSET 0x4d0 /* I2STX_CLK0 */ -#define LPC313X_CGU_ESR77_OFFSET 0x4d4 /* I2STX_IF_BCK1_N */ -#define LPC313X_CGU_ESR78_OFFSET 0x4d8 /* I2STX_WS1 */ -#define LPC313X_CGU_ESR79_OFFSET 0x4dc /* CLK_256FS */ -#define LPC313X_CGU_ESR80_OFFSET 0x4e0 /* I2SRX_BCK0_N */ -#define LPC313X_CGU_ESR81_OFFSET 0x4e4 /* I2SRX_WS0 */ -#define LPC313X_CGU_ESR82_OFFSET 0x4e8 /* I2SRX_BCK1_N */ -#define LPC313X_CGU_ESR83_OFFSET 0x4ec /* I2SRX_WS1 */ -#define LPC313X_CGU_ESR84_OFFSET 0x4f0 /* Reserved */ -#define LPC313X_CGU_ESR85_OFFSET 0x4f4 /* Reserved */ -#define LPC313X_CGU_ESR86_OFFSET 0x4f8 /* Reserved */ -#define LPC313X_CGU_ESR87_OFFSET 0x4fc /* SPI_CLK */ -#define LPC313X_CGU_ESR88_OFFSET 0x500 /* SPI_CLK_GATED */ - -/* Base control registers (BCR) for SYS base */ - -#define LPC313X_CGU_BCR_OFFSET(n) (0x504+((n)<<2)) -#define LPC313X_CGU_BCR0_OFFSET 0x504 /* SYS base */ -#define LPC313X_CGU_BCR1_OFFSET 0x508 /* AHB0_APB0 base */ -#define LPC313X_CGU_BCR2_OFFSET 0x50c /* AHB0_APB1 base */ -#define LPC313X_CGU_BCR3_OFFSET 0x510 /* AHB0_APB2 base */ -#define LPC313X_CGU_BCR7_OFFSET 0x514 /* CLK1024FS base */ - -/* Fractional divider configuration (FDC) registers */ - -#define LPC313X_CGU_FDC_OFFSET(n) (0x518+((n)<<2)) -#define LPC313X_CGU_FDC0_OFFSET 0x518 /* Fractional Divider 0 (SYS base) */ -#define LPC313X_CGU_FDC1_OFFSET 0x51c /* Fractional Divider 1 (SYS base) */ -#define LPC313X_CGU_FDC2_OFFSET 0x520 /* Fractional Divider 2 (SYS base) */ -#define LPC313X_CGU_FDC3_OFFSET 0x524 /* Fractional Divider 3 (SYS base) */ -#define LPC313X_CGU_FDC4_OFFSET 0x528 /* Fractional Divider 4 (SYS base) */ -#define LPC313X_CGU_FDC5_OFFSET 0x52c /* Fractional Divider 5 (SYS base) */ -#define LPC313X_CGU_FDC6_OFFSET 0x530 /* Fractional Divider 6 (SYS base) */ -#define LPC313X_CGU_FDC7_OFFSET 0x534 /* Fractional Divider 7 (AHB0_APB0 base) */ -#define LPC313X_CGU_FDC8_OFFSET 0x538 /* Fractional Divider 8 (AHB0_APB0 base) */ -#define LPC313X_CGU_FDC9_OFFSET 0x53c /* Fractional Divider 9 (AHB0_APB1 base) */ -#define LPC313X_CGU_FDC10_OFFSET 0x540 /* Fractional Divider 10 (AHB0_APB1 base) */ -#define LPC313X_CGU_FDC11_OFFSET 0x544 /* Fractional Divider 11 (AHB0_APB2 base) */ -#define LPC313X_CGU_FDC12_OFFSET 0x548 /* Fractional Divider 12 (AHB0_APB2 base) */ -#define LPC313X_CGU_FDC13_OFFSET 0x54c /* Fractional Divider 13 (AHB0_APB2 base) */ -#define LPC313X_CGU_FDC14_OFFSET 0x550 /* Fractional Divider 14 (AHB0_APB3 base) */ -#define LPC313X_CGU_FDC15_OFFSET 0x554 /* Fractional Divider 15 (PCM base) */ -#define LPC313X_CGU_FDC16_OFFSET 0x558 /* Fractional Divider 16 (UART base) */ -#define LPC313X_CGU_FDC17_OFFSET 0x55c /* Fractional Divider 17 (CLK1024FS base) */ -#define LPC313X_CGU_FDC18_OFFSET 0x560 /* Fractional Divider 18 (CLK1024FS base) */ -#define LPC313X_CGU_FDC19_OFFSET 0x564 /* Fractional Divider 19 (CLK1024FS base) */ -#define LPC313X_CGU_FDC20_OFFSET 0x568 /* Fractional Divider 20 (CLK1024FS base) */ -#define LPC313X_CGU_FDC21_OFFSET 0x56c /* Fractional Divider 21 (CLK1024FS base) */ -#define LPC313X_CGU_FDC22_OFFSET 0x570 /* Fractional Divider 22 (CLK1024FS base) */ -#define LPC313X_CGU_FDC23_OFFSET 0x574 /* Fractional Divider 23 (SPI_CLK base) */ - -/* Dynamic fractional divider configuration (DYNFDC) registers (SYS base only) */ - -#define LPC313X_CGU_DYNFDC_OFFSET(n) (0x578+((n)<<2)) -#define LPC313X_CGU_DYNFDC0_OFFSET 0x578 /* Fractional Divider 0 (SYS base) */ -#define LPC313X_CGU_DYNFDC1_OFFSET 0x57c /* Fractional Divider 1 (SYS base) */ -#define LPC313X_CGU_DYNFDC2_OFFSET 0x580 /* Fractional Divider 2 (SYS base) */ -#define LPC313X_CGU_DYNFDC3_OFFSET 0x584 /* Fractional Divider 3 (SYS base) */ -#define LPC313X_CGU_DYNFDC4_OFFSET 0x588 /* Fractional Divider 4 (SYS base) */ -#define LPC313X_CGU_DYNFDC5_OFFSET 0x58c /* Fractional Divider 5 (SYS base) */ -#define LPC313X_CGU_DYNFDC6_OFFSET 0x590 /* Fractional Divider 6 (SYS base) */ - -/* Dynamic fractional divider selection (DYNSEL) registers (SYS base only) */ - -#define LPC313X_CGU_DYNSEL_OFFSET(n) (0x594+((n)<<2)) -#define LPC313X_CGU_DYNSEL0_OFFSET 0x594 /* Fractional Divider 0 (SYS base) */ -#define LPC313X_CGU_DYNSEL1_OFFSET 0x598 /* Fractional Divider 1 (SYS base) */ -#define LPC313X_CGU_DYNSEL2_OFFSET 0x59c /* Fractional Divider 2 (SYS base) */ -#define LPC313X_CGU_DYNSEL3_OFFSET 0x5a0 /* Fractional Divider 3 (SYS base) */ -#define LPC313X_CGU_DYNSEL4_OFFSET 0x5a4 /* Fractional Divider 4 (SYS base) */ -#define LPC313X_CGU_DYNSEL5_OFFSET 0x5a8 /* Fractional Divider 5 (SYS base) */ -#define LPC313X_CGU_DYNSEL6_OFFSET 0x5ac /* Fractional Divider 6 (SYS base) */ - -/* CGU configuration register offsets (with respect to the CGU CFG register base) ***************/ -/* Power and oscillator control */ - -#define LPC313X_CGU_POWERMODE_OFFSET 0x000 /* Power mode register */ -#define LPC313X_CGU_WDBARK_OFFSET 0x004 /* Watch dog bark register */ -#define LPC313X_CGU_FFASTON_OFFSET 0x008 /* Activate fast oscillator register */ -#define LPC313X_CGU_FFASTBYP_OFFSET 0x00c /* Bypass comparator register fast oscillator reset */ - -/* Reset control */ - -#define LPC313X_CGU_SOFTRST_OFFSET(n) (0x010+((n)<<2)) -#define LPC313X_CGU_APB0RST_OFFSET 0x010 /* Reset AHB part of AHB_TO_APB0 bridge */ -#define LPC313X_CGU_AHB2APB0RST_OFFSET 0x014 /* Reset APB part of AHB_TO_APB0 bridge */ -#define LPC313X_CGU_APB1RST_OFFSET 0x018 /* Reset AHB part of AHB_TO_APB1 bridge */ -#define LPC313X_CGU_AHB2PB1RST_OFFSET 0x01c /* Reset APB part of AHB_TO_APB1 bridge */ -#define LPC313X_CGU_APB2RST_OFFSET 0x020 /* Reset AHB part of AHB_TO_APB2 bridge */ -#define LPC313X_CGU_AHB2APB2RST_OFFSET 0x024 /* Reset APB part of AHB_TO_APB2 bridge */ -#define LPC313X_CGU_APB3RST_OFFSET 0x028 /* Reset AHB part of AHB_TO_APB3 bridge */ -#define LPC313X_CGU_AHB2APB3RST_OFFSET 0x02c /* Reset APB part of AHB_TO_APB3 bridge */ -#define LPC313X_CGU_APB4RST_OFFSET 0x030 /* Reset AHB_TO_APB4 bridge */ -#define LPC313X_CGU_AHB2INTCRST_OFFSET 0x034 /* Reset AHB_TO_INTC */ -#define LPC313X_CGU_AHB0RST_OFFSET 0x038 /* Reset AHB0 */ -#define LPC313X_CGU_EBIRST_OFFSET 0x03c /* Reset EBI */ -#define LPC313X_CGU_PCMAPBRST_OFFSET 0x040 /* Reset APB domain of PCM */ -#define LPC313X_CGU_PCMCLKIPRST_OFFSET 0x044 /* Reset synchronous clk_ip domain of PCM */ -#define LPC313X_CGU_PCMRSTASYNC_OFFSET 0x048 /* Reset asynchronous clk_ip domain of PCM */ -#define LPC313X_CGU_TIMER0RST_OFFSET 0x04c /* Reset Timer0 */ -#define LPC313X_CGU_TIMER1RST_OFFSET 0x050 /* Reset Timer1 */ -#define LPC313X_CGU_TIMER2RST_OFFSET 0x054 /* Reset Timer2 */ -#define LPC313X_CGU_TIMER3RST_OFFSET 0x058 /* Reset Timer3 */ -#define LPC313X_CGU_ADCPRST_OFFSET 0x05c /* Reset controller of 10 bit ADC Interface */ -#define LPC313X_CGU_ADCRST_OFFSET 0x060 /* Reset A/D converter of ADC Interface */ -#define LPC313X_CGU_PWMRST_OFFSET 0x064 /* Reset PWM */ -#define LPC313X_CGU_UARTRST_OFFSET 0x068 /* Reset UART/IrDA */ -#define LPC313X_CGU_I2C0RST_OFFSET 0x06c /* Reset I2C0 */ -#define LPC313X_CGU_I2C1RST_OFFSET 0x070 /* Reset I2C1 */ -#define LPC313X_CGU_I2SCFGRST_OFFSET 0x074 /* Reset I2S_Config */ -#define LPC313X_CGU_I2SNSOFRST_OFFSET 0x078 /* Reset NSOF counter of I2S_CONFIG */ -#define LPC313X_CGU_EDGEDETRST_OFFSET 0x07c /* Reset Edge_det */ -#define LPC313X_CGU_I2STXFF0RST_OFFSET 0x080 /* Reset I2STX_FIFO_0 */ -#define LPC313X_CGU_I2STXIF0RST_OFFSET 0x084 /* Reset I2STX_IF_0 */ -#define LPC313X_CGU_I2STXFF1RST_OFFSET 0x088 /* Reset I2STX_FIFO_1 */ -#define LPC313X_CGU_I2STXIF1RST_OFFSET 0x08c /* Reset I2STX_IF_1 */ -#define LPC313X_CGU_I2SRXFF0RST_OFFSET 0x090 /* Reset I2SRX_FIFO_0 */ -#define LPC313X_CGU_I2SRXIF0RST_OFFSET 0x094 /* Reset I2SRX_IF_0 */ -#define LPC313X_CGU_I2SRXFF1RST_OFFSET 0x098 /* Reset I2SRX_FIFO_1 */ -#define LPC313X_CGU_I2SRXIF1RST_OFFSET 0x09c /* Reset I2SRX_IF_1 */ - /* 0x0a0 to 0x0b0: Reserved */ -#define LPC313X_CGU_LCDRST_OFFSET 0x0b4 /* Reset LCD Interface */ -#define LPC313X_CGU_SPIRSTAPB_OFFSET 0x0b8 /* Reset apb_clk domain of SPI */ -#define LPC313X_CGU_SPIRSTIP_OFFSET 0x0bc /* Reset ip_clk domain of SPI */ -#define LPC313X_CGU_DMARST_OFFSET 0x0c0 /* Reset DMA */ -#define LPC313X_CGU_NANDECCRST_OFFSET 0x0c4 /* Reset Nandflash Controller ECC clock */ - /* 0x0c8: Reserved */ -#define LPC313X_CGU_NANDCTRLRST_OFFSET 0x0cc /* Reset of Nandflash Controller */ -#define LPC313X_CGU_RNGRST_OFFSET 0x0d0 /* Reset of RNG */ -#define LPC313X_CGU_SDMMCRST_OFFSET 0x0d4 /* Reset MCI (on AHB clock) */ -#define LPC313X_CGU_SDMMCRSTCKIN_OFFSET 0x0d8 /* Reset MCI synchronous (on IP clock) */ -#define LPC313X_CGU_USBOTGAHBRST_OFFSET 0x0dc /* Reset USB_OTG */ -#define LPC313X_CGU_REDCTLRST_OFFSET 0x0e0 /* Reset Redundancy Controller */ -#define LPC313X_CGU_AHBMPMCHRST_OFFSET 0x0e4 /* Reset MPMC */ -#define LPC313X_CGU_AHBMPMCRFRST_OFFSET 0x0e8 /* Reset refresh generator used for MPMC */ -#define LPC313X_CGU_INTCRST_OFFSET 0x0ec /* Reset Interrupt Controller */ - -/* HP PLL controls */ - -#define LPC313x_CGU_HP0PLL_OFFSET 0x0f0 /* Base offset to HP0 PLL registers */ -#define LPC313x_CGU_HP1PLL_OFFSET 0x128 /* Base offset to HP1 PLL registers */ -#define CGU_HP0PLL 0 /* HP0 PLL selector */ -#define CGU_HP1PLL 1 /* HP1 PLL selector */ -#define LPC313x_CGU_HPPLL_OFFSET(n) ((n) ? LPC313x_CGU_HP1PLL_OFFSET : LPC313x_CGU_HP0PLL_OFFSET) - -#define LPC313X_CGU_HPFINSEL_OFFSET 0x000 /* Register for selecting input to high HPPLL0/1 */ -#define LPC313X_CGU_HPMDEC_OFFSET 0x004 /* M-divider register of HP0/1 PLL */ -#define LPC313X_CGU_HPNDEC_OFFSET 0x008 /* N-divider register of HP0/1 PLL */ -#define LPC313X_CGU_HPPDEC_OFFSET 0x00c /* P-divider register of HP0/1 PLL */ -#define LPC313X_CGU_HPMODE_OFFSET 0x010 /* Mode register of HP0/1 PLL */ -#define LPC313X_CGU_HPSTATUS_OFFSET 0x014 /* Status register of HP0/1 PLL */ -#define LPC313X_CGU_HPACK_OFFSET 0x018 /* Ratio change acknowledge register of HP0/1 PLL */ -#define LPC313X_CGU_HPREQ_OFFSET 0x01c /* Ratio change request register of HP0/1 PLL */ -#define LPC313X_CGU_HPINSELR_OFFSET 0x020 /* Bandwidth selection register of HP0/1 PLL */ -#define LPC313X_CGU_HPINSELI_OFFSET 0x024 /* Bandwidth selection register of HP0/1 PLL */ -#define LPC313X_CGU_HPINSELP_OFFSET 0x028 /* Bandwidth selection register of HP0/1 PLL */ -#define LPC313X_CGU_HPSELR_OFFSET 0x02c /* Bandwidth selection register of HP0/1 PLL */ -#define LPC313X_CGU_HPSELI_OFFSET 0x030 /* Bandwidth selection register of HP0/1 PLL */ -#define LPC313X_CGU_HPSELP_OFFSET 0x034 /* Bandwidth selection register of HP0/1 PLL */ - -/* HP0 PLL control (audio PLL) */ - -#define LPC313X_CGU_HP0FINSEL_OFFSET 0x0f0 /* Register for selecting input to high HPPLL0 */ -#define LPC313X_CGU_HP0MDEC_OFFSET 0x0f4 /* M-divider register of HP0 PLL */ -#define LPC313X_CGU_HP0NDEC_OFFSET 0x0f8 /* N-divider register of HP0 PLL */ -#define LPC313X_CGU_HP0PDEC_OFFSET 0x0fc /* P-divider register of HP0 PLL */ -#define LPC313X_CGU_HP0MODE_OFFSET 0x100 /* Mode register of HP0 PLL */ -#define LPC313X_CGU_HP0STATUS_OFFSET 0x104 /* Status register of HP0 PLL */ -#define LPC313X_CGU_HP0ACK_OFFSET 0x108 /* Ratio change acknowledge register of HP0 PLL */ -#define LPC313X_CGU_HP0REQ_OFFSET 0x10c /* Ratio change request register of HP0 PLL */ -#define LPC313X_CGU_HP0INSELR_OFFSET 0x110 /* Bandwidth selection register of HP0 PLL */ -#define LPC313X_CGU_HP0INSELI_OFFSET 0x114 /* Bandwidth selection register of HP0 PLL */ -#define LPC313X_CGU_HP0INSELP_OFFSET 0x118 /* Bandwidth selection register of HP0 PLL */ -#define LPC313X_CGU_HP0SELR_OFFSET 0x11c /* Bandwidth selection register of HP0 PLL */ -#define LPC313X_CGU_HP0SELI_OFFSET 0x120 /* Bandwidth selection register of HP0 PLL */ -#define LPC313X_CGU_HP0SELP_OFFSET 0x124 /* Bandwidth selection register of HP0 PLL */ - -/* HP1 PLL control (system PLL) */ - -#define LPC313X_CGU_HP1FINSEL_OFFSET 0x128 /* Register for selecting input to high HP1 PLL */ -#define LPC313X_CGU_HP1MDEC_OFFSET 0x12c /* M-divider register of HP1 PLL */ -#define LPC313X_CGU_HP1NDEC_OFFSET 0x130 /* N-divider register of HP1 PLL */ -#define LPC313X_CGU_HP1PDEC_OFFSET 0x134 /* P-divider register of HP1 PLL */ -#define LPC313X_CGU_HP1MODE_OFFSET 0x138 /* Mode register of HP1 PLL */ -#define LPC313X_CGU_HP1STATUS_OFFSET 0x13c /* Status register of HP1 PLL */ -#define LPC313X_CGU_HP1ACK_OFFSET 0x140 /* Ratio change acknowledge register of HP1 PLL */ -#define LPC313X_CGU_HP1REQ_OFFSET 0x144 /* Ratio change request register of HP1 PLL */ -#define LPC313X_CGU_HP1INSELR_OFFSET 0x148 /* Bandwidth selection register of HP1 PLL */ -#define LPC313X_CGU_HP1INSELI_OFFSET 0x14c /* Bandwidth selection register of HP1 PLL */ -#define LPC313X_CGU_HP1INSELP_OFFSET 0x150 /* Bandwidth selection register of HP1 PLL */ -#define LPC313X_CGU_HP1SELR_OFFSET 0x154 /* Bandwidth selection register of HP1 PLL */ -#define LPC313X_CGU_HP1SELI_OFFSET 0x158 /* Bandwidth selection register of HP1 PLL */ -#define LPC313X_CGU_HP1SELP_OFFSET 0x15c /* Bandwidth selection register of HP1 PLL */ - -/* CGU register (virtual) addresses *************************************************************/ -/* CGU clock switchbox (virtual) register addresses *********************************************/ -/* Switch configuration registers (SCR) for base clocks */ - -#define LPC313X_CGU_SCR(n) (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_SCR_OFFSET(n)) -#define LPC313X_CGU_SCR0 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_SCR0_OFFSET) -#define LPC313X_CGU_SCR1 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_SCR1_OFFSET) -#define LPC313X_CGU_SCR2 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_SCR2_OFFSET) -#define LPC313X_CGU_SCR3 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_SCR3_OFFSET) -#define LPC313X_CGU_SCR4 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_SCR4_OFFSET) -#define LPC313X_CGU_SCR5 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_SCR5_OFFSET) -#define LPC313X_CGU_SCR6 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_SCR6_OFFSET) -#define LPC313X_CGU_SCR7 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_SCR7_OFFSET) -#define LPC313X_CGU_SCR8 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_SCR8_OFFSET) -#define LPC313X_CGU_SCR9 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_SCR9_OFFSET) -#define LPC313X_CGU_SCR10 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_SCR10_OFFSET) -#define LPC313X_CGU_SCR11 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_SCR11_OFFSET) - -/* Frequency select (FS) registers 1 for base clocks */ - -#define LPC313X_CGU_FS1(n) (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_FS1_OFFSET(n)) -#define LPC313X_CGU_FS1_0 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_FS1_0_OFFSET) -#define LPC313X_CGU_FS1_1 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_FS1_1_OFFSET) -#define LPC313X_CGU_FS1_2 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_FS1_2_OFFSET) -#define LPC313X_CGU_FS1_3 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_FS1_3_OFFSET) -#define LPC313X_CGU_FS1_4 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_FS1_4_OFFSET) -#define LPC313X_CGU_FS1_5 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_FS1_5_OFFSET) -#define LPC313X_CGU_FS1_6 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_FS1_6_OFFSET) -#define LPC313X_CGU_FS1_7 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_FS1_7_OFFSET) -#define LPC313X_CGU_FS1_8 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_FS1_8_OFFSET) -#define LPC313X_CGU_FS1_9 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_FS1_9_OFFSET) -#define LPC313X_CGU_FS1_10 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_FS1_10_OFFSET) -#define LPC313X_CGU_FS1_11 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_FS1_11_OFFSET) - -/* Frequency select (FS) registers 2 for base clocks */ - -#define LPC313X_CGU_FS2(n) (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_FS2_OFFSET(n)) -#define LPC313X_CGU_FS2_0 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_FS2_0_OFFSET) -#define LPC313X_CGU_FS2_1 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_FS2_1_OFFSET) -#define LPC313X_CGU_FS2_2 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_FS2_2_OFFSET) -#define LPC313X_CGU_FS2_3 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_FS2_3_OFFSET) -#define LPC313X_CGU_FS2_4 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_FS2_4_OFFSET) -#define LPC313X_CGU_FS2_5 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_FS2_5_OFFSET) -#define LPC313X_CGU_FS2_6 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_FS2_6_OFFSET) -#define LPC313X_CGU_FS2_7 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_FS2_7_OFFSET) -#define LPC313X_CGU_FS2_8 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_FS2_8_OFFSET) -#define LPC313X_CGU_FS2_9 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_FS2_9_OFFSET) -#define LPC313X_CGU_FS2_10 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_FS2_10_OFFSET) -#define LPC313X_CGU_FS2_11 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_FS2_11_OFFSET) - -/* Switch status registers (SSR) for base clocks */ - -#define LPC313X_CGU_SSR(n) (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_SSR_OFFSET(n)) -#define LPC313X_CGU_SSR0 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_SSR0_OFFSET) -#define LPC313X_CGU_SSR1 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_SSR1_OFFSET) -#define LPC313X_CGU_SSR2 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_SSR2_OFFSET) -#define LPC313X_CGU_SSR3 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_SSR3_OFFSET) -#define LPC313X_CGU_SSR4 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_SSR4_OFFSET) -#define LPC313X_CGU_SSR5 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_SSR5_OFFSET) -#define LPC313X_CGU_SSR6 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_SSR6_OFFSET) -#define LPC313X_CGU_SSR7 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_SSR7_OFFSET) -#define LPC313X_CGU_SSR8 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_SSR8_OFFSET) -#define LPC313X_CGU_SSR9 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_SSR9_OFFSET) -#define LPC313X_CGU_SSR10 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_SSR10_OFFSET) -#define LPC313X_CGU_SSR11 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_SSR11_OFFSET) - -/* Power control registers (PCR), spreading stage */ - -#define LPC313X_CGU_PCR(n) (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_PCR_OFFSET(n)) -#define LPC313X_CGU_PCR0 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_PCR0_OFFSET) -#define LPC313X_CGU_PCR1 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_PCR1_OFFSET) -#define LPC313X_CGU_PCR2 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_PCR2_OFFSET) -#define LPC313X_CGU_PCR3 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_PCR3_OFFSET) -#define LPC313X_CGU_PCR4 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_PCR4_OFFSET) -#define LPC313X_CGU_PCR5 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_PCR5_OFFSET) -#define LPC313X_CGU_PCR6 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_PCR6_OFFSET) -#define LPC313X_CGU_PCR7 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_PCR7_OFFSET) -#define LPC313X_CGU_PCR8 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_PCR8_OFFSET) -#define LPC313X_CGU_PCR9 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_PCR9_OFFSET) -#define LPC313X_CGU_PCR10 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_PCR10_OFFSET) -#define LPC313X_CGU_PCR11 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_PCR11_OFFSET) -#define LPC313X_CGU_PCR12 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_PCR12_OFFSET) -#define LPC313X_CGU_PCR13 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_PCR13_OFFSET) -#define LPC313X_CGU_PCR14 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_PCR14_OFFSET) -#define LPC313X_CGU_PCR15 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_PCR15_OFFSET) -#define LPC313X_CGU_PCR16 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_PCR16_OFFSET) -#define LPC313X_CGU_PCR17 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_PCR17_OFFSET) -#define LPC313X_CGU_PCR18 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_PCR18_OFFSET) -#define LPC313X_CGU_PCR19 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_PCR19_OFFSET) -#define LPC313X_CGU_PCR20 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_PCR20_OFFSET) -#define LPC313X_CGU_PCR21 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_PCR21_OFFSET) -#define LPC313X_CGU_PCR22 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_PCR22_OFFSET) -#define LPC313X_CGU_PCR23 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_PCR23_OFFSET) -#define LPC313X_CGU_PCR24 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_PCR24_OFFSET) -#define LPC313X_CGU_PCR25 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_PCR25_OFFSET) -#define LPC313X_CGU_PCR26 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_PCR26_OFFSET) -#define LPC313X_CGU_PCR27 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_PCR27_OFFSET) -#define LPC313X_CGU_PCR28 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_PCR28_OFFSET) -#define LPC313X_CGU_PCR29 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_PCR29_OFFSET) -#define LPC313X_CGU_PCR30 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_PCR30_OFFSET) -#define LPC313X_CGU_PCR31 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_PCR31_OFFSET) -#define LPC313X_CGU_PCR32 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_PCR32_OFFSET) -#define LPC313X_CGU_PCR33 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_PCR33_OFFSET) -#define LPC313X_CGU_PCR34 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_PCR34_OFFSET) -#define LPC313X_CGU_PCR35 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_PCR35_OFFSET) -#define LPC313X_CGU_PCR36 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_PCR36_OFFSET) -#define LPC313X_CGU_PCR37 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_PCR37_OFFSET) -#define LPC313X_CGU_PCR38 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_PCR38_OFFSET) -#define LPC313X_CGU_PCR39 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_PCR39_OFFSET) -#define LPC313X_CGU_PCR40 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_PCR40_OFFSET) -#define LPC313X_CGU_PCR41 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_PCR41_OFFSET) -#define LPC313X_CGU_PCR42 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_PCR42_OFFSET) -#define LPC313X_CGU_PCR43 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_PCR43_OFFSET) -#define LPC313X_CGU_PCR44 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_PCR44_OFFSET) -#define LPC313X_CGU_PCR45 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_PCR45_OFFSET) -#define LPC313X_CGU_PCR46 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_PCR46_OFFSET) -#define LPC313X_CGU_PCR47 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_PCR47_OFFSET) -#define LPC313X_CGU_PCR48 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_PCR48_OFFSET) -#define LPC313X_CGU_PCR49 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_PCR49_OFFSET) -#define LPC313X_CGU_PCR50 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_PCR50_OFFSET) -#define LPC313X_CGU_PCR51 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_PCR51_OFFSET) -#define LPC313X_CGU_PCR52 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_PCR52_OFFSET) -#define LPC313X_CGU_PCR53 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_PCR53_OFFSET) -#define LPC313X_CGU_PCR54 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_PCR54_OFFSET) -#define LPC313X_CGU_PCR55 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_PCR55_OFFSET) -#define LPC313X_CGU_PCR56 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_PCR56_OFFSET) -#define LPC313X_CGU_PCR57 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_PCR57_OFFSET) -#define LPC313X_CGU_PCR58 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_PCR58_OFFSET) -#define LPC313X_CGU_PCR59 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_PCR59_OFFSET) -#define LPC313X_CGU_PCR60 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_PCR60_OFFSET) -#define LPC313X_CGU_PCR61 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_PCR61_OFFSET) -#define LPC313X_CGU_PCR62 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_PCR62_OFFSET) -#define LPC313X_CGU_PCR63 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_PCR63_OFFSET) -#define LPC313X_CGU_PCR64 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_PCR64_OFFSET) -#define LPC313X_CGU_PCR65 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_PCR65_OFFSET) -#define LPC313X_CGU_PCR66 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_PCR66_OFFSET) -#define LPC313X_CGU_PCR67 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_PCR67_OFFSET) -#define LPC313X_CGU_PCR68 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_PCR68_OFFSET) -#define LPC313X_CGU_PCR69 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_PCR69_OFFSET) -#define LPC313X_CGU_PCR70 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_PCR70_OFFSET) -#define LPC313X_CGU_PCR71 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_PCR71_OFFSET) -#define LPC313X_CGU_PCR72 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_PCR72_OFFSET) -#define LPC313X_CGU_PCR73 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_PCR73_OFFSET) -#define LPC313X_CGU_PCR74 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_PCR74_OFFSET) -#define LPC313X_CGU_PCR75 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_PCR75_OFFSET) -#define LPC313X_CGU_PCR76 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_PCR76_OFFSET) -#define LPC313X_CGU_PCR77 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_PCR77_OFFSET) -#define LPC313X_CGU_PCR78 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_PCR78_OFFSET) -#define LPC313X_CGU_PCR79 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_PCR79_OFFSET) -#define LPC313X_CGU_PCR80 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_PCR80_OFFSET) -#define LPC313X_CGU_PCR81 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_PCR81_OFFSET) -#define LPC313X_CGU_PCR82 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_PCR82_OFFSET) -#define LPC313X_CGU_PCR83 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_PCR83_OFFSET) -#define LPC313X_CGU_PCR84 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_PCR84_OFFSET) -#define LPC313X_CGU_PCR85 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_PCR85_OFFSET) -#define LPC313X_CGU_PCR86 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_PCR86_OFFSET) -#define LPC313X_CGU_PCR87 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_PCR87_OFFSET) -#define LPC313X_CGU_PCR88 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_PCR88_OFFSET) -#define LPC313X_CGU_PCR89 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_PCR89_OFFSET) -#define LPC313X_CGU_PCR90 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_PCR90_OFFSET) -#define LPC313X_CGU_PCR91 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_PCR91_OFFSET) - -/* Power status registers (PSR), spreading stage */ - -#define LPC313X_CGU_PSR(n) (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_PSR_OFFSET(n)) -#define LPC313X_CGU_PSR0 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_PSR0_OFFSET) -#define LPC313X_CGU_PSR1 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_PSR1_OFFSET) -#define LPC313X_CGU_PSR2 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_PSR2_OFFSET) -#define LPC313X_CGU_PSR3 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_PSR3_OFFSET) -#define LPC313X_CGU_PSR4 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_PSR4_OFFSET) -#define LPC313X_CGU_PSR5 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_PSR5_OFFSET) -#define LPC313X_CGU_PSR6 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_PSR6_OFFSET) -#define LPC313X_CGU_PSR7 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_PSR7_OFFSET) -#define LPC313X_CGU_PSR8 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_PSR8_OFFSET) -#define LPC313X_CGU_PSR9 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_PSR9_OFFSET) -#define LPC313X_CGU_PSR10 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_PSR10_OFFSET) -#define LPC313X_CGU_PSR11 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_PSR11_OFFSET) -#define LPC313X_CGU_PSR12 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_PSR12_OFFSET) -#define LPC313X_CGU_PSR13 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_PSR13_OFFSET) -#define LPC313X_CGU_PSR14 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_PSR14_OFFSET) -#define LPC313X_CGU_PSR15 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_PSR15_OFFSET) -#define LPC313X_CGU_PSR16 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_PSR16_OFFSET) -#define LPC313X_CGU_PSR17 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_PSR17_OFFSET) -#define LPC313X_CGU_PSR18 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_PSR18_OFFSET) -#define LPC313X_CGU_PSR19 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_PSR19_OFFSET) -#define LPC313X_CGU_PSR20 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_PSR20_OFFSET) -#define LPC313X_CGU_PSR21 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_PSR21_OFFSET) -#define LPC313X_CGU_PSR22 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_PSR22_OFFSET) -#define LPC313X_CGU_PSR23 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_PSR23_OFFSET) -#define LPC313X_CGU_PSR24 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_PSR24_OFFSET) -#define LPC313X_CGU_PSR25 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_PSR25_OFFSET) -#define LPC313X_CGU_PSR26 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_PSR26_OFFSET) -#define LPC313X_CGU_PSR27 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_PSR27_OFFSET) -#define LPC313X_CGU_PSR28 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_PSR28_OFFSET) -#define LPC313X_CGU_PSR29 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_PSR29_OFFSET) -#define LPC313X_CGU_PSR30 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_PSR30_OFFSET) -#define LPC313X_CGU_PSR31 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_PSR31_OFFSET) -#define LPC313X_CGU_PSR32 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_PSR32_OFFSET) -#define LPC313X_CGU_PSR33 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_PSR33_OFFSET) -#define LPC313X_CGU_PSR34 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_PSR34_OFFSET) -#define LPC313X_CGU_PSR35 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_PSR35_OFFSET) -#define LPC313X_CGU_PSR36 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_PSR36_OFFSET) -#define LPC313X_CGU_PSR37 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_PSR37_OFFSET) -#define LPC313X_CGU_PSR38 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_PSR38_OFFSET) -#define LPC313X_CGU_PSR39 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_PSR39_OFFSET) -#define LPC313X_CGU_PSR40 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_PSR40_OFFSET) -#define LPC313X_CGU_PSR41 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_PSR41_OFFSET) -#define LPC313X_CGU_PSR42 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_PSR42_OFFSET) -#define LPC313X_CGU_PSR43 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_PSR43_OFFSET) -#define LPC313X_CGU_PSR44 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_PSR44_OFFSET) -#define LPC313X_CGU_PSR45 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_PSR45_OFFSET) -#define LPC313X_CGU_PSR46 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_PSR46_OFFSET) -#define LPC313X_CGU_PSR47 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_PSR47_OFFSET) -#define LPC313X_CGU_PSR48 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_PSR48_OFFSET) -#define LPC313X_CGU_PSR49 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_PSR49_OFFSET) -#define LPC313X_CGU_PSR50 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_PSR50_OFFSET) -#define LPC313X_CGU_PSR51 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_PSR51_OFFSET) -#define LPC313X_CGU_PSR52 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_PSR52_OFFSET) -#define LPC313X_CGU_PSR53 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_PSR53_OFFSET) -#define LPC313X_CGU_PSR54 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_PSR54_OFFSET) -#define LPC313X_CGU_PSR55 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_PSR55_OFFSET) -#define LPC313X_CGU_PSR56 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_PSR56_OFFSET) -#define LPC313X_CGU_PSR57 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_PSR57_OFFSET) -#define LPC313X_CGU_PSR58 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_PSR58_OFFSET) -#define LPC313X_CGU_PSR59 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_PSR59_OFFSET) -#define LPC313X_CGU_PSR60 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_PSR60_OFFSET) -#define LPC313X_CGU_PSR61 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_PSR61_OFFSET) -#define LPC313X_CGU_PSR62 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_PSR62_OFFSET) -#define LPC313X_CGU_PSR63 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_PSR63_OFFSET) -#define LPC313X_CGU_PSR64 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_PSR64_OFFSET) -#define LPC313X_CGU_PSR65 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_PSR65_OFFSET) -#define LPC313X_CGU_PSR66 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_PSR66_OFFSET) -#define LPC313X_CGU_PSR67 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_PSR67_OFFSET) -#define LPC313X_CGU_PSR68 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_PSR68_OFFSET) -#define LPC313X_CGU_PSR69 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_PSR69_OFFSET) -#define LPC313X_CGU_PSR70 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_PSR70_OFFSET) -#define LPC313X_CGU_PSR71 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_PSR71_OFFSET) -#define LPC313X_CGU_PSR72 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_PSR72_OFFSET) -#define LPC313X_CGU_PSR73 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_PSR73_OFFSET) -#define LPC313X_CGU_PSR74 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_PSR74_OFFSET) -#define LPC313X_CGU_PSR75 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_PSR75_OFFSET) -#define LPC313X_CGU_PSR76 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_PSR76_OFFSET) -#define LPC313X_CGU_PSR77 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_PSR77_OFFSET) -#define LPC313X_CGU_PSR78 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_PSR78_OFFSET) -#define LPC313X_CGU_PSR79 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_PSR79_OFFSET) -#define LPC313X_CGU_PSR80 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_PSR80_OFFSET) -#define LPC313X_CGU_PSR81 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_PSR81_OFFSET) -#define LPC313X_CGU_PSR82 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_PSR82_OFFSET) -#define LPC313X_CGU_PSR83 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_PSR83_OFFSET) -#define LPC313X_CGU_PSR84 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_PSR84_OFFSET) -#define LPC313X_CGU_PSR85 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_PSR85_OFFSET) -#define LPC313X_CGU_PSR86 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_PSR86_OFFSET) -#define LPC313X_CGU_PSR87 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_PSR87_OFFSET) -#define LPC313X_CGU_PSR88 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_PSR88_OFFSET) -#define LPC313X_CGU_PSR89 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_PSR89_OFFSET) -#define LPC313X_CGU_PSR90 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_PSR90_OFFSET) -#define LPC313X_CGU_PSR91 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_PSR91_OFFSET) - -/* Enable select registers (ESR), spreading stage */ - -#define LPC313X_CGU_ESR(n) (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_ESR_OFFSET(n)) -#define LPC313X_CGU_ESR0 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_ESR0_OFFSET) -#define LPC313X_CGU_ESR1 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_ESR1_OFFSET) -#define LPC313X_CGU_ESR2 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_ESR2_OFFSET) -#define LPC313X_CGU_ESR3 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_ESR3_OFFSET) -#define LPC313X_CGU_ESR4 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_ESR4_OFFSET) -#define LPC313X_CGU_ESR5 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_ESR5_OFFSET) -#define LPC313X_CGU_ESR6 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_ESR6_OFFSET) -#define LPC313X_CGU_ESR7 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_ESR7_OFFSET) -#define LPC313X_CGU_ESR8 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_ESR8_OFFSET) -#define LPC313X_CGU_ESR9 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_ESR9_OFFSET) -#define LPC313X_CGU_ESR10 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_ESR10_OFFSET) -#define LPC313X_CGU_ESR11 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_ESR11_OFFSET) -#define LPC313X_CGU_ESR12 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_ESR12_OFFSET) -#define LPC313X_CGU_ESR13 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_ESR13_OFFSET) -#define LPC313X_CGU_ESR14 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_ESR14_OFFSET) -#define LPC313X_CGU_ESR15 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_ESR15_OFFSET) -#define LPC313X_CGU_ESR16 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_ESR16_OFFSET) -#define LPC313X_CGU_ESR17 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_ESR17_OFFSET) -#define LPC313X_CGU_ESR18 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_ESR18_OFFSET) -#define LPC313X_CGU_ESR19 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_ESR19_OFFSET) -#define LPC313X_CGU_ESR20 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_ESR20_OFFSET) -#define LPC313X_CGU_ESR21 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_ESR21_OFFSET) -#define LPC313X_CGU_ESR22 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_ESR22_OFFSET) -#define LPC313X_CGU_ESR23 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_ESR23_OFFSET) -#define LPC313X_CGU_ESR24 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_ESR24_OFFSET) -#define LPC313X_CGU_ESR25 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_ESR25_OFFSET) -#define LPC313X_CGU_ESR26 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_ESR26_OFFSET) -#define LPC313X_CGU_ESR27 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_ESR27_OFFSET) -#define LPC313X_CGU_ESR28 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_ESR28_OFFSET) -#define LPC313X_CGU_ESR29 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_ESR29_OFFSET) -#define LPC313X_CGU_ESR30 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_ESR30_OFFSET) -#define LPC313X_CGU_ESR31 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_ESR31_OFFSET) -#define LPC313X_CGU_ESR32 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_ESR32_OFFSET) -#define LPC313X_CGU_ESR33 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_ESR33_OFFSET) -#define LPC313X_CGU_ESR34 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_ESR34_OFFSET) -#define LPC313X_CGU_ESR35 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_ESR35_OFFSET) -#define LPC313X_CGU_ESR36 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_ESR36_OFFSET) -#define LPC313X_CGU_ESR37 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_ESR37_OFFSET) -#define LPC313X_CGU_ESR38 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_ESR38_OFFSET) -#define LPC313X_CGU_ESR39 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_ESR39_OFFSET) -#define LPC313X_CGU_ESR40 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_ESR40_OFFSET) -#define LPC313X_CGU_ESR41 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_ESR41_OFFSET) -#define LPC313X_CGU_ESR42 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_ESR42_OFFSET) -#define LPC313X_CGU_ESR43 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_ESR43_OFFSET) -#define LPC313X_CGU_ESR44 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_ESR44_OFFSET) -#define LPC313X_CGU_ESR45 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_ESR45_OFFSET) -#define LPC313X_CGU_ESR46 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_ESR46_OFFSET) -#define LPC313X_CGU_ESR47 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_ESR47_OFFSET) -#define LPC313X_CGU_ESR48 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_ESR48_OFFSET) -#define LPC313X_CGU_ESR49 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_ESR49_OFFSET) -#define LPC313X_CGU_ESR50 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_ESR50_OFFSET) -#define LPC313X_CGU_ESR51 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_ESR51_OFFSET) -#define LPC313X_CGU_ESR52 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_ESR52_OFFSET) -#define LPC313X_CGU_ESR53 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_ESR53_OFFSET) -#define LPC313X_CGU_ESR54 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_ESR54_OFFSET) -#define LPC313X_CGU_ESR55 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_ESR55_OFFSET) -#define LPC313X_CGU_ESR56 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_ESR56_OFFSET) -#define LPC313X_CGU_ESR57 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_ESR57_OFFSET) -#define LPC313X_CGU_ESR58 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_ESR58_OFFSET) -#define LPC313X_CGU_ESR59 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_ESR59_OFFSET) -#define LPC313X_CGU_ESR60 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_ESR60_OFFSET) -#define LPC313X_CGU_ESR61 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_ESR61_OFFSET) -#define LPC313X_CGU_ESR62 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_ESR62_OFFSET) -#define LPC313X_CGU_ESR63 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_ESR63_OFFSET) -#define LPC313X_CGU_ESR64 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_ESR64_OFFSET) -#define LPC313X_CGU_ESR65 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_ESR65_OFFSET) -#define LPC313X_CGU_ESR66 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_ESR66_OFFSET) -#define LPC313X_CGU_ESR67 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_ESR67_OFFSET) -#define LPC313X_CGU_ESR68 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_ESR68_OFFSET) -#define LPC313X_CGU_ESR69 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_ESR69_OFFSET) -#define LPC313X_CGU_ESR70 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_ESR70_OFFSET) -#define LPC313X_CGU_ESR71 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_ESR71_OFFSET) -#define LPC313X_CGU_ESR72 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_ESR72_OFFSET) -#define LPC313X_CGU_ESR73 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_ESR73_OFFSET) -#define LPC313X_CGU_ESR74 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_ESR74_OFFSET) -#define LPC313X_CGU_ESR75 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_ESR75_OFFSET) -#define LPC313X_CGU_ESR76 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_ESR76_OFFSET) -#define LPC313X_CGU_ESR77 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_ESR77_OFFSET) -#define LPC313X_CGU_ESR78 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_ESR78_OFFSET) -#define LPC313X_CGU_ESR79 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_ESR79_OFFSET) -#define LPC313X_CGU_ESR80 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_ESR80_OFFSET) -#define LPC313X_CGU_ESR81 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_ESR81_OFFSET) -#define LPC313X_CGU_ESR82 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_ESR82_OFFSET) -#define LPC313X_CGU_ESR83 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_ESR83_OFFSET) -#define LPC313X_CGU_ESR84 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_ESR84_OFFSET) -#define LPC313X_CGU_ESR85 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_ESR85_OFFSET) -#define LPC313X_CGU_ESR86 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_ESR86_OFFSET) -#define LPC313X_CGU_ESR87 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_ESR87_OFFSET) -#define LPC313X_CGU_ESR88 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_ESR88_OFFSET) - -/* Base control registers (BCR) for SYS base */ - -#define LPC313X_CGU_BCR(n) (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_BCR_OFFSET(n)) -#define LPC313X_CGU_BCR0 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_BCR0_OFFSET) -#define LPC313X_CGU_BCR1 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_BCR1_OFFSET) -#define LPC313X_CGU_BCR2 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_BCR2_OFFSET) -#define LPC313X_CGU_BCR3 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_BCR3_OFFSET) -#define LPC313X_CGU_BCR7 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_BCR7_OFFSET) - -/* Fractional divider configuration (FDC) registers */ - -#define LPC313X_CGU_FDC(n) (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_FDC_OFFSET(n)) -#define LPC313X_CGU_FDC0 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_FDC0_OFFSET) -#define LPC313X_CGU_FDC1 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_FDC1_OFFSET) -#define LPC313X_CGU_FDC2 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_FDC2_OFFSET) -#define LPC313X_CGU_FDC3 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_FDC3_OFFSET) -#define LPC313X_CGU_FDC4 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_FDC4_OFFSET) -#define LPC313X_CGU_FDC5 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_FDC5_OFFSET) -#define LPC313X_CGU_FDC6 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_FDC6_OFFSET) -#define LPC313X_CGU_FDC7 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_FDC7_OFFSET) -#define LPC313X_CGU_FDC8 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_FDC8_OFFSET) -#define LPC313X_CGU_FDC9 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_FDC9_OFFSET) -#define LPC313X_CGU_FDC10 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_FDC10_OFFSET) -#define LPC313X_CGU_FDC11 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_FDC11_OFFSET) -#define LPC313X_CGU_FDC12 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_FDC12_OFFSET) -#define LPC313X_CGU_FDC13 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_FDC13_OFFSET) -#define LPC313X_CGU_FDC14 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_FDC14_OFFSET) -#define LPC313X_CGU_FDC15 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_FDC15_OFFSET) -#define LPC313X_CGU_FDC16 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_FDC16_OFFSET) -#define LPC313X_CGU_FDC17 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_FDC17_OFFSET) -#define LPC313X_CGU_FDC18 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_FDC18_OFFSET) -#define LPC313X_CGU_FDC19 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_FDC19_OFFSET) -#define LPC313X_CGU_FDC20 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_FDC20_OFFSET) -#define LPC313X_CGU_FDC21 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_FDC21_OFFSET) -#define LPC313X_CGU_FDC22 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_FDC22_OFFSET) -#define LPC313X_CGU_FDC23 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_FDC23_OFFSET) - -/* Dynamic fractional divider configuration (DYNFDC) registers (SYS base only) */ - -#define LPC313X_CGU_DYNFDC(n) (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_DYNFDC_OFFSET(n)) -#define LPC313X_CGU_DYNFDC0 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_DYNFDC0_OFFSET) -#define LPC313X_CGU_DYNFDC1 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_DYNFDC1_OFFSET) -#define LPC313X_CGU_DYNFDC2 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_DYNFDC2_OFFSET) -#define LPC313X_CGU_DYNFDC3 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_DYNFDC3_OFFSET) -#define LPC313X_CGU_DYNFDC4 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_DYNFDC4_OFFSET) -#define LPC313X_CGU_DYNFDC5 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_DYNFDC5_OFFSET) -#define LPC313X_CGU_DYNFDC6 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_DYNFDC6_OFFSET) - -/* Dynamic fractional divider selection (DYNSEL) registers (SYS base only) */ - -#define LPC313X_CGU_DYNSEL(n) (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_DYNSEL_OFFSET(n)) -#define LPC313X_CGU_DYNSEL0 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_DYNSEL0_OFFSET) -#define LPC313X_CGU_DYNSEL1 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_DYNSEL1_OFFSET) -#define LPC313X_CGU_DYNSEL2 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_DYNSEL2_OFFSET) -#define LPC313X_CGU_DYNSEL3 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_DYNSEL3_OFFSET) -#define LPC313X_CGU_DYNSEL4 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_DYNSEL4_OFFSET) -#define LPC313X_CGU_DYNSEL5 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_DYNSEL5_OFFSET) -#define LPC313X_CGU_DYNSEL6 (LPC313X_CGU_CSB_VBASE+LPC313X_CGU_DYNSEL6_OFFSET) - -/* CGU configuration (virtural) register address ************************************************/ -/* Power and oscillator control */ - -#define LPC313X_CGU_POWERMODE (LPC313X_CGU_CFG_VBASE+LPC313X_CGU_POWERMODE_OFFSET) -#define LPC313X_CGU_WDBARK (LPC313X_CGU_CFG_VBASE+LPC313X_CGU_WDBARK_OFFSET) -#define LPC313X_CGU_FFASTON (LPC313X_CGU_CFG_VBASE+LPC313X_CGU_FFASTON_OFFSET) -#define LPC313X_CGU_FFASTBYP (LPC313X_CGU_CFG_VBASE+LPC313X_CGU_FFASTBYP_OFFSET) - -/* Reset control */ - -#define LPC313X_CGU_SOFTRST(n) (LPC313X_CGU_CFG_VBASE+LPC313X_CGU_SOFTRST_OFFSET(n)) -#define LPC313X_CGU_APB0RST (LPC313X_CGU_CFG_VBASE+LPC313X_CGU_APB0RST_OFFSET) -#define LPC313X_CGU_AHB2APB0RST (LPC313X_CGU_CFG_VBASE+LPC313X_CGU_AHB2APB0RST_OFFSET) -#define LPC313X_CGU_APB1RST (LPC313X_CGU_CFG_VBASE+LPC313X_CGU_APB1RST_OFFSET) -#define LPC313X_CGU_AHB2PB1RST (LPC313X_CGU_CFG_VBASE+LPC313X_CGU_AHB2PB1RST_OFFSET) -#define LPC313X_CGU_APB2RST (LPC313X_CGU_CFG_VBASE+LPC313X_CGU_APB2RST_OFFSET) -#define LPC313X_CGU_AHB2APB2RST (LPC313X_CGU_CFG_VBASE+LPC313X_CGU_AHB2APB2RST_OFFSET) -#define LPC313X_CGU_APB3RST (LPC313X_CGU_CFG_VBASE+LPC313X_CGU_APB3RST_OFFSET) -#define LPC313X_CGU_AHB2APB3RST (LPC313X_CGU_CFG_VBASE+LPC313X_CGU_AHB2APB3RST_OFFSET) -#define LPC313X_CGU_APB4RST (LPC313X_CGU_CFG_VBASE+LPC313X_CGU_APB4RST_OFFSET) -#define LPC313X_CGU_AHB2INTCRST (LPC313X_CGU_CFG_VBASE+LPC313X_CGU_AHB2INTCRST_OFFSET) -#define LPC313X_CGU_AHB0RST (LPC313X_CGU_CFG_VBASE+LPC313X_CGU_AHB0RST_OFFSET) -#define LPC313X_CGU_EBIRST (LPC313X_CGU_CFG_VBASE+LPC313X_CGU_EBIRST_OFFSET) -#define LPC313X_CGU_PCMAPBRST (LPC313X_CGU_CFG_VBASE+LPC313X_CGU_PCMAPBRST_OFFSET) -#define LPC313X_CGU_PCMCLKIPRST (LPC313X_CGU_CFG_VBASE+LPC313X_CGU_PCMCLKIPRST_OFFSET) -#define LPC313X_CGU_PCMRSTASYNC (LPC313X_CGU_CFG_VBASE+LPC313X_CGU_PCMRSTASYNC_OFFSET) -#define LPC313X_CGU_TIMER0RST (LPC313X_CGU_CFG_VBASE+LPC313X_CGU_TIMER0RST_OFFSET) -#define LPC313X_CGU_TIMER1RST (LPC313X_CGU_CFG_VBASE+LPC313X_CGU_TIMER1RST_OFFSET) -#define LPC313X_CGU_TIMER2RST (LPC313X_CGU_CFG_VBASE+LPC313X_CGU_TIMER2RST_OFFSET) -#define LPC313X_CGU_TIMER3RST (LPC313X_CGU_CFG_VBASE+LPC313X_CGU_TIMER3RST_OFFSET) -#define LPC313X_CGU_ADCPRST (LPC313X_CGU_CFG_VBASE+LPC313X_CGU_ADCPRST_OFFSET) -#define LPC313X_CGU_ADCRST (LPC313X_CGU_CFG_VBASE+LPC313X_CGU_ADCRST_OFFSET) -#define LPC313X_CGU_PWMRST (LPC313X_CGU_CFG_VBASE+LPC313X_CGU_PWMRST_OFFSET) -#define LPC313X_CGU_UARTRST (LPC313X_CGU_CFG_VBASE+LPC313X_CGU_UARTRST_OFFSET) -#define LPC313X_CGU_I2C0RST (LPC313X_CGU_CFG_VBASE+LPC313X_CGU_I2C0RST_OFFSET) -#define LPC313X_CGU_I2C1RST (LPC313X_CGU_CFG_VBASE+LPC313X_CGU_I2C1RST_OFFSET) -#define LPC313X_CGU_I2SCFGRST (LPC313X_CGU_CFG_VBASE+LPC313X_CGU_I2SCFGRST_OFFSET) -#define LPC313X_CGU_I2SNSOFRST (LPC313X_CGU_CFG_VBASE+LPC313X_CGU_I2SNSOFRST_OFFSET) -#define LPC313X_CGU_EDGEDETRST (LPC313X_CGU_CFG_VBASE+LPC313X_CGU_EDGEDETRST_OFFSET) -#define LPC313X_CGU_I2STXFF0RST (LPC313X_CGU_CFG_VBASE+LPC313X_CGU_I2STXFF0RST_OFFSET) -#define LPC313X_CGU_I2STXIF0RST (LPC313X_CGU_CFG_VBASE+LPC313X_CGU_I2STXIF0RST_OFFSET) -#define LPC313X_CGU_I2STXFF1RST (LPC313X_CGU_CFG_VBASE+LPC313X_CGU_I2STXFF1RST_OFFSET) -#define LPC313X_CGU_I2STXIF1RST (LPC313X_CGU_CFG_VBASE+LPC313X_CGU_I2STXIF1RST_OFFSET) -#define LPC313X_CGU_I2SRXFF0RST (LPC313X_CGU_CFG_VBASE+LPC313X_CGU_I2SRXFF0RST_OFFSET) -#define LPC313X_CGU_I2SRXIF0RST (LPC313X_CGU_CFG_VBASE+LPC313X_CGU_I2SRXIF0RST_OFFSET) -#define LPC313X_CGU_I2SRXFF1RST (LPC313X_CGU_CFG_VBASE+LPC313X_CGU_I2SRXFF1RST_OFFSET) -#define LPC313X_CGU_I2SRXIF1RST (LPC313X_CGU_CFG_VBASE+LPC313X_CGU_I2SRXIF1RST_OFFSET) -#define LPC313X_CGU_LCDRST (LPC313X_CGU_CFG_VBASE+LPC313X_CGU_LCDRST_OFFSET) -#define LPC313X_CGU_SPIRSTAPB (LPC313X_CGU_CFG_VBASE+LPC313X_CGU_SPIRSTAPB_OFFSET) -#define LPC313X_CGU_SPIRSTIP (LPC313X_CGU_CFG_VBASE+LPC313X_CGU_SPIRSTIP_OFFSET) -#define LPC313X_CGU_DMARST (LPC313X_CGU_CFG_VBASE+LPC313X_CGU_DMARST_OFFSET) -#define LPC313X_CGU_NANDECCRST (LPC313X_CGU_CFG_VBASE+LPC313X_CGU_NANDECCRST_OFFSET) -#define LPC313X_CGU_NANDCTRLRST (LPC313X_CGU_CFG_VBASE+LPC313X_CGU_NANDCTRLRST_OFFSET) -#define LPC313X_CGU_SDMMCRST (LPC313X_CGU_CFG_VBASE+LPC313X_CGU_SDMMCRST_OFFSET) -#define LPC313X_CGU_SDMMCRSTCKIN (LPC313X_CGU_CFG_VBASE+LPC313X_CGU_SDMMCRSTCKIN_OFFSET) -#define LPC313X_CGU_USBOTGAHBRST (LPC313X_CGU_CFG_VBASE+LPC313X_CGU_USBOTGAHBRST_OFFSET) -#define LPC313X_CGU_REDCTLRST (LPC313X_CGU_CFG_VBASE+LPC313X_CGU_REDCTLRST_OFFSET) -#define LPC313X_CGU_AHBMPMCHRST (LPC313X_CGU_CFG_VBASE+LPC313X_CGU_AHBMPMCHRST_OFFSET) -#define LPC313X_CGU_AHBMPMCRFRST (LPC313X_CGU_CFG_VBASE+LPC313X_CGU_AHBMPMCRFRST_OFFSET) -#define LPC313X_CGU_INTCRST (LPC313X_CGU_CFG_VBASE+LPC313X_CGU_INTCRST_OFFSET) - -/* HP PLL controls */ - -#define LPC313x_CGU_HP0PLL (LPC313X_CGU_CFG_VBASE+LPC313x_CGU_HP0PLL_OFFSET) -#define LPC313x_CGU_HP1PLL (LPC313X_CGU_CFG_VBASE+LPC313x_CGU_HP1PLL_OFFSET) -#define LPC313x_CGU_HPPLL(n) ((n) ? LPC313x_CGU_HP1PLL : LPC313x_CGU_HP0PLL) - -/* HPO PLL control (audio PLL) */ - -#define LPC313X_CGU_HP0FINSEL (LPC313X_CGU_CFG_VBASE+LPC313X_CGU_HP0FINSEL_OFFSET) -#define LPC313X_CGU_HP0MDEC (LPC313X_CGU_CFG_VBASE+LPC313X_CGU_HP0MDEC_OFFSET) -#define LPC313X_CGU_HP0NDEC (LPC313X_CGU_CFG_VBASE+LPC313X_CGU_HP0NDEC_OFFSET) -#define LPC313X_CGU_HP0PDEC (LPC313X_CGU_CFG_VBASE+LPC313X_CGU_HP0PDEC_OFFSET) -#define LPC313X_CGU_HP0MODE (LPC313X_CGU_CFG_VBASE+LPC313X_CGU_HP0MODE_OFFSET) -#define LPC313X_CGU_HP0STATUS (LPC313X_CGU_CFG_VBASE+LPC313X_CGU_HP0STATUS_OFFSET) -#define LPC313X_CGU_HP0ACK (LPC313X_CGU_CFG_VBASE+LPC313X_CGU_HP0ACK_OFFSET) -#define LPC313X_CGU_HP0REQ (LPC313X_CGU_CFG_VBASE+LPC313X_CGU_HP0REQ_OFFSET) -#define LPC313X_CGU_HP0INSELR (LPC313X_CGU_CFG_VBASE+LPC313X_CGU_HP0INSELR_OFFSET) -#define LPC313X_CGU_HP0INSELI (LPC313X_CGU_CFG_VBASE+LPC313X_CGU_HP0INSELI_OFFSET) -#define LPC313X_CGU_HP0INSELP (LPC313X_CGU_CFG_VBASE+LPC313X_CGU_HP0INSELP_OFFSET) -#define LPC313X_CGU_HP0SELR (LPC313X_CGU_CFG_VBASE+LPC313X_CGU_HP0SELR_OFFSET) -#define LPC313X_CGU_HP0SELI (LPC313X_CGU_CFG_VBASE+LPC313X_CGU_HP0SELI_OFFSET) -#define LPC313X_CGU_HP0SELP (LPC313X_CGU_CFG_VBASE+LPC313X_CGU_HP0SELP_OFFSET) - -/* HP1 PLL control (system PLL) */ - -#define LPC313X_CGU_HP1FINSEL (LPC313X_CGU_CFG_VBASE+LPC313X_CGU_HP1FINSEL_OFFSET) -#define LPC313X_CGU_HP1MDEC (LPC313X_CGU_CFG_VBASE+LPC313X_CGU_HP1MDEC_OFFSET) -#define LPC313X_CGU_HP1NDEC (LPC313X_CGU_CFG_VBASE+LPC313X_CGU_HP1NDEC_OFFSET) -#define LPC313X_CGU_HP1PDEC (LPC313X_CGU_CFG_VBASE+LPC313X_CGU_HP1PDEC_OFFSET) -#define LPC313X_CGU_HP1MODE (LPC313X_CGU_CFG_VBASE+LPC313X_CGU_HP1MODE_OFFSET) -#define LPC313X_CGU_HP1STATUS (LPC313X_CGU_CFG_VBASE+LPC313X_CGU_HP1STATUS_OFFSET) -#define LPC313X_CGU_HP1ACK (LPC313X_CGU_CFG_VBASE+LPC313X_CGU_HP1ACK_OFFSET) -#define LPC313X_CGU_HP1REQ (LPC313X_CGU_CFG_VBASE+LPC313X_CGU_HP1REQ_OFFSET) -#define LPC313X_CGU_HP1INSELR (LPC313X_CGU_CFG_VBASE+LPC313X_CGU_HP1INSELR_OFFSET) -#define LPC313X_CGU_HP1INSELI (LPC313X_CGU_CFG_VBASE+LPC313X_CGU_HP1INSELI_OFFSET) -#define LPC313X_CGU_HP1INSELP (LPC313X_CGU_CFG_VBASE+LPC313X_CGU_HP1INSELP_OFFSET) -#define LPC313X_CGU_HP1SELR (LPC313X_CGU_CFG_VBASE+LPC313X_CGU_HP1SELR_OFFSET) -#define LPC313X_CGU_HP1SELI (LPC313X_CGU_CFG_VBASE+LPC313X_CGU_HP1SELI_OFFSET) -#define LPC313X_CGU_HP1SELP (LPC313X_CGU_CFG_VBASE+LPC313X_CGU_HP1SELP_OFFSET) - -/* CGU register bit definitions *****************************************************************/ - -/* Frequency inputs */ - -#define CGU_FREQIN_FFAST 0 /* ffast 12 MHz */ -#define CGU_FREQIN_I2SRXBCK0 1 /* I2SRX_BCK0 */ -#define CGU_FREQIN_I2SRXWS0 2 /* I2SRX_WS0 */ -#define CGU_FREQIN_I2SRXBCK1 3 /* I2SRX_BCK1 */ -#define CGU_FREQIN_I2SRXWS1 4 /* I2SRX_WS1 */ -#define CGU_FREQIN_HPPLL0 5 /* HPPLL0 (Audio/I2S PLL) */ -#define CGU_FREQIN_HPPLL1 6 /* HPPLL1 (System PLL) */ -#define CGU_NFREQIN 7 - -/* CGU clock switchbox register bit definitions *************************************************/ - -/* Switch configuration register SCR0 to SCR11, addresses 0x13004000 to 0x1300402c */ - -#define CGU_SCR_STOP (1 << 3) /* Bit 3: Forces switch in disable mode */ -#define CGU_SCR_RESET (1 << 2) /* Bit 2: Asynchronous reset of both switches */ -#define CGU_SCR_ENF2 (1 << 1) /* Bit 1: Enable side #2 of switch */ -#define CGU_SCR_ENF1 (1 << 0) /* Bit 0: Enable side #1 of switch */ - -/* Frequency select register 1 FS1_0 to FS1_11, addresses 0x13004030 to 0x1300405c, - * Frequency Select register 2 FS2_0 to FS2_11, addresses 0x13004060 to 0x1300408c - */ - -#define CGU_FS_SHIFT (0) /* Bits 0-2: Selects input frequency for either side of frequency switch */ -#define CGU_FS_MASK (7 << CGU_FS_SHIFT) -# define CGU_FS_FFAST (CGU_FREQIN_FFAST << CGU_FS_SHIFT) /* ffast 12 MHz */ -# define CGU_FS_I2SRXBCK0 (CGU_FREQIN_I2SRXBCK0 << CGU_FS_SHIFT) /* I2SRX_BCK0 */ -# define CGU_FS_I2SRXWS0 (CGU_FREQIN_I2SRXWS0 << CGU_FS_SHIFT) /* I2SRX_WS0 */ -# define CGU_FS_I2SRXBCK1 (CGU_FREQIN_I2SRXBCK1 << CGU_FS_SHIFT) /* I2SRX_BCK1 */ -# define CGU_FS_I2SRXWS1 (CGU_FREQIN_I2SRXWS1 << CGU_FS_SHIFT) /* I2SRX_WS1 */ -# define CGU_FS_HPPLL0 (CGU_FREQIN_HPPLL0 << CGU_FS_SHIFT) /* HPPLL0 (Audio/I2S PLL) */ -# define CGU_FS_HPPLL1 (CGU_FREQIN_HPPLL1 << CGU_FS_SHIFT) /* HPPLL1 (System PLL) */ - -/* Switch Status register SSR0 to SSR11, addresses 0x13004090 to 0x1300 40bc */ - -#define CGU_SSR_FS_SHIFT (2) /* Bits 2-4: Feedback of current frequency selection */ -#define CGU_SSR_FS_MASK (7 << CGU_SSR_FS_SHIFT) -# define CGU_SSR_FFAST (CGU_FREQIN_FFAST << CGU_SSR_FS_SHIFT) /* ffast 12 MHz */ -# define CGU_SSR_I2SRXBCK0 (CGU_FREQIN_I2SRXBCK0 << CGU_SSR_FS_SHIFT) /* I2SRX_BCK0 */ -# define CGU_SSR_I2SRXWS0 (CGU_FREQIN_I2SRXWS0 << CGU_SSR_FS_SHIFT) /* I2SRX_WS0 */ -# define CGU_SSR_I2SRXBCK1 (CGU_FREQIN_I2SRXBCK1 << CGU_SSR_FS_SHIFT) /* I2SRX_BCK1 */ -# define CGU_SSR_I2SRXWS1 (CGU_FREQIN_I2SRXWS1 << CGU_SSR_FS_SHIFT) /* I2SRX_WS1 */ -# define CGU_SSR_HPPLL0 (CGU_FREQIN_HPPLL0 << CGU_SSR_FS_SHIFT) /* HPPLL0 (Audio/I2S PLL) */ -# define CGU_SSR_HPPLL1 (CGU_FREQIN_HPPLL1 << CGU_SSR_FS_SHIFT) /* HPPLL1 (System PLL) */ -#define CGU_SSR_FS2STAT (1 << 1) /* Bit 1: Enable side #2 of the frequency switch */ -#define CGU_SSR_FS1STAT (1 << 0) /* Bit 0: Enable side #1 of the frequency switch */ - -/* Power Control register PCR0 to PCR91, addresses 0x130040c0 to 0x1300422c */ - -#define CGU_PCR_ENOUTEN (1 << 4) /* Bit 4: Enable clock preview signal */ -#define CGU_PCR_EXTENEN (1 << 3) /* Bit 3: Enable external enabling */ -#define CGU_PCR_WAKEEN (1 << 2) /* Bit 2: Enable central wakeup */ -#define CGU_PCR_AUTO (1 << 1) /* Bit 1: Enable wakeup and external enable */ -#define CGU_PCR_RUN (1 << 0) /* Bit 0: Enable clocks */ - -/* Power Status register PSR0 to PSR91, addresses 0x13004230 to 0x1300439c */ - -#define CGU_PSR_WAKEUP (1 << 1) /* Bit 1: Clock wakeup condition */ -#define CGU_PSR_ACTIVE (1 << 0) /* Bit 0: Indicates clock is active */ - -/* Enable Select register ESR0 to ESR88, addresses 0x130043a0 to 0x13004500 */ -/* The ESR_SEL varies according to the selected clock */ - -#define CGU_ESR_ESRSEL_SHIFT (1) /* Bits 1-n: Common shift value */ -#define CGU_ESR0_29_ESRSEL_SHIFT (1) /* Bits 1-3: Selection of fractional dividers */ -#define CGU_ESR0_29_ESRSEL_MASK (7 << CGU_ESR0_29_ESRSEL_SHIFT) -# define CGU_ESR0_29_ESRSEL_FDC0 (0 << CGU_ESR0_29_ESRSEL_SHIFT) /* Selects FDC0 */ -# define CGU_ESR0_29_ESRSEL_FDC1 (1 << CGU_ESR0_29_ESRSEL_SHIFT) /* Selects FDC1 */ -# define CGU_ESR0_29_ESRSEL_FDC2 (2 << CGU_ESR0_29_ESRSEL_SHIFT) /* Selects FDC2 */ -# define CGU_ESR0_29_ESRSEL_FDC3 (3 << CGU_ESR0_29_ESRSEL_SHIFT) /* Selects FDC3 */ -# define CGU_ESR0_29_ESRSEL_FDC4 (4 << CGU_ESR0_29_ESRSEL_SHIFT) /* Selects FDC4 */ -# define CGU_ESR0_29_ESRSEL_FDC5 (5 << CGU_ESR0_29_ESRSEL_SHIFT) /* Selects FDC5 */ -# define CGU_ESR0_29_ESRSEL_FDC6 (6 << CGU_ESR0_29_ESRSEL_SHIFT) /* Selects FDC6 */ - -#define CGU_ESR30_39_ESRSEL_FDC7 (0) /* Bit 1=0 selects FDC7 */ -#define CGU_ESR30_39_ESRSEL_FDC8 (1 << 1) /* Bit 1=1 selects FDC8 */ - -#define CGU_ESR40_49_ESRSEL_FDC9 (0) /* Bit 1=0 selects FDC9 */ -#define CGU_ESR40_49_ESRSEL_FDC10 (1 << 1) /* Bit 1=1 selects FDC10 */ - -#define CGU_ESR50_57_ESRSEL_SHIFT (1) /* Bits 1-3: Selection of fractional dividers */ -#define CGU_ESR50_57_ESRSEL_MASK (3 << CGU_ESR50_57_ESRSEL_SHIFT) -# define CGU_ESR50_57_ESRSEL_FDC11 (0 << CGU_ESR50_57_ESRSEL_SHIFT) /* Selects FDC11 */ -# define CGU_ESR50_57_ESRSEL_FDC12 (1 << CGU_ESR50_57_ESRSEL_SHIFT) /* Selects FDC12 */ -# define CGU_ESR50_57_ESRSEL_FDC13 (2 << CGU_ESR50_57_ESRSEL_SHIFT) /* Selects FDC13 */ - -#define CGU_ESR58_70_ESRSEL_FDC14 (0) /* Only option */ -#define CGU_ESR71_ESRSEL_FDC15 (0) /* Only option */ -#define CGU_ESR72_ESRSEL_FDC16 (0) /* Only option */ - -#define CGU_ESR73_86_ESRSEL_SHIFT (1) /* Bits 1-3: Selection of fractional dividers */ -#define CGU_ESR73_86_ESRSEL_MASK (7 << CGU_ESR73_86_ESRSEL_SHIFT) -# define CGU_ESR73_86_ESRSEL_FDC17 (0 << CGU_ESR73_86_ESRSEL_SHIFT) /* Selects FDC17 */ -# define CGU_ESR73_86_ESRSEL_FDC18 (1 << CGU_ESR73_86_ESRSEL_SHIFT) /* Selects FDC18 */ -# define CGU_ESR73_86_ESRSEL_FDC19 (2 << CGU_ESR73_86_ESRSEL_SHIFT) /* Selects FDC19 */ -# define CGU_ESR73_86_ESRSEL_FDC20 (3 << CGU_ESR73_86_ESRSEL_SHIFT) /* Selects FDC20 */ -# define CGU_ESR73_86_ESRSEL_FDC21 (4 << CGU_ESR73_86_ESRSEL_SHIFT) /* Selects FDC21 */ -# define CGU_ESR73_86_ESRSEL_FDC22 (5 << CGU_ESR73_86_ESRSEL_SHIFT) /* Selects FDC22 */ - -#define CGU_ESR87_88_ESRSEL_FDC23 (0) /* Only option */ - -#define CGU_ESR_ESREN (1 << 0) /* Bit 0: Enable from FD selected by ESRSEL */ - -/* Base control registers 0 BCR0 to BCR7, addresses 0x13004504 to 0x13004514 */ - -#define CGU_BCR_FDRUN (1 << 0) /* Bit 0: Enable fractional dividers */ - -/* Fractional divider register 0 to 23 FDC0 to FDC23 (except FDC17) addresses 0x13004518 to 0x13004574 */ - -#define CGU_FDC_MSUB_SHIFT (11) /* Bits 11-18: Modulo subtraction value */ -#define CGU_FDC_MSUB_MASK (0x000000ff << CGU_FDC_MSUB_SHIFT) -#define CGU_FDC_MSUB_EXTEND (0xffffff00) -#define CGU_FDC_MADD_SHIFT (3) /* Bits 3-10: Modulo addition value */ -#define CGU_FDC_MADD_MASK (0x000000ff << CGU_FDC_MADD_SHIFT) -#define CGU_FDC_STRETCH (1 << 2) /* Bit 2: Enables the stretching option */ -#define CGU_FDC_RESET (1 << 1) /* Bit 1: Reset fractional divider */ -#define CGU_FDC_RUN (1 << 0) /* Bit 0: Enable fractional divider */ - -#define CGU_FDC17_MSUB_SHIFT (16) /* Bits 16-28: Modulo subtraction value */ -#define CGU_FDC17_MSUB_MASK (0x00001fff << CGU_FDC17_MSUB_SHIFT) -#define CGU_FDC17_MSUB_EXTEND (0xffffe000) -#define CGU_FDC17_MADD_SHIFT (3) /* Bits 3-15: Modulo addition value */ -#define CGU_FDC17_MADD_MASK (0x00001fff << CGU_FDC17_MADD_SHIFT) -#define CGU_FDC17_STRETCH (1 << 2) /* Bit 2: Enables the stretching option */ -#define CGU_FDC17_RESET (1 << 1) /* Bit 1: Reset fractional divider */ -#define CGU_FDC17_RUN (1 << 0) /* Bit 0: Enable fractional divider */ - -#define CGU_FDC_FIELDWIDTH 8 /* MSUB and MADD fields are 8-bits in width */ -#define CGU_FDC17_FIELDWIDTH 13 /* Exept for FDC17 which is 13-bits in width */ - -/* Dynamic Fractional Divider registers DYNFDC0 to DYNFDC6, addresses 0x13004578 to 0x13004590 */ - -#define CGU_DYNFDC_STOPAUTORST (1 << 19) /* Bit 19: Disable auto reset of fractional divider */ -#define CGU_DYNFDC_MSUB_SHIFT (11) /* Bits 11-18: Modulo subtraction value */ -#define CGU_DYNFDC_MSUB_MASK (255 << CGU_DYNFDC_MSUB_SHIFT) -#define CGU_DYNFDC_MADD_SHIFT (3) /* Bits 3-10: Modulo addition value */ -#define CGU_DYNFDC_MADD_MASK (255 << CGU_DYNFDC_MADD_SHIFT) -#define CGU_DYNFDC_STRETCH (1 << 2) /* Bit 2: Enables the stretching option */ -#define CGU_DYNFDC_ALLOW (1 << 1) /* Bit 1: Enable dynamic fractional divider */ -#define CGU_DYNFDC_RUN (1 << 0) /* Bit 0: Enable the fractional divider during low speeds */ - -/* Dynamic Fractional Divider Selection register DYNSEL0 to DYNSEL6, addresses 0x13004594 to 0x130045ac */ - -#define CGU_DYNSEL_MPMCREFRESHREQ (1 << 8) /* Bit 8: Ext SDRAM refresh can enable high speed */ -#define CGU_DYNSEL_ECCRAMBUSY (1 << 7) /* Bit 7: Hispeed mode during NAND ECC */ -#define CGU_DYNSEL_USBOTGMSTTRANS (1 << 6) /* Bit 6: USB OTG transfers can enable high speed */ -#define CGU_DYNSEL_ARM926LPDREADY (1 << 5) /* Bit 5: ARM926 data transfers can enable high-speed */ -#define CGU_DYNSEL_ARM926LPDTRANS (1 << 4) /* Bit 4: ARM926 data transfers can enable high-speed */ -#define CGU_DYNSEL_ARM926LPIREADY (1 << 3) /* Bit 3: ARM926 instr last transfers can enable high-speed */ -#define CGU_DYNSEL_ARM926LPITRANS (1 << 2) /* Bit 2: ARM926 instr transfers can enable high-speed */ -#define CGU_DYNSEL_DMAREADY (1 << 1) /* Bit 1: dma last transfers can enable high-speed */ -#define CGU_DYNSEL_DMATRANS (1 << 0) /* Bit 0: dma transfers can enable high-speed */ -#define CGU_DYNSEL_ALLBITS (0x1ff) - -/* CGU configuration register bit definitions ***************************************************/ -/* Power and oscillator control registers */ -/* Powermode register POWERMODE, address 0x13004c00 */ - -#define CGU_POWERMODE_SHIFT (0) /* Bits 0-1: Powermode */ -#define CGU_POWERMODE_MASK (3 << bb) -#define CGU_POWERMODE_NORMAL (1 << bb) /* Normal operational mode */ -#define CGU_POWERMODE_WAKEUP (3 << bb) /* Wakeup clocks disabled until wakeup event */ - -/* Watchdog Bark register WDBARK, address 0x13004c04 */ - -#define CGU_WDBARK_RESET (1 << 0) /* Bit 0: Set when a watchdog reset has occurred */ - -/* Fast Oscillator activate register FFASTON, 0x13004c08 */ - -#define CGU_FFASTON_ACTIVATE (1 << 0) /* Bit 0: Activate fast oscillator */ - -/* Fast Oscillator Bypass comparator register FFASTBYP, 0x13004c0c */ - -#define CGU_FFASTBYP_TESTMODE (1 << 0) /* Bit 0: Oscillator test mode */ - -/* Reset control registers */ - -#define CGU_SOFTRESET (1 << 0) /* Bit 0: in all of the reset control registers */ - -/* APB0_RESETN_SOFT register, address 0x13004c10 */ - -#define CGU_APB0RST_RESET (1 << 0) /* Bit 0: Reserved */ - -/* AHB_TO_APB0_PNRES_SOFT register, address 0x13004c14 */ - -#define CGU_AHB2APB0RST_RESET (1 << 0) /* Bit 0: Reserved */ - -/* APB1_RESETN_SOFT register, address 0x13004c18 */ - -#define CGU_APB1RST_RESET (1 << 0) /* Bit 0: Reset for AHB part of AHB_TO_APB1 bridge */ - -/* AHB_TO_APB1_PNRES_SOFT register, address 0x13004c1c */ - -#define CGU_AHB2PB1RST_RESET (1 << 0) /* Bit 0: Reset for APB part of AHB_TO_APB1 bridge */ - -/* APB2_RESETN_SOFT register, address 0x13004c20 */ - -#define CGU_APB2RST_RESET (1 << 0) /* Bit 0: Reset for AHB part of AHB_TO_APB2 bridge */ - -/* AHB_TO_APB2_PNRES_SOFT register, address 0x13004c24 */ - -#define CGU_AHB2APB2RST_RESET (1 << 0) /* Bit 0: Reset for APB part of AHB_TO_APB2 bridge */ - -/* APB3_RESETN_SOFT register, address 0x13004c28 */ - -#define CGU_APB3RST_RESET (1 << 0) /* Bit 0: Reset for AHB part of AHB_TO_APB3 bridge */ - -/* AHB_TO_APB3_PNRES_SOFT register, address 0x13004c2c */ - -#define CGU_AHB2APB3RST_RESET (1 << 0) /* Bit 0: Reset for APB part of AHB_TO_APB3 bridge */ - -/* APB4_RESETN_SOFT register, address 0x13004c30 */ - -#define CGU_APB4RST_RESET (1 << 0) /* Bit 0: Reset for AHB part of AHB_TO_APB4 bridge */ - -/* AHB_TO_INTC_RESETN_SOFT register, address 0x13004c34 */ - -#define CGU_AHB2INTCRST_RESET (1 << 0) /* Bit 0: Reset for AHB_TO_INTC */ - -/* AHB0_RESETN_SOFT register, address 0x13004c38 */ - -#define CGU_AHB0RST_RESET (1 << 0) /* Bit 0: Reserved */ - -/* EBI_RESETN_SOFT register, address 0x13004c2c */ - -#define CGU_EBIRST_RESET (1 << 0) /* Bit 0: Reset for EBI */ - -/* PCM_PNRES_SOFT UNIT register, address 0x13004c40 */ - -#define CGU_PCMAPBRST_RESET (1 << 0) /* Bit 0: Reset for APB domain of PCM */ - -/* PCM_RESET_N_SOFT register, address 0x13004c44 */ - -#define CGU_PCMCLKIPRST_RESET (1 << 0) /* Bit 0: Reset for synchronous clk_ip domain of PCM */ - -/* PCM_RESET_ASYNC_N_SOFT register, address 0x13004c48 */ - -#define CGU_PCMRSTASYNC_RESET (1 << 0) /* Bit 0: Reset for asynchronous clk_ip domain of PCM */ - -/* TIMER0_PNRES_SOFT register, address 0x13004c4c */ - -#define CGU_TIMER0RST_RESET (1 << 0) /* Bit 0: Reset for Timer0 */ - -/* TIMER1_PNRES_SOFT register, address 0x13004c50 */ - -#define CGU_TIMER1RST_RESET (1 << 0) /* Bit 0: Reset for Timer1 */ - -/* TIMER2_PNRES_SOFT register, address 0x13004c54 */ - -#define CGU_TIMER2RST_RESET (1 << 0) /* Bit 0: Reset for Timer2 */ - -/* TIMER3_PNRES_SOFT register, address 0x13004c58 */ - -#define CGU_TIMER3RST_RESET (1 << 0) /* Bit 0: Reset for Timer3 */ - -/* ADC_PRESETN_SOFT register, address 0x13004c5c */ - -#define CGU_ADCPRST_RESET (1 << 0) /* Bit 0: Reset for controller of 10 bit ADC Interface */ - -/* ADC_RESETN_ADC10BITS_SOFT register, address 0x1300 4c60 */ - -#define CGU_ADCRST_RESET (1 << 0) /* Bit 0: Reset for A/D converter of ADC Interface */ - -/* PWM_RESET_AN_SOFT register, address 0x13004c64 */ - -#define CGU_PWMRST_RESET (1 << 0) /* Bit 0: Reset for PWM */ - -/* UART_SYS_RST_AN_SOFT register, address 0x13004c68 */ - -#define CGU_UARTRST_RESET (1 << 0) /* Bit 0: Reset for UART/IrDA */ - -/* I2C0_PNRES_SOFT register, address 0x13004c6c */ - -#define CGU_I2C0RST_RESET (1 << 0) /* Bit 0: Reset for I2C0 */ - -/* I2C1_PNRES_SOFT register, address 0x13004c70 */ - -#define CGU_I2C1RST_RESET (1 << 0) /* Bit 0: Reset for I2C1 */ - -/* I2S_CFG_RST_N_SOFT register, address 0x13004c74 */ - -#define CGU_I2SCFGRST_RESET (1 << 0) /* Bit 0: Reset for I2S_Config */ - -/* I2S_NSOF_RST_N_SOFT register, address 0x13004c78 */ - -#define CGU_I2SNSOFRST_RESET (1 << 0) /* Bit 0: Reset for NSOF counter of I2S_CONFIG */ - -/* EDGE_DET_RST_N_SOFT register, address 0x13004c7c */ - -#define CGU_EDGEDETRST_RESET (1 << 0) /* Bit 0: Reset for Edge_det */ - -/* I2STX_FIFO_0_RST_N_SOFT register, address 0x13004c80 */ - -#define CGU_I2STXFF0RST_RESET (1 << 0) /* Bit 0: Reset for I2STX_FIFO_0 */ - -/* I2STX_IF_0_RST_N_SOFT register, address 0x13004c84 */ - -#define CGU_I2STXIF0RST_RESET (1 << 0) /* Bit 0: Reset for I2STX_IF_0 */ - -/* I2STX_FIFO_1_RST_N_SOFT register, address 0x13004c88 */ - -#define CGU_I2STXFF1RST_RESET (1 << 0) /* Bit 0: Reset for I2STX_FIFO_1 */ - -/* I2STX_IF_1_RST_N_SOFT register, address 0x13004c8c */ - -#define CGU_I2STXIF1RST_RESET (1 << 0) /* Bit 0: Reset for I2STX_IF_1 */ - -/* I2SRX_FIFO_0_RST_N_SOFT register, address 0x13004c90 */ - -#define CGU_I2SRXFF0RST_RESET (1 << 0) /* Bit 0: Reset for I2SRX_FIFO_0 */ - -/* I2SRX_IF_0_RST_N_SOFT register, address 0x13004c94 */ - -#define CGU_I2SRXIF0RST_RESET (1 << 0) /* Bit 0: Reset for I2SRX_IF_0 */ - -/* I2SRX_FIFO_1_RST_N_SOFT register, address 0x13004c98 */ - -#define CGU_I2SRXFF1RST_RESET (1 << 0) /* Bit 0: Reset for I2SRX_FIFO_1 */ - -/* I2SRX_IF_1_RST_N_SOFT register, address 0x13004c9c */ - -#define CGU_I2SRXIF1RST_RESET (1 << 0) /* Bit 0: Reset for I2SRX_IF_1 */ - -/* LCD_PNRES_SOFT register, address 0x13004cB4 */ - -#define CGU_LCDRST_RESET (1 << 0) /* Bit 0: Reset for LCD Interface */ - -/* SPI_PNRES_APB_SOFT register, address 0x13004cb8 */ - -#define CGU_SPIRSTAPB_RESET (1 << 0) /* Bit 0: Reset register for apb_clk domain of SPI */ - -/* SPI_PNRES_IP_SOFT register, address 0x13004cbc */ - -#define CGU_SPIRSTIP_RESET (1 << 0) /* Bit 0: Reset for ip_clk domain of SPI */ - -/* DMA_PNRES_SOFT register, address 0x13004cc0 */ - -#define CGU_DMARST_RESET (1 << 0) /* Bit 0: Reset for DMA */ - -/* NANDFLASH_CTRL_ECC_RESET_N_SOFT register, address 0x13004cc4 */ - -#define CGU_NANDECCRST_RESET (1 << 0) /* Bit 0: Reset for ECC clock domain of Nandflash Controller */ - -/* NANDFLASH_CTRL_NAND_RESET_N_SOFT register, address 0x13004ccc */ - -#define CGU_NANDCTRLRST_RESET (1 << 0) /* Bit 0: Reset for Nandflash Controller */ - -/* SD_MMC_PNRES_SOFT register, address 0x13004cd4 */ - -#define CGU_SDMMCRST_RESET (1 << 0) /* Bit 0: Reset for MCI synchronous with AHB clock */ - -/* SD_MMC_NRES_CCLK_IN_SOFT register, address 0x1300 4cd8 */ - -#define CGU_SDMMCRSTCKIN_RESET (1 << 0) /* Bit 0: Reset register for MCI synchronous with IP clock */ - -/* USB_OTG_AHB_RST_N_SOFT, address 0x13004cdc */ - -#define CGU_USBOTGAHBRST_RESET (1 << 0) /* Bit 0: Reset for USB_OTG */ - -/* RED_CTL_RESET_N_SOFT, address 0x13004ce0 */ - -#define CGU_REDCTLRST_RESET (1 << 0) /* Bit 0: Reset for Redundancy Controller */ - -/* AHB_MPMC_HRESETN_SOFT, address 0x13004ce4 */ - -#define CGU_AHBMPMCHRST_RESET (1 << 0) /* Bit 0: Reset for MPMC */ - -/* AHB_MPMC_REFRESH_RESETN_SOFT, address 0x13004ce8 */ - -#define CGU_AHBMPMCRFRST_RESET (1 << 0) /* Bit 0: Reset for refresh generator used for MPMC */ - -/* INTC_RESETN_SOFT, address 0x13004cec */ - -#define CGU_INTCRST_RESET (1 << 0) /* Bit 0: Reset for Interrupt Controller */ - -/* PLL control registers */ -/* HP0 Frequency Input Select register HP0_FIN_SELECT, address 0x13004cf0, - * HP1 Frequency Input Select register HP1_FIN_SELECT, address 0x13004d28 - */ - -#define CGU_HPFINSEL_SHIFT (0) /* Bits 0-3: Select input to high HPPLL0 */ -#define CGU_HPFINSEL_MASK (15 << CGU_HPFINSEL_SHIFT) -# define CGU_HPFINSEL_FFAST (CGU_FREQIN_FFAST << CGU_HPFINSEL_SHIFT) /* ffast (12 Mhz) */ -# define CGU_HPFINSEL_I2SRXBCK0 (CGU_FREQIN_I2SRXBCK0 << CGU_HPFINSEL_SHIFT) /* I2SRX_BCK0 */ -# define CGU_HPFINSEL_I2SRXWS0 (CGU_FREQIN_I2SRXWS0 << CGU_HPFINSEL_SHIFT) /* I2SRX_WS0 */ -# define CGU_HPFINSEL_I2SRXBCK1 (CGU_FREQIN_I2SRXBCK1 << CGU_HPFINSEL_SHIFT) /* I2SRX_BCK1 */ -# define CGU_HPFINSEL_I2SRXWS1 (CGU_FREQIN_I2SRXWS1 << CGU_HPFINSEL_SHIFT) /* I2SRX_WS1 */ -# define CGU_HPFINSEL_HP0FOUT (CGU_FREQIN_HPPLL0 << CGU_HPFINSEL_SHIFT) /* HP0_FOUT */ -# define CGU_HPFINSEL_HP1FOUT (CGU_FREQIN_HPPLL1 << CGU_HPFINSEL_SHIFT) /* HP1_FOUT */ - -/* HP0 M-divider register HP0_MDEC, address 0x13004cF4, - * HP1 M-divider register HP1_MDEC, address 0x13004d2C - */ - -#define CGU_HPMDEC_SHIFT (0) /* Bits 0-16: Decoded divider ratio for M-divider */ -#define CGU_HPMDEC_MASK (0x1ffff << CGU_HPMDEC_SHIFT) - -/* HP0 N-divider register HP0_NDEC, address 0x13004cf8, - * HP1 N-divider register HP1_NDEC, address 0x13004D30 - */ - -#define CGU_HPNDEC_SHIFT (0) /* Bits 0-9: Decoded divider ratio for N-divider */ -#define CGU_HPNDEC_MASK (0x3ff << CGU_HPNDEC_SHIFT) - -/* HP0 P-divider register HP0_PDEC, address 0x13004cfc. - * HP1 P-divider register HP1_PDEC, address 0x13004D34 - */ - -#define CGU_HPPDEC_SHIFT (0) /* Bits 0-6: Decoded divider ratio for P-divider */ -#define CGU_HPPDEC_MASK (0x7F << CGU_HPPDEC_SHIFT) - -/* HP0 Mode register HP0_MODE, address 0x13004d00, - * HP1 Mode register HP1_MODE, address 0x13004d38 - */ - -#define CGU_HPMODE_BYPASS (1 << 8) /* Bit 8: Bypass mode */ -#define CGU_HPMODE_LIMUPOFF (1 << 7) /* Bit 7: Up limiter */ -#define CGU_HPMODE_BANDSEL (1 << 6) /* Bit 6: Bandwidth adjustment pin */ -#define CGU_HPMODE_FRM (1 << 5) /* Bit 5: Free Running Mode */ -#define CGU_HPMODE_DIRECTI (1 << 4) /* Bit 4: Normal operation with DIRECTO */ -#define CGU_HPMODE_DIRECTO (1 << 3) /* Bit 3: Normal operation with DIRECTI */ -#define CGU_HPMODE_PD (1 << 2) /* Bit 2: Power down mode */ -#define CGU_HPMODE_SKEWEN (1 << 1) /* Bit 1: Skew mode */ -#define CGU_HPMODE_CLKEN (1 << 0) /* Bit 0: Enable mode */ - -/* HP0 Status register HP0_STATUS, address 0x13004d04, - * HP1 Status register HP1_STATUS, address 0x13004d3c - */ - -#define CGU_HPSTATUS_FR (1 << 1) /* Bit 1: Free running detector */ -#define CGU_HPSTATUS_LOCK (1 << 0) /* Bit 0: Lock detector */ - -/* HP0 Acknowledge register HP0_ACK, address 0x13004d08, - * HP1 Acknowledge register HP1_ACK, address 0x13004d40 - */ - -#define CGU_HPACK_P (1 << 2) /* Bit 2: Post-divider ratio change acknowledge */ -#define CGU_HPACK_N (1 << 1) /* Bit 1: Pre-divider ratio change acknowledge */ -#define CGU_HPACK_M (1 << 0) /* Bit 0: Feedback divider ratio change acknowledge */ - -/* HP0 request register HP0_REQ, address 0x13004d0c, - * HP1 Request register HP1_REQ, address 0x13004d44 - */ - -#define CGU_HPREQ_P (1 << 2) /* Bit 2: Post-divider ratio change request */ -#define CGU_HPREQ_N (1 << 1) /* Bit 1: Pre-divider ratio change request */ -#define CGU_HPREQ_M (1 << 0) /* Bit 0: Feedback divider ratio change request */ - -/* HP0 Bandwith Selection register HP0_INSELR, address 0x13004d10, - * HP1 bandwith Selection register HP1_INSELR, address 0x13004d48 - */ - -#define CGU_HPINSELR_SHIFT (0) /* Bits 0-3: Pins to select the bandwidth */ -#define CGU_HPINSELR_MASK (15 << CGU_HPINSELR_SHIFT) - -/* HP0 Bandwith Selection register HP0_INSELI, address 0x13004d14, - * HP1 bandwith Selection register HP1_INSELI, address 0x13004d4c - */ - -#define CGU_HPINSELI_SHIFT (0) /* Bits 0-5: Bandwidth selection register of HP0/1 PLL */ -#define CGU_HPINSELI_MASK (63 << CGU_HPINSELI_SHIFT) - - -/* HP0 Bandwith Selection register HP0_INSELP, address 0x13004d18, - * HP1 bandwith Selection register HP1_INSELP, address 0x13004d50 - */ - -#define CGU_HPINSELP_SHIFT (0) /* Bits 0-4: Bandwidth selection register of HP0/1 PLL */ -#define CGU_HPINSELP_MASK (31 << CGU_HPINSELP_SHIFT) - -/* HP0 Bandwith Selection register HP0_SELR, address 0x13004d1c, - * HP1 bandwith Selection register HP1_SELR, address 0x13004d54 - */ - -#define CGU_HPSELR_SHIFT (0) /* Bits 0-3: Bandwidth selection register of HP0/1 PLL */ -#define CGU_HPSELR_MASK (15 << CGU_HPSELR_SHIFT) - -/* HP0 Bandwith Selection register HP0_SELI, address 0x13004d20 - * HP1 bandwith Selection register HP1_SELI, address 0x13004d58 - */ - -#define CGU_HPSELI_SHIFT (0) /* Bits 0-5: Bandwidth selection register of HP0/1 PLL */ -#define CGU_HPSELI_MASK (63 << CGU_HPSELI_SHIFT) - -/* HP0 Bandwith Selection register HP0_SELP, address 0x13004d24, - * HP1 bandwith Selection register HP1_SELP, address 0x13004d5c - */ - -#define CGU_HPSELP_SHIFT (0) /* Bits 0-4: Bandwidth selection register of HP0/1 PLL */ -#define CGU_HPIELP_MASK (31 << CGU_HPSELP_SHIFT) - -/************************************************************************************************ - * Public Types - ************************************************************************************************/ - -#ifndef __ASSEMBLY__ - -/************************************************************************************************ - * Public Data - ************************************************************************************************/ - -/************************************************************************************************ - * Inline Functions - ************************************************************************************************/ - -/************************************************************************************************ - * Public Functions - ************************************************************************************************/ - -#endif /* __ASSEMBLY__ */ -#endif /* __ARCH_ARM_SRC_LPC313X_CGU_H */ diff --git a/nuttx/arch/arm/src/lpc313x/lpc313x_cgudrvr.h b/nuttx/arch/arm/src/lpc313x/lpc313x_cgudrvr.h deleted file mode 100755 index b728d2b2e..000000000 --- a/nuttx/arch/arm/src/lpc313x/lpc313x_cgudrvr.h +++ /dev/null @@ -1,819 +0,0 @@ -/************************************************************************ - * arch/arm/src/lpc313x/lpc313x_cgudrvr.h - * - * Copyright (C) 2009-2010 Gregory Nutt. All rights reserved. - * Author: Gregory Nutt - * - * References: - * - NXP UM10314 LPC3130/31 User manual Rev. 1.01 — 9 September 2009 - * - NXP lpc313x.cdl.drivers.zip example driver code - * - * 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_LPC313X_CGUDRVR_H -#define __ARCH_ARM_SRC_LPC313X_CGUDRVR_H - -/************************************************************************ - * Included Files - ************************************************************************/ - -#include - -#include -#include - -#include "up_arch.h" -#include "lpc313x_cgu.h" - -/************************************************************************ - * Pre-processor Definitions - ************************************************************************/ - -/* Maps a valid, x, relative to a base value, b, and converts that to a bit position */ - -#define _RBIT(x,b) (1<<((x)-(b))) - -/* Clock ID ranges (see enum lpc313x_clockid_e) *************************************************/ - -#define CLKID_FIRST CLKID_APB0CLK -#define CLKID_SYSBASE_FIRST CLKID_APB0CLK /* Domain 0: SYS_BASE */ -#define CLKID_SYSBASE_LAST CLKID_INTCCLK -#define _D0B(id) _RBIT(id,CLKID_SYSBASE_FIRST) - -#define CLKID_AHB0APB0_FIRST CLKID_AHB2APB0PCLK /* Domain 1: AHB0APB0_BASE */ -#define CLKID_AHB0APB0_LAST CLKID_RNGPCLK -#define _D1B(id) _RBIT(id,CLKID_AHB0APB0_FIRST) - -#define CLKID_AHB0APB1_FIRST CLKID_AHB2APB1PCLK /* Domain 2: AHB0APB1_BASE */ -#define CLKID_AHB0APB1_LAST CLKID_I2C1PCLK -#define _D2B(id) _RBIT(id,CLKID_AHB0APB1_FIRST) - -#define CLKID_AHB0APB2_FIRST CLKID_AHB2APB2PCLK /* Domain 3: AHB0APB2_BASE */ -#define CLKID_AHB0APB2_LAST CLKID_SPIPCLKGATED -#define _D3B(id) _RBIT(id,CLKID_AHB0APB2_FIRST) - -#define CLKID_AHB0APB3_FIRST CLKID_AHB2APB3PCLK /* Domain 4: AHB0APB3_BASE */ -#define CLKID_AHB0APB3_LAST CLKID_RESERVED70 -#define _D4B(id) _RBIT(id,CLKID_AHB0APB3_FIRST) - -#define CLKID_PCM_FIRST CLKID_PCMCLKIP /* Domain 5: PCM_BASE */ -#define CLKID_PCM_LAST CLKID_PCMCLKIP -#define _D5B(id) _RBIT(id,CLKID_PCM_FIRST) - -#define CLKID_UART_FIRST CLKID_UARTUCLK /* Domain 6: UART_BASE */ -#define CLKID_UART_LAST CLKID_UARTUCLK -#define _D6B(id) _RBIT(id,CLKID_UART_FIRST) - -#define CLKID_CLK1024FS_FIRST CLKID_I2SEDGEDETECTCLK /* Domain 7: CLK1024FS_BASE */ -#define CLKID_CLK1024FS_LAST CLKID_RESERVED86 -#define _D7B(id) _RBIT(id,CLKID_CLK1024FS_FIRST) - -#define CLKID_I2SRXBCK0_FIRST CLKID_I2SRXBCK0 /* Domain 8: BCK0_BASE */ -#define CLKID_I2SRXBCK0_LAST CLKID_I2SRXBCK0 -#define _D8B(id) _RBIT(id,CLKID_I2SRXBCK0_FIRST) - -#define CLKID_I2SRXBCK1_FIRST CLKID_I2SRXBCK1 /* Domain 9: BCK1_BASE */ -#define CLKID_I2SRXBCK1_LAST CLKID_I2SRXBCK1 -#define _D9B(id) _RBIT(id,CLKID_SYSBASE_FIRST) - -#define CLKID_SPI_FIRST CLKID_SPICLK /* Domain 10: SPI_BASE */ -#define CLKID_SPI_LAST CLKID_SPICLKGATED -#define _D10B(id) _RBIT(id,CLKID_I2SRXBCK1_FIRST) - -#define CLKID_SYSCLKO_FIRST CLKID_SYSCLKO /* Domain 11: SYSCLKO_BASE */ -#define CLKID_SYSCLKO_LAST CLKID_SYSCLKO -#define _D11B(id) _RBIT(id,CLKID_SYSCLKO_FIRST) -#define CLKID_LAST CLKID_SYSCLKO - -#define CGU_NDOMAINS 12 /* The number of clock domains */ -#define CLKID_INVALIDCLK -1 /* Indicates and invalid clock ID */ -#define DOMAINID_INVALID -1 /* Indicates an invalid domain ID */ -#define ESRNDX_INVALID -1 /* Indicates an invalid ESR register index */ -#define BCRNDX_INVALID -1 /* Indicates an invalid BCR register index */ - -/* There are 24 fractional dividers, indexed 0 to 23. The following definitions - * provide (1) the number of fractional dividers available for each base frequency, - * (2) start and end indices, and (3) extraction info for sub elements from the - * fractional divider configuration register - */ - -#define FRACDIV_BASE0_CNT 7 /* 7 fractional dividers available */ -#define FRACDIV_BASE0_LOW 0 /* First is index 0 */ -#define FRACDIV_BASE0_HIGH 6 /* Last is index 6 */ -#define FRACDIV_BASE0_FDIV0W 8 - -#define FRACDIV_BASE1_CNT 2 /* 2 fractional dividers available */ -#define FRACDIV_BASE1_LOW 7 /* First is index 7 */ -#define FRACDIV_BASE1_HIGH 8 /* Last is index 8 */ -#define FRACDIV_BASE1_FDIV0W 8 - -#define FRACDIV_BASE2_CNT 2 /* 2 fractional dividers available */ -#define FRACDIV_BASE2_LOW 9 /* First is index 9 */ -#define FRACDIV_BASE2_HIGH 10 /* Last is index 10 */ -#define FRACDIV_BASE2_FDIV0W 8 - -#define FRACDIV_BASE3_CNT 3 /* 3 fractional dividers available */ -#define FRACDIV_BASE3_LOW 11 /* First is index 11 */ -#define FRACDIV_BASE3_HIGH 13 /* Last is index 12 */ -#define FRACDIV_BASE3_FDIV0W 8 - -#define FRACDIV_BASE4_CNT 1 /* 1 fractional divider available */ -#define FRACDIV_BASE4_LOW 14 /* First is index 14 */ -#define FRACDIV_BASE4_HIGH 14 /* Last is index 14 */ -#define FRACDIV_BASE4_FDIV0W 8 - -#define FRACDIV_BASE5_CNT 1 /* 1 fractional divider available */ -#define FRACDIV_BASE5_LOW 15 /* First is index 15 */ -#define FRACDIV_BASE5_HIGH 15 /* Last is index 15 */ -#define FRACDIV_BASE5_FDIV0W 8 - -#define FRACDIV_BASE6_CNT 1 /* 1 fractional divider available */ -#define FRACDIV_BASE6_LOW 16 /* First is index 16 */ -#define FRACDIV_BASE6_HIGH 16 /* Last is index 16 */ -#define FRACDIV_BASE6_FDIV0W 8 - -#define FRACDIV_BASE7_CNT 6 /* 6 fractional dividers available */ -#define FRACDIV_BASE7_LOW 17 /* First is index 17 */ -#define FRACDIV_BASE7_HIGH 22 /* Last is index 22 */ -#define FRACDIV_BASE7_FDIV0W 13 - -#define FRACDIV_BASE8_CNT 0 /* No fractional divider available */ -#define FRACDIV_BASE9_CNT 0 /* No fractional divider available */ - -#define FRACDIV_BASE10_CNT 1 /* 1 fractional divider available */ -#define FRACDIV_BASE10_LOW 23 /* First is index 23 */ -#define FRACDIV_BASE10_HIGH 23 /* Last is index 23 */ -#define FRACDIV_BASE10_FDIV0W 8 - -#define FRACDIV_BASE11_CNT 0 /* No fractional divider available */ - -#define CGU_NFRACDIV 24 /* Number of fractional dividers: 0-23 */ -#define CGU_NDYNFRACDIV 7 /* Number of dynamic fractional dividers: 0-6 */ -#define FDCNDX_INVALID -1 /* Indicates an invalid fractional - * divider index */ - -/************************************************************************ - * Public Types - ************************************************************************/ - -#ifndef __ASSEMBLY__ -#ifdef __cplusplus -#define EXTERN extern "C" -extern "C" { -#else -#define EXTERN extern -#endif - -/* Clock domains */ - -enum lpc313x_domainid_e -{ - DOMAINID_SYS = 0, /* Domain 0: SYS_BASE */ - DOMAINID_AHB0APB0, /* Domain 1: AHB0APB0_BASE */ - DOMAINID_AHB0APB1, /* Domain 2: AHB0APB1_BASE */ - DOMAINID_AHB0APB2, /* Domain 3: AHB0APB2_BASE */ - DOMAINID_AHB0APB3, /* Domain 4: AHB0APB3_BASE */ - DOMAINID_PCM, /* Domain 5: PCM_BASE */ - DOMAINID_UART, /* Domain 6: UART_BASE */ - DOMAINID_CLK1024FS, /* Domain 7: CLK1024FS_BASE */ - DOMAINID_BCK0, /* Domain 8: BCK0_BASE */ - DOMAINID_BCK1, /* Domain 9: BCK1_BASE */ - DOMAINID_SPI, /* Domain 10: SPI_BASE */ - DOMAINID_SYSCLKO /* Domain 11: SYSCLKO_BASE */ -}; - -/* Clock IDs -- These are indices must correspond to the register - * offsets in lpc313x_cgu.h - */ - -enum lpc313x_clockid_e -{ - /* Domain 0: SYS_BASE */ - - CLKID_APB0CLK = 0, /* 0 APB0_CLK */ - CLKID_APB1CLK, /* 1 APB1_CLK */ - CLKID_APB2CLK, /* 2 APB2_CLK */ - CLKID_APB3CLK, /* 3 APB3_CLK */ - CLKID_APB4CLK, /* 4 APB4_CLK */ - CLKID_AHB2INTCCLK, /* 5 AHB_TO_INTC_CLK */ - CLKID_AHB0CLK, /* 6 AHB0_CLK */ - CLKID_EBICLK, /* 7 EBI_CLK */ - CLKID_DMAPCLK, /* 8 DMA_PCLK */ - CLKID_DMACLKGATED, /* 9 DMA_CLK_GATED */ - CLKID_NANDFLASHS0CLK, /* 10 NANDFLASH_S0_CLK */ - CLKID_NANDFLASHECCCLK, /* 11 NANDFLASH_ECC_CLK */ - CLKID_NANDFLASHAESCLK, /* 12 NANDFLASH_AES_CLK (Reserved on LPC313x) */ - CLKID_NANDFLASHNANDCLK, /* 13 NANDFLASH_NAND_CLK */ - CLKID_NANDFLASHPCLK, /* 14 NANDFLASH_PCLK */ - CLKID_CLOCKOUT, /* 15 CLOCK_OUT */ - CLKID_ARM926CORECLK, /* 16 ARM926_CORE_CLK */ - CLKID_ARM926BUSIFCLK, /* 17 ARM926_BUSIF_CLK */ - CLKID_ARM926RETIMECLK, /* 18 ARM926_RETIME_CLK */ - CLKID_SDMMCHCLK, /* 19 SD_MMC_HCLK */ - CLKID_SDMMCCCLKIN, /* 20 SD_MMC_CCLK_IN */ - CLKID_USBOTGAHBCLK, /* 21 USB_OTG_AHB_CLK */ - CLKID_ISRAM0CLK, /* 22 ISRAM0_CLK */ - CLKID_REDCTLRSCLK, /* 23 RED_CTL_RSCLK */ - CLKID_ISRAM1CLK, /* 24 ISRAM1_CLK (LPC313x only) */ - CLKID_ISROMCLK, /* 25 ISROM_CLK */ - CLKID_MPMCCFGCLK, /* 26 MPMC_CFG_CLK */ - CLKID_MPMCCFGCLK2, /* 27 MPMC_CFG_CLK2 */ - CLKID_MPMCCFGCLK3, /* 28 MPMC_CFG_CLK3 */ - CLKID_INTCCLK, /* 29 INTC_CLK */ - - /* Domain 1: AHB0APB0_BASE */ - - CLKID_AHB2APB0PCLK, /* 30 AHB_TO_APB0_PCLK */ - CLKID_EVENTROUTERPCLK, /* 31 EVENT_ROUTER_PCLK */ - CLKID_ADCPCLK, /* 32 ADC_PCLK */ - CLKID_ADCCLK, /* 33 ADC_CLK */ - CLKID_WDOGPCLK, /* 34 WDOG_PCLK */ - CLKID_IOCONFPCLK, /* 35 IOCONF_PCLK */ - CLKID_CGUPCLK, /* 36 CGU_PCLK */ - CLKID_SYSCREGPCLK, /* 37 SYSCREG_PCLK */ - CLKID_OTPPCLK, /* 38 OTP_PCLK (Reserved on LPC313X) */ - CLKID_RNGPCLK, /* 39 RNG_PCLK */ - - /* Domain 2: AHB0APB1_BASE */ - - CLKID_AHB2APB1PCLK, /* 40 AHB_TO_APB1_PCLK */ - CLKID_TIMER0PCLK, /* 41 TIMER0_PCLK */ - CLKID_TIMER1PCLK, /* 42 TIMER1_PCLK */ - CLKID_TIMER2PCLK, /* 43 TIMER2_PCLK */ - CLKID_TIMER3PCLK, /* 44 TIMER3_PCLK */ - CLKID_PWMPCLK, /* 45 PWM_PCLK */ - CLKID_PWMPCLKREGS, /* 46 PWM_PCLK_REGS */ - CLKID_PWMCLK, /* 47 PWM_CLK */ - CLKID_I2C0PCLK, /* 48 I2C0_PCLK */ - CLKID_I2C1PCLK, /* 49 I2C1_PCLK */ - - /* Domain 3: AHB0APB2_BASE */ - - CLKID_AHB2APB2PCLK, /* 50 AHB_TO_APB2_PCLK */ - CLKID_PCMPCLK, /* 51 PCM_PCLK */ - CLKID_PCMAPBPCLK, /* 52 PCM_APB_PCLK */ - CLKID_UARTAPBCLK, /* 53 UART_APB_CLK */ - CLKID_LCDPCLK, /* 54 LCD_PCLK */ - CLKID_LCDCLK, /* 55 LCD_CLK */ - CLKID_SPIPCLK, /* 56 SPI_PCLK */ - CLKID_SPIPCLKGATED, /* 57 SPI_PCLK_GATED */ - - /* Domain 4: AHB0APB3BASE */ - CLKID_AHB2APB3PCLK, /* 58 AHB_TO_APB3_PCLK */ - CLKID_I2SCFGPCLK, /* 59 I2S_CFG_PCLK */ - CLKID_EDGEDETPCLK, /* 60 EDGE_DET_PCLK */ - CLKID_I2STXFIFO0PCLK, /* 61 I2STX_FIFO_0_PCLK */ - CLKID_I2STXIF0PCLK, /* 62 I2STX_IF_0_PCLK */ - CLKID_I2STXFIFO1PCLK, /* 63 I2STX_FIFO_1_PCLK */ - CLKID_I2STXIF1PCLK, /* 64 I2STX_IF_1_PCLK */ - CLKID_I2SRXFIFO0PCLK, /* 65 I2SRX_FIFO_0_PCLK */ - CLKID_I2SRXIF0PCLK, /* 66 I2SRX_IF_0_PCLK */ - CLKID_I2SRXFIFO1PCLK, /* 67 I2SRX_FIFO_1_PCLK */ - CLKID_I2SRXIF1PCLK, /* 68 I2SRX_IF_1_PCLK */ - CLKID_RESERVED69, /* 69 Reserved */ - CLKID_RESERVED70, /* 70 Reserved */ - - /* Domain 5: PCM_BASE */ - - CLKID_PCMCLKIP, /* 71 PCM_CLK_IP */ - - /* Domain 6: UART_BASE */ - - CLKID_UARTUCLK, /* 72 UART_U_CLK */ - - /* Domain 7: CLK1024FS_BASE */ - - CLKID_I2SEDGEDETECTCLK, /* 73 I2S_EDGE_DETECT_CLK */ - CLKID_I2STXBCK0N, /* 74 I2STX_BCK0_N */ - CLKID_I2STXWS0, /* 75 I2STX_WS0 */ - CLKID_I2STXCLK0, /* 76 I2STX_CLK0 */ - CLKID_I2STXBCK1N, /* 77 I2STX_BCK1_N */ - CLKID_I2STXWS1, /* 78 I2STX_WS1 */ - CLKID_CLK256FS, /* 79 CLK_256FS */ - CLKID_I2SRXBCK0N, /* 80 I2SRX_BCK0_N */ - CLKID_I2SRXWS0, /* 81 I2SRX_WS0 */ - CLKID_I2SRXBCK1N, /* 82 I2SRX_BCK1_N */ - CLKID_I2SRXWS1, /* 83 I2SRX_WS1 */ - CLKID_RESERVED84, /* 84 Reserved */ - CLKID_RESERVED85, /* 85 Reserved */ - CLKID_RESERVED86, /* 86 Reserved */ - - /* Domain 8: BCK0_BASE */ - - CLKID_I2SRXBCK0, /* 87 I2SRX_BCK0 */ - - /* Domain 9: BCK1_BASE */ - - CLKID_I2SRXBCK1, /* 88 I2SRX_BCK1 */ - - /* Domain 10: SPI_BASE */ - - CLKID_SPICLK, /* 89 SPI_CLK */ - CLKID_SPICLKGATED, /* 90 SPI_CLK_GATED */ - - /* Domain 11: SYSCLKO_BASE */ - - CLKID_SYSCLKO /* 91 SYSCLK_O */ -}; - -/* Indices into the CGU configuration reset control registers */ - -enum lpc313x_resetid_e -{ - RESETID_APB0RST, /* 0 AHB part of AHB_TO_APB0 bridge (Reserved) */ - RESETID_AHB2APB0RST, /* 1 APB part of AHB_TO_APB0 bridge (Reserved) */ - RESETID_APB1RST, /* 2 AHB part of AHB_TO_APB1 bridge */ - RESETID_AHB2PB1RST, /* 3 APB part of AHB_TO_APB1 bridge */ - RESETID_APB2RST, /* 4 AHB part of AHB_TO_APB2 bridge */ - RESETID_AHB2APB2RST, /* 5 APB part of AHB_TO_APB2 bridge */ - RESETID_APB3RST, /* 6 AHB part of AHB_TO_APB3 bridge */ - RESETID_AHB2APB3RST, /* 7 APB part of AHB_TO_APB3 bridge */ - RESETID_APB4RST, /* 8 AHB_TO_APB4 bridge */ - RESETID_AHB2INTCRST, /* 9 AHB_TO_INTC */ - RESETID_AHB0RST, /* 10 AHB0 */ - RESETID_EBIRST, /* 11 EBI */ - RESETID_PCMAPBRST, /* 12 APB domain of PCM */ - RESETID_PCMCLKIPRST, /* 13 synchronous clk_ip domain of PCM */ - RESETID_PCMRSTASYNC, /* 14 asynchronous clk_ip domain of PCM */ - RESETID_TIMER0RST, /* 15 Timer0 */ - RESETID_TIMER1RST, /* 16 Timer1 */ - RESETID_TIMER2RST, /* 17 Timer2 */ - RESETID_TIMER3RST, /* 18 Timer3 */ - RESETID_ADCPRST, /* 19 controller of 10 bit ADC Interface */ - RESETID_ADCRST, /* 20 A/D converter of ADC Interface */ - RESETID_PWMRST, /* 21 PWM */ - RESETID_UARTRST, /* 22 UART/IrDA */ - RESETID_I2C0RST, /* 23 I2C0 */ - RESETID_I2C1RST, /* 24 I2C1 */ - RESETID_I2SCFGRST, /* 25 I2S_Config */ - RESETID_I2SNSOFRST, /* 26 NSOF counter of I2S_CONFIG */ - RESETID_EDGEDETRST, /* 27 Edge_det */ - RESETID_I2STXFF0RST, /* 28 I2STX_FIFO_0 */ - RESETID_I2STXIF0RST, /* 29 I2STX_IF_0 */ - RESETID_I2STXFF1RST, /* 30 I2STX_FIFO_1 */ - RESETID_I2STXIF1RST, /* 31 I2STX_IF_1 */ - RESETID_I2SRXFF0RST, /* 32 I2SRX_FIFO_0 */ - RESETID_I2SRXIF0RST, /* 33 I2SRX_IF_0 */ - RESETID_I2SRXFF1RST, /* 34 I2SRX_FIFO_1 */ - RESETID_I2SRXIF1RST, /* 35 I2SRX_IF_1 */ - RESETID_RESERVED40, /* 36 Reserved */ - RESETID_RESERVED41, /* 37 Reserved */ - RESETID_RESERVED42, /* 38 Reserved */ - RESETID_RESERVED43, /* 39 Reserved */ - RESETID_RESERVED44, /* 40 Reserved */ - RESETID_LCDRST, /* 41 LCD Interface */ - RESETID_SPIRSTAPB, /* 42 apb_clk domain of SPI */ - RESETID_SPIRSTIP, /* 43 ip_clk domain of SPI */ - RESETID_DMARST, /* 44 DMA */ - RESETID_NANDECCRST, /* 45 Nandflash Controller ECC clock */ - RESETID_NANDAESRST, /* 46 Nandflash Controller AES clock (reserved for lpc313x) */ - RESETID_NANDCTRLRST, /* 47 Nandflash Controller */ - RESETID_RNG, /* 48 RNG */ - RESETID_SDMMCRST, /* 49 MCI (on AHB clock) */ - RESETID_SDMMCRSTCKIN, /* 50 CI synchronous (on IP clock) */ - RESETID_USBOTGAHBRST, /* 51 USB_OTG */ - RESETID_REDCTLRST, /* 52 Redundancy Controller */ - RESETID_AHBMPMCHRST, /* 53 MPMC */ - RESETID_AHBMPMCRFRST, /* 54 refresh generator used for MPMC */ - RESETID_INTCRST, /* 55 Interrupt Controller */ -}; - -/* This structure describes one CGU fractional divider configuration */ - -struct lpc313x_fdivconfig_s -{ - uint8_t stretch; /* Fractional divider stretch enable. */ - uint8_t n; /* Fractional divider nominal nominator */ - uint16_t m; /* Fractional divider nominal denominator */ -}; - -/* The structure describes the configuration of one CGU sub-domain */ - -struct lpc313x_subdomainconfig_s -{ - struct lpc313x_fdivconfig_s fdiv; /* Fractional divider settings */ - uint32_t clkset; /* Bitset of all clocks in the sub-domain */ -}; - -/* CGU clock initilization structure. Describes the platform-specific - * configuration of every clock domain. - */ - -struct lpc313x_clkinit_s -{ - struct - { - uint8_t finsel; - struct lpc313x_subdomainconfig_s sub[FRACDIV_BASE0_CNT]; - } domain0; - - struct - { - uint8_t finsel; - struct lpc313x_subdomainconfig_s sub[FRACDIV_BASE1_CNT]; - } domain1; - - struct - { - uint8_t finsel; - struct lpc313x_subdomainconfig_s sub[FRACDIV_BASE2_CNT]; - } domain2; - - struct - { - uint8_t finsel; - struct lpc313x_subdomainconfig_s sub[FRACDIV_BASE3_CNT]; - } domain3; - - struct - { - uint8_t finsel; - struct lpc313x_subdomainconfig_s sub[FRACDIV_BASE4_CNT]; - } domain4; - - struct - { - uint8_t finsel; - struct lpc313x_subdomainconfig_s sub[FRACDIV_BASE5_CNT]; - } domain5; - - struct - { - uint8_t finsel; - struct lpc313x_subdomainconfig_s sub[FRACDIV_BASE6_CNT]; - } domain6; - - struct - { - uint8_t finsel; - struct lpc313x_subdomainconfig_s sub[FRACDIV_BASE7_CNT]; - } domain7; - - struct - { - uint8_t finsel; - } domain8; - - struct - { - uint8_t finsel; - } domain9; - - struct - { - uint8_t finsel; - struct lpc313x_subdomainconfig_s sub[FRACDIV_BASE10_CNT]; - } domain10; - - struct - { - uint8_t finsel; - } domain11; - -#if 0 /* Dynamic fractional divider initialization not implemented */ - struct - { - uint16_t sel; - struct lpc313x_fdivconfig_s cfg; - } dynfdiv[CGU_NDYNFRACDIV]; -#endif -}; - -/* This structure is used to pass PLL configuration data to - * lpc313x_pllconfig() - */ - -struct lpc313x_pllconfig_s -{ - uint8_t hppll; /* PLL selection: 0=HPLL0 1=HPLL1 */ - uint8_t pdec; /* PLL P-divider value: 0-0x7f */ - uint8_t selr; /* SELR bandwidth selection: 0-15 */ - uint8_t seli; /* SELI bandwidth selection: 0-63 */ - uint8_t selp; /* SELP bandwidth selection: 0-31 */ - uint16_t ndec; /* PLL N-divider value: 0-0x3ff */ - uint16_t mode; /* PLL mode: 9-bits */ - uint32_t freq; /* Frequency of the PLL in MHz */ - uint32_t finsel; /* Frequency input selection: CGU_HPFINSEL_* */ - uint32_t mdec; /* PLL M-divider value: 0-0x1ffff */ -}; - -/************************************************************************ - * Public Data - ************************************************************************/ - -/* This array is managed by the chip-specific logic and provides the - * programmed frequency of every input source - */ - -EXTERN uint32_t g_boardfreqin[CGU_NFREQIN]; - -/* This instance of the lpc313x_clkinit_s structure provides the initial, - * default clock configuration for the board. Every board must provide - * an implementation of g_boardclks. This rather complex structure is - * used by the boot-up logic to configure initial lpc313x clocking. - */ - -EXTERN const struct lpc313x_clkinit_s g_boardclks; - -/************************************************************************ - * Inline Functions - ************************************************************************/ - -/************************************************************************ - * Name: lpc313x_getbasefreq - * - * Description: - * Return the base frequency associated with a clock domain - * - ************************************************************************/ - -static inline uint32_t lpc313x_getbasefreq(enum lpc313x_domainid_e dmnid) -{ - uint32_t regval; - int ndx; - - /* Fetch the SSR register associated with this clock domain */ - - regval = getreg32(LPC313X_CGU_SSR((int)dmnid)); - - /* Extract the last frequency input selection */ - - ndx = (regval & CGU_SSR_FS_MASK) >> CGU_SSR_FS_SHIFT; - - /* And return the user-supplied value for that frequency input */ - - return g_boardfreqin[ndx]; -} - -/************************************************************************ - * Name: lpc313x_enableclock - * - * Description: - * Enable the specified clock - * - ************************************************************************/ - -static inline void lpc313x_enableclock(enum lpc313x_clockid_e clkid) -{ - uint32_t address = LPC313X_CGU_PCR((int)clkid); - uint32_t regval = getreg32(address); - - regval |= CGU_PCR_RUN; - putreg32(regval, address); -} - -/************************************************************************ - * Name: lpc313x_disableclock - * - * Description: - * Disable the specified clock - * - ************************************************************************/ - -static inline void lpc313x_disableclock(enum lpc313x_clockid_e clkid) -{ - uint32_t address = LPC313X_CGU_PCR((int)clkid); - uint32_t regval = getreg32(address); - - regval &= ~CGU_PCR_RUN; - putreg32(regval, address); -} - -/************************************************************************ - * Public Functions - ************************************************************************/ - -/**************************************************************************** - * Name: lpc313x_defclk - * - * Description: - * Enable the specified clock if it is one of the default clocks needed - * by the board. - * - ****************************************************************************/ - -EXTERN bool lpc313x_defclk(enum lpc313x_clockid_e clkid); - -/**************************************************************************** - * Name: lpc313x_resetclks - * - * Description: - * Put all clocks into a known, initial state - * - ****************************************************************************/ - -EXTERN void lpc313x_resetclks(void); - -/************************************************************************ - * Name: lpc313x_clkinit - * - * Description: - * Initialize all clock domains based on board-specific clock - * configuration data - * - ************************************************************************/ - -EXTERN void lpc313x_clkinit(const struct lpc313x_clkinit_s* cfg); - -/************************************************************************ - * Name: lpc313x_fdivinit - * - * Description: - * Enable and configure (or disable) a fractional divider. For - * internal us only... see lpc313x_setfdiv() the externally usable - * function. - * - ************************************************************************/ - -EXTERN uint32_t lpc313x_fdivinit(int fdcndx, - const struct lpc313x_fdivconfig_s *fdiv, - bool enable); - -/************************************************************************ - * Name: lpc313x_setfdiv - * - * Description: - * Set/reset subdomain frequency containing the specified clock using - * the provided divider settings - * - ************************************************************************/ - -EXTERN void lpc313x_setfdiv(enum lpc313x_domainid_e dmnid, - enum lpc313x_clockid_e clkid, - const struct lpc313x_fdivconfig_s *fdiv); - -/**************************************************************************** - * Name: lpc313x_pllconfig - * - * Description: - * Re-onfigure the PLL according to the provided selections. - * - ****************************************************************************/ - -EXTERN void lpc313x_pllconfig(const struct lpc313x_pllconfig_s * const cfg); - -/************************************************************************ - * Name: lpc313x_hp0pllconfig - * - * Description: - * Configure the HP0 PLL according to the board.h default selections. - * - ************************************************************************/ - -EXTERN void lpc313x_hp0pllconfig(void); - -/************************************************************************ - * Name: lpc313x_hp1pllconfig - * - * Description: - * Configure the HP1 PLL according to the board.h default selections. - * - ************************************************************************/ - -EXTERN void lpc313x_hp1pllconfig(void); - -/************************************************************************ - * Name: lpc313x_softreset - * - * Description: - * Perform a soft reset on the specified module. - * - ************************************************************************/ - -EXTERN void lpc313x_softreset(enum lpc313x_resetid_e resetid); - -/************************************************************************ - * Name: lpc313x_clkdomain - * - * Description: - * Given a clock ID, return the ID of the domain in which the clock - * resides. - * - ************************************************************************/ - -EXTERN enum lpc313x_domainid_e lpc313x_clkdomain(enum lpc313x_clockid_e clkid); - -/************************************************************************ - * Name: lpc313x_esrndx - * - * Description: - * Given a clock ID, return the index of the corresponding ESR - * register (or ESRNDX_INVALID if there is no ESR associated with - * this clock ID). Indexing of ESRs differs slightly from the clock - * ID: There are 92 clock IDs but only 89 ESR regisers. There are no - * ESR registers for : - * - * - * CLKID_I2SRXBCK0 Clock ID 87: I2SRX_BCK0 - * CLKID_I2SRXBCK1, Clock ID 88: I2SRX_BCK1 - * - * and - * - * CLKID_SYSCLKO Clock ID 91: SYSCLK_O - * - ************************************************************************/ - -EXTERN int lpc313x_esrndx(enum lpc313x_clockid_e clkid); - -/************************************************************************ - * Name: lpc313x_bcrndx - * - * Description: - * Only 5 of the 12 domains have an associated BCR register. This - * function returns the index to the associated BCR register (if any) - * or BCRNDX_INVALID otherwise. - * - ************************************************************************/ - -EXTERN int lpc313x_bcrndx(enum lpc313x_domainid_e dmnid); - -/************************************************************************ - * Name: lpc313x_fdcndx - * - * Description: - * Given a clock ID and its domain ID, return the index of the - * corresponding fractional divider register (or FDCNDX_INVALID if - * there is no fractional divider associated with this clock). - * - ************************************************************************/ - -EXTERN int lpc313x_fdcndx(enum lpc313x_clockid_e clkid, - enum lpc313x_domainid_e dmnid); - -/************************************************************************ - * Name: lpc313x_selectfreqin - * - * Description: - * Set the base frequency source selection for with a clock domain - * - ************************************************************************/ - -EXTERN void lpc313x_selectfreqin(enum lpc313x_domainid_e dmnid, - uint32_t finsel); - -/************************************************************************ - * Name: lpc313x_clkfreq - * - * Description: - * Given a clock ID and its domain ID, return the frequency of the - * clock. - * - ************************************************************************/ - -EXTERN uint32_t lpc313x_clkfreq(enum lpc313x_clockid_e clkid, - enum lpc313x_domainid_e dmnid); - -/************************************************************************ - * Name: lpc313x_enableexten - * - * Description: - * Enable external enabling for the the specified possible clocks. - * - ************************************************************************/ - -EXTERN void lpc313x_enableexten(enum lpc313x_clockid_e clkid); - -/************************************************************************ - * Name: lpc313x_disableexten - * - * Description: - * Disable external enabling for the the specified possible clocks. - * - ************************************************************************/ - -EXTERN void lpc313x_disableexten(enum lpc313x_clockid_e clkid); - -#undef EXTERN -#ifdef __cplusplus -} -#endif - -#endif /* __ASSEMBLY__ */ -#endif /* __ARCH_ARM_SRC_LPC313X_CGUDRVR_H */ diff --git a/nuttx/arch/arm/src/lpc313x/lpc313x_clkdomain.c b/nuttx/arch/arm/src/lpc313x/lpc313x_clkdomain.c deleted file mode 100755 index e02300e24..000000000 --- a/nuttx/arch/arm/src/lpc313x/lpc313x_clkdomain.c +++ /dev/null @@ -1,125 +0,0 @@ -/************************************************************************ - * arch/arm/src/lpc313x/lpc313x_clkdomain.c - * - * Copyright (C) 2009 Gregory Nutt. All rights reserved. - * Author: Gregory Nutt - * - * References: - * - UM10314 LPC3130/31 User manual Rev. 1.01 — 9 September 2009 - * - lpc313x.cdl.drivers.zip example driver code - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name NuttX nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - ************************************************************************/ - -/************************************************************************ - * Included Files - ************************************************************************/ - -#include -#include - -#include "up_arch.h" -#include "lpc313x_cgudrvr.h" - -/************************************************************************ - * Pre-processor Definitions - ************************************************************************/ - -/************************************************************************ - * Private Data - ************************************************************************/ - -/************************************************************************ - * Private Functions - ************************************************************************/ - -/************************************************************************ - * Public Functions - ************************************************************************/ - -/************************************************************************ - * Name: lpc313x_clkdomain - * - * Description: - * Given a clock ID, return the ID of the domain in which the clock - * resides. - * - ************************************************************************/ - -enum lpc313x_domainid_e lpc313x_clkdomain(enum lpc313x_clockid_e clkid) -{ - if (clkid <= CLKID_SYSBASE_LAST) /* Domain 0: SYS_BASE */ - { - return DOMAINID_SYS; - } - else if (clkid <= CLKID_AHB0APB0_LAST) /* Domain 1: AHB0APB0_BASE */ - { - return DOMAINID_AHB0APB0; - } - else if (clkid <= CLKID_AHB0APB1_LAST) /* Domain 2: AHB0APB1_BASE */ - { - return DOMAINID_AHB0APB1; - } - else if (clkid <= CLKID_AHB0APB2_LAST) /* Domain 3: AHB0APB2_BASE */ - { - return DOMAINID_AHB0APB2; - } - else if (clkid <= CLKID_AHB0APB3_LAST) /* Domain 4: AHB0APB3_BASE */ - { - return DOMAINID_AHB0APB3; - } - else if (clkid <= CLKID_PCM_LAST) /* Domain 5: PCM_BASE */ - { - return DOMAINID_PCM; - } - else if (clkid <= CLKID_UART_LAST) /* Domain 6: UART_BASE */ - { - return DOMAINID_UART; - } - else if (clkid <= CLKID_CLK1024FS_LAST) /* Domain 7: CLK1024FS_BASE */ - { - return DOMAINID_CLK1024FS; - } - else if (clkid <= CLKID_I2SRXBCK0_LAST) /* Domain 8: BCK0_BASE */ - { - return DOMAINID_BCK0; - } - else if (clkid <= CLKID_I2SRXBCK1_LAST) /* Domain 9: BCK1_BASE */ - { - return DOMAINID_BCK1; - } - else if (clkid <= CLKID_SPI_LAST) /* Domain 10: SPI_BASE */ - { - return DOMAINID_SPI; - } - else /* if (clkid <= CLKID_SYSCLKO_LAST) */ /* Domain 11: SYSCLKO_BASE */ - { - return DOMAINID_SYSCLKO; - } -} diff --git a/nuttx/arch/arm/src/lpc313x/lpc313x_clkexten.c b/nuttx/arch/arm/src/lpc313x/lpc313x_clkexten.c deleted file mode 100755 index 20e42a83a..000000000 --- a/nuttx/arch/arm/src/lpc313x/lpc313x_clkexten.c +++ /dev/null @@ -1,152 +0,0 @@ -/**************************************************************************** - * arch/arm/src/lpc313x/lpc313x_exten.c - * - * Copyright (C) 2009 Gregory Nutt. All rights reserved. - * Author: Gregory Nutt - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name NuttX nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************/ - -/**************************************************************************** - * Included Files - ****************************************************************************/ - -#include - -#include - -#include - -#include "lpc313x_cgudrvr.h" - -/**************************************************************************** - * Pre-processor Definitions - ****************************************************************************/ - -/**************************************************************************** - * Private Data - ****************************************************************************/ - -/**************************************************************************** - * Public Data - ****************************************************************************/ - -/**************************************************************************** - * Private Functions - ****************************************************************************/ - -/**************************************************************************** - * Public Functions - ****************************************************************************/ - -/**************************************************************************** - * Name: lpc313x_enableexten - * - * Description: - * Enable external enabling for the the specified possible clocks. - * - ****************************************************************************/ - -void lpc313x_enableexten(enum lpc313x_clockid_e clkid) -{ - uint32_t regaddr; - uint32_t regval; - - switch (clkid) - { - case CLKID_DMACLKGATED: /* 9 DMA_CLK_GATED */ - case CLKID_EVENTROUTERPCLK: /* 31 EVENT_ROUTER_PCLK */ - case CLKID_ADCPCLK: /* 32 ADC_PCLK */ - case CLKID_IOCONFPCLK: /* 35 IOCONF_PCLK */ - case CLKID_CGUPCLK: /* 36 CGU_PCLK */ - case CLKID_SYSCREGPCLK: /* 37 SYSCREG_PCLK */ - case CLKID_OTPPCLK: /* 38 OTP_PCLK (Reserved on LPC313X) */ - case CLKID_PWMPCLKREGS: /* 46 PWM_PCLK_REGS */ - case CLKID_PCMAPBPCLK: /* 52 PCM_APB_PCLK */ - case CLKID_SPIPCLKGATED: /* 57 SPI_PCLK_GATED */ - case CLKID_SPICLKGATED: /* 90 SPI_CLK_GATED */ - case CLKID_PCMCLKIP: /* 71 PCM_CLK_IP */ - regaddr = LPC313X_CGU_PCR(clkid); - regval = getreg32(regaddr); - regval |= CGU_PCR_EXTENEN; - putreg32(regval, regaddr); - break; - - /* Otherwise, force disable for the clocks. NOTE that a larger set will - * be disabled than will be enabled. - */ - - default: - lpc313x_disableexten(clkid); - break; - } -} - -/**************************************************************************** - * Name: lpc313x_disableexten - * - * Description: - * Disable external enabling for the the specified possible clocks. - * - ****************************************************************************/ - -void lpc313x_disableexten(enum lpc313x_clockid_e clkid) -{ - uint32_t regaddr; - uint32_t regval; - - switch (clkid) - { - case CLKID_DMACLKGATED: /* 9 DMA_CLK_GATED */ - case CLKID_EVENTROUTERPCLK: /* 31 EVENT_ROUTER_PCLK */ - case CLKID_ADCPCLK: /* 32 ADC_PCLK */ - case CLKID_WDOGPCLK: /* 34 WDOG_PCLK */ - case CLKID_IOCONFPCLK: /* 35 IOCONF_PCLK */ - case CLKID_CGUPCLK: /* 36 CGU_PCLK */ - case CLKID_SYSCREGPCLK: /* 37 SYSCREG_PCLK */ - case CLKID_OTPPCLK: /* 38 OTP_PCLK (Reserved on LPC313X) */ - case CLKID_PWMPCLKREGS: /* 46 PWM_PCLK_REGS */ - case CLKID_I2C0PCLK: /* 48 I2C0_PCLK */ - case CLKID_I2C1PCLK: /* 49 I2C1_PCLK */ - case CLKID_PCMAPBPCLK: /* 52 PCM_APB_PCLK */ - case CLKID_UARTAPBCLK: /* 53 UART_APB_CLK */ - case CLKID_SPIPCLKGATED: /* 57 SPI_PCLK_GATED */ - case CLKID_SPICLKGATED: /* 90 SPI_CLK_GATED */ - case CLKID_PCMCLKIP: /* 71 PCM_CLK_IP */ - case CLKID_LCDPCLK: /* 54 LCD_PCLK */ - regaddr = LPC313X_CGU_PCR(clkid); - regval = getreg32(regaddr); - regval &= ~CGU_PCR_EXTENEN; - putreg32(regval, regaddr); - break; - - default: - break; - } -} diff --git a/nuttx/arch/arm/src/lpc313x/lpc313x_clkfreq.c b/nuttx/arch/arm/src/lpc313x/lpc313x_clkfreq.c deleted file mode 100755 index b2cb0361f..000000000 --- a/nuttx/arch/arm/src/lpc313x/lpc313x_clkfreq.c +++ /dev/null @@ -1,177 +0,0 @@ -/************************************************************************ - * arch/arm/src/lpc313x/lpc313x_clkfreq.c - * - * Copyright (C) 2009-2010 Gregory Nutt. All rights reserved. - * Author: Gregory Nutt - * - * References: - * - UM10314 LPC3130/31 User manual Rev. 1.01 — 9 September 2009 - * - lpc313x.cdl.drivers.zip example driver code - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name NuttX nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - ************************************************************************/ - -/************************************************************************ - * Included Files - ************************************************************************/ - -#include -#include - -#include "up_arch.h" -#include "lpc313x_cgudrvr.h" - -/************************************************************************ - * Pre-processor Definitions - ************************************************************************/ - -/************************************************************************ - * Private Data - ************************************************************************/ - -/************************************************************************ - * Private Functions - ************************************************************************/ - -/************************************************************************ - * Public Functions - ************************************************************************/ - -/************************************************************************ - * Name: lpc313x_fdcndx - * - * Description: - * Given a clock ID and its domain ID, return the frequency of the - * clock. - * - ************************************************************************/ - -uint32_t lpc313x_clkfreq(enum lpc313x_clockid_e clkid, - enum lpc313x_domainid_e dmnid) -{ - uint32_t freq = 0; - uint32_t fdcndx; - uint32_t regval; - - /* Get then fractional divider register index for this clock */ - - fdcndx = lpc313x_fdcndx(clkid, dmnid); - - /* Get base frequency for the domain */ - - freq = lpc313x_getbasefreq(dmnid); - - /* If there is no fractional divider associated with the clodk, then the - * connection is directo and we just return the base frequency. - */ - - if (fdcndx == FDCNDX_INVALID) - { - return freq; - } - - /* Read fractional divider control (FDC) register value and double check that - * it is enabled (not necessary since lpc313x_fdcndx() also does this check - */ - - regval = getreg32(LPC313X_CGU_FDC(fdcndx)); - if ((regval & CGU_ESR_ESREN) != 0) - { - int32_t msub; - int32_t madd; - int32_t n; - int32_t m; - - /* Yes, extract modulo subtraction and addition values, msub and madd. - * Fractional divider 17 is a special case because its msub and madd - * fields have greater range. - */ - - if (fdcndx == 17) - { - /* Range is 0-0x1fff for both */ - - msub = ((regval & CGU_FDC17_MSUB_MASK) >> CGU_FDC17_MSUB_SHIFT) | CGU_FDC17_MSUB_EXTEND; - madd = (regval & CGU_FDC17_MADD_MASK) >> CGU_FDC17_MADD_SHIFT; - } - else - { - /* Range is 0-255 for both */ - - msub = ((regval & CGU_FDC_MSUB_MASK) >> CGU_FDC_MSUB_SHIFT) | CGU_FDC_MSUB_EXTEND; - madd = (regval & CGU_FDC_MADD_MASK) >> CGU_FDC_MADD_SHIFT; - } - - /* Handle a corner case that would result in an infinite loop below */ - - if (msub == 0 && madd == 0) - { - return 0; - } - - /* Reduce to the greatest common power-of-2 denominator. To minimize - * power consumption, the lpc313x user manual recommends that madd and msub - * be shifted right to have as many trailing zero's as possible. The - * following undoes that shift. - */ - - while ((msub & 1) == 0 && (madd & 1) == 0) - { - madd = madd >> 1; - msub = msub >> 1; - } - - /* Then compute n and m values: - * - * fout = n/m * fin - * - * where - * - * madd = m - n - * msub = -n - */ - - n = -msub; - m = madd + n; - - /* Check that both m and n are non-zero values */ - - if ((n == 0) || (m == 0)) - { - return 0; - } - - /* Finally, calculate the frequency based on m and n values */ - - freq = (freq * n) / m ; - } - - return freq; -} - diff --git a/nuttx/arch/arm/src/lpc313x/lpc313x_clkinit.c b/nuttx/arch/arm/src/lpc313x/lpc313x_clkinit.c deleted file mode 100755 index 81bf3fb0f..000000000 --- a/nuttx/arch/arm/src/lpc313x/lpc313x_clkinit.c +++ /dev/null @@ -1,298 +0,0 @@ -/************************************************************************************ - * arch/arm/src/lpc313x/lpc313x_clkinit.c - * - * Copyright (C) 2009-2010 Gregory Nutt. All rights reserved. - * Author: Gregory Nutt - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name NuttX nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - ************************************************************************************/ - -/************************************************************************************ - * Included Files - ************************************************************************************/ - -#include - -#include - -#include - -#include "lpc313x_cgu.h" -#include "lpc313x_cgudrvr.h" - -/************************************************************************************ - * Pre-processor Definitions - ************************************************************************************/ - -/************************************************************************************ - * Private Types - ************************************************************************************/ - -/* This structure describes the configuration of one domain */ - -struct lpc313x_domainconfig_s -{ - enum lpc313x_domainid_e dmnid; /* Domain ID */ - uint32_t finsel; /* Frequency input selection */ - uint32_t clk1; /* ID of first clock in the domain */ - uint32_t nclks; /* Number of clocks in the domain */ - uint32_t fdiv1; /* First frequency divider in the domain */ - uint32_t nfdiv; /* Number of frequency dividers in the domain */ - const struct lpc313x_subdomainconfig_s* sub; /* Sub=domain array */ -}; - -/************************************************************************************ - * Private Data - ************************************************************************************/ - -/************************************************************************************ - * Public Data - ************************************************************************************/ - -/************************************************************************************ - * Private Functions - ************************************************************************************/ - -/************************************************************************************ - * Name: lpc313x_domaininit - * - * Description: - * Initialize one clock domain based on board-specific clock configuration data - * - ************************************************************************************/ - -static void lpc313x_domaininit(struct lpc313x_domainconfig_s* dmn) -{ - const struct lpc313x_subdomainconfig_s * sub = dmn->sub; - uint32_t fdivcfg; - uint32_t regaddr; - uint32_t regval; - int fdndx; - int clkndx; - int bcrndx = lpc313x_bcrndx(dmn->dmnid); - int esrndx; - - if (bcrndx != BCRNDX_INVALID) - { - /* Disable BCR for domain */ - - regaddr = LPC313X_CGU_BCR(bcrndx); - putreg32(0, regaddr); - } - - /* Configure the fractional dividers in this domain */ - - for (fdndx = 0; fdndx < dmn->nfdiv; fdndx++, sub++) - { - /* Set fractional divider confiruation but don't enable it yet */ - - fdivcfg = lpc313x_fdivinit(fdndx + dmn->fdiv1, &sub->fdiv, false); - - /* Enable frac divider only if it has valid settings */ - - if (fdivcfg != 0) - { - /* Select the fractional dividir for each clock in this - * sub domain. - */ - - for (clkndx = 0; clkndx <= dmn->nclks; clkndx++) - { - /* Does this clock have an ESR register? */ - - esrndx = lpc313x_esrndx((enum lpc313x_clockid_e)(clkndx + dmn->clk1)); - if (esrndx != ESRNDX_INVALID) - { - /* Yes.. Check if this clock belongs to this sub-domain */ - - if (sub->clkset & (1 << clkndx)) - { - /* Yes.. configure the clock to use this fractional divider */ - - regaddr = LPC313X_CGU_ESR(esrndx); - putreg32((fdndx << CGU_ESR_ESRSEL_SHIFT) | CGU_ESR_ESREN, regaddr); - } - } - } - - /* Enable the fractional divider */ - - regaddr = LPC313X_CGU_FDC(fdndx + dmn->fdiv1); - regval = getreg32(regaddr); - regval |= CGU_FDC_RUN; - putreg32(regval, regaddr); - } - } - - if (bcrndx != BCRNDX_INVALID) - { - /* Enable the BCR for domain */ - - regaddr = LPC313X_CGU_BCR(bcrndx); - putreg32(CGU_BCR_FDRUN, regaddr); - } - - /* Select input base clock for domain*/ - - lpc313x_selectfreqin(dmn->dmnid, dmn->finsel); -} - -/************************************************************************************ - * Public Functions - ************************************************************************************/ - -/************************************************************************************ - * Name: lpc313x_clkinit - * - * Description: - * Initialize all clock domains based on board-specific clock configuration data - * - ************************************************************************************/ - -void lpc313x_clkinit(const struct lpc313x_clkinit_s* cfg) -{ - struct lpc313x_domainconfig_s domain; - - /* Reset all clocks and connect them to FFAST */ - - lpc313x_resetclks(); - - /* Initialize Domain0 = SYS_BASE clocks */ - - domain.dmnid = DOMAINID_SYS; - domain.finsel = cfg->domain0.finsel; - domain.clk1 = CLKID_SYSBASE_FIRST; - domain.nclks = (CLKID_SYSBASE_LAST - CLKID_SYSBASE_FIRST) + 1; - domain.fdiv1 = FRACDIV_BASE0_LOW; - domain.nfdiv = FRACDIV_BASE0_CNT; - domain.sub = cfg->domain0.sub; - lpc313x_domaininit(&domain); - - /* Initialize Domain1 = AHB0APB0_BASE clocks */ - - domain.dmnid = DOMAINID_AHB0APB0; - domain.finsel = cfg->domain1.finsel; - domain.clk1 = CLKID_AHB0APB0_FIRST; - domain.nclks = (CLKID_AHB0APB0_LAST - CLKID_AHB0APB0_FIRST) + 1; - domain.fdiv1 = FRACDIV_BASE1_LOW; - domain.nfdiv = FRACDIV_BASE1_CNT; - domain.sub = cfg->domain1.sub; - lpc313x_domaininit(&domain); - - /* Initialize Domain2 = AHB0APB1_BASE clocks */ - - domain.dmnid = DOMAINID_AHB0APB1; - domain.finsel = cfg->domain2.finsel; - domain.clk1 = CLKID_AHB0APB1_FIRST; - domain.nclks = (CLKID_AHB0APB1_LAST - CLKID_AHB0APB1_FIRST) + 1; - domain.fdiv1 = FRACDIV_BASE2_LOW; - domain.nfdiv = FRACDIV_BASE2_CNT; - domain.sub = cfg->domain2.sub; - lpc313x_domaininit(&domain); - - /* Initialize Domain3 = AHB0APB2_BASE clocks */ - - domain.dmnid = DOMAINID_AHB0APB2; - domain.finsel = cfg->domain3.finsel; - domain.clk1 = CLKID_AHB0APB2_FIRST; - domain.nclks = (CLKID_AHB0APB2_LAST - CLKID_AHB0APB2_FIRST) + 1; - domain.fdiv1 = FRACDIV_BASE3_LOW; - domain.nfdiv = FRACDIV_BASE3_CNT; - domain.sub = cfg->domain3.sub; - lpc313x_domaininit(&domain); - - /* Initialize Domain4 = AHB0APB3_BASE clocks */ - - domain.dmnid = DOMAINID_AHB0APB3; - domain.finsel = cfg->domain4.finsel; - domain.clk1 = CLKID_AHB0APB3_FIRST; - domain.nclks = (CLKID_AHB0APB3_LAST - CLKID_AHB0APB3_FIRST) + 1; - domain.fdiv1 = FRACDIV_BASE4_LOW; - domain.nfdiv = FRACDIV_BASE4_CNT; - domain.sub = cfg->domain4.sub; - lpc313x_domaininit(&domain); - - /* Initialize Domain5 = PCM_BASE clocks */ - - domain.dmnid = DOMAINID_PCM; - domain.finsel = cfg->domain5.finsel; - domain.clk1 = CLKID_PCM_FIRST; - domain.nclks = 1; - domain.fdiv1 = FRACDIV_BASE5_LOW; - domain.nfdiv = FRACDIV_BASE5_CNT; - domain.sub = cfg->domain5.sub; - lpc313x_domaininit(&domain); - - /* Initialize Domain6 = UART_BASE clocks */ - - domain.dmnid = DOMAINID_UART; - domain.finsel = cfg->domain6.finsel; - domain.clk1 = CLKID_UART_FIRST; - domain.nclks = 1; - domain.fdiv1 = FRACDIV_BASE6_LOW; - domain.nfdiv = FRACDIV_BASE6_CNT; - domain.sub = cfg->domain6.sub; - lpc313x_domaininit(&domain); - - /* Initialize Domain7 = CLK1024FS_BASE clocks */ - - domain.dmnid = DOMAINID_CLK1024FS; - domain.finsel = cfg->domain7.finsel; - domain.clk1 = CLKID_CLK1024FS_FIRST; - domain.nclks = (CLKID_CLK1024FS_LAST - CLKID_CLK1024FS_FIRST) + 1; - domain.fdiv1 = FRACDIV_BASE7_LOW; - domain.nfdiv = FRACDIV_BASE7_CNT; - domain.sub = cfg->domain7.sub; - lpc313x_domaininit(&domain); - - /* Initialize Domain8 = I2SRX_BCK0_BASE clocks */ - - lpc313x_selectfreqin(DOMAINID_BCK0, cfg->domain8.finsel); - - /* Initialize Domain9 = I2SRX_BCK1_BASE clocks */ - - lpc313x_selectfreqin(DOMAINID_BCK1, cfg->domain9.finsel); - - /* Initialize Domain10 = SPI_BASE clocks */ - - domain.dmnid = DOMAINID_SPI; - domain.finsel = cfg->domain10.finsel; - domain.clk1 = CLKID_SPI_FIRST; - domain.nclks = (CLKID_SPI_LAST - CLKID_SPI_FIRST) + 1; - domain.fdiv1 = FRACDIV_BASE10_LOW; - domain.nfdiv = FRACDIV_BASE10_CNT; - domain.sub = cfg->domain10.sub; - lpc313x_domaininit(&domain); - - /* Initialize Domain11 = SYSCLK_O_BASE clocks */ - - lpc313x_selectfreqin(DOMAINID_SYSCLKO, cfg->domain11.finsel); - - /* Initialize Dynamic fractional dividers -- to be provided */ -} diff --git a/nuttx/arch/arm/src/lpc313x/lpc313x_decodeirq.c b/nuttx/arch/arm/src/lpc313x/lpc313x_decodeirq.c deleted file mode 100755 index 119e65c50..000000000 --- a/nuttx/arch/arm/src/lpc313x/lpc313x_decodeirq.c +++ /dev/null @@ -1,137 +0,0 @@ -/******************************************************************************** - * arch/arm/src/lpc313x/lpc313x_decodeirq.c - * arch/arm/src/chip/lpc313x_decodeirq.c - * - * Copyright (C) 2009 Gregory Nutt. All rights reserved. - * Author: Gregory Nutt - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name NuttX nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - ********************************************************************************/ - -/******************************************************************************** - * Included Files - ********************************************************************************/ - -#include - -#include -#include -#include -#include -#include - -#include "chip.h" -#include "up_arch.h" - -#include "os_internal.h" -#include "up_internal.h" - -#include "lpc313x_intc.h" - -/******************************************************************************** - * Pre-processor Definitions - ********************************************************************************/ - -/******************************************************************************** - * Public Data - ********************************************************************************/ - -/******************************************************************************** - * Private Data - ********************************************************************************/ - -/******************************************************************************** - * Private Functions - ********************************************************************************/ - -/******************************************************************************** - * Public Functions - ********************************************************************************/ - -void up_decodeirq(uint32_t *regs) -{ -#ifdef CONFIG_SUPPRESS_INTERRUPTS - lib_lowprintf("Unexpected IRQ\n"); - current_regs = regs; - PANIC(OSERR_ERREXCEPTION); -#else - int index; - int irq; - - /* Read the IRQ vector status register. Bits 3-10 provide the IRQ number - * of the interrupt (the TABLE_ADDR was initialized to zero, so the - * following masking should be unnecessary) - */ - - index = getreg32(LPC313X_INTC_VECTOR0) & INTC_VECTOR_INDEX_MASK; - if (index != 0) - { - /* Shift the index so that the range of IRQ numbers are in bits 0-7 (values - * 1-127) and back off the IRQ number by 1 so that the numbering is zero-based - */ - - irq = (index >> INTC_VECTOR_INDEX_SHIFT) -1; - - /* Verify that the resulting IRQ number is valid */ - - if ((unsigned)irq < NR_IRQS) - { - uint32_t* savestate; - - /* Mask and acknowledge the interrupt */ - - up_maskack_irq(irq); - - /* Current regs non-zero indicates that we are processing an interrupt; - * current_regs is also used to manage interrupt level context switches. - */ - - savestate = (uint32_t*)current_regs; - current_regs = regs; - - /* Deliver the IRQ */ - - irq_dispatch(irq, regs); - - /* Restore the previous value of current_regs. NULL would indicate that - * we are no longer in an interrupt handler. It will be non-NULL if we - * are returning from a nested interrupt. - */ - - current_regs = savestate; - - /* Unmask the last interrupt (global interrupts are still - * disabled). - */ - - up_enable_irq(irq); - } - } -#endif -} diff --git a/nuttx/arch/arm/src/lpc313x/lpc313x_defclk.c b/nuttx/arch/arm/src/lpc313x/lpc313x_defclk.c deleted file mode 100755 index bdef026b5..000000000 --- a/nuttx/arch/arm/src/lpc313x/lpc313x_defclk.c +++ /dev/null @@ -1,119 +0,0 @@ -/**************************************************************************** - * arch/arm/src/lpc313x/lpc313x_defclk.c - * - * Copyright (C) 2009 Gregory Nutt. All rights reserved. - * Author: Gregory Nutt - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name NuttX nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************/ - -/**************************************************************************** - * Included Files - ****************************************************************************/ - -#include - -#include -#include - -#include - -#include "lpc313x_cgudrvr.h" - -/**************************************************************************** - * Pre-processor Definitions - ****************************************************************************/ - -/**************************************************************************** - * Private Data - ****************************************************************************/ - -/**************************************************************************** - * Public Data - ****************************************************************************/ - -/**************************************************************************** - * Private Functions - ****************************************************************************/ - -/**************************************************************************** - * Public Functions - ****************************************************************************/ - -/**************************************************************************** - * Name: lpc313x_defclk - * - * Description: - * Enable the specified clock if it is one of the default clocks needed - * by the board. - * - ****************************************************************************/ - -bool lpc313x_defclk(enum lpc313x_clockid_e clkid) -{ - - uint32_t regaddr; - uint32_t regval; - bool enable; - - /* Check if this clock should be enabled. This is determined by - * 3 bitsets provided by board-specific logic in board/board.h. - */ - - if ((int)clkid < 32) - { - enable = ((BOARD_CLKS_0_31 & (1 << (int)clkid)) != 0); - } - else if ((int)clkid < 64) - { - enable = ((BOARD_CLKS_32_63 & (1 << ((int)clkid - 32))) != 0); - } - else - { - enable = ((BOARD_CLKS_64_92 & (1 << ((int)clkid - 64))) != 0); - } - - /* Then set/clear the RUN bit in the PCR register for this clock - * accordingly. - */ - - regaddr = LPC313X_CGU_PCR((int)clkid); - regval = getreg32(regaddr); - if (enable) - { - regval |= CGU_PCR_RUN; - } - else - { - regval &= ~CGU_PCR_RUN; - } - putreg32(regval, regaddr); - return enable; -} - diff --git a/nuttx/arch/arm/src/lpc313x/lpc313x_dma.h b/nuttx/arch/arm/src/lpc313x/lpc313x_dma.h deleted file mode 100755 index a36edeffe..000000000 --- a/nuttx/arch/arm/src/lpc313x/lpc313x_dma.h +++ /dev/null @@ -1,423 +0,0 @@ -/************************************************************************************************ - * arch/arm/src/lpc313x/lpc313x_dma.h - * - * Copyright (C) 2009 Gregory Nutt. All rights reserved. - * Author: Gregory Nutt - * - * 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_LPC313X_DMA_H -#define __ARCH_ARM_SRC_LPC313X_DMA_H - -/************************************************************************************************ - * Included Files - ************************************************************************************************/ - -#include -#include "lpc313x_memorymap.h" - -/************************************************************************************************ - * Pre-processor Definitions - ************************************************************************************************/ - -/* DMA register base address offset into the APB4 domain ****************************************/ - -#define LPC313X_DMA_VBASE (LPC313X_APB4_VADDR+LPC313X_APB4_DMA_OFFSET) -#define LPC313X_DMA_PBASE (LPC313X_APB4_PADDR+LPC313X_APB4_DMA_OFFSET) - -/* DMA channel offsets (with respect to the DMA register base address) **************************/ - -#define LPC313X_DMACHAN_OFFSET(n) ((n)*0x020) -#define LPC313X_DMACHAN0_OFFSET 0x000 -#define LPC313X_DMACHAN1_OFFSET 0x020 -#define LPC313X_DMACHAN2_OFFSET 0x040 -#define LPC313X_DMACHAN3_OFFSET 0x060 -#define LPC313X_DMACHAN4_OFFSET 0x080 -#define LPC313X_DMACHAN5_OFFSET 0x0a0 -#define LPC313X_DMACHAN6_OFFSET 0x0c0 -#define LPC313X_DMACHAN7_OFFSET 0x0e0 -#define LPC313X_DMACHAN8_OFFSET 0x100 -#define LPC313X_DMACHAN9_OFFSET 0x120 -#define LPC313X_DMACHAN10_OFFSET 0x140 -#define LPC313X_DMACHAN11_OFFSET 0x160 - -#define LPC313X_DMACHAN_ALT_OFFSET(n) (0x200+((n)*0x020)) -#define LPC313X_DMACHAN0_ALT_OFFSET 0x200 -#define LPC313X_DMACHAN1_ALT_OFFSET 0x220 -#define LPC313X_DMACHAN2_ALT_OFFSET 0x240 -#define LPC313X_DMACHAN3_ALT_OFFSET 0x260 -#define LPC313X_DMACHAN4_ALT_OFFSET 0x280 -#define LPC313X_DMACHAN5_ALT_OFFSET 0x2a0 -#define LPC313X_DMACHAN6_ALT_OFFSET 0x2c0 -#define LPC313X_DMACHAN7_ALT_OFFSET 0x2e0 -#define LPC313X_DMACHAN8_ALT_OFFSET 0x300 -#define LPC313X_DMACHAN9_ALT_OFFSET 0x320 -#define LPC313X_DMACHAN10_ALT_OFFSET 0x340 -#define LPC313X_DMACHAN11_ALT_OFFSET 0x360 - -/* DMA channel virtual base addresses ***********************************************************/ - -#define LPC313X_DMACHAN_VBASE(n) (LPC313X_DMA_VBASE+LPC313X_DMACHAN_OFFSET(n)) -#define LPC313X_DMACHAN0_VBASE (LPC313X_DMA_VBASE+LPC313X_DMACHAN0_OFFSET) -#define LPC313X_DMACHAN1_VBASE (LPC313X_DMA_VBASE+LPC313X_DMACHAN1_OFFSET) -#define LPC313X_DMACHAN2_VBASE (LPC313X_DMA_VBASE+LPC313X_DMACHAN2_OFFSET) -#define LPC313X_DMACHAN3_VBASE (LPC313X_DMA_VBASE+LPC313X_DMACHAN3_OFFSET) -#define LPC313X_DMACHAN4_VBASE (LPC313X_DMA_VBASE+LPC313X_DMACHAN4_OFFSET) -#define LPC313X_DMACHAN5_VBASE (LPC313X_DMA_VBASE+LPC313X_DMACHAN5_OFFSET) -#define LPC313X_DMACHAN6_VBASE (LPC313X_DMA_VBASE+LPC313X_DMACHAN6_OFFSET) -#define LPC313X_DMACHAN7_VBASE (LPC313X_DMA_VBASE+LPC313X_DMACHAN7_OFFSET) -#define LPC313X_DMACHAN8_VBASE (LPC313X_DMA_VBASE+LPC313X_DMACHAN8_OFFSET) -#define LPC313X_DMACHAN9_VBASE (LPC313X_DMA_VBASE+LPC313X_DMACHAN9_OFFSET) -#define LPC313X_DMACHAN10_VBASE (LPC313X_DMA_VBASE+LPC313X_DMACHAN10_OFFSET) -#define LPC313X_DMACHAN11_VBASE (LPC313X_DMA_VBASE+LPC313X_DMACHAN11_OFFSET) - -#define LPC313X_DMACHAN_ALT_VBASE(n) (LPC313X_DMA_VBASE+LPC313X_DMACHAN_ALT_OFFSET(n)) -#define LPC313X_DMACHAN0_VBASE (LPC313X_DMA_VBASE+LPC313X_DMACHAN0_ALT_OFFSET) -#define LPC313X_DMACHAN1_VBASE (LPC313X_DMA_VBASE+LPC313X_DMACHAN1_ALT_OFFSET) -#define LPC313X_DMACHAN2_VBASE (LPC313X_DMA_VBASE+LPC313X_DMACHAN2_ALT_OFFSET) -#define LPC313X_DMACHAN3_VBASE (LPC313X_DMA_VBASE+LPC313X_DMACHAN3_ALT_OFFSET) -#define LPC313X_DMACHAN4_VBASE (LPC313X_DMA_VBASE+LPC313X_DMACHAN4_ALT_OFFSET) -#define LPC313X_DMACHAN5_VBASE (LPC313X_DMA_VBASE+LPC313X_DMACHAN5_ALT_OFFSET) -#define LPC313X_DMACHAN6_VBASE (LPC313X_DMA_VBASE+LPC313X_DMACHAN6_ALT_OFFSET) -#define LPC313X_DMACHAN7_VBASE (LPC313X_DMA_VBASE+LPC313X_DMACHAN7_ALT_OFFSET) -#define LPC313X_DMACHAN8_VBASE (LPC313X_DMA_VBASE+LPC313X_DMACHAN8_ALT_OFFSET) -#define LPC313X_DMACHAN9_VBASE (LPC313X_DMA_VBASE+LPC313X_DMACHAN9_ALT_OFFSET) -#define LPC313X_DMACHAN10_VBASE (LPC313X_DMA_VBASE+LPC313X_DMACHAN10_ALT_OFFSET) -#define LPC313X_DMACHAN11_VBASE (LPC313X_DMA_VBASE+LPC313X_DMACHAN11_ALT_OFFSET) - -/* DMA channel register offsets (with respect to the DMA channel register base) *****************/ - -#define LPC313X_DMACHAN_SRCADDR_OFFSET 0x000 /* Source address register of DMA channel */ -#define LPC313X_DMACHAN_DESTADDR_OFFSET 0X004 /* Destination address register of DMA channel */ -#define LPC313X_DMACHAN_XFERLEN_OFFSET 0X008 /* Transfer length register for DMA channel */ -#define LPC313X_DMACHAN_CONFIG_OFFSET 0x00c /* Configuration register for DMA channel */ -#define LPC313X_DMACHAN_ENABLE_OFFSET 0x010 /* Enable register for DMA channel */ -#define LPC313X_DMACHAN_XFERCOUNT_OFFSET 0x01c /* Transfer counter register for DMA channel */ - -/* DMA global register offsets (with respect to the DMA register base) *************************/ - -#define LPC313X_DMA_ALTENABLE_OFFSET 0x400 /* Alternative enable register */ -#define LPC313X_DMA_IRQSTATUSCLR_OFFSET 0x404 /* IRQ status clear register */ -#define LPC313X_DMA_IRQMASK_OFFSET 0x408 /* IRQ mask register */ -#define LPC313X_DMA_TESTSTATUS_OFFSET 0x40c /* Test FIFO response status register */ -#define LPC313X_DMA_SOFTINT_OFFSET 0x410 /* Software interrupt register */ - -/* DMA channel register (virtual) addresses *****************************************************/ - -#define LPC313X_DMACHAN_SRCADDR(n) (LPC313X_DMACHAN_VBASE(n)+LPC313X_DMACHAN_SRCADDR_OFFSET) -#define LPC313X_DMACHAN_DESTADDR(n) (LPC313X_DMACHAN_VBASE(n)+LPC313X_DMACHAN_DESTADDR_OFFSET) -#define LPC313X_DMACHAN_XFERLEN(n) (LPC313X_DMACHAN_VBASE(n)+LPC313X_DMACHAN_XFERLEN_OFFSET) -#define LPC313X_DMACHAN_CONFIG(n) (LPC313X_DMACHAN_VBASE(n)+LPC313X_DMACHAN_CONFIG_OFFSET) -#define LPC313X_DMACHAN_ENABLE(n) (LPC313X_DMACHAN_VBASE(n)+LPC313X_DMACHAN_ENABLE_OFFSET) -#define LPC313X_DMACHAN_XFERCOUNT(n) (LPC313X_DMACHAN_VBASE(n)+LPC313X_DMACHAN_XFERCOUNT_OFFSET) - -#define LPC313X_DMACHAN0_SRCADDR (LPC313X_DMACHAN0_VBASE+LPC313X_DMACHAN_SRCADDR_OFFSET) -#define LPC313X_DMACHAN0_DESTADDR (LPC313X_DMACHAN0_VBASE+LPC313X_DMACHAN_DESTADDR_OFFSET) -#define LPC313X_DMACHAN0_XFERLEN (LPC313X_DMACHAN0_VBASE+LPC313X_DMACHAN_XFERLEN_OFFSET) -#define LPC313X_DMACHAN0_CONFIG (LPC313X_DMACHAN0_VBASE+LPC313X_DMACHAN_CONFIG_OFFSET) -#define LPC313X_DMACHAN0_ENABLE (LPC313X_DMACHAN0_VBASE+LPC313X_DMACHAN_ENABLE_OFFSET) -#define LPC313X_DMACHAN0_XFERCOUNT (LPC313X_DMACHAN0_VBASE+LPC313X_DMACHAN_XFERCOUNT_OFFSET) - -#define LPC313X_DMACHAN1_SRCADDR (LPC313X_DMACHAN1_VBASE+LPC313X_DMACHAN_SRCADDR_OFFSET) -#define LPC313X_DMACHAN1_DESTADDR (LPC313X_DMACHAN1_VBASE+LPC313X_DMACHAN_DESTADDR_OFFSET) -#define LPC313X_DMACHAN1_XFERLEN (LPC313X_DMACHAN1_VBASE+LPC313X_DMACHAN_XFERLEN_OFFSET) -#define LPC313X_DMACHAN1_CONFIG (LPC313X_DMACHAN1_VBASE+LPC313X_DMACHAN_CONFIG_OFFSET) -#define LPC313X_DMACHAN1_ENABLE (LPC313X_DMACHAN1_VBASE+LPC313X_DMACHAN_ENABLE_OFFSET) -#define LPC313X_DMACHAN1_XFERCOUNT (LPC313X_DMACHAN1_VBASE+LPC313X_DMACHAN_XFERCOUNT_OFFSET) - -#define LPC313X_DMACHAN2_SRCADDR (LPC313X_DMACHAN2_VBASE+LPC313X_DMACHAN_SRCADDR_OFFSET) -#define LPC313X_DMACHAN2_DESTADDR (LPC313X_DMACHAN2_VBASE+LPC313X_DMACHAN_DESTADDR_OFFSET) -#define LPC313X_DMACHAN2_XFERLEN (LPC313X_DMACHAN2_VBASE+LPC313X_DMACHAN_XFERLEN_OFFSET) -#define LPC313X_DMACHAN2_CONFIG (LPC313X_DMACHAN2_VBASE+LPC313X_DMACHAN_CONFIG_OFFSET) -#define LPC313X_DMACHAN2_ENABLE (LPC313X_DMACHAN2_VBASE+LPC313X_DMACHAN_ENABLE_OFFSET) -#define LPC313X_DMACHAN2_XFERCOUNT (LPC313X_DMACHAN2_VBASE+LPC313X_DMACHAN_XFERCOUNT_OFFSET) - -#define LPC313X_DMACHAN3_SRCADDR (LPC313X_DMACHAN3_VBASE+LPC313X_DMACHAN_SRCADDR_OFFSET) -#define LPC313X_DMACHAN3_DESTADDR (LPC313X_DMACHAN3_VBASE+LPC313X_DMACHAN_DESTADDR_OFFSET) -#define LPC313X_DMACHAN3_XFERLEN (LPC313X_DMACHAN3_VBASE+LPC313X_DMACHAN_XFERLEN_OFFSET) -#define LPC313X_DMACHAN3_CONFIG (LPC313X_DMACHAN3_VBASE+LPC313X_DMACHAN_CONFIG_OFFSET) -#define LPC313X_DMACHAN3_ENABLE (LPC313X_DMACHAN3_VBASE+LPC313X_DMACHAN_ENABLE_OFFSET) -#define LPC313X_DMACHAN3_XFERCOUNT (LPC313X_DMACHAN3_VBASE+LPC313X_DMACHAN_XFERCOUNT_OFFSET) - -#define LPC313X_DMACHAN4_SRCADDR (LPC313X_DMACHAN4_VBASE+LPC313X_DMACHAN_SRCADDR_OFFSET) -#define LPC313X_DMACHAN4_DESTADDR (LPC313X_DMACHAN4_VBASE+LPC313X_DMACHAN_DESTADDR_OFFSET) -#define LPC313X_DMACHAN4_XFERLEN (LPC313X_DMACHAN4_VBASE+LPC313X_DMACHAN_XFERLEN_OFFSET) -#define LPC313X_DMACHAN4_CONFIG (LPC313X_DMACHAN4_VBASE+LPC313X_DMACHAN_CONFIG_OFFSET) -#define LPC313X_DMACHAN4_ENABLE (LPC313X_DMACHAN4_VBASE+LPC313X_DMACHAN_ENABLE_OFFSET) -#define LPC313X_DMACHAN4_XFERCOUNT (LPC313X_DMACHAN4_VBASE+LPC313X_DMACHAN_XFERCOUNT_OFFSET) - -#define LPC313X_DMACHAN5_SRCADDR (LPC313X_DMACHAN5_VBASE+LPC313X_DMACHAN_SRCADDR_OFFSET) -#define LPC313X_DMACHAN5_DESTADDR (LPC313X_DMACHAN5_VBASE+LPC313X_DMACHAN_DESTADDR_OFFSET) -#define LPC313X_DMACHAN5_XFERLEN (LPC313X_DMACHAN5_VBASE+LPC313X_DMACHAN_XFERLEN_OFFSET) -#define LPC313X_DMACHAN5_CONFIG (LPC313X_DMACHAN5_VBASE+LPC313X_DMACHAN_CONFIG_OFFSET) -#define LPC313X_DMACHAN5_ENABLE (LPC313X_DMACHAN5_VBASE+LPC313X_DMACHAN_ENABLE_OFFSET) -#define LPC313X_DMACHAN5_XFERCOUNT (LPC313X_DMACHAN5_VBASE+LPC313X_DMACHAN_XFERCOUNT_OFFSET) - -#define LPC313X_DMACHAN6_SRCADDR (LPC313X_DMACHAN6_VBASE+LPC313X_DMACHAN_SRCADDR_OFFSET) -#define LPC313X_DMACHAN6_DESTADDR (LPC313X_DMACHAN6_VBASE+LPC313X_DMACHAN_DESTADDR_OFFSET) -#define LPC313X_DMACHAN6_XFERLEN (LPC313X_DMACHAN6_VBASE+LPC313X_DMACHAN_XFERLEN_OFFSET) -#define LPC313X_DMACHAN6_CONFIG (LPC313X_DMACHAN6_VBASE+LPC313X_DMACHAN_CONFIG_OFFSET) -#define LPC313X_DMACHAN6_ENABLE (LPC313X_DMACHAN6_VBASE+LPC313X_DMACHAN_ENABLE_OFFSET) -#define LPC313X_DMACHAN6_XFERCOUNT (LPC313X_DMACHAN6_VBASE+LPC313X_DMACHAN_XFERCOUNT_OFFSET) - -#define LPC313X_DMACHAN7_SRCADDR (LPC313X_DMACHAN7_VBASE+LPC313X_DMACHAN_SRCADDR_OFFSET) -#define LPC313X_DMACHAN7_DESTADDR (LPC313X_DMACHAN7_VBASE+LPC313X_DMACHAN_DESTADDR_OFFSET) -#define LPC313X_DMACHAN7_XFERLEN (LPC313X_DMACHAN7_VBASE+LPC313X_DMACHAN_XFERLEN_OFFSET) -#define LPC313X_DMACHAN7_CONFIG (LPC313X_DMACHAN7_VBASE+LPC313X_DMACHAN_CONFIG_OFFSET) -#define LPC313X_DMACHAN7_ENABLE (LPC313X_DMACHAN7_VBASE+LPC313X_DMACHAN_ENABLE_OFFSET) -#define LPC313X_DMACHAN7_XFERCOUNT (LPC313X_DMACHAN7_VBASE+LPC313X_DMACHAN_XFERCOUNT_OFFSET)7 - -#define LPC313X_DMACHAN8_SRCADDR (LPC313X_DMACHAN8_VBASE+LPC313X_DMACHAN_SRCADDR_OFFSET) -#define LPC313X_DMACHAN8_DESTADDR (LPC313X_DMACHAN8_VBASE+LPC313X_DMACHAN_DESTADDR_OFFSET) -#define LPC313X_DMACHAN8_XFERLEN (LPC313X_DMACHAN8_VBASE+LPC313X_DMACHAN_XFERLEN_OFFSET) -#define LPC313X_DMACHAN8_CONFIG (LPC313X_DMACHAN8_VBASE+LPC313X_DMACHAN_CONFIG_OFFSET) -#define LPC313X_DMACHAN8_ENABLE (LPC313X_DMACHAN8_VBASE+LPC313X_DMACHAN_ENABLE_OFFSET) -#define LPC313X_DMACHAN8_XFERCOUNT (LPC313X_DMACHAN8_VBASE+LPC313X_DMACHAN_XFERCOUNT_OFFSET) - -#define LPC313X_DMACHAN9_SRCADDR (LPC313X_DMACHAN9_VBASE+LPC313X_DMACHAN_SRCADDR_OFFSET) -#define LPC313X_DMACHAN9_DESTADDR (LPC313X_DMACHAN9_VBASE+LPC313X_DMACHAN_DESTADDR_OFFSET) -#define LPC313X_DMACHAN9_XFERLEN (LPC313X_DMACHAN9_VBASE+LPC313X_DMACHAN_XFERLEN_OFFSET) -#define LPC313X_DMACHAN9_CONFIG (LPC313X_DMACHAN9_VBASE+LPC313X_DMACHAN_CONFIG_OFFSET) -#define LPC313X_DMACHAN9_ENABLE (LPC313X_DMACHAN9_VBASE+LPC313X_DMACHAN_ENABLE_OFFSET) -#define LPC313X_DMACHAN9_XFERCOUNT (LPC313X_DMACHAN9_VBASE+LPC313X_DMACHAN_XFERCOUNT_OFFSET) - -#define LPC313X_DMACHAN10_SRCADDR (LPC313X_DMACHAN10_VBASE+LPC313X_DMACHAN_SRCADDR_OFFSET) -#define LPC313X_DMACHAN10_DESTADDR (LPC313X_DMACHAN10_VBASE+LPC313X_DMACHAN_DESTADDR_OFFSET) -#define LPC313X_DMACHAN10_XFERLEN (LPC313X_DMACHAN10_VBASE+LPC313X_DMACHAN_XFERLEN_OFFSET) -#define LPC313X_DMACHAN10_CONFIG (LPC313X_DMACHAN10_VBASE+LPC313X_DMACHAN_CONFIG_OFFSET) -#define LPC313X_DMACHAN10_ENABLE (LPC313X_DMACHAN10_VBASE+LPC313X_DMACHAN_ENABLE_OFFSET) -#define LPC313X_DMACHAN10_XFERCOUNT (LPC313X_DMACHAN10_VBASE+LPC313X_DMACHAN_XFERCOUNT_OFFSET) - -#define LPC313X_DMACHAN11_SRCADDR (LPC313X_DMACHAN11_VBASE+LPC313X_DMACHAN_SRCADDR_OFFSET) -#define LPC313X_DMACHAN11_DESTADDR (LPC313X_DMACHAN11_VBASE+LPC313X_DMACHAN_DESTADDR_OFFSET) -#define LPC313X_DMACHAN11_XFERLEN (LPC313X_DMACHAN11_VBASE+LPC313X_DMACHAN_XFERLEN_OFFSET) -#define LPC313X_DMACHAN11_CONFIG (LPC313X_DMACHAN11_VBASE+LPC313X_DMACHAN_CONFIG_OFFSET) -#define LPC313X_DMACHAN11_ENABLE (LPC313X_DMACHAN11_VBASE+LPC313X_DMACHAN_ENABLE_OFFSET) -#define LPC313X_DMACHAN11_XFERCOUNT (LPC313X_DMACHAN11_VBASE+LPC313X_DMACHAN_XFERCOUNT_OFFSET) - -#define LPC313X_DMACHAN_ALT_SRCADDR(n) (LPC313X_DMACHAN_ALT_VBASE(n)+LPC313X_DMACHAN_SRCADDR_OFFSET) -#define LPC313X_DMACHAN_ALT_DESTADDR(n) (LPC313X_DMACHAN_ALT_VBASE(n)+LPC313X_DMACHAN_DESTADDR_OFFSET) -#define LPC313X_DMACHAN_ALT_XFERLEN(n) (LPC313X_DMACHAN_ALT_VBASE(n)+LPC313X_DMACHAN_XFERLEN_OFFSET) -#define LPC313X_DMACHAN_ALT_CONFIG(n) (LPC313X_DMACHAN_ALT_VBASE(n)+LPC313X_DMACHAN_CONFIG_OFFSET) - -#define LPC313X_DMACHAN0_ALT_SRCADDR (LPC313X_DMACHAN0_ALT_VBASE+LPC313X_DMACHAN_SRCADDR_OFFSET) -#define LPC313X_DMACHAN0_ALT_DESTADDR (LPC313X_DMACHAN0_ALT_VBASE+LPC313X_DMACHAN_DESTADDR_OFFSET) -#define LPC313X_DMACHAN0_ALT_XFERLEN (LPC313X_DMACHAN0_ALT_VBASE+LPC313X_DMACHAN_XFERLEN_OFFSET) -#define LPC313X_DMACHAN0_ALT_CONFIG (LPC313X_DMACHAN0_ALT_VBASE+LPC313X_DMACHAN_CONFIG_OFFSET) - -#define LPC313X_DMACHAN1_ALT_SRCADDR (LPC313X_DMACHAN1_ALT_VBASE+LPC313X_DMACHAN_SRCADDR_OFFSET) -#define LPC313X_DMACHAN1_ALT_DESTADDR (LPC313X_DMACHAN1_ALT_VBASE+LPC313X_DMACHAN_DESTADDR_OFFSET) -#define LPC313X_DMACHAN1_ALT_XFERLEN (LPC313X_DMACHAN1_ALT_VBASE+LPC313X_DMACHAN_XFERLEN_OFFSET) -#define LPC313X_DMACHAN1_ALT_CONFIG (LPC313X_DMACHAN1_ALT_VBASE+LPC313X_DMACHAN_CONFIG_OFFSET) - -#define LPC313X_DMACHAN2_ALT_SRCADDR (LPC313X_DMACHAN2_ALT_VBASE+LPC313X_DMACHAN_SRCADDR_OFFSET) -#define LPC313X_DMACHAN2_ALT_DESTADDR (LPC313X_DMACHAN2_ALT_VBASE+LPC313X_DMACHAN_DESTADDR_OFFSET) -#define LPC313X_DMACHAN2_ALT_XFERLEN (LPC313X_DMACHAN2_ALT_VBASE+LPC313X_DMACHAN_XFERLEN_OFFSET) -#define LPC313X_DMACHAN2_ALT_CONFIG (LPC313X_DMACHAN2_ALT_VBASE+LPC313X_DMACHAN_CONFIG_OFFSET) - -#define LPC313X_DMACHAN3_ALT_SRCADDR (LPC313X_DMACHAN3_ALT_VBASE+LPC313X_DMACHAN_SRCADDR_OFFSET) -#define LPC313X_DMACHAN3_ALT_DESTADDR (LPC313X_DMACHAN3_ALT_VBASE+LPC313X_DMACHAN_DESTADDR_OFFSET) -#define LPC313X_DMACHAN3_ALT_XFERLEN (LPC313X_DMACHAN3_ALT_VBASE+LPC313X_DMACHAN_XFERLEN_OFFSET) -#define LPC313X_DMACHAN3_ALT_CONFIG (LPC313X_DMACHAN3_ALT_VBASE+LPC313X_DMACHAN_CONFIG_OFFSET) - -#define LPC313X_DMACHAN4_ALT_SRCADDR (LPC313X_DMACHAN4_ALT_VBASE+LPC313X_DMACHAN_SRCADDR_OFFSET) -#define LPC313X_DMACHAN4_ALT_DESTADDR (LPC313X_DMACHAN4_ALT_VBASE+LPC313X_DMACHAN_DESTADDR_OFFSET) -#define LPC313X_DMACHAN4_ALT_XFERLEN (LPC313X_DMACHAN4_ALT_VBASE+LPC313X_DMACHAN_XFERLEN_OFFSET) -#define LPC313X_DMACHAN4_ALT_CONFIG (LPC313X_DMACHAN4_ALT_VBASE+LPC313X_DMACHAN_CONFIG_OFFSET) - -#define LPC313X_DMACHAN5_ALT_SRCADDR (LPC313X_DMACHAN5_ALT_VBASE+LPC313X_DMACHAN_SRCADDR_OFFSET) -#define LPC313X_DMACHAN5_ALT_DESTADDR (LPC313X_DMACHAN5_ALT_VBASE+LPC313X_DMACHAN_DESTADDR_OFFSET) -#define LPC313X_DMACHAN5_ALT_XFERLEN (LPC313X_DMACHAN5_ALT_VBASE+LPC313X_DMACHAN_XFERLEN_OFFSET) -#define LPC313X_DMACHAN5_ALT_CONFIG (LPC313X_DMACHAN5_ALT_VBASE+LPC313X_DMACHAN_CONFIG_OFFSET) - -#define LPC313X_DMACHAN6_ALT_SRCADDR (LPC313X_DMACHAN6_ALT_VBASE+LPC313X_DMACHAN_SRCADDR_OFFSET) -#define LPC313X_DMACHAN6_ALT_DESTADDR (LPC313X_DMACHAN6_ALT_VBASE+LPC313X_DMACHAN_DESTADDR_OFFSET) -#define LPC313X_DMACHAN6_ALT_XFERLEN (LPC313X_DMACHAN6_ALT_VBASE+LPC313X_DMACHAN_XFERLEN_OFFSET) -#define LPC313X_DMACHAN6_ALT_CONFIG (LPC313X_DMACHAN6_ALT_VBASE+LPC313X_DMACHAN_CONFIG_OFFSET) - -#define LPC313X_DMACHAN7_ALT_SRCADDR (LPC313X_DMACHAN7_ALT_VBASE+LPC313X_DMACHAN_SRCADDR_OFFSET) -#define LPC313X_DMACHAN7_ALT_DESTADDR (LPC313X_DMACHAN7_ALT_VBASE+LPC313X_DMACHAN_DESTADDR_OFFSET) -#define LPC313X_DMACHAN7_ALT_XFERLEN (LPC313X_DMACHAN7_ALT_VBASE+LPC313X_DMACHAN_XFERLEN_OFFSET) -#define LPC313X_DMACHAN7_ALT_CONFIG (LPC313X_DMACHAN7_ALT_VBASE+LPC313X_DMACHAN_CONFIG_OFFSET) - -#define LPC313X_DMACHAN8_ALT_SRCADDR (LPC313X_DMACHAN8_ALT_VBASE+LPC313X_DMACHAN_SRCADDR_OFFSET) -#define LPC313X_DMACHAN8_ALT_DESTADDR (LPC313X_DMACHAN8_ALT_VBASE+LPC313X_DMACHAN_DESTADDR_OFFSET) -#define LPC313X_DMACHAN8_ALT_XFERLEN (LPC313X_DMACHAN8_ALT_VBASE+LPC313X_DMACHAN_XFERLEN_OFFSET) -#define LPC313X_DMACHAN8_ALT_CONFIG (LPC313X_DMACHAN8_ALT_VBASE+LPC313X_DMACHAN_CONFIG_OFFSET) - -#define LPC313X_DMACHAN9_ALT_SRCADDR (LPC313X_DMACHAN9_ALT_VBASE+LPC313X_DMACHAN_SRCADDR_OFFSET) -#define LPC313X_DMACHAN9_ALT_DESTADDR (LPC313X_DMACHAN9_ALT_VBASE+LPC313X_DMACHAN_DESTADDR_OFFSET) -#define LPC313X_DMACHAN9_ALT_XFERLEN (LPC313X_DMACHAN9_ALT_VBASE+LPC313X_DMACHAN_XFERLEN_OFFSET) -#define LPC313X_DMACHAN9_ALT_CONFIG (LPC313X_DMACHAN9_ALT_VBASE+LPC313X_DMACHAN_CONFIG_OFFSET) - -#define LPC313X_DMACHAN10_ALT_SRCADDR (LPC313X_DMACHAN10_ALT_VBASE+LPC313X_DMACHAN_SRCADDR_OFFSET) -#define LPC313X_DMACHAN10_ALT_DESTADDR (LPC313X_DMACHAN10_ALT_VBASE+LPC313X_DMACHAN_DESTADDR_OFFSET) -#define LPC313X_DMACHAN10_ALT_XFERLEN (LPC313X_DMACHAN10_ALT_VBASE+LPC313X_DMACHAN_XFERLEN_OFFSET) -#define LPC313X_DMACHAN10_ALT_CONFIG (LPC313X_DMACHAN10_ALT_VBASE+LPC313X_DMACHAN_CONFIG_OFFSET) - -#define LPC313X_DMACHAN11_ALT_SRCADDR (LPC313X_DMACHAN11_ALT_VBASE+LPC313X_DMACHAN_SRCADDR_OFFSET) -#define LPC313X_DMACHAN11_ALT_DESTADDR (LPC313X_DMACHAN11_ALT_VBASE+LPC313X_DMACHAN_DESTADDR_OFFSET) -#define LPC313X_DMACHAN11_ALT_XFERLEN (LPC313X_DMACHAN11_ALT_VBASE+LPC313X_DMACHAN_XFERLEN_OFFSET) -#define LPC313X_DMACHAN11_ALT_CONFIG (LPC313X_DMACHAN11_ALT_VBASE+LPC313X_DMACHAN_CONFIG_OFFSET) - -/* DMA global register (virtual) addresses ******************************************************/ - -#define LPC313X_DMA_ALTENABLE (LPC313X_DMA_VBASE+LPC313X_DMA_ALTENABLE_OFFSET) -#define LPC313X_DMA_IRQSTATUSCLR (LPC313X_DMA_VBASE+LPC313X_DMA_IRQSTATUSCLR_OFFSET) -#define LPC313X_DMA_IRQMASK (LPC313X_DMA_VBASE+LPC313X_DMA_IRQMASK_OFFSET) -#define LPC313X_DMA_TESTSTATUS (LPC313X_DMA_VBASE+LPC313X_DMA_TESTSTATUS_OFFSET) -#define LPC313X_DMA_SOFTINT (LPC313X_DMA_VBASE+LPC313X_DMA_SOFTINT_OFFSET) - -/* DMA channel register bit definitions *********************************************************/ - -/* TRANSFER_LENGTH (addresses 0x17000008 (channel 0) to 0x17000168 (channel 11)) */ - -#define DMACHAN_XFRLEN_SHIFT (0) /* Bits 0-20: Transfer length */ -#define DMACHAN_XFRLEN_MASK (0x001fffff << DMACHAN_XFRLEN_SHIFT) - -/* CONFIGURATION (addresses 0x1700000c (channel 0) to 0x1700016c (channel 11)) */ - -#define DMACHAN_CONFIG_CIRC (1 << 18) /* Bit 18: Enable circular buffer */ -#define DMACHAN_CONFIG_COMPCHENABLE (1 << 17) /* Bit 17: Enable companion channel */ -#define DMACHAN_CONFIG_COMPCHNR_SHIFT (13) /* Bits 13-15: Companion channel number */ -#define DMACHAN_CONFIG_COMPCHNR_MASK (7 << DMACHAN_CONFIG_COMPCHNR_SHIFT) -#define DMACHAN_CONFIG_INVENDIAN (1 << 12) /* Bit 12: Invert endian-ness */ -#define DMACHAN_CONFIG_XFERSIZE_SHIFT (10) /* Bits 10-11: Transfer size */ -#define DMACHAN_CONFIG_XFERSIZE_MASK (3 << DMACHAN_CONFIG_XFERSIZE_SHIFT) -# define DMACHAN_CONFIG_XFERSIZE_WORDS (0 << DMACHAN_CONFIG_XFERSIZE_SHIFT) /* Transfer words */ -# define DMACHAN_CONFIG_XFERSIZE_HWORDS (1 << DMACHAN_CONFIG_XFERSIZE_SHIFT) /* Transfer half-words */ -# define DMACHAN_CONFIG_XFERSIZE_BYTES (2 << DMACHAN_CONFIG_XFERSIZE_SHIFT) /* Transfer bytes */ -# define DMACHAN_CONFIG_XFERSIZE_BURSTS (3 << DMACHAN_CONFIG_XFERSIZE_SHIFT) /* Transfer bursts */ -#define DMACHAN_CONFIG_RDSLAVENR_SHIFT (5) /* Bits 5-9: Read slave enable */ -#define DMACHAN_CONFIG_RDSLAVENR_MASK (31 << DMACHAN_CONFIG_RDSLAVENR_SHIFT) -#define DMACHAN_CONFIG_WRSLAVENR_SHIFT (0) /* Bits 0-4: Write slave enable */ -#define DMACHAN_CONFIG_WRSLAVENR_MASK (31 << DMACHAN_CONFIG_WRSLAVENR_SHIFT) - -/* ENABLE (addresses 0x17000010 (channel 0) to 0x17000170 (channel 11)) */ - -#define DMACHAN_ENABLE_BIT (1 << 0) /* Bit 0: Enable */ - -/* TRANSFER_COUNTER (addresses 0x1700001v (channel 0) to 0x1700017c (channel 11)) */ - -#define DMACHAN_XFRCOUNT_SHIFT (0) /* Bits 0-20: Transfer count */ -#define DMACHAN_XFRCOUNT_MASK (0x001fffff << DMACHAN_XFRCOUNT_SHIFT) - -/* DMA global register bit definitions **********************************************************/ - -/* ALT_ENABLE (address 0x17000400) */ - -#define DMA_ALTENABLE_CHAN11 (1 << 11) /* Bit 11: Enable channel 11 */ -#define DMA_ALTENABLE_CHAN10 (1 << 10) /* Bit 10: Enable channel 10 */ -#define DMA_ALTENABLE_CHAN9 (1 << 9) /* Bit 9: Enable channel 9 */ -#define DMA_ALTENABLE_CHAN8 (1 << 8) /* Bit 8: Enable channel 8 */ -#define DMA_ALTENABLE_CHAN7 (1 << 7) /* Bit 7: Enable channel 7 */ -#define DMA_ALTENABLE_CHAN6 (1 << 6) /* Bit 6: Enable channel 6 */ -#define DMA_ALTENABLE_CHAN5 (1 << 5) /* Bit 5: Enable channel 5 */ -#define DMA_ALTENABLE_CHAN4 (1 << 4) /* Bit 4: Enable channel 4 */ -#define DMA_ALTENABLE_CHAN3 (1 << 3) /* Bit 3: Enable channel 3 */ -#define DMA_ALTENABLE_CHAN2 (1 << 2) /* Bit 2: Enable channel 2 */ -#define DMA_ALTENABLE_CHAN1 (1 << 1) /* Bit 1: Enable channel 1 */ -#define DMA_ALTENABLE_CHAN0 (1 << 0) /* Bit 0: Enable channel 0 */ - -/* IRQ_STATUS_CLR (address 0x17000404) */ - -#define DMA_IRQSTATUSCLR_DMAABORT (1 << 31) /* Bit 31: DMA abort */ -#define DMA_IRQSTATUSCLR_SOFTINT (1 << 30) /* Bit 30: Soft interrupt, scatter gather */ -#define DMA_IRQSTATUSCLR_HALFWAY11 (1 << 23) /* Bit 23: Chan 11 more than half finished */ -#define DMA_IRQSTATUSCLR_FINISHED11 (1 << 22) /* Bit 22: Chan 11 finished */ -#define DMA_IRQSTATUSCLR_HALFWAY10 (1 << 21) /* Bit 21: Chan 10 more than half finished */ -#define DMA_IRQSTATUSCLR_FINISHED10 (1 << 20) /* Bit 20: Chan 10 finished */ -#define DMA_IRQSTATUSCLR_HALFWAY9 (1 << 19) /* Bit 19: Chan 9 more than half finished */ -#define DMA_IRQSTATUSCLR_FINISHED9 (1 << 18) /* Bit 18: Chan 9 finished */ -#define DMA_IRQSTATUSCLR_HALFWAY8 (1 << 17) /* Bit 17: Chan 8 more than half finished */ -#define DMA_IRQSTATUSCLR_FINISHED8 (1 << 16) /* Bit 16: Chan 8 finished */ -#define DMA_IRQSTATUSCLR_HALFWAY7 (1 << 15) /* Bit 15: Chan 7 more than half finished */ -#define DMA_IRQSTATUSCLR_FINISHED7 (1 << 14) /* Bit 14: Chan 7 finished */ -#define DMA_IRQSTATUSCLR_HALFWAY6 (1 << 13) /* Bit 13: Chan 6 more than half finished */ -#define DMA_IRQSTATUSCLR_FINISHED6 (1 << 12) /* Bit 12: Chan 6 finished */ -#define DMA_IRQSTATUSCLR_HALFWAY5 (1 << 11) /* Bit 11: Chan 5 more than half finished */ -#define DMA_IRQSTATUSCLR_FINISHED5 (1 << 10) /* Bit 10: Chan 5 finished */ -#define DMA_IRQSTATUSCLR_HALFWAY4 (1 << 9) /* Bit 9: Chan 4 more than half finished */ -#define DMA_IRQSTATUSCLR_FINISHED4 (1 << 8) /* Bit 8: Chan 4 finished */ -#define DMA_IRQSTATUSCLR_HALFWAY3 (1 << 7) /* Bit 7: Chan 3 more than half finished */ -#define DMA_IRQSTATUSCLR_FINISHED3 (1 << 6) /* Bit 6: Chan 3 finished */ -#define DMA_IRQSTATUSCLR_HALFWAY2 (1 << 5) /* Bit 5: Chan 2 more than half finished */ -#define DMA_IRQSTATUSCLR_FINISHED2 (1 << 4) /* Bit 4: Chan 2 finished */ -#define DMA_IRQSTATUSCLR_HALFWAY1 (1 << 3) /* Bit 3: Chan 1 more than half finished */ -#define DMA_IRQSTATUSCLR_FINISHED1 (1 << 2) /* Bit 2: Chan 1 finished */ -#define DMA_IRQSTATUSCLR_HALFWAY0 (1 << 1) /* Bit 1: Chan 0 more than half finished */ -#define DMA_IRQSTATUSCLR_FINISHED0 (1 << 0) /* Bit 0: Chan 0 finished */ - -/* IRQ_MASK (address 0x17000404) */ - -#define DMA_IRQMASK_DMAABORT (1 << 31) /* Bit 31: DMA abort */ -#define DMA_IRQMASK_SOFTINT (1 << 30) /* Bit 30: Soft interrupt, scatter gather */ -#define DMA_IRQMASK_HALFWAY11 (1 << 23) /* Bit 23: Chan 11 more than half finished */ -#define DMA_IRQMASK_FINISHED11 (1 << 22) /* Bit 22: Chan 11 finished */ -#define DMA_IRQMASK_HALFWAY10 (1 << 21) /* Bit 21: Chan 10 more than half finished */ -#define DMA_IRQMASK_FINISHED10 (1 << 20) /* Bit 20: Chan 10 finished */ -#define DMA_IRQMASK_HALFWAY9 (1 << 19) /* Bit 19: Chan 9 more than half finished */ -#define DMA_IRQMASK_FINISHED9 (1 << 18) /* Bit 18: Chan 9 finished */ -#define DMA_IRQMASK_HALFWAY8 (1 << 17) /* Bit 17: Chan 8 more than half finished */ -#define DMA_IRQMASK_FINISHED8 (1 << 16) /* Bit 16: Chan 8 finished */ -#define DMA_IRQMASK_HALFWAY7 (1 << 15) /* Bit 15: Chan 7 more than half finished */ -#define DMA_IRQMASK_FINISHED7 (1 << 14) /* Bit 14: Chan 7 finished */ -#define DMA_IRQMASK_HALFWAY6 (1 << 13) /* Bit 13: Chan 6 more than half finished */ -#define DMA_IRQMASK_FINISHED6 (1 << 12) /* Bit 12: Chan 6 finished */ -#define DMA_IRQMASK_HALFWAY5 (1 << 11) /* Bit 11: Chan 5 more than half finished */ -#define DMA_IRQMASK_FINISHED5 (1 << 10) /* Bit 10: Chan 5 finished */ -#define DMA_IRQMASK_HALFWAY4 (1 << 9) /* Bit 9: Chan 4 more than half finished */ -#define DMA_IRQMASK_FINISHED4 (1 << 8) /* Bit 8: Chan 4 finished */ -#define DMA_IRQMASK_HALFWAY3 (1 << 7) /* Bit 7: Chan 3 more than half finished */ -#define DMA_IRQMASK_FINISHED3 (1 << 6) /* Bit 6: Chan 3 finished */ -#define DMA_IRQMASK_HALFWAY2 (1 << 5) /* Bit 5: Chan 2 more than half finished */ -#define DMA_IRQMASK_FINISHED2 (1 << 4) /* Bit 4: Chan 2 finished */ -#define DMA_IRQMASK_HALFWAY1 (1 << 3) /* Bit 3: Chan 1 more than half finished */ -#define DMA_IRQMASK_FINISHED1 (1 << 2) /* Bit 2: Chan 1 finished */ -#define DMA_IRQMASK_HALFWAY0 (1 << 1) /* Bit 1: Chan 0 more than half finished */ -#define DMA_IRQMASK_FINISHED0 (1 << 0) /* Bit 0: Chan 0 finished */ - -/* SOFT_INT (address 0x1700040c) */ - -#define DMA_SOFTINT_ENABLE (1 << 0) /* Bit 0: Enable soft interrupt */ - -/************************************************************************************************ - * Public Types - ************************************************************************************************/ - -/************************************************************************************************ - * Public Data - ************************************************************************************************/ - -/************************************************************************************************ - * Public Functions - ************************************************************************************************/ - -#endif /* __ARCH_ARM_SRC_LPC313X_DMA_H */ diff --git a/nuttx/arch/arm/src/lpc313x/lpc313x_esrndx.c b/nuttx/arch/arm/src/lpc313x/lpc313x_esrndx.c deleted file mode 100755 index 3fa300cfe..000000000 --- a/nuttx/arch/arm/src/lpc313x/lpc313x_esrndx.c +++ /dev/null @@ -1,134 +0,0 @@ -/************************************************************************ - * arch/arm/src/lpc313x/lpc313x_esrndx.c - * - * Copyright (C) 2009-2010 Gregory Nutt. All rights reserved. - * Author: Gregory Nutt - * - * References: - * - UM10314 LPC3130/31 User manual Rev. 1.01 — 9 September 2009 - * - lpc313x.cdl.drivers.zip example driver code - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name NuttX nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - ************************************************************************/ - -/************************************************************************ - * Included Files - ************************************************************************/ - -#include -#include - -#include "up_arch.h" -#include "lpc313x_cgudrvr.h" - -/************************************************************************ - * Pre-processor Definitions - ************************************************************************/ - -/************************************************************************ - * Private Data - ************************************************************************/ - -/************************************************************************ - * Private Functions - ************************************************************************/ - -/************************************************************************ - * Public Functions - ************************************************************************/ - -/************************************************************************ - * Name: lpc313x_esrndx - * - * Description: - * Given a clock ID, return the index of the corresponding ESR - * register (or ESRNDX_INVALID if there is no ESR associated with - * this clock ID). Indexing of ESRs differs slightly from the clock - * ID: There are 92 clock IDs but only 89 ESR regisers. There are no - * ESR registers for : - * - * - * CLKID_I2SRXBCK0 Clock ID 87: I2SRX_BCK0 - * CLKID_I2SRXBCK1, Clock ID 88: I2SRX_BCK1 - * - * and - * - * CLKID_SYSCLKO Clock ID 91: SYSCLK_O - * - ************************************************************************/ - -int lpc313x_esrndx(enum lpc313x_clockid_e clkid) -{ - int esrndx = (int)clkid; - - /* There ar 89 Enable Select Registers (ESR). Indexing for these - * registers is identical to indexing to other registers (like PCR), - * except that there are no ESR registers for - * - * - * CLKID_I2SRXBCK0 Clock ID 87: I2SRX_BCK0 - * CLKID_I2SRXBCK1, Clock ID 88: I2SRX_BCK1 - * - * and - * - * CLKID_SYSCLKO Clock ID 91: SYSCLK_O - */ - - switch (clkid) - { - /* There are no ESR registers corresponding to the following - * three clocks: - */ - - case CLKID_I2SRXBCK0: - case CLKID_I2SRXBCK1: - case CLKID_SYSCLKO: - esrndx = ESRNDX_INVALID; - break; - - /* These clock IDs are a special case and need to be adjusted - * by two: - * - * CLKID_SPICLK Clock ID 89, ESR index 87 - * CLKID_SPICLKGATED Clock ID 90, ESR index 88 - */ - - case CLKID_SPICLK: - case CLKID_SPICLKGATED: - esrndx = esrndx - 2; - break; - - /* The rest of the indices match up and we don't have to do anything. */ - - default: - break; - } - - return esrndx; -} diff --git a/nuttx/arch/arm/src/lpc313x/lpc313x_evntrtr.h b/nuttx/arch/arm/src/lpc313x/lpc313x_evntrtr.h deleted file mode 100755 index bf2162dbc..000000000 --- a/nuttx/arch/arm/src/lpc313x/lpc313x_evntrtr.h +++ /dev/null @@ -1,264 +0,0 @@ -/******************************************************************************************************** - * arch/arm/src/lpc313x/lpc313x_evntrtr.h - * - * Copyright (C) 2009-2010 Gregory Nutt. All rights reserved. - * Author: Gregory Nutt - * - * 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_LPC313X_EVNTRTR_H -#define __ARCH_ARM_SRC_LPC313X_EVNTRTR_H - -/******************************************************************************************************** - * Included Files - ********************************************************************************************************/ - -#include -#include "lpc313x_memorymap.h" - -/******************************************************************************************************** - * Pre-processor Definitions - ********************************************************************************************************/ - -/* EVNTRTR register base address offset into the APB0 domain ********************************************/ - -#define LPC313X_EVNTRTR_VBASE (LPC313X_APB0_VADDR+LPC313X_APB0_EVNTRTR_OFFSET) -#define LPC313X_EVNTRTR_PBASE (LPC313X_APB0_PADDR+LPC313X_APB0_EVNTRTR_OFFSET) - -/* Sizes of things */ - -#define LPC313X_EVNTRTR_NBANKS 4 /* Banks b=0-3 */ -#define LPC313X_EVNTRTR_NOUTPUTS 5 /* Outputs o=0-4 (incl CGU Wakeup) */ -#define LPC313X_EVNTRTR_NEVENTS (32*LPC313X_EVNTRTR_NBANKS) - -#define _B(b) ((b)<<2) /* Maps bank number 0-3 to word offset */ -#define _O(o) ((o)<<5) /* Maps output to bank group offset */ -#define _OB(o,b) (_O(o)+_B(b)) /* Mqpw output and bank to word offset */ - -#define EVNTRTR_EVENT(bank,bit) ((bank)<<5|bit) /* Makes a event number from a bank and bit */ -#define EVNTRTR_BANK(e) ((e)>>5) /* Maps a event to a bank */ -#define EVNTRTR_BIT(e) ((e)&0x1f) /* Maps a event to a bit */ - -/* EVNTRTR register offsets (with respect to the EVNTRTR base) ******************************************/ - - /* 0x0000-0x0bff: Reserved */ -#define LPC313X_EVNTRTR_PEND_OFFSET(b) (0x0c00+_B(b)) /* Input event pending */ -#define LPC313X_EVNTRTR_INTCLR_OFFSET(b) (0x0c20+_B(b)) /* Input event clear */ -#define LPC313X_EVNTRTR_INTSET_OFFSET(b) (0x0c40+_B(b)) /* Input event set */ -#define LPC313X_EVNTRTR_MASK_OFFSET(b) (0x0c60+_B(b)) /* Input event mask */ -#define LPC313X_EVNTRTR_MASKCLR_OFFSET(b) (0x0c80+_B(b)) /* Input event mask clear */ -#define LPC313X_EVNTRTR_MASKSET_OFFSET(b) (0x0ca0+_B(b)) /* Input event mask set */ -#define LPC313X_EVNTRTR_APR_OFFSET(b) (0x0cc0+_B(b)) /* Input event activation polarity */ -#define LPC313X_EVNTRTR_ATR_OFFSET(b) (0x0ce0+_B(b)) /* Input event activation type */ -#define LPC313X_EVNTRTR_RSR_OFFSET(b) (0x0d20+_B(b)) /* Input event raw status */ -#define LPC313X_EVNTRTR_INTOUT_OFFSET 0x0d40 /* State of interrupt output pins */ - /* 0x0e00-0x0ffc: Reserved */ -#define LPC313X_EVNTRTR_INTOUTPEND_OFFSET(o,b) (0x1000+_OB(o,b)) /* Interrupt output 'o' pending */ -#define LPC313X_EVNTRTR_CGUWKUPPEND_OFFSET(b) (0x1000+_OB(4,b)) /* cgu_wakeup pending */ -#define LPC313X_EVNTRTR_INTOUTMASK_OFFSET(o,b) (0x1400+_OB(o,b)) /* Interrupt output 'o' mask */ -#define LPC313X_EVNTRTR_CGUWKUPMASK_OFFSET(b) (0x1400+_OB(4,b)) /* cgu_wakeup mask */ -#define LPC313X_EVNTRTR_INTOUTMASKCLR_OFFSET(o,b) (0x1800+_OB(o,b)) /* Interrupt output 'o' mask clear */ -#define LPC313X_EVNTRTR_CGUWKUPMASKCLR_OFFSET(b) (0x1800+_OB(4,b)) /* cgu_wakeup mask clear */ -#define LPC313X_EVNTRTR_INTOUTMASKSET_OFFSET(o,b) (0x1c00+_OB(o,b)) /* Interrupt output 'o' mask set */ -#define LPC313X_EVNTRTR_CGUWKUPMASKSET_OFFSET(b) (0x1c00+_OB(4,b)) /* cgu_wakeup mask set */ - -/* EVNTRTR register (virtual) addresses *********************************************************************/ - -#define LPC313X_EVNTRTR_PEND(b) (LPC313X_EVNTRTR_VBASE+LPC313X_EVNTRTR_PEND_OFFSET(b)) -#define LPC313X_EVNTRTR_INTCLR(b) (LPC313X_EVNTRTR_VBASE+LPC313X_EVNTRTR_INTCLR_OFFSET(b)) -#define LPC313X_EVNTRTR_INTSET(b) (LPC313X_EVNTRTR_VBASE+LPC313X_EVNTRTR_INTSET_OFFSET(b)) -#define LPC313X_EVNTRTR_MASK(b) (LPC313X_EVNTRTR_VBASE+LPC313X_EVNTRTR_MASK_OFFSET(b)) -#define LPC313X_EVNTRTR_MASKCLR(b) (LPC313X_EVNTRTR_VBASE+LPC313X_EVNTRTR_MASKCLR_OFFSET(b)) -#define LPC313X_EVNTRTR_MASKSET(b) (LPC313X_EVNTRTR_VBASE+LPC313X_EVNTRTR_MASKSET_OFFSET(b)) -#define LPC313X_EVNTRTR_APR(b) (LPC313X_EVNTRTR_VBASE+LPC313X_EVNTRTR_APR_OFFSET(b)) -#define LPC313X_EVNTRTR_ATR(b) (LPC313X_EVNTRTR_VBASE+LPC313X_EVNTRTR_ATR_OFFSET(b)) -#define LPC313X_EVNTRTR_RSR(b) (LPC313X_EVNTRTR_VBASE+LPC313X_EVNTRTR_RSR_OFFSET(b)) -#define LPC313X_EVNTRTR_INTOUT (LPC313X_EVNTRTR_VBASE+LPC313X_EVNTRTR_INTOUT_OFFSET) -#define LPC313X_EVNTRTR_INTOUTPEND(o,b) (LPC313X_EVNTRTR_VBASE+LPC313X_EVNTRTR_INTOUTPEND_OFFSET(o,b)) -#define LPC313X_EVNTRTR_CGUWKUPPEND(b) (LPC313X_EVNTRTR_VBASE+LPC313X_EVNTRTR_CGUWKUPPEND_OFFSET(b)) -#define LPC313X_EVNTRTR_INTOUTMASK(o,b) (LPC313X_EVNTRTR_VBASE+LPC313X_EVNTRTR_INTOUTMASK_OFFSET(o,b)) -#define LPC313X_EVNTRTR_CGUWKUPMASK(b) (LPC313X_EVNTRTR_VBASE+LPC313X_EVNTRTR_CGUWKUPMASK_OFFSET(b)) -#define LPC313X_EVNTRTR_INTOUTMASKCLR(o,b) (LPC313X_EVNTRTR_VBASE+LPC313X_EVNTRTR_INTOUTMASKCLR_OFFSET(o,b)) -#define LPC313X_EVNTRTR_CGUWKUPMASKCLR(b) (LPC313X_EVNTRTR_VBASE+LPC313X_EVNTRTR_CGUWKUPMASKCLR_OFFSET(b)) -#define LPC313X_EVNTRTR_INTOUTMASKSET(o,b) (LPC313X_EVNTRTR_VBASE+LPC313X_EVNTRTR_INTOUTMASKSET_OFFSET(o,b)) -#define LPC313X_EVNTRTR_CGUWKUPMASKSET(b) (LPC313X_EVNTRTR_VBASE+LPC313X_EVNTRTR_CGUWKUPMASKSET_OFFSET(b) - -/* EVNTRTR event definitions ********************************************************************************/ -/* Bank 0 */ - -#define EVENTRTR_EBID6 EVNTRTR_EVENT(0,31) /* Input event from GPIO pin */ -#define EVENTRTR_EBID5 EVNTRTR_EVENT(0,30) /* Input event from GPIO pin */ -#define EVENTRTR_EBID4 EVNTRTR_EVENT(0,29) /* Input event from GPIO pin */ -#define EVENTRTR_EBID3 EVNTRTR_EVENT(0,28) /* Input event from GPIO pin */ -#define EVENTRTR_EBID2 EVNTRTR_EVENT(0,27) /* Input event from GPIO pin */ -#define EVENTRTR_EBID1 EVNTRTR_EVENT(0,26) /* Input event from GPIO pin */ -#define EVENTRTR_EBID0 EVNTRTR_EVENT(0,25) /* Input event from GPIO pin */ -#define EVENTRTR_MNANDRYBN3 EVNTRTR_EVENT(0,24) /* Input event from GPIO pin */ -#define EVENTRTR_MNANDRYBN2 EVNTRTR_EVENT(0,23) /* Input event from GPIO pin */ -#define EVENTRTR_MNANDRYBN1 EVNTRTR_EVENT(0,22) /* Input event from GPIO pin */ -#define EVENTRTR_MNANDRYBN0 EVNTRTR_EVENT(0,21) /* Input event from GPIO pin */ -#define EVENTRTR_MLCDRWWR EVNTRTR_EVENT(0,20) /* Input event from GPIO pin */ -#define EVENTRTR_MLCDERD EVNTRTR_EVENT(0,19) /* Input event from GPIO pin */ -#define EVENTRTR_MLCDCSB EVNTRTR_EVENT(0,18) /* Input event from GPIO pin */ -#define EVENTRTR_MLCDRS EVNTRTR_EVENT(0,17) /* Input event from GPIO pin */ -#define EVENTRTR_MLCDDB15 EVNTRTR_EVENT(0,16) /* Input event from GPIO pin */ -#define EVENTRTR_MLCDDB14 EVNTRTR_EVENT(0,15) /* Input event from GPIO pin */ -#define EVENTRTR_MLCDDB13 EVNTRTR_EVENT(0,14) /* Input event from GPIO pin */ -#define EVENTRTR_MLCDDB12 EVNTRTR_EVENT(0,13) /* Input event from GPIO pin */ -#define EVENTRTR_MLCDDB11 EVNTRTR_EVENT(0,12) /* Input event from GPIO pin */ -#define EVENTRTR_MLCDDB10 EVNTRTR_EVENT(0,11) /* Input event from GPIO pin */ -#define EVENTRTR_MLCDDB9 EVNTRTR_EVENT(0,10) /* Input event from GPIO pin */ -#define EVENTRTR_MLCDDB8 EVNTRTR_EVENT(0,9) /* Input event from GPIO pin */ -#define EVENTRTR_MLCDDB7 EVNTRTR_EVENT(0,8) /* Input event from GPIO pin */ -#define EVENTRTR_MLCDDB6 EVNTRTR_EVENT(0,7) /* Input event from GPIO pin */ -#define EVENTRTR_MLCDDB5 EVNTRTR_EVENT(0,6) /* Input event from GPIO pin */ -#define EVENTRTR_MLCDDB4 EVNTRTR_EVENT(0,5) /* Input event from GPIO pin */ -#define EVENTRTR_MLCDDB3 EVNTRTR_EVENT(0,4) /* Input event from GPIO pin */ -#define EVENTRTR_MLCDDB2 EVNTRTR_EVENT(0,3) /* Input event from GPIO pin */ -#define EVENTRTR_MLCDDB1 EVNTRTR_EVENT(0,2) /* Input event from GPIO pin */ -#define EVENTRTR_MLCDDB0 EVNTRTR_EVENT(0,1) /* Input event from GPIO pin */ -#define EVENTRTR_PCMINT EVNTRTR_EVENT(0,0) /* Input event from PCM */ - -/* Bank 1 */ - -#define EVENTRTR_GPIO16 EVNTRTR_EVENT(1,31) /* Input event from GPIO pin */ -#define EVENTRTR_GPIO15 EVNTRTR_EVENT(1,30) /* Input event from GPIO pin */ -#define EVENTRTR_GPIO14 EVNTRTR_EVENT(1,29) /* Input event from GPIO pin */ -#define EVENTRTR_GPIO13 EVNTRTR_EVENT(1,28) /* Input event from GPIO pin */ -#define EVENTRTR_GPIO12 EVNTRTR_EVENT(1,27) /* Input event from GPIO pin */ -#define EVENTRTR_GPIO11 EVNTRTR_EVENT(1,26) /* Input event from GPIO pin */ -#define EVENTRTR_MGPIO10 EVNTRTR_EVENT(1,25) /* Input event from GPIO pin */ -#define EVENTRTR_MGPIO9 EVNTRTR_EVENT(1,24) /* Input event from GPIO pin */ -#define EVENTRTR_MGPIO8 EVNTRTR_EVENT(1,23) /* Input event from GPIO pin */ -#define EVENTRTR_MGPIO7 EVNTRTR_EVENT(1,22) /* Input event from GPIO pin */ -#define EVENTRTR_MGPIO6 EVNTRTR_EVENT(1,21) /* Input event from GPIO pin */ -#define EVENTRTR_MGPIO5 EVNTRTR_EVENT(1,20) /* Input event from GPIO pin */ -#define EVENTRTR_GPIO4 EVNTRTR_EVENT(1,19) /* Input event from GPIO pin */ -#define EVENTRTR_GPIO3 EVNTRTR_EVENT(1,18) /* Input event from GPIO pin */ -#define EVENTRTR_GPIO2 EVNTRTR_EVENT(1,17) /* Input event from GPIO pin */ -#define EVENTRTR_GPIO1 EVNTRTR_EVENT(1,16) /* Input event from GPIO pin */ -#define EVENTRTR_GPIO0 EVNTRTR_EVENT(1,15) /* Input event from GPIO pin */ -#define EVENTRTR_EBINRASBLOUT1 EVNTRTR_EVENT(1,14) /* Input event from GPIO pin */ -#define EVENTRTR_EBINCASBLOUT0 EVNTRTR_EVENT(1,13) /* Input event from GPIO pin */ -#define EVENTRTR_EBIDQM0NOE EVNTRTR_EVENT(1,12) /* Input event from GPIO pin */ -#define EVENTRTR_EBIA1CLE EVNTRTR_EVENT(1,11) /* Input event from GPIO pin */ -#define EVENTRTR_EBIA0ALE EVNTRTR_EVENT(1,10) /* Input event from GPIO pin */ -#define EVENTRTR_EBINWE EVNTRTR_EVENT(1,9) /* Input event from GPIO pin */ -#define EVENTRTR_EBID15 EVNTRTR_EVENT(1,8) /* Input event from GPIO pin */ -#define EVENTRTR_EBID14 EVNTRTR_EVENT(1,7) /* Input event from GPIO pin */ -#define EVENTRTR_EBID13 EVNTRTR_EVENT(1,6) /* Input event from GPIO pin */ -#define EVENTRTR_EBID12 EVNTRTR_EVENT(1,5) /* Input event from GPIO pin */ -#define EVENTRTR_EBID11 EVNTRTR_EVENT(1,4) /* Input event from GPIO pin */ -#define EVENTRTR_EBID10 EVNTRTR_EVENT(1,3) /* Input event from GPIO pin */ -#define EVENTRTR_EBID9 EVNTRTR_EVENT(1,2) /* Input event from GPIO pin */ -#define EVENTRTR_EBID8 EVNTRTR_EVENT(1,1) /* Input event from GPIO pin */ -#define EVENTRTR_EBID7 EVNTRTR_EVENT(1,0) /* Input event from GPIO pin */ - -/* Bank 2 */ - -#define EVENTRTR_PWMDATA EVNTRTR_EVENT(2,31) /* Input event from GPIO pin */ -#define EVENTRTR_I2CSCL1 EVNTRTR_EVENT(2,30) /* Input event from GPIO pin */ -#define EVENTRTR_I2CSDA1 EVNTRTR_EVENT(2,29) /* Input event from GPIO pin */ -#define EVENTRTR_CLK256FSO EVNTRTR_EVENT(2,28) /* Input event from GPIO pin */ -#define EVENTRTR_I2STXWS1 EVNTRTR_EVENT(2,27) /* Input event from GPIO pin */ -#define EVENTRTR_I2STXBCK1 EVNTRTR_EVENT(2,26) /* Input event from GPIO pin */ -#define EVENTRTR_I2STXDATA1 EVNTRTR_EVENT(2,25) /* Input event from GPIO pin */ -#define EVENTRTR_I2SRXWS1 EVNTRTR_EVENT(2,24) /* Input event from GPIO pin */ -#define EVENTRTR_I2SRXBCK1 EVNTRTR_EVENT(2,23) /* Input event from GPIO pin */ -#define EVENTRTR_I2SRXDATA1 EVNTRTR_EVENT(2,22) /* Input event from GPIO pin */ -#define EVENTRTR_I2SRXWS0 EVNTRTR_EVENT(2,21) /* Input event from GPIO pin */ -#define EVENTRTR_I2SRXDATA0 EVNTRTR_EVENT(2,20) /* Input event from GPIO pin */ -#define EVENTRTR_I2SRXBCK0 EVNTRTR_EVENT(2,19) /* Input event from GPIO pin */ -#define EVENTRTR_MI2STXWS0 EVNTRTR_EVENT(2,18) /* Input event from GPIO pin */ -#define EVENTRTR_MI2STXDATA0 EVNTRTR_EVENT(2,17) /* Input event from GPIO pin */ -#define EVENTRTR_MI2STXBCK0 EVNTRTR_EVENT(2,16) /* Input event from GPIO pin */ -#define EVENTRTR_MI2STXCLK0 EVNTRTR_EVENT(2,15) /* Input event from GPIO pin */ -#define EVENTRTR_MUARTRTSN EVNTRTR_EVENT(2,14) /* Input event from GPIO pin */ -#define EVENTRTR_MUARTCTSN EVNTRTR_EVENT(2,13) /* Input event from GPIO pin */ -#define EVENTRTR_UARTTXD EVNTRTR_EVENT(2,12) /* Input event from GPIO pin */ -#define EVENTRTR_UARTRXD EVNTRTR_EVENT(2,11) /* Input event from GPIO pin */ -#define EVENTRTR_SPICSOUT0 EVNTRTR_EVENT(2,10) /* Input event from GPIO pin */ -#define EVENTRTR_SPISCK EVNTRTR_EVENT(2,9) /* Input event from GPIO pin */ -#define EVENTRTR_SPICSIN EVNTRTR_EVENT(2,8) /* Input event from GPIO pin */ -#define EVENTRTR_SPIMOSI EVNTRTR_EVENT(2,7) /* Input event from GPIO pin */ -#define EVENTRTR_SPIMISO EVNTRTR_EVENT(2,6) /* Input event from GPIO pin */ -#define EVENTRTR_NANDNCS3 EVNTRTR_EVENT(2,5) /* Input event from GPIO pin */ -#define EVENTRTR_NANDNCS2 EVNTRTR_EVENT(2,4) /* Input event from GPIO pin */ -#define EVENTRTR_NANDNCS1 EVNTRTR_EVENT(2,3) /* Input event from GPIO pin */ -#define EVENTRTR_NANDNCS0 EVNTRTR_EVENT(2,2) /* Input event from GPIO pin */ -#define EVENTRTR_GPIO18 EVNTRTR_EVENT(2,1) /* Input event from GPIO pin */ -#define EVENTRTR_GPIO17 EVNTRTR_EVENT(2,0) /* Input event from GPIO pin */ - -/* Bank 3 */ - /* 30-31: Reserved */ -#define EVENTRTR_ISRAM1MRCFINISHED EVNTRTR_EVENT(3,29) /* ISRAM1 redundancy controller event */ -#define EVENTRTR_ISRAM0MRCFINISHED EVNTRTR_EVENT(3,28) /* ISRAM0 redundancy controller event */ -#define EVENTRTR_USBID EVNTRTR_EVENT(3,27) /* Input event from GPIO pin */ -#define EVENTRTR_USBOTGVBUSPWREN EVNTRTR_EVENT(3,26) /* Input event from USB */ -#define EVENTRTR_USBATXPLLLOCK EVNTRTR_EVENT(3,25) /* USB PLL lock event */ -#define EVENTRTR_USBOTGAHBNEEDCLK EVNTRTR_EVENT(3,24) /* Input event from USB */ -#define EVENTRTR_USBVBUS EVNTRTR_EVENT(3,23) /* Input event from USB VBUS pin */ -#define EVENTRTR_MCICLK EVNTRTR_EVENT(3,22) /* Input event from GPIO pin */ -#define EVENTRTR_MCICMD EVNTRTR_EVENT(3,21) /* Input event from GPIO pin */ -#define EVENTRTR_MCIDAT7 EVNTRTR_EVENT(3,20) /* Input event from GPIO pin */ -#define EVENTRTR_MCIDAT6 EVNTRTR_EVENT(3,19) /* Input event from GPIO pin */ -#define EVENTRTR_MCIDAT5 EVNTRTR_EVENT(3,18) /* Input event from GPIO pin */ -#define EVENTRTR_MCIDAT4 EVNTRTR_EVENT(3,17) /* Input event from GPIO pin */ -#define EVENTRTR_MCIDAT3 EVNTRTR_EVENT(3,16) /* Input event from GPIO pin */ -#define EVENTRTR_MCIDAT2 EVNTRTR_EVENT(3,15) /* Input event from GPIO pin */ -#define EVENTRTR_MCIDAT1 EVNTRTR_EVENT(3,14) /* Input event from GPIO pin */ -#define EVENTRTR_MCIDAT0 EVNTRTR_EVENT(3,13) /* Input event from GPIO pin */ -#define EVENTRTR_ARM926LPNIRQ EVNTRTR_EVENT(3,12) /* Reflects nIRQ signal to ARM core */ -#define EVENTRTR_ARM926LPNFIQ EVNTRTR_EVENT(3,11) /* Reflects nFIQ signal to ARM core */ -#define EVENTRTR_I2C1SCLN EVNTRTR_EVENT(3,10) /* Input event from I2C1 */ -#define EVENTRTR_I2C0SCLN EVNTRTR_EVENT(3,9) /* Input event from I2C0 */ -#define EVENTRTR_UART EVNTRTR_EVENT(3,8) /* Input event from UART */ -#define EVENTRTR_WDOGM0 EVNTRTR_EVENT(3,7) /* Input event from Watchdog Timer */ -#define EVENTRTR_ADCINT EVNTRTR_EVENT(3,6) /* Input event from ADC */ -#define EVENTRTR_TIMER3INTCT1 EVNTRTR_EVENT(3,5) /* Input event from Timer 3 */ -#define EVENTRTR_TIMER2INTCT1 EVNTRTR_EVENT(3,4) /* Input event from Timer 2 */ -#define EVENTRTR_TIMER1INTCT1 EVNTRTR_EVENT(3,3) /* Input event from Timer 1 */ -#define EVENTRTR_TIMER0INTCT1 EVNTRTR_EVENT(3,2) /* Input event from Timer 0 */ -#define EVENTRTR_GPIO20 EVNTRTR_EVENT(3,1) /* Input event from GPIO20 */ -#define EVENTRTR_GPIO19 EVNTRTR_EVENT(3,0) /* Input event from GPIO19 */ - -/******************************************************************************************************** - * Public Types - ********************************************************************************************************/ - -/******************************************************************************************************** - * Public Data - ********************************************************************************************************/ - -/******************************************************************************************************** - * Public Functions - ********************************************************************************************************/ - -#endif /* __ARCH_ARM_SRC_LPC313X_EVNTRTR_H */ diff --git a/nuttx/arch/arm/src/lpc313x/lpc313x_fdcndx.c b/nuttx/arch/arm/src/lpc313x/lpc313x_fdcndx.c deleted file mode 100755 index bd8824a0c..000000000 --- a/nuttx/arch/arm/src/lpc313x/lpc313x_fdcndx.c +++ /dev/null @@ -1,127 +0,0 @@ -/************************************************************************ - * arch/arm/src/lpc313x/lpc313x_fdcndx.c - * - * Copyright (C) 2009-2010 Gregory Nutt. All rights reserved. - * Author: Gregory Nutt - * - * References: - * - UM10314 LPC3130/31 User manual Rev. 1.01 — 9 September 2009 - * - lpc313x.cdl.drivers.zip example driver code - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name NuttX nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - ************************************************************************/ - -/************************************************************************ - * Included Files - ************************************************************************/ - -#include -#include - -#include "up_arch.h" -#include "lpc313x_cgudrvr.h" - -/************************************************************************ - * Pre-processor Definitions - ************************************************************************/ - -/* The select register in the ESR registers vary in width from 1-3 bits. - * Below is a macro to select the widest case (which is OK because the - * undefined bits will be read as zero). Within the field, bits 0-7 to - * indicate the offset from the base FDC index. - */ - -#define CGU_ESRSEL(n) (((n)>>1)&7) - -/************************************************************************ - * Private Data - ************************************************************************/ - -static const uint8_t g_fdcbase[CGU_NDOMAINS] = -{ - FRACDIV_BASE0_LOW, /* Domain 0: SYS_BASE */ - FRACDIV_BASE1_LOW, /* Domain 1: AHB0APB0_BASE */ - FRACDIV_BASE2_LOW, /* Domain 2: AHB0APB1_BASE */ - FRACDIV_BASE3_LOW, /* Domain 3: AHB0APB2_BASE */ - FRACDIV_BASE4_LOW, /* Domain 4: AHB0APB3_BASE */ - FRACDIV_BASE5_LOW, /* Domain 5: PCM_BASE */ - FRACDIV_BASE6_LOW, /* Domain 6: UART_BASE */ - FRACDIV_BASE7_LOW, /* Domain 7: CLK1024FS_BASE */ - 0, /* Domain 8: BCK0_BASE (no ESR register) */ - 0, /* Domain 9: BCK1_BASE (no ESR register) */ - FRACDIV_BASE10_LOW, /* Domain 10: SPI_BASE */ - 0, /* Domain 11: SYSCLKO_BASE (no ESR register) */ -}; - -/************************************************************************ - * Private Functions - ************************************************************************/ - -/************************************************************************ - * Public Functions - ************************************************************************/ - -/************************************************************************ - * Name: lpc313x_fdcndx - * - * Description: - * Given a clock ID and its domain ID, return the index of the - * corresponding fractional divider register (or FDCNDX_INVALID if - * there is no fractional divider associated with this clock). - * - ************************************************************************/ - -int lpc313x_fdcndx(enum lpc313x_clockid_e clkid, enum lpc313x_domainid_e dmnid) -{ - int esrndx; - int fdcndx = FDCNDX_INVALID; - - /* Check if there is an ESR register associate with this clock ID */ - - esrndx = lpc313x_esrndx(clkid); - if (esrndx != ESRNDX_INVALID) - { - /* Read the clock's ESR to get the fractional divider */ - - uint32_t regval = getreg32(LPC313X_CGU_ESR(esrndx)); - - /* Check if any fractional divider is enabled for this clock. */ - - if ((regval & CGU_ESR_ESREN) != 0) - { - /* Yes.. The FDC index is an offset from this fractional - * divider base for this domain. - */ - - fdcndx = CGU_ESRSEL(regval) + (int)g_fdcbase[dmnid]; - } - } - return fdcndx; -} - diff --git a/nuttx/arch/arm/src/lpc313x/lpc313x_fdivinit.c b/nuttx/arch/arm/src/lpc313x/lpc313x_fdivinit.c deleted file mode 100755 index 3d90bcba6..000000000 --- a/nuttx/arch/arm/src/lpc313x/lpc313x_fdivinit.c +++ /dev/null @@ -1,204 +0,0 @@ -/**************************************************************************** - * arch/arm/src/lpc313x/lpc313x_fdivinit.c - * - * Copyright (C) 2009 Gregory Nutt. All rights reserved. - * Author: Gregory Nutt - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name NuttX nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************/ - -/**************************************************************************** - * Included Files - ****************************************************************************/ - -#include - -#include - -#include - -#include "lpc313x_cgu.h" -#include "lpc313x_cgudrvr.h" - -/**************************************************************************** - * Pre-processor Definitions - ****************************************************************************/ - -/**************************************************************************** - * Private Data - ****************************************************************************/ - -/**************************************************************************** - * Public Data - ****************************************************************************/ - -/**************************************************************************** - * Private Functions - ****************************************************************************/ - -/**************************************************************************** - * Name: lpc313x_bitwidth - * - * Description: - * Find the bit width of a msub or madd value. This will be use to - * extend the msub or madd values. To minimize power consumption, the - * lpc313x user manual recommends that madd and msub be shifted right - * to have as many trailing zero's as possible. This function detmines - * the pre-shifted with of one of the msub or madd values. - * - * EXAMPLE: - * - * Say an input frequency of 13 MHz is given while a frequency of 12 - * MHz is required. In this case we want a frequency - * - * f’ = 12/13 × f - * - * So n = 12 and m = 13. This then gives - * - * madd = m - n = 13 - 12 = 1 - * msub = -n = -12 - * - * In order to minimize power consumption madd and msub must be as - * large as possible. The limit of their values is determined by the - * madd/msub bit width. In this case msub is the largest value, - * in order to express -12, five bits are required. However since msub is - * always negative the fractional divider does not need the sign bit, leaving - * 4 bits. If madd/msub bit width has been set to say 8 bits, it is allowed - * to shift 4 bits, giving: - * - * msub’ = -(12<<4)= -12 × 24 = -12 × 16 = -192 - * madd’ = 1<<4 = 24 = 16 - * - ****************************************************************************/ - -static inline unsigned int -lpc313x_bitwidth(unsigned int value, unsigned int fdwid) -{ - unsigned int width = 0; - int bit; - - /* Examine bits from the most significant down */ - - for (bit = fdwid-1; bit >= 0; bit--) - { - /* Is this bit set? If so, then the width of the value is 0 to bit, - * or bit+1. - */ - - if ((value & (1 << bit)) != 0) - { - width = bit + 1; - break; - } - } - return width; -} - -/**************************************************************************** - * Public Functions - ****************************************************************************/ -/**************************************************************************** - * Name: lpc313x_fdivinit - * - * Description: - * Enable and configure (or disable) a fractional divider. - * - ****************************************************************************/ - -uint32_t lpc313x_fdivinit(int fdcndx, - const struct lpc313x_fdivconfig_s *fdiv, bool enable) -{ - uint32_t regaddr; - uint32_t regval; - unsigned int fdshift; - unsigned int fdwid; - unsigned int fdmask; - unsigned int maddshift; - unsigned int msubshift; - int madd; - int msub; - - /* Calculating the (unshifted) divider values.To minimize power - * consumption, the lpc313x user manual recommends that madd and msub - * be shifted right to have as many trailing zero's as possible. - */ - - madd = fdiv->m - fdiv->n; - msub = -fdiv->n; - - /* Determine the width of the madd and msub fields in the fractional divider - * register. They are all 8-bits in width except for fractional divider 17. - */ - - fdwid = CGU_FDC_FIELDWIDTH; - maddshift = CGU_FDC_MADD_SHIFT; - msubshift = CGU_FDC_MSUB_SHIFT; - - if (fdcndx == 17) - { - /* For fractional divider 17, the msub/madd field width is 13 */ - - fdwid = CGU_FDC17_FIELDWIDTH; - maddshift = CGU_FDC17_MADD_SHIFT; - msubshift = CGU_FDC17_MSUB_SHIFT; - } - - /* Find maximum bit width of madd & msub. Here we calculate the width of the OR - * of the two values. The width of the OR will be the width of the wider value - */ - - fdshift = fdwid - lpc313x_bitwidth((unsigned int)madd | (unsigned int)fdiv->n, fdwid); - - /* Calculate the fractional divider register values */ - - fdmask = (1 << fdwid) - 1; - madd = (madd << fdshift) & fdmask; - msub = (msub << fdshift) & fdmask; - regval = (madd << maddshift) | (msub << msubshift); - - /* Check if 50% duty cycle is needed for this divider */ - - if (fdiv->stretch) - { - regval |= CGU_FDC_STRETCH; - } - - /* Check if we should enable the divider immediately */ - - if (enable) - { - regval |= CGU_FDC_RUN; - } - - /* Finally configure the divider */ - - regaddr = LPC313X_CGU_FDC(fdcndx); - putreg32(regval, regaddr); - return regval; -} diff --git a/nuttx/arch/arm/src/lpc313x/lpc313x_freqin.c b/nuttx/arch/arm/src/lpc313x/lpc313x_freqin.c deleted file mode 100755 index deec49911..000000000 --- a/nuttx/arch/arm/src/lpc313x/lpc313x_freqin.c +++ /dev/null @@ -1,82 +0,0 @@ -/**************************************************************************** - * arch/arm/src/lpc313x/lpc313x_freqin.c - * - * Copyright (C) 2009 Gregory Nutt. All rights reserved. - * Author: Gregory Nutt - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name NuttX nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************/ - -/**************************************************************************** - * Included Files - ****************************************************************************/ - -#include - -#include - -#include - -#include "lpc313x_cgudrvr.h" - -/**************************************************************************** - * Pre-processor Definitions - ****************************************************************************/ - -/**************************************************************************** - * Private Data - ****************************************************************************/ - -/**************************************************************************** - * Public Data - ****************************************************************************/ - -/* This array provides the programmed frequency of every input source. The - * board FFAST input crystal frequency is the only value known initially. - * Additional frequencies will be added to the table as they are determined - */ - -uint32_t g_boardfreqin[CGU_NFREQIN] = -{ - BOARD_FREQIN_FFAST, /* Index=CGU_FREQIN_FFAST */ - 0, /* Index=CGU_FREQIN_I2SRXBCK0 */ - 0, /* Index=CGU_FREQIN_I2SRXWS0 */ - 0, /* Index=CGU_FREQIN_I2SRXBCK1 */ - 0, /* Index=CGU_FREQIN_I2SRXWS1 */ - 0, /* Index=CGU_FREQIN_HPPLL0 (Audio/I2S PLL) */ - 0 /* Index=CGU_FREQIN_HPPLL1 (System PLL) */ -}; - -/**************************************************************************** - * Private Functions - ****************************************************************************/ - -/**************************************************************************** - * Public Functions - ****************************************************************************/ diff --git a/nuttx/arch/arm/src/lpc313x/lpc313x_i2c.c b/nuttx/arch/arm/src/lpc313x/lpc313x_i2c.c deleted file mode 100644 index 3477b9e53..000000000 --- a/nuttx/arch/arm/src/lpc313x/lpc313x_i2c.c +++ /dev/null @@ -1,608 +0,0 @@ -/******************************************************************************* - * arch/arm/src/lpc313x/lpc313x_i2c.c - * - * Author: David Hewson - * - * Copyright (C) 2010-2011 Gregory Nutt. All rights reserved. - * Author: Gregory Nutt - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name NuttX nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - *******************************************************************************/ - -/******************************************************************************* - * Included Files - *******************************************************************************/ - -#include - -#include -#include -#include -#include -#include -#include -#include - -#include -#include - -#include -#include - -#include "wdog.h" -#include "chip.h" -#include "up_arch.h" -#include "up_internal.h" - -#include "lpc313x_i2c.h" -#include "lpc313x_evntrtr.h" -#include "lpc313x_syscreg.h" - -/******************************************************************************* - * Definitions - *******************************************************************************/ - -/**************************************************************************** - * Pre-processor Definitions - ****************************************************************************/ - -#define I2C_TIMEOUT ((20 * CLK_TCK) / 1000) /* 20 mS */ - -/**************************************************************************** - * Private Data - ****************************************************************************/ -struct lpc313x_i2cdev_s -{ - struct i2c_dev_s dev; /* Generic I2C device */ - struct i2c_msg_s msg; /* a single message for legacy read/write */ - unsigned int base; /* Base address of registers */ - uint16_t clkid; /* Clock for this device */ - uint16_t rstid; /* Reset for this device */ - uint16_t irqid; /* IRQ for this device */ - - sem_t mutex; /* Only one thread can access at a time */ - - sem_t wait; /* Place to wait for state machine completion */ - volatile uint8_t state; /* State of state machine */ - WDOG_ID timeout; /* watchdog to timeout when bus hung */ - - struct i2c_msg_s *msgs; /* remaining transfers - first one is in progress */ - unsigned int nmsg; /* number of transfer remaining */ - - uint16_t header[3]; /* I2C address header */ - uint16_t hdrcnt; /* number of bytes of header */ - uint16_t wrcnt; /* number of bytes sent to tx fifo */ - uint16_t rdcnt; /* number of bytes read from rx fifo */ -}; - -#define I2C_STATE_DONE 0 -#define I2C_STATE_START 1 -#define I2C_STATE_HEADER 2 -#define I2C_STATE_TRANSFER 3 - -static struct lpc313x_i2cdev_s i2cdevices[2]; - -/**************************************************************************** - * Private Functions - ****************************************************************************/ -static int i2c_interrupt (int irq, FAR void *context); -static void i2c_progress (struct lpc313x_i2cdev_s *priv); -static void i2c_timeout (int argc, uint32_t arg, ...); -static void i2c_reset (struct lpc313x_i2cdev_s *priv); - -/**************************************************************************** - * Public Functions - ****************************************************************************/ - -/**************************************************************************** - * I2C device operations - ****************************************************************************/ - -static uint32_t i2c_setfrequency(FAR struct i2c_dev_s *dev, uint32_t frequency); -static int i2c_setaddress(FAR struct i2c_dev_s *dev, int addr, int nbits); -static int i2c_write(FAR struct i2c_dev_s *dev, const uint8_t *buffer, int buflen); -static int i2c_read(FAR struct i2c_dev_s *dev, uint8_t *buffer, int buflen); -static int i2c_transfer(FAR struct i2c_dev_s *dev, FAR struct i2c_msg_s *msgs, int count); - -struct i2c_ops_s lpc313x_i2c_ops = { - .setfrequency = i2c_setfrequency, - .setaddress = i2c_setaddress, - .write = i2c_write, - .read = i2c_read, -#ifdef CONFIG_I2C_TRANSFER - .transfer = i2c_transfer -#endif -}; - -/******************************************************************************* - * Name: up_i2cinitialize - * - * Description: - * Initialise an I2C device - * - *******************************************************************************/ - -struct i2c_dev_s *up_i2cinitialize(int port) -{ - struct lpc313x_i2cdev_s *priv = &i2cdevices[port]; - - priv->base = (port == 0) ? LPC313X_I2C0_VBASE : LPC313X_I2C1_VBASE; - priv->clkid = (port == 0) ? CLKID_I2C0PCLK : CLKID_I2C1PCLK; - priv->rstid = (port == 0) ? RESETID_I2C0RST : RESETID_I2C1RST; - priv->irqid = (port == 0) ? LPC313X_IRQ_I2C0 : LPC313X_IRQ_I2C1; - - sem_init (&priv->mutex, 0, 1); - sem_init (&priv->wait, 0, 0); - - /* Enable I2C system clocks */ - - lpc313x_enableclock (priv->clkid); - - /* Reset I2C blocks */ - - lpc313x_softreset (priv->rstid); - - /* Soft reset the device */ - - i2c_reset (priv); - - /* Allocate a watchdog timer */ - priv->timeout = wd_create(); - - DEBUGASSERT(priv->timeout != 0); - - /* Attach Interrupt Handler */ - irq_attach (priv->irqid, i2c_interrupt); - - /* Enable Interrupt Handler */ - up_enable_irq(priv->irqid); - - /* Install our operations */ - priv->dev.ops = &lpc313x_i2c_ops; - - return &priv->dev; -} - -/******************************************************************************* - * Name: up_i2cuninitalize - * - * Description: - * Uninitialise an I2C device - * - *******************************************************************************/ - -void up_i2cuninitalize (struct lpc313x_i2cdev_s *priv) -{ - /* Disable All Interrupts, soft reset the device */ - - i2c_reset (priv); - - /* Detach Interrupt Handler */ - - irq_detach (priv->irqid); - - /* Reset I2C blocks */ - - lpc313x_softreset (priv->rstid); - - /* Disable I2C system clocks */ - - lpc313x_disableclock (priv->clkid); -} - -/******************************************************************************* - * Name: lpc313x_i2c_setfrequency - * - * Description: - * Set the frequence for the next transfer - * - *******************************************************************************/ - -static uint32_t i2c_setfrequency(FAR struct i2c_dev_s *dev, uint32_t frequency) -{ - struct lpc313x_i2cdev_s *priv = (struct lpc313x_i2cdev_s *) dev; - - uint32_t freq = lpc313x_clkfreq (priv->clkid, DOMAINID_AHB0APB1); - - if (freq > 100000) - { - /* asymetric per 400Khz I2C spec */ - putreg32 (((47 * freq) / (83 + 47)) / frequency, priv->base + LPC313X_I2C_CLKHI_OFFSET); - putreg32 (((83 * freq) / (83 + 47)) / frequency, priv->base + LPC313X_I2C_CLKLO_OFFSET); - } - else - { - /* 50/50 mark space ratio */ - putreg32 (((50 * freq) / 100) / frequency, priv->base + LPC313X_I2C_CLKLO_OFFSET); - putreg32 (((50 * freq) / 100) / frequency, priv->base + LPC313X_I2C_CLKHI_OFFSET); - } - - /* FIXME: This function should return the actual selected frequency */ - return frequency; -} - -/******************************************************************************* - * Name: lpc313x_i2c_setaddress - * - * Description: - * Set the I2C slave address for a subsequent read/write - * - *******************************************************************************/ -static int i2c_setaddress(FAR struct i2c_dev_s *dev, int addr, int nbits) -{ - struct lpc313x_i2cdev_s *priv = (struct lpc313x_i2cdev_s *) dev; - - DEBUGASSERT(dev != NULL); - DEBUGASSERT(nbits == 7 || nbits == 10); - - priv->msg.addr = addr; - priv->msg.flags = (nbits == 7) ? 0 : I2C_M_TEN; - - return OK; -} - -/******************************************************************************* - * Name: lpc313x_i2c_write - * - * Description: - * Send a block of data on I2C using the previously selected I2C - * frequency and slave address. - * - *******************************************************************************/ -static int i2c_write(FAR struct i2c_dev_s *dev, const uint8_t *buffer, int buflen) -{ - struct lpc313x_i2cdev_s *priv = (struct lpc313x_i2cdev_s *) dev; - int ret; - - DEBUGASSERT (dev != NULL); - - priv->msg.flags &= ~I2C_M_READ; - priv->msg.buffer = (uint8_t*)buffer; - priv->msg.length = buflen; - - ret = i2c_transfer (dev, &priv->msg, 1); - - return ret == 1 ? OK : -ETIMEDOUT; -} - -/******************************************************************************* - * Name: lpc313x_i2c_read - * - * Description: - * Receive a block of data on I2C using the previously selected I2C - * frequency and slave address. - * - *******************************************************************************/ -static int i2c_read(FAR struct i2c_dev_s *dev, uint8_t *buffer, int buflen) -{ - struct lpc313x_i2cdev_s *priv = (struct lpc313x_i2cdev_s *) dev; - int ret; - - DEBUGASSERT (dev != NULL); - - priv->msg.flags |= I2C_M_READ; - priv->msg.buffer = buffer; - priv->msg.length = buflen; - - ret = i2c_transfer (dev, &priv->msg, 1); - - return ret == 1 ? OK : -ETIMEDOUT; -} - -/******************************************************************************* - * Name: i2c_transfer - * - * Description: - * Perform a sequence of I2C transfers - * - *******************************************************************************/ - -static int i2c_transfer (FAR struct i2c_dev_s *dev, FAR struct i2c_msg_s *msgs, int count) -{ - struct lpc313x_i2cdev_s *priv = (struct lpc313x_i2cdev_s *) dev; - irqstate_t flags; - int ret; - - sem_wait (&priv->mutex); - flags = irqsave(); - - priv->state = I2C_STATE_START; - priv->msgs = msgs; - priv->nmsg = count; - - i2c_progress (priv); - - /* start a watchdog to timeout the transfer if - * the bus is locked up... */ - wd_start (priv->timeout, I2C_TIMEOUT, i2c_timeout, 1, (uint32_t)priv); - - while (priv->state != I2C_STATE_DONE) - { - sem_wait (&priv->wait); - } - - wd_cancel (priv->timeout); - - ret = count - priv->nmsg; - - irqrestore (flags); - sem_post (&priv->mutex); - - return ret; -} - -/******************************************************************************* - * Name: i2c_interrupt - * - * Description: - * The I2C Interrupt Handler - * - *******************************************************************************/ - -static int i2c_interrupt (int irq, FAR void *context) -{ - if (irq == LPC313X_IRQ_I2C0) - { - i2c_progress (&i2cdevices[0]); - } - - if (irq == LPC313X_IRQ_I2C1) - { - i2c_progress (&i2cdevices[1]); - } - - return OK; -} - -/******************************************************************************* - * Name: i2c_progress - * - * Description: - * Progress any remaining I2C transfers - * - *******************************************************************************/ - -static void i2c_progress (struct lpc313x_i2cdev_s *priv) -{ - struct i2c_msg_s *msg; - uint32_t stat, ctrl; - - stat = getreg32 (priv->base + LPC313X_I2C_STAT_OFFSET); - - /* Were there arbitration problems? */ - if ((stat & I2C_STAT_AFI) != 0) - { - /* Perform a soft reset */ - i2c_reset (priv); - - /* FIXME: automatic retry? */ - - priv->state = I2C_STATE_DONE; - sem_post (&priv->wait); - return; - } - - while (priv->nmsg > 0) - { - ctrl = I2C_CTRL_NAIE | I2C_CTRL_AFIE | I2C_CTRL_TDIE; - msg = priv->msgs; - - switch (priv->state) - { - case I2C_STATE_START: - if ((msg->flags & I2C_M_TEN) != 0) - { - priv->header[0] = I2C_TX_START | 0xF0 | ((msg->addr & 0x300) >> 7); - priv->header[1] = msg->addr & 0xFF; - priv->hdrcnt = 2; - if (msg->flags & I2C_M_READ) - { - priv->header[2] = priv->header[0] | 1; - priv->hdrcnt++; - } - } - else - { - priv->header[0] = I2C_TX_START | (msg->addr << 1) | (msg->flags & I2C_M_READ); - priv->hdrcnt = 1; - } - - putreg32 (ctrl, priv->base + LPC313X_I2C_CTRL_OFFSET); - - priv->state = I2C_STATE_HEADER; - priv->wrcnt = 0; - /* DROP THROUGH */ - - case I2C_STATE_HEADER: - while ((priv->wrcnt != priv->hdrcnt) && (stat & I2C_STAT_TFF) == 0) - { - putreg32(priv->header[priv->wrcnt], priv->base + LPC313X_I2C_TX_OFFSET); - priv->wrcnt++; - - stat = getreg32 (priv->base + LPC313X_I2C_STAT_OFFSET); - } - - if (priv->wrcnt < priv->hdrcnt) - { - /* Enable Tx FIFO Not Full Interrupt */ - putreg32 (ctrl | I2C_CTRL_TFFIE, priv->base + LPC313X_I2C_CTRL_OFFSET); - goto out; - } - - priv->state = I2C_STATE_TRANSFER; - priv->wrcnt = 0; - priv->rdcnt = 0; - /* DROP THROUGH */ - - case I2C_STATE_TRANSFER: - if (msg->flags & I2C_M_READ) - { - while ((priv->rdcnt != msg->length) && (stat & I2C_STAT_RFE) == 0) - { - msg->buffer[priv->rdcnt] = getreg32 (priv->base + LPC313X_I2C_RX_OFFSET); - priv->rdcnt++; - - stat = getreg32 (priv->base + LPC313X_I2C_STAT_OFFSET); - } - - if (priv->rdcnt < msg->length) - { - /* Not all data received, fill the Tx FIFO with more dummies */ - while ((priv->wrcnt != msg->length) && (stat & I2C_STAT_TFF) == 0) - { - if ((priv->wrcnt + 1) == msg->length && priv->nmsg == 1) - putreg32 (I2C_TX_STOP, priv->base + LPC313X_I2C_TX_OFFSET); - else - putreg32 (0, priv->base + LPC313X_I2C_TX_OFFSET); - priv->wrcnt++; - - stat = getreg32 (priv->base + LPC313X_I2C_STAT_OFFSET); - } - - if (priv->wrcnt < msg->length) - { - /* Enable Tx FIFO not full and Rx Fifo Avail Interrupts */ - putreg32 (ctrl | I2C_CTRL_TFFIE | I2C_CTRL_RFDAIE, priv->base + LPC313X_I2C_CTRL_OFFSET); - } - else - { - /* Enable Rx Fifo Avail Interrupts */ - putreg32 (ctrl | I2C_CTRL_RFDAIE, priv->base + LPC313X_I2C_CTRL_OFFSET); - } - goto out; - } - } - else /* WRITE */ - { - while ((priv->wrcnt != msg->length) && (stat & I2C_STAT_TFF) == 0) - { - if ((priv->wrcnt + 1) == msg->length && priv->nmsg == 1) - putreg32 (I2C_TX_STOP | msg->buffer[priv->wrcnt], priv->base + LPC313X_I2C_TX_OFFSET); - else - putreg32 (msg->buffer[priv->wrcnt], priv->base + LPC313X_I2C_TX_OFFSET); - - priv->wrcnt++; - - stat = getreg32 (priv->base + LPC313X_I2C_STAT_OFFSET); - } - - if (priv->wrcnt < msg->length) - { - /* Enable Tx Fifo not full Interrupt */ - putreg32 (ctrl | I2C_CTRL_TFFIE, priv->base + LPC313X_I2C_CTRL_OFFSET); - goto out; - } - } - - /* Transfer completed, move onto the next one */ - priv->state = I2C_STATE_START; - - if (--priv->nmsg == 0) - { - /* Final transfer, wait for Transmit Done Interrupt */ - putreg32 (ctrl, priv->base + LPC313X_I2C_CTRL_OFFSET); - goto out; - } - priv->msgs++; - break; - } - } - -out: - if (stat & I2C_STAT_TDI) - { - putreg32 (I2C_STAT_TDI, priv->base + LPC313X_I2C_STAT_OFFSET); - - /* You'd expect the NAI bit to be set when no acknowledge was - * received - but it gets cleared whenever a write it done to - * the TXFIFO - so we've gone and cleared it while priming the - * rest of the transfer! */ - if ((stat = getreg32 (priv->base + LPC313X_I2C_TXFL_OFFSET)) != 0) - { - if (priv->nmsg == 0) - priv->nmsg++; - i2c_reset (priv); - } - - priv->state = I2C_STATE_DONE; - sem_post (&priv->wait); - } -} - -/******************************************************************************* - * Name: i2c_timeout - * - * Description: - * Watchdog timer for timeout of I2C operation - * - *******************************************************************************/ - -static void i2c_timeout (int argc, uint32_t arg, ...) -{ - struct lpc313x_i2cdev_s *priv = (struct lpc313x_i2cdev_s *) arg; - - irqstate_t flags = irqsave(); - - if (priv->state != I2C_STATE_DONE) - { - /* If there's data remaining in the TXFIFO, then ensure at least - * one transfer has failed to complete.. */ - - if (getreg32 (priv->base + LPC313X_I2C_TXFL_OFFSET) != 0) - { - if (priv->nmsg == 0) - priv->nmsg++; - } - - /* Soft reset the USB controller */ - i2c_reset (priv); - - /* Mark the transfer as finished */ - priv->state = I2C_STATE_DONE; - sem_post (&priv->wait); - } - - irqrestore (flags); -} - -/******************************************************************************* - * Name: i2c_reset - * - * Description: - * Perform a soft reset of the I2C controller - * - *******************************************************************************/ -static void i2c_reset (struct lpc313x_i2cdev_s *priv) -{ - putreg32 (I2C_CTRL_RESET, priv->base + LPC313X_I2C_CTRL_OFFSET); - - /* Wait for Reset to complete */ - while ((getreg32 (priv->base + LPC313X_I2C_CTRL_OFFSET) & I2C_CTRL_RESET) != 0) - ; -} diff --git a/nuttx/arch/arm/src/lpc313x/lpc313x_i2c.h b/nuttx/arch/arm/src/lpc313x/lpc313x_i2c.h deleted file mode 100755 index 81b9608df..000000000 --- a/nuttx/arch/arm/src/lpc313x/lpc313x_i2c.h +++ /dev/null @@ -1,207 +0,0 @@ -/************************************************************************************************ - * arch/arm/src/lpc313x/lpc313x_i2c.h - * - * Copyright (C) 2009-2010 Gregory Nutt. All rights reserved. - * Author: Gregory Nutt - * - * 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_LPC313X_I2C_H -#define __ARCH_ARM_SRC_LPC313X_I2C_H - -/************************************************************************************************ - * Included Files - ************************************************************************************************/ - -#include -#include "lpc313x_memorymap.h" - -/************************************************************************************************ - * Pre-processor Definitions - ************************************************************************************************/ - -/* I2C register base address offset into the APB1 domain ****************************************/ - -#define LPC313X_I2C0_VBASE (LPC313X_APB1_VADDR+LPC313X_APB1_I2C0_OFFSET) -#define LPC313X_I2C0_PBASE (LPC313X_APB1_PADDR+LPC313X_APB1_I2C0_OFFSET) - -#define LPC313X_I2C1_VBASE (LPC313X_APB1_VADDR+LPC313X_APB1_I2C1_OFFSET) -#define LPC313X_I2C1_PBASE (LPC313X_APB1_PADDR+LPC313X_APB1_I2C1_OFFSET) - -/* I2C register offsets (with respect to the I2C base) ******************************************/ - -#define LPC313X_I2C_RX_OFFSET 0x00 /* I2C RX Data FIFO */ -#define LPC313X_I2C_TX_OFFSET 0x00 /* I2C TX Data FIFO */ -#define LPC313X_I2C_STAT_OFFSET 0x04 /* I2C Status Register */ -#define LPC313X_I2C_CTRL_OFFSET 0x08 /* I2C Control Register */ -#define LPC313X_I2C_CLKHI_OFFSET 0x0c /* I2C Clock Divider high */ -#define LPC313X_I2C_CLKLO_OFFSET 0x10 /* I2C Clock Divider low */ -#define LPC313X_I2C_ADR_OFFSET 0x14 /* I2C Slave Address */ -#define LPC313X_I2C_RXFL_OFFSET 0x18 /* I2C Rx FIFO level */ -#define LPC313X_I2C_TXFL_OFFSET 0x1c /* I2C Tx FIFO level */ -#define LPC313X_I2C_RXB_OFFSET 0x20 /* I2C Number of bytes received */ -#define LPC313X_I2C_TXB_OFFSET 0x24 /* I2C Number of bytes transmitted */ -#define LPC313X_I2C_STX_OFFSET 0x28 /* Slave Transmit FIFO */ -#define LPC313X_I2C_STXFL_OFFSET 0x2c /* Slave Transmit FIFO level */ - -/* I2C register (virtual) addresses *************************************************************/ - -#define LPC313X_I2C0_RX (LPC313X_I2C0_VBASE+LPC313X_I2C_RX_OFFSET) -#define LPC313X_I2C0_TX (LPC313X_I2C0_VBASE+LPC313X_I2C_TX_OFFSET) -#define LPC313X_I2C0_STAT (LPC313X_I2C0_VBASE+LPC313X_I2C_STAT_OFFSET) -#define LPC313X_I2C0_CTRL (LPC313X_I2C0_VBASE+LPC313X_I2C_CTRL_OFFSET) -#define LPC313X_I2C0_CLKHI (LPC313X_I2C0_VBASE+LPC313X_I2C_CLKHI_OFFSET) -#define LPC313X_I2C0_CLKLO (LPC313X_I2C0_VBASE+LPC313X_I2C_CLKLO_OFFSET) -#define LPC313X_I2C0_ADR (LPC313X_I2C0_VBASE+LPC313X_I2C_ADR_OFFSET) -#define LPC313X_I2C0_RXFL (LPC313X_I2C0_VBASE+LPC313X_I2C_RXFL_OFFSET) -#define LPC313X_I2C0_TXFL (LPC313X_I2C0_VBASE+LPC313X_I2C_TXFL_OFFSET) -#define LPC313X_I2C0_RXB (LPC313X_I2C0_VBASE+LPC313X_I2C_RXB_OFFSET) -#define LPC313X_I2C0_TXB (LPC313X_I2C0_VBASE+LPC313X_I2C_TXB_OFFSET) -#define LPC313X_I2C0_STX (LPC313X_I2C0_VBASE+LPC313X_I2C_STX_OFFSET) -#define LPC313X_I2C0_STXFL (LPC313X_I2C0_VBASE+LPC313X_I2C_STXFL_OFFSET) - -#define LPC313X_I2C1_RX (LPC313X_I2C1_VBASE+LPC313X_I2C_RX_OFFSET) -#define LPC313X_I2C1_TX (LPC313X_I2C1_VBASE+LPC313X_I2C_TX_OFFSET) -#define LPC313X_I2C1_STAT (LPC313X_I2C1_VBASE+LPC313X_I2C_STAT_OFFSET) -#define LPC313X_I2C1_CTRL (LPC313X_I2C1_VBASE+LPC313X_I2C_CTRL_OFFSET) -#define LPC313X_I2C1_CLKHI (LPC313X_I2C1_VBASE+LPC313X_I2C_CLKHI_OFFSET) -#define LPC313X_I2C1_CLKLO (LPC313X_I2C1_VBASE+LPC313X_I2C_CLKLO_OFFSET) -#define LPC313X_I2C1_ADR (LPC313X_I2C1_VBASE+LPC313X_I2C_ADR_OFFSET) -#define LPC313X_I2C1_RXFL (LPC313X_I2C1_VBASE+LPC313X_I2C_RXFL_OFFSET) -#define LPC313X_I2C1_TXFL (LPC313X_I2C1_VBASE+LPC313X_I2C_TXFL_OFFSET) -#define LPC313X_I2C1_RXB (LPC313X_I2C1_VBASE+LPC313X_I2C_RXB_OFFSET) -#define LPC313X_I2C1_TXB (LPC313X_I2C1_VBASE+LPC313X_I2C_TXB_OFFSET) -#define LPC313X_I2C1_STX (LPC313X_I2C1_VBASE+LPC313X_I2C_STX_OFFSET) -#define LPC313X_I2C1_STXFL (LPC313X_I2C1_VBASE+LPC313X_I2C_STXFL_OFFSET) - -/* I2C register bit definitions *****************************************************************/ - -/* I2Cn RX Data FIFO I2C0_RX, address 0x1300a000, I2C1_RX, address 0x1300a400 */ - -#define I2C_RX_DATA_SHIFT (0) /* Bits 0-7: RxData Receive FIFO data bits */ -#define I2C_RX_DATA_MASK (0xff << I2C_RX_DATA_HIFT) - -/* I2Cn TX Data FIFO I2C0_TX, 0x1300a000, I2C1_TX, address 0x1300a400 */ - -#define I2C_TX_STOP (1 << 9) /* Bit 9: Issue STOP condition after transmitting byte */ -#define I2C_TX_START (1 << 8) /* Bit 8: Issue START condition before transmitting byte */ -#define I2C_TX_DATA_SHIFT (0) /* Bits 0-7: TxData Transmit FIFO data bits */ -#define I2C_TX_DATA_MASK (0xff << I2C_TX_DATA_SHIFT) - -/* I2Cn Status register I2C0_STAT, address 0x1300a004, I2C1_STAT, address 0x1300a404 */ - -#define I2C_STAT_TFES (1 << 13) /* Bit 13: Slave Transmit FIFO Empty */ -#define I2C_STAT_TFFS (1 << 12) /* Bit 12: Slave Transmit FIFO Full */ -#define I2C_STAT_TFE (1 << 11) /* Bit 11: Transmit FIFO Empty */ -#define I2C_STAT_TFF (1 << 10) /* Bit 10: Transmit FIFO Full */ -#define I2C_STAT_RFE (1 << 9) /* Bit 9: Receive FIFO Empty */ -#define I2C_STAT_RFF (1 << 8) /* Bit 8: Receive FIFO Full */ -#define I2C_STAT_SDA (1 << 7) /* Bit 7: The current value of the SDA signal */ -#define I2C_STAT_SCL (1 << 6) /* Bit 6: The current value of the SCL signal */ -#define I2C_STAT_ACTIVE (1 << 5) /* Bit 5: Indicates whether the bus is busy */ -#define I2C_STAT_DRSI (1 << 4) /* Bit 4: Slave Data Request Interrupt */ -#define I2C_STAT_DRMI (1 << 3) /* Bit 3: Master Data Request Interrupt */ -#define I2C_STAT_NAI (1 << 2) /* Bit 2: No Acknowledge Interrupt */ -#define I2C_STAT_AFI (1 << 1) /* Bit 1: Arbitration Failure Interrupt */ -#define I2C_STAT_TDI (1 << 0) /* Bit 0: Transaction Done Interrupt */ - -/* I2Cn Control register I2C0_CTRL, address 0x1300a008, I2C1_CTRL, address 0x1300a408 */ - -#define I2C_CTRL_TFFSIE (1 << 10) /* Bit 10: Slave Transmit FIFO Not Full Interrupt Enable */ -#define I2C_CTRL_SEVEN (1 << 9) /* Bit 9: Seven-bit slave address */ -#define I2C_CTRL_RESET (1 << 8) /* Bit 8: Soft Reset */ -#define I2C_CTRL_TFFIE (1 << 7) /* Bit 7: Transmit FIFO Not Full Interrupt Enable */ -#define I2C_CTRL_RFDAIE (1 << 6) /* Bit 6: Receive FIFO Data Available Interrupt Enable */ -#define I2C_CTRL_RFFIE (1 << 5) /* Bit 5: Receive FIFO Full Interrupt Enable */ -#define I2C_CTRL_DRSIE (1 << 4) /* Bit 4: Data Request Slave Transmitter Interrupt Enable */ -#define I2C_CTRL_DRMIE (1 << 3) /* Bit 3: Data Request Master Transmitter Interrupt Enable */ -#define I2C_CTRL_NAIE (1 << 2) /* Bit 2: Transmitter No Acknowledge Interrupt Enable */ -#define I2C_CTRL_AFIE (1 << 1) /* Bit 1: Transmitter Arbitration Failure Interrupt Enable */ -#define I2C_CTRL_TDIE (1 << 0) /* Bit 0: Transmit Done Interrupt Enable */ - -/* I2Cn Clock Divider High I2C0_CLKHI, address 0x1300a00c, I2C1_CLKHI, address 0x1300a40c */ - -#define I2C_CLKHI_SHIFT (0) /* Bits 0-9: Clock Divisor High */ -#define I2C_CLKHI_MASK (0x3ff << I2C_CLKHI_SHIFT) - -/* I2Cn Clock Divider Low I2C0_CLKLO, address 0x1300a010, I2C1_CLKLO, address 0x1300a410 */ - -#define I2C_CLKLO_SHIFT (0) /* Bits 0-9: Clock Divisor Low */ -#define I2C_CLKLO_MASK (0x3ff << I2C_CLKLO_SHIFT) - - -/* I2Cn Slave Addres I2C0_ADDR, address 0x1300a014, I2C1_ADDR, address 0x1300a414 */ - -#define I2C_ADR_SHIFT (0) /* Bits 0-9: I2C bus slave address */ -#define I2C_ADR_MASK (0x3ff << I2C_ADR_SHIFT) - -/* I2Cn RX FIFO level I2C0_RXFL, address 0x1300a018, I2C1_RXFL, address 0x1300a018 */ - -#define I2C_RXFL_SHIFT (0) /* Bits 0-1: Receive FIFO level */ -#define I2C_RXFL_MASK (3 << I2C_RXFL_SHIFT) - -/* I2Cn TX FIFO level I2C0_TXFL, address 0x1300a01c, I2C1_TXFL, address 0x1300a01c */ - -#define I2C_TXFL_SHIFT (0) /* Bits 0-1: Receive FIFO level */ -#define I2C_TXFL_MASK (3 << I2C_TXFL_SHIFT) - -/* I2Cn RX byte count I2C0_RXB, address 0x1300a020, I2C1_RXB, address 0x1300a420 */ - -#define I2C_RXB_SHIFT (0) /* Bits 0-15: Number of bytes received */ -#define I2C_RXB_MASK (0xffff << I2C_RXB_SHIFT) - -/* I2Cn TX byte count I2C0_TXB, address 0x1300a024, I2C1_TXB, address 0x1300a424 */ - -#define I2C_TXB_SHIFT (0) /* Bits 0-15: Number of bytes sent */ -#define I2C_TXB_MASK (0xffff << I2C_TXB_SHIFT) - -/* I2Cn Slave TX Data FIFO I2C0_STX, address 0x1300a028, I2C1_STX, 0x1300a428 */ - -#define I2C_STX_SHIFT (0) /* Bits 0-7: Slave Transmit FIFO data */ -#define I2C_STX_MASK (0xff << I2C_STX_SHIFT) - -/* I2Cn Slave TX FIFO level I2C0_STXFL, address 0x1300a02c, I2C1_STXFL, address 0x1300a42c */ - -#define I2C_STXFL_SHIFT (0) /* Bits 0-1: Slave Transmit FIFO level */ -#define I2C_STXFL_MASK (3 << I2C_STXFL_SHIFT) - -/************************************************************************************************ - * Public Types - ************************************************************************************************/ - -/************************************************************************************************ - * Public Data - ************************************************************************************************/ - -/************************************************************************************************ - * Public Functions - ************************************************************************************************/ - -#endif /* __ARCH_ARM_SRC_LPC313X_I2C_H */ diff --git a/nuttx/arch/arm/src/lpc313x/lpc313x_i2s.h b/nuttx/arch/arm/src/lpc313x/lpc313x_i2s.h deleted file mode 100755 index 44ff86a09..000000000 --- a/nuttx/arch/arm/src/lpc313x/lpc313x_i2s.h +++ /dev/null @@ -1,315 +0,0 @@ -/************************************************************************************************ - * arch/arm/src/lpc313x/lpc313x_i2s.h - * - * Copyright (C) 2009 Gregory Nutt. All rights reserved. - * Author: Gregory Nutt - * - * 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_LPC313X_I2S_H -#define __ARCH_ARM_SRC_LPC313X_I2S_H - -/************************************************************************************************ - * Included Files - ************************************************************************************************/ - -#include -#include "lpc313x_memorymap.h" - -/************************************************************************************************ - * Pre-processor Definitions - ************************************************************************************************/ - -/* I2S register base address offset into the APB3 domain ****************************************/ - -#define LPC313X_I2SCONFIG_VBASE (LPC313X_APB3_VSECTION+LPC313X_APB3_I2SCONFIG_OFFSET) -#define LPC313X_I2SCONFIG_PBASE (LPC313X_APB3_PSECTION+LPC313X_APB3_I2SCONFIG_OFFSET) - -#define LPC313X_I2STX0_VBASE (LPC313X_APB3_VSECTION+LPC313X_APB3_I2STX0_OFFSET) -#define LPC313X_I2STX0_PBASE (LPC313X_APB3_PSECTION+LPC313X_APB3_I2STX0_OFFSET) - -#define LPC313X_I2STX1_VBASE (LPC313X_APB3_VSECTION+LPC313X_APB3_I2STX1_OFFSET) -#define LPC313X_I2STX1_PBASE (LPC313X_APB3_PSECTION+LPC313X_APB3_I2STX1_OFFSET) - -#define LPC313X_I2SRX0_VBASE (LPC313X_APB3_VSECTION+LPC313X_APB3_I2SRX0_OFFSET) -#define LPC313X_I2SRX0_PBASE (LPC313X_APB3_PSECTION+LPC313X_APB3_I2SRX0_OFFSET) - -#define LPC313X_I2SRX1_VBASE (LPC313X_APB3_VSECTION+LPC313X_APB3_I2SRX1_OFFSET) -#define LPC313X_I2SRX1_PBASE (LPC313X_APB3_PSECTION+LPC313X_APB3_I2SRX1_OFFSET) - -/* I2S register offsets (with respect to the I2S base) ******************************************/ -/* I2S configuration module offset */ - -#define LPC313X_I2SCONFIG_FORMAT_OFFSET 0x000 /* I2S formats */ -#define LPC313X_I2SCONFIG_CFGMUX_OFFSET 0x004 /* Misc controls */ - /* 0x008-0x00c: Reserved */ -#define LPC313X_I2SCONFIG_NSOFCNTR_OFFSET 0x010 /* NSOF counter control */ - -/* I2STX0, I2STX1, I2SRX0, and I2SRX1 module offsets */ - -#define LPC313X_I2S_L16BIT_OFFSET 0x000 /* 16 bits left channel data */ -#define LPC313X_I2S_R16BIT_OFFSET 0x004 /* 16 bits right channel data */ -#define LPC313X_I2S_L24BIT_OFFSET 0x008 /* 24 bits left channel data */ -#define LPC313X_I2S_R24BIT_OFFSET 0x00c /* 24 bits right channel data */ -#define LPC313X_I2S_INTSTATUS_OFFSET 0x010 /* FIFO status register */ -#define LPC313X_I2S_INTMASK_OFFSET 0x014 /* Interrupt Mask register */ -#define LPC313X_I2S_L32BIT_OFFSET(n) (0x020+((n)<<2)) -#define LPC313X_I2S_L32BIT0_OFFSET 0x020 /* 2x16 bits left channel data */ -#define LPC313X_I2S_L32BIT1_OFFSET 0x024 /* " " " " " " " " " " */ -#define LPC313X_I2S_L32BIT2_OFFSET 0x028 /* " " " " " " " " " " */ -#define LPC313X_I2S_L32BIT3_OFFSET 0x02c /* " " " " " " " " " " */ -#define LPC313X_I2S_L32BIT4_OFFSET 0x030 /* " " " " " " " " " " */ -#define LPC313X_I2S_L32BIT5_OFFSET 0x034 /* " " " " " " " " " " */ -#define LPC313X_I2S_L32BIT6_OFFSET 0x038 /* " " " " " " " " " " */ -#define LPC313X_I2S_L32BIT7_OFFSET 0x03c /* " " " " " " " " " " */ -#define LPC313X_I2S_R32BIT_OFFSET(n) (0x040+((n)<<2)) -#define LPC313X_I2S_R32BIT0_OFFSET 0x040 /* 2x16 bits right channel data */ -#define LPC313X_I2S_R32BIT1_OFFSET 0x044 /* " " " " " " " " " " */ -#define LPC313X_I2S_R32BIT2_OFFSET 0x048 /* " " " " " " " " " " */ -#define LPC313X_I2S_R32BIT3_OFFSET 0x04c /* " " " " " " " " " " */ -#define LPC313X_I2S_R32BIT4_OFFSET 0x050 /* " " " " " " " " " " */ -#define LPC313X_I2S_R32BIT5_OFFSET 0x054 /* " " " " " " " " " " */ -#define LPC313X_I2S_R32BIT6_OFFSET 0x058 /* " " " " " " " " " " */ -#define LPC313X_I2S_R32BIT7_OFFSET 0x05c /* " " " " " " " " " " */ -#define LPC313X_I2S_ILVD_OFFSET(n) (0x060+((n)<<2)) -#define LPC313X_I2S_ILVD0_OFFSET 0x060 /* Interleaved data */ -#define LPC313X_I2S_ILVD1_OFFSET 0x064 /* " " " " */ -#define LPC313X_I2S_ILVD2_OFFSET 0x068 /* " " " " */ -#define LPC313X_I2S_ILVD3_OFFSET 0x06c /* " " " " */ -#define LPC313X_I2S_ILVD4_OFFSET 0x070 /* " " " " */ -#define LPC313X_I2S_ILVD5_OFFSET 0x074 /* " " " " */ -#define LPC313X_I2S_ILVD6_OFFSET 0x078 /* " " " " */ -#define LPC313X_I2S_ILVD7_OFFSET 0x07c /* " " " " */ - -/* I2S register (virtual) addresses *************************************************************/ -/* I2S configuration module registers */ - -#define LPC313X_I2SCONFIG_FORMAT (LPC313X_I2SCONFIG_VBASE+lPC313X_I2SCONFIG_FORMAT_OFFSET) -#define LPC313X_I2SCONFIG_CFGMUX (LPC313X_I2SCONFIG_VBASE+LPC313X_I2SCONFIG_CFGMUX_OFFSET) -#define LPC313X_I2SCONFIG_NSOFCNTR (LPC313X_I2SCONFIG_VBASE+LPC313X_I2SCONFIG_NSOFCNTR_OFFSET) - -/* I2STX0 module registers */ - -#define LPC313X_I2STX0_L16BIT (LPC313X_I2STX0_VBASE+LPC313X_I2S_L16BIT_OFFSET) -#define LPC313X_I2STX0_R16BIT (LPC313X_I2STX0_VBASE+LPC313X_I2S_R16BIT_OFFSET) -#define LPC313X_I2STX0_L24BIT (LPC313X_I2STX0_VBASE+LPC313X_I2S_L24BIT_OFFSET) -#define LPC313X_I2STX0_R24BIT (LPC313X_I2STX0_VBASE+LPC313X_I2S_R24BIT_OFFSET) -#define LPC313X_I2STX0_INTSTATUS (LPC313X_I2STX0_VBASE+LPC313X_I2S_INTSTATUS_OFFSET) -#define LPC313X_I2STX0_INTMASK (LPC313X_I2STX0_VBASE+LPC313X_I2S_INTMASK_OFFSET) -#define LPC313X_I2STX0_L32BIT(n) (LPC313X_I2STX0_VBASE+LPC313X_I2S_L32BIT_OFFSET(n)) -#define LPC313X_I2STX0_L32BIT0 (LPC313X_I2STX0_VBASE+LPC313X_I2S_L32BIT0_OFFSET) -#define LPC313X_I2STX0_L32BIT1 (LPC313X_I2STX0_VBASE+LPC313X_I2S_L32BIT1_OFFSET) -#define LPC313X_I2STX0_L32BIT2 (LPC313X_I2STX0_VBASE+LPC313X_I2S_L32BIT2_OFFSET) -#define LPC313X_I2STX0_L32BIT3 (LPC313X_I2STX0_VBASE+LPC313X_I2S_L32BIT3_OFFSET) -#define LPC313X_I2STX0_L32BIT4 (LPC313X_I2STX0_VBASE+LPC313X_I2S_L32BIT4_OFFSET) -#define LPC313X_I2STX0_L32BIT5 (LPC313X_I2STX0_VBASE+LPC313X_I2S_L32BIT5_OFFSET) -#define LPC313X_I2STX0_L32BIT6 (LPC313X_I2STX0_VBASE+LPC313X_I2S_L32BIT6_OFFSET) -#define LPC313X_I2STX0_L32BIT7 (LPC313X_I2STX0_VBASE+LPC313X_I2S_L32BIT7_OFFSET) -#define LPC313X_I2STX0_R32BIT(n) (LPC313X_I2STX0_VBASE+LPC313X_I2S_R32BIT_OFFSET(n)) -#define LPC313X_I2STX0_R32BIT0 (LPC313X_I2STX0_VBASE+LPC313X_I2S_R32BIT0_OFFSET) -#define LPC313X_I2STX0_R32BIT1 (LPC313X_I2STX0_VBASE+LPC313X_I2S_R32BIT1_OFFSET) -#define LPC313X_I2STX0_R32BIT2 (LPC313X_I2STX0_VBASE+LPC313X_I2S_R32BIT2_OFFSET) -#define LPC313X_I2STX0_R32BIT3 (LPC313X_I2STX0_VBASE+LPC313X_I2S_R32BIT3_OFFSET) -#define LPC313X_I2STX0_R32BIT4 (LPC313X_I2STX0_VBASE+LPC313X_I2S_R32BIT4_OFFSET) -#define LPC313X_I2STX0_R32BIT5 (LPC313X_I2STX0_VBASE+LPC313X_I2S_R32BIT5_OFFSET) -#define LPC313X_I2STX0_R32BIT6 (LPC313X_I2STX0_VBASE+LPC313X_I2S_R32BIT6_OFFSET) -#define LPC313X_I2STX0_R32BIT7 (LPC313X_I2STX0_VBASE+LPC313X_I2S_R32BIT7_OFFSET) -#define LPC313X_I2STX0_ILVD(n) (LPC313X_I2STX0_VBASE+LPC313X_I2S_ILVD_OFFSET(n)) -#define LPC313X_I2STX0_ILVD0 (LPC313X_I2STX0_VBASE+LPC313X_I2S_ILVD0_OFFSET) -#define LPC313X_I2STX0_ILVD1 (LPC313X_I2STX0_VBASE+LPC313X_I2S_ILVD1_OFFSET) -#define LPC313X_I2STX0_ILVD2 (LPC313X_I2STX0_VBASE+LPC313X_I2S_ILVD2_OFFSET) -#define LPC313X_I2STX0_ILVD3 (LPC313X_I2STX0_VBASE+LPC313X_I2S_ILVD3_OFFSET) -#define LPC313X_I2STX0_ILVD4 (LPC313X_I2STX0_VBASE+LPC313X_I2S_ILVD4_OFFSET) -#define LPC313X_I2STX0_ILVD5 (LPC313X_I2STX0_VBASE+LPC313X_I2S_ILVD5_OFFSET) -#define LPC313X_I2STX0_ILVD6 (LPC313X_I2STX0_VBASE+LPC313X_I2S_ILVD6_OFFSET) -#define LPC313X_I2STX0_ILVD7 (LPC313X_I2STX0_VBASE+LPC313X_I2S_ILVD7_OFFSET) - -/* I2STX1 module registers */ - -#define LPC313X_I2STX1_L16BIT (LPC313X_I2STX1_VBASE+LPC313X_I2S_L16BIT_OFFSET) -#define LPC313X_I2STX1_R16BIT (LPC313X_I2STX1_VBASE+LPC313X_I2S_R16BIT_OFFSET) -#define LPC313X_I2STX1_L24BIT (LPC313X_I2STX1_VBASE+LPC313X_I2S_L24BIT_OFFSET) -#define LPC313X_I2STX1_R24BIT (LPC313X_I2STX1_VBASE+LPC313X_I2S_R24BIT_OFFSET) -#define LPC313X_I2STX1_INTSTATUS (LPC313X_I2STX1_VBASE+LPC313X_I2S_INTSTATUS_OFFSET) -#define LPC313X_I2STX1_INTMASK (LPC313X_I2STX1_VBASE+LPC313X_I2S_INTMASK_OFFSET) -#define LPC313X_I2STX1_L32BIT(n) (LPC313X_I2STX1_VBASE+LPC313X_I2S_L32BIT_OFFSET(n)) -#define LPC313X_I2STX1_L32BIT0 (LPC313X_I2STX1_VBASE+LPC313X_I2S_L32BIT0_OFFSET) -#define LPC313X_I2STX1_L32BIT1 (LPC313X_I2STX1_VBASE+LPC313X_I2S_L32BIT1_OFFSET) -#define LPC313X_I2STX1_L32BIT2 (LPC313X_I2STX1_VBASE+LPC313X_I2S_L32BIT2_OFFSET) -#define LPC313X_I2STX1_L32BIT3 (LPC313X_I2STX1_VBASE+LPC313X_I2S_L32BIT3_OFFSET) -#define LPC313X_I2STX1_L32BIT4 (LPC313X_I2STX1_VBASE+LPC313X_I2S_L32BIT4_OFFSET) -#define LPC313X_I2STX1_L32BIT5 (LPC313X_I2STX1_VBASE+LPC313X_I2S_L32BIT5_OFFSET) -#define LPC313X_I2STX1_L32BIT6 (LPC313X_I2STX1_VBASE+LPC313X_I2S_L32BIT6_OFFSET) -#define LPC313X_I2STX1_L32BIT7 (LPC313X_I2STX1_VBASE+LPC313X_I2S_L32BIT7_OFFSET) -#define LPC313X_I2STX1_R32BIT(n) (LPC313X_I2STX1_VBASE+LPC313X_I2S_R32BIT_OFFSET(n)) -#define LPC313X_I2STX1_R32BIT0 (LPC313X_I2STX1_VBASE+LPC313X_I2S_R32BIT0_OFFSET) -#define LPC313X_I2STX1_R32BIT1 (LPC313X_I2STX1_VBASE+LPC313X_I2S_R32BIT1_OFFSET) -#define LPC313X_I2STX1_R32BIT2 (LPC313X_I2STX1_VBASE+LPC313X_I2S_R32BIT2_OFFSET) -#define LPC313X_I2STX1_R32BIT3 (LPC313X_I2STX1_VBASE+LPC313X_I2S_R32BIT3_OFFSET) -#define LPC313X_I2STX1_R32BIT4 (LPC313X_I2STX1_VBASE+LPC313X_I2S_R32BIT4_OFFSET) -#define LPC313X_I2STX1_R32BIT5 (LPC313X_I2STX1_VBASE+LPC313X_I2S_R32BIT5_OFFSET) -#define LPC313X_I2STX1_R32BIT6 (LPC313X_I2STX1_VBASE+LPC313X_I2S_R32BIT6_OFFSET) -#define LPC313X_I2STX1_R32BIT7 (LPC313X_I2STX1_VBASE+LPC313X_I2S_R32BIT7_OFFSET) -#define LPC313X_I2STX1_ILVD(n) (LPC313X_I2STX1_VBASE+LPC313X_I2S_ILVD_OFFSET(n)) -#define LPC313X_I2STX1_ILVD0 (LPC313X_I2STX1_VBASE+LPC313X_I2S_ILVD0_OFFSET) -#define LPC313X_I2STX1_ILVD1 (LPC313X_I2STX1_VBASE+LPC313X_I2S_ILVD1_OFFSET) -#define LPC313X_I2STX1_ILVD2 (LPC313X_I2STX1_VBASE+LPC313X_I2S_ILVD2_OFFSET) -#define LPC313X_I2STX1_ILVD3 (LPC313X_I2STX1_VBASE+LPC313X_I2S_ILVD3_OFFSET) -#define LPC313X_I2STX1_ILVD4 (LPC313X_I2STX1_VBASE+LPC313X_I2S_ILVD4_OFFSET) -#define LPC313X_I2STX1_ILVD5 (LPC313X_I2STX1_VBASE+LPC313X_I2S_ILVD5_OFFSET) -#define LPC313X_I2STX1_ILVD6 (LPC313X_I2STX1_VBASE+LPC313X_I2S_ILVD6_OFFSET) -#define LPC313X_I2STX1_ILVD7 (LPC313X_I2STX1_VBASE+LPC313X_I2S_ILVD7_OFFSET) - -/* I2SRX0 module registers */ - -#define LPC313X_I2SRX0_L16BIT (LPC313X_I2SRX0_VBASE+LPC313X_I2S_L16BIT_OFFSET) -#define LPC313X_I2SRX0_R16BIT (LPC313X_I2SRX0_VBASE+LPC313X_I2S_R16BIT_OFFSET) -#define LPC313X_I2SRX0_L24BIT (LPC313X_I2SRX0_VBASE+LPC313X_I2S_L24BIT_OFFSET) -#define LPC313X_I2SRX0_R24BIT (LPC313X_I2SRX0_VBASE+LPC313X_I2S_R24BIT_OFFSET) -#define LPC313X_I2SRX0_INTSTATUS (LPC313X_I2SRX0_VBASE+LPC313X_I2S_INTSTATUS_OFFSET) -#define LPC313X_I2SRX0_INTMASK (LPC313X_I2SRX0_VBASE+LPC313X_I2S_INTMASK_OFFSET) -#define LPC313X_I2SRX0_L32BIT(n) (LPC313X_I2SRX0_VBASE+LPC313X_I2S_L32BIT_OFFSET(n)) -#define LPC313X_I2SRX0_L32BIT0 (LPC313X_I2SRX0_VBASE+LPC313X_I2S_L32BIT0_OFFSET) -#define LPC313X_I2SRX0_L32BIT1 (LPC313X_I2SRX0_VBASE+LPC313X_I2S_L32BIT1_OFFSET) -#define LPC313X_I2SRX0_L32BIT2 (LPC313X_I2SRX0_VBASE+LPC313X_I2S_L32BIT2_OFFSET) -#define LPC313X_I2SRX0_L32BIT3 (LPC313X_I2SRX0_VBASE+LPC313X_I2S_L32BIT3_OFFSET) -#define LPC313X_I2SRX0_L32BIT4 (LPC313X_I2SRX0_VBASE+LPC313X_I2S_L32BIT4_OFFSET) -#define LPC313X_I2SRX0_L32BIT5 (LPC313X_I2SRX0_VBASE+LPC313X_I2S_L32BIT5_OFFSET) -#define LPC313X_I2SRX0_L32BIT6 (LPC313X_I2SRX0_VBASE+LPC313X_I2S_L32BIT6_OFFSET) -#define LPC313X_I2SRX0_L32BIT7 (LPC313X_I2SRX0_VBASE+LPC313X_I2S_L32BIT7_OFFSET) -#define LPC313X_I2SRX0_R32BIT(n) (LPC313X_I2SRX0_VBASE+LPC313X_I2S_R32BIT_OFFSET(n)) -#define LPC313X_I2SRX0_R32BIT0 (LPC313X_I2SRX0_VBASE+LPC313X_I2S_R32BIT0_OFFSET) -#define LPC313X_I2SRX0_R32BIT1 (LPC313X_I2SRX0_VBASE+LPC313X_I2S_R32BIT1_OFFSET) -#define LPC313X_I2SRX0_R32BIT2 (LPC313X_I2SRX0_VBASE+LPC313X_I2S_R32BIT2_OFFSET) -#define LPC313X_I2SRX0_R32BIT3 (LPC313X_I2SRX0_VBASE+LPC313X_I2S_R32BIT3_OFFSET) -#define LPC313X_I2SRX0_R32BIT4 (LPC313X_I2SRX0_VBASE+LPC313X_I2S_R32BIT4_OFFSET) -#define LPC313X_I2SRX0_R32BIT5 (LPC313X_I2SRX0_VBASE+LPC313X_I2S_R32BIT5_OFFSET) -#define LPC313X_I2SRX0_R32BIT6 (LPC313X_I2SRX0_VBASE+LPC313X_I2S_R32BIT6_OFFSET) -#define LPC313X_I2SRX0_R32BIT7 (LPC313X_I2SRX0_VBASE+LPC313X_I2S_R32BIT7_OFFSET) -#define LPC313X_I2SRX0_ILVD(n) (LPC313X_I2SRX0_VBASE+LPC313X_I2S_ILVD_OFFSET(n)) -#define LPC313X_I2SRX0_ILVD0 (LPC313X_I2SRX0_VBASE+LPC313X_I2S_ILVD0_OFFSET) -#define LPC313X_I2SRX0_ILVD1 (LPC313X_I2SRX0_VBASE+LPC313X_I2S_ILVD1_OFFSET) -#define LPC313X_I2SRX0_ILVD2 (LPC313X_I2SRX0_VBASE+LPC313X_I2S_ILVD2_OFFSET) -#define LPC313X_I2SRX0_ILVD3 (LPC313X_I2SRX0_VBASE+LPC313X_I2S_ILVD3_OFFSET) -#define LPC313X_I2SRX0_ILVD4 (LPC313X_I2SRX0_VBASE+LPC313X_I2S_ILVD4_OFFSET) -#define LPC313X_I2SRX0_ILVD5 (LPC313X_I2SRX0_VBASE+LPC313X_I2S_ILVD5_OFFSET) -#define LPC313X_I2SRX0_ILVD6 (LPC313X_I2SRX0_VBASE+LPC313X_I2S_ILVD6_OFFSET) -#define LPC313X_I2SRX0_ILVD7 (LPC313X_I2SRX0_VBASE+LPC313X_I2S_ILVD7_OFFSET) - -/* I2SRX1 module registers */ - -#define LPC313X_I2SRX1_L16BIT (LPC313X_I2SRX1_VBASE+LPC313X_I2S_L16BIT_OFFSET) -#define LPC313X_I2SRX1_R16BIT (LPC313X_I2SRX1_VBASE+LPC313X_I2S_R16BIT_OFFSET) -#define LPC313X_I2SRX1_L24BIT (LPC313X_I2SRX1_VBASE+LPC313X_I2S_L24BIT_OFFSET) -#define LPC313X_I2SRX1_R24BIT (LPC313X_I2SRX1_VBASE+LPC313X_I2S_R24BIT_OFFSET) -#define LPC313X_I2SRX1_INTSTATUS (LPC313X_I2SRX1_VBASE+LPC313X_I2S_INTSTATUS_OFFSET) -#define LPC313X_I2SRX1_INTMASK (LPC313X_I2SRX1_VBASE+LPC313X_I2S_INTMASK_OFFSET) -#define LPC313X_I2SRX1_L32BIT(n) (LPC313X_I2SRX1_VBASE+LPC313X_I2S_L32BIT_OFFSET(n)) -#define LPC313X_I2SRX1_L32BIT0 (LPC313X_I2SRX1_VBASE+LPC313X_I2S_L32BIT0_OFFSET) -#define LPC313X_I2SRX1_L32BIT1 (LPC313X_I2SRX1_VBASE+LPC313X_I2S_L32BIT1_OFFSET) -#define LPC313X_I2SRX1_L32BIT2 (LPC313X_I2SRX1_VBASE+LPC313X_I2S_L32BIT2_OFFSET) -#define LPC313X_I2SRX1_L32BIT3 (LPC313X_I2SRX1_VBASE+LPC313X_I2S_L32BIT3_OFFSET) -#define LPC313X_I2SRX1_L32BIT4 (LPC313X_I2SRX1_VBASE+LPC313X_I2S_L32BIT4_OFFSET) -#define LPC313X_I2SRX1_L32BIT5 (LPC313X_I2SRX1_VBASE+LPC313X_I2S_L32BIT5_OFFSET) -#define LPC313X_I2SRX1_L32BIT6 (LPC313X_I2SRX1_VBASE+LPC313X_I2S_L32BIT6_OFFSET) -#define LPC313X_I2SRX1_L32BIT7 (LPC313X_I2SRX1_VBASE+LPC313X_I2S_L32BIT7_OFFSET) -#define LPC313X_I2SRX1_R32BIT(n) (LPC313X_I2SRX1_VBASE+LPC313X_I2S_R32BIT_OFFSET(n)) -#define LPC313X_I2SRX1_R32BIT0 (LPC313X_I2SRX1_VBASE+LPC313X_I2S_R32BIT0_OFFSET) -#define LPC313X_I2SRX1_R32BIT1 (LPC313X_I2SRX1_VBASE+LPC313X_I2S_R32BIT1_OFFSET) -#define LPC313X_I2SRX1_R32BIT2 (LPC313X_I2SRX1_VBASE+LPC313X_I2S_R32BIT2_OFFSET) -#define LPC313X_I2SRX1_R32BIT3 (LPC313X_I2SRX1_VBASE+LPC313X_I2S_R32BIT3_OFFSET) -#define LPC313X_I2SRX1_R32BIT4 (LPC313X_I2SRX1_VBASE+LPC313X_I2S_R32BIT4_OFFSET) -#define LPC313X_I2SRX1_R32BIT5 (LPC313X_I2SRX1_VBASE+LPC313X_I2S_R32BIT5_OFFSET) -#define LPC313X_I2SRX1_R32BIT6 (LPC313X_I2SRX1_VBASE+LPC313X_I2S_R32BIT6_OFFSET) -#define LPC313X_I2SRX1_R32BIT7 (LPC313X_I2SRX1_VBASE+LPC313X_I2S_R32BIT7_OFFSET) -#define LPC313X_I2SRX1_ILVD(n) (LPC313X_I2SRX1_VBASE+LPC313X_I2S_ILVD_OFFSET(n)) -#define LPC313X_I2SRX1_ILVD0 (LPC313X_I2SRX1_VBASE+LPC313X_I2S_ILVD0_OFFSET) -#define LPC313X_I2SRX1_ILVD1 (LPC313X_I2SRX1_VBASE+LPC313X_I2S_ILVD1_OFFSET) -#define LPC313X_I2SRX1_ILVD2 (LPC313X_I2SRX1_VBASE+LPC313X_I2S_ILVD2_OFFSET) -#define LPC313X_I2SRX1_ILVD3 (LPC313X_I2SRX1_VBASE+LPC313X_I2S_ILVD3_OFFSET) -#define LPC313X_I2SRX1_ILVD4 (LPC313X_I2SRX1_VBASE+LPC313X_I2S_ILVD4_OFFSET) -#define LPC313X_I2SRX1_ILVD5 (LPC313X_I2SRX1_VBASE+LPC313X_I2S_ILVD5_OFFSET) -#define LPC313X_I2SRX1_ILVD6 (LPC313X_I2SRX1_VBASE+LPC313X_I2S_ILVD6_OFFSET) -#define LPC313X_I2SRX1_ILVD7 (LPC313X_I2SRX1_VBASE+LPC313X_I2S_ILVD7_OFFSET) - -/* I2S register bit definitions *****************************************************************/ -/* I2S configuration module offset */ - -/* I2SCONFIG_FORMAT address 0x16000000 */ - -#define I2SCONFIG_FORMAT_I2SRX1_SHIFT (9) /* Bits 9-11: I2SRX1 I2S output format */ -#define I2SCONFIG_FORMAT_I2SRX1_MASK (7 << I2SCONFIG_FORMAT_I2SRX1_SHIFT) -# define I2SCONFIG_FORMAT_I2SRX1_I2S (3 << I2SCONFIG_FORMAT_I2SRX1_SHIFT) /* I2S */ -# define I2SCONFIG_FORMAT_I2SRX1_16BIT (4 << I2SCONFIG_FORMAT_I2SRX1_SHIFT) /* LSB justified 16 bits */ -# define I2SCONFIG_FORMAT_I2SRX1_18BIT (5 << I2SCONFIG_FORMAT_I2SRX1_SHIFT) /* LSB justified 18 bits */ -# define I2SCONFIG_FORMAT_I2SRX1_20BIT (6 << I2SCONFIG_FORMAT_I2SRX1_SHIFT) /* LSB justified 20 bits */ -# define I2SCONFIG_FORMAT_I2SRX1_24BIT (7 << I2SCONFIG_FORMAT_I2SRX1_SHIFT) /* LSB justified 24 bits */ -#define I2SCONFIG_FORMAT_I2SRX0_SHIFT (6) /* Bits 6-8: I2SRX0 I2S output format */ -#define I2SCONFIG_FORMAT_I2SRX0_MASK (7 << I2SCONFIG_FORMAT_I2SRX0_SHIFT) -# define I2SCONFIG_FORMAT_I2SRX0_I2S (3 << I2SCONFIG_FORMAT_I2SRX0_SHIFT) /* I2S */ -# define I2SCONFIG_FORMAT_I2SRX0_16BIT (4 << I2SCONFIG_FORMAT_I2SRX0_SHIFT) /* LSB justified 16 bits */ -# define I2SCONFIG_FORMAT_I2SRX0_18BIT (5 << I2SCONFIG_FORMAT_I2SRX0_SHIFT) /* LSB justified 18 bits */ -# define I2SCONFIG_FORMAT_I2SRX0_20BIT (6 << I2SCONFIG_FORMAT_I2SRX0_SHIFT) /* LSB justified 20 bits */ -# define I2SCONFIG_FORMAT_I2SRX0_24BIT (7 << I2SCONFIG_FORMAT_I2SRX0_SHIFT) /* LSB justified 24 bits */ -#define I2SCONFIG_FORMAT_I2STX1_SHIFT (3) /* Bits 3-5: 2STX1 I2S input format */ -#define I2SCONFIG_FORMAT_I2STX1_MASK (7 << I2SCONFIG_FORMAT_I2STX1_SHIFT) -# define I2SCONFIG_FORMAT_I2STX1_I2S (3 << I2SCONFIG_FORMAT_I2STX1_SHIFT) /* I2S */ -# define I2SCONFIG_FORMAT_I2STX1_16BIT (4 << I2SCONFIG_FORMAT_I2STX1_SHIFT) /* LSB justified 16 bits */ -# define I2SCONFIG_FORMAT_I2STX1_18BIT (5 << I2SCONFIG_FORMAT_I2STX1_SHIFT) /* LSB justified 18 bits */ -# define I2SCONFIG_FORMAT_I2STX1_20BIT (6 << I2SCONFIG_FORMAT_I2STX1_SHIFT) /* LSB justified 20 bits */ -# define I2SCONFIG_FORMAT_I2STX1_24BIT (7 << I2SCONFIG_FORMAT_I2STX1_SHIFT) /* LSB justified 24 bits */ -#define I2SCONFIG_FORMAT_I2STX0_SHIFT (0) /* Bits 0-2: I2STX0 I2S input format */ -#define I2SCONFIG_FORMAT_I2STX0_MASK (7 << I2SCONFIG_FORMAT_I2STX0_SHIFT) -# define I2SCONFIG_FORMAT_I2STX0_I2S (3 << I2SCONFIG_FORMAT_I2STX0_SHIFT) /* I2S */ -# define I2SCONFIG_FORMAT_I2STX0_16BIT (4 << I2SCONFIG_FORMAT_I2STX0_SHIFT) /* LSB justified 16 bits */ -# define I2SCONFIG_FORMAT_I2STX0_18BIT (5 << I2SCONFIG_FORMAT_I2STX0_SHIFT) /* LSB justified 18 bits */ -# define I2SCONFIG_FORMAT_I2STX0_20BIT (6 << I2SCONFIG_FORMAT_I2STX0_SHIFT) /* LSB justified 20 bits */ -# define I2SCONFIG_FORMAT_I2STX0_24BIT (7 << I2SCONFIG_FORMAT_I2STX0_SHIFT) /* LSB justified 24 bits */ - -/* II2SCONFIG_CFGMUX address 0x16000004 */ - -#define I2SCONFIG_CFGMUX_I2SRX1OEN (1 << 2) /* Bit 2: Selects faster mode for I2SRX1 */ -#define I2SCONFIG_CFGMUX_I2SRX0OEN (1 << 1) /* Bit 1: Slects master mode for I2SRX0 */ - -/* I2SCONFIG_NSOFCNT address 0x16000010 */ - -/************************************************************************************************ - * Public Types - ************************************************************************************************/ - -/************************************************************************************************ - * Public Data - ************************************************************************************************/ - -/************************************************************************************************ - * Public Functions - ************************************************************************************************/ - -#endif /* __ARCH_ARM_SRC_LPC313X_I2S_H */ diff --git a/nuttx/arch/arm/src/lpc313x/lpc313x_intc.h b/nuttx/arch/arm/src/lpc313x/lpc313x_intc.h deleted file mode 100755 index 301272945..000000000 --- a/nuttx/arch/arm/src/lpc313x/lpc313x_intc.h +++ /dev/null @@ -1,198 +0,0 @@ -/************************************************************************************************ - * arch/arm/src/lpc313x/lpc313x_intc.h - * - * Copyright (C) 2009-2010 Gregory Nutt. All rights reserved. - * Author: Gregory Nutt - * - * 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_LPC313X_INTC_H -#define __ARCH_ARM_SRC_LPC313X_INTC_H - -/************************************************************************************************ - * Included Files - ************************************************************************************************/ - -#include -#include "lpc313x_memorymap.h" - -/************************************************************************************************ - * Pre-processor Definitions - ************************************************************************************************/ - -/* INTC register base address *******************************************************************/ - -#define LPC313X_INTC_VBASE (LPC313X_INTC_VSECTION) -#define LPC313X_INTC_PBASE (LPC313X_INTC_PSECTION) - -/* INTC register offsets (with respect to the base of the INTC domain) **************************/ - -#define LPC313X_INTC_PRIORITYMASK0_OFFSET 0x000 /* Interrupt target 0 priority threshold */ -#define LPC313X_INTC_PRIORITYMASK1_OFFSET 0x004 /* Interrupt target 0 priority threshold */ -#define LPC313X_INTC_VECTOR0_OFFSET 0x100 /* Vector register for target 0 => nIRQ */ -#define LPC313X_INTC_VECTOR1_OFFSET 0x104 /* Vector register for target 1 => nFIQ */ -#define LPC313X_INTC_PENDING_OFFSET 0x200 /* Status of interrupt request 1..29 */ -#define LPC313X_INTC_FEATURES_OFFSET 0x300 /* Interrupt controller configuration */ -#define LPC313X_INTC_REQUEST_OFFSET(n) (0x400+((n) << 2)) -#define LPC313X_INTC_REQUEST1_OFFSET 0x404 /* Interrupt request 1 configuration */ -#define LPC313X_INTC_REQUEST2_OFFSET 0x408 /* Interrupt request 2 configuration */ -#define LPC313X_INTC_REQUEST3_OFFSET 0x40c /* Interrupt request 3 configuration */ -#define LPC313X_INTC_REQUEST4_OFFSET 0x410 /* Interrupt request 4 configuration */ -#define LPC313X_INTC_REQUEST5_OFFSET 0x414 /* Interrupt request 5 configuration */ -#define LPC313X_INTC_REQUEST6_OFFSET 0x418 /* Interrupt request 6 configuration */ -#define LPC313X_INTC_REQUEST7_OFFSET 0x41c /* Interrupt request 7 configuration */ -#define LPC313X_INTC_REQUEST8_OFFSET 0x420 /* Interrupt request 8 configuration */ -#define LPC313X_INTC_REQUEST9_OFFSET 0x424 /* Interrupt request 9 configuration */ -#define LPC313X_INTC_REQUEST10_OFFSET 0x428 /* Interrupt request 10 configuration */ -#define LPC313X_INTC_REQUEST11_OFFSET 0x42c /* Interrupt request 11 configuration */ -#define LPC313X_INTC_REQUEST12_OFFSET 0x430 /* Interrupt request 12 configuration */ -#define LPC313X_INTC_REQUEST13_OFFSET 0x434 /* Interrupt request 13 configuration */ -#define LPC313X_INTC_REQUEST14_OFFSET 0x438 /* Interrupt request 14 configuration */ -#define LPC313X_INTC_REQUEST15_OFFSET 0x43c /* Interrupt request 15 configuration */ -#define LPC313X_INTC_REQUEST16_OFFSET 0x440 /* Interrupt request 16 configuration */ -#define LPC313X_INTC_REQUEST17_OFFSET 0x444 /* Interrupt request 17 configuration */ -#define LPC313X_INTC_REQUEST18_OFFSET 0x448 /* Interrupt request 18 configuration */ -#define LPC313X_INTC_REQUEST19_OFFSET 0x44c /* Interrupt request 19 configuration */ -#define LPC313X_INTC_REQUEST20_OFFSET 0x450 /* Interrupt request 20 configuration */ -#define LPC313X_INTC_REQUEST21_OFFSET 0x454 /* Interrupt request 21 configuration */ -#define LPC313X_INTC_REQUEST22_OFFSET 0x458 /* Interrupt request 22 configuration */ -#define LPC313X_INTC_REQUEST23_OFFSET 0x45c /* Interrupt request 23 configuration */ -#define LPC313X_INTC_REQUEST24_OFFSET 0x460 /* Interrupt request 24 configuration */ -#define LPC313X_INTC_REQUEST25_OFFSET 0x464 /* Interrupt request 25 configuration */ -#define LPC313X_INTC_REQUEST26_OFFSET 0x468 /* Interrupt request 26 configuration */ -#define LPC313X_INTC_REQUEST27_OFFSET 0x46c /* Interrupt request 27 configuration */ -#define LPC313X_INTC_REQUEST28_OFFSET 0x470 /* Interrupt request 28 configuration */ -#define LPC313X_INTC_REQUEST29_OFFSET 0x474 /* Interrupt request 29 configuration */ - -/* INTC register (virtual) addresses ************************************************************/ - -#define LPC313X_INTC_PRIORITYMASK0 (LPC313X_INTC_VBASE+LPC313X_INTC_PRIORITYMASK0_OFFSET) -#define LPC313X_INTC_PRIORITYMASK1 (LPC313X_INTC_VBASE+LPC313X_INTC_PRIORITYMASK1_OFFSET) -#define LPC313X_INTC_VECTOR0 (LPC313X_INTC_VBASE+LPC313X_INTC_VECTOR0_OFFSET) -#define LPC313X_INTC_VECTOR1 (LPC313X_INTC_VBASE+LPC313X_INTC_VECTOR1_OFFSET) -#define LPC313X_INTC_PENDING (LPC313X_INTC_VBASE+LPC313X_INTC_PENDING_OFFSET) -#define LPC313X_INTC_FEATURES (LPC313X_INTC_VBASE+LPC313X_INTC_FEATURES_OFFSET) -#define LPC313X_INTC_REQUEST(n) (LPC313X_INTC_VBASE+LPC313X_INTC_REQUEST_OFFSET(n)) -#define LPC313X_INTC_REQUEST1 (LPC313X_INTC_VBASE+LPC313X_INTC_REQUEST1_OFFSET) -#define LPC313X_INTC_REQUEST2 (LPC313X_INTC_VBASE+LPC313X_INTC_REQUEST2_OFFSET) -#define LPC313X_INTC_REQUEST3 (LPC313X_INTC_VBASE+LPC313X_INTC_REQUEST3_OFFSET) -#define LPC313X_INTC_REQUEST4 (LPC313X_INTC_VBASE+LPC313X_INTC_REQUEST4_OFFSET) -#define LPC313X_INTC_REQUEST5 (LPC313X_INTC_VBASE+LPC313X_INTC_REQUEST5_OFFSET) -#define LPC313X_INTC_REQUEST6 (LPC313X_INTC_VBASE+LPC313X_INTC_REQUEST6_OFFSET) -#define LPC313X_INTC_REQUEST7 (LPC313X_INTC_VBASE+LPC313X_INTC_REQUEST7_OFFSET) -#define LPC313X_INTC_REQUEST8 (LPC313X_INTC_VBASE+LPC313X_INTC_REQUEST8_OFFSET) -#define LPC313X_INTC_REQUEST9 (LPC313X_INTC_VBASE+LPC313X_INTC_REQUEST9_OFFSET) -#define LPC313X_INTC_REQUEST10 (LPC313X_INTC_VBASE+LPC313X_INTC_REQUEST10_OFFSET) -#define LPC313X_INTC_REQUEST11 (LPC313X_INTC_VBASE+LPC313X_INTC_REQUEST11_OFFSET) -#define LPC313X_INTC_REQUEST12 (LPC313X_INTC_VBASE+LPC313X_INTC_REQUEST12_OFFSET) -#define LPC313X_INTC_REQUEST13 (LPC313X_INTC_VBASE+LPC313X_INTC_REQUEST13_OFFSET) -#define LPC313X_INTC_REQUEST14 (LPC313X_INTC_VBASE+LPC313X_INTC_REQUEST14_OFFSET) -#define LPC313X_INTC_REQUEST15 (LPC313X_INTC_VBASE+LPC313X_INTC_REQUEST15_OFFSET) -#define LPC313X_INTC_REQUEST16 (LPC313X_INTC_VBASE+LPC313X_INTC_REQUEST16_OFFSET) -#define LPC313X_INTC_REQUEST17 (LPC313X_INTC_VBASE+LPC313X_INTC_REQUEST17_OFFSET) -#define LPC313X_INTC_REQUEST18 (LPC313X_INTC_VBASE+LPC313X_INTC_REQUEST18_OFFSET) -#define LPC313X_INTC_REQUEST19 (LPC313X_INTC_VBASE+LPC313X_INTC_REQUEST19_OFFSET) -#define LPC313X_INTC_REQUEST20 (LPC313X_INTC_VBASE+LPC313X_INTC_REQUEST20_OFFSET) -#define LPC313X_INTC_REQUEST21 (LPC313X_INTC_VBASE+LPC313X_INTC_REQUEST21_OFFSET) -#define LPC313X_INTC_REQUEST22 (LPC313X_INTC_VBASE+LPC313X_INTC_REQUEST22_OFFSET) -#define LPC313X_INTC_REQUEST23 (LPC313X_INTC_VBASE+LPC313X_INTC_REQUEST23_OFFSET) -#define LPC313X_INTC_REQUEST24 (LPC313X_INTC_VBASE+LPC313X_INTC_REQUEST24_OFFSET) -#define LPC313X_INTC_REQUEST25 (LPC313X_INTC_VBASE+LPC313X_INTC_REQUEST25_OFFSET) -#define LPC313X_INTC_REQUEST26 (LPC313X_INTC_VBASE+LPC313X_INTC_REQUEST26_OFFSET) -#define LPC313X_INTC_REQUEST27 (LPC313X_INTC_VBASE+LPC313X_INTC_REQUEST27_OFFSET) -#define LPC313X_INTC_REQUEST28 (LPC313X_INTC_VBASE+LPC313X_INTC_REQUEST28_OFFSET) -#define LPC313X_INTC_REQUEST29 (LPC313X_INTC_VBASE+LPC313X_INTC_REQUEST29_OFFSET) - -/* INTC register bit definitions ****************************************************************/ - -/* Interrupt priority mask register (INT_PRIORITYMASK0 address 0x60000000 and - * INTC_PRIORITYMASK1 address 0x60000004) - */ - -#define INTC_PRIORITYMASK_PRIOLIMIT_SHIFT (0) /* Bits 0-7: Priority threshold for interrupts */ -#define INTC_PRIORITYMASK_PRIOLIMIT_MASK (255 << INTC_PRIORITYMASK_PRIOLIMIT_MASK) - -/* Interrupt vector registers (INTC_VECTOR0 address 0x60000100 and INTC_VECTOR1 address - * 0x60000104) - */ - -#define INTC_VECTOR_TABLEADDR_SHIFT (11) /* Bits 11-31: Table start address */ -#define INTC_VECTOR_TABLEADDR_MASK (0x001fffff << INTC_VECTOR_TABLEADDR_SHIFT) -#define INTC_VECTOR_INDEX_SHIFT (3) /* Bits 3-10: IRQ number of interrupt */ -#define INTC_VECTOR_INDEX_MASK (255 << INTC_VECTOR_INDEX_SHIFT) - -/* Interrupt pending register (INT_PENDING1_31, address 0x60000200) */ - -#define INTC_PENDING_SHIFT (1) /* Bits 1-29: Pending interrupt request */ -#define INTC_PENDING_MASK (0x1fffffff << INTC_PENDING_SHIFT) - -/* Interrupt controller features register (INT_FEATURES, address 0x60000300) */ - -#define INTC_FEATURES_T_SHIFT (16) /* Bits 16-21: Number interrupt targets supported (+1) */ -#define INTC_FEATURES_T_MASK (63 << INTC_FEATURES_T_SHIFT) -#define INTC_FEATURES_P_SHIFT (8) /* Bits 8-15: Number priority levels supported */ -#define INTC_FEATURES_P_MASK (255 << INTC_FEATURES_P_SHIFT) -#define INTC_FEATURES_N_SHIFT (0) /* Bits 0-7: Number interrupt request inputs */ -#define INTC_FEATURES_N_MASK (255 << INTC_FEATURES_N_SHIFT) - -/* Interrupt request registers (INT_REQUEST1 address 0x60000404 to INTC_REQUEST29 address - * 0x60000474) - */ - -#define INTC_REQUEST_PENDING (1 << 31) /* Bit 31: Pending interrupt request */ -#define INTC_REQUEST_SETSWINT (1 << 30) /* Bit 30: Set software interrupt request */ -#define INTC_REQUEST_CLRSWINT (1 << 29) /* Bit 29: Clear software interrupt request */ -#define INTC_REQUEST_WEPRIO (1 << 28) /* Bit 28: Write Enable PRIORITY_LEVEL */ -#define INTC_REQUEST_WETARGET (1 << 27) /* Bit 27: Write Enable TARGET */ -#define INTC_REQUEST_WEENABLE (1 << 26) /* Bit 26: Write Enable ENABLE */ -#define INTC_REQUEST_WEACTLOW (1 << 25) /* Bit 25: Write Enable ACTIVE_LOW */ -#define INTC_REQUEST_ACTLOW (1 << 17) /* Bit 17: Active Low */ -#define INTC_REQUEST_ENABLE (1 << 16) /* Bit 16: Enable interrupt request */ -#define INTC_REQUEST_TARGET_SHIFT (8) /* Bits 8-13: Interrupt target */ -#define INTC_REQUEST_TARGET_MASK (63 << INTC_REQUEST_TARGET_SHIFT) -# define INTC_REQUEST_TARGET_IRQ (INTC_REQUEST_WETARGET | (0 << INTC_REQUEST_TARGET_SHIFT)) /* Proc interrupt request 0: IRQ */ -# define INTC_REQUEST_TARGET_FIQ (INTC_REQUEST_WETARGET | (1 << INTC_REQUEST_TARGET_SHIFT)) /* Proc interrupt request 1: FIQ */ -#define INTC_REQUEST_PRIOLEVEL_SHIFT (0) /* Bits 0-7: Priority level */ -#define INTC_REQUEST_PRIOLEVEL_MASK (255 << INTC_REQUEST_PRIOLEVEL_SHIFT) -# define INTC_REQUEST_PRIOLEVEL(n) (((n) << INTC_REQUEST_PRIOLEVEL_SHIFT) & INTC_REQUEST_PRIOLEVEL_MASK) - -/************************************************************************************************ - * Public Types - ************************************************************************************************/ - -/************************************************************************************************ - * Public Data - ************************************************************************************************/ - -/************************************************************************************************ - * Public Functions - ************************************************************************************************/ - -#endif /* __ARCH_ARM_SRC_LPC313X_INTC_H */ diff --git a/nuttx/arch/arm/src/lpc313x/lpc313x_internal.h b/nuttx/arch/arm/src/lpc313x/lpc313x_internal.h deleted file mode 100755 index 2ba9f94ab..000000000 --- a/nuttx/arch/arm/src/lpc313x/lpc313x_internal.h +++ /dev/null @@ -1,300 +0,0 @@ -/************************************************************************************ - * arch/arm/src/lpc313x/lpc313x_internal.h - * - * Copyright (C) 2009-2010 Gregory Nutt. All rights reserved. - * Author: Gregory Nutt - * - * 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_LPC313X_LPC313X_INTERNAL_H -#define __ARCH_ARM_SRC_LPC313X_LPC313X_INTERNAL_H - -/************************************************************************************ - * Included Files - ************************************************************************************/ - -#include - -#include -#include -#include - -#include "up_internal.h" -#include "up_arch.h" -#include "chip.h" -#include "lpc313x_ioconfig.h" - -/************************************************************************************ - * Definitions - ************************************************************************************/ - -/* Configuration ********************************************************************/ - -/* NVIC priority levels *************************************************************/ - -/************************************************************************************ - * Public Types - ************************************************************************************/ - -/************************************************************************************ - * Inline Functions - ************************************************************************************/ - -#ifndef __ASSEMBLY__ - -/************************************************************************************ - * Public Data - ************************************************************************************/ - -#undef EXTERN -#if defined(__cplusplus) -#define EXTERN extern "C" -extern "C" { -#else -#define EXTERN extern -#endif - -/************************************************************************************ - * Inline Functions - ************************************************************************************/ - -/* Configure a pin as an input */ - -static inline void gpio_configinput(uint32_t ioconfig, uint32_t bit) -{ - uint32_t regaddr; - - regaddr = ioconfig + LPC313X_IOCONFIG_MODE0RESET_OFFSET; - putreg32(bit, regaddr); - - regaddr = ioconfig + LPC313X_IOCONFIG_MODE1RESET_OFFSET; - putreg32(bit, regaddr); -} - -/* Return the current state of an input GPIO pin */ - -static inline bool lpc313x_gpioread(uint32_t ioconfig, uint32_t bit) -{ - uint32_t regaddr = ioconfig + LPC313X_IOCONFIG_PINS_OFFSET; - return (getreg32(regaddr) & bit) != 0; -} - -/* Configure the pin so that it is driven by the device */ - -static inline void gpio_configdev(uint32_t ioconfig, uint32_t bit) -{ - uint32_t regaddr; - - regaddr = ioconfig + LPC313X_IOCONFIG_MODE1RESET_OFFSET; - putreg32(bit, regaddr); - - regaddr = ioconfig + LPC313X_IOCONFIG_MODE0SET_OFFSET; - putreg32(bit, regaddr); -} - -/* Configure a pin as a low output */ - -static inline void gpio_outputlow(uint32_t ioconfig, uint32_t bit) -{ - uint32_t regaddr; - - regaddr = ioconfig + LPC313X_IOCONFIG_MODE1SET_OFFSET; - putreg32(bit, regaddr); - - regaddr = ioconfig + LPC313X_IOCONFIG_MODE0RESET_OFFSET; - putreg32(bit, regaddr); -} - -/* Configure a pin as a high output */ - -static inline void gpio_outputhigh(uint32_t ioconfig, uint32_t bit) -{ - uint32_t regaddr; - - regaddr = ioconfig + LPC313X_IOCONFIG_MODE1SET_OFFSET; - putreg32(bit, regaddr); - - regaddr = ioconfig + LPC313X_IOCONFIG_MODE0SET_OFFSET; - putreg32(bit, regaddr); -} - -/************************************************************************************ - * Public Function Prototypes - ************************************************************************************/ - -/************************************************************************************ - * Name: lpc313x_lowsetup - * - * Description: - * Called early in up_boot. Performs chip-common low level initialization. - * - ************************************************************************************/ - -EXTERN void lpc313x_lowsetup(void); - -/************************************************************************************ - * Name: lpc313x_clockconfig - * - * Description: - * Called to change to new clock based on settings in board.h - * - ************************************************************************************/ - -EXTERN void lpc313x_clockconfig(void); - -/************************************************************************************ - * Name: lpc313x_spiselect and lpc313x_spistatus - * - * Description: - * The external functions, lpc313x_spiselect, lpc313x_spistatus, and - * lpc313x_spicmddata must be provided by board-specific logic. These are - * implementations of the select, status, and cmddata methods of the SPI interface - * defined by struct spi_ops_s (see include/nuttx/spi.h). All other methods - * (including up_spiinitialize()) are provided by common LPC313X logic. To use - * this common SPI logic on your board: - * - * 1. Provide logic in lpc313x_boardinitialize() to configure SPI chip select - * pins. - * 2. Provide lpc313x_spiselect() and lpc313x_spistatus() functions in your - * board-specific logic. These functions will perform chip selection and - * status operations using GPIOs in the way your board is configured. - * 3. If CONFIG_SPI_CMDDATA is selected in your NuttX configuration, provide - * the lpc313x_spicmddata() function in your board-specific logic. This - * function will perform cmd/data selection operations using GPIOs in the - * way your board is configured. - * 4. Add a calls to up_spiinitialize() in your low level application - * initialization logic - * 5. The handle returned by up_spiinitialize() may then be used to bind the - * SPI driver to higher level logic (e.g., calling - * mmcsd_spislotinitialize(), for example, will bind the SPI driver to - * the SPI MMC/SD driver). - * - ************************************************************************************/ - -struct spi_dev_s; -enum spi_dev_e; -EXTERN void lpc313x_spiselect(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected); -EXTERN uint8_t lpc313x_spistatus(FAR struct spi_dev_s *dev, enum spi_dev_e devid); -#ifdef CONFIG_SPI_CMDDATA -EXTERN int lpc313x_spicmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd); -#endif - -/************************************************************************************ - * Name: lpc313x_usbpullup - * - * Description: - * If USB is supported and the board supports a pullup via GPIO (for USB software - * connect and disconnect), then the board software must provide lpc313x_pullup. - * See include/nuttx/usb/usbdev.h for additional description of this method. - * Alternatively, if no pull-up GPIO the following EXTERN can be redefined to be - * NULL. - * - ************************************************************************************/ - -struct usbdev_s; -EXTERN int lpc313x_usbpullup(FAR struct usbdev_s *dev, bool enable); - -/************************************************************************************ - * Name: lpc313x_usbsuspend - * - * Description: - * Board logic must provide the lpc313x_usbsuspend logic if the USBDEV driver is - * used. This function is called whenever the USB enters or leaves suspend mode. - * This is an opportunity for the board logic to shutdown clocks, power, etc. - * while the USB is suspended. - * - ************************************************************************************/ - -struct usbdev_s; -EXTERN void lpc313x_usbsuspend(FAR struct usbdev_s *dev, bool resume); - -/**************************************************************************** - * Name: sdio_initialize - * - * Description: - * Initialize SDIO for operation. - * - * Input Parameters: - * slotno - Not used. - * - * Returned Values: - * A reference to an SDIO interface structure. NULL is returned on failures. - * - ****************************************************************************/ - -struct sdio_dev_s; /* See include/nuttx/sdio.h */ -EXTERN FAR struct sdio_dev_s *sdio_initialize(int slotno); - -/**************************************************************************** - * Name: sdio_mediachange - * - * Description: - * Called by board-specific logic -- posssible from an interrupt handler -- - * in order to signal to the driver that a card has been inserted or - * removed from the slot - * - * Input Parameters: - * dev - An instance of the SDIO driver device state structure. - * cardinslot - true is a card has been detected in the slot; false if a - * card has been removed from the slot. Only transitions - * (inserted->removed or removed->inserted should be reported) - * - * Returned Values: - * None - * - ****************************************************************************/ - -EXTERN void sdio_mediachange(FAR struct sdio_dev_s *dev, bool cardinslot); - -/**************************************************************************** - * Name: sdio_wrprotect - * - * Description: - * Called by board-specific logic to report if the card in the slot is - * mechanically write protected. - * - * Input Parameters: - * dev - An instance of the SDIO driver device state structure. - * wrprotect - true is a card is writeprotected. - * - * Returned Values: - * None - * - ****************************************************************************/ - -EXTERN void sdio_wrprotect(FAR struct sdio_dev_s *dev, bool wrprotect); - -#undef EXTERN -#if defined(__cplusplus) -} -#endif - -#endif /* __ASSEMBLY__ */ -#endif /* __ARCH_ARM_SRC_LPC313X_LPC313X_INTERNAL_H */ diff --git a/nuttx/arch/arm/src/lpc313x/lpc313x_ioconfig.h b/nuttx/arch/arm/src/lpc313x/lpc313x_ioconfig.h deleted file mode 100755 index 739ac5ab1..000000000 --- a/nuttx/arch/arm/src/lpc313x/lpc313x_ioconfig.h +++ /dev/null @@ -1,357 +0,0 @@ -/************************************************************************************************ - * arch/arm/src/lpc313x/lpc313x_ioconfig.h - * - * Copyright (C) 2009-2010 Gregory Nutt. All rights reserved. - * Author: Gregory Nutt - * - * 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_LPC313X_IOCONFIG_H -#define __ARCH_ARM_SRC_LPC313X_IOCONFIG_H - -/************************************************************************************************ - * Included Files - ************************************************************************************************/ - -#include -#include "lpc313x_memorymap.h" - -/************************************************************************************************ - * Pre-processor Definitions - ************************************************************************************************/ - -/* IOCONFIG register base address offset into the APB0 domain ***********************************/ - -#define LPC313X_IOCONFIG_VBASE (LPC313X_APB0_VADDR+LPC313X_APB0_IOCONFIG_OFFSET) -#define LPC313X_IOCONFIG_PBASE (LPC313X_APB0_PADDR+LPC313X_APB0_IOCONFIG_OFFSET) - -/* IOCONFIG function block offsets (with respect to the IOCONFIG register base address) *********/ - -#define LPC313X_IOCONFIG_EBIMCI_OFFSET 0x000 /* First set of 32 multiplexed pads */ -#define LPC313X_IOCONFIG_EBII2STX0_OFFSET 0X040 /* Second set of 32 of multiplexed pads */ -#define LPC313X_IOCONFIG_CGU_OFFSET 0X080 /* Clock Generation Unit function block */ -#define LPC313X_IOCONFIG_I2SRX0_OFFSET 0x0c0 /* I2SRX function block 0 */ -#define LPC313X_IOCONFIG_I2SRX1_OFFSET 0x100 /* I2SRX function block 1 */ -#define LPC313X_IOCONFIG_I2STX1_OFFSET 0x140 /* I2STX function block 1 */ -#define LPC313X_IOCONFIG_EBI_OFFSET 0x180 /* External Bus Interface function block */ -#define LPC313X_IOCONFIG_GPIO_OFFSET 0x1c0 /* General purpose IO */ -#define LPC313X_IOCONFIG_I2C1_OFFSET 0x200 /* I2C function block */ -#define LPC313X_IOCONFIG_SPI_OFFSET 0x240 /* SPI function block */ -#define LPC313X_IOCONFIG_NAND_OFFSET 0x280 /* NANDFLASH function block */ -#define LPC313X_IOCONFIG_PWM_OFFSET 0x2c0 /* PWM function block */ -#define LPC313X_IOCONFIG_UART_OFFSET 0x300 /* UART function block */ - -/* IOCONFIG register offsets (with respect to any funcion block base address) *******************/ - -#define LPC313X_IOCONFIG_PINS_OFFSET 0x000 /* WR: RD: Input pin state */ - /* 0x004-0x00c: Reserved */ -#define LPC313X_IOCONFIG_MODE0_OFFSET 0x010 /* WR:Load RD: */ -#define LPC313X_IOCONFIG_MODE0SET_OFFSET 0x014 /* WR:Set Bits RD:Read Mode 0 */ -#define LPC313X_IOCONFIG_MODE0RESET_OFFSET 0x018 /* WR:Reset Bits RD: */ - /* 0x01c: Reserved */ -#define LPC313X_IOCONFIG_MODE1_OFFSET 0x020 /* WR:Load RD: */ -#define LPC313X_IOCONFIG_MODE1SET_OFFSET 0x024 /* WR:Set Bits RD:Read Mode 1 */ -#define LPC313X_IOCONFIG_MODE1RESET_OFFSET 0x028 /* WR:Reset Bits RD: */ - /* 0x02c-0x3c: Reserved */ - -/* IOCONFIG function block (virtual) base addresses *********************************************/ - -#define LPC313X_IOCONFIG_EBIMCI (LPC313X_IOCONFIG_VBASE+LPC313X_IOCONFIG_EBIMCI_OFFSET) -#define LPC313X_IOCONFIG_EBII2STX0 (LPC313X_IOCONFIG_VBASE+LPC313X_IOCONFIG_EBII2STX0_OFFSET) -#define LPC313X_IOCONFIG_CGU (LPC313X_IOCONFIG_VBASE+LPC313X_IOCONFIG_CGU_OFFSET) -#define LPC313X_IOCONFIG_I2SRX0 (LPC313X_IOCONFIG_VBASE+LPC313X_IOCONFIG_I2SRX0_OFFSET) -#define LPC313X_IOCONFIG_I2SRX1 (LPC313X_IOCONFIG_VBASE+LPC313X_IOCONFIG_I2SRX1_OFFSET) -#define LPC313X_IOCONFIG_I2STX1 (LPC313X_IOCONFIG_VBASE+LPC313X_IOCONFIG_I2STX1_OFFSET) -#define LPC313X_IOCONFIG_EBI (LPC313X_IOCONFIG_VBASE+LPC313X_IOCONFIG_EBI_OFFSET) -#define LPC313X_IOCONFIG_GPIO (LPC313X_IOCONFIG_VBASE+LPC313X_IOCONFIG_GPIO_OFFSET) -#define LPC313X_IOCONFIG_I2C1 (LPC313X_IOCONFIG_VBASE+LPC313X_IOCONFIG_I2C1_OFFSET) -#define LPC313X_IOCONFIG_SPI (LPC313X_IOCONFIG_VBASE+LPC313X_IOCONFIG_SPI_OFFSET) -#define LPC313X_IOCONFIG_NAND (LPC313X_IOCONFIG_VBASE+LPC313X_IOCONFIG_NAND_OFFSET) -#define LPC313X_IOCONFIG_PWM (LPC313X_IOCONFIG_VBASE+LPC313X_IOCONFIG_PWM_OFFSET) -#define LPC313X_IOCONFIG_UART (LPC313X_IOCONFIG_VBASE+LPC313X_IOCONFIG_UART_OFFSET) - -/* IOCONFIG register (virtual) addresses ********************************************************/ - -#define LPC313X_IOCONFIG_EBIMCI_PINS (LPC313X_IOCONFIG_EBIMCI+LPC313X_IOCONFIG_PINS_OFFSET) -#define LPC313X_IOCONFIG_EBIMCI_MODE0 (LPC313X_IOCONFIG_EBIMCI+LPC313X_IOCONFIG_MODE0_OFFSET) -#define LPC313X_IOCONFIG_EBIMCI_MODE0SET (LPC313X_IOCONFIG_EBIMCI+LPC313X_IOCONFIG_MODE0SET_OFFSET) -#define LPC313X_IOCONFIG_EBIMCI_MODE0RESET (LPC313X_IOCONFIG_EBIMCI+LPC313X_IOCONFIG_MODE0RESET_OFFSET) -#define LPC313X_IOCONFIG_EBIMCI_MODE1 (LPC313X_IOCONFIG_EBIMCI+LPC313X_IOCONFIG_MODE1_OFFSET) -#define LPC313X_IOCONFIG_EBIMCI_MODE1SET (LPC313X_IOCONFIG_EBIMCI+LPC313X_IOCONFIG_MODE1SET_OFFSET) -#define LPC313X_IOCONFIG_EBIMCI_MODE1RESET (LPC313X_IOCONFIG_EBIMCI+LPC313X_IOCONFIG_MODE1RESET_OFFSET) - -#define LPC313X_IOCONFIG_EBII2STX0_PINS (LPC313X_IOCONFIG_EBII2STX0+LPC313X_IOCONFIG_PINS_OFFSET) -#define LPC313X_IOCONFIG_EBII2STX0_MODE0 (LPC313X_IOCONFIG_EBII2STX0+LPC313X_IOCONFIG_MODE0_OFFSET) -#define LPC313X_IOCONFIG_EBII2STX0_MODE0SET (LPC313X_IOCONFIG_EBII2STX0+LPC313X_IOCONFIG_MODE0SET_OFFSET) -#define LPC313X_IOCONFIG_EBII2STX0_MODE0RESET (LPC313X_IOCONFIG_EBII2STX0+LPC313X_IOCONFIG_MODE0RESET_OFFSET) -#define LPC313X_IOCONFIG_EBII2STX0_MODE1 (LPC313X_IOCONFIG_EBII2STX0+LPC313X_IOCONFIG_MODE1_OFFSET) -#define LPC313X_IOCONFIG_EBII2STX0_MODE1SET (LPC313X_IOCONFIG_EBII2STX0+LPC313X_IOCONFIG_MODE1SET_OFFSET) -#define LPC313X_IOCONFIG_EBII2STX0_MODE1RESET (LPC313X_IOCONFIG_EBII2STX0+LPC313X_IOCONFIG_MODE1RESET_OFFSET) - -#define LPC313X_IOCONFIG_CGU_PINS (LPC313X_IOCONFIG_CGU+LPC313X_IOCONFIG_PINS_OFFSET) -#define LPC313X_IOCONFIG_CGU_MODE0 (LPC313X_IOCONFIG_CGU+LPC313X_IOCONFIG_MODE0_OFFSET) -#define LPC313X_IOCONFIG_CGU_MODE0SET (LPC313X_IOCONFIG_CGU+LPC313X_IOCONFIG_MODE0SET_OFFSET) -#define LPC313X_IOCONFIG_CGU_MODE0RESET (LPC313X_IOCONFIG_CGU+LPC313X_IOCONFIG_MODE0RESET_OFFSET) -#define LPC313X_IOCONFIG_CGU_MODE1 (LPC313X_IOCONFIG_CGU+LPC313X_IOCONFIG_MODE1_OFFSET) -#define LPC313X_IOCONFIG_CGU_MODE1SET (LPC313X_IOCONFIG_CGU+LPC313X_IOCONFIG_MODE1SET_OFFSET) -#define LPC313X_IOCONFIG_CGU_MODE1RESET (LPC313X_IOCONFIG_CGU+LPC313X_IOCONFIG_MODE1RESET_OFFSET) - -#define LPC313X_IOCONFIG_I2SRX0_PINS (LPC313X_IOCONFIG_I2SRX0+LPC313X_IOCONFIG_PINS_OFFSET) -#define LPC313X_IOCONFIG_I2SRX0_MODE0 (LPC313X_IOCONFIG_I2SRX0+LPC313X_IOCONFIG_MODE0_OFFSET) -#define LPC313X_IOCONFIG_I2SRX0_MODE0SET (LPC313X_IOCONFIG_I2SRX0+LPC313X_IOCONFIG_MODE0SET_OFFSET) -#define LPC313X_IOCONFIG_I2SRX0_MODE0RESET (LPC313X_IOCONFIG_I2SRX0+LPC313X_IOCONFIG_MODE0RESET_OFFSET) -#define LPC313X_IOCONFIG_I2SRX0_MODE1 (LPC313X_IOCONFIG_I2SRX0+LPC313X_IOCONFIG_MODE1_OFFSET) -#define LPC313X_IOCONFIG_I2SRX0_MODE1SET (LPC313X_IOCONFIG_I2SRX0+LPC313X_IOCONFIG_MODE1SET_OFFSET) -#define LPC313X_IOCONFIG_I2SRX0_MODE1RESET (LPC313X_IOCONFIG_I2SRX0+LPC313X_IOCONFIG_MODE1RESET_OFFSET) - -#define LPC313X_IOCONFIG_I2SRX1_PINS (LPC313X_IOCONFIG_I2SRX1+LPC313X_IOCONFIG_PINS_OFFSET) -#define LPC313X_IOCONFIG_I2SRX1_MODE0 (LPC313X_IOCONFIG_I2SRX1+LPC313X_IOCONFIG_MODE0_OFFSET) -#define LPC313X_IOCONFIG_I2SRX1_MODE0SET (LPC313X_IOCONFIG_I2SRX1+LPC313X_IOCONFIG_MODE0SET_OFFSET) -#define LPC313X_IOCONFIG_I2SRX1_MODE0RESET (LPC313X_IOCONFIG_I2SRX1+LPC313X_IOCONFIG_MODE0RESET_OFFSET) -#define LPC313X_IOCONFIG_I2SRX1_MODE1 (LPC313X_IOCONFIG_I2SRX1+LPC313X_IOCONFIG_MODE1_OFFSET) -#define LPC313X_IOCONFIG_I2SRX1_MODE1SET (LPC313X_IOCONFIG_I2SRX1+LPC313X_IOCONFIG_MODE1SET_OFFSET) -#define LPC313X_IOCONFIG_I2SRX1_MODE1RESET (LPC313X_IOCONFIG_I2SRX1+LPC313X_IOCONFIG_MODE1RESET_OFFSET) - -#define LPC313X_IOCONFIG_I2STX1_PINS (LPC313X_IOCONFIG_I2STX1+LPC313X_IOCONFIG_PINS_OFFSET) -#define LPC313X_IOCONFIG_I2STX1_MODE0 (LPC313X_IOCONFIG_I2STX1+LPC313X_IOCONFIG_MODE0_OFFSET) -#define LPC313X_IOCONFIG_I2STX1_MODE0SET (LPC313X_IOCONFIG_I2STX1+LPC313X_IOCONFIG_MODE0SET_OFFSET) -#define LPC313X_IOCONFIG_I2STX1_MODE0RESET (LPC313X_IOCONFIG_I2STX1+LPC313X_IOCONFIG_MODE0RESET_OFFSET) -#define LPC313X_IOCONFIG_I2STX1_MODE1 (LPC313X_IOCONFIG_I2STX1+LPC313X_IOCONFIG_MODE1_OFFSET) -#define LPC313X_IOCONFIG_I2STX1_MODE1SET (LPC313X_IOCONFIG_I2STX1+LPC313X_IOCONFIG_MODE1SET_OFFSET) -#define LPC313X_IOCONFIG_I2STX1_MODE1RESET (LPC313X_IOCONFIG_I2STX1+LPC313X_IOCONFIG_MODE1RESET_OFFSET) - -#define LPC313X_IOCONFIG_EBI_PINS (LPC313X_IOCONFIG_EBI+LPC313X_IOCONFIG_PINS_OFFSET) -#define LPC313X_IOCONFIG_EBI_MODE0 (LPC313X_IOCONFIG_EBI+LPC313X_IOCONFIG_MODE0_OFFSET) -#define LPC313X_IOCONFIG_EBI_MODE0SET (LPC313X_IOCONFIG_EBI+LPC313X_IOCONFIG_MODE0SET_OFFSET) -#define LPC313X_IOCONFIG_EBI_MODE0RESET (LPC313X_IOCONFIG_EBI+LPC313X_IOCONFIG_MODE0RESET_OFFSET) -#define LPC313X_IOCONFIG_EBI_MODE1 (LPC313X_IOCONFIG_EBI+LPC313X_IOCONFIG_MODE1_OFFSET) -#define LPC313X_IOCONFIG_EBI_MODE1SET (LPC313X_IOCONFIG_EBI+LPC313X_IOCONFIG_MODE1SET_OFFSET) -#define LPC313X_IOCONFIG_EBI_MODE1RESET (LPC313X_IOCONFIG_EBI+LPC313X_IOCONFIG_MODE1RESET_OFFSET) - -#define LPC313X_IOCONFIG_GPIO_PINS (LPC313X_IOCONFIG_GPIO+LPC313X_IOCONFIG_PINS_OFFSET) -#define LPC313X_IOCONFIG_GPIO_MODE0 (LPC313X_IOCONFIG_GPIO+LPC313X_IOCONFIG_MODE0_OFFSET) -#define LPC313X_IOCONFIG_GPIO_MODE0SET (LPC313X_IOCONFIG_GPIO+LPC313X_IOCONFIG_MODE0SET_OFFSET) -#define LPC313X_IOCONFIG_GPIO_MODE0RESET (LPC313X_IOCONFIG_GPIO+LPC313X_IOCONFIG_MODE0RESET_OFFSET) -#define LPC313X_IOCONFIG_GPIO_MODE1 (LPC313X_IOCONFIG_GPIO+LPC313X_IOCONFIG_MODE1_OFFSET) -#define LPC313X_IOCONFIG_GPIO_MODE1SET (LPC313X_IOCONFIG_GPIO+LPC313X_IOCONFIG_MODE1SET_OFFSET) -#define LPC313X_IOCONFIG_GPIO_MODE1RESET (LPC313X_IOCONFIG_GPIO+LPC313X_IOCONFIG_MODE1RESET_OFFSET) - -#define LPC313X_IOCONFIG_I2C1_PINS (LPC313X_IOCONFIG_I2C1+LPC313X_IOCONFIG_PINS_OFFSET) -#define LPC313X_IOCONFIG_I2C1_MODE0 (LPC313X_IOCONFIG_I2C1+LPC313X_IOCONFIG_MODE0_OFFSET) -#define LPC313X_IOCONFIG_I2C1_MODE0SET (LPC313X_IOCONFIG_I2C1+LPC313X_IOCONFIG_MODE0SET_OFFSET) -#define LPC313X_IOCONFIG_I2C1_MODE0RESET (LPC313X_IOCONFIG_I2C1+LPC313X_IOCONFIG_MODE0RESET_OFFSET) -#define LPC313X_IOCONFIG_I2C1_MODE1 (LPC313X_IOCONFIG_I2C1+LPC313X_IOCONFIG_MODE1_OFFSET) -#define LPC313X_IOCONFIG_I2C1_MODE1SET (LPC313X_IOCONFIG_I2C1+LPC313X_IOCONFIG_MODE1SET_OFFSET) -#define LPC313X_IOCONFIG_I2C1_MODE1RESET (LPC313X_IOCONFIG_I2C1+LPC313X_IOCONFIG_MODE1RESET_OFFSET) - -#define LPC313X_IOCONFIG_SPI_PINS (LPC313X_IOCONFIG_SPI+LPC313X_IOCONFIG_PINS_OFFSET) -#define LPC313X_IOCONFIG_SPI_MODE0 (LPC313X_IOCONFIG_SPI+LPC313X_IOCONFIG_MODE0_OFFSET) -#define LPC313X_IOCONFIG_SPI_MODE0SET (LPC313X_IOCONFIG_SPI+LPC313X_IOCONFIG_MODE0SET_OFFSET) -#define LPC313X_IOCONFIG_SPI_MODE0RESET (LPC313X_IOCONFIG_SPI+LPC313X_IOCONFIG_MODE0RESET_OFFSET) -#define LPC313X_IOCONFIG_SPI_MODE1 (LPC313X_IOCONFIG_SPI+LPC313X_IOCONFIG_MODE1_OFFSET) -#define LPC313X_IOCONFIG_SPI_MODE1SET (LPC313X_IOCONFIG_SPI+LPC313X_IOCONFIG_MODE1SET_OFFSET) -#define LPC313X_IOCONFIG_SPI_MODE1RESET (LPC313X_IOCONFIG_SPI+LPC313X_IOCONFIG_MODE1RESET_OFFSET) - -#define LPC313X_IOCONFIG_NAND_PINS (LPC313X_IOCONFIG_NAND+LPC313X_IOCONFIG_PINS_OFFSET) -#define LPC313X_IOCONFIG_NAND_MODE0 (LPC313X_IOCONFIG_NAND+LPC313X_IOCONFIG_MODE0_OFFSET) -#define LPC313X_IOCONFIG_NAND_MODE0SET (LPC313X_IOCONFIG_NAND+LPC313X_IOCONFIG_MODE0SET_OFFSET) -#define LPC313X_IOCONFIG_NAND_MODE0RESET (LPC313X_IOCONFIG_NAND+LPC313X_IOCONFIG_MODE0RESET_OFFSET) -#define LPC313X_IOCONFIG_NAND_MODE1 (LPC313X_IOCONFIG_NAND+LPC313X_IOCONFIG_MODE1_OFFSET) -#define LPC313X_IOCONFIG_NAND_MODE1SET (LPC313X_IOCONFIG_NAND+LPC313X_IOCONFIG_MODE1SET_OFFSET) -#define LPC313X_IOCONFIG_NAND_MODE1RESET (LPC313X_IOCONFIG_NAND+LPC313X_IOCONFIG_MODE1RESET_OFFSET) - -#define LPC313X_IOCONFIG_PWM_PINS (LPC313X_IOCONFIG_PWM+LPC313X_IOCONFIG_PINS_OFFSET) -#define LPC313X_IOCONFIG_PWM_MODE0 (LPC313X_IOCONFIG_PWM+LPC313X_IOCONFIG_MODE0_OFFSET) -#define LPC313X_IOCONFIG_PWM_MODE0SET (LPC313X_IOCONFIG_PWM+LPC313X_IOCONFIG_MODE0SET_OFFSET) -#define LPC313X_IOCONFIG_PWM_MODE0RESET (LPC313X_IOCONFIG_PWM+LPC313X_IOCONFIG_MODE0RESET_OFFSET) -#define LPC313X_IOCONFIG_PWM_MODE1 (LPC313X_IOCONFIG_PWM+LPC313X_IOCONFIG_MODE1_OFFSET) -#define LPC313X_IOCONFIG_PWM_MODE1SET (LPC313X_IOCONFIG_PWM+LPC313X_IOCONFIG_MODE1SET_OFFSET) -#define LPC313X_IOCONFIG_PWM_MODE1RESET (LPC313X_IOCONFIG_PWM+LPC313X_IOCONFIG_MODE1RESET_OFFSET) - -#define LPC313X_IOCONFIG_UART_PINS (LPC313X_IOCONFIG_UART+LPC313X_IOCONFIG_PINS_OFFSET) -#define LPC313X_IOCONFIG_UART_MODE0 (LPC313X_IOCONFIG_UART+LPC313X_IOCONFIG_MODE0_OFFSET) -#define LPC313X_IOCONFIG_UART_MODE0SET (LPC313X_IOCONFIG_UART+LPC313X_IOCONFIG_MODE0SET_OFFSET) -#define LPC313X_IOCONFIG_UART_MODE0RESET (LPC313X_IOCONFIG_UART+LPC313X_IOCONFIG_MODE0RESET_OFFSET) -#define LPC313X_IOCONFIG_UART_MODE1 (LPC313X_IOCONFIG_UART+LPC313X_IOCONFIG_MODE1_OFFSET) -#define LPC313X_IOCONFIG_UART_MODE1SET (LPC313X_IOCONFIG_UART+LPC313X_IOCONFIG_MODE1SET_OFFSET) -#define LPC313X_IOCONFIG_UART_MODE1RESET (LPC313X_IOCONFIG_UART+LPC313X_IOCONFIG_MODE1RESET_OFFSET) - -/* IOCONFIG register bit definitions ************************************************************/ -/* EBI_MCI register bit definitions (all registers) */ - - -#define IOCONFIG_EBIMCI_MGPIO9 (1 << 0) -#define IOCONFIG_EBIMCI_MGPIO6 (1 << 1) -#define IOCONFIG_EBIMCI_MLCDDB7 (1 << 2) -#define IOCONFIG_EBIMCI_MLCDDB4 (1 << 3) -#define IOCONFIG_EBIMCI_MLCDDB2 (1 << 4) -#define IOCONFIG_EBIMCI_MNANDRYBN0 (1 << 5) -#define IOCONFIG_EBIMCI_MI2STXCLK0 (1 << 6) -#define IOCONFIG_EBIMCI_MI2STXBCK0 (1 << 7) -#define IOCONFIG_EBIMCI_EBIA1CLE (1 << 8) -#define IOCONFIG_EBIMCI_EBINCASBLOUT0 (1 << 9) -#define IOCONFIG_EBIMCI_MLCDDB0 (1 << 10) -#define IOCONFIG_EBIMCI_EBIDQM0NOE (1 << 11) -#define IOCONFIG_EBIMCI_MLCDCSB (1 << 12) -#define IOCONFIG_EBIMCI_MLCDDB1 (1 << 13) -#define IOCONFIG_EBIMCI_MLCDERD (1 << 14) -#define IOCONFIG_EBIMCI_MLCDRS (1 << 15) -#define IOCONFIG_EBIMCI_MLCDRWWR (1 << 16) -#define IOCONFIG_EBIMCI_MLCDDB3 (1 << 17) -#define IOCONFIG_EBIMCI_MLCDDB5 (1 << 18) -#define IOCONFIG_EBIMCI_MLCDDB6 (1 << 19) -#define IOCONFIG_EBIMCI_MLCDDB8 (1 << 20) -#define IOCONFIG_EBIMCI_MLCDDB9 (1 << 21) -#define IOCONFIG_EBIMCI_MLCDDB10 (1 << 22) -#define IOCONFIG_EBIMCI_MLCDDB11 (1 << 23) -#define IOCONFIG_EBIMCI_MLCDDB12 (1 << 24) -#define IOCONFIG_EBIMCI_MLCDDB13 (1 << 25) -#define IOCONFIG_EBIMCI_MLCDDB14 (1 << 26) -#define IOCONFIG_EBIMCI_MLCDDB15 (1 << 27) -#define IOCONFIG_EBIMCI_MGPIO5 (1 << 28) -#define IOCONFIG_EBIMCI_MGPIO7 (1 << 29) -#define IOCONFIG_EBIMCI_MGPIO8 (1 << 30) -#define IOCONFIG_EBIMCI_MGPIO10 (1 << 31) - -/* EBI_I2STX_0 register bit definitions (all registers) */ - -#define IOCONFIG_EBII2STX0_MNANDRYBN1 (1 << 0) -#define IOCONFIG_EBII2STX0_MNANDRYBN2 (1 << 1) -#define IOCONFIG_EBII2STX0_MNANDRYBN3 (1 << 2) -#define IOCONFIG_EBII2STX0_MUARTCTSN (1 << 3) -#define IOCONFIG_EBII2STX0_MUARTRTSN (1 << 4) -#define IOCONFIG_EBII2STX0_MI2STXDATA0 (1 << 5) -#define IOCONFIG_EBII2STX0_MI2STXWS0 (1 << 6) -#define IOCONFIG_EBII2STX0_EBINRASBLOUT1 (1 << 7) -#define IOCONFIG_EBII2STX0_EBIA0ALE (1 << 8) -#define IOCONFIG_EBII2STX0_EBINWE (1 << 9) - -/* CGU register bit definitions (all registers) */ - -#define IOCONFIG_CGU_SYSCLKO (1 << 0) - -/* I2SRX_0 register bit definitions (all registers) */ - -#define IOCONFIG_I2SRX0_BCK (1 << 0) -#define IOCONFIG_I2SRX0_DATA (1 << 1) -#define IOCONFIG_I2SRX0_WS (1 << 2) - -/* I2SRX_1 register bit definitions (all registers) */ - -#define IOCONFIG_I2SRX1_DATA (1 << 0) -#define IOCONFIG_I2SRX1_BCK (1 << 1) -#define IOCONFIG_I2SRX1_WS (1 << 2) - -/* I2STX_1 register bit definitions (all registers) */ - -#define IOCONFIG_I2STX1_DATA (1 << 0) -#define IOCONFIG_I2STX1_BCK (1 << 1) -#define IOCONFIG_I2STX1_WS (1 << 2) -#define IOCONFIG_I2STX1_256FSO (1 << 3) - -/* EBI register bit definitions (all registers) */ - -#define IOCONFIG_EBI_D9 (1 << 0) -#define IOCONFIG_EBI_D10 (1 << 1) -#define IOCONFIG_EBI_D11 (1 << 2) -#define IOCONFIG_EBI_D12 (1 << 3) -#define IOCONFIG_EBI_D13 (1 << 4) -#define IOCONFIG_EBI_D14 (1 << 5) -#define IOCONFIG_EBI_D4 (1 << 6) -#define IOCONFIG_EBI_D0 (1 << 7) -#define IOCONFIG_EBI_D1 (1 << 8) -#define IOCONFIG_EBI_D2 (1 << 9) -#define IOCONFIG_EBI_D3 (1 << 10) -#define IOCONFIG_EBI_D5 (1 << 11) -#define IOCONFIG_EBI_D6 (1 << 12) -#define IOCONFIG_EBI_D7 (1 << 13) -#define IOCONFIG_EBI_D8 (1 << 14) -#define IOCONFIG_EBI_D15 (1 << 15) - -/* GPIO register bit definitions (all registers) */ - -#define IOCONFIG_GPIO_GPIO1 (1 << 0) -#define IOCONFIG_GPIO_GPIO0 (1 << 1) -#define IOCONFIG_GPIO_GPIO2 (1 << 2) -#define IOCONFIG_GPIO_GPIO3 (1 << 3) -#define IOCONFIG_GPIO_GPIO4 (1 << 4) -#define IOCONFIG_GPIO_GPIO11 (1 << 5) -#define IOCONFIG_GPIO_GPIO12 (1 << 6) -#define IOCONFIG_GPIO_GPIO13 (1 << 7) -#define IOCONFIG_GPIO_GPIO14 (1 << 8) -#define IOCONFIG_GPIO_GPIO15 (1 << 9) -#define IOCONFIG_GPIO_GPIO16 (1 << 10) -#define IOCONFIG_GPIO_GPIO17 (1 << 11) -#define IOCONFIG_GPIO_GPIO18 (1 << 12) -#define IOCONFIG_GPIO_GPIO19 (1 << 13) -#define IOCONFIG_GPIO_GPIO20 (1 << 14) - -/* I2C1 register bit definitions (all registers) */ - -#define IOCONFIG_I2C1_SDA1 (1 << 0) -#define IOCONFIG_I2C1_SCL1 (1 << 1) - -/* SPI register bit definitions (all registers) */ - -#define IOCONFIG_SPI_MISO (1 << 0) -#define IOCONFIG_SPI_MOSI (1 << 1) -#define IOCONFIG_SPI_CSIN (1 << 2) -#define IOCONFIG_SPI_SCK (1 << 3) -#define IOCONFIG_SPI_CSOUT0 (1 << 4) - -/* NAND register bit definitions (all registers) */ - -#define IOCONFIG_NAND_NCS3 (1 << 0) -#define IOCONFIG_NAND_NCS0 (1 << 1) -#define IOCONFIG_NAND_NCS1 (1 << 2) -#define IOCONFIG_NAND_NCS2 (1 << 3) - -/* PWM register bit definitions (all registers) */ - -#define IOCONFIG_PWM_DATA (1 << 0) - -/* UART register bit definitions (all registers) */ - -#define IOCONFIG_UART_RXD (1 << 0) -#define IOCONFIG_UART_TXD (1 << 1) - -/************************************************************************************************ - * Public Types - ************************************************************************************************/ - -/************************************************************************************************ - * Public Data - ************************************************************************************************/ - -/************************************************************************************************ - * Public Functions - ************************************************************************************************/ - -#endif /* __ARCH_ARM_SRC_LPC313X_IOCONFIG_H */ diff --git a/nuttx/arch/arm/src/lpc313x/lpc313x_irq.c b/nuttx/arch/arm/src/lpc313x/lpc313x_irq.c deleted file mode 100755 index 9b7f10e12..000000000 --- a/nuttx/arch/arm/src/lpc313x/lpc313x_irq.c +++ /dev/null @@ -1,218 +0,0 @@ -/**************************************************************************** - * arch/arm/src/lpc313x/lpc313x_irq.c - * arch/arm/src/chip/lpc313x_irq.c - * - * Copyright (C) 2009-2011 Gregory Nutt. All rights reserved. - * Author: Gregory Nutt - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name NuttX nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************/ - -/**************************************************************************** - * Included Files - ****************************************************************************/ - -#include - -#include -#include - -#include -#include -#include - -#include "arm.h" -#include "up_arch.h" -#include "os_internal.h" -#include "up_internal.h" - -#include "lpc313x_intc.h" -#include "lpc313x_cgudrvr.h" -#include "lpc313x_internal.h" - -/**************************************************************************** - * Definitions - ****************************************************************************/ - -/**************************************************************************** - * Public Data - ****************************************************************************/ - -volatile uint32_t *current_regs; - -/**************************************************************************** - * Private Data - ****************************************************************************/ - -/**************************************************************************** - * Private Functions - ****************************************************************************/ - -/**************************************************************************** - * Public Functions - ****************************************************************************/ - -/**************************************************************************** - * Name: up_irqinitialize - ****************************************************************************/ - -void up_irqinitialize(void) -{ - int irq; - - /* Enable clock to interrupt controller */ - - lpc313x_enableclock(CLKID_AHB2INTCCLK); /* AHB_TO_INTC_CLK */ - lpc313x_enableclock(CLKID_INTCCLK); /* INTC_CLK */ - - /* Set the vector base. We don't use direct vectoring, so these are set to 0. */ - - putreg32(0, LPC313X_INTC_VECTOR0); - putreg32(0, LPC313X_INTC_VECTOR1); - - /* Set the priority treshold to 0, i.e. don't mask any interrupt on the - * basis of priority level, for both targets (IRQ/FIQ) - */ - - putreg32(0, LPC313X_INTC_PRIORITYMASK0); /* Proc interrupt request 0: IRQ */ - putreg32(0, LPC313X_INTC_PRIORITYMASK1); /* Proc interrupt request 1: FIQ */ - - /* Disable all interrupts. Start from index 1 since 0 is unused.*/ - - for (irq = 0; irq < NR_IRQS; irq++) - { - /* Initialize as high-active, disable the interrupt, set target to IRQ, - * Set priority level to 1 (= lowest) for all the interrupt lines - */ - - uint32_t address = LPC313X_INTC_REQUEST(irq+1); - putreg32(INTC_REQUEST_WEACTLOW|INTC_REQUEST_WEENABLE|INTC_REQUEST_TARGET_IRQ| - INTC_REQUEST_PRIOLEVEL(1)|INTC_REQUEST_WEPRIO, address); - - } - - /* currents_regs is non-NULL only while processing an interrupt */ - - current_regs = NULL; - - /* And finally, enable interrupts */ - -#ifndef CONFIG_SUPPRESS_INTERRUPTS - irqrestore(SVC_MODE | PSR_F_BIT); -#endif -} - -/**************************************************************************** - * Name: up_disable_irq - * - * Description: - * Disable the IRQ specified by 'irq' - * - ****************************************************************************/ - -void up_disable_irq(int irq) -{ - /* Get the address of the request register corresponding to this - * interrupt source - */ - - uint32_t address = LPC313X_INTC_REQUEST(irq+1); - - /* Clear the ENABLE bit with WE_ENABLE=1. Configuration settings will be - * preserved because WE_TARGET is zero. - */ - - putreg32(INTC_REQUEST_WEENABLE, address); -} - -/**************************************************************************** - * Name: up_enable_irq - * - * Description: - * Enable the IRQ specified by 'irq' - * - ****************************************************************************/ - -void up_enable_irq(int irq) -{ - /* Get the address of the request register corresponding to this - * interrupt source - */ - - uint32_t address = LPC313X_INTC_REQUEST(irq+1); - - /* Set the ENABLE bit with WE_ENABLE=1. Configuration settings will be - * preserved because WE_TARGET is zero. - */ - - putreg32(INTC_REQUEST_ENABLE|INTC_REQUEST_WEENABLE, address); -} - -/**************************************************************************** - * Name: up_maskack_irq - * - * Description: - * Mask the IRQ and acknowledge it - * - ****************************************************************************/ - -void up_maskack_irq(int irq) -{ - /* Get the address of the request register corresponding to this - * interrupt source - */ - - uint32_t address = LPC313X_INTC_REQUEST(irq+1); - - /* Clear the pending interrupt (INTC_REQUEST_CLRSWINT=1) AND disable interrupts - * (ENABLE=0 && WE_ENABLE=1). Configuration settings will be preserved because - * WE_TARGET is zero. - */ - - putreg32(INTC_REQUEST_CLRSWINT|INTC_REQUEST_WEENABLE, address); -} - -/**************************************************************************** - * Name: up_prioritize_irq - * - * Description: - * Set the priority of an IRQ. - * - * Since this API is not supported on all architectures, it should be - * avoided in common implementations where possible. - * - ****************************************************************************/ - -#ifdef CONFIG_ARCH_IRQPRIO -int up_prioritize_irq(int irq, int priority) -{ -#warning "Not implemented" - return OK; -} -#endif diff --git a/nuttx/arch/arm/src/lpc313x/lpc313x_lcd.h b/nuttx/arch/arm/src/lpc313x/lpc313x_lcd.h deleted file mode 100755 index f248c32a3..000000000 --- a/nuttx/arch/arm/src/lpc313x/lpc313x_lcd.h +++ /dev/null @@ -1,161 +0,0 @@ -/************************************************************************************************ - * arch/arm/src/lpc313x/lpc313x_lcd.h - * - * Copyright (C) 2009 Gregory Nutt. All rights reserved. - * Author: Gregory Nutt - * - * 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_LPC313X_LCD_H -#define __ARCH_ARM_SRC_LPC313X_LCD_H - -/************************************************************************************************ - * Included Files - ************************************************************************************************/ - -#include -#include "lpc313x_memorymap.h" - -/************************************************************************************************ - * Pre-processor Definitions - ************************************************************************************************/ - -/* LCD register base address offset into the APB2 domain ****************************************/ - -#define LPC313X_LCD_VBASE (LPC313X_APB2_VSECTION+LPC313X_APB2_LCD_OFFSET) -#define LPC313X_LCD_PBASE (LPC313X_APB2_PSECTION+LPC313X_APB2_LCD_OFFSET) - -/* LCD register offsets (with respect to the LCD base) ******************************************/ - -#define LPC313X_LCD_STATUS_OFFSET 0x000 /* Status register */ -#define LPC313X_LCD_CONTROL_OFFSET 0x004 /* Control register */ -#define LPC313X_LCD_INTRAW_OFFSET 0x008 /* Interrupt Raw register */ -#define LPC313X_LCD_INTCLEAR_OFFSET 0x00c /* Interrupt Clear register */ -#define LPC313X_LCD_INTMASK_OFFSET 0x010 /* Interrupt Mask Register */ -#define LPC313X_LCD_READCMD_OFFSET 0x014 /* Read Command register */ -#define LPC313X_LCD_INSTBYTE_OFFSET 0x020 /* Instruction Byte Register */ -#define LPC313X_LCD_DATABYTE_OFFSET 0x030 /* Data Byte Register */ -#define LPC313X_LCD_INSTWORD_OFFSET 0x040 /* Instruction Word register */ -#define LPC313X_LCD_DATAWORD_OFFSET 0x080 /* Data Word register */ - -/* LCD register (virtual) addresses *************************************************************/ - -#define LPC313X_LCD_STATUS (LPC313X_LCD_VBASE+LPC313X_LCD_STATUS_OFFSET) -#define LPC313X_LCD_CONTROL (LPC313X_LCD_VBASE+LPC313X_LCD_CONTROL_OFFSET) -#define LPC313X_LCD_INTRAW (LPC313X_LCD_VBASE+LPC313X_LCD_INTRAW_OFFSET) -#define LPC313X_LCD_INTCLEAR (LPC313X_LCD_VBASE+LPC313X_LCD_INTCLEAR_OFFSET) -#define LPC313X_LCD_INTMASK (LPC313X_LCD_VBASE+LPC313X_LCD_INTMASK_OFFSET) -#define LPC313X_LCD_READCMD (LPC313X_LCD_VBASE+LPC313X_LCD_READCMD_OFFSET) -#define LPC313X_LCD_INSTBYTE (LPC313X_LCD_VBASE+LPC313X_LCD_INSTBYTE_OFFSET) -#define LPC313X_LCD_DATABYTE (LPC313X_LCD_VBASE+LPC313X_LCD_DATABYTE_OFFSET) -#define LPC313X_LCD_INSTWORD (LPC313X_LCD_VBASE+LPC313X_LCD_INSTWORD_OFFSET) -#define LPC313X_LCD_DATAWORD (LPC313X_LCD_VBASE+LPC313X_LCD_DATAWORD_OFFSET) - -/* LCD register bit definitions *****************************************************************/ -/* LCD interface Status Register LCD_STATUS, address 0x15000400 */ - -#define LCD_STATUS_COUNTER_SHIFT (5) /* Bits 5-9: Current value of the FIFO counter */ -#define LCD_STATUS_COUNTER_MASK (0x1f << LCD_STATUS_COUNTER_SHIFT) -#define LCD_STATUS_INTERFACEBUSY (1 << 4) /* Bit 4: LCD interface still reading value */ -#define LCD_STATUS_INTREADVALID (1 << 3) /* Bit 3: Value read from the LCD controller is valid */ -#define LCD_STATUS_INTFIFOOVERRUN (1 << 2) /* Bit 2: Value written is larger than the FIFO can hold */ -#define LCD_STATUS_INTFIFOHALFEMPTY (1 << 1) /* Bit 1: FIFO is less then half full */ -#define LCD_STATUS_INTFIFOEMPTY (1 << 0) /* Bit 0: FIFO is empty */ - -/* LCD interface Control register LCD_CONTROL, address 0x15000404 */ - -#define LCD_CONTROL_BYASYNCRELCLK (1 << 20) /* Bit 20: Bypass PCLK & LCDLCOK asynch logic */ -#define LCD_CONTROL_IF16 (1 << 19) /* Bit 19: Interface to 16 bit LCD-Controller*/ -#define LCD_CONTROL_LOOPBACK (1 << 18) /* Bit 18: LCD Interface in Loopback mode*/ -#define LCD_CONTROL_MSBFIRST (1 << 17) /* Bit 17: Send multi-byte data MSB first*/ -#define LCD_CONTROL_INVERTERD (1 << 16) /* Bit 16: Invert polarity of E_RD*/ -#define LCD_CONTROL_INVERTCS (1 << 15) /* Bit 15: Invert CS*/ -#define LCD_CONTROL_BUSYRSVALUE (1 << 14) /* Bit 14: Busy check on RS=1*/ -#define LCD_CONTROL_BUSYBITNR_SHIFT (10) /* Bits 10-13: Bit that represents busy flag*/ -#define LCD_CONTROL_BUSYBITNR_MASK (15 << LCD_CONTROL_BUSYBITNR_SHIFT) -#define LCD_CONTROL_BUSYVALUE (1 << 9) /* Bit 9: LCD controller is busy if bit=1*/ -#define LCD_CONTROL_BUSYFLAGCHECK (1 << 8) /* Bit 8: Enable the busy-flag-checking*/ -#define LCD_CONTROL_SERRDPOSS_SHIFT (9) /* Bits 6-7: 7:6 Serial sample mode*/ -#define LCD_CONTROL_SERRDPOSS_MASK (3 << LCD_CONTROL_SERRDPOSS_SHIFT) -# define LCD_CONTROL_SERRDPOSS_START (0 << LCD_CONTROL_SERRDPOSS_SHIFT) /* Sample at beginning of cycle*/ -# define LCD_CONTROL_SERRDPOSS_FOURTH (1 << LCD_CONTROL_SERRDPOSS_SHIFT) /* Sample at 0.25 * cycle*/ -# define LCD_CONTROL_SERRDPOSS_HALF (2 << LCD_CONTROL_SERRDPOSS_SHIFT) /* Sample at 0.5 * cycle*/ -# define LCD_CONTROL_SERRDPOSS_3FOURTHS (3 << LCD_CONTROL_SERRDPOSS_SHIFT) /* Sample at 0.75 * cycle*/ -#define LCD_CONTROL_SERCLKSHIFT_SHIFT (4) /* Bits 4-5: Serial clock mode*/ -#define LCD_CONTROL_SERCLKSHIFT_MASK (3 << LCD_CONTROL_SERCLKSHIFT_SHIFT) -# define LCD_CONTROL_SERCLKSHIFT_MODE0 (0 << LCD_CONTROL_SERCLKSHIFT_SHIFT) /* Clock mode 0*/ -# define LCD_CONTROL_SERCLKSHIFT_MODE1 (1 << LCD_CONTROL_SERCLKSHIFT_SHIFT) /* Clock mode 1*/ -# define LCD_CONTROL_SERCLKSHIFT_MODE2 (2 << LCD_CONTROL_SERCLKSHIFT_SHIFT) /* Clock mode 2*/ -# define LCD_CONTROL_SERCLKSHIFT_MODE3 (3 << LCD_CONTROL_SERCLKSHIFT_SHIFT) /* Clock mode 3*/ -#define LCD_CONTROL_4BIT (1 << 3) /* Bit 2: LCD interface 4 bit mode (vs 8)*/ -#define LCD_CONTROL_MI (1 << 2) /* Bit 2: LCD interface 6800 mode (vs 8080 mode)*/ -#define LCD_CONTROL_PS (1 << 1) /* Bit 1: LCD interface serial mode (vs parallel)*/ - -/* LCD interface Interrupt Raw register LCD_INTRAW, address 0x15000408 - * LCD interface Interrupt Clear register LCD_INTCLEAR, address 0x1500040c - * LCD interface Interrupt Mask register LCD_INTMASK, address 0x15000410 - */ - -#define LCD_INT_READVALID (1 << 3) /* Bit 3: Value that has been read from the LCD controller */ -#define LCD_INT_OVERRUN (1 << 2) /* Bit 2: FIFO overrun */ -#define LCD_INT_FIFOHALFEMPTY (1 << 1) /* Bit 1: FIFO is less then half full */ -#define LCD_INT_FIFO_EMPTY (1 << 0) /* Bit 0: FIFO is empty */ - -/* LCD interface Read Command register LCD_READCMD, address 0x15000414 */ - -#define LCD_READCMD_DATABYTE (1 << 0) /* Bit 0: Read in DATA byte (vs INST) */ - -/* LCD interface Instruction Byte register LCD_INSTBYTE, address 0x15000420 */ - -#define LCD_INSTBYTE_WORD_SHIFT (0) /* Bits 0-15: 16 bit mode = 15:0 Instruction */ -#define LCD_INSTBYTE_WORD_MASK (0xffff << LCD_INSTBYTE_WORD_SHIFT) -#define LCD_INSTBYTE_BYTE_SHIFT (0) /* Bits 0-7: 8 bit mode = 7:0 Instruction */ -#define LCD_INSTBYTE_BYTE_MASK (0xff << LCD_INSTBYTE_BYTE_SHIFT) - -/* LCD interface Data Byte register LCD_DATABYTE, address 0x15000430 */ - -#define LCD_DATABYTE_WORD_SHIFT (0) /* Bits 0-15: 16 bit mode = 15:0 Instruction */ -#define LCD_DATABYTE_WORD_MASK (0xffff << LCD_IDATABYTE_WORD_SHIFT) -#define LCD_DATABYTE_BYTE_SHIFT (0) /* Bits 0-7: 8 bit mode = 7:0 Instruction */ -#define LCD_DATABYTE_BYTE_MASK (0xff << LCD_IDATABYTE_BYTE_SHIFT) - -/************************************************************************************************ - * Public Types - ************************************************************************************************/ - -/************************************************************************************************ - * Public Data - ************************************************************************************************/ - -/************************************************************************************************ - * Public Functions - ************************************************************************************************/ - -#endif /* __ARCH_ARM_SRC_LPC313X_LCD_H */ diff --git a/nuttx/arch/arm/src/lpc313x/lpc313x_lowputc.c b/nuttx/arch/arm/src/lpc313x/lpc313x_lowputc.c deleted file mode 100755 index 5bfde83fc..000000000 --- a/nuttx/arch/arm/src/lpc313x/lpc313x_lowputc.c +++ /dev/null @@ -1,356 +0,0 @@ -/**************************************************************************** - * arch/arm/src/lpc313x/lpc313x_lowputc.c - * - * Copyright (C) 2009-2010 Gregory Nutt. All rights reserved. - * Author: Gregory Nutt - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name NuttX nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************/ - -/**************************************************************************** - * Included Files - ****************************************************************************/ - -#include - -#include -#include -#include - -#include - -#include "up_arch.h" -#include "up_internal.h" - -#include "lpc313x_cgudrvr.h" -#include "lpc313x_uart.h" - -/**************************************************************************** - * Definitions - ****************************************************************************/ - -/* Configuration ************************************************************/ - -/* Is the UART enabled? */ - -#ifdef CONFIG_LPC313X_UART -# define HAVE_UART 1 - -/* Is it a serial console? */ - -# ifdef CONFIG_UART_SERIAL_CONSOLE -# define HAVE_CONSOLE 1 - - /* Is initialization performed by up_earlyserialinit()? Or is UART - * initialization suppressed? - */ - -# if defined(CONFIG_USE_EARLYSERIALINIT) || defined(CONFIG_SUPPRESS_LPC313X_UART_CONFIG) -# undef NEED_LOWSETUP -# else -# define NEED_LOWSETUP 1 -# endif -# else -# undef HAVE_CONSOLE -# undef NEED_LOWSETUP -# endif - -#else -# undef HAVE_UART -# undef HAVE_CONSOLE -# undef NEED_LOWSETUP -#endif - -/**************************************************************************** - * Private Types - ****************************************************************************/ - -/**************************************************************************** - * Private Variables - ****************************************************************************/ - -/**************************************************************************** - * Private Functions - ****************************************************************************/ - -/**************************************************************************** - * Name: up_waittxready - ****************************************************************************/ - -#ifdef HAVE_CONSOLE -static inline void up_waittxready(void) -{ - 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 ((getreg32(LPC313X_UART_LSR) & UART_LSR_THRE) != 0) - { - /* The THR is empty, return */ - - break; - } - } -} -#endif - -/**************************************************************************** - * Name: up_configbaud - ****************************************************************************/ - -#ifdef NEED_LOWSETUP -static inline void up_configbaud(void) -{ - /* 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_LPC313X_UART_MULVAL - uint32_t qtrclk; - uint32_t regval; - - /* 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 = lpc313x_clkfreq(CLKID_UARTUCLK, DOMAINID_UART) >> 4; - - /* 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 + (CONFIG_UART_BAUD>>1)) / CONFIG_UART_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 <= CONFIG_UART_BAUD) - { - terr = CONFIG_UART_BAUD - actualbaud; - } - else - { - terr = actualbaud - CONFIG_UART_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; - } - } - } - } - - /* Set the Divisor Latch Access Bit (DLAB) to enable DLL/DLM access */ - - regval = getreg32(LPC313X_UART_LCR); - regval |= UART_LCR_DLAB; - putreg32(regval, LPC313X_UART_LCR); - - /* Configure the MS and LS DLAB registers */ - - putreg32(div & UART_DLL_MASK, LPC313X_UART_DLL); - putreg32((div >> 8) & UART_DLL_MASK, LPC313X_UART_DLM); - - regval &= ~UART_LCR_DLAB; - putreg32(regval, LPC313X_UART_LCR); - - /* Configure the Fractional Divider Register (FDR) */ - - putreg32((mulval << UART_FDR_MULVAL_SHIFT) | - (divaddval << UART_FDR_DIVADDVAL_SHIFT), - LPC313X_UART_FDR); -#else - /* Set the Divisor Latch Access Bit (DLAB) to enable DLL/DLM access */ - - regval = getreg32(LPC313X_UART_LCR); - regval |= UART_LCR_DLAB; - putreg32(regval, LPC313X_UART_LCR); - - /* Configure the MS and LS DLAB registers */ - - putreg32(CONFIG_LPC313X_UART_DIVISOR & UART_DLL_MASK, LPC313X_UART_DLL); - putreg32((CONFIG_LPC313X_UART_DIVISOR >> 8) & UART_DLL_MASK, LPC313X_UART_DLM); - - regval &= ~UART_LCR_DLAB; - putreg32(regval, LPC313X_UART_LCR); - - /* Configure the Fractional Divider Register (FDR) */ - - putreg32((CONFIG_LPC313X_UART_MULVAL << UART_FDR_MULVAL_SHIFT) | - (CONFIG_LPC313X_UART_DIVADDVAL << UART_FDR_DIVADDVAL_SHIFT), - LPC313X_UART_FDR); -#endif -} -#endif - -/**************************************************************************** - * Public Functions - ****************************************************************************/ -/**************************************************************************** - * Name: lpc313x_lowsetup - * - * Description: - * Called early in up_boot. Performs chip-common low level initialization. - * - ****************************************************************************/ - -void lpc313x_lowsetup(void) -{ -#ifdef NEED_LOWSETUP - uint32_t regval; - - /* Enable UART system clock */ - - lpc313x_enableclock(CLKID_UARTAPBCLK); - lpc313x_enableclock(CLKID_UARTUCLK); - - /* Clear fifos */ - - putreg32((UART_FCR_RXFIFORST|UART_FCR_TXFIFORST), LPC313X_UART_FCR); - - /* Set trigger */ - - putreg32((UART_FCR_FIFOENABLE|UART_FCR_RXTRIGLEVEL_16), LPC313X_UART_FCR); - - /* Set up the LCR */ - - regval = 0; - -#if CONFIG_UART_BITS == 5 - regval |= UART_LCR_WDLENSEL_5BITS; -#elif CONFIG_UART_BITS == 6 - regval |= UART_LCR_WDLENSEL_6BITS; -#elif CONFIG_UART_BITS == 7 - regval |= UART_LCR_WDLENSEL_7BITS; -#else - regval |= UART_LCR_WDLENSEL_8BITS; -#endif - -#if CONFIG_UART_2STOP > 0 - regval |= UART_LCR_NSTOPBITS; -#endif - -#if CONFIG_UART_PARITY == 1 - regval |= UART_LCR_PAREN; -#elif CONFIG_UART_PARITY == 2 - regval |= (UART_LCR_PAREVEN|UART_LCR_PAREN); -#endif - putreg32(regval, LPC313X_UART_LCR); - - /* Set the BAUD divisor */ - - up_configbaud(); - - /* Configure the FIFOs */ - - putreg32((UART_FCR_RXTRIGLEVEL_16|UART_FCR_TXFIFORST| - UART_FCR_RXFIFORST|UART_FCR_FIFOENABLE), - LPC313X_UART_FCR); - - /* The NuttX serial driver waits for the first THRE interrrupt before - * sending serial data... However, it appears that the lpc313x hardware - * 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. - */ - - putreg32('\0', LPC313X_UART_THR); -#endif -} - -/**************************************************************************** - * Name: up_lowputc - * - * Description: - * Provide priority, low-level access to support OS debug writes - * - ****************************************************************************/ - -void up_lowputc(char ch) -{ -#ifdef HAVE_CONSOLE - up_waittxready(); - putreg32((uint32_t)ch, LPC313X_UART_THR); -#endif -} diff --git a/nuttx/arch/arm/src/lpc313x/lpc313x_mci.h b/nuttx/arch/arm/src/lpc313x/lpc313x_mci.h deleted file mode 100755 index 881929d71..000000000 --- a/nuttx/arch/arm/src/lpc313x/lpc313x_mci.h +++ /dev/null @@ -1,270 +0,0 @@ -/************************************************************************************************ - * arch/arm/src/lpc313x/lpc313x_mci.h - * - * Copyright (C) 2009 Gregory Nutt. All rights reserved. - * Author: Gregory Nutt - * - * 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_LPC313X_MCI_H -#define __ARCH_ARM_SRC_LPC313X_MCI_H - -/************************************************************************************************ - * Included Files - ************************************************************************************************/ - -#include -#include "lpc313x_memorymap.h" - -/************************************************************************************************ - * Pre-processor Definitions - ************************************************************************************************/ - -/* MCI register base address offset into the MCI domain *****************************************/ - -#define LPC313X_MCI_VBASE (LPC313X_MCI_VSECTION) -#define LPC313X_MCI_PBASE (LPC313X_MCI_PSECTION) - -/* MCI register offsets (with respect to the MCI base) ******************************************/ - -#define LPC313X_MCI_CTRL_OFFSET 0x000 /* Control register */ -#define LPC313X_MCI_PWREN_OFFSET 0x004 /* Reserved */ -#define LPC313X_MCI_CLKDIV_OFFSET 0x008 /* Clock-divider register */ -#define LPC313X_MCI_CLKSRC_OFFSET 0x00c /* Clock-source register */ -#define LPC313X_MCI_CLKENA_OFFSET 0x010 /* Clock-enable register */ -#define LPC313X_MCI_TMOUT_OFFSET 0x014 /* Time-out register */ -#define LPC313X_MCI_CTYPE_OFFSET 0x018 /* Card-type register */ -#define LPC313X_MCI_BLKSIZ_OFFSET 0x01c /* Block-size register */ -#define LPC313X_MCI_BYTCNT_OFFSET 0x020 /* Byte-count register */ -#define LPC313X_MCI_INTMASK_OFFSET 0x024 /* Interrupt-mask register */ -#define LPC313X_MCI_CMDARG_OFFSET 0x028 /* Command-argument register */ -#define LPC313X_MCI_CMD_OFFSET 0x02c /* Command register */ -#define LPC313X_MCI_RESP0_OFFSET 0x030 /* Response-0 register */ -#define LPC313X_MCI_RESP1_OFFSET 0x034 /* Response-1register */ -#define LPC313X_MCI_RESP2_OFFSET 0x038 /* Response-2 register */ -#define LPC313X_MCI_RESP3_OFFSET 0x03c /* Response-3 register */ -#define LPC313X_MCI_MINTSTS_OFFSET 0x040 /* Masked interrupt-status register */ -#define LPC313X_MCI_RINTSTS_OFFSET 0x044 /* Raw interrupt-status register */ -#define LPC313X_MCI_STATUS_OFFSET 0x048 /* Status register */ -#define LPC313X_MCI_FIFOTH_OFFSET 0x04c /* FIFO threshold register */ -#define LPC313X_MCI_CDETECT_OFFSET 0x050 /* Card-detect register value */ -#define LPC313X_MCI_WRTPRT_OFFSET 0x054 /* Write-protect register */ - /* 0x58: Reserved */ -#define LPC313X_MCI_TCBCNT_OFFSET 0x05c /* Transferred CIU card byte count */ -#define LPC313X_MCI_TBBCNT_OFFSET 0x060 /* Transferred cpu/DMA to/from BIU-FIFO byte count */ - /* 0x064-0x0ff: Reserved */ -#define LPC313X_MCI_DATA_OFFSET 0x100 /* Data FIFO read/write (>=) */ - -/* MCI register (virtual) addresses *************************************************************/ - -#define LPC313X_MCI_CTRL (LPC313X_MCI_VBASE+LPC313X_MCI_CTRL_OFFSET) -#define LPC313X_MCI_PWREN (LPC313X_MCI_VBASE+LPC313X_MCI_PWREN_OFFSET) -#define LPC313X_MCI_CLKDIV (LPC313X_MCI_VBASE+LPC313X_MCI_CLKDIV_OFFSET) -#define LPC313X_MCI_CLKSRC (LPC313X_MCI_VBASE+LPC313X_MCI_CLKSRC_OFFSET) -#define LPC313X_MCI_CLKENA (LPC313X_MCI_VBASE+LPC313X_MCI_CLKENA_OFFSET) -#define LPC313X_MCI_TMOUT (LPC313X_MCI_VBASE+LPC313X_MCI_TMOUT_OFFSET) -#define LPC313X_MCI_CTYPE (LPC313X_MCI_VBASE+LPC313X_MCI_CTYPE_OFFSET) -#define LPC313X_MCI_BLKSIZ (LPC313X_MCI_VBASE+LPC313X_MCI_BLKSIZ_OFFSET) -#define LPC313X_MCI_BYTCNT (LPC313X_MCI_VBASE+LPC313X_MCI_BYTCNT_OFFSET) -#define LPC313X_MCI_INTMASK (LPC313X_MCI_VBASE+LPC313X_MCI_INTMASK_OFFSET) -#define LPC313X_MCI_CMDARG (LPC313X_MCI_VBASE+LPC313X_MCI_CMDARG_OFFSET) -#define LPC313X_MCI_CMD (LPC313X_MCI_VBASE+LPC313X_MCI_CMD_OFFSET) -#define LPC313X_MCI_RESP0 (LPC313X_MCI_VBASE+LPC313X_MCI_RESP0_OFFSET) -#define LPC313X_MCI_RESP1 (LPC313X_MCI_VBASE+LPC313X_MCI_RESP1_OFFSET) -#define LPC313X_MCI_RESP2 (LPC313X_MCI_VBASE+LPC313X_MCI_RESP2_OFFSET) -#define LPC313X_MCI_RESP3 (LPC313X_MCI_VBASE+LPC313X_MCI_RESP3_OFFSET) -#define LPC313X_MCI_MINTSTS (LPC313X_MCI_VBASE+LPC313X_MCI_MINTSTS_OFFSET) -#define LPC313X_MCI_RINTSTS (LPC313X_MCI_VBASE+LPC313X_MCI_RINTSTS_OFFSET) -#define LPC313X_MCI_STATUS (LPC313X_MCI_VBASE+LPC313X_MCI_STATUS_OFFSET) -#define LPC313X_MCI_FIFOTH (LPC313X_MCI_VBASE+LPC313X_MCI_FIFOTH_OFFSET) -#define LPC313X_MCI_CDETECT (LPC313X_MCI_VBASE+LPC313X_MCI_CDETECT_OFFSET) -#define LPC313X_MCI_WRTPRT (LPC313X_MCI_VBASE+LPC313X_MCI_WRTPRT_OFFSET) -#define LPC313X_MCI_TCBCNT (LPC313X_MCI_VBASE+LPC313X_MCI_TCBCNT_OFFSET) -#define LPC313X_MCI_TBBCNT (LPC313X_MCI_VBASE+LPC313X_MCI_TBBCNT_OFFSET) -#define LPC313X_MCI_DATA (LPC313X_MCI_VBASE+LPC313X_MCI_DATA_OFFSET) - -/* MCI register bit definitions *****************************************************************/ - -/* Control register CTRL, address 0x18000000 */ - -#define MCI_CTRL_CEATAINT (1 << 11) /* Bit 11: CE-ATA device interrupts enabled */ -#define MCI_CTRL_AUTOSTOP (1 << 10) /* Bit 10: Send STOP after CCSD to CE-ATA device */ -#define MCI_CTRL_SENDCCSD (1 << 9) /* Bit 9: Send CCSD to CE-ATA device */ -#define MCI_CTRL_ABORTREAD (1 << 8) /* Bit 8: Reset data state-machine (suspend sequence) */ -#define MCI_CTRL_SENDIRQRESP (1 << 7) /* Bit 7: Send auto IRQ response */ -#define MCI_CTRL_READWAIT (1 << 6) /* Bit 6: Assert read wait */ -#define MCI_CTRL_DMAENABLE (1 << 5) /* Bit 5: Enable DMA transfer mode */ -#define MCI_CTRL_INTENABLE (1 << 4) /* Bit 4: Enable interrupts */ -#define MCI_CTRL_DMARESET (1 << 2) /* Bit 2: Reset internal DMA interface control logic */ -#define MCI_CTRL_FIFORESET (1 << 1) /* Bit 1: Reset to data FIFO To reset FIFO pointers */ -#define MCI_CTRL_CNTLRRESET (1 << 0) /* Bit 0: Reset Module controller */ - -/* Clock divider register CLKDIV, address 0x18000008 */ - -#define MCI_CLKDIV_SHIFT (0) /* Bits 0-7: Clock divider */ -#define MCI_CLKDIV_MASK (255 << MCI_CLKDIV_SHIFT) - -/* Clock source register CLKSRC, address 0x1800000c */ - -#define MCI_CLKSRC_SHIFT (0) /* Bits 0-1: Must be zero */ -#define MCI_CLKSRC_MASK (3 << MCI_CLKSRC_SHIFT) - -/* Clock enable register CLKENA, address 0x18000010 */ - -#define MCI_CLKENA_LOWPOWER (1 << 16) /* Bit 16: Low-power mode */ -#define MCI_CLKENA_EMABLE (1 << 0) /* Bit 0: Clock enable */ - -/*Timeout register TMOUT, address 0x18000014 */ - -#define MCI_TMOUT_DATA_SHIFT (8) /* Bits 8-31: Data Read Timeout value */ -#define MCI_TMOUT_DATA_MASK (0x00ffffff << MCI_TMOUT_DATA_SHIFT) -#define MCI_TMOUT_RESPONSE_SHIFT (0) /* Bits 0-7: Response timeout value */ -#define MCI_TMOUT_RESPONSE_MASK (255 << MCI_TMOUT_RESPONSE_SHIFT) - -/* Card type register CTYPE, address 0x18000018 */ - -#define MCI_CTYPE_WIDTH8 (1 << 16) /* Bit 16: 8-bit mode */ -#define MCI_CTYPE_WIDTH4 (1 << 0) /* Bit 0: 4-bit mode */ - -/* Blocksize register BLKSIZ, address 0x1800001c */ - -#define MCI_BLKSIZ_SHIFT (0) /* Bits 0-15: Block size */ -#define MCI_BLKSIZ_MASK (0xffff << MCI_BLKSIZ_SHIFT) - -/* Interrupt mask register INTMASK, address 0x18000024 - * Masked interrupt status register MINTSTS, address 0x18000040 - * Raw interrupt status register RINTSTS, address 0x18000044 - */ - -#define MCI_INT_SDIO (1 << 16) /* Bit 16: Mask SDIO interrupt */ -#define MCI_INT_EBE (1 << 15) /* Bit 15: End-bit error (read)/Write no CRC */ -#define MCI_INT_ACD (1 << 14) /* Bit 14: Auto command done */ -#define MCI_INT_SBE (1 << 13) /* Bit 13: Start-bit error */ -#define MCI_INT_HLE (1 << 12) /* Bit 12: Hardware locked write error */ -#define MCI_INT_FRUN (1 << 11) /* Bit 11: FIFO underrun/overrun error */ -#define MCI_INT_HTO (1 << 10) /* Bit 10: Data starvation-by-cpu timeout */ -#define MCI_INT_DRTO (1 << 9) /* Bit 9: Data read timeout */ -#define MCI_INT_RTO (1 << 8) /* Bit 8: Response timeout */ -#define MCI_INT_DCRC (1 << 7) /* Bit 7: Data CRC error */ -#define MCI_INT_RCRC (1 << 6) /* Bit 6: Response CRC error */ -#define MCI_INT_RXDR (1 << 5) /* Bit 5: Receive FIFO data request */ -#define MCI_INT_TXDR (1 << 4) /* Bit 4: Transmit FIFO data request */ -#define MCI_INT_DTO (1 << 3) /* Bit 3: Data transfer over */ -#define MCI_INT_CD (1 << 2) /* Bit 2: Command done */ -#define MCI_INT_RE (1 << 1) /* Bit 1: Response error */ -#define MCI_INT_CD (1 << 0) /* Bit 0: Card detect */ -#define MCI_INT_ALL (0x1ffff) - -/* Command register CMD, address 0x1800002c */ - -#define MCI_CMD_STARTCMD (1 << 31) /* Bit 31: Start command */ -#define MCI_CMD_CCSEXPTD (1 << 23) /* Bit 23: Expect command completion from CE-ATA device */ -#define MCI_CMD_READCEATA (1 << 22) /* Bit 22: Performing read access on CE-ATA device */ -#define MCI_CMD_UPDCLOCK (1 << 21) /* Bit 21: Update clock register value (no command) */ -#define MCI_CMD_SENDINIT (1 << 15) /* Bit 15: Send initialization sequence before command */ -#define MCI_CMD_STOPABORT (1 << 14) /* Bit 14: Stop current data transfer */ -#define MCI_CMD_WAITPREV (1 << 13) /* Bit 13: Wait previous transfer complete before sending */ -#define MCI_CMD_AUTOSTOP (1 << 12) /* Bit 12: Send stop command at end of data transfer */ -#define MCI_CMD_XFRMODE (1 << 11) /* Bit 11: Stream data transfer command */ -#define MCI_CMD_WRITE (1 << 10) /* Bit 10: Write to card */ -#define MCI_CMD_DATAXFREXPTD (1 << 9) /* Bit 9: Data transfer expected (read/write) */ -#define MCI_CMD_RESPCRC (1 << 8) /* Bit 8: Check response CRC */ -#define MCI_CMD_LONGRESP (1 << 7) /* Bit 7: Long response expected from card */ -#define MCI_CMD_RESPONSE (1 << 6) /* Bit 6: Response expected from card */ -#define MCI_CMD_CMDINDEX_SHIFT (0) /* Bits 0-5: 5:0 Command index */ -#define MCI_CMD_CMDINDEX_MASK (63 << MCI_CMD_CMDINDEX_SHIFT) - -/* Status register STATUS, address 0x18000048 */ - -#define MCI_STATUS_DMAREQ (1 << 31) /* Bit 31: DMA request signal state */ -#define MCI_STATUS_DMAACK (1 << 30) /* Bit 30: DMA acknowledge signal state */ -#define MCI_STATUS_FIFOCOUNT_SHIFT (17) /* Bits 17-29: FIFO count */ -#define MCI_STATUS_FIFOCOUNT_MASK (0x1fff << MCI_STATUS_FIFOCOUNT_SHIFT) -#define MCI_STATUS_RESPINDEX_SHIFT (11) /* Bits 11-16: Index of previous response */ -#define MCI_STATUS_RESPINDEX_MASK (63 << MCI_STATUS_RESPINDEX_SHIFT) -#define MCI_STATUS_MCBUSY (1 << 10) /* Bit 10: Data transmit/receive state machine busy */ -#define MCI_STATUS_DATABUSY (1 << 9) /* Bit 9: Card data busy */ -#define MCI_STATUS_DAT3 (1 << 8) /* Bit 8: DAT3=1: Card present */ -#define MCI_STATUS_FSMSTATE_SHIFT (4) /* Bits 4-7: 7:4 Command FSM states */ -#define MCI_STATUS_FSMSTATE_MASK (15 << MCI_STATUS_FSMSTATE_SHIFT) -# define MCI_STATUS_FSMSTATE_IDLE (0 << MCI_STATUS_FSMSTATE_SHIFT) /* Idle */ -# define MCI_STATUS_FSMSTATE_INIT (1 << MCI_STATUS_FSMSTATE_SHIFT) /* Send init sequence */ -# define MCI_STATUS_FSMSTATE_TXSTART (2 << MCI_STATUS_FSMSTATE_SHIFT) /* Tx cmd start bit */ -# define MCI_STATUS_FSMSTATE_TXTXBIT (3 << MCI_STATUS_FSMSTATE_SHIFT) /* Tx cmd tx bit */ -# define MCI_STATUS_FSMSTATE_TXCMDARG (4 << MCI_STATUS_FSMSTATE_SHIFT) /* Tx cmd index + arg */ -# define MCI_STATUS_FSMSTATE_TXCMDCRC (5 << MCI_STATUS_FSMSTATE_SHIFT) /* Tx cmd crc7 */ -# define MCI_STATUS_FSMSTATE_TXEND (6 << MCI_STATUS_FSMSTATE_SHIFT) /* Tx cmd end bit */ -# define MCI_STATUS_FSMSTATE_RXSTART (7 << MCI_STATUS_FSMSTATE_SHIFT) /* Rx resp start bit */ -# define MCI_STATUS_FSMSTATE_RXIRQ (8 << MCI_STATUS_FSMSTATE_SHIFT) /* Rx resp IRQ response */ -# define MCI_STATUS_FSMSTATE_RXTXBIT (9 << MCI_STATUS_FSMSTATE_SHIFT) /* Rx resp tx bit */ -# define MCI_STATUS_FSMSTATE_RXCMD (10 << MCI_STATUS_FSMSTATE_SHIFT) /* Rx resp cmd idx */ -# define MCI_STATUS_FSMSTATE_RXRESP (11 << MCI_STATUS_FSMSTATE_SHIFT) /* Rx resp data */ -# define MCI_STATUS_FSMSTATE_RXRESPCRC (12 << MCI_STATUS_FSMSTATE_SHIFT) /* Rx resp crc7 */ -# define MCI_STATUS_FSMSTATE_RXEND (13 << MCI_STATUS_FSMSTATE_SHIFT) /* Rx resp end bit */ -# define MCI_STATUS_FSMSTATE_WAITNCC (14 << MCI_STATUS_FSMSTATE_SHIFT) /* Cmd path wait NCC */ -# define MCI_STATUS_FSMSTATE_WAITTURN (15 << MCI_STATUS_FSMSTATE_SHIFT) /* Wait; CMD-to-response turnaround */ -#define MCI_STATUS_FIFOFULL (1 << 3) /* Bit 3: FIFO is full */ -#define MCI_STATUS_FIFOEMPTY (1 << 2) /* Bit 2: FIFO is empty */ -#define MCI_STATUS_TXWMARK (1 << 1) /* Bit 1: FIFO reached Transmit watermark level */ -#define MCI_STATUS_RXWMARK (1 << 0) /* Bit 0: FIFO reached Receive watermark level */ - -/* FIFO threshold register FIFOTH, address 0x1800004c */ - -#define MCI_FIFOTH_DMABURST_SHIFT (28) /* Bits 28-30: Burst size for multiple transaction */ -#define MCI_FIFOTH_DMABURST_MASK (7 << MCI_FIFOTH_DMABURST_SHIFT) - define MCI_FIFOTH_DMABURST_1XFR (0 << MCI_FIFOTH_DMABURST_SHIFT) /* 1 transfer */ -# define MCI_FIFOTH_DMABURST_4XFRS (1 << MCI_FIFOTH_DMABURST_SHIFT) /* 4 transfers */ -# define MCI_FIFOTH_DMABURST_8XFRS (2 << MCI_FIFOTH_DMABURST_SHIFT) /* 8 transfers */ -#define MCI_FIFOTH_RXWMARK_SHIFT (16) /* Bits 16-27: FIFO threshold level when receiving */ -#define MCI_FIFOTH_RXWMARK_MASK (0xfff << MCI_FIFOTH_RXWMARK_SHIFT) -#define MCI_FIFOTH_TXWMARK_SHIFT (0) /* Bits 0-11: FIFO threshold level when transmitting */ -#define MCI_FIFOTH_TXWMARK_MASK (0xfff << MCI_FIFOTH_TXWMARK_SHIFT) - -/* Card detect register CDETECT, address 0x18000050 */ - -#define MCI_CDETECT_NOTPRESENT (1 << 0) - -/* Write protect register WRTPRT, address 0x18000054 */ - -#define MCI_WRTPRT_PROTECTED (1 << 0) - -/************************************************************************************************ - * Public Types - ************************************************************************************************/ - -/************************************************************************************************ - * Public Data - ************************************************************************************************/ - -/************************************************************************************************ - * Public Functions - ************************************************************************************************/ - -#endif /* __ARCH_ARM_SRC_LPC313X_MCI_H */ diff --git a/nuttx/arch/arm/src/lpc313x/lpc313x_memorymap.h b/nuttx/arch/arm/src/lpc313x/lpc313x_memorymap.h deleted file mode 100755 index 0539495f9..000000000 --- a/nuttx/arch/arm/src/lpc313x/lpc313x_memorymap.h +++ /dev/null @@ -1,414 +0,0 @@ -/************************************************************************************ - * arch/arm/src/lpc313x/chip.h - * - * Copyright (C) 2009-2010 Gregory Nutt. All rights reserved. - * Author: Gregory Nutt - * - * 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_LPC313X_MEMORYMAP_H -#define __ARCH_ARM_SRC_LPC313X_MEMORYMAP_H - -/************************************************************************************ - * Included Files - ************************************************************************************/ - -#include - -/************************************************************************************ - * Pre-processor Definitions - ************************************************************************************/ - -/* LPC313X Physical (unmapped) Memory Map */ - -#define LPC313X_FIRST_PSECTION 0x00000000 /* Beginning of the physical address space */ -#define LPC313X_SHADOWSPACE_PSECTION 0x00000000 /* 0x00000000-0x00000fff: Shadow Area 4Kb */ - /* 0x00001000-0xff027fff: Reserved */ -#define LPC313X_INTSRAM_PSECTION 0x11028000 /* Internal SRAM 0+1 192Kb */ -# define LPC313X_INTSRAM0_PADDR 0x11028000 /* 0x11028000-0x1103ffff: Internal SRAM 0 96Kb */ -# define LPC313X_INTSRAM1_PADDR 0x11040000 /* 0x11040000-0x11057fff: Internal SRAM 1 96Kb */ - /* 0x11058000-11ffffffff: Reserved */ -#define LPC313X_INTSROM0_PSECTION 0x12000000 /* 0x12000000-0x1201ffff: Internal SROM 0 128Kb */ - /* 0x12020000-0x12ffffff: Reserved */ -#define LPC313X_APB01_PSECTION 0x13000000 /* 0x13000000-0x1300bfff: APB0 32Kb APB1 16Kb */ -# define LPC313X_APB0_PADDR 0x13000000 /* 0x13000000-0x13007fff: APB0 32Kb */ -# define LPC313X_APB1_PADDR 0x13008000 /* 0x13008000-0x1300bfff: APB1 16Kb */ - /* 0x1300c000-0x14ffffff: Reserved */ -#define LPC313X_APB2_PSECTION 0x15000000 /* 0x15000000-0x15003fff: APB2 16Kb */ -#define LPC313X_APB3_PSECTION 0x16000000 /* 0x16000000-0x160003ff: APB3 1Kb */ -#define LPC313X_APB4MPMC_PSECTION 0x17000000 /* 8Kb */ -# define LPC313X_APB4_PADDR 0x17000000 /* 0x17000000-0x17000fff: APB4 4Kb */ -# define LPC313X_MPMC_PADDR 0x17008000 /* 0x17008000-0x17008fff: MPMC cfg 4Kb */ - /* 0x17009000-0x17ffffff: Reserved */ -#define LPC313X_MCI_PSECTION 0x18000000 /* 0x18000000 0x180003ff: MCI/SD/SDIO 1Kb */ - /* 0x18000900-0x18ffffff: Reserved */ -#define LPC313X_USBOTG_PSECTION 0x19000000 /* 0x19000000-0x19000fff: USB OTG 4Kb */ - /* 0x19001000-0x1fffffff: Reserved */ -#define LPC313X_EXTSRAM_PSECTION 0x20000000 /* 64-128Kb */ -# define LPC313X_EXTSRAM0_PADDR 0x20000000 /* 0x20000000-0x2001ffff: External SRAM 0 64-128Kb */ -# define LPC313X_EXTSRAM1_PADDR 0x20020000 /* 0x20020000-0x2003ffff: External SRAM 1 64-128Kb */ -#define LPC313X_EXTSDRAM0_PSECTION 0x30000000 /* 0x30000000-0x37ffffff: External SDRAM 0 128Mb */ - /* 0x40000000-0x5fffffff: Reserved */ -#define LPC313X_INTC_PSECTION 0x60000000 /* 0x60000000-0x60000fff: Interrupt controller 4Kb */ - /* 0x60001000-0x6fffffff: Reserved */ -#define LPC313X_NAND_PSECTION 0x70000000 /* 0x70000000-0x700007ff: NANDFLASH Ctrl 2Kb */ - /* 0x70000800-0xffffffff: Reserved */ -#ifdef CONFIG_LPC313X_EXTNAND /* End of the physical address space */ -# define LPC313X_LAST_PSECTION (LPC313X_NAND_PSECTION + (1 << 20)) -#else -# define LPC313X_LAST_PSECTION (LPC313X_INTC_PSECTION + (1 << 20)) -#endif - -/* APB0-4 Domain Offsets */ - -#define LPC313X_APB0_EVNTRTR_OFFSET 0x00000000 /* Event Router */ -#define LPC313X_APB0_ADC_OFFSET 0x00002000 /* ADC 10-bit */ -#define LPC313X_APB0_WDT_OFFSET 0x00002400 /* WDT */ -#define LPC313X_APB0_SYSCREG_OFFSET 0x00002800 /* SYSCREG block */ -#define LPC313X_APB0_IOCONFIG_OFFSET 0x00003000 /* IOCONFIG */ -#define LPC313X_APB0_GCU_OFFSET 0x00004000 /* GCU */ - /* 0x00005000 Reserved */ -#define LPC313X_APB0_RNG_OFFSET 0x00006000 /* RNG */ - -#define LPC313X_APB1_TIMER0_OFFSET 0x00000000 /* TIMER0 */ -#define LPC313X_APB1_TIMER1_OFFSET 0x00000400 /* TIMER1 */ -#define LPC313X_APB1_TIMER2_OFFSET 0x00000800 /* TIMER2 */ -#define LPC313X_APB1_TIMER3_OFFSET 0x00000c00 /* TIMER3 */ -#define LPC313X_APB1_PWM_OFFSET 0x00001000 /* PWM */ -#define LPC313X_APB1_I2C0_OFFSET 0x00002000 /* I2C0 */ -#define LPC313X_APB1_I2C1_OFFSET 0x00002400 /* I2C1 */ - -#define LPC313X_APB2_PCM_OFFSET 0x00000000 /* PCM */ -#define LPC313X_APB2_LCD_OFFSET 0x00000400 /* LCD */ - /* 0x00000800 Reserved */ -#define LPC313X_APB2_UART_OFFSET 0x00001000 /* UART */ -#define LPC313X_APB2_SPI_OFFSET 0x00002000 /* SPI */ - /* 0x00003000 Reserved */ - -#define LPC313X_APB3_I2SCONFIG_OFFSET 0x00000000 /* I2S System Configuration */ -#define LPC313X_APB3_I2STX0_OFFSET 0x00000080 /* I2S TX0 */ -#define LPC313X_APB3_I2STX1_OFFSET 0x00000100 /* I2S TX1 */ -#define LPC313X_APB3_I2SRX0_OFFSET 0x00000180 /* I2S RX0 */ -#define LPC313X_APB3_I2SRX1_OFFSET 0x00000200 /* I2S RX1 */ - /* 0x00000280 Reserved */ - -#define LPC313X_APB4_DMA_OFFSET 0x00000000 /* DMA */ -#define LPC313X_APB4_NAND_OFFSET 0x00000800 /* NAND FLASH Controller */ - /* 0x00001000 Reserved */ - -/* Sizes of memory regions in bytes */ - -#define LPC313X_SHADOWSPACE_SIZE (4*1024) -#define LPC313X_INTSRAM0_SIZE (96*1024) -#define LPC313X_INTSRAM1_SIZE (96*1024) -#define LPC313X_INTSROM0_SIZE (128*1024) -#define LPC313X_APB0_SIZE (32*1024) -#define LPC313X_APB1_SIZE (16*1024) -#define LPC313X_APB2_SIZE (16*1024) -#define LPC313X_APB3_SIZE (1*1024) -#define LPC313X_APB4_SIZE (4*1024) -#define LPC313X_MPMC_SIZE (4*1024) -#define LPC313X_APB4MPMC_SIZE (LPC313X_APB4_SIZE+LPC313X_MPMC_SIZE) -#define LPC313X_MCI_SIZE (1*1024) -#define LPC313X_USBOTG_SIZE (4*1024) -#define LPC313X_INTC_SIZE (4*1024) -#define LPC313X_NAND_SIZE (2*1024) - -#if defined(CONFIG_ARCH_CHIP_LPC3131) -# define LPC313X_ISRAM_SIZE (LPC313X_INTSRAM0_SIZE+LPC313X_INTSRAM1_SIZE) -#elif defined(CONFIG_ARCH_CHIP_LPC3130) -# define LPC313X_ISRAM_SIZE LPC313X_INTSRAM0_SIZE -#else -# error "Unsupported LPC313X architecture" -#endif - -/* Convert size in bytes to number of sections (in Mb). */ - -#define _NSECTIONS(b) (((b)+0x000fffff) >> 20) - -/* Sizes of sections/regions. The boot logic in lpc313x_boot.c, will select - * 1Mb level 1 MMU mappings to span the entire physical address space. - * The definitiions below specifiy the number of 1Mb entries that are - * required to span a particular address region. - */ - -#define LPC313X_SHADOWSPACE_NSECTIONS 1 /* 4Kb - <1 section */ -#define LPC313X_INTSRAM_NSECTIONS 1 /* 96 or 192Kb - <1 section */ -#define LPC313X_APB01_NSECTIONS 1 /* 32Kb - <1 section */ -#define LPC313X_INTSROM0_NSECTIONS 1 /* 128Kb - <1 section */ -#define LPC313X_APB1_NSECTIONS 1 /* 16Kb - <1 section */ -#define LPC313X_APB2_NSECTIONS 1 /* 16Kb - <1 section */ -#define LPC313X_APB3_NSECTIONS 1 /* 1Kb - <1 section */ -#define LPC313X_APB4MPMC_NSECTIONS 1 /* 8Kb - <1 section */ -#define LPC313X_MCI_NSECTIONS 1 /* 1Kb - <1 section */ -#define LPC313X_USBOTG_NSECTIONS 1 /* 4Kb - <1 section */ -#define LPC313X_EXTSRAM_NSECTIONS 1 /* 64-128Kb - <1 section */ -#define LPC313X_INTC_NSECTIONS 1 /* 4Kb - <1 section */ -#define LPC313X_NAND_NSECTIONS 1 /* 2Kb - <1 section */ - -/* External SDRAM is a special case -- the number of sections depends upon - * the size of the SDRAM installed. - */ - -#if defined(CONFIG_LPC313X_EXTSDRAM) && CONFIG_LPC313X_EXTSDRAMSIZE > 0 -# define LPC313X_EXTSDRAM0_NSECTIONS _NSECTIONS(CONFIG_LPC313X_EXTSDRAMSIZE) -#endif - -/* Section MMU Flags */ - -#define LPC313X_SHADOWSPACE_MMUFLAGS MMU_ROMFLAGS -#define LPC313X_INTSRAM_MMUFLAGS MMU_MEMFLAGS -#define LPC313X_INTSROM_MMUFLAGS MMU_MEMFLAGS -#define LPC313X_APB01_MMUFLAGS MMU_IOFLAGS -#define LPC313X_APB2_MMUFLAGS MMU_IOFLAGS -#define LPC313X_APB3_MMUFLAGS MMU_IOFLAGS -#define LPC313X_APB4MPMC_MMUFLAGS MMU_IOFLAGS -#define LPC313X_MCI_MMUFLAGS MMU_IOFLAGS -#define LPC313X_USBOTG_MMUFLAGS MMU_IOFLAGS -#define LPC313X_EXTSRAM_MMUFLAGS MMU_MEMFLAGS -#define LPC313X_EXTSDRAM_MMUFLAGS MMU_MEMFLAGS -#define LPC313X_INTC_MMUFLAGS MMU_IOFLAGS -#define LPC313X_NAND_MMUFLAGS MMU_IOFLAGS - -/* board_memorymap.h contains special mappings that are needed when a ROM - * memory map is used. It is included in this odd location becaue it depends - * on some the virtual address definitions provided above. - */ - -#include - -/* LPC313X Virtual (mapped) Memory Map. These are the mappings that will - * be created if the page table lies in RAM. If the platform has another, - * read-only, pre-initialized page table (perhaps in ROM), then the board.h - * file must provide these definitions. - */ - -#ifndef CONFIG_ARCH_ROMPGTABLE -# define LPC313X_FIRST_VSECTION 0x00000000 /* Beginning of the virtual address space */ -# define LPC313X_SHADOWSPACE_VSECTION 0x00000000 /* 0x00000000-0x00000fff: Shadow Area 4Kb */ -# define LPC313X_INTSRAM_VSECTION 0x11028000 /* Internal SRAM 96Kb-192Kb */ -# define LPC313X_INTSRAM0_VADDR 0x11028000 /* 0x11028000-0x1103ffff: Internal SRAM 0 96Kb */ -# define LPC313X_INTSRAM1_VADDR 0x11040000 /* 0x11040000-0x11057fff: Internal SRAM 1 96Kb */ -# define LPC313X_INTSROM0_VSECTION 0x12000000 /* 0x12000000-0x1201ffff: Internal SROM 0 128Kb */ -# define LPC313X_APB01_VSECTION 0x13000000 /* 0x13000000-0x1300bfff: APB0 32Kb APB0 32Kb */ -# define LPC313X_APB0_VADDR 0x13000000 /* 0x13000000-0x13007fff: APB0 32Kb */ -# define LPC313X_APB1_VADDR 0x13008000 /* 0x13008000-0x1300bfff: APB1 16Kb */ -# define LPC313X_APB2_VSECTION 0x15000000 /* 0x15000000-0x15003fff: APB2 16Kb */ -# define LPC313X_APB3_VSECTION 0x16000000 /* 0x16000000-0x160003ff: APB3 1Kb */ -# define LPC313X_APB4MPMC_VSECTION 0x17000000 /* 8Kb */ -# define LPC313X_APB4_VADDR 0x17000000 /* 0x17000000-0x17000fff: APB4 4Kb */ -# define LPC313X_MPMC_VADDR 0x17008000 /* 0x17008000-0x17008fff: MPMC cfg 4Kb */ -# define LPC313X_MCI_VSECTION 0x18000000 /* 0x18000000 0x180003ff: MCI/SD/SDIO 1Kb */ -# define LPC313X_USBOTG_VSECTION 0x19000000 /* 0x19000000-0x19000fff: USB OTG 4Kb */ -# define LPC313X_EXTSRAM_VSECTION 0x20020000 /* 64-128Kb */ -# define LPC313X_EXTSRAM0_VADDR 0x20000000 /* 0x20000000-0x2001ffff: External SRAM 0 64-128Kb */ -# define LPC313X_EXTSRAM1_VADDR 0x20020000 /* 0x20020000-0x2003ffff: External SRAM 1 64-128Kb */ -# define LPC313X_EXTSDRAM0_VSECTION 0x30000000 /* 0x30000000-0x37ffffff: External SDRAM 0 128Mb */ -# define LPC313X_INTC_VSECTION 0x60000000 /* 0x60000000-0x60000fff: Interrupt controller 4Kb */ -# define LPC313X_NAND_VSECTION 0x70000000 /* 0x70000000-0x700007ff: NANDFLASH Ctrl 2Kb */ -# -# ifdef CONFIG_LPC313X_EXTNAND /* End of the virtual address space */ -# define LPC313X_LAST_VSECTION (LPC313X_NAND_VSECTION + (1 << 20)) -# else -# define LPC313X_LAST_VSECTION (LPC313X_INTC_VSECTION + (1 << 20)) -# endif -#endif - -/* The boot logic will create a temporarily mapping based on where NuttX is - * executing in memory. In this case, NuttX could be running from NOR FLASH, - * SDRAM, external SRAM, or ISRAM. - */ - -#if defined(CONFIG_BOOT_RUNFROMFLASH) -# define NUTTX_START_VADDR LPC313X_MPMC_VADDR -#elif defined(CONFIG_BOOT_RUNFROMSDRAM) -# define NUTTX_START_VADDR LPC313X_EXTSDRAM0_VSECTION -#elif defined(CONFIG_BOOT_RUNFROMEXTSRAM) -# define NUTTX_START_VADDR LPC313X_EXTSRAM0_VADDR -#else /* CONFIG_BOOT_RUNFROMISRAM, CONFIG_PAGING */ -# define NUTTX_START_VADDR LPC313X_INTSRAM0_VADDR -#endif - -/* Determine the address of the MMU page table. We will try to place that page - * table at the beginng of ISRAM0 if the vectors are at the high address, 0xffff:0000 - * or at the end of ISRAM1 (or ISRAM0 on a LPC3130) if the vectors are at 0x0000:0000 - * - * Or... the user may specify the address of the page table explicitly be defining - * CONFIG_PGTABLE_VADDR and CONFIG_PGTABLE_PADDR in the configuration or board.h file. - */ - -#undef PGTABLE_IN_HIGHSRAM -#undef PGTABLE_IN_LOWSRAM - -#if !defined(PGTABLE_BASE_PADDR) || !defined(PGTABLE_BASE_VADDR) - - /* Sanity check.. if one is undefined, both should be undefined */ - -# if defined(PGTABLE_BASE_PADDR) || defined(PGTABLE_BASE_VADDR) -# error "Only one of PGTABLE_BASE_PADDR or PGTABLE_BASE_VADDR is defined" -# endif - - /* A sanity check, if the configuration says that the page table is read-only - * and pre-initialized (maybe ROM), then it should have also defined both of - * the page table base addresses. - */ - -# ifdef CONFIG_ARCH_ROMPGTABLE -# error "CONFIG_ARCH_ROMPGTABLE defined; PGTABLE_BASE_P/VADDR not defined" -# else - - /* If CONFIG_PAGING is selected, then parts of the 1-to-1 virtual memory - * map probably do not apply because paging logic will probably partition - * the SRAM section differently. In particular, if the page table is located - * at the end of SRAM, then the virtual page table address defined below - * will probably be in error. - * - * We work around this header file interdependency by (1) insisting that - * pg_macros.h be included AFTER this header file, then (2) allowing the - * pg_macros.h header file to redefine PGTABLE_BASE_VADDR. - */ - -# if defined(CONFIG_PAGING) && defined(__ARCH_ARM_SRC_ARM_PG_MACROS_H) -# error "pg_macros.h must be included AFTER this header file" -# endif - - - /* We must declare the page table in ISRAM0 or 1. We decide depending upon - * where the vector table was place. - */ - -# ifdef CONFIG_ARCH_LOWVECTORS /* Vectors located at 0x0000:0000 */ - - /* In this case, ISRAM0 will be shadowed at address 0x0000:0000. The page - * table must lie at the top 16Kb of ISRAM1 (or ISRAM0 if this is a LPC3130) - */ - -# if CONFIG_ARCH_CHIP_LPC3131 -# define PGTABLE_BASE_PADDR (LPC313X_INTSRAM1_PADDR+LPC313X_INTSRAM1_SIZE-PGTABLE_SIZE) -# define PGTABLE_BASE_VADDR (LPC313X_INTSRAM1_VADDR+LPC313X_INTSRAM1_SIZE-PGTABLE_SIZE) -# else -# define PGTABLE_BASE_PADDR (LPC313X_INTSRAM0_PADDR+LPC313X_INTSRAM0_SIZE-PGTABLE_SIZE) -# define PGTABLE_BASE_VADDR (LPC313X_INTSRAM0_VADDR+LPC313X_INTSRAM0_SIZE-PGTABLE_SIZE) -# endif -# define PGTABLE_IN_HIGHSRAM 1 - - /* If CONFIG_PAGING is defined, insist that pg_macros.h assign the virtual - * address of the page table. - */ - -# ifdef CONFIG_PAGING -# undef PGTABLE_BASE_VADDR -# endif -# else - - /* Otherwise, ISRAM1 (or ISRAM0 for the LPC3130) will be mapped so that - * the end of the SRAM region will provide memory for the vectors. The page - * table will then be places at the first 16Kb of ISRAM0 (which will be in - * the shadow memory region. - */ - -# define PGTABLE_BASE_PADDR LPC313X_SHADOWSPACE_PSECTION -# define PGTABLE_BASE_VADDR LPC313X_SHADOWSPACE_VSECTION -# define PGTABLE_IN_LOWSRAM 1 -# endif -# endif -#endif - -/* Page table start addresses: - * - * 16Kb of memory is reserved hold the page table for the virtual mappings. A - * portion of this table is not accessible in the virtual address space (for - * normal operation). We will reuse this memory for coarse page tables as follows: - * - * NOTE: If CONFIG_PAGING is defined, pg_macros.h will re-assign the virtual - * address of the page table. - */ - -#define PGTABLE_L2_COARSE_OFFSET ((((LPC313X_LAST_PSECTION >> 20) + 255) & ~255) << 2) -#define PGTABLE_L2_COARSE_PBASE (PGTABLE_BASE_PADDR+PGTABLE_L2_COARSE_OFFSET) -#define PGTABLE_L2_COARSE_VBASE (PGTABLE_BASE_VADDR+PGTABLE_L2_COARSE_OFFSET) - -#define PGTABLE_L2_FINE_OFFSET ((((LPC313X_LAST_PSECTION >> 20) + 1023) & ~1023) << 2) -#define PGTABLE_L2_FINE_PBASE (PGTABLE_BASE_PADDR+PGTABLE_L2_FINE_OFFSET) -#define PGTABLE_L2_FINE_VBASE (PGTABLE_BASE_VADDR+PGTABLE_L2_FINE_OFFSET) - -/* Page table end addresses: */ - -#define PGTABLE_L2_END_PADDR (PGTABLE_BASE_PADDR+PGTABLE_SIZE) -#define PGTABLE_L2_END_VADDR (PGTABLE_BASE_VADDR+PGTABLE_SIZE) - -/* Page table sizes */ - -#define PGTABLE_L2_COARSE_ALLOC (PGTABLE_L2_END_VADDR-PGTABLE_L2_COARSE_VBASE) -#define PGTABLE_COARSE_TABLE_SIZE (4*256) -#define PGTABLE_NCOARSE_TABLES (PGTABLE_L2_COARSE_ALLOC / PGTABLE_COARSE_TABLE_SIZE) - -#define PGTABLE_L2_FINE_ALLOC (PGTABLE_L2_END_VADDR-PGTABLE_L2_FINE_VBASE) -#define PGTABLE_FINE_TABLE_SIZE (4*1024) -#define PGTABLE_NFINE_TABLES (PGTABLE_L2_FINE_ALLOC / PGTABLE_FINE_TABLE_SIZE) - -/* Determine the base address of the vector table: - * - * LPC313X_VECTOR_PADDR - Unmapped, physical address of vector table in SRAM - * LPC313X_VECTOR_VSRAM - Virtual address of vector table in SRAM - * LPC313X_VECTOR_VADDR - Virtual address of vector table (0x00000000 or 0xffff0000) - */ - -#define VECTOR_TABLE_SIZE 0x00010000 -#ifdef CONFIG_ARCH_LOWVECTORS /* Vectors located at 0x0000:0000 */ -# define LPC313X_VECTOR_PADDR LPC313X_INTSRAM0_PADDR -# define LPC313X_VECTOR_VSRAM LPC313X_INTSRAM0_VADDR -# define LPC313X_VECTOR_VADDR 0x00000000 -# define LPC313X_VECTOR_VCOARSE 0x00000000 -#else /* Vectors located at 0xffff:0000 -- this probably does not work */ -# if CONFIG_ARCH_CHIP_LPC3131 -# define LPC313X_VECTOR_PADDR (LPC313X_INTSRAM1_PADDR+LPC313X_INTSRAM1_SIZE-VECTOR_TABLE_SIZE) -# define LPC313X_VECTOR_VSRAM (LPC313X_INTSRAM1_VADDR+LPC313X_INTSRAM1_SIZE-VECTOR_TABLE_SIZE) -# else -# define LPC313X_VECTOR_PADDR (LPC313X_INTSRAM0_PADDR+LPC313X_INTSRAM0_SIZE-VECTOR_TABLE_SIZE) -# define LPC313X_VECTOR_VSRAM (LPC313X_INTSRAM0_VADDR+LPC313X_INTSRAM0_SIZE-VECTOR_TABLE_SIZE) -# endif -# define LPC313X_VECTOR_VADDR 0xffff0000 -# define LPC313X_VECTOR_VCOARSE 0xfff00000 -#endif - -/************************************************************************************ - * Public Types - ************************************************************************************/ - -/************************************************************************************ - * Public Data - ************************************************************************************/ - -/************************************************************************************ - * Public Functions - ************************************************************************************/ - -#endif /* __ARCH_ARM_SRC_LPC313X_MEMORYMAP_H */ diff --git a/nuttx/arch/arm/src/lpc313x/lpc313x_mpmc.h b/nuttx/arch/arm/src/lpc313x/lpc313x_mpmc.h deleted file mode 100755 index 5e62e6b91..000000000 --- a/nuttx/arch/arm/src/lpc313x/lpc313x_mpmc.h +++ /dev/null @@ -1,340 +0,0 @@ -/************************************************************************************************ - * arch/arm/src/lpc313x/lpc313x_mpmc.h - * - * Copyright (C) 2009 Gregory Nutt. All rights reserved. - * Author: Gregory Nutt - * - * 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_LPC313X_MPMC_H -#define __ARCH_ARM_SRC_LPC313X_MPMC_H - -/************************************************************************************************ - * Included Files - ************************************************************************************************/ - -#include -#include "lpc313x_memorymap.h" - -/************************************************************************************************ - * Pre-processor Definitions - ************************************************************************************************/ - -/* MPMC register base address offset into the MPMC domain ***************************************/ - -#define LPC313X_MPMC_VBASE (LPC313X_MPMC_VADDR) -#define LPC313X_MPMC_PBASE (LPC313X_MPMC_PADDR) - -/* MPMC register offsets (with respect to the base of the MPMC domain) **************************/ - -#define LPC313X_MPMC_CONTROL_OFFSET 0x000 /* Control Register */ -#define LPC313X_MPMC_STATUS_OFFSET 0x004 /* Status Register */ -#define LPC313X_MPMC_CONFIG_OFFSET 0x008 /* Configuration register */ -#define LPC313X_MPMC_DYNCONTROL_OFFSET 0x020 /* Dynamic Memory Control Register */ -#define LPC313X_MPMC_DYNREFRESH_OFFSET 0x024 /* Dynamic Memory Refresh Timer Register */ -#define LPC313X_MPMC_DYNREADCONFIG_OFFSET 0x028 /* Dynamic Memory Read Configuration Register */ -#define LPC313X_MPMC_DYNTRP_OFFSET 0x030 /* Dynamic Memory Precharge Command Period Register */ -#define LPC313X_MPMC_DYNTRAS_OFFSET 0x034 /* Dynamic Memory Active To Precharge Command Period Register */ -#define LPC313X_MPMC_DYNTSREX_OFFSET 0x038 /* Dynamic Memory Self-refresh Exit Time Register */ -#define LPC313X_MPMC_DYNTAPR_OFFSET 0x03c /* Dynamic Memory Last Data Out To Active Time Register */ -#define LPC313X_MPMC_DYNTDAL_OFFSET 0x040 /* Dynamic Memory Data-in To Active Command Time Register */ -#define LPC313X_MPMC_DYNTWR_OFFSET 0x044 /* Dynamic Memory Write Recovery Time Register */ -#define LPC313X_MPMC_DYNTRC_OFFSET 0x048 /* Dynamic Memory Active To Active Command Period Register */ -#define LPC313X_MPMC_DYNTRFC_OFFSET 0x04c /* Dynamic Memory Auto-refresh Period Register */ -#define LPC313X_MPMC_DYNTXSR_OFFSET 0x050 /* Dynamic Memory Exit Self-refresh Register */ -#define LPC313X_MPMC_DYNTRRD_OFFSET 0x054 /* Dynamic Memory Active Bank A to Active Bank B Time Register */ -#define LPC313X_MPMC_DYNTMRD_OFFSET 0x058 /* Dynamic Memory Load Mode Register To Active Command Time Register */ -#define LPC313X_MPMC_STEXTWAIT_OFFSET 0x080 /* Static Memory Extended Wait Register */ -#define LPC313X_MPMC_DYNCONFIG0_OFFSET 0x100 /* Dynamic Memory Configuration Registers 0 */ -#define LPC313X_MPMC_DYNRASCAS0_OFFSET 0x104 /* Dynamic Memory RAS and CAS Delay Registers 0 */ - /* 0x120-0x164: reserved */ -#define LPC313X_MPMC_STCONFIG0_OFFSET 0x200 /* Static Memory Configuration Registers 0 */ -#define LPC313X_MPMC_STWAITWEN0_OFFSET 0x204 /* Static Memory Write Enable Delay Registers 0 */ -#define LPC313X_MPMC_STWAITOEN0_OFFSET 0x208 /* Static Memory Output Enable Delay Registers 0 */ -#define LPC313X_MPMC_STWAITRD0_OFFSET 0x20c /* Static Memory Read Delay Registers 0 */ -#define LPC313X_MPMC_STWAITPAGE0_OFFSET 0x210 /* Static Memory Page Mode Read Delay Registers 0 */ -#define LPC313X_MPMC_STWAITWR0_OFFSET 0x214 /* Static Memory Write Delay Registers 0 */ -#define LPC313X_MPMC_STWAITTURN0_OFFSET 0x218 /* Static Memory Turn Round Delay Registers 0 */ -#define LPC313X_MPMC_STCONFIG1_OFFSET 0x220 /* tatic Memory Configuration Registers 1 */ -#define LPC313X_MPMC_STWAITWEN1_OFFSET 0x224 /* Static Memory Write Enable Delay Registers 1 */ -#define LPC313X_MPMC_STWAITOEN1_OFFSET 0x228 /* Static Memory Output Enable Delay Registers 1 */ -#define LPC313X_MPMC_STWAITRD1_OFFSET 0x22c /* Static Memory Read Delay Registers 1 */ -#define LPC313X_MPMC_STWAITPAGE1_OFFSET 0x230 /* Static Memory Page Mode Read Delay Registers 1 */ -#define LPC313X_MPMC_STWAITWR1_OFFSET 0x234 /* Static Memory Write Delay Registers 1 */ -#define LPC313X_MPMC_STWAITTURN1_OFFSET 0x238 /* Static Memory Turn Round Delay Registers 1 */ - /* 0x240-0x278: Reserverd */ - -/* MPMC register (virtual) addresses ************************************************************/ - -#define LPC313X_MPMC_CONTROL (LPC313X_MPMC_VBASE+LPC313X_MPMC_CONTROL_OFFSET) -#define LPC313X_MPMC_STATUS (LPC313X_MPMC_VBASE+LPC313X_MPMC_STATUS_OFFSET) -#define LPC313X_MPMC_CONFIG (LPC313X_MPMC_VBASE+LPC313X_MPMC_CONFIG_OFFSET) -#define LPC313X_MPMC_DYNCONTROL (LPC313X_MPMC_VBASE+LPC313X_MPMC_DYNCONTROL_OFFSET) -#define LPC313X_MPMC_DYNREFRESH (LPC313X_MPMC_VBASE+LPC313X_MPMC_DYNREFRESH_OFFSET) -#define LPC313X_MPMC_DYNREADCONFIG (LPC313X_MPMC_VBASE+LPC313X_MPMC_DYNREADCONFIG_OFFSET) -#define LPC313X_MPMC_DYNTRP (LPC313X_MPMC_VBASE+LPC313X_MPMC_DYNTRP_OFFSET) -#define LPC313X_MPMC_DYNTRAS (LPC313X_MPMC_VBASE+LPC313X_MPMC_DYNTRAS_OFFSET) -#define LPC313X_MPMC_DYNTSREX (LPC313X_MPMC_VBASE+LPC313X_MPMC_DYNTSREX_OFFSET) -#define LPC313X_MPMC_DYNTAPR (LPC313X_MPMC_VBASE+LPC313X_MPMC_DYNTAPR_OFFSET) -#define LPC313X_MPMC_DYNTDAL (LPC313X_MPMC_VBASE+LPC313X_MPMC_DYNTDAL_OFFSET) -#define LPC313X_MPMC_DYNTWR (LPC313X_MPMC_VBASE+LPC313X_MPMC_DYNTWR_OFFSET) -#define LPC313X_MPMC_DYNTRC (LPC313X_MPMC_VBASE+LPC313X_MPMC_DYNTRC_OFFSET) -#define LPC313X_MPMC_DYNTRFC (LPC313X_MPMC_VBASE+LPC313X_MPMC_DYNTRFC_OFFSET) -#define LPC313X_MPMC_DYNTXSR (LPC313X_MPMC_VBASE+LPC313X_MPMC_DYNTXSR_OFFSET) -#define LPC313X_MPMC_DYNTRRD (LPC313X_MPMC_VBASE+LPC313X_MPMC_DYNTRRD_OFFSET) -#define LPC313X_MPMC_DYNTMRD (LPC313X_MPMC_VBASE+LPC313X_MPMC_DYNTMRD_OFFSET) -#define LPC313X_MPMC_STEXTWAIT (LPC313X_MPMC_VBASE+LPC313X_MPMC_STEXTWAIT_OFFSET) -#define LPC313X_MPMC_DYNCONFIG0 (LPC313X_MPMC_VBASE+LPC313X_MPMC_DYNCONFIG0_OFFSET) -#define LPC313X_MPMC_DYNRASCAS0 (LPC313X_MPMC_VBASE+LPC313X_MPMC_DYNRASCAS0_OFFSET) -#define LPC313X_MPMC_STCONFIG0 (LPC313X_MPMC_VBASE+LPC313X_MPMC_STCONFIG0_OFFSET) -#define LPC313X_MPMC_STWAITWEN0 (LPC313X_MPMC_VBASE+LPC313X_MPMC_STWAITWEN0_OFFSET) -#define LPC313X_MPMC_STWAITOEN0 (LPC313X_MPMC_VBASE+LPC313X_MPMC_STWAITOEN0_OFFSET) -#define LPC313X_MPMC_STWAITRD0 (LPC313X_MPMC_VBASE+LPC313X_MPMC_STWAITRD0_OFFSET) -#define LPC313X_MPMC_STWAITPAGE0 (LPC313X_MPMC_VBASE+LPC313X_MPMC_STWAITPAGE0_OFFSET) -#define LPC313X_MPMC_STWAITWR0 (LPC313X_MPMC_VBASE+LPC313X_MPMC_STWAITWR0_OFFSET) -#define LPC313X_MPMC_STWAITTURN0 (LPC313X_MPMC_VBASE+LPC313X_MPMC_STWAITTURN0_OFFSET) -#define LPC313X_MPMC_STCONFIG1 (LPC313X_MPMC_VBASE+LPC313X_MPMC_STCONFIG1_OFFSET) -#define LPC313X_MPMC_STWAITWEN1 (LPC313X_MPMC_VBASE+LPC313X_MPMC_STWAITWEN1_OFFSET) -#define LPC313X_MPMC_STWAITOEN1 (LPC313X_MPMC_VBASE+LPC313X_MPMC_STWAITOEN1_OFFSET) -#define LPC313X_MPMC_STWAITRD1 (LPC313X_MPMC_VBASE+LPC313X_MPMC_STWAITRD1_OFFSET) -#define LPC313X_MPMC_STWAITPAGE1 (LPC313X_MPMC_VBASE+LPC313X_MPMC_STWAITPAGE1_OFFSET) -#define LPC313X_MPMC_STWAITWR1 (LPC313X_MPMC_VBASE+LPC313X_MPMC_STWAITWR1_OFFSET) -#define LPC313X_MPMC_STWAITTURN1 (LPC313X_MPMC_VBASE+LPC313X_MPMC_STWAITTURN1_OFFSET) - -/* MPMC register bit definitions ****************************************************************/ -/* MPMCControl (address 0x17008000) */ - -#define MPMC_CONTROL_L (1 << 2) /* Bit 2: Indicates normal or low-power mode */ -#define MPMC_CONTROL_M (1 << 1) /* Bit 1: Indicates normal or reset memory map */ -#define MPMC_CONTROL_E (1 << 0) /* Bit 0: Indicates when the MPMC is enabled or disabled */ - -/* MPMCStatus (address 0x17008004) */ - -#define MPMC_STATUS_SA (1 << 2) /* Bit 2: Indicates the operating self-refresh mode */ -#define MPMC_STATUS_S (1 << 1) /* Bit 1: Write buffer status */ -#define MPMC_STATUS_B (1 << 0) /* Bit 0: MPMC is busy performing memory transactions */ - -/* MPMCConfig (address 0x17008008) */ - -#define MPMC_CONFIG_CLK (1 << 8) /* Bit 8: Indicates Clock ratio 1:2 */ -#define MPMC_CONFIG_N (1 << 0) /* Bit 0: Indicates big-endian mode */ - -/* MPMCDynamicControl (address 0x17008020) */ - -#define MPMC_DYNCONTROL_DP (1 << 13) /* Bit 13: Low-power SDRAM deep-sleep mode */ -#define MPMC_DYNCONTROL_I_SHIFT (8) /* Bits 7-8: I SDRAM initialization */ -#define MPMC_DYNCONTROL_I_MASK (3 << MPMC_DYNCONTROL_I_SHIFT) -# define MPMC_DYNCONTROL_INORMAL (0 << MPMC_DYNCONTROL_I_SHIFT) /* SDRAM NORMAL operation command */ -# define MPMC_DYNCONTROL_IMODE (1 << MPMC_DYNCONTROL_I_SHIFT) /* SDRAM MODE command */ -# define MPMC_DYNCONTROL_IPALL (2 << MPMC_DYNCONTROL_I_SHIFT) /* SDRAM PALL (pre charge all) */ -# define MPMC_DYNCONTROL_INOP (3 << MPMC_DYNCONTROL_I_SHIFT) /* SDRAM NOP (no operation) */ -#define MPMC_DYNCONTROL_MMC (1 << 5) /* Bit 5: Memory clock control */ -#define MPMC_DYNCONTROL_SR (1 << 2) /* Bit 2: Self-refresh request */ -#define MPMC_DYNCONTROL_CS (1 << 1) /* Bit 1: Dynamic-memory clock control */ -#define MPMC_DYNCONTROL_CE (1 << 0) /* Bit 0: Dynamic-memory clock enable */ - -/* MPMCDynamicRefresh (address 0x17008024) */ - -#define MPMC_DYNREFRESH_TIMER_SHIFT (0) /* Bits 0-10: Refresh timer */ -#define MPMC_DYNREFRESH_TIMER_MASK (0x07ff << MPMC_DYNREFRESH_TIMER_SHIFT) - -/* MPMCDynamicReadConfig (address 0x17008028) */ - -#define MPMC_DYNREADCONFIG_RD_SHIFT (0) /* Bits 0-1: Read data strategy */ -#define MPMC_DYNREADCONFIG_RD_MASK (2 << MPMC_DYNREADCONFIG_RD_SHIFT) -# define MPMC_DYNREADCONFIG_CLKOUTDEL (0 << MPMC_DYNREADCONFIG_RD_SHIFT) /* Clock out delay */ -# define MPMC_DYNREADCONFIG_CMDDEL (1 << MPMC_DYNREADCONFIG_RD_SHIFT) /* Command delay */ -# define MPMC_DYNREADCONFIG_CMDDELP1 (2 << MPMC_DYNREADCONFIG_RD_SHIFT) /* Command delay plus 1*/ -# define MPMC_DYNREADCONFIG_CMDDELP2 (3 << MPMC_DYNREADCONFIG_RD_SHIFT) /* Command delay plus 2 */ - -/* MPMCDynamictRP (address 0x17008030) */ - -#define MPMC_DYNTRP_SHIFT (0) /* Bits 0-3: Precharge command period */ -#define MPMC_DYNTRP_MASK (15 << MPMC_DYNTRP_SHIFT) - -/* MPMCDynamictRAS (address 0x17008034) */ - -#define MPMC_DYNTRAS_SHIFT (0) /* Bits 0-3: Active to pre charge command period */ -#define MPMC_DYNTRAS_MASK (15 << MPMC_DYNTRAS_SHIFT) - -/* MPMCDynamictSREX (address 0x17008038) */ - -#define MPMC_DYNTSREX_SHIFT (0) /* Bits 0-3: Self-refresh exit time */ -#define MPMC_DYNTSREX_MASK (15 << MPMC_DYNTSREX_SHIFT) - -/* MPMCDynamictAPR (address 0x1700803c) */ - -#define MPMC_DYNTAPR_SHIFT (0) /* Bits 0-3: Last-data-out to active command time */ -#define MPMC_DYNTAPR_MASK (15 << MPMC_DYNTAPR_SHIFT) - -/* MPMCDynamictDAL (address 0x17008040) */ - -#define MPMC_DYNTDAL_SHIFT (0) /* Bits 0-3: Data-in to active command */ -#define MPMC_DYNTDAL_MASK (15 << MPMC_DYNTDAL_SHIFT) - -/* MPMCDynamictWR (address 0x17008044) */ - -#define MPMC_DYNTWR_SHIFT (0) /* Bits 0-3: Write recovery time */ -#define MPMC_DYNTWR_MASK (15 << MPMC_DYNTWR_SHIFT) - -/* MPMCDynamictRC (address 0x17008048) */ - -#define MPMC_DYNTRC_SHIFT (0) /* Bits 0-4: Active to active command period */ -#define MPMC_DYNTRC_MASK (31 << MPMC_DYNTRC_SHIFT) - -/* MPMCDynamictRFC (address 0x1700804c) */ - -#define MPMC_DYNTRFC_SHIFT (0) /* Bits 0-4: Auto-refresh period and auto-refresh to active command period, */ -#define MPMC_DYNTRFC_MASK (31 << MPMC_DYNTRFC_SHIFT) - -/* MPMCDynamictXSR (address 0x1700804c) */ - -#define MPMC_DYNTXSR_SHIFT (0) /* Bits 0-4: Exit self-refresh to active command time */ -#define MPMC_DYNTXSR_MASK (31 << MPMC_DYNTXSR_SHIFT) - -/* MPMCDynamictRRD (address 0x17008050) */ - -#define MPMC_DYNTRRD_SHIFT (0) /* Bits 0-3: Active bank A to active bank B latency */ -#define MPMC_DYNTRRD_MASK (15 << MPMC_DYNTRRD_SHIFT) - -/* MPMCDynamictMRD (address 0x17008054) */ - -#define MPMC_DYNTMRD_SHIFT (0) /* Bits 0-3: Load mode register to active command time */ -#define MPMC_DYNTMRD_MASK (15 << MPMC_DYNTMRD_SHIFT) - -/* MPMCStaticExtendedWait (address 0x17008080) */ - -#define MPMC_DYNSTEXTWAIT_SHIFT (0) /* Bits 0-9: External wait time out */ -#define MPMC_DYNSTEXTWAIT_MASK (0x03ff << MPMC_DYNSTEXTWAIT_SHIFT) - -/* MPMCDynamicConfig0 (address 0x17008100) */ - -#define MPMC_DYNCONFIG0_P (1 << 20) /* Bit 20: Write protect */ -#define MPMC_DYNCONFIG0_B (1 << 19) /* Bit 19: Buffer enable */ -#define MPMC_DYNCONFIG0_AM (1 << 14) /* Bit 14: Address mapping */ -#define MPMC_DYNCONFIG0_AM_SHIFT (7) /* Bits 7-12: Address mapping */ -#define MPMC_DYNCONFIG0_AM_MASK (0x3c << MPMC_DYNCONFIG0_AM_SHIFT) - /* 16-bit external bus high-performance address mapping */ -# define MPMC_DYNCONFIG_HP16_2MX8 (0x00 << MPMC_DYNCONFIG0_AM_SHIFT) /* 16Mb (2Mx8), 2 banks, row length=11, column length=9 */ -# define MPMC_DYNCONFIG_HP16_1MX16 (0x01 << MPMC_DYNCONFIG0_AM_SHIFT) /* 16Mb (1Mx16), 2 banks, row length=11, column length=8 */ -# define MPMC_DYNCONFIG_HP16_8MX8 (0x04 << MPMC_DYNCONFIG0_AM_SHIFT) /* 64Mb (8Mx8), 4 banks, row length=12, column length=9 */ -# define MPMC_DYNCONFIG_HP16_4MX16 (0x05 << MPMC_DYNCONFIG0_AM_SHIFT) /* 64Mb (4Mx16), 4 banks, row length=12, column length=8 */ -# define MPMC_DYNCONFIG_HP16_16MX8 (0x08 << MPMC_DYNCONFIG0_AM_SHIFT) /* 128Mb (16Mx8), 4 banks, row length=12, column length=10 */ -# define MPMC_DYNCONFIG_HP16_8MX16 (0x09 << MPMC_DYNCONFIG0_AM_SHIFT) /* 128Mb (8Mx16), 4 banks, row length=12, column length=9 */ -# define MPMC_DYNCONFIG_HP16_32MX8 (0x0c << MPMC_DYNCONFIG0_AM_SHIFT) /* 256Mb (32Mx8), 4 banks, row length=13, column length=10 */ -# define MPMC_DYNCONFIG_HP16_16MX16 (0x0d << MPMC_DYNCONFIG0_AM_SHIFT) /* 256Mb (16Mx16), 4 banks, row length=13, column length=9 */ -# define MPMC_DYNCONFIG_HP16_64MX8 (0x10 << MPMC_DYNCONFIG0_AM_SHIFT) /* 512Mb (64Mx8), 4 banks, row length=13, column length=11 */ -# define MPMC_DYNCONFIG_HP16_32MX16 (0x11 << MPMC_DYNCONFIG0_AM_SHIFT) /* 512Mb (32Mx16), 4 banks, row length=13, column length=10 */ - /* 16-bit external bus low power SDRAM address mapping */ -# define MPMC_DYNCONFIG_LP16_2MX8 (0x20 << MPMC_DYNCONFIG0_AM_SHIFT) /* 6Mb (2Mx8), 2 banks, row length=11, column length=9 */ -# define MPMC_DYNCONFIG_LP16_1MX16 (0x21 << MPMC_DYNCONFIG0_AM_SHIFT) /* 16Mb (1Mx16), 2 banks, row length=11, column length=8 */ -# define MPMC_DYNCONFIG_LP16_8MX8 (0x24 << MPMC_DYNCONFIG0_AM_SHIFT) /* 64Mb (8Mx8), 4 banks, row length=12, column length=9 */ -# define MPMC_DYNCONFIG_LP16_4MX16 (0x25 << MPMC_DYNCONFIG0_AM_SHIFT) /* 64Mb (4Mx16), 4 banks, row length=12, column length=8 */ -# define MPMC_DYNCONFIG_LP16_16MX8 (0x28 << MPMC_DYNCONFIG0_AM_SHIFT) /* 128Mb (16Mx8), 4 banks, row length=12, column length=10 */ -# define MPMC_DYNCONFIG_LP16_8MX16 (0x29 << MPMC_DYNCONFIG0_AM_SHIFT) /* 128Mb (8Mx16), 4 banks, row length=12, column length=9 */ -# define MPMC_DYNCONFIG_LP16_32MX8 (0x2c << MPMC_DYNCONFIG0_AM_SHIFT) /* 256Mb (32Mx8), 4 banks, row length=13, column length=10 */ -# define MPMC_DYNCONFIG_LP16_16MX16 (0x2d << MPMC_DYNCONFIG0_AM_SHIFT) /* 256Mb (16Mx16), 4 banks, row length=13, column length=9 */ -# define MPMC_DYNCONFIG_LP16_64MX8 (0x30 << MPMC_DYNCONFIG0_AM_SHIFT) /* 512Mb (64Mx8), 4 banks, row length=13, column length=11 */ -# define MPMC_DYNCONFIG_LP16_32MX16 (0x31 << MPMC_DYNCONFIG0_AM_SHIFT) /* 512Mb (32Mx16), 4 banks, row length=13, column length=10 */ -#define MPMC_DYNCONFIG0_MD_SHIFT (3) /* Bits 3-4: Memory device */ -#define MPMC_DYNCONFIG0_MD_MASK (3 << MPMC_DYNCONFIG0_MD_SHIFT) -# define MPMC_DYNCONFIG0_MDSDRAM (0 << MPMC_DYNCONFIG0_MD_SHIFT) /* SDRAM */ -# define MPMC_DYNCONFIG0_MDLPSDRAM (1 << MPMC_DYNCONFIG0_MD_SHIFT) /* low-power SDRAM */ -# define MPMC_DYNCONFIG0_MDMSF (2 << MPMC_DYNCONFIG0_MD_SHIFT) /* Micron SyncFlash */ - -/* MPMCDynamicRasCas0 (address 0x17008104) */ - -#define MPMC_DYNRASCAS0_CAS_SHIFT (8) /* Bits 8-9: CAS latency */ -#define MPMC_DYNRASCAS0_CAS_MASK (3 << MPMC_DYNRASCAS0_CAS_SHIFT) -# define MPMC_DYNRASCAS0_CAS1CLK (1 << MPMC_DYNRASCAS0_CAS_SHIFT) /* one clock cycle */ -# define MPMC_DYNRASCAS0_CAS2CLK (2 << MPMC_DYNRASCAS0_CAS_SHIFT) /* two clock cycles */ -# define MPMC_DYNRASCAS0_CAS3CLK (3 << MPMC_DYNRASCAS0_CAS_SHIFT) /* three clock cycles */ -#define MPMC_DYNRASCAS0_RAS_SHIFT (0) /* Bits 0-1: RAS latency */ -#define MPMC_DYNRASCAS0_RAS_MASK (3 << MPMC_DYNRASCAS0_RAS_SHIFT) -# define MPMC_DYNRASCAS0_RAS1CLK (1 << MPMC_DYNRASCAS0_RAS_SHIFT) /* one clock cycle */ -# define MPMC_DYNRASCAS0_RAS2CLK (2 << MPMC_DYNRASCAS0_RAS_SHIFT) /* two clock cycles */ -# define MPMC_DYNRASCAS0_RAS3CLK (3 << MPMC_DYNRASCAS0_RAS_SHIFT) /* three clock cycles */ - -/* MPMCStaticConfig0 (address 0x17008120) and MPMCStaticConfig1 (address 0x17008220) */ - -#define MPMC_STCONFIG_WP (1 << 20) /* Bit 20: Write protect */ -#define MPMC_STCONFIG_B (1 << 19) /* Bit 19: Buffer enable */ -#define MPMC_STCONFIG_EW (1 << 8) /* Bit 8: Extended wait */ -#define MPMC_STCONFIG_BLS (1 << 7) /* Bit 7: BLS EBI_NCAS_BLOUT_0/1 EBI_nWE config */ -#define MPMC_STCONFIG_PC (1 << 6) /* Bit 6: Chip select polarity */ -#define MPMC_STCONFIG_PM (1 << 63 /* Bit 3: Page mode */ -#define MPMC_STCONFIG_MW_SHIFT (0) /* Bits 0-1: Memory width */ -#define MPMC_STCONFIG_MW_MASK (3 << MPMC_STCONFIG_MW_SHIFT) -# define MPMC_STCONFIG_MW8BIT (0 << MPMC_STCONFIG_MW_SHIFT) /* 8-bit */ -# define MPMC_STCONFIG_MW16BIT (1 << MPMC_STCONFIG_MW_SHIFT) /* 16-bit */ - -/* MPMCStaticWaitWen0 (address 0x17008204) and MPMCStaticWaitWen1 (address 0x17008224) */ - -#define MPMC_STWAITWEN_SHIFT (0) /* WAITWEN Delay from chip select to write enable */ -#define MPMC_STWAITWEN_MASK (15 << MPMC_STWAITWEN_SHIFT) - -/* MPMCStaticWaitOen (address 0x17008208) and MPMCStaticWaitOen1 (address 0x17008228) */ - -#define MPMC_STWAITOEN_SHIFT (0) /* WAITOEN Delay from chip select to output enable */ -#define MPMC_STWAITOEN_MASK (15 << MPMC_STWAITOEN_SHIFT) - -/* MPMCStaticWaitRd0 (address 0x1700820c) and MPMCStaticWaitRd1 (address 0x17008022c) */ - -#define MPMC_STWAITRD_SHIFT (0) /* Read first access wait state */ -#define MPMC_STWAITRD_MASK (31 << MPMC_STWAITRD_SHIFT) - -/* MPMCStaticWaitPage0 (address 0x17008210) and MPMCStaticWaitPage1 (address 0x17008230) */ - -#define MPMC_STWAITPAGE_SHIFT (0) /* Read after the first read wait states */ -#define MPMC_STWAITPAGE_MASK (31 << MPMC_STWAITPAGE_SHIFT) - -/* MPMCStaticWaitWr0 (address 0x17008214) and MPMCStaticWaitWr1 (address 0x17008234) */ - -#define MPMC_STWAITWR_SHIFT (0) /* Time for write accesses after the first read */ -#define MPMC_STWAITWR_MASK (31 << MPMC_STWAITWR_SHIFT) - -/* MPMCStaticWaitTurn0 (address 0x17008218) and MPMCStaticWaitTurn1 (address 0x17008238) */ - -#define MPMC_STWAITTURN_SHIFT (0) /* Bus turnaround cycles */ -#define MPMC_STWAITTURN_MASK (15 << MPMC_STWAITTURN_SHIFT) - -/************************************************************************************************ - * Public Types - ************************************************************************************************/ - -/************************************************************************************************ - * Public Data - ************************************************************************************************/ - -/************************************************************************************************ - * Public Functions - ************************************************************************************************/ - -#endif /* __ARCH_ARM_SRC_LPC313X_MPMC_H */ diff --git a/nuttx/arch/arm/src/lpc313x/lpc313x_nand.h b/nuttx/arch/arm/src/lpc313x/lpc313x_nand.h deleted file mode 100755 index 1c04055bb..000000000 --- a/nuttx/arch/arm/src/lpc313x/lpc313x_nand.h +++ /dev/null @@ -1,378 +0,0 @@ -/************************************************************************************************ - * arch/arm/src/lpc313x/lpc313x_nand.h - * - * Copyright (C) 2009 Gregory Nutt. All rights reserved. - * Author: Gregory Nutt - * - * 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_LPC313X_NAND_H -#define __ARCH_ARM_SRC_LPC313X_NAND_H - -/************************************************************************************************ - * Included Files - ************************************************************************************************/ - -#include -#include "lpc313x_memorymap.h" - -/************************************************************************************************ - * Pre-processor Definitions - ************************************************************************************************/ - -/* NAND FLASH controller register base address offset into the APB4 domain **********************/ - -#define LPC313X_NAND_VBASE (LPC313X_APB4_VADDR+LPC313X_APB4_NAND_OFFSET) -#define LPC313X_NAND_PBASE (LPC313X_APB4_PADDR+LPC313X_APB4_NAND_OFFSET) - -/* NAND FLASH controller register offsets (with respect to the base of the APB4 domain) *********/ - -#define LPC313X_NAND_IRQSTATUS1_OFFSET 0x00 /* Interrrupt status register (first 32-bits) */ -#define LPC313X_NAND_IRQMASK1_OFFSET 0x04 /* Interrupt mask register (first 32-bits) */ -#define LPC313X_NAND_IRQSTATUSRAW1_OFFSET 0x08 /* Unmasked register status (first 32-bits) */ -#define LPC313X_NAND_CONFIG_OFFSET 0x0c /* NAND Flash controller configuration register */ -#define LPC313X_NAND_IOCONFIG_OFFSET 0x10 /* Default value settings for IO signals */ -#define LPC313X_NAND_TIMING1_OFFSET 0x14 /* First NAND FLASH controller timing register */ -#define LPC313X_NAND_TIMING2_OFFSET 0x18 /* Second NAND FLASH controller timing register */ -#define LPC313X_NAND_SETCMD_OFFSET 0x20 /* NAND FLASH device command register */ -#define LPC313X_NAND_SETADDR_OFFSET 0x24 /* NAND FLASH device address register */ -#define LPC313X_NAND_WRITEDATA_OFFSET 0x28 /* NAND FLASH device write data register */ -#define LPC313X_NAND_SETCE_OFFSET 0x2c /* Set all CE and WP_n signals */ -#define LPC313X_NAND_READDATA_OFFSET 0x30 /* NAND FLASH device read data register */ -#define LPC313X_NAND_CHECKSTS_OFFSET 0x34 /* Check status of interrupts */ -#define LPC313X_NAND_CONTROLFLOW_OFFSET 0x38 /* Commands to read and write pages */ -#define LPC313X_NAND_GPIO1_OFFSET 0x40 /* Program IO pins that can be used as GPIO */ -#define LPC313X_NAND_GPIO2_OFFSET 0x44 /* Program IO pins that can be used as GPIO */ -#define LPC313X_NAND_IRQSTATUS2_OFFSET 0x48 /* Interrrupt status register (second 32-bits) */ -#define LPC313X_NAND_IRQMASK3_OFFSET 0x4c /* Interrupt mask register (second 32-bits) */ -#define LPC313X_NAND_IRQSTATUSRAW2_OFFSET 0x50 /* Unmasked register status (second 32-bits) */ -#define LPC313X_NAND_ECCERRSTATUS_OFFSET 0x78 /* ECC error status register */ - -/* NAND FLASH controller register (virtual) addresses *******************************************/ - -#define LPC313X_NAND_IRQSTATUS1 (LPC313X_NAND_VBASE+LPC313X_NAND_IRQSTATUS1_OFFSET) -#define LPC313X_NAND_IRQMASK1 (LPC313X_NAND_VBASE+LPC313X_NAND_IRQMASK1_OFFSET) -#define LPC313X_NAND_IRQSTATUSRAW1 (LPC313X_NAND_VBASE+LPC313X_NAND_IRQSTATUSRAW1_OFFSET) -#define LPC313X_NAND_CONFIG (LPC313X_NAND_VBASE+LPC313X_NAND_CONFIG_OFFSET) -#define LPC313X_NAND_IOCONFIG (LPC313X_NAND_VBASE+LPC313X_NAND_IOCONFIG_OFFSET) -#define LPC313X_NAND_TIMING1 (LPC313X_NAND_VBASE+LPC313X_NAND_TIMING1_OFFSET) -#define LPC313X_NAND_TIMING2 (LPC313X_NAND_VBASE+LPC313X_NAND_TIMING2_OFFSET) -#define LPC313X_NAND_SETCMD (LPC313X_NAND_VBASE+LPC313X_NAND_SETCMD_OFFSET) -#define LPC313X_NAND_SETADDR (LPC313X_NAND_VBASE+LPC313X_NAND_SETADDR_OFFSET) -#define LPC313X_NAND_WRITEDATA (LPC313X_NAND_VBASE+LPC313X_NAND_WRITEDATA_OFFSET) -#define LPC313X_NAND_SETCE (LPC313X_NAND_VBASE+LPC313X_NAND_SETCE_OFFSET) -#define LPC313X_NAND_READDATA (LPC313X_NAND_VBASE+LPC313X_NAND_READDATA_OFFSET) -#define LPC313X_NAND_CHECKSTS (LPC313X_NAND_VBASE+LPC313X_NAND_CHECKSTS_OFFSET) -#define LPC313X_NAND_CONTROLFLOW (LPC313X_NAND_VBASE+LPC313X_NAND_CONTROLFLOW_OFFSET) -#define LPC313X_NAND_GPIO1 (LPC313X_NAND_VBASE+LPC313X_NAND_GPIO1_OFFSET) -#define LPC313X_NAND_GPIO2 (LPC313X_NAND_VBASE+LPC313X_NAND_GPIO2_OFFSET) -#define LPC313X_NAND_IRQSTATUS2 (LPC313X_NAND_VBASE+LPC313X_NAND_IRQSTATUS2_OFFSET) -#define LPC313X_NAND_IRQMASK3 (LPC313X_NAND_VBASE+LPC313X_NAND_IRQMASK3_OFFSET) -#define LPC313X_NAND_IRQSTATUSRAW2 (LPC313X_NAND_VBASE+LPC313X_NAND_IRQSTATUSRAW2_OFFSET) -#define LPC313X_NAND_ECCERRSTATUS (LPC313X_NAND_VBASE+LPC313X_NAND_ECCERRSTATUS_OFFSET) - -/* NAND FLASH controller register bit definitions ***********************************************/ -/* NandIRQStatus1 register description (NandIRQStatus1, address 0x17000800) */ - -#define NAND_IRQSTATUS1_MNANDRYBN3 (1 << 31) /* Bit 31: mNAND_RYBN3 positive edge */ -#define NAND_IRQSTATUS1_MNANDRYBN2 (1 << 30) /* Bit 30: mNAND_RYBN2 positive edge */ -#define NAND_IRQSTATUS1_MNANDRYBN1 (1 << 29) /* Bit 29: mNAND_RYBN1 positive edge */ -#define NAND_IRQSTATUS1_MNANDRYBN0 (1 << 28) /* Bit 28: mNAND_RYBN0 positive edge */ -#define NAND_IRQSTATUS1_RAM1ERASED (1 << 27) /* Bit 27: RAM 1 erased */ -#define NAND_IRQSTATUS1_RAM0ERASED (1 << 26) /* Bit 26: RAM 0 erased */ -#define NAND_IRQSTATUS1_WRPG1DONE (1 << 25) /* Bit 25: Write page 1 done */ -#define NAND_IRQSTATUS1_WRPG0DONE (1 << 24) /* Bit 24: Write page 0 done */ -#define NAND_IRQSTATUS1_RDPG1DONE (1 << 23) /* Bit 23: Read page 1 done */ -#define NAND_IRQSTATUS1_RDPG0DONE (1 << 22) /* Bit 22: Read page 0 done */ -#define NAND_IRQSTATUS1_RAM0DECODE (1 << 21) /* Bit 21: RAM 0 decoded */ -#define NAND_IRQSTATUS1_RAM0ENCODE (1 << 20) /* Bit 20: RAM 0 encoded */ -#define NAND_IRQSTATUS1_RAM1DECODE (1 << 19) /* Bit 19: RAM 1 decoded */ -#define NAND_IRQSTATUS1_RAM1ENCODE (1 << 18) /* Bit 18: RAM 1 encoded */ -#define NAND_IRQSTATUS1_RAM00ERRS (1 << 17) /* Bit 17: RAM 0 decoded with 0 errors */ -#define NAND_IRQSTATUS1_RAM01ERR (1 << 16) /* Bit 16: RAM 0 decoded with 1 error (depends on mode) */ -#define NAND_IRQSTATUS1_RAM02ERR (1 << 15) /* Bit 15: RAM 0 decoded with 2 error */ -#define NAND_IRQSTATUS1_RAM03ERR (1 << 14) /* Bit 14: RAM 0 decoded with 3 error */ -#define NAND_IRQSTATUS1_RAM04ERR (1 << 13) /* Bit 13: RAM 0 decoded with 4 error */ -#define NAND_IRQSTATUS1_RAM05ERR (1 << 12) /* Bit 12: RAM 0 decoded with 5 error */ -#define NAND_IRQSTATUS1_RAM0UNCORR (1 << 11) /* Bit 11: RAM 0 uncorrectable */ -#define NAND_IRQSTATUS1_RAM10ERR (1 << 10) /* Bit 10: RAM 1 decoded with 0 errors */ -#define NAND_IRQSTATUS1_RAM11ERR (1 << 9) /* Bit 9: RAM 1 decoded with 1 error (depends on mode) */ -#define NAND_IRQSTATUS1_RAM12ERR (1 << 8) /* Bit 8: RAM 1 decoded with 2 error */ -#define NAND_IRQSTATUS1_RAM13ERR (1 << 7) /* Bit 7: RAM 1 decoded with 3 error */ -#define NAND_IRQSTATUS1_RAM14ERR (1 << 6) /* Bit 6: RAM 1 decoded with 4 error */ -#define NAND_IRQSTATUS1_RAM15ERR (1 << 5) /* Bit 5: RAM 1 decoded with 5 error */ -#define NAND_IRQSTATUS1_RAM1UNCORR (1 << 4) /* Bit 4: RAM 1 uncorrectable */ - -/* NandIRQMask1 register description (NandIRQMask1, address 0x17000804) */ - -#define NAND_IRQIRQMASK1_MNANDRYBN3 (1 << 31) /* Bit 31: mNAND_RYBN3 positive edge */ -#define NAND_IRQIRQMASK1_MNANDRYBN2 (1 << 30) /* Bit 30: mNAND_RYBN2 positive edge */ -#define NAND_IRQIRQMASK1_MNANDRYBN1 (1 << 29) /* Bit 29: mNAND_RYBN1 positive edge */ -#define NAND_IRQIRQMASK1_MNANDRYBN0 (1 << 28) /* Bit 28: mNAND_RYBN0 positive edge */ -#define NAND_IRQIRQMASK1_RAM1ERASED (1 << 27) /* Bit 27: RAM 1 erased */ -#define NAND_IRQIRQMASK1_RAM0ERASED (1 << 26) /* Bit 26: RAM 0 erased */ -#define NAND_IRQIRQMASK1_WRPG1DONE (1 << 25) /* Bit 25: Write page 1 done */ -#define NAND_IRQIRQMASK1_WRPG0DONE (1 << 24) /* Bit 24: Write page 0 done */ -#define NAND_IRQIRQMASK1_RDPG1DONE (1 << 23) /* Bit 23: Read page 1 done */ -#define NAND_IRQIRQMASK1_RDPG0DONE (1 << 22) /* Bit 22: Read page 0 done */ -#define NAND_IRQIRQMASK1_RAM0DECODE (1 << 21) /* Bit 21: RAM 0 decoded */ -#define NAND_IRQIRQMASK1_RAM0ENCODE (1 << 20) /* Bit 20: RAM 0 encoded */ -#define NAND_IRQIRQMASK1_RAM1DECODE (1 << 19) /* Bit 19: RAM 1 decoded */ -#define NAND_IRQIRQMASK1_RAM1ENCODE (1 << 18) /* Bit 18: RAM 1 encoded */ -#define NAND_IRQIRQMASK1_RAM00ERRS (1 << 17) /* Bit 17: RAM 0 decoded with 0 errors */ -#define NAND_IRQIRQMASK1_RAM01ERR (1 << 16) /* Bit 16: RAM 0 decoded with 1 error (depends on mode) */ -#define NAND_IRQIRQMASK1_RAM02ERR (1 << 15) /* Bit 15: RAM 0 decoded with 2 error */ -#define NAND_IRQIRQMASK1_RAM03ERR (1 << 14) /* Bit 14: RAM 0 decoded with 3 error */ -#define NAND_IRQIRQMASK1_RAM04ERR (1 << 13) /* Bit 13: RAM 0 decoded with 4 error */ -#define NAND_IRQIRQMASK1_RAM05ERR (1 << 12) /* Bit 12: RAM 0 decoded with 5 error */ -#define NAND_IRQIRQMASK1_RAM0UNCORR (1 << 11) /* Bit 11: RAM 0 uncorrectable */ -#define NAND_IRQIRQMASK1_RAM10ERR (1 << 10) /* Bit 10: RAM 1 decoded with 0 errors */ -#define NAND_IRQIRQMASK1_RAM11ERR (1 << 9) /* Bit 9: RAM 1 decoded with 1 error (depends on mode) */ -#define NAND_IRQIRQMASK1_RAM12ERR (1 << 8) /* Bit 8: RAM 1 decoded with 2 error */ -#define NAND_IRQIRQMASK1_RAM13ERR (1 << 7) /* Bit 7: RAM 1 decoded with 3 error */ -#define NAND_IRQIRQMASK1_RAM14ERR (1 << 6) /* Bit 6: RAM 1 decoded with 4 error */ -#define NAND_IRQIRQMASK1_RAM15ERR (1 << 5) /* Bit 5: RAM 1 decoded with 5 error */ -#define NAND_IRQIRQMASK1_RAM1UNCORR (1 << 4) /* Bit 4: RAM 1 uncorrectable */ - -/* NandIRQStatusRaw1 register description (NandIRQStatusRaw1, address 0x17000808) */ - -#define NAND_IRQSTATUSRAW1_MNANDRYBN3 (1 << 31) /* Bit 31: mNAND_RYBN3 positive edge */ -#define NAND_IRQSTATUSRAW1_MNANDRYBN2 (1 << 30) /* Bit 30: mNAND_RYBN2 positive edge */ -#define NAND_IRQSTATUSRAW1_MNANDRYBN1 (1 << 29) /* Bit 29: mNAND_RYBN1 positive edge */ -#define NAND_IRQSTATUSRAW1_MNANDRYBN0 (1 << 28) /* Bit 28: mNAND_RYBN0 positive edge */ -#define NAND_IRQSTATUSRAW1_RAM1ERASED (1 << 27) /* Bit 27: RAM 1 erased */ -#define NAND_IRQSTATUSRAW1_RAM0ERASED (1 << 26) /* Bit 26: RAM 0 erased */ -#define NAND_IRQSTATUSRAW1_WRPG1DONE (1 << 25) /* Bit 25: Write page 1 done */ -#define NAND_IRQSTATUSRAW1_WRPG0DONE (1 << 24) /* Bit 24: Write page 0 done */ -#define NAND_IRQSTATUSRAW1_RDPG1DONE (1 << 23) /* Bit 23: Read page 1 done */ -#define NAND_IRQSTATUSRAW1_RDPG0DONE (1 << 22) /* Bit 22: Read page 0 done */ -#define NAND_IRQSTATUSRAW1_RAM0DECODE (1 << 21) /* Bit 21: RAM 0 decoded */ -#define NAND_IRQSTATUSRAW1_RAM0ENCODE (1 << 20) /* Bit 20: RAM 0 encoded */ -#define NAND_IRQSTATUSRAW1_RAM1DECODE (1 << 19) /* Bit 19: RAM 1 decoded */ -#define NAND_IRQSTATUSRAW1_RAM1ENCODE (1 << 18) /* Bit 18: RAM 1 encoded */ -#define NAND_IRQSTATUSRAW1_RAM00ERRS (1 << 17) /* Bit 17: RAM 0 decoded with 0 errors */ -#define NAND_IRQSTATUSRAW1_RAM01ERR (1 << 16) /* Bit 16: RAM 0 decoded with 1 error (depends on mode) */ -#define NAND_IRQSTATUSRAW1_RAM02ERR (1 << 15) /* Bit 15: RAM 0 decoded with 2 error */ -#define NAND_IRQSTATUSRAW1_RAM03ERR (1 << 14) /* Bit 14: RAM 0 decoded with 3 error */ -#define NAND_IRQSTATUSRAW1_RAM04ERR (1 << 13) /* Bit 13: RAM 0 decoded with 4 error */ -#define NAND_IRQSTATUSRAW1_RAM05ERR (1 << 12) /* Bit 12: RAM 0 decoded with 5 error */ -#define NAND_IRQSTATUSRAW1_RAM0UNCORR (1 << 11) /* Bit 11: RAM 0 uncorrectable */ -#define NAND_IRQSTATUSRAW1_RAM10ERR (1 << 10) /* Bit 10: RAM 1 decoded with 0 errors */ -#define NAND_IRQSTATUSRAW1_RAM11ERR (1 << 9) /* Bit 9: RAM 1 decoded with 1 error (depends on mode) */ -#define NAND_IRQSTATUSRAW1_RAM12ERR (1 << 8) /* Bit 8: RAM 1 decoded with 2 error */ -#define NAND_IRQSTATUSRAW1_RAM13ERR (1 << 7) /* Bit 7: RAM 1 decoded with 3 error */ -#define NAND_IRQSTATUSRAW1_RAM14ERR (1 << 6) /* Bit 6: RAM 1 decoded with 4 error */ -#define NAND_IRQSTATUSRAW1_RAM15ERR (1 << 5) /* Bit 5: RAM 1 decoded with 5 error */ -#define NAND_IRQSTATUSRAW1_RAM1UNCORR (1 << 4) /* Bit 4: RAM 1 uncorrectable */ - -/* NandConfig register description (NandConfig, address 0x1700080c) */ - -#define NAND_CONFIG_ECC_MODE (1 << 12) /* Bit 12: ECC mode 0 */ -#define NAND_CONFIG_TL_SHIFT (10) /* Bits 10-11: Transfer limit */ -#define NAND_CONFIG_TL_MASK (3 < - * - * 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_LPC313X_PCM_H -#define __ARCH_ARM_SRC_LPC313X_PCM_H - -/************************************************************************************************ - * Included Files - ************************************************************************************************/ - -#include -#include "lpc313x_memorymap.h" - -/************************************************************************************************ - * Pre-processor Definitions - ************************************************************************************************/ - -/* PCM register base address offset into the APB2 domain ****************************************/ - -#define LPC313X_PCM_VBASE (LPC313X_APB2_VSECTION+LPC313X_APB2_PCM_OFFSET) -#define LPC313X_PCM_PBASE (LPC313X_APB2_PSECTION+LPC313X_APB2_PCM_OFFSET) - -/* PCM register offsets (with respect to the PCM base) ******************************************/ - -#define LPC313X_PCM_GLOBAL_OFFSET 0x000 /* Global register */ -#define LPC313X_PCM_CNTL0_OFFSET 0x004 /* Control register 0 */ -#define LPC313X_PCM_CNTL1_OFFSET 0x008 /* Control register 1 */ -#define LPC313X_PCM_HPOUT_OFFSET(n) (0x00c+((n)<<2)) /* Transmit data register n */ -#define LPC313X_PCM_HPOUT0_OFFSET 0x00c /* Transmit data register 0 */ -#define LPC313X_PCM_HPOUT1_OFFSET 0x010 /* Transmit data register 1 */ -#define LPC313X_PCM_HPOUT2_OFFSET 0x014 /* Transmit data register 2 */ -#define LPC313X_PCM_HPOUT3_OFFSET 0x018 /* Transmit data register 3 */ -#define LPC313X_PCM_HPOUT4_OFFSET 0x01c /* Transmit data register 4 */ -#define LPC313X_PCM_HPOUT5_OFFSET 0x020 /* Transmit data register 5 */ -#define LPC313X_PCM_HPIN_OFFSET(n) (0x024+((n)<<2)) /* Transmit data register n */ -#define LPC313X_PCM_HPIN0_OFFSET 0x024 /* Receive data register 0 */ -#define LPC313X_PCM_HPIN1_OFFSET 0x028 /* Receive data register 1 */ -#define LPC313X_PCM_HPIN2_OFFSET 0x02c /* Receive data register 2 */ -#define LPC313X_PCM_HPIN3_OFFSET 0x030 /* Receive data register 3 */ -#define LPC313X_PCM_HPIN4_OFFSET 0x034 /* Receive data register 4 */ -#define LPC313X_PCM_HPIN5_OFFSET 0x038 /* Receive data register 5 */ -#define LPC313X_PCM_CNTL2_OFFSET 0x03c /* Control register 2 */ - -/* PCM register (virtual) addresses *************************************************************/ - -#define LPC313X_PCM_GLOBAL (LPC313X_PCM_VBASE+LPC313X_PCM_GLOBAL_OFFSET) -#define LPC313X_PCM_CNTL0 (LPC313X_PCM_VBASE+LPC313X_PCM_CNTL0_OFFSET) -#define LPC313X_PCM_CNTL1 (LPC313X_PCM_VBASE+LPC313X_PCM_CNTL1_OFFSET) -#define LPC313X_PCM_HPOUT(n) (LPC313X_PCM_VBASE+LPC313X_PCM_HPOUT_OFFSET(n)) -#define LPC313X_PCM_HPOUT0 (LPC313X_PCM_VBASE+LPC313X_PCM_HPOUT0_OFFSET) -#define LPC313X_PCM_HPOUT1 (LPC313X_PCM_VBASE+LPC313X_PCM_HPOUT1_OFFSET) -#define LPC313X_PCM_HPOUT2 (LPC313X_PCM_VBASE+LPC313X_PCM_HPOUT2_OFFSET) -#define LPC313X_PCM_HPOUT3 (LPC313X_PCM_VBASE+LPC313X_PCM_HPOUT3_OFFSET) -#define LPC313X_PCM_HPOUT4 (LPC313X_PCM_VBASE+LPC313X_PCM_HPOUT4_OFFSET) -#define LPC313X_PCM_HPOUT5 (LPC313X_PCM_VBASE+LPC313X_PCM_HPOUT5_OFFSET) -#define LPC313X_PCM_HPIN(n) (LPC313X_PCM_VBASE+LPC313X_PCM_HPIN_OFFSET(n)) -#define LPC313X_PCM_HPIN0 (LPC313X_PCM_VBASE+LPC313X_PCM_HPIN0_OFFSET) -#define LPC313X_PCM_HPIN1 (LPC313X_PCM_VBASE+LPC313X_PCM_HPIN1_OFFSET) -#define LPC313X_PCM_HPIN2 (LPC313X_PCM_VBASE+LPC313X_PCM_HPIN2_OFFSET) -#define LPC313X_PCM_HPIN3 (LPC313X_PCM_VBASE+LPC313X_PCM_HPIN3_OFFSET) -#define LPC313X_PCM_HPIN4 (LPC313X_PCM_VBASE+LPC313X_PCM_HPIN4_OFFSET) -#define LPC313X_PCM_HPIN5 (LPC313X_PCM_VBASE+LPC313X_PCM_HPIN5_OFFSET) -#define LPC313X_PCM_CNTL2 (LPC313X_PCM_VBASE+LPC313X_PCM_CNTL2_OFFSET) - -/* PCM register bit definitions *****************************************************************/ - -/* GLOBAL register, address 0x15000000 */ - -#define PCM_GLOBAL_DMARXENABLE (1 << 4) /* Bit 4: Enable DMA RX */ -#define PCM_GLOBAL_DMATXENABLE (1 << 3) /* Bit 3: Enable DMA TX */ -#define PCM_GLOBAL_NORMAL (1 << 2) /* Bit 2: Slave/Normal mode */ -#define PCM_GLOBAL_ONOFF (1 << 0) /* Bit 0: IPINT active */ - -/* CNTL0 register, address 0x15000004 */ - -#define PCM_CNTL0_MASTER (1 << 14) /* Bit 14: PCM/IOM master mode */ -#define PCM_CNTL0_LOOPBACK (1 << 11) /* Bit 11: Internal loop-back mode */ -#define PCM_CNTL0_TYPOD (1 << 10) /* Bit 10: Type of PCM_FCS and PCM_DCLK output port */ -#define PCM_CNTL0_TYPDOIP_SHIFT (8) /* Bits 8-9: Type of PCM/IOM data output ports */ -#define PCM_CNTL0_TYPDOIP_MASK (3 << PCM_CNTL0_TYPDOIP_SHIFT) -#define PCM_CNTL0_TYPFRMSYNC_SHIFT (6) /* Bits 6-7: Shape of frame synchronization signal */ -#define PCM_CNTL0_TYPFRMSYNC_MASK (3 << PCM_CNTL0_TYPFRMSYNC_SHIFT) -#define PCM_CNTL0_CLKSPD_SHIFT (3) /* Bits 3-5: Port frequency selection */ -#define PCM_CNTL0_CLKSPD_MASK (7 << PCM_CNTL0_CLKSPD_SHIFT) - -/* CNTL1 register, address 0x15000008 */ - -#define PCM_CNTL1_ENSLT_SHIFT (0) /* Bits 0-11: Enable PCM/IOM Slots, one per slot */ -#define PCM_CNTL1_ENSLT_MASK (0xfff << PCM_CNTL1_ENSLT_SHIFT) -# define PCM_CNTL1_ENSLT0 (0x001 << PCM_CNTL1_ENSLT_SHIFT) -# define PCM_CNTL1_ENSLT1 (0x002 << PCM_CNTL1_ENSLT_SHIFT) -# define PCM_CNTL1_ENSLT2 (0x004 << PCM_CNTL1_ENSLT_SHIFT) -# define PCM_CNTL1_ENSLT3 (0x008 << PCM_CNTL1_ENSLT_SHIFT) -# define PCM_CNTL1_ENSLT4 (0x010 << PCM_CNTL1_ENSLT_SHIFT) -# define PCM_CNTL1_ENSLT5 (0x020 << PCM_CNTL1_ENSLT_SHIFT) -# define PCM_CNTL1_ENSLT6 (0x040 << PCM_CNTL1_ENSLT_SHIFT) -# define PCM_CNTL1_ENSLT7 (0x080 << PCM_CNTL1_ENSLT_SHIFT) -# define PCM_CNTL1_ENSLT8 (0x100 << PCM_CNTL1_ENSLT_SHIFT) -# define PCM_CNTL1_ENSLT9 (0x200 << PCM_CNTL1_ENSLT_SHIFT) -# define PCM_CNTL1_ENSLT10 (0x400 << PCM_CNTL1_ENSLT_SHIFT) -# define PCM_CNTL1_ENSLT11 (0x800 << PCM_CNTL1_ENSLT_SHIFT) - -/* HPOUTn registers, addresses 0x1500000c to 0x15000020 (two per slot) */ - -#define PCM_HPOUT_SHIFT (0) /* Bits 0-15: Transmit data register */ -#define PCM_HPOUT_MASK (0xffff << PCM_HPOUT_SHIFT) - -/* HPINn registers, addresses 0x15000024 to 0x15000038 (two per slot) */ - -#define PCM_HPIN_SHIFT (0) /* Bits 0-15: Receive data register */ -#define PCM_HPIN_MASK (0xffff << PCM_HPIN_SHIFT) - -/* CNTL2 register, address 0x1500003c */ - -#define PCM_CNTL2_SLOTDIRINV_SHIFT (0) /* Bits 0-11: PCM A/B port configuration, one per slot */ -#define PCM_CNTL2_SLOTDIRINV_MASK (0xfff << PCM_CNTL2_SLOTDIRINV_SHIFT) -# define PCM_CNTL2_SLOTDIRINV0 (0x001 << PCM_CNTL2_SLOTDIRINV_SHIFT) -# define PCM_CNTL2_SLOTDIRINV1 (0x002 << PCM_CNTL2_SLOTDIRINV_SHIFT) -# define PCM_CNTL2_SLOTDIRINV2 (0x004 << PCM_CNTL2_SLOTDIRINV_SHIFT) -# define PCM_CNTL2_SLOTDIRINV3 (0x008 << PCM_CNTL2_SLOTDIRINV_SHIFT) -# define PCM_CNTL2_SLOTDIRINV4 (0x010 << PCM_CNTL2_SLOTDIRINV_SHIFT) -# define PCM_CNTL2_SLOTDIRINV5 (0x020 << PCM_CNTL2_SLOTDIRINV_SHIFT) -# define PCM_CNTL2_SLOTDIRINV6 (0x040 << PCM_CNTL2_SLOTDIRINV_SHIFT) -# define PCM_CNTL2_SLOTDIRINV7 (0x080 << PCM_CNTL2_SLOTDIRINV_SHIFT) -# define PCM_CNTL2_SLOTDIRINV8 (0x100 << PCM_CNTL2_SLOTDIRINV_SHIFT) -# define PCM_CNTL2_SLOTDIRINV9 (0x200 << PCM_CNTL2_SLOTDIRINV_SHIFT) -# define PCM_CNTL2_SLOTDIRINV10 (0x400 << PCM_CNTL2_SLOTDIRINV_SHIFT) -# define PCM_CNTL2_SLOTDIRINV11 (0x800 << PCM_CNTL2_SLOTDIRINV_SHIFT) - -/************************************************************************************************ - * Public Types - ************************************************************************************************/ - -/************************************************************************************************ - * Public Data - ************************************************************************************************/ - -/************************************************************************************************ - * Public Functions - ************************************************************************************************/ - -#endif /* __ARCH_ARM_SRC_LPC313X_PCM_H */ diff --git a/nuttx/arch/arm/src/lpc313x/lpc313x_pllconfig.c b/nuttx/arch/arm/src/lpc313x/lpc313x_pllconfig.c deleted file mode 100755 index 8ecbc4a5c..000000000 --- a/nuttx/arch/arm/src/lpc313x/lpc313x_pllconfig.c +++ /dev/null @@ -1,267 +0,0 @@ -/**************************************************************************** - * arch/arm/src/lpc313x/lpc313x_pllconfig.c - * - * Copyright (C) 2009-2010 Gregory Nutt. All rights reserved. - * Author: Gregory Nutt - * - * References: - * - NXP UM10314 LPC3130/31 User manual Rev. 1.01 — 9 September 2009 - * - NXP lpc313x.cdl.drivers.zip example driver code - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name NuttX nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************/ - -/**************************************************************************** - * Included Files - ****************************************************************************/ - -#include - -#include - -#include - -#include "lpc313x_cgudrvr.h" - -/**************************************************************************** - * Pre-processor Definitions - ****************************************************************************/ - -/**************************************************************************** - * Private Types - ****************************************************************************/ - -/**************************************************************************** - * Private Data - ****************************************************************************/ - -/**************************************************************************** - * Private Functions - ****************************************************************************/ - -/**************************************************************************** - * Name: lpc313x_switchdomains - * - * Description: - * Temporarily switch the referemce clock of all domains whose selected - * input is the PLL-to-be configured . - * - ****************************************************************************/ - -static inline uint16_t -lpc313x_switchdomains(const struct lpc313x_pllconfig_s * const cfg) -{ - uint32_t hppll = (cfg->hppll ? CGU_SSR_HPPLL1 : CGU_SSR_HPPLL0); - uint32_t address; - uint32_t regval; - uint16_t dmnset = 0; - int i; - - /* Check each domain */ - - for (i = 0; i < CGU_NDOMAINS; i++) - { - /* Get the switch status registers (SSR) for this frequency input domain */ - - address = LPC313X_CGU_SSR(i); - regval = getreg32(address); - - /* Check if the current frequency selection is the PLL-to-be-configured */ - - if ((regval & CGU_SSR_FS_MASK) == hppll) - { - /* Yes.. switch reference clock in to FFAST */ - - lpc313x_selectfreqin((enum lpc313x_domainid_e)i, CGU_FS_FFAST); - - /* Add the domain to the set to be restored after the PLL is configured */ - - dmnset |= (1 << i); - } - } - - return dmnset; -} - -/**************************************************************************** - * Name: lpc313x_restoredomains - * - * Description: - * Restore the PLL reference clock to the domains that were temporarily - switched to FFAST by lpc313x_switchdomains. - * - ****************************************************************************/ - -static inline void -lpc313x_restoredomains(const struct lpc313x_pllconfig_s * const cfg, - uint16_t dmnset) -{ - uint32_t finsel = (cfg->hppll ? CGU_FS_HPPLL1 : CGU_FS_HPPLL0); - int i; - - /* Check each domain */ - - for (i = 0; i < CGU_NDOMAINS; i++) - { - /* Was this one switched? */ - - if ((dmnset & (1 << i)) != 0) - { - /* Switch input reference clock to newly configured HPLL */ - - lpc313x_selectfreqin((enum lpc313x_domainid_e)i, finsel); - } - } -} - -/**************************************************************************** - * Public Functions - ****************************************************************************/ - -/**************************************************************************** - * Name: lpc313x_pllconfig - * - * Description: - * Configure the PLL according to the provided selections. - * - ****************************************************************************/ - -void lpc313x_pllconfig(const struct lpc313x_pllconfig_s * const cfg) -{ - uint32_t pllbase; - uint16_t dmnset = 0; - - /* Switch domains connected to HPLL to FFAST */ - - dmnset = lpc313x_switchdomains(cfg); - - /* Get the PLL register base address */ - - pllbase = LPC313x_CGU_HPPLL(cfg->hppll); - - /* Disable clock, disable skew enable, power down pll, (dis/en)able post - * divider, (dis/en)able pre-divider, disable free running mode, disable bandsel, - * enable up limmiter, disable bypass - */ - - putreg32(CGU_HPMODE_PD, pllbase + LPC313X_CGU_HPMODE_OFFSET); - - /* Select PLL input frequency source */ - - putreg32(cfg->finsel, pllbase + LPC313X_CGU_HPFINSEL_OFFSET); - - /* Set M divider */ - - putreg32(cfg->mdec & CGU_HPMDEC_MASK, pllbase + LPC313X_CGU_HPMDEC_OFFSET); - - /* Set N divider */ - - putreg32(cfg->ndec & CGU_HPNDEC_MASK, pllbase + LPC313X_CGU_HPNDEC_OFFSET); - - /* Set P divider */ - - putreg32(cfg->pdec & CGU_HPPDEC_MASK, pllbase + LPC313X_CGU_HPPDEC_OFFSET); - - /* Set bandwidth */ - - putreg32(cfg->selr, pllbase + LPC313X_CGU_HPSELR_OFFSET); - putreg32(cfg->seli, pllbase + LPC313X_CGU_HPSELI_OFFSET); - putreg32(cfg->selp, pllbase + LPC313X_CGU_HPSELP_OFFSET); - - /* Power up pll */ - - putreg32((cfg->mode & ~CGU_HPMODE_PD) | CGU_HPMODE_CLKEN, pllbase + LPC313X_CGU_HPMODE_OFFSET); - - /* Save the estimated freq in driver data for future clk calcs */ - - g_boardfreqin[CGU_FREQIN_HPPLL0 + cfg->hppll] = cfg->freq; - - /* Wait for PLL to lock */ - - while ((getreg32(pllbase + LPC313X_CGU_HPSTATUS_OFFSET) & CGU_HPSTATUS_LOCK) == 0); - - /* Switch the domains that were temporarily switched to FFAST back to the HPPLL */ - - lpc313x_restoredomains(cfg, dmnset); -} - -/************************************************************************ - * Name: lpc313x_hp0pllconfig - * - * Description: - * Configure the HP0 PLL according to the board.h selections. - * - ************************************************************************/ - -void lpc313x_hp0pllconfig(void) -{ - struct lpc313x_pllconfig_s cfg = - { - .hppll = CGU_HP0PLL, - .finsel = BOARD_HPLL0_FINSEL, - .ndec = BOARD_HPLL0_NDEC, - .mdec = BOARD_HPLL0_MDEC, - .pdec = BOARD_HPLL0_PDEC, - .selr = BOARD_HPLL0_SELR, - .seli = BOARD_HPLL0_SELI, - .selp = BOARD_HPLL0_SELP, - .mode = BOARD_HPLL0_MODE, - .freq = BOARD_HPLL0_FREQ - }; - - lpc313x_pllconfig(&cfg); -} - -/************************************************************************ - * Name: lpc313x_hp1pllconfig - * - * Description: - * Configure the HP1 PLL according to the board.h selections. - * - ************************************************************************/ - -void lpc313x_hp1pllconfig(void) -{ - struct lpc313x_pllconfig_s cfg = - { - .hppll = CGU_HP1PLL, - .finsel = BOARD_HPLL1_FINSEL, - .ndec = BOARD_HPLL1_NDEC, - .mdec = BOARD_HPLL1_MDEC, - .pdec = BOARD_HPLL1_PDEC, - .selr = BOARD_HPLL1_SELR, - .seli = BOARD_HPLL1_SELI, - .selp = BOARD_HPLL1_SELP, - .mode = BOARD_HPLL1_MODE, - .freq = BOARD_HPLL1_FREQ - }; - - lpc313x_pllconfig(&cfg); -} - diff --git a/nuttx/arch/arm/src/lpc313x/lpc313x_pwm.h b/nuttx/arch/arm/src/lpc313x/lpc313x_pwm.h deleted file mode 100755 index 45065546c..000000000 --- a/nuttx/arch/arm/src/lpc313x/lpc313x_pwm.h +++ /dev/null @@ -1,97 +0,0 @@ -/************************************************************************************************ - * arch/arm/src/lpc313x/lpc313x_pwm.h - * - * Copyright (C) 2009-2010 Gregory Nutt. All rights reserved. - * Author: Gregory Nutt - * - * 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_LPC313X_PWM_H -#define __ARCH_ARM_SRC_LPC313X_PWM_H - -/************************************************************************************************ - * Included Files - ************************************************************************************************/ - -#include -#include "lpc313x_memorymap.h" - -/************************************************************************************************ - * Pre-processor Definitions - ************************************************************************************************/ - -/* PWM register base address offset into the APB1 domain ****************************************/ - -#define LPC313X_PWM_VBASE (LPC313X_APB1_VADDR+LPC313X_APB1_PWM_OFFSET) -#define LPC313X_PWM_PBASE (LPC313X_APB1_PADDR+LPC313X_APB1_PWM_OFFSET) - -/* PWM register offsets (with respect to the PWM base) ******************************************/ - -#define LPC313X_PWM_TMR_OFFSET 0x000 /* Timer Register */ -#define LPC313X_PWM_CNTL_OFFSET 0x004 /* Control Register */ - -/* PWM register (virtual) addresses *************************************************************/ - -#define LPC313X_PWM_TMR (LPC313X_PWM_VBASE+LPC313X_PWM_TMR_OFFSET) -#define LPC313X_PWM_CNTL (LPC313X_PWM_VBASE+LPC313X_PWM_CNTL_OFFSET) - -/* PWM register bit definitions *****************************************************************/ - -/* Timer register TMR, address 0x13009000 */ - -#define PWM_TMR_SHIFT (0) /* Bits 0-11: Timer used for PWM and PDM */ -#define PWM_TMR_MASK (0xfff << PWM_TMR_SHIFT) - -/* Control register CNTL, address 0x13009004 */ - -#define PWM_CNTL_PDM (1 << 7) /* Bit 7: PDM Select PDM mode */ -#define PWM_CNTL_LOOP (1 << 6) /* Bit 6: Output inverted with top 4 TMR bits */ -#define PWM_CNTL_HI (1 << 4) /* Bit 4: PWM output forced high */ - /* Bits 2-3: Reserved */ -#define PWM_CNTL_CLK_SHIFT (0) /* Bits 0-1: Configure PWM_CLK for output pulses */ -#define PWM_CNTL_CLK_MASK (3 << PWM_CNTL_CLK_SHIFT) -# define PWM_CNTL_CLKDIV1 (0 << PWM_CNTL_CLK_SHIFT) /* PWM_CLK */ -# define PWM_CNTL_CLKDIV2 (1 << PWM_CNTL_CLK_SHIFT) /* PWM_CLK/2 */ -# define PWM_CNTL_CLKDIV4 (2 << PWM_CNTL_CLK_SHIFT) /* PWM_CLK/4 */ -# define PWM_CNTL_CLKDIV8 (3 << PWM_CNTL_CLK_SHIFT) /* PWM_CLK/8 */ - -/************************************************************************************************ - * Public Types - ************************************************************************************************/ - -/************************************************************************************************ - * Public Data - ************************************************************************************************/ - -/************************************************************************************************ - * Public Functions - ************************************************************************************************/ - -#endif /* __ARCH_ARM_SRC_LPC313X_PWM_H */ diff --git a/nuttx/arch/arm/src/lpc313x/lpc313x_resetclks.c b/nuttx/arch/arm/src/lpc313x/lpc313x_resetclks.c deleted file mode 100755 index 257430f8e..000000000 --- a/nuttx/arch/arm/src/lpc313x/lpc313x_resetclks.c +++ /dev/null @@ -1,151 +0,0 @@ -/**************************************************************************** - * arch/arm/src/lpc313x/lpc313x_resetclks.c - * - * Copyright (C) 2009 Gregory Nutt. All rights reserved. - * Author: Gregory Nutt - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name NuttX nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************/ - -/**************************************************************************** - * Included Files - ****************************************************************************/ - -#include - -#include - -#include - -#include "lpc313x_cgudrvr.h" - -/**************************************************************************** - * Pre-processor Definitions - ****************************************************************************/ - -/**************************************************************************** - * Private Data - ****************************************************************************/ - -/**************************************************************************** - * Public Data - ****************************************************************************/ - -/**************************************************************************** - * Private Functions - ****************************************************************************/ - -/**************************************************************************** - * Public Functions - ****************************************************************************/ - -/**************************************************************************** - * Name: lpc313x_resetclks - * - * Description: - * Put all clocks into a known, initial state - * - ****************************************************************************/ - -void lpc313x_resetclks(void) -{ - uint32_t regaddr; - uint32_t regval; - int bcrndx; - int esrndx; - int i; - - /* Switch all domain reference clocks to FFAST */ - - for (i = 0; i < CGU_NDOMAINS; i++) - { - /* Switch reference clock in to FFAST */ - - lpc313x_selectfreqin((enum lpc313x_domainid_e)i, CGU_FS_FFAST); - - /* Check if the domain has a BCR */ - - bcrndx = lpc313x_bcrndx((enum lpc313x_domainid_e)i); - if (bcrndx != BCRNDX_INVALID) - { - /* Yes.. disable all BCRs */ - - putreg32(0, LPC313X_CGU_BCR(bcrndx)); - } - } - - /* Disable all clocks except those that are necessary */ - - for (i = CLKID_FIRST; i <= CLKID_LAST; i++) - { - /* Check if this clock has an ESR register */ - - esrndx = lpc313x_esrndx((enum lpc313x_clockid_e)i); - if (esrndx != ESRNDX_INVALID) - { - /* Yes.. Clear the clocks ESR to deselect fractional divider */ - - putreg32(0, LPC313X_CGU_ESR(esrndx)); - } - - /* Enable external enabling for all possible clocks to conserve power */ - - lpc313x_enableexten((enum lpc313x_clockid_e)i); - - /* Set enable-out's for only the following clocks */ - - regaddr = LPC313X_CGU_PCR(i); - regval = getreg32(regaddr); - if (i == (int)CLKID_ARM926BUSIFCLK || i == (int)CLKID_MPMCCFGCLK) - { - regval |= CGU_PCR_ENOUTEN; - } - else - { - regval &= ~CGU_PCR_ENOUTEN; - } - putreg32(regval, regaddr); - - /* Set/clear the RUN bit in the PCR regiser of all clocks, depending - * upon if the clock is needed by the board logic or not - */ - - (void)lpc313x_defclk((enum lpc313x_clockid_e)i); - } - - /* Disable all fractional dividers */ - - for (i = 0; i < CGU_NFRACDIV; i++) - { - regaddr = LPC313X_CGU_FDC(i); - regval = getreg32(regaddr); - regval &= ~CGU_FDC_RUN; - putreg32(regval, regaddr); - } -} diff --git a/nuttx/arch/arm/src/lpc313x/lpc313x_rng.h b/nuttx/arch/arm/src/lpc313x/lpc313x_rng.h deleted file mode 100755 index dc65d71c2..000000000 --- a/nuttx/arch/arm/src/lpc313x/lpc313x_rng.h +++ /dev/null @@ -1,85 +0,0 @@ -/************************************************************************************************ - * arch/arm/src/lpc313x/lpc313x_rng.h - * - * Copyright (C) 2009-2010 Gregory Nutt. All rights reserved. - * Author: Gregory Nutt - * - * 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_LPC313X_RNG_H -#define __ARCH_ARM_SRC_LPC313X_RNG_H - -/************************************************************************************************ - * Included Files - ************************************************************************************************/ - -#include -#include "lpc313x_memorymap.h" - -/************************************************************************************************ - * Pre-processor Definitions - ************************************************************************************************/ - -/* RNG register base address offset into the APB0 domain ****************************************/ - -#define LPC313X_RNG_VBASE (LPC313X_APB0_VADDR+LPC313X_APB0_RNG_OFFSET) -#define LPC313X_RNG_PBASE (LPC313X_APB0_PADDR+LPC313X_APB0_RNG_OFFSET) - -/* RNG register offsets (with respect to the RNG base) ******************************************/ - -#define LPC313X_RNG_RAND_OFFSET 0x0000 /* Random number */ -#define LPC313X_RNG_PWRDWN_OFFSET 0x0ff4 /* Power-down mode */ - -/* RNG register (virtual) addresses *************************************************************/ - -#define LPC313X_RNG_RAND (LPC313X_RNG_VBASE+LPC313X_RNG_RAND_OFFSET) -#define LPC313X_RNG_PWRDWN (LPC313X_RNG_VBASE+LPC313X_RNG_PWRDWN_OFFSET) - -/* RNG register bit definitions *****************************************************************/ - -/* POWERDOWN, address 0x13006ff4 */ - -#define RNG_PWRDWN_PWRDWN (1 << 2) /* Block all accesses to standard registers */ -#define RNG_PWRDWN_FORCERST (1 << 1) /* With SOFTRST forces immediate RNG reset */ -#define RNG_PWRDWN_SOFTRST (1 << 0) /* Software RNG reset (delayed) */ - -/************************************************************************************************ - * Public Types - ************************************************************************************************/ - -/************************************************************************************************ - * Public Data - ************************************************************************************************/ - -/************************************************************************************************ - * Public Functions - ************************************************************************************************/ - -#endif /* __ARCH_ARM_SRC_LPC313X_RNG_H */ diff --git a/nuttx/arch/arm/src/lpc313x/lpc313x_serial.c b/nuttx/arch/arm/src/lpc313x/lpc313x_serial.c deleted file mode 100755 index 51dcb8e9a..000000000 --- a/nuttx/arch/arm/src/lpc313x/lpc313x_serial.c +++ /dev/null @@ -1,856 +0,0 @@ -/**************************************************************************** - * arch/arm/src/lpc313x/lpc313x_serial.c - * - * Copyright (C) 2009 Gregory Nutt. All rights reserved. - * Author: Gregory Nutt - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name NuttX nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************/ - -/**************************************************************************** - * Included Files - ****************************************************************************/ - -#include - -#include -#include -#include -#include -#include -#include -#include -#include - -#include -#include -#include -#include - -#include "up_arch.h" -#include "os_internal.h" -#include "up_internal.h" - -#include "lpc313x_cgudrvr.h" -#include "lpc313x_uart.h" - -#ifdef CONFIG_USE_SERIALDRIVER - -/**************************************************************************** - * Definitions - ****************************************************************************/ - -/**************************************************************************** - * Private Types - ****************************************************************************/ - -struct up_dev_s -{ - uint8_t ier; /* Saved IER value */ -}; - -/**************************************************************************** - * Private Function Prototypes - ****************************************************************************/ - -static inline void up_disableuartint(struct up_dev_s *priv, uint8_t *ier); -static inline void up_restoreuartint(struct up_dev_s *priv, uint8_t ier); -static inline void up_enablebreaks(void); -static inline void up_disablebreaks(void); -static inline void up_configbaud(void); - -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_rxbuffer[CONFIG_UART_RXBUFSIZE]; -static char g_txbuffer[CONFIG_UART_TXBUFSIZE]; - -/* This describes the state of the single LPC313X uart port. */ - -static struct up_dev_s g_uartpriv; -static uart_dev_t g_uartport = -{ - .recv = - { - .size = CONFIG_UART_RXBUFSIZE, - .buffer = g_rxbuffer, - }, - .xmit = - { - .size = CONFIG_UART_TXBUFSIZE, - .buffer = g_txbuffer, - }, - .ops = &g_uart_ops, - .priv = &g_uartpriv, -}; - -/**************************************************************************** - * Private Functions - ****************************************************************************/ - -/**************************************************************************** - * Name: up_disableuartint - ****************************************************************************/ - -static inline void up_disableuartint(struct up_dev_s *priv, uint8_t *ier) -{ - if (ier) - { - *ier = priv->ier & UART_IER_ALLINTS; - } - - priv->ier &= ~UART_IER_ALLINTS; - putreg32((uint32_t)priv->ier, LPC313X_UART_IER); -} - -/**************************************************************************** - * Name: up_restoreuartint - ****************************************************************************/ - -static inline void up_restoreuartint(struct up_dev_s *priv, uint8_t ier) -{ - priv->ier |= ier & UART_IER_ALLINTS; - putreg32((uint32_t)priv->ier, LPC313X_UART_IER); -} - -/**************************************************************************** - * Name: up_enablebreaks - ****************************************************************************/ - -static inline void up_enablebreaks(void) -{ - uint32_t lcr = getreg32(LPC313X_UART_LCR); - lcr |= UART_LCR_BRKCTRL; - putreg32(lcr, LPC313X_UART_LCR); -} - -/**************************************************************************** - * Name: up_disablebreaks - ****************************************************************************/ - -static inline void up_disablebreaks(void) -{ - uint32_t lcr = getreg32(LPC313X_UART_LCR); - lcr &= ~UART_LCR_BRKCTRL; - putreg32(lcr, LPC313X_UART_LCR); -} - -/**************************************************************************** - * Name: up_configbaud - ****************************************************************************/ - -static inline void up_configbaud(void) -{ - /* 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_LPC313X_UART_MULVAL - uint32_t qtrclk; - uint32_t regval; - - /* 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 = lpc313x_clkfreq(CLKID_UARTUCLK, DOMAINID_UART) >> 4; - - /* 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 + (CONFIG_UART_BAUD>>1)) / CONFIG_UART_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 <= CONFIG_UART_BAUD) - { - terr = CONFIG_UART_BAUD - actualbaud; - } - else - { - terr = actualbaud - CONFIG_UART_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; - } - } - } - } - - /* Set the Divisor Latch Access Bit (DLAB) to enable DLL/DLM access */ - - regval = getreg32(LPC313X_UART_LCR); - regval |= UART_LCR_DLAB; - putreg32(regval, LPC313X_UART_LCR); - - /* Configure the MS and LS DLAB registers */ - - putreg32(div & UART_DLL_MASK, LPC313X_UART_DLL); - putreg32((div >> 8) & UART_DLL_MASK, LPC313X_UART_DLM); - - regval &= ~UART_LCR_DLAB; - putreg32(regval, LPC313X_UART_LCR); - - /* Configure the Fractional Divider Register (FDR) */ - - putreg32((mulval << UART_FDR_MULVAL_SHIFT) | - (divaddval << UART_FDR_DIVADDVAL_SHIFT), - LPC313X_UART_FDR); -#else - /* Set the Divisor Latch Access Bit (DLAB) to enable DLL/DLM access */ - - regval = getreg32(LPC313X_UART_LCR); - regval |= UART_LCR_DLAB; - putreg32(regval, LPC313X_UART_LCR); - - /* Configure the MS and LS DLAB registers */ - - putreg32(CONFIG_LPC313X_UART_DIVISOR & UART_DLL_MASK, LPC313X_UART_DLL); - putreg32((CONFIG_LPC313X_UART_DIVISOR >> 8) & UART_DLL_MASK, LPC313X_UART_DLM); - - regval &= ~UART_LCR_DLAB; - putreg32(regval, LPC313X_UART_LCR); - - /* Configure the Fractional Divider Register (FDR) */ - - putreg32((CONFIG_LPC313X_UART_MULVAL << UART_FDR_MULVAL_SHIFT) | - (CONFIG_LPC313X_UART_DIVADDVAL << UART_FDR_DIVADDVAL_SHIFT), - LPC313X_UART_FDR); -#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_LPC313X_UART_CONFIG - struct up_dev_s *priv = (struct up_dev_s*)dev->priv; - uint32_t regval; - - /* Clear fifos */ - - putreg32((UART_FCR_RXFIFORST|UART_FCR_TXFIFORST), LPC313X_UART_FCR); - - /* Set trigger */ - - putreg32((UART_FCR_FIFOENABLE|UART_FCR_RXTRIGLEVEL_16), LPC313X_UART_FCR); - - /* Set up the IER */ - - priv->ier = getreg32(LPC313X_UART_IER); - - /* Set up the LCR */ - - regval = 0; - -#if CONFIG_UART_BITS == 5 - regval |= UART_LCR_WDLENSEL_5BITS; -#elif CONFIG_UART_BITS == 6 - regval |= UART_LCR_WDLENSEL_6BITS; -#elif CONFIG_UART_BITS == 7 - regval |= UART_LCR_WDLENSEL_7BITS; -#else - regval |= UART_LCR_WDLENSEL_8BITS; -#endif - -#if CONFIG_UART_2STOP > 0 - regval |= UART_LCR_NSTOPBITS; -#endif - -#if CONFIG_UART_PARITY == 1 - regval |= UART_LCR_PAREN; -#elif CONFIG_UART_PARITY == 2 - regval |= (UART_LCR_PAREVEN|UART_LCR_PAREN); -#endif - putreg32(regval, LPC313X_UART_LCR); - - /* Set the BAUD divisor */ - - up_configbaud(); - - /* Configure the FIFOs */ - - putreg32((UART_FCR_RXTRIGLEVEL_16|UART_FCR_TXFIFORST| - UART_FCR_RXFIFORST|UART_FCR_FIFOENABLE), - LPC313X_UART_FCR); - - /* The NuttX serial driver waits for the first THRE interrrupt before - * sending serial data... However, it appears that the lpc313x hardware - * 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. - */ - - putreg32('\0', LPC313X_UART_THR); -#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 - * he the setup() method is called, however, the serial console may operate in - * 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 - * and TX interrupts are not enabled until the txint() and rxint() methods - * are called. - * - ****************************************************************************/ - -static int up_attach(struct uart_dev_s *dev) -{ - int ret; - - /* Attach and enable the IRQ */ - - ret = irq_attach(LPC313X_IRQ_UART, up_interrupt); - if (ret == OK) - { - /* Enable the interrupt (RX and TX interrupts are still disabled - * in the UART - */ - - up_enable_irq(LPC313X_IRQ_UART); - } - 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) -{ - up_disable_irq(LPC313X_IRQ_UART); - irq_detach(LPC313X_IRQ_UART); -} - -/**************************************************************************** - * Name: up_interrupt - * - * Description: - * This is the UART interrupt handler. It will be invoked when an - * interrupt received on the UART irq. It should call uart_transmitchars - * or uart_receivechar to perform the appropriate data transfers. - * - ****************************************************************************/ - -static int up_interrupt(int irq, void *context) -{ - struct uart_dev_s *dev = &g_uartport; - uint8_t status; - int passes; - - /* 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 = getreg32(LPC313X_UART_IIR); - - /* The NO INTERRUPT should be zero if there are pending - * interrupts - */ - - if ((status & UART_IIR_NOINT) != 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 & UART_IIR_INTID_MASK) - { - /* Handle incoming, receive bytes (with or without timeout) */ - - case UART_IIR_INTID_RDA: /* Received Data Available */ - case UART_IIR_INTID_TIMEOUT: /* Character time-out */ - { - uart_recvchars(dev); - break; - } - - /* Handle outgoing, transmit bytes */ - - case UART_IIR_INTID_THRE: /* Transmitter Holding Register empty */ - { - uart_xmitchars(dev); - break; - } - - /* Just clear modem status interrupts */ - - case UART_IIR_INTID_MS: /* Modem status */ - { - /* Read the modem status register (MSR) to clear */ - - status = getreg32(LPC313X_UART_MSR); - fvdbg("MSR: %02x\n", status); - break; - } - - /* Just clear any line status interrupts */ - - case UART_IIR_INTID_RLS: /* Receiver Line Status */ - { - /* Read the line status register (LSR) to clear */ - - status = getreg32(LPC313X_UART_LSR); - fvdbg("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; - int ret = OK; - - switch (cmd) - { - case TIOCSERGSTRUCT: - { - struct up_dev_s *user = (struct up_dev_s*)arg; - if (!user) - { - ret = -EINVAL; - } - else - { - memcpy(user, dev, sizeof(struct up_dev_s)); - } - } - break; - - case TIOCSBRK: /* BSD compatibility: Turn break on, unconditionally */ - { - irqstate_t flags = irqsave(); - up_enablebreaks(); - irqrestore(flags); - } - break; - - case TIOCCBRK: /* BSD compatibility: Turn break off, unconditionally */ - { - irqstate_t flags; - flags = irqsave(); - up_disablebreaks(); - irqrestore(flags); - } - break; - - default: - errno = 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) -{ - uint32_t rbr; - - *status = getreg32(LPC313X_UART_LSR); - rbr = getreg32(LPC313X_UART_RBR); - return rbr & 0xff; -} - -/**************************************************************************** - * 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 |= UART_IER_RDAINTEN; -#endif - } - else - { - priv->ier &= ~UART_IER_RDAINTEN; - } - putreg32(priv->ier, LPC313X_UART_IER); -} - -/**************************************************************************** - * Name: up_rxavailable - * - * Description: - * Return true if the receive fifo is not empty - * - ****************************************************************************/ - -static bool up_rxavailable(struct uart_dev_s *dev) -{ - return ((getreg32(LPC313X_UART_LSR) & UART_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) -{ - putreg32((uint32_t)ch, LPC313X_UART_THR); -} - -/**************************************************************************** - * 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 |= UART_IER_THREINTEN; -#endif - } - else - { - priv->ier &= ~UART_IER_THREINTEN; - } - putreg32(priv->ier, LPC313X_UART_IER); -} - -/**************************************************************************** - * Name: up_txready - * - * Description: - * Return true if the tranmsit fifo is not full - * - ****************************************************************************/ - -static bool up_txready(struct uart_dev_s *dev) -{ - return ((getreg32(LPC313X_UART_LSR) & UART_LSR_THRE) != 0); -} - -/**************************************************************************** - * Name: up_txempty - * - * Description: - * Return true if the transmit fifo is empty - * - ****************************************************************************/ - -static bool up_txempty(struct uart_dev_s *dev) -{ - return ((getreg32(LPC313X_UART_LSR) & UART_LSR_TEMT) != 0); -} - -/**************************************************************************** - * Public Functions - ****************************************************************************/ - -/**************************************************************************** - * Name: up_earlyserialinit - * - * Description: - * Performs the low level UART initialization early in debug so that the - * serial console will be available during bootup (via up_putc). This must - * be called before up_serialinit. - * - ****************************************************************************/ - -void up_earlyserialinit(void) -{ - /* Enable UART system clock */ - - lpc313x_enableclock(CLKID_UARTAPBCLK); - lpc313x_enableclock(CLKID_UARTUCLK); - - /* Disable UART interrupts */ - - up_disableuartint(g_uartport.priv, NULL); - - /* Configuration the serial console */ - -#if defined(CONFIG_UART_SERIAL_CONSOLE) - g_uartport.isconsole = true; - up_setup(&g_uartport); -#endif -} - -/**************************************************************************** - * Name: up_serialinit - * - * Description: - * Register serial console and serial ports. This assumes that - * up_earlyserialinit was called previously. - * - ****************************************************************************/ - -void up_serialinit(void) -{ -#if defined(CONFIG_UART_SERIAL_CONSOLE) - (void)uart_register("/dev/console", &g_uartport); -#endif - (void)uart_register("/dev/ttyS0", &g_uartport); -} - -/**************************************************************************** - * Name: up_putc - * - * Description: - * Provide priority, low-level access to support OS debug writes - * - ****************************************************************************/ - -int up_putc(int ch) -{ - struct up_dev_s *priv = &g_uartpriv; - uint8_t ier; - - /* Keep UART interrupts disabled so that we do not interfere with the - * serial driver. - */ - - up_disableuartint(priv, &ier); - - /* Check for LF */ - - if (ch == '\n') - { - /* Add CR */ - - up_lowputc('\r'); - } - - /* Output the character */ - - up_lowputc(ch); - 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'); - } - - /* Output the character */ - - up_lowputc(ch); - return ch; -} - -#endif /* CONFIG_USE_SERIALDRIVER */ diff --git a/nuttx/arch/arm/src/lpc313x/lpc313x_setfdiv.c b/nuttx/arch/arm/src/lpc313x/lpc313x_setfdiv.c deleted file mode 100755 index 5b0fdf904..000000000 --- a/nuttx/arch/arm/src/lpc313x/lpc313x_setfdiv.c +++ /dev/null @@ -1,135 +0,0 @@ -/**************************************************************************** - * arch/arm/src/lpc313x/lpc313x_setfdiv.c - * - * Copyright (C) 2009-2010 Gregory Nutt. All rights reserved. - * Author: Gregory Nutt - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name NuttX nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************/ - -/**************************************************************************** - * Included Files - ****************************************************************************/ - -#include - -#include -#include - -#include - -#include "lpc313x_cgu.h" -#include "lpc313x_cgudrvr.h" - -/**************************************************************************** - * Pre-processor Definitions - ****************************************************************************/ - -/**************************************************************************** - * Private Data - ****************************************************************************/ - -/**************************************************************************** - * Public Data - ****************************************************************************/ - -/**************************************************************************** - * Private Functions - ****************************************************************************/ - -/**************************************************************************** - * Public Functions - ****************************************************************************/ - -/**************************************************************************** - * Name: lpc313x_setfdiv - * - * Description: - * Set/reset subdomain frequency containing the specified clock using the - * provided divider settings - * - ****************************************************************************/ - -void lpc313x_setfdiv(enum lpc313x_domainid_e dmnid, - enum lpc313x_clockid_e clkid, - const struct lpc313x_fdivconfig_s *fdiv) -{ - uint32_t regaddr; - unsigned int basefreq; - int fdcndx; - int bcrndx; - - /* Get the frequency divider associated with this clock */ - - fdcndx = lpc313x_fdcndx(clkid, dmnid); - - /* Does this clock have a frequency divicer? */ - - if (fdcndx != FDCNDX_INVALID) - { - /* Yes.. Save the current reference frequency selection */ - - regaddr = LPC313X_CGU_SSR((int)dmnid); - basefreq = (getreg32(regaddr) & CGU_SSR_FS_MASK) >> CGU_SSR_FS_SHIFT; - - /* Switch domain to FFAST input */ - - lpc313x_selectfreqin(dmnid, CGU_FS_FFAST); - - /* Get the index of the associated BCR register. Does this domain - * have a BCR? - */ - - bcrndx = lpc313x_bcrndx(dmnid); - if (bcrndx != BCRNDX_INVALID) - { - - /* Yes... Disable the BCR */ - - regaddr = LPC313X_CGU_BCR(bcrndx); - putreg32(0, regaddr); - } - - /* Change fractional divider to the provided settings */ - - lpc313x_fdivinit(fdcndx, fdiv, true); - - /* Re-enable the BCR (if one is associated with this domain) */ - - if (bcrndx != BCRNDX_INVALID) - { - regaddr = LPC313X_CGU_BCR(bcrndx); - putreg32(CGU_BCR_FDRUN, regaddr); - } - - /* Switch the domain back to its original base frequency */ - - lpc313x_selectfreqin(dmnid, basefreq); - } -} diff --git a/nuttx/arch/arm/src/lpc313x/lpc313x_setfreqin.c b/nuttx/arch/arm/src/lpc313x/lpc313x_setfreqin.c deleted file mode 100755 index dc6ef2b3a..000000000 --- a/nuttx/arch/arm/src/lpc313x/lpc313x_setfreqin.c +++ /dev/null @@ -1,119 +0,0 @@ -/**************************************************************************** - * arch/arm/src/lpc313x/lpc313x_setfreqin.c - * - * Copyright (C) 2009-2010 Gregory Nutt. All rights reserved. - * Author: Gregory Nutt - * - * References: - * - NXP UM10314 LPC3130/31 User manual Rev. 1.01 — 9 September 2009 - * - NXP lpc313x.cdl.drivers.zip example driver code - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name NuttX nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************/ - -/**************************************************************************** - * Included Files - ****************************************************************************/ - -#include - -#include - -#include - -#include "lpc313x_cgudrvr.h" - -/**************************************************************************** - * Pre-processor Definitions - ****************************************************************************/ - -/**************************************************************************** - * Private Data - ****************************************************************************/ - -/**************************************************************************** - * Public Data - ****************************************************************************/ - -/**************************************************************************** - * Private Functions - ****************************************************************************/ - -/**************************************************************************** - * Public Functions - ****************************************************************************/ - -/**************************************************************************** - * Name: lpc313x_selectfreqin - * - * Description: - * Set the base frequency source selection for with a clock domain - * - ****************************************************************************/ - -void lpc313x_selectfreqin(enum lpc313x_domainid_e dmnid, uint32_t finsel) -{ - uint32_t scraddr = LPC313X_CGU_SCR(dmnid); - uint32_t fs1addr = LPC313X_CGU_FS1(dmnid); - uint32_t fs2addr = LPC313X_CGU_FS2(dmnid); - uint32_t scrbits; - - /* Get the frequency selection from the switch configuration register (SCR) - * for this domain. - */ - - scrbits = getreg32(scraddr) & ~(CGU_SCR_ENF1|CGU_SCR_ENF2); - - /* If FS1 is currently enabled set the reference clock to FS2 and enable FS2 */ - - if ((getreg32(LPC313X_CGU_SSR(dmnid)) & CGU_SSR_FS1STAT) != 0) - { - /* Check if the selected frequency, FS1, is same as requested */ - - if ((getreg32(fs1addr) & CGU_FS_MASK) != finsel) - { - /* No.. Set up FS2 */ - - putreg32(finsel, fs2addr); - putreg32(scrbits | CGU_SCR_ENF2, scraddr); - } - } - - /* FS1 is not currently enabled, check if the selected frequency, FS2, - * is same as requested - */ - - else if ((getreg32(fs2addr) & CGU_FS_MASK) != finsel) - { - /* No.. Set up FS1 */ - - putreg32(finsel, fs1addr); - putreg32(scrbits | CGU_SCR_ENF1, scraddr); - } -} diff --git a/nuttx/arch/arm/src/lpc313x/lpc313x_softreset.c b/nuttx/arch/arm/src/lpc313x/lpc313x_softreset.c deleted file mode 100755 index 9e8ecfab3..000000000 --- a/nuttx/arch/arm/src/lpc313x/lpc313x_softreset.c +++ /dev/null @@ -1,90 +0,0 @@ -/************************************************************************ - * arch/arm/src/lpc313x/lpc313x_softreset.c - * - * Copyright (C) 2009 Gregory Nutt. All rights reserved. - * Author: Gregory Nutt - * - * References: - * - UM10314 LPC3130/31 User manual Rev. 1.01 — 9 September 2009 - * - lpc313x.cdl.drivers.zip example driver code - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name NuttX nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - ************************************************************************/ - -/************************************************************************ - * Included Files - ************************************************************************/ - -#include -#include - -#include "up_arch.h" -#include "lpc313x_cgudrvr.h" - -/************************************************************************ - * Pre-processor Definitions - ************************************************************************/ - -/************************************************************************ - * Private Data - ************************************************************************/ - -/************************************************************************ - * Private Functions - ************************************************************************/ - -/************************************************************************ - * Public Functions - ************************************************************************/ - -/************************************************************************ - * Name: lpc313x_softreset - * - * Description: - * Perform a soft reset on the specified module. - * - ************************************************************************/ - -void lpc313x_softreset(enum lpc313x_resetid_e resetid) -{ - uint32_t address = LPC313X_CGU_SOFTRST(resetid); - volatile int i; - - /* Clear and set the register */ - - putreg32(0, address); - - /* Delay a bit */ - - for (i = 0;i < 1000; i++); - - /* Then set the the soft reset bit */ - - putreg32(CGU_SOFTRESET, address); -} diff --git a/nuttx/arch/arm/src/lpc313x/lpc313x_spi.c b/nuttx/arch/arm/src/lpc313x/lpc313x_spi.c deleted file mode 100644 index af4c9ce09..000000000 --- a/nuttx/arch/arm/src/lpc313x/lpc313x_spi.c +++ /dev/null @@ -1,971 +0,0 @@ -/************************************************************************************ - * arm/arm/src/lpc313x/lpc313x_spi.c - * - * Copyright (C) 2009-2010 Gregory Nutt. All rights reserved. - * Author: David Hewson, deriving in part from other SPI drivers originally by - * Gregory Nutt - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name NuttX nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - ************************************************************************************/ - -/************************************************************************************ - * Included Files - ************************************************************************************/ - -#include - -#include -#include -#include -#include -#include -#include - -#include -#include - -#include - -#include "lpc313x_spi.h" -#include "lpc313x_ioconfig.h" - -/************************************************************************************ - * Definitions - ************************************************************************************/ - -/* Configuration ********************************************************************/ - -/* Debug ****************************************************************************/ -/* Define the following to enable extremely detailed register debug */ - -#undef CONFIG_DEBUG_SPIREGS - -/* CONFIG_DEBUG must also be defined */ - -#ifndef CONFIG_DEBUG -# undef CONFIG_DEBUG_SPIREGS -#endif - -/* FIFOs ****************************************************************************/ - -#define SPI_FIFO_DEPTH 64 /* 64 words deep (8- or 16-bit words) */ - -/* Timing ***************************************************************************/ - -#define SPI_MAX_DIVIDER 65024 /* = 254 * (255 + 1) */ -#define SPI_MIN_DIVIDER 2 - -/************************************************************************************ - * Private Types - ************************************************************************************/ - -struct lpc313x_spidev_s -{ - struct spi_dev_s spidev; /* Externally visible part of the SPI interface */ - sem_t exclsem; /* Held while chip is selected for mutual exclusion */ - uint32_t frequency; /* Requested clock frequency */ - uint32_t actual; /* Actual clock frequency */ - uint8_t nbits; /* Width of work in bits (8 or 16) */ - uint8_t mode; /* Mode 0,1,2,3 */ - - uint32_t slv1; - uint32_t slv2; -}; - -/************************************************************************************ - * Private Function Prototypes - ************************************************************************************/ - -#ifdef CONFIG_DEBUG_SPIREGS -static bool spi_checkreg(bool wr, uint32_t value, uint32_t address); -static void spi_putreg(uint32_t value, uint32_t address); -static uint32_t spi_getreg(uint32_t address); -#else -# define spi_putreg(v,a) putreg32(v,a) -# define spi_getreg(a) getreg32(a) -#endif - -static inline void spi_drive_cs(FAR struct lpc313x_spidev_s *priv, uint8_t slave, uint8_t val); -static inline void spi_select_slave(FAR struct lpc313x_spidev_s *priv, uint8_t slave); -static inline uint16_t spi_readword(FAR struct lpc313x_spidev_s *priv); -static inline void spi_writeword(FAR struct lpc313x_spidev_s *priv, uint16_t word); - -static int spi_lock(FAR struct spi_dev_s *dev, bool lock); -static void spi_select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected); -static uint32_t spi_setfrequency(FAR struct spi_dev_s *dev, uint32_t frequency); -static void spi_setmode(FAR struct spi_dev_s *dev, enum spi_mode_e mode); -static void spi_setbits(FAR struct spi_dev_s *dev, int nbits); -static uint8_t spi_status(FAR struct spi_dev_s *dev, enum spi_dev_e devid); -static uint16_t spi_send(FAR struct spi_dev_s *dev, uint16_t word); -static void spi_exchange(FAR struct spi_dev_s *dev, FAR const void *txbuffer, - FAR void *rxbuffer, size_t nwords); -#ifndef CONFIG_SPI_EXCHANGE -static void spi_sndblock(FAR struct spi_dev_s *dev, FAR const void *txbuffer, - size_t nwords); -static void spi_recvblock(FAR struct spi_dev_s *dev, FAR void *rxbuffer, - size_t nwords); -#endif - - -/************************************************************************************ - * Private Data - ************************************************************************************/ - -static const struct spi_ops_s g_spiops = -{ - .lock = spi_lock, - .select = spi_select, - .setfrequency = spi_setfrequency, - .setmode = spi_setmode, - .setbits = spi_setbits, - .status = spi_status, -#ifdef CONFIG_SPI_CMDDATA - .cmddata = lpc313x_spicmddata, -#endif - .send = spi_send, -#ifdef CONFIG_SPI_EXCHANGE - .exchange = spi_exchange, -#else - .sndblock = spi_sndblock, - .recvblock = spi_recvblock, -#endif - .registercallback = 0, -}; - -static struct lpc313x_spidev_s g_spidev = -{ - .spidev = { &g_spiops }, -}; - -#ifdef CONFIG_DEBUG_SPIREGS -static bool g_wrlast; -static uint32_t g_addresslast; -static uint32_t g_valuelast; -static int g_ntimes; -#endif - -/************************************************************************************ - * Public Data - ************************************************************************************/ - -/************************************************************************************ - * Private Functions - ************************************************************************************/ - -/**************************************************************************** - * Name: spi_checkreg - * - * Description: - * Check if the current register access is a duplicate of the preceding. - * - * Input Parameters: - * value - The value to be written - * address - The address of the register to write to - * - * Returned Value: - * true: This is the first register access of this type. - * flase: This is the same as the preceding register access. - * - ****************************************************************************/ - -#ifdef CONFIG_DEBUG_SPIREGS -static bool spi_checkreg(bool wr, uint32_t value, uint32_t address) -{ - if (wr == g_wrlast && value == g_valuelast && address == g_addresslast) - { - g_ntimes++; - return false; - } - else - { - if (g_ntimes > 0) - { - lldbg("...[Repeats %d times]...\n", g_ntimes); - } - - g_wrlast = wr; - g_valuelast = value; - g_addresslast = address; - g_ntimes = 0; - } - return true; -} -#endif - -/**************************************************************************** - * Name: spi_putreg - * - * Description: - * Write a 32-bit value to an SPI register - * - * Input Parameters: - * value - The value to be written - * address - The address of the register to write to - * - * Returned Value: - * None - * - ****************************************************************************/ - -#ifdef CONFIG_DEBUG_SPIREGS -static void spi_putreg(uint32_t value, uint32_t address) -{ - if (spi_checkreg(true, value, address)) - { - lldbg("%08x<-%08x\n", address, value); - } - putreg32(value, address); -} -#endif - -/**************************************************************************** - * Name: spi_getreg - * - * Description: - * Read a 32-bit value from an SPI register - * - * Input Parameters: - * address - The address of the register to read from - * - * Returned Value: - * The value read from the register - * - ****************************************************************************/ - -#ifdef CONFIG_DEBUG_SPIREGS -static uint32_t spi_getreg(uint32_t address) -{ - uint32_t value = getreg32(address); - if (spi_checkreg(false, value, address)) - { - lldbg("%08x->%08x\n", address, value); - } - return value; -} -#endif - -/**************************************************************************** - * Name: spi_drive_cs - * - * Description: - * Drive the chip select signal for this slave - * - * Input Parameters: - * dev - Device-specific state data - * slave - slave id - * value - value (0 for assert) - * - * Returned Value: - * None - * - ****************************************************************************/ - -static inline void spi_drive_cs(FAR struct lpc313x_spidev_s *priv, uint8_t slave, uint8_t val) -{ - switch (slave) - { - case 0: - if (val == 0) - { - spi_putreg(IOCONFIG_SPI_CSOUT0, LPC313X_IOCONFIG_SPI_MODE0RESET); - } - else - { - spi_putreg(IOCONFIG_SPI_CSOUT0, LPC313X_IOCONFIG_SPI_MODE0SET); - } - spi_putreg(IOCONFIG_SPI_CSOUT0, LPC313X_IOCONFIG_SPI_MODE1SET); - break; - - case 1: - if (val == 0) - { - spi_putreg(IOCONFIG_EBII2STX0_MUARTCTSN, LPC313X_IOCONFIG_EBII2STX0_MODE0RESET); - } - else - { - spi_putreg(IOCONFIG_EBII2STX0_MUARTCTSN, LPC313X_IOCONFIG_EBII2STX0_MODE0SET); - } - spi_putreg(IOCONFIG_EBII2STX0_MUARTCTSN, LPC313X_IOCONFIG_EBII2STX0_MODE1SET); - break; - - case 2: - if (val == 0) - { - spi_putreg(IOCONFIG_EBII2STX0_MUARTRTSN, LPC313X_IOCONFIG_EBII2STX0_MODE0RESET); - } - else - { - spi_putreg(IOCONFIG_EBII2STX0_MUARTRTSN, LPC313X_IOCONFIG_EBII2STX0_MODE0SET); - } - spi_putreg(IOCONFIG_EBII2STX0_MUARTRTSN, LPC313X_IOCONFIG_EBII2STX0_MODE1SET); - break; - } -} - -/**************************************************************************** - * Name: spi_select_slave - * - * Description: - * Select the slave device for the next transfer - * - * Input Parameters: - * dev - Device-specific state data - * slave - slave id - * - * Returned Value: - * None - * - ****************************************************************************/ - -static inline void spi_select_slave(FAR struct lpc313x_spidev_s *priv, uint8_t slave) -{ - switch (slave) - { - case 0: - spi_putreg(priv->slv1, LPC313X_SPI_SLV0_1); - spi_putreg(priv->slv2, LPC313X_SPI_SLV0_2); - spi_putreg(SPI_SLVENABLE1_ENABLED, LPC313X_SPI_SLVENABLE); - break; - - case 1: - spi_putreg(priv->slv1, LPC313X_SPI_SLV1_1); - spi_putreg(priv->slv2, LPC313X_SPI_SLV1_2); - spi_putreg(SPI_SLVENABLE2_ENABLED, LPC313X_SPI_SLVENABLE); - break; - - case 2: - spi_putreg(priv->slv1, LPC313X_SPI_SLV2_1); - spi_putreg(priv->slv2, LPC313X_SPI_SLV2_2); - spi_putreg(SPI_SLVENABLE3_ENABLED, LPC313X_SPI_SLVENABLE); - break; - } -} - -/************************************************************************************ - * Name: spi_readword - * - * Description: - * Read one word from SPI - * - * Input Parameters: - * priv - Device-specific state data - * - * Returned Value: - * Byte as read - * - ************************************************************************************/ - -static inline uint16_t spi_readword(FAR struct lpc313x_spidev_s *priv) -{ - /* Wait until the RX FIFO is not empty */ - - while ((spi_getreg(LPC313X_SPI_STATUS) & SPI_STATUS_RXFIFOEMPTY) != 0); - - /* Then return the received word */ - - return (uint16_t)spi_getreg(LPC313X_SPI_FIFODATA); -} - -/************************************************************************************ - * Name: spi_writeword - * - * Description: - * Write one word to SPI - * - * Input Parameters: - * priv - Device-specific state data - * word - Word to send - * - * Returned Value: - * None - * - ************************************************************************************/ - -static inline void spi_writeword(FAR struct lpc313x_spidev_s *priv, uint16_t word) -{ - /* Wait until the TX FIFO is not full */ - - while ((spi_getreg(LPC313X_SPI_STATUS) & SPI_STATUS_TXFIFOFULL) != 0); - - /* Then send the word */ - - spi_putreg(word, LPC313X_SPI_FIFODATA); -} - -/**************************************************************************** - * Name: spi_lock - * - * Description: - * On SPI busses where there are multiple devices, it will be necessary to - * lock SPI to have exclusive access to the busses for a sequence of - * transfers. The bus should be locked before the chip is selected. After - * locking the SPI bus, the caller should then also call the setfrequency, - * setbits, and setmode methods to make sure that the SPI is properly - * configured for the device. If the SPI buss is being shared, then it - * may have been left in an incompatible state. - * - * Input Parameters: - * dev - Device-specific state data - * lock - true: Lock spi bus, false: unlock SPI bus - * - * Returned Value: - * None - * - ****************************************************************************/ - -static int spi_lock(FAR struct spi_dev_s *dev, bool lock) -{ - FAR struct lpc313x_spidev_s *priv = (FAR struct lpc313x_spidev_s *)dev; - - if (lock) - { - /* Take the semaphore (perhaps waiting) */ - - while (sem_wait(&priv->exclsem) != 0) - { - /* The only case that an error should occur here is if the wait was awakened - * by a signal. - */ - - ASSERT(errno == EINTR); - } - } - else - { - (void)sem_post(&priv->exclsem); - } - return OK; -} - -/**************************************************************************** - * Name: spi_select - * - * Description: - * Enable/disable the SPI slave select. The implementation of this method - * must include handshaking: If a device is selected, it must hold off - * all other attempts to select the device until the device is deselecte. - * - * Input Parameters: - * dev - Device-specific state data - * devid - Identifies the device to select - * selected - true: slave selected, false: slave de-selected - * - * Returned Value: - * None - * - ****************************************************************************/ - -static void spi_select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected) -{ - struct lpc313x_spidev_s *priv = (struct lpc313x_spidev_s *) dev; - uint8_t slave = 0; - - /* FIXME: map the devid to the SPI slave - this should really - * be in board specific code..... */ - switch (devid) - { - case SPIDEV_FLASH: - slave = 0; - break; - - case SPIDEV_MMCSD: - slave = 1; - break; - - case SPIDEV_ETHERNET: - slave = 2; - break; - - default: - return; - } - - /* - * Since we don't use sequential multi-slave mode, but rather - * perform the transfer piecemeal by consecutive calls to - * SPI_SEND, then we must manually assert the chip select - * across the whole transfer - */ - - if (selected) - { - spi_drive_cs(priv, slave, 0); - spi_select_slave(priv, slave); - - /* Enable SPI as master and notify of slave enables change */ - - spi_putreg((1 << SPI_CONFIG_INTERSLVDELAY_SHIFT) | SPI_CONFIG_UPDENABLE | SPI_CONFIG_SPIENABLE, LPC313X_SPI_CONFIG); - } - else - { - spi_drive_cs(priv, slave, 1); - - /* Disable all slaves */ - - spi_putreg(0, LPC313X_SPI_SLVENABLE); - - /* Disable SPI as master */ - - spi_putreg(SPI_CONFIG_UPDENABLE, LPC313X_SPI_CONFIG); - } -} - -/************************************************************************************ - * Name: spi_setfrequency - * - * Description: - * Set the SPI frequency. - * - * Input Parameters: - * dev - Device-specific state data - * frequency - The SPI frequency requested - * - * Returned Value: - * Returns the actual frequency selected - * - ************************************************************************************/ - -static uint32_t spi_setfrequency(FAR struct spi_dev_s *dev, uint32_t frequency) -{ - FAR struct lpc313x_spidev_s *priv = (FAR struct lpc313x_spidev_s *)dev; - uint32_t spi_clk, div, div1, div2; - - if (priv->frequency != frequency) - { - /* The SPI clock is derived from the (main system oscillator / 2), - * so compute the best divider from that clock */ - - spi_clk = lpc313x_clkfreq(CLKID_SPICLK, DOMAINID_SPI); - - /* Find closest divider to get at or under the target frequency */ - - div = (spi_clk + frequency / 2) / frequency; - - if (div > SPI_MAX_DIVIDER) - { - div = SPI_MAX_DIVIDER; - } - else if (div < SPI_MIN_DIVIDER) - { - div = SPI_MIN_DIVIDER; - } - - div2 = (((div-1) / 512) + 2) * 2; - div1 = ((((div + div2 / 2) / div2) - 1)); - - priv->slv1 = (priv->slv1 & ~(SPI_SLV_1_CLKDIV2_MASK | SPI_SLV_1_CLKDIV1_MASK)) | (div2 << SPI_SLV_1_CLKDIV2_SHIFT) | (div1 << SPI_SLV_1_CLKDIV1_SHIFT); - - priv->frequency = frequency; - priv->actual = frequency; // FIXME - } - - return priv->actual; -} - -/************************************************************************************ - * Name: spi_setmode - * - * Description: - * Set the SPI mode. see enum spi_mode_e for mode definitions - * - * Input Parameters: - * dev - Device-specific state data - * mode - The SPI mode requested - * - * Returned Value: - * Returns the actual frequency selected - * - ************************************************************************************/ - -static void spi_setmode(FAR struct spi_dev_s *dev, enum spi_mode_e mode) -{ - FAR struct lpc313x_spidev_s *priv = (FAR struct lpc313x_spidev_s *)dev; - uint16_t setbits; - uint16_t clrbits; - -/* Has the mode changed? */ - - if (mode != priv->mode) - { - /* Yes... Set CR1 appropriately */ - - switch (mode) - { - case SPIDEV_MODE0: /* SPO=0; SPH=0 */ - setbits = 0; - clrbits = SPI_SLV_2_SPO|SPI_SLV_2_SPH; - break; - - case SPIDEV_MODE1: /* SPO=0; SPH=1 */ - setbits = SPI_SLV_2_SPH; - clrbits = SPI_SLV_2_SPO; - break; - - case SPIDEV_MODE2: /* SPO=1; SPH=0 */ - setbits = SPI_SLV_2_SPO; - clrbits = SPI_SLV_2_SPH; - break; - - case SPIDEV_MODE3: /* SPO=1; SPH=1 */ - setbits = SPI_SLV_2_SPO|SPI_SLV_2_SPH; - clrbits = 0; - break; - - default: - return; - } - - priv->slv2 = (priv->slv2 & ~clrbits) | setbits; - priv->mode = mode; - } -} - -/************************************************************************************ - * Name: spi_setbits - * - * Description: - * Set the number of bits per word. - * - * Input Parameters: - * dev - Device-specific state data - * nbits - The number of bits requested - * - * Returned Value: - * None - * - ************************************************************************************/ - -static void spi_setbits(FAR struct spi_dev_s *dev, int nbits) -{ - FAR struct lpc313x_spidev_s *priv = (FAR struct lpc313x_spidev_s *)dev; - - /* Has the number of bits changed? */ - - if (nbits != priv->nbits) - { - priv->slv2 = (priv->slv2 & ~SPI_SLV_2_WDSIZE_MASK) | ((nbits-1) << SPI_SLV_2_WDSIZE_SHIFT); - priv->nbits = nbits; - } -} - -/**************************************************************************** - * Name: spi_status - * - * Description: - * Get SPI/MMC status - * - * Input Parameters: - * dev - Device-specific state data - * devid - Identifies the device to report status on - * - * Returned Value: - * Returns a bitset of status values (see SPI_STATUS_* defines - * - ****************************************************************************/ - -static uint8_t spi_status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) -{ - /* FIXME: is there anyway to determine this - * it should probably be board dependant anyway */ - - return SPI_STATUS_PRESENT; -} - -/************************************************************************************ - * Name: spi_send - * - * Description: - * Exchange one word on SPI - * - * Input Parameters: - * dev - Device-specific state data - * word - The word to send. the size of the data is determined by the - * number of bits selected for the SPI interface. - * - * Returned Value: - * response - * - ************************************************************************************/ - -static uint16_t spi_send(FAR struct spi_dev_s *dev, uint16_t word) -{ - FAR struct lpc313x_spidev_s *priv = (FAR struct lpc313x_spidev_s *)dev; - DEBUGASSERT(priv); - - spi_writeword(priv, word); - return spi_readword(priv); -} - -/************************************************************************* - * Name: spi_exchange - * - * Description: - * Exchange a block of data on SPI - * - * Input Parameters: - * dev - Device-specific state data - * txbuffer - A pointer to the buffer of data to be sent - * rxbuffer - A pointer to a buffer in which to receive data - * nwords - the length of data to be exchaned in units of words. - * The wordsize is determined by the number of bits-per-word - * selected for the SPI interface. If nbits <= 8, the data is - * packed into uint8_t's; if nbits >8, the data is packed into uint16_t's - * - * Returned Value: - * None - * - ************************************************************************************/ - -static void spi_exchange(FAR struct spi_dev_s *dev, FAR const void *txbuffer, - FAR void *rxbuffer, size_t nwords) -{ - FAR struct lpc313x_spidev_s *priv = (FAR struct lpc313x_spidev_s *)dev; - unsigned int maxtx; - unsigned int ntx; - - DEBUGASSERT(priv); - - /* 8- or 16-bit mode? */ - - if (priv->nbits == 16) - { - /* 16-bit mode */ - - const uint16_t *src = (const uint16_t*)txbuffer;; - uint16_t *dest = (uint16_t*)rxbuffer; - uint16_t word; - - while (nwords > 0) - { - /* Fill up the TX FIFO */ - - maxtx = nwords > SPI_FIFO_DEPTH ? SPI_FIFO_DEPTH : nwords; - for (ntx = 0; ntx < maxtx; ntx++) - { - /* Get the next word to write. Is there a source buffer? */ - - word = src ? *src++ : 0xffff; - - /* Then send the word */ - - spi_writeword(priv, word); - } - nwords -= maxtx; - - /* Then empty the RX FIFO */ - - while (ntx-- > 0) - { - word = spi_readword(priv); - - /* Is there a buffer to receive the return value? */ - - if (dest) - { - *dest++ = word; - } - } - } - } - else - { - /* 8-bit mode */ - - const uint8_t *src = (const uint8_t*)txbuffer;; - uint8_t *dest = (uint8_t*)rxbuffer; - uint8_t word; - - while (nwords > 0) - { - /* Fill up the TX FIFO */ - - maxtx = nwords > SPI_FIFO_DEPTH ? SPI_FIFO_DEPTH : nwords; - for (ntx = 0; ntx < maxtx; ntx++) - { - /* Get the next word to write. Is there a source buffer? */ - - word = src ? *src++ : 0xff; - - /* Then send the word */ - - spi_writeword(priv, (uint16_t)word); - } - nwords -= maxtx; - - /* Then empty the RX FIFO */ - - while (ntx-- > 0) - { - word = (uint8_t)spi_readword(priv); - - /* Is there a buffer to receive the return value? */ - - if (dest) - { - *dest++ = word; - } - } - } - } -} - -/************************************************************************* - * Name: spi_sndblock - * - * Description: - * Send a block of data on SPI - * - * Input Parameters: - * dev - Device-specific state data - * txbuffer - A pointer to the buffer of data to be sent - * nwords - the length of data to send from the buffer in number of words. - * The wordsize is determined by the number of bits-per-word - * selected for the SPI interface. If nbits <= 8, the data is - * packed into uint8_t's; if nbits >8, the data is packed into uint16_t's - * - * Returned Value: - * None - * - ************************************************************************************/ - -#ifndef CONFIG_SPI_EXCHANGE -static void spi_sndblock(FAR struct spi_dev_s *dev, FAR const void *txbuffer, size_t nwords) -{ - return spi_exchange(dev, txbuffer, NULL, nwords); -} -#endif - -/************************************************************************************ - * Name: spi_recvblock - * - * Description: - * Revice a block of data from SPI - * - * Input Parameters: - * dev - Device-specific state data - * rxbuffer - A pointer to the buffer in which to recieve data - * nwords - the length of data that can be received in the buffer in number - * of words. The wordsize is determined by the number of bits-per-word - * selected for the SPI interface. If nbits <= 8, the data is - * packed into uint8_t's; if nbits >8, the data is packed into uint16_t's - * - * Returned Value: - * None - * - ************************************************************************************/ - -#ifndef CONFIG_SPI_EXCHANGE -static void spi_recvblock(FAR struct spi_dev_s *dev, FAR void *rxbuffer, size_t nwords) -{ - return spi_exchange(dev, NULL, rxbuffer, nwords); -} -#endif - -/************************************************************************************ - * Public Functions - ************************************************************************************/ - -/************************************************************************************ - * Name: up_spiinitialize - * - * Description: - * Initialize the selected SPI port - * - * Input Parameter: - * Port number (for hardware that has mutiple SPI interfaces) - * - * Returned Value: - * Valid SPI device structure reference on succcess; a NULL on failure - * - ************************************************************************************/ - -FAR struct spi_dev_s *up_spiinitialize(int port) -{ - FAR struct lpc313x_spidev_s *priv = &g_spidev; - - /* Only the SPI0 interface is supported */ - - if (port != 0) - { - return NULL; - } - - /* Configure SPI pins. Nothing needs to be done here because the SPI pins - * default to "driven-by-IP" on reset. - */ - -#ifdef CONFIG_DEBUG_SPIREGS - lldbg("PINS: %08x MODE0: %08x MODE1: %08x\n", - spi_getreg(LPC313X_IOCONFIG_SPI_PINS), - spi_getreg(LPC313X_IOCONFIG_SPI_MODE0), - spi_getreg(LPC313X_IOCONFIG_SPI_MODE1)); -#endif - - /* Enable SPI clocks */ - - lpc313x_enableclock(CLKID_SPIPCLK); - lpc313x_enableclock(CLKID_SPIPCLKGATED); - lpc313x_enableclock(CLKID_SPICLK); - lpc313x_enableclock(CLKID_SPICLKGATED); - - /* Soft Reset the module */ - - lpc313x_softreset(RESETID_SPIRSTAPB); - lpc313x_softreset(RESETID_SPIRSTIP); - - /* Initialize the SPI semaphore that enforces mutually exclusive access */ - - sem_init(&priv->exclsem, 0, 1); - - /* Reset the SPI block */ - - spi_putreg(SPI_CONFIG_SOFTRST, LPC313X_SPI_CONFIG); - - /* Initialise Slave 0 settings registers */ - - priv->slv1 = 0; - priv->slv2 = 0; - - /* Configure initial default mode */ - - priv->mode = SPIDEV_MODE1; - spi_setmode(&priv->spidev, SPIDEV_MODE0); - - /* Configure word width */ - - priv->nbits = 0; - spi_setbits(&priv->spidev, 8); - - /* Select a default frequency of approx. 400KHz */ - - priv->frequency = 0; - spi_setfrequency(&priv->spidev, 400000); - - return (FAR struct spi_dev_s *)priv; -} diff --git a/nuttx/arch/arm/src/lpc313x/lpc313x_spi.h b/nuttx/arch/arm/src/lpc313x/lpc313x_spi.h deleted file mode 100755 index b817f4518..000000000 --- a/nuttx/arch/arm/src/lpc313x/lpc313x_spi.h +++ /dev/null @@ -1,252 +0,0 @@ -/************************************************************************************************ - * arch/arm/src/lpc313x/lpc313x_spi.h - * - * Copyright (C) 2009-2010 Gregory Nutt. All rights reserved. - * Author: Gregory Nutt - * - * 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_LPC313X_SPI_H -#define __ARCH_ARM_SRC_LPC313X_SPI_H - -/************************************************************************************************ - * Included Files - ************************************************************************************************/ - -#include -#include "lpc313x_memorymap.h" - -/************************************************************************************************ - * Pre-processor Definitions - ************************************************************************************************/ - -/* SPI register base address offset into the APB2 domain ****************************************/ - -#define LPC313X_SPI_VBASE (LPC313X_APB2_VSECTION+LPC313X_APB2_SPI_OFFSET) -#define LPC313X_SPI_PBASE (LPC313X_APB2_PSECTION+LPC313X_APB2_SPI_OFFSET) - -/* SPI register offsets (with respect to the SPI base) ******************************************/ -/* SPI configuration registers */ - -#define LPC313X_SPI_CONFIG_OFFSET 0x000 /* Configuration register */ -#define LPC313X_SPI_SLVENABLE_OFFSET 0x004 /* Slave enable register */ -#define LPC313X_SPI_TXFIFO_OFFSET 0x008 /* Transmit FIFO flush register */ -#define LPC313X_SPI_FIFODATA_OFFSET 0x00C /* FIFO data register */ -#define LPC313X_SPI_NHPPOP_OFFSET 0x010 /* NHP pop register */ -#define LPC313X_SPI_NHPMODE_OFFSET 0x014 /* NHP mode selection register */ -#define LPC313X_SPI_DMA_OFFSET 0x018 /* DMA settings register */ -#define LPC313X_SPI_STATUS_OFFSET 0x01c /* Status register */ -#define LPC313X_SPI_HWINFO_OFFSET 0x020 /* Hardware information register */ - -/* SPI slave registers */ - -#define LPC313X_SPI_SLV0_1_OFFSET 0x024 /* Slave settings register 1 (for slave 0) */ -#define LPC313X_SPI_SLV0_2_OFFSET 0x028 /* Slave settings register 2 (for slave 0) */ -#define LPC313X_SPI_SLV1_1_OFFSET 0x02c /* Slave settings register 1 (for slave 1) */ -#define LPC313X_SPI_SLV1_2_OFFSET 0x030 /* Slave settings register 2 (for slave 1) */ -#define LPC313X_SPI_SLV2_1_OFFSET 0x034 /* Slave settings register 1 (for slave 2) */ -#define LPC313X_SPI_SLV2_2_OFFSET 0x038 /* Slave settings register 2 (for slave 2) */ - /* 0x03c-0xfd0: Reserved */ -/* SPI interrupt registers */ - -#define LPC313X_SPI_INTTHR_OFFSET 0xfd4 /* Tx/Rx threshold interrupt levels */ -#define LPC313X_SPI_INTCLRENABLE_OFFSET 0xfd8 /* INT_ENABLE bits clear register */ -#define LPC313X_SPI_INTSETENABLE_OFFSET 0xfdc /* INT_ENABLE bits set register */ -#define LPC313X_SPI_INTSTATUS_OFFSET 0xfe0 /* Interrupt status register */ -#define LPC313X_SPI_INTENABLE_OFFSET 0xfe4 /* Interrupt enable register */ -#define LPC313X_SPI_INTCLRSTATUS_OFFSET 0xfe8 /* INT_STATUS bits clear register */ -#define LPC313X_SPI_INTSETSTATUS_OFFSET 0xfec /* INT_STATUS bits set register */ - /* 0xff0-0xff8: Reserved */ - -/* SPI register (virtual) addresses *************************************************************/ - -/* SPI configuration registers */ - -#define LPC313X_SPI_CONFIG (LPC313X_SPI_VBASE+LPC313X_SPI_CONFIG_OFFSET) -#define LPC313X_SPI_SLVENABLE (LPC313X_SPI_VBASE+LPC313X_SPI_SLVENABLE_OFFSET) -#define LPC313X_SPI_TXFIFO (LPC313X_SPI_VBASE+LPC313X_SPI_TXFIFO_OFFSET) -#define LPC313X_SPI_FIFODATA (LPC313X_SPI_VBASE+LPC313X_SPI_FIFODATA_OFFSET) -#define LPC313X_SPI_NHPPOP (LPC313X_SPI_VBASE+LPC313X_SPI_NHPPOP_OFFSET) -#define LPC313X_SPI_NHPMODE (LPC313X_SPI_VBASE+LPC313X_SPI_NHPMODE_OFFSET) -#define LPC313X_SPI_DMA (LPC313X_SPI_VBASE+LPC313X_SPI_DMA_OFFSET) -#define LPC313X_SPI_STATUS (LPC313X_SPI_VBASE+LPC313X_SPI_STATUS_OFFSET) -#define LPC313X_SPI_HWINFO (LPC313X_SPI_VBASE+LPC313X_SPI_HWINFO_OFFSET) - -/* SPI slave registers */ - -#define LPC313X_SPI_SLV0_1 (LPC313X_SPI_VBASE+LPC313X_SPI_SLV0_1_OFFSET) -#define LPC313X_SPI_SLV0_2 (LPC313X_SPI_VBASE+LPC313X_SPI_SLV0_2_OFFSET) -#define LPC313X_SPI_SLV1_1 (LPC313X_SPI_VBASE+LPC313X_SPI_SLV1_1_OFFSET) -#define LPC313X_SPI_SLV1_2 (LPC313X_SPI_VBASE+LPC313X_SPI_SLV1_2_OFFSET) -#define LPC313X_SPI_SLV2_1 (LPC313X_SPI_VBASE+LPC313X_SPI_SLV2_1_OFFSET) -#define LPC313X_SPI_SLV2_2 (LPC313X_SPI_VBASE+LPC313X_SPI_SLV2_2_OFFSET) - -/* SPI interrupt registers */ - -#define LPC313X_SPI_INTTHR (LPC313X_SPI_VBASE+LPC313X_SPI_INTTHR_OFFSET) -#define LPC313X_SPI_INTCLRENABLE (LPC313X_SPI_VBASE+LPC313X_SPI_INTCLRENABLE_OFFSET) -#define LPC313X_SPI_INTSETENABLE (LPC313X_SPI_VBASE+LPC313X_SPI_INTSETENABLE_OFFSET) -#define LPC313X_SPI_INTSTATUS (LPC313X_SPI_VBASE+LPC313X_SPI_INTSTATUS_OFFSET) -#define LPC313X_SPI_INTENABLE (LPC313X_SPI_VBASE+LPC313X_SPI_INTENABLE_OFFSET) -#define LPC313X_SPI_INTCLRSTATUS (LPC313X_SPI_VBASE+LPC313X_SPI_INTCLRSTATUS_OFFSET) -#define LPC313X_SPI_INTSETSTATUS (LPC313X_SPI_VBASE+LPC313X_SPI_INTSETSTATUS_OFFSET) - -/* SPI register bit definitions *****************************************************************/ -/* SPI Configuration register CONFIG, address 0x15002000 */ - -#define SPI_CONFIG_INTERSLVDELAY_SHIFT (16) /* Bits 16-31: Delay between xfrs to different slaves */ -#define SPI_CONFIG_NTERSLVDELAY_MASK (0xffff << SPI_CONFIG_INTERSLVDELAY_SHIFT) -#define SPI_CONFIG_UPDENABLE (1 << 7) /* Bit 7: 7 Update enable bit */ -#define SPI_CONFIG_SOFTRST (1 << 6) /* Bit 6: 6 Software reset bit */ -#define SPI_CONFIG_SLVDISABLE (1 << 4) /* Bit 4: 4 Slave output disable (slave mode) */ -#define SPI_CONFIG_XMITMODE (1 << 3) /* Bit 3: 3 Transmit mode */ -#define SPI_CONFIG_LOOPBACK (1 << 2) /* Bit 2: 2 Loopback mode bit */ -#define SPI_CONFIG_MS (1 << 1) /* Bit 1: 1 Master/slave mode bit */ -#define SPI_CONFIG_SPIENABLE (1 << 0) /* Bit 0: 0 SPI enable bit */ - -/* Slave Enable register SLVENABLE, address 0x15002004 */ - -#define SPI_SLVENABLE3_SHIFT (4) /* Bits 4-5: Slave 3 enable bits */ -#define SPI_SLVENABLE3_MASK (3 << SPI_SLVENABLE3_SHIFT) -# define SPI_SLVENABLE3_DISABLED (0 << SPI_SLVENABLE3_SHIFT) /* Disabled */ -# define SPI_SLVENABLE3_ENABLED (1 << SPI_SLVENABLE3_SHIFT) /* Enabled */ -# define SPI_SLVENABLE3_SUSPENDED (3 << SPI_SLVENABLE3_SHIFT) /* Suspended */ -#define SPI_SLVENABLE2_SHIFT (2) /* Bits 2-3: Slave 2 enable bits */ -#define SPI_SLVENABLE2_MASK (3 << SPI_SLVENABLE2_SHIFT) -# define SPI_SLVENABLE2_DISABLED (0 << SPI_SLVENABLE2_SHIFT) /* Disabled */ -# define SPI_SLVENABLE2_ENABLED (1 << SPI_SLVENABLE2_SHIFT) /* Enabled */ -# define SPI_SLVENABLE2_SUSPENDED (3 << SPI_SLVENABLE2_SHIFT) /* Suspended */ -#define SPI_SLVENABLE1_SHIFT (0) /* Bits 0-1: Slave 1 enable bits */ -#define SPI_SLVENABLE1_MASK (3 << SPI_SLVENABLE1_SHIFT) -# define SPI_SLVENABLE1_DISABLED (0 << SPI_SLVENABLE1_SHIFT) /* Disabled */ -# define SPI_SLVENABLE1_ENABLED (1 << SPI_SLVENABLE1_SHIFT) /* Enabled */ -# define SPI_SLVENABLE1_SUSPENDED (3 << SPI_SLVENABLE1_SHIFT) /* Suspended */ - -/* Transmit FIFO flush register TXFIFO, address 0x15002008 */ - -#define SPI_TXFIFO_FLUSH (1 << 0) /* Bit 0: Transmit FIFO flush bit */ - -/* FIFO data register FIFODATA, address 0x1500200c */ - -#define SPI_FIFODATA_SHIFT (0) /* Bits 0-15: FIFO data */ -#define SPI_FIFODATA_MASK (0xffff << SPI_FIFODATA_SHIFT) - -/* NHP POP register NHPPOP, address 0x15002010 */ - -#define SPI_NHPPOP (1 << 0) /* Bit 0: NHP pop bit */ - -/* NHP mode register NHPMODE, address 0x15002014 */ - -#define SPI_NHPMODE (1 << 0) /* Bit 0: NHP mode bit */ - -/* DMA setting register DMA, address 0x15002018 */ - -#define SPI_DMA_TXENABLE (1 << 1) /* Bit 1: Tx DMA enable bit */ -#define SPI_DMA_RXEMABLE (1 << 0) /* Bit 0: Rx DMA enable bit */ - -/* Status register STATUS, address 0x1500201c */ - -#define SPI_STATUS_SMSBUSY (1 << 5) /* Bit 5: Sequential multi-slave mode busy */ -#define SPI_STATUS_BUSY (1 << 4) /* Bit 4: SPI busy flag */ -#define SPI_STATUS_RXFIFOFULL (1 << 3) /* Bit 3: Receive FIFO full bit */ -#define SPI_STATUS_RXFIFOEMPTY (1 << 2) /* Bit 2: Receive FIFO empty bit */ -#define SPI_STATUS_TXFIFOFULL (1 << 1) /* Bit 1: Transmit FIFO full bit */ -#define SPI_STATUS_TXFIFOEMPTY (1 << 0) /* Bit 0: Transmit FIFO empty bit */ - -/* Hardware information register HWINFO, address 0x15002020 */ - -#define SPI_HWINFO_FIFOIMPLT (1 << 30) /* Bit 30: FIFO memory implementation */ -#define SPI_HWINFO_NSLAVES_SHIFT (26) /* Bits 26-29: Maximum number of slaves (minus 1) */ -#define SPI_HWINFO_NSLAVES_MASK (0x0f << SPI_HWINFO_NSLAVES_SHIFT) -#define SPI_HWINFO_TXFIFOWIDTH_SHIFT (21) /* Bits 21-25: Width transmit FIFO (minus 1) */ -#define SPI_HWINFO_TXFIFOWIDTH_MASK (0x1f << SPI_HWINFO_TXFIFOWIDTH_SHIFT) -#define SPI_HWINFO_RXFIFOWIDTH_SHIFT (16) /* Bits 16-20: Width receive FIFO (minus 1) */ -#define SPI_HWINFO_RXFIFOWIDTH_MASK (0x1f << SPI_HWINFO_RXFIFOWIDTH_SHIFT) -#define SPI_HWINFO_TXFIFODEPTH_SHIFT (8) /* Bits 8-15: 64 */ -#define SPI_HWINFO_TXFIFODEPTH_MASK (0x0ff << SPI_HWINFO_TXFIFODEPTH_SHIFT) -#define SPI_HWINFO_RXFIFODEPTH_SHIFT (0) /* Bits 0-7: 64 */ -#define SPI_HWINFO_RXFIFODEPTH_MASK (0xff << SPI_HWINFO_RXFIFODEPTH_SHIFT) - -/* Slave settings 1 SLV0-2_1, addresses 0x15002024, 0x1500202c, and 0x15002034 */ - -#define SPI_SLV_1_INTERXFRDLY_SHIFT (24) /* Bits 24-31: Delay between slave xfrs (master mode) */ -#define SPI_SLV_1_INTERXFRDLY_MASK (0xff << SPI_SLV_1_INTERXFRDLY_SHIFT) -#define SPI_SLV_1_NWORDS_SHIFT (16) /* Bits 16-23: Number words to send in SMS mode (master mode) */ -#define SPI_SLV_1_NWORDS_MASK (0xff << SPI_SLV_1_NWORDS_SHIFT) -#define SPI_SLV_1_CLKDIV2_SHIFT (8) /* Bits 8-15: Serial clock divisor 2 */ -#define SPI_SLV_1_CLKDIV2_MASK (0xff << SPI_SLV_1_CLKDIV2_SHIFT) -#define SPI_SLV_1_CLKDIV1_SHIFT (0) /* Bits 0-7: Serial clock rate divisor 1 */ -#define SPI_SLV_1_CLKDIV1_MASK (0xff << SPI_SLV_1_CLKDIV1_SHIFT) - -/* Slave settings 2 SLV0-2_2, addresses 0x15002028, 0x15002030, and0x15002038 */ - -#define SPI_SLV_2_DELAY_SHIFT (9) /* Bits 9-16: Programmable delay */ -#define SPI_SLV_2_DELAY_MASK (0xff << SPI_SLV_2_DELAY_SHIFT) -#define SPI_SLV_2_CSVAL (1 << 8) /* Bit 8: Chip select value between transfers */ -#define SPI_SLV_2_XFRFMT (1 << 7) /* Bit 7: Format of transfer */ -#define SPI_SLV_2_SPO (1 << 6) /* Bit 6: Serial clock polarity */ -#define SPI_SLV_2_SPH (1 << 5) /* Bit 5: Serial clock phase */ -#define SPI_SLV_2_WDSIZE_SHIFT (0) /* Bits 0-4: Word size of transfers slave (minus 1) */ -#define SPI_SLV_2_WDSIZE_MASK (0x1f << SPI_SLV_2_WDSIZE_SHIFT) - -/* Interrupt threshold register INTTHR, address 0x15002fd4 */ - -#define SPI_INTTHR_TX_SHIFT (8) /* Bits 8-15: Interrupt when less than this in TX FIFO */ -#define SPI_INTTHR_TX_MASK (0xff << SPI_INTTHR_TX_SHIFT) -#define SPI_INTTHR_RX_SHIFT (0) /* Bits 0-7: Interrupt when more than this in RX FIFO */ -#define SPI_INTTHR_RX_MASK (0xff << SPI_INTTHR_TX_SHIFT) - -/* Interrupt clear enable register INTCLRENABLE, address 0x15002fd8, - * Interrupt set enable register INTSETENABLE, address 0x15002fdc, - * Interrupt status register INTSTATUS, address 0x15002fe0, - * Interrupt enable register INTENABLE, address 0x15002fe4, - * Interrupt clear status register INTCLRSTATUS, address 0x15002fe8, - * Interrupt set status register INTSETSTATUS, address 0x15002fec - */ - -#define SPI_INT_SMS (1 << 4) /* Bit 4: Sequential multi-slave mode ready interrupt bit */ -#define SPI_INT_TX (1 << 3) /* Bit 3: Transmit threshold level interrupt bit */ -#define SPI_INT_RX (1 << 2) /* Bit 3: Receive threshold level interrupt bit */ -#define SPI_INT_TO (1 << 1) /* Bit 1: Receive timeout interrupt bit */ -#define SPI_INT_OV (1 << 0) /* Bit 0: Receive overrtun interrrupt bit */ - -/************************************************************************************************ - * Public Types - ************************************************************************************************/ - -/************************************************************************************************ - * Public Data - ************************************************************************************************/ - -/************************************************************************************************ - * Public Functions - ************************************************************************************************/ - -#endif /* __ARCH_ARM_SRC_LPC313X_SPI_H */ diff --git a/nuttx/arch/arm/src/lpc313x/lpc313x_syscreg.h b/nuttx/arch/arm/src/lpc313x/lpc313x_syscreg.h deleted file mode 100755 index 6467484d5..000000000 --- a/nuttx/arch/arm/src/lpc313x/lpc313x_syscreg.h +++ /dev/null @@ -1,611 +0,0 @@ -/******************************************************************************************************** - * arch/arm/src/lpc313x/lpc313x_syscreg.h - * - * Copyright (C) 2009-2010 Gregory Nutt. All rights reserved. - * Author: Gregory Nutt - * - * 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_LPC313X_SYSCREG_H -#define __ARCH_ARM_SRC_LPC313X_SYSCREG_H - -/******************************************************************************************************** - * Included Files - ********************************************************************************************************/ - -#include -#include "lpc313x_memorymap.h" - -/******************************************************************************************************** - * Pre-processor Definitions - ********************************************************************************************************/ - -/* SYSCREG register base address offset into the APB0 domain ********************************************/ - -#define LPC313X_SYSCREG_VBASE (LPC313X_APB0_VADDR+LPC313X_APB0_SYSCREG_OFFSET) -#define LPC313X_SYSCREG_PBASE (LPC313X_APB0_PADDR+LPC313X_APB0_SYSCREG_OFFSET) - -/* SYSCREG register offsets (with respect to the SYSCREG base) ******************************************/ -/* Miscellaneous system configuration registers, part1 */ - /* 0x000-0x004: Reserved */ -#define LPC313X_SYSCREG_EBIMPMCPRIO_OFFSET 0x008 /* Priority of MPMC channel for EBI interface */ -#define LPC313X_SYSCREG_EBNANDCPRIO_OFFSET 0x00c /* Priority of NAND controller channel for EBI interface */ -#define LPC313X_SYSCREG_EBIUNUSEDPRIO_OFFSET 0x010 /* Priority of unused channel */ -#define LPC313X_SYSCREG_RINGOSCCFG_OFFSET 0x014 /* RING oscillator configuration register */ -#define LPC313X_SYSCREG_ADCPDADC10BITS_OFFSET 0x018 /* Powerdown register of ADC 10bits */ -#define LPC313X_SYSCREG_CGUDYNHP0_OFFSET 0x01c /* reserved */ -#define LPC313X_SYSCREG_CGUDYNHP1_OFFSET 0x020 /* reserved */ -#define LPC313X_SYSCREG_ABCCFG_OFFSET 0x024 /* AHB burst control register */ -#define LPC313X_SYSCREG_SDMMCCFG_OFFSET 0x028 /* SD_MMC (MCI) configuration register */ -#define LPC313X_SYSCREG_MCIDELAYMODES_OFFSET 0x02c /* Delay register for the SD_MMC (MCI) clocks */ - -/* USB configuration registers */ - -#define LPC313X_SYSCREG_USB_ATXPLLPDREG_OFFSET 0x030 /* Power down register of USB ATX PLL */ -#define LPC313X_SYSCREG_USB_OTGCFG_OFFSET 0x034 /* USB OTG configuration register */ -#define LPC313X_SYSCREG_USB_OTGPORTINDCTL_OFFSET 0x038 /* USB OTG port indicator LED control outputs */ - /* 0x03c: Reserved */ -#define LPC313X_SYSCREG_USB_PLLNDEC_OFFSET 0x040 /* USB OTG PLL configuration register NOEC */ -#define LPC313X_SYSCREG_USB_PLLMDEC_OFFSET 0x044 /* USB OTG PLL configuration register MDEC */ -#define LPC313X_SYSCREG_USB_PLLPDEC_OFFSET 0x048 /* USB OTG PLL configuration register PDEC */ -#define LPC313X_SYSCREG_USB_PLLSELR_OFFSET 0x04c /* USB OTG PLL configuration register SELR */ -#define LPC313X_SYSCREG_USB_PLLSELI_OFFSET 0x050 /* USB OTG PLL configuration register SELI */ -#define LPC313X_SYSCREG_USB_PLLSELP_OFFSET 0x054 /* USB OTG PLL configuration register SELP */ - -/* ISRAM/ISROM configuration registers */ - -#define LPC313X_SYSCREG_ISRAM0_LATENCYCFG_OFFSET 0x058 /* Internal SRAM 0 latency configuration register */ -#define LPC313X_SYSCREG_ISRAM1_LATENCYCFG_OFFSET 0x05c /* Internal SRAM 1 latency configuration register */ -#define LPC313X_SYSCREG_ISROM_LATENCYCFG_OFFSET 0x060 /* Internal SROM latency configuration register */ - -/* MPMC configuration registers */ - -#define LPC313X_SYSCREG_MPMC_AHBMISC_OFFSET 0x064 /* Configuration register of MPMC */ -#define LPC313X_SYSCREG_MPMC_DELAYMODES_OFFSET 0x068 /* Configuration of MPMC clock delay */ -#define LPC313X_SYSCREG_MPMC_WAITRD0_OFFSET 0x06c /* Configuration of the wait cycles for read transfers */ -#define LPC313X_SYSCREG_MPMC_WAITRD1_OFFSET 0x070 /* Configuration of the wait cycles for read transfers */ -#define LPC313X_SYSCREG_MPMC_WIREEBIMSZ_OFFSET 0x074 /* Configuration of the memory width for MPMC */ -#define LPC313X_SYSCREG_MPMC_TESTMODE0_OFFSET 0x078 /* Configuration for refresh generation of MPMC */ -#define LPC313X_SYSCREG_MPMC_TESTMODE1_OFFSET 0x07c /* Configuration for refresh generation of MPMC */ - -/* Miscellaneous system configuration registers, part 2 */ - -#define LPC313X_SYSCREG_AHB0EXTPRIO_OFFSET 0x080 /* Priority of the AHB masters */ -#define LPC313X_SYSCREG_ARM926SHADOWPTR_OFFSET 0x084 /* Memory mapping */ - /* 0x088-0x08c reserved */ -/* Pin multiplexing control registers */ - -#define LPC313X_SYSCREG_MUX_LCDEBISEL_OFFSET 0x090 /* Selects between lcd_interface and EBI pins */ -#define LPC313X_SYSCREG_MUX_GPIOMCISEL_OFFSET 0x094 /* Selects between GPIO and MCI pins */ -#define LPC313X_SYSCREG_MUX_NANDMCISEL_OFFSET 0x098 /* Selects between NAND flash controller and MCI pins */ -#define LPC313X_SYSCREG_MUX_UARTSPISEL_OFFSET 0x09c /* Selects between UART and SPI pins */ -#define LPC313X_SYSCREG_MUX_I2STXPCMSEL_OFFSET 0x0a0 /* Selects between I2STX and PCM pins */ - -/* Pad configuration registers */ - -#define LPC313X_SYSCREG_PAD_EBID9_OFFSET 0x0a4 /* Control pad EBI_D_9 */ -#define LPC313X_SYSCREG_PAD_EBID10_OFFSET 0x0a8 /* Control pad EBI_D_10 */ -#define LPC313X_SYSCREG_PAD_EBID11_OFFSET 0x0ac /* Control pad EBI_D_11 */ -#define LPC313X_SYSCREG_PAD_EBID12_OFFSET 0x0b0 /* Control pad EBI_D_12 */ -#define LPC313X_SYSCREG_PAD_EBID13_OFFSET 0x0b4 /* Control pad EBI_D_13 */ -#define LPC313X_SYSCREG_PAD_EBID14_OFFSET 0x0b8 /* Control pad EBI_D_14 */ -#define LPC313X_SYSCREG_PAD_I2SRXBCK0_OFFSET 0x0bc /* Control pad I2SRX_BCK0 */ -#define LPC313X_SYSCREG_PAD_MGPIO9_OFFSET 0x0c0 /* Control pad MGPIO9 */ -#define LPC313X_SYSCREG_PAD_MGPIO6_OFFSET 0x0c4 /* Control pad MGPIO6 */ -#define LPC313X_SYSCREG_PAD_MLCDDB7_OFFSET 0x0c8 /* Control pad MLCD_DB_7 */ -#define LPC313X_SYSCREG_PAD_MLCDDB4_OFFSET 0x0cc /* Control pad MLCD_DB_4 */ -#define LPC313X_SYSCREG_PAD_MLCDDB2_OFFSET 0x0d0 /* Control pad MLCD_DB_2 */ -#define LPC313X_SYSCREG_PAD_MNANDRYBN0_OFFSET 0x0d4 /* Control pad MNAND_RYBN0 */ -#define LPC313X_SYSCREG_PAD_GPIO1_OFFSET 0x0d8 /* Control pad GPIO1 */ -#define LPC313X_SYSCREG_PAD_EBID4_OFFSET 0x0dc /* Control pad EBI_D_4 */ -#define LPC313X_SYSCREG_PAD_MI2STXCLK0_OFFSET 0x0e0 /* Control pad MI2STX_CLK0 */ -#define LPC313X_SYSCREG_PAD_MI2STXBCK0_OFFSET 0x0e4 /* Control pad MI2STX_BCK0 */ -#define LPC313X_SYSCREG_PAD_EBIA1CLE_OFFSET 0x0e8 /* Control pad EBI_A_1_CLE */ -#define LPC313X_SYSCREG_PAD_EBINCASBLOUT0_OFFSET 0x0ec /* Control pad EBI_NCAS_BLOUT_0 */ -#define LPC313X_SYSCREG_PAD_NANDNCS3_OFFSET 0x0f0 /* Control pad NAND_NCS_3 */ -#define LPC313X_SYSCREG_PAD_MLCDDB0_OFFSET 0x0f4 /* Control pad MLCD_DB_0 */ -#define LPC313X_SYSCREG_PAD_EBIDQM0NOE_OFFSET 0x0f8 /* Control pad EBI_DQM_0_NOE */ -#define LPC313X_SYSCREG_PAD_EBID0_OFFSET 0x0fc /* Control pad EBI_D_0 */ -#define LPC313X_SYSCREG_PAD_EBID1_OFFSET 0x100 /* Control pad EBI_D_1 */ -#define LPC313X_SYSCREG_PAD_EBID2_OFFSET 0x104 /* Control pad EBI_D_2 */ -#define LPC313X_SYSCREG_PAD_EBID3_OFFSET 0x108 /* Control pad EBI_D_3 */ -#define LPC313X_SYSCREG_PAD_EBID5_OFFSET 0x10c /* Control pad EBI_D_5 */ -#define LPC313X_SYSCREG_PAD_EBID6_OFFSET 0x110 /* Control pad EBI_D_6 */ -#define LPC313X_SYSCREG_PAD_EBID7_OFFSET 0x114 /* Control pad EBI_D_7 */ -#define LPC313X_SYSCREG_PAD_EBID8_OFFSET 0x118 /* Control pad EBI_D_8 */ -#define LPC313X_SYSCREG_PAD_EBID15_OFFSET 0x11c /* Control pad EBI_D_15 */ -#define LPC313X_SYSCREG_PAD_I2STXDATA1_OFFSET 0x120 /* Control pad I2STX_DATA1 */ -#define LPC313X_SYSCREG_PAD_I2STXBCK1_OFFSET 0x124 /* Control pad I2STX_BCK1 */ -#define LPC313X_SYSCREG_PAD_I2STXWS1_OFFSET 0x128 /* Control pad I2STX_WS1 */ -#define LPC313X_SYSCREG_PAD_I2SRXDATA0_OFFSET 0x12c /* Control pad I2SRX_DATA0 */ -#define LPC313X_SYSCREG_PAD_I2SRXWS0_OFFSET 0x130 /* Control pad I2SRX_WS0 */ -#define LPC313X_SYSCREG_PAD_I2SRXDATA1_OFFSET 0x134 /* Control pad I2SRX_DATA1 */ -#define LPC313X_SYSCREG_PAD_I2SRXBCK1_OFFSET 0x138 /* Control pad I2SRX_BCK1 */ -#define LPC313X_SYSCREG_PAD_I2SRXWS1_OFFSET 0x13c /* Control pad I2SRX_WS1 */ -#define LPC313X_SYSCREG_PAD_SYSCLKO_OFFSET 0x140 /* Control pad SYSCLK_O */ -#define LPC313X_SYSCREG_PAD_PWMDATA_OFFSET 0x144 /* Control pad PWM_DATA */ -#define LPC313X_SYSCREG_PAD_UARTRXD_OFFSET 0x148 /* Control pad UART_RXD */ -#define LPC313X_SYSCREG_PAD_UARTTXD_OFFSET 0x14c /* Control pad UART_TXD */ -#define LPC313X_SYSCREG_PAD_I2CSDA1_OFFSET 0x150 /* Control pad I2C_SDA1 */ -#define LPC313X_SYSCREG_PAD_I2CSCL1_OFFSET 0x154 /* Control pad I2C_SCL1 */ -#define LPC313X_SYSCREG_PAD_CLK256FSO_OFFSET 0x158 /* Control pad CLK_256FS_O */ -#define LPC313X_SYSCREG_PAD_GPIO0_OFFSET 0x15c /* Control pad GPIO0 */ -#define LPC313X_SYSCREG_PAD_GPIO2_OFFSET 0x160 /* Control pad GPIO2 */ -#define LPC313X_SYSCREG_PAD_GPIO3_OFFSET 0x164 /* Control pad GPIO3 */ -#define LPC313X_SYSCREG_PAD_GPIO4_OFFSET 0x168 /* Control pad GPIO4 */ -#define LPC313X_SYSCREG_PAD_GPIO11_OFFSET 0x16c /* Control pad GPIO11 */ -#define LPC313X_SYSCREG_PAD_GPIO12_OFFSET 0x170 /* Control pad GPIO12 */ -#define LPC313X_SYSCREG_PAD_GPIO13_OFFSET 0x174 /* Control pad GPIO13 */ -#define LPC313X_SYSCREG_PAD_GPIO14_OFFSET 0x178 /* Control pad GPIO14 */ -#define LPC313X_SYSCREG_PAD_GPIO15_OFFSET 0x17c /* Control pad GPIO15 */ -#define LPC313X_SYSCREG_PAD_GPIO16_OFFSET 0x180 /* Control pad GPIO16 */ -#define LPC313X_SYSCREG_PAD_GPIO17_OFFSET 0x184 /* Control pad GPIO17 */ -#define LPC313X_SYSCREG_PAD_GPIO18_OFFSET 0x188 /* Control pad GPIO18 */ -#define LPC313X_SYSCREG_PAD_GPIO19_OFFSET 0x18c /* Control pad GPIO19 */ -#define LPC313X_SYSCREG_PAD_GPIO20_OFFSET 0x190 /* Control pad GPIO20 */ -#define LPC313X_SYSCREG_PAD_SPIMISO_OFFSET 0x194 /* Control pad SPI_MISO */ -#define LPC313X_SYSCREG_PAD_SPIMOSI_OFFSET 0x198 /* Control pad SPI_MOSI */ -#define LPC313X_SYSCREG_PAD_SPICSIN_OFFSET 0x19c /* Control pad SPI_CS_IN */ -#define LPC313X_SYSCREG_PAD_SPISCK_OFFSET 0x1a0 /* Control pad SPI_SCK */ -#define LPC313X_SYSCREG_PAD_SPICSOUT0_OFFSET 0x1a4 /* Control pad SPI_CS_OUT0 */ -#define LPC313X_SYSCREG_PAD_NANDNCS0_OFFSET 0x1a8 /* Control pad NAND_NCS_0 */ -#define LPC313X_SYSCREG_PAD_NANDNCS1_OFFSET 0x1ac /* Control pad NAND_NCS_1 */ -#define LPC313X_SYSCREG_PAD_NANDNCS2_OFFSET 0x1b0 /* Control pad NAND_NCS_2 */ -#define LPC313X_SYSCREG_PAD_MLCDCSB_OFFSET 0x1b4 /* Control pad MLCD_CSB */ -#define LPC313X_SYSCREG_PAD_MLCDDB1_OFFSET 0x1b8 /* Control pad MLCD_DB_1 */ -#define LPC313X_SYSCREG_PAD_MLCDERD_OFFSET 0x1bc /* Control pad MLCD_E_RD */ -#define LPC313X_SYSCREG_PAD_MLCDRS_OFFSET 0x1c0 /* Control pad MLCD_RS */ -#define LPC313X_SYSCREG_PAD_MLCDRWWR_OFFSET 0x1c4 /* Control pad MLCD_RW_WR */ -#define LPC313X_SYSCREG_PAD_MLCDDB3_OFFSET 0x1c8 /* Control pad MLCD_DB_3 */ -#define LPC313X_SYSCREG_PAD_MLCDDB5_OFFSET 0x1cc /* Control pad MLCD_DB_5 */ -#define LPC313X_SYSCREG_PAD_MLCDDB6_OFFSET 0x1d0 /* Control pad MLCD_DB_6 */ -#define LPC313X_SYSCREG_PAD_MLCDDB8_OFFSET 0x1d4 /* Control pad MLCD_DB_8 */ -#define LPC313X_SYSCREG_PAD_MLCDDB9_OFFSET 0x1d8 /* Control pad MLCD_DB_9 */ -#define LPC313X_SYSCREG_PAD_MLCDDB10_OFFSET 0x1dc /* Control pad MLCD_DB_10 */ -#define LPC313X_SYSCREG_PAD_MLCDDB11_OFFSET 0x1e0 /* Control pad MLCD_DB_11 */ -#define LPC313X_SYSCREG_PAD_MLCDDB12_OFFSET 0x1e4 /* Control pad MLCD_DB_12 */ -#define LPC313X_SYSCREG_PAD_MLCDDB13_OFFSET 0x1e8 /* Control pad MLCD_DB_13 */ -#define LPC313X_SYSCREG_PAD_MLCDDB14_OFFSET 0x1ec /* Control pad MLCD_DB_14 */ -#define LPC313X_SYSCREG_PAD_MLCDDB15_OFFSET 0x1f0 /* Control pad MLCD_DB_15 */ -#define LPC313X_SYSCREG_PAD_MGPIO5_OFFSET 0x1f4 /* Control pad MGPIO5 */ -#define LPC313X_SYSCREG_PAD_MGPIO7_OFFSET 0x1f8 /* Control pad MGPIO5 */ -#define LPC313X_SYSCREG_PAD_MGPIO8_OFFSET 0x1fc /* Control pad MGPIO8 */ -#define LPC313X_SYSCREG_PAD_MGPIO10_OFFSET 0x200 /* Control pad MGPIO10 */ -#define LPC313X_SYSCREG_PAD_MNANDRYBN1_OFFSET 0x204 /* Control pad MNAND_RYBN1 */ -#define LPC313X_SYSCREG_PAD_MNANDRYBN2_OFFSET 0x208 /* Control pad MNAND_RYBN2 */ -#define LPC313X_SYSCREG_PAD_MNANDRYBN3_OFFSET 0x20c /* Control pad MNAND_RYBN3 */ -#define LPC313X_SYSCREG_PAD_MUARTCTSN_OFFSET 0x210 /* Control pad MUART_CTS_N */ -#define LPC313X_SYSCREG_PAD_MI2STXDATA0_OFFSET 0x218 /* Control pad MI2STX_DATA0 */ -#define LPC313X_SYSCREG_PAD_MI2STXWS0_OFFSET 0x21c /* Control pad MI2STX_WS0 */ -#define LPC313X_SYSCREG_PAD_EBINRASBLOUT1_OFFSET 0x220 /* Control pad EBI_NRAS_BLOUT_1 */ -#define LPC313X_SYSCREG_PAD_EBIA0ALE_OFFSET 0x224 /* Control pad EBI_A_0_ALE */ -#define LPC313X_SYSCREG_PAD_EBINWE_OFFSET 0x228 /* Control pad EBI_NWE */ -#define LPC313X_SYSCREG_PAD_ESHCTRLSUP4_OFFSET 0x22c /* Control pad at 1.8 and 3.3V (Nandflash/EBI pads) */ -#define LPC313X_SYSCREG_PAD_ESHCTRLSUP8_OFFSET 0x230 /* Control pad at 1.8 and 3.3V (LCD interface/SDRAM pads) */ - -/* SYSCREG register (virtual) addresses *****************************************************************/ -/* Miscellaneous system configuration registers, part1 */ - -#define LPC313X_SYSCREG_EBIMPMCPRIO (LPC313X_SYSCREG_VBASE+LPC313X_SYSCREG_EBIMPMCPRIO_OFFSET) -#define LPC313X_SYSCREG_EBNANDCPRIO (LPC313X_SYSCREG_VBASE+LPC313X_SYSCREG_EBNANDCPRIO_OFFSET) -#define LPC313X_SYSCREG_EBIUNUSEDPRIO (LPC313X_SYSCREG_VBASE+LPC313X_SYSCREG_EBIUNUSEDPRIO_OFFSET) -#define LPC313X_SYSCREG_RINGOSCCFG (LPC313X_SYSCREG_VBASE+LPC313X_SYSCREG_RINGOSCCFG_OFFSET) -#define LPC313X_SYSCREG_ADCPDADC10BITS (LPC313X_SYSCREG_VBASE+LPC313X_SYSCREG_ADCPDADC10BITS_OFFSET) -#define LPC313X_SYSCREG_ABCCFG (LPC313X_SYSCREG_VBASE+LPC313X_SYSCREG_ABCCFG_OFFSET) -#define LPC313X_SYSCREG_SDMMCCFG (LPC313X_SYSCREG_VBASE+LPC313X_SYSCREG_SDMMCCFG_OFFSET) -#define LPC313X_SYSCREG_MCIDELAYMODES (LPC313X_SYSCREG_VBASE+LPC313X_SYSCREG_MCIDELAYMODES_OFFSET) - -/* USB configuration registers */ - -#define LPC313X_SYSCREG_USB_ATXPLLPDREG (LPC313X_SYSCREG_VBASE+LPC313X_SYSCREG_USB_ATXPLLPDREG_OFFSET) -#define LPC313X_SYSCREG_USB_OTGCFG (LPC313X_SYSCREG_VBASE+LPC313X_SYSCREG_USB_OTGCFG_OFFSET) -#define LPC313X_SYSCREG_USB_OTGPORTINDCTL (LPC313X_SYSCREG_VBASE+LPC313X_SYSCREG_USB_OTGPORTINDCTL_OFFSET) -#define LPC313X_SYSCREG_USB_PLLNDEC (LPC313X_SYSCREG_VBASE+LPC313X_SYSCREG_USB_PLLNDEC_OFFSET) -#define LPC313X_SYSCREG_USB_PLLMDEC (LPC313X_SYSCREG_VBASE+LPC313X_SYSCREG_USB_PLLMDEC_OFFSET) -#define LPC313X_SYSCREG_USB_PLLPDEC (LPC313X_SYSCREG_VBASE+LPC313X_SYSCREG_USB_PLLPDEC_OFFSET) -#define LPC313X_SYSCREG_USB_PLLSELR (LPC313X_SYSCREG_VBASE+LPC313X_SYSCREG_USB_PLLSELR_OFFSET) -#define LPC313X_SYSCREG_USB_PLLSELI (LPC313X_SYSCREG_VBASE+LPC313X_SYSCREG_USB_PLLSELI_OFFSET) -#define LPC313X_SYSCREG_USB_PLLSELP (LPC313X_SYSCREG_VBASE+LPC313X_SYSCREG_USB_PLLSELP_OFFSET) - -/* ISRAM/ISROM configuration registers */ - -#define LPC313X_SYSCREG_ISRAM0_LATENCYCFG (LPC313X_SYSCREG_VBASE+LPC313X_SYSCREG_ISRAM0_LATENCYCFG_OFFSET) -#define LPC313X_SYSCREG_ISRAM1_LATENCYCFG (LPC313X_SYSCREG_VBASE+LPC313X_SYSCREG_ISRAM1_LATENCYCFG_OFFSET) -#define LPC313X_SYSCREG_ISROM_LATENCYCFG (LPC313X_SYSCREG_VBASE+LPC313X_SYSCREG_ISROM_LATENCYCFG_OFFSET) - -/* MPMC configuration registers */ - -#define LPC313X_SYSCREG_MPMC_AHBMISC (LPC313X_SYSCREG_VBASE+LPC313X_SYSCREG_MPMC_AHBMISC_OFFSET) -#define LPC313X_SYSCREG_MPMC_DELAYMODES (LPC313X_SYSCREG_VBASE+LPC313X_SYSCREG_MPMC_DELAYMODES_OFFSET) -#define LPC313X_SYSCREG_MPMC_WAITRD0 (LPC313X_SYSCREG_VBASE+LPC313X_SYSCREG_MPMC_WAITRD0_OFFSET) -#define LPC313X_SYSCREG_MPMC_WAITRD1 (LPC313X_SYSCREG_VBASE+LPC313X_SYSCREG_MPMC_WAITRD1_OFFSET) -#define LPC313X_SYSCREG_MPMC_WIREEBIMSZ (LPC313X_SYSCREG_VBASE+LPC313X_SYSCREG_MPMC_WIREEBIMSZ_OFFSET) -#define LPC313X_SYSCREG_MPMC_TESTMODE0 (LPC313X_SYSCREG_VBASE+LPC313X_SYSCREG_MPMC_TESTMODE0_OFFSET) -#define LPC313X_SYSCREG_MPMC_TESTMODE1 (LPC313X_SYSCREG_VBASE+LPC313X_SYSCREG_MPMC_TESTMODE1_OFFSET) - -/* Miscellaneous system configuration registers, part 2 */ - -#define LPC313X_SYSCREG_AHB0EXTPRIO (LPC313X_SYSCREG_VBASE+LPC313X_SYSCREG_AHB0EXTPRIO_OFFSET) -#define LPC313X_SYSCREG_ARM926SHADOWPTR (LPC313X_SYSCREG_VBASE+LPC313X_SYSCREG_ARM926SHADOWPTR_OFFSET) - -/* Pin multiplexing control registers */ - -#define LPC313X_SYSCREG_MUX_LCDEBISEL (LPC313X_SYSCREG_VBASE+LPC313X_SYSCREG_MUX_LCDEBISEL_OFFSET) -#define LPC313X_SYSCREG_MUX_GPIOMCISEL (LPC313X_SYSCREG_VBASE+LPC313X_SYSCREG_MUX_GPIOMCISEL_OFFSET) -#define LPC313X_SYSCREG_MUX_NANDMCISEL (LPC313X_SYSCREG_VBASE+LPC313X_SYSCREG_MUX_NANDMCISEL_OFFSET) -#define LPC313X_SYSCREG_MUX_UARTSPISEL (LPC313X_SYSCREG_VBASE+LPC313X_SYSCREG_MUX_UARTSPISEL_OFFSET) -#define LPC313X_SYSCREG_MUX_I2STXPCMSEL (LPC313X_SYSCREG_VBASE+LPC313X_SYSCREG_MUX_I2STXPCMSEL_OFFSET) - -/* Pad configuration registers */ - -#define LPC313X_SYSCREG_PAD_EBID9 (LPC313X_SYSCREG_VBASE+LPC313X_SYSCREG_PAD_EBID9_OFFSET) -#define LPC313X_SYSCREG_PAD_EBID10 (LPC313X_SYSCREG_VBASE+LPC313X_SYSCREG_PAD_EBID10_OFFSET) -#define LPC313X_SYSCREG_PAD_EBID11 (LPC313X_SYSCREG_VBASE+LPC313X_SYSCREG_PAD_EBID11_OFFSET) -#define LPC313X_SYSCREG_PAD_EBID12 (LPC313X_SYSCREG_VBASE+LPC313X_SYSCREG_PAD_EBID12_OFFSET) -#define LPC313X_SYSCREG_PAD_EBID13 (LPC313X_SYSCREG_VBASE+LPC313X_SYSCREG_PAD_EBID13_OFFSET) -#define LPC313X_SYSCREG_PAD_EBID14 (LPC313X_SYSCREG_VBASE+LPC313X_SYSCREG_PAD_EBID14_OFFSET) -#define LPC313X_SYSCREG_PAD_I2SRXBCK0 (LPC313X_SYSCREG_VBASE+LPC313X_SYSCREG_PAD_I2SRXBCK0_OFFSET) -#define LPC313X_SYSCREG_PAD_MGPIO9 (LPC313X_SYSCREG_VBASE+LPC313X_SYSCREG_PAD_MGPIO9_OFFSET) -#define LPC313X_SYSCREG_PAD_MGPIO6 (LPC313X_SYSCREG_VBASE+LPC313X_SYSCREG_PAD_MGPIO6_OFFSET) -#define LPC313X_SYSCREG_PAD_MLCDDB7 (LPC313X_SYSCREG_VBASE+LPC313X_SYSCREG_PAD_MLCDDB7_OFFSET) -#define LPC313X_SYSCREG_PAD_MLCDDB4 (LPC313X_SYSCREG_VBASE+LPC313X_SYSCREG_PAD_MLCDDB4_OFFSET) -#define LPC313X_SYSCREG_PAD_MLCDDB2 (LPC313X_SYSCREG_VBASE+LPC313X_SYSCREG_PAD_MLCDDB2_OFFSET) -#define LPC313X_SYSCREG_PAD_MNANDRYBN0 (LPC313X_SYSCREG_VBASE+LPC313X_SYSCREG_PAD_MNANDRYBN0_OFFSET) -#define LPC313X_SYSCREG_PAD_GPIO1 (LPC313X_SYSCREG_VBASE+LPC313X_SYSCREG_PAD_GPIO1_OFFSET) -#define LPC313X_SYSCREG_PAD_EBID4 (LPC313X_SYSCREG_VBASE+LPC313X_SYSCREG_PAD_EBID4_OFFSET) -#define LPC313X_SYSCREG_PAD_MI2STXCLK0 (LPC313X_SYSCREG_VBASE+LPC313X_SYSCREG_PAD_MI2STXCLK0_OFFSET) -#define LPC313X_SYSCREG_PAD_MI2STXBCK0 (LPC313X_SYSCREG_VBASE+LPC313X_SYSCREG_PAD_MI2STXBCK0_OFFSET) -#define LPC313X_SYSCREG_PAD_EBIA1CLE (LPC313X_SYSCREG_VBASE+LPC313X_SYSCREG_PAD_EBIA1CLE_OFFSET) -#define LPC313X_SYSCREG_PAD_EBINCASBLOUT0 (LPC313X_SYSCREG_VBASE+LPC313X_SYSCREG_PAD_EBINCASBLOUT0_OFFSET) -#define LPC313X_SYSCREG_PAD_NANDNCS3 (LPC313X_SYSCREG_VBASE+LPC313X_SYSCREG_PAD_NANDNCS3_OFFSET) -#define LPC313X_SYSCREG_PAD_MLCDDB0 (LPC313X_SYSCREG_VBASE+LPC313X_SYSCREG_PAD_MLCDDB0_OFFSET) -#define LPC313X_SYSCREG_PAD_EBIDQM0NOE (LPC313X_SYSCREG_VBASE+LPC313X_SYSCREG_PAD_EBIDQM0NOE_OFFSET) -#define LPC313X_SYSCREG_PAD_EBID0 (LPC313X_SYSCREG_VBASE+LPC313X_SYSCREG_PAD_EBID0_OFFSET) -#define LPC313X_SYSCREG_PAD_EBID1 (LPC313X_SYSCREG_VBASE+LPC313X_SYSCREG_PAD_EBID1_OFFSET) -#define LPC313X_SYSCREG_PAD_EBID2 (LPC313X_SYSCREG_VBASE+LPC313X_SYSCREG_PAD_EBID2_OFFSET) -#define LPC313X_SYSCREG_PAD_EBID3 (LPC313X_SYSCREG_VBASE+LPC313X_SYSCREG_PAD_EBID3_OFFSET) -#define LPC313X_SYSCREG_PAD_EBID5 (LPC313X_SYSCREG_VBASE+LPC313X_SYSCREG_PAD_EBID5_OFFSET) -#define LPC313X_SYSCREG_PAD_EBID6 (LPC313X_SYSCREG_VBASE+LPC313X_SYSCREG_PAD_EBID6_OFFSET) -#define LPC313X_SYSCREG_PAD_EBID7 (LPC313X_SYSCREG_VBASE+LPC313X_SYSCREG_PAD_EBID7_OFFSET) -#define LPC313X_SYSCREG_PAD_EBID8 (LPC313X_SYSCREG_VBASE+LPC313X_SYSCREG_PAD_EBID8_OFFSET) -#define LPC313X_SYSCREG_PAD_EBID15 (LPC313X_SYSCREG_VBASE+LPC313X_SYSCREG_PAD_EBID15_OFFSET) -#define LPC313X_SYSCREG_PAD_I2STXDATA1 (LPC313X_SYSCREG_VBASE+LPC313X_SYSCREG_PAD_I2STXDATA1_OFFSET) -#define LPC313X_SYSCREG_PAD_I2STXBCK1 (LPC313X_SYSCREG_VBASE+LPC313X_SYSCREG_PAD_I2STXBCK1_OFFSET) -#define LPC313X_SYSCREG_PAD_I2STXWS1 (LPC313X_SYSCREG_VBASE+LPC313X_SYSCREG_PAD_I2STXWS1_OFFSET) -#define LPC313X_SYSCREG_PAD_I2SRXDATA0 (LPC313X_SYSCREG_VBASE+LPC313X_SYSCREG_PAD_I2SRXDATA0_OFFSET) -#define LPC313X_SYSCREG_PAD_I2SRXWS0 (LPC313X_SYSCREG_VBASE+LPC313X_SYSCREG_PAD_I2SRXWS0_OFFSET) -#define LPC313X_SYSCREG_PAD_I2SRXDATA1 (LPC313X_SYSCREG_VBASE+LPC313X_SYSCREG_PAD_I2SRXDATA1_OFFSET) -#define LPC313X_SYSCREG_PAD_I2SRXBCK1 (LPC313X_SYSCREG_VBASE+LPC313X_SYSCREG_PAD_I2SRXBCK1_OFFSET) -#define LPC313X_SYSCREG_PAD_I2SRXWS1 (LPC313X_SYSCREG_VBASE+LPC313X_SYSCREG_PAD_I2SRXWS1_OFFSET) -#define LPC313X_SYSCREG_PAD_SYSCLKO (LPC313X_SYSCREG_VBASE+LPC313X_SYSCREG_PAD_SYSCLKO_OFFSET) -#define LPC313X_SYSCREG_PAD_PWMDATA (LPC313X_SYSCREG_VBASE+LPC313X_SYSCREG_PAD_PWMDATA_OFFSET) -#define LPC313X_SYSCREG_PAD_UARTRXD (LPC313X_SYSCREG_VBASE+LPC313X_SYSCREG_PAD_UARTRXD_OFFSET) -#define LPC313X_SYSCREG_PAD_UARTTXD (LPC313X_SYSCREG_VBASE+LPC313X_SYSCREG_PAD_UARTTXD_OFFSET) -#define LPC313X_SYSCREG_PAD_I2CSDA1 (LPC313X_SYSCREG_VBASE+LPC313X_SYSCREG_PAD_I2CSDA1_OFFSET) -#define LPC313X_SYSCREG_PAD_I2CSCL1 (LPC313X_SYSCREG_VBASE+LPC313X_SYSCREG_PAD_I2CSCL1_OFFSET) -#define LPC313X_SYSCREG_PAD_CLK256FSO (LPC313X_SYSCREG_VBASE+LPC313X_SYSCREG_PAD_CLK256FSO_OFFSET) -#define LPC313X_SYSCREG_PAD_GPIO0 (LPC313X_SYSCREG_VBASE+LPC313X_SYSCREG_PAD_GPIO0_OFFSET) -#define LPC313X_SYSCREG_PAD_GPIO2 (LPC313X_SYSCREG_VBASE+LPC313X_SYSCREG_PAD_GPIO2_OFFSET) -#define LPC313X_SYSCREG_PAD_GPIO3 (LPC313X_SYSCREG_VBASE+LPC313X_SYSCREG_PAD_GPIO3_OFFSET) -#define LPC313X_SYSCREG_PAD_GPIO4 (LPC313X_SYSCREG_VBASE+LPC313X_SYSCREG_PAD_GPIO4_OFFSET) -#define LPC313X_SYSCREG_PAD_GPIO11 (LPC313X_SYSCREG_VBASE+LPC313X_SYSCREG_PAD_GPIO11_OFFSET) -#define LPC313X_SYSCREG_PAD_GPIO12 (LPC313X_SYSCREG_VBASE+LPC313X_SYSCREG_PAD_GPIO12_OFFSET) -#define LPC313X_SYSCREG_PAD_GPIO13 (LPC313X_SYSCREG_VBASE+LPC313X_SYSCREG_PAD_GPIO13_OFFSET) -#define LPC313X_SYSCREG_PAD_GPIO14 (LPC313X_SYSCREG_VBASE+LPC313X_SYSCREG_PAD_GPIO14_OFFSET) -#define LPC313X_SYSCREG_PAD_GPIO15 (LPC313X_SYSCREG_VBASE+LPC313X_SYSCREG_PAD_GPIO15_OFFSET) -#define LPC313X_SYSCREG_PAD_GPIO16 (LPC313X_SYSCREG_VBASE+LPC313X_SYSCREG_PAD_GPIO16_OFFSET) -#define LPC313X_SYSCREG_PAD_GPIO17 (LPC313X_SYSCREG_VBASE+LPC313X_SYSCREG_PAD_GPIO17_OFFSET) -#define LPC313X_SYSCREG_PAD_GPIO18 (LPC313X_SYSCREG_VBASE+LPC313X_SYSCREG_PAD_GPIO18_OFFSET) -#define LPC313X_SYSCREG_PAD_GPIO19 (LPC313X_SYSCREG_VBASE+LPC313X_SYSCREG_PAD_GPIO19_OFFSET) -#define LPC313X_SYSCREG_PAD_GPIO20 (LPC313X_SYSCREG_VBASE+LPC313X_SYSCREG_PAD_GPIO20_OFFSET) -#define LPC313X_SYSCREG_PAD_SPIMISO (LPC313X_SYSCREG_VBASE+LPC313X_SYSCREG_PAD_SPIMISO_OFFSET) -#define LPC313X_SYSCREG_PAD_SPIMOSI (LPC313X_SYSCREG_VBASE+LPC313X_SYSCREG_PAD_SPIMOSI_OFFSET) -#define LPC313X_SYSCREG_PAD_SPICSIN (LPC313X_SYSCREG_VBASE+LPC313X_SYSCREG_PAD_SPICSIN_OFFSET) -#define LPC313X_SYSCREG_PAD_SPISCK (LPC313X_SYSCREG_VBASE+LPC313X_SYSCREG_PAD_SPISCK_OFFSET) -#define LPC313X_SYSCREG_PAD_SPICSOUT0 (LPC313X_SYSCREG_VBASE+LPC313X_SYSCREG_PAD_SPICSOUT0_OFFSET) -#define LPC313X_SYSCREG_PAD_NANDNCS0 (LPC313X_SYSCREG_VBASE+LPC313X_SYSCREG_PAD_NANDNCS0_OFFSET) -#define LPC313X_SYSCREG_PAD_NANDNCS1 (LPC313X_SYSCREG_VBASE+LPC313X_SYSCREG_PAD_NANDNCS1_OFFSET) -#define LPC313X_SYSCREG_PAD_NANDNCS2 (LPC313X_SYSCREG_VBASE+LPC313X_SYSCREG_PAD_NANDNCS2_OFFSET) -#define LPC313X_SYSCREG_PAD_MLCDCSB (LPC313X_SYSCREG_VBASE+LPC313X_SYSCREG_PAD_MLCDCSB_OFFSET) -#define LPC313X_SYSCREG_PAD_MLCDDB1 (LPC313X_SYSCREG_VBASE+LPC313X_SYSCREG_PAD_MLCDDB1_OFFSET) -#define LPC313X_SYSCREG_PAD_MLCDERD (LPC313X_SYSCREG_VBASE+LPC313X_SYSCREG_PAD_MLCDERD_OFFSET) -#define LPC313X_SYSCREG_PAD_MLCDRS (LPC313X_SYSCREG_VBASE+LPC313X_SYSCREG_PAD_MLCDRS_OFFSET) -#define LPC313X_SYSCREG_PAD_MLCDRWWR (LPC313X_SYSCREG_VBASE+LPC313X_SYSCREG_PAD_MLCDRWWR_OFFSET) -#define LPC313X_SYSCREG_PAD_MLCDDB3 (LPC313X_SYSCREG_VBASE+LPC313X_SYSCREG_PAD_MLCDDB3_OFFSET) -#define LPC313X_SYSCREG_PAD_MLCDDB5 (LPC313X_SYSCREG_VBASE+LPC313X_SYSCREG_PAD_MLCDDB5_OFFSET) -#define LPC313X_SYSCREG_PAD_MLCDDB6 (LPC313X_SYSCREG_VBASE+LPC313X_SYSCREG_PAD_MLCDDB6_OFFSET) -#define LPC313X_SYSCREG_PAD_MLCDDB8 (LPC313X_SYSCREG_VBASE+LPC313X_SYSCREG_PAD_MLCDDB8_OFFSET) -#define LPC313X_SYSCREG_PAD_MLCDDB9 (LPC313X_SYSCREG_VBASE+LPC313X_SYSCREG_PAD_MLCDDB9_OFFSET) -#define LPC313X_SYSCREG_PAD_MLCDDB10 (LPC313X_SYSCREG_VBASE+LPC313X_SYSCREG_PAD_MLCDDB10_OFFSET) -#define LPC313X_SYSCREG_PAD_MLCDDB11 (LPC313X_SYSCREG_VBASE+LPC313X_SYSCREG_PAD_MLCDDB11_OFFSET) -#define LPC313X_SYSCREG_PAD_MLCDDB12 (LPC313X_SYSCREG_VBASE+LPC313X_SYSCREG_PAD_MLCDDB12_OFFSET) -#define LPC313X_SYSCREG_PAD_MLCDDB13 (LPC313X_SYSCREG_VBASE+LPC313X_SYSCREG_PAD_MLCDDB13_OFFSET) -#define LPC313X_SYSCREG_PAD_MLCDDB14 (LPC313X_SYSCREG_VBASE+LPC313X_SYSCREG_PAD_MLCDDB14_OFFSET) -#define LPC313X_SYSCREG_PAD_MLCDDB15 (LPC313X_SYSCREG_VBASE+LPC313X_SYSCREG_PAD_MLCDDB15_OFFSET) -#define LPC313X_SYSCREG_PAD_MGPIO5 (LPC313X_SYSCREG_VBASE+LPC313X_SYSCREG_PAD_MGPIO5_OFFSET) -#define LPC313X_SYSCREG_PAD_MGPIO7 (LPC313X_SYSCREG_VBASE+LPC313X_SYSCREG_PAD_MGPIO7_OFFSET) -#define LPC313X_SYSCREG_PAD_MGPIO8 (LPC313X_SYSCREG_VBASE+LPC313X_SYSCREG_PAD_MGPIO8_OFFSET) -#define LPC313X_SYSCREG_PAD_MGPIO10 (LPC313X_SYSCREG_VBASE+LPC313X_SYSCREG_PAD_MGPIO10_OFFSET) -#define LPC313X_SYSCREG_PAD_MNANDRYBN1 (LPC313X_SYSCREG_VBASE+LPC313X_SYSCREG_PAD_MNANDRYBN1_OFFSET) -#define LPC313X_SYSCREG_PAD_MNANDRYBN2 (LPC313X_SYSCREG_VBASE+LPC313X_SYSCREG_PAD_MNANDRYBN2_OFFSET) -#define LPC313X_SYSCREG_PAD_MNANDRYBN3 (LPC313X_SYSCREG_VBASE+LPC313X_SYSCREG_PAD_MNANDRYBN3_OFFSET) -#define LPC313X_SYSCREG_PAD_MUARTCTSN (LPC313X_SYSCREG_VBASE+LPC313X_SYSCREG_PAD_MUARTCTSN_OFFSET) -#define LPC313X_SYSCREG_PAD_MI2STXDATA0 (LPC313X_SYSCREG_VBASE+LPC313X_SYSCREG_PAD_MI2STXDATA0_OFFSET) -#define LPC313X_SYSCREG_PAD_MI2STXWS0 (LPC313X_SYSCREG_VBASE+LPC313X_SYSCREG_PAD_MI2STXWS0_OFFSET) -#define LPC313X_SYSCREG_PAD_EBINRASBLOUT1 (LPC313X_SYSCREG_VBASE+LPC313X_SYSCREG_PAD_EBINRASBLOUT1_OFFSET) -#define LPC313X_SYSCREG_PAD_EBIA0ALE (LPC313X_SYSCREG_VBASE+LPC313X_SYSCREG_PAD_EBIA0ALE_OFFSET) -#define LPC313X_SYSCREG_PAD_EBINWE (LPC313X_SYSCREG_VBASE+LPC313X_SYSCREG_PAD_EBINWE_OFFSET) -#define LPC313X_SYSCREG_PAD_ESHCTRLSUP4 (LPC313X_SYSCREG_VBASE+LPC313X_SYSCREG_PAD_ESHCTRLSUP4_OFFSET) -#define LPC313X_SYSCREG_PAD_ESHCTRLSUP8 (LPC313X_SYSCREG_VBASE+LPC313X_SYSCREG_PAD_ESHCTRLSUP8_OFFSET) - -/* SYSCREG register bit definitions *********************************************************************/ -/* Miscellaneous system configuration registers, part1 */ - -/* SYSCREG_EBIMPMCPRIO, address 0x13002808 - * SYSCREG_EBINANDCPRIO address 0x1300280c - * SYSCREG_EBIUNUSEDPRIO address 0x13002810 - */ - -#define SYSCREG_EBI_TIMEOUT_SHIFT (0) /* Bits 0-9: Time MPMC, NAND or unused channel */ -#define SYSCREG_EBI_TIMEOUT_MASK (0x3ff << SYSCREG_EBI_TIMEOUT_SHIFT) - -/* RINGOSCCFG address 0x13002814 */ - -#define SYSCREG_RINGOSCCFG_OSC1EN (1 << 1) /* Bit 1: Enable ring oscillator 1 */ -#define SYSCREG_RINGOSCCFG_OSC0EN (1 << 0) /* Bit 0: Enable oscillator 0 */ - -/* SYSCREG_ADCPDADC10BITS address 0x13002818 */ - -#define SYSCREG_ADCPDADC10BITS_PWRDOWN (1 << 0) /* Bit 0: Power down ADC */ - -/* SYSCREG_ABCCFG address 0x13002824 */ - -#define SYSCREG_ABCCFG_USBOTG_SHIFT (9) /* Bits 9-11: USB_OTG AHB bus bandwidth control */ -#define SYSCREG_ABCCFG_USBOTG_MASK (7 << SYSCREG_ABCCFG_USBOTG_SHIFT) -# define SYSCREG_ABCCFG_USBOTG_NORMAL (0 << SYSCREG_ABCCFG_USBOTG_SHIFT) /* Normal mode */ -# define SYSCREG_ABCCFG_USBOTG_NONSEQ (1 << SYSCREG_ABCCFG_USBOTG_SHIFT) /* Make non-sequential */ -# define SYSCREG_ABCCFG_USBOTG_SPLIT4 (2 << SYSCREG_ABCCFG_USBOTG_SHIFT) /* Split to 4-beat */ -# define SYSCREG_ABCCFG_USBOTG_SPLIT8 (3 << SYSCREG_ABCCFG_USBOTG_SHIFT) /* Split to 8-beat */ -# define SYSCREG_ABCCFG_USBOTG_EXT8 (4 << SYSCREG_ABCCFG_USBOTG_SHIFT) /* Extend to 8-beat */ -# define SYSCREG_ABCCFG_USBOTG_EXT16 (5 << SYSCREG_ABCCFG_USBOTG_SHIFT) /* Extend to 16-beat */ -# define SYSCREG_ABCCFG_USBOTG_SPLIT4W (6 << SYSCREG_ABCCFG_USBOTG_SHIFT) /* Split to 4-beat */ -# define SYSCREG_ABCCFG_USBOTG_EXT32 (7 << SYSCREG_ABCCFG_USBOTG_SHIFT) /* extend to 32-beat */ -#define SYSCREG_ABCCFG_ARM926EJSI_SHIFT (6) /* Bits 6-8: ARM926EJS instruction AHB bus bandwidth control */ -#define SYSCREG_ABCCFG_ARM926EJSI_MASK (7 << SYSCREG_ABCCFG_ARM926EJSI_SHIFT) -# define SYSCREG_ABCCFG_ARM926EJSI_NORMAL (0 << SYSCREG_ABCCFG_ARM926EJSI_SHIFT) /* Normal mode */ -# define SYSCREG_ABCCFG_ARM926EJSI_NONSEQ (1 << SYSCREG_ABCCFG_ARM926EJSI_SHIFT) /* Make non-sequential */ -# define SYSCREG_ABCCFG_ARM926EJSI_SPLIT4 (2 << SYSCREG_ABCCFG_ARM926EJSI_SHIFT) /* Split to 4-beat */ -# define SYSCREG_ABCCFG_ARM926EJSI_SPLIT8 (3 << SYSCREG_ABCCFG_ARM926EJSI_SHIFT) /* Split to 8-beat */ -# define SYSCREG_ABCCFG_ARM926EJSI_EXT8 (4 << SYSCREG_ABCCFG_ARM926EJSI_SHIFT) /* Extend to 8-beat */ -# define SYSCREG_ABCCFG_ARM926EJSI_EXT16 (5 << SYSCREG_ABCCFG_ARM926EJSI_SHIFT) /* Extend to 16-beat */ -# define SYSCREG_ABCCFG_ARM926EJSI_SPLIT4W (6 << SYSCREG_ABCCFG_ARM926EJSI_SHIFT) /* Split to 4-beat */ -# define SYSCREG_ABCCFG_ARM926EJSI_EXT32 (7 << SYSCREG_ABCCFG_ARM926EJSI_SHIFT) /* extend to 32-beat */ -#define SYSCREG_ABCCFG_ARM926EJSD_SHIFT (3) /* Bits 3-5: ARM926EJS data AHB bus bandwidth control */ -#define SYSCREG_ABCCFG_ARM926EJSD_MASK (7 << SYSCREG_ABCCFG_ARM926EJSD_SHIFT) -# define SYSCREG_ABCCFG_ARM926EJSD_NORMAL (0 << SYSCREG_ABCCFG_ARM926EJSD_SHIFT) /* Normal mode */ -# define SYSCREG_ABCCFG_ARM926EJSD_NONSEQ (1 << SYSCREG_ABCCFG_ARM926EJSD_SHIFT) /* Make non-sequential */ -# define SYSCREG_ABCCFG_ARM926EJSD_SPLIT4 (2 << SYSCREG_ABCCFG_ARM926EJSD_SHIFT) /* Split to 4-beat */ -# define SYSCREG_ABCCFG_ARM926EJSD_SPLIT8 (3 << SYSCREG_ABCCFG_ARM926EJSD_SHIFT) /* Split to 8-beat */ -# define SYSCREG_ABCCFG_ARM926EJSD_EXT8 (4 << SYSCREG_ABCCFG_ARM926EJSD_SHIFT) /* Extend to 8-beat */ -# define SYSCREG_ABCCFG_ARM926EJSD_EXT16 (5 << SYSCREG_ABCCFG_ARM926EJSD_SHIFT) /* Extend to 16-beat */ -# define SYSCREG_ABCCFG_ARM926EJSD_SPLIT4W (6 << SYSCREG_ABCCFG_ARM926EJSD_SHIFT) /* Split to 4-beat */ -# define SYSCREG_ABCCFG_ARM926EJSD_EXT32 (7 << SYSCREG_ABCCFG_ARM926EJSD_SHIFT) /* extend to 32-beat */ -#define SYSCREG_ABCCFG_DMA_SHIFT (0) /* Bits 0-2: 2:0 DMA AHB bus bandwidth control */ -#define SYSCREG_ABCCFG_DMA_MASK (7 << SYSCREG_ABCCFG_DMA_SHIFT) -# define SYSCREG_ABCCFG_DMA_NORMAL (0 << SYSCREG_ABCCFG_DMA_SHIFT) /* Normal mode */ -# define SYSCREG_ABCCFG_DMA_NONSEQ (1 << SYSCREG_ABCCFG_DMA_SHIFT) /* Make non-sequential */ -# define SYSCREG_ABCCFG_DMA_SPLIT4 (2 << SYSCREG_ABCCFG_DMA_SHIFT) /* Split to 4-beat */ -# define SYSCREG_ABCCFG_DMA_SPLIT8 (3 << SYSCREG_ABCCFG_DMA_SHIFT) /* Split to 8-beat */ -# define SYSCREG_ABCCFG_DMA_EXT8 (4 << SYSCREG_ABCCFG_DMA_SHIFT) /* Extend to 8-beat */ -# define SYSCREG_ABCCFG_DMA_EXT16 (5 << SYSCREG_ABCCFG_DMA_SHIFT) /* Extend to 16-beat */ -# define SYSCREG_ABCCFG_DMA_SPLIT4W (6 << SYSCREG_ABCCFG_DMA_SHIFT) /* Split to 4-beat */ -# define SYSCREG_ABCCFG_DMA_EXT32 (7 << SYSCREG_ABCCFG_DMA_SHIFT) /* extend to 32-beat */ - -/* SYSCREG_SDMMCCFG address 0x13002828 */ - -#define SYSCREG_SDMMCCFG_CARDDETECT (1 << 1) /* Bit 1: Card detect signal */ -#define SYSCREG_SDMMCCFG_CARDWRITEPRT (1 << 0) /* Bit 0: Card write protect signal for SD cards */ - -/* SYSCREG_MCIDELAYMODES address 0x1300282c */ - -#define SYSCREG_MCIDELAYMODES_DELAYENABLE (1 << 4) /* Bit 4: Enable delay cells */ -#define SYSCREG_MCIDELAYMODES_DELAYCELLS_SHIFT (0) /* Bits 0-3: Number of delay cells needed */ -#define SYSCREG_MCIDELAYMODES_DELAYCELLS_MASK (15 << SYSCREG_MCIDELAYMODES_DELAYCELLS_SHIFT) - -/* USB configuration registers */ -/* USB_ATXPLLPDREG address 0x13002830 */ - -#define SYSCREG_USB_ATXPLLPDREG_PWRDOWN (1 << 0) /* Bit 0: Powerdown */ - -/* USB_OTGCFG address 0x13002834 */ - -#define SYSCREG_USB_OTGCFG_VBUSPWRFAULT (1 << 3) /* Bit 3: Charge pump overcurrent */ -#define SYSCREG_USB_OTGCFG_DEVWAKEUP (1 << 2) /* Bit 2: External wakeup (device mode) */ -#define SYSCREG_USB_OTGCFG_HOSTWAKEUP (1 << 1) /* Bit 1: External wake-up (host mode) */ - -/* USB_OTGPORTINDCTL address 0x1300 2838 */ - -#define SYSCREG_USB_OTGPORTINDCTL_SHIFT (0) /* Bits 0-1: Status bits for USB connector LEDs */ -#define SYSCREG_USB_OTGPORTINDCTL_MASK (3 << SYSCREG_USB_OTGPORTINDCTL_SHIFT) -# define SYSCREG_USB_OTGPORTINDCTL_OFF (0 << SYSCREG_USB_OTGPORTINDCTL_SHIFT) /* off */ -# define SYSCREG_USB_OTGPORTINDCTL_AMBER (1 << SYSCREG_USB_OTGPORTINDCTL_SHIFT) /* amber */ -# define SYSCREG_USB_OTGPORTINDCTL_GREEN (2 << SYSCREG_USB_OTGPORTINDCTL_SHIFT) /* green */ - -/* USB_PLLNDEC address 0x13002840 */ - -#define SYSCREG_USB_PLLNDEC_SHIFT (0) /* Bits 0-9: Pre-divider for the USB pll */ -#define SYSCREG_USB_PLLNDEC_MASK (0x3ff << SYSCREG_USB_PLLNDEC_SHIFT) - -/* USB_PLLMDEC address 0x13002844 */ - -#define SYSCREG_USB_PLLMDEC_SHIFT (0) /* Bits 0-16: Feedback-divider for the USB pll */ -#define SYSCREG_USB_PLLMDEC_MASK (0x1ffff << SYSCREG_USB_PLLMDEC_SHIFT) - -/* USB_PLLPDEC address 0x13002848 */ - -#define SYSCREG_USB_PLLPDEC_SHIFT (0) /* Bits 0-3: Feedback-divider for the USB pll */ -#define SYSCREG_USB_PLLPDEC_MASK (15 << SYSCREG_USB_PLLPDEC_SHIFT) - -/* USB_PLLSELR address 0x1300284c */ - -#define SYSCREG_USB_PLLSELR_SHIFT (0) /* Bits 0-3: Bandwidth selection */ -#define SYSCREG_USB_PLLSELR_MASK (15 << SYSCREG_USB_PLLSELR_SHIFT) - -/* USB_PLLSELI address 0x13002850 */ - -#define SYSCREG_USB_PLLSELI_SHIFT (0) /* Bits 0-3: Bandwidth selection */ -#define SYSCREG_USB_PLLSELI_MASK (15 << SYSCREG_USB_PLLSELI_SHIFT) - -/* USB_PLLSELP address 0x13002854 */ - -#define SYSCREG_USB_PLLSELP_SHIFT (0) /* Bits 0-3: Bandwidth selection */ -#define SYSCREG_USB_PLLSELP_MASK (15 << SYSCREG_USB_PLLSELP_SHIFT) - -/* ISRAM/ISROM configuration registers */ -/* SYSCREG_ISRAM0_LATENCYCFG address 0x13002858 */ - -#define SYSCREG_ISRAM0_LATENCYCFG_SHIFT (0) /* Bits 0-1: Number of waitstates */ -#define SYSCREG_ISRAM0_LATENCYCFG_MASK (3 << SYSCREG_ISRAM0_LATENCYCFG_SHIFT) - -/* SYSCREG_ISRAM1_LATENCYCFG address 0x1300285c */ - -#define SYSCREG_ISRAM1_LATENCYCFG_SHIFT (0) /* Bits 0-1: Number of waitstates */ -#define SYSCREG_ISRAM1_LATENCYCFG_MASK (3 << SYSCREG_ISRAM1_LATENCYCFG_SHIFT) - -/* SYSCREG_ISROM_LATENCYCFG address 0x13002860 */ - -#define SYSCREG_ISROM_LATENCYCFG_SHIFT (0) /* Bits 0-1: Number of waitstates */ -#define SYSCREG_ISROM_LATENCYCFG_MASK (3 << SYSCREG_ISROM_LATENCYCFG_SHIFT) - -/* MPMC configuration registers */ -/* SYSCREG_AHB_MPMC_MISC (address 0x13002864 */ - -#define SYSCREG_MPMC_MISC_REL1CONFIG (1 << 8) /* Bit 8: Static memory address mode select */ -#define SYSCREG_MPMC_MISC_STCS1PB (1 << 7) /* Bit 7: Polarity of byte lane select for static memory CS1 */ -#define SYSCREG_MPMC_MISC_STCS1POL (1 << 4) /* Bit 4: Polarity of static memory CS1 */ -#define SYSCREG_MPMC_MISC_STCS0POL (1 << 3) /* Bit 3: Polarity of static memory CS0 */ -#define SYSCREG_MPMC_MISC_SREFREQ (1 << 0) /* Bit 0: Self refresh request */ - -/* SYSCREG_MPMC_DELAYMODES address 0x13002868 */ - -#define SYSCREG_MPMC_DELAYMODES_DEL1_SHIFT (12) /* Bits 12-17: Delay cells for MPMCCLKOUT */ -#define SYSCREG_MPMC_DELAYMODES_DEL1_MASK (63 << SYSCREG_MPMC_DELAYMODES_DEL1_SHIFT) -#define SYSCREG_MPMC_DELAYMODES_DEL2_SHIFT (6) /* Bits 6-11: Delay cells between MPMCCLK and MPMCCLKDELAY */ -#define SYSCREG_MPMC_DELAYMODES_DEL2_MASK (63 << SYSCREG_MPMC_DELAYMODES_DEL2_SHIFT) -#define SYSCREG_MPMC_DELAYMODES_DEL3_SHIFT (0) /* Bits 0-5: Delay cells between MPMCCLK and MPMCFBCLKIN */ -#define SYSCREG_MPMC_DELAYMODES_DEL3_MASK (63 << SYSCREG_MPMC_DELAYMODES_DEL3_SHIFT) - -/* SYSCREG_MPMC_WAITRD0 address 0x1300286c */ - -#define SYSCREG_MPMC_WAITRD0_EXTRAOE (1 << 5) /* Bit 5: Enable the extra inactive OE cycle */ -#define SYSCREG_MPMC_WAITRD0_SHIFT (0) /* Bits 0-4: Value for MPMCStaticWaitRd0 */ -#define SYSCREG_MPMC_WAITRD0_MASK (31 << SYSCREG_MPMC_WAITRD0_SHIFT) - -/* SYSCREG_MPMC_WAITRD1 address 0x13002870 */ - -#define SYSCREG_MPMC_WAITRD1_EXTRAOE (1 << 5) /* Bit 5: Enable the extra inactive OE cycle */ -#define SYSCREG_MPMC_WAITRD1_SHIFT (0) /* Bits 0-4: Value for MPMCStaticWaitRd1 */ -#define SYSCREG_MPMC_WAITRD1_MASK (31 << SYSCREG_MPMC_WAITRD1_SHIFT) - -/* SYSCREG_WIR_EBIMSINIT address 0x13002874 */ - -#define SYSCREG_MPMC_WIREEBIMSZ_SHIFT (0) /* Bits 0-1: Memory width of CS1 */ -#define SYSCREG_MPMC_WIREEBIMSZ_MASK (3 << SYSCREG_MPMC_WIREEBIMSZ_SHIFT) - -/* MPMC_TESTMODE0 address 0x13002878 */ - -#define SYSCREG_MPMC_TESTMODE0_EXTREFENABLE (1 << 12) /* Bit 13: External refresh of MPMC */ -#define SYSCREG_MPMC_TESTMODE0_EXTREFCNT_SHIFT (0) /* Bits 0-11: Period of external refresh */ -#define SYSCREG_MPMC_TESTMODE0_EXTREFCNT_MASK (0xfff << SYSCREG_MPMC_TESTMODE0_EXTREFCNT_SHIFT) - -/* MPMC_TESTMODE1 address 0x1300287c */ - -#define SYSCREG_MPMC_TESTMODE1_HSENABLE_SHIFT (0) /* Bits 0-7: Allows AHB to run faster while refreshing */ -#define SYSCREG_MPMC_TESTMODE1_HSENABLE_MASK (0xff << SYSCREG_MPMC_TESTMODE1_HSENABLE_SHIFT) - -/* Miscellaneous system configuration registers, part 2 */ -/* AHB0EXTPRIO address 0x13002880 */ - -#define SYSCREG_AHB0EXTPRIO_USBOTG (1 << 3) /* Bit 3: USBOTG has higher priority */ -#define SYSCREG_AHB0EXTPRIO_ARM926DATA (1 << 2) /* Bit 2: ARM926 Data has higher priority */ -#define SYSCREG_AHB0EXTPRIO_ARM926NSTR (1 << 1) /* Bit 1: ARM926 Instruction has higher priority */ -#define SYSCREG_AHB0EXTPRIO_DMA (1 << 0) /* Bit 0: DMA has higher priority */ - -/* Pin multiplexing control registers */ -/* SYSCREG_MUX_LCDEBISEL address 0x13002890 */ - -#define SYSCREG_MUX_LCDEBISEL_EBIMPMC (1 << 0) /* Bit 0: Selects between LCD and EBI/MPMC pins */ - -/* SYSCREG_MUX_GPIOMCISEL address 0x13002894 */ - -#define SYSCREG_MUX_GPIOMCISEL_MCI (1 << 0) /* Bit 0: Selects between GPIO and MCI pins */ - -/* SYSCREG_MUX_NANDMCISEL address 0x13002898 */ - -#define SYSCREG_MUX_NANDMCISEL_MCI (1 << 0) /* Bit 0: Selects between NAND and MCI pins */ - -/* SYSCREG_MUX_UARTSPISEL address 0x1300289c */ - -#define SYSCREG_MUX_UARTSPISEL_SPI (1 << 0) /* Bit 0: Selects between SPI and UART pins */ - -/* SYSCREG_MUX_I2STXIPCMSEL address 0x130028a0 */ - -#define SYSCREG_MUX_I2STXPCMSEL_PCM (1 << 0) /* Bit 0: Selects between I2STX_0 and IPINT_1 pins */ - -/* Pad configuration registers */ -/* SYSCREG_PAD_padname addresses 0x130028a4 to 0x13002a28 */ - -#define SYSCREG_PAD_P2 (1 << 1) /* Bit 1: The logic pin p2 of the pad */ -#define SYSCREG_PAD_P1 (1 << 0) /* Bit 0: The logic pin p1 of the pad */ -#define SYSCREG_PAD_PULLUP (0) -#define SYSCREG_PAD_INPUT (SYSCREG_PAD_P2) -#define SYSCREG_PAD_REPEATER (SYSCREG_PAD_P1) -#define SYSCREG_PAD_WEAKPULLUP (SYSCREG_PAD_P1|SYSCREG_PAD_P2) - -/* SYSCREG_ESHCTRLSUP4 address 0x13002a2c */ - -#define SYSCREG_PAD_ESHCTRLSUP4_LESS (1 << 0) /* Bit 0: Domain SUP4 less switching noise */ - -/* SYSCREG_ESHCTRLSUP8 address 0x13002a2c */ - -#define SYSCREG_PAD_ESHCTRLSUP8_LESS (1 << 0) /* Bit 0: Domain SUP8 switching less noise */ -/******************************************************************************************************** - * Public Types - ********************************************************************************************************/ - -/******************************************************************************************************** - * Public Data - ********************************************************************************************************/ - -/******************************************************************************************************** - * Public Functions - ********************************************************************************************************/ - -#endif /* __ARCH_ARM_SRC_LPC313X_SYSCREG_H */ diff --git a/nuttx/arch/arm/src/lpc313x/lpc313x_timer.h b/nuttx/arch/arm/src/lpc313x/lpc313x_timer.h deleted file mode 100755 index 528ea4f06..000000000 --- a/nuttx/arch/arm/src/lpc313x/lpc313x_timer.h +++ /dev/null @@ -1,119 +0,0 @@ -/************************************************************************************************ - * arch/arm/src/lpc313x/lpc313x_timer.h - * - * Copyright (C) 2009-2010 Gregory Nutt. All rights reserved. - * Author: Gregory Nutt - * - * 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_LPC313X_TIMER_H -#define __ARCH_ARM_SRC_LPC313X_TIMER_H - -/************************************************************************************************ - * Included Files - ************************************************************************************************/ - -#include -#include "lpc313x_memorymap.h" - -/************************************************************************************************ - * Pre-processor Definitions - ************************************************************************************************/ - -/* TIMER register base address offset into the APB1 domain **************************************/ - -#define LPC313X_TIMER0_VBASE (LPC313X_APB1_VADDR+LPC313X_APB1_TIMER0_OFFSET) -#define LPC313X_TIMER0_PBASE (LPC313X_APB1_PADDR+LPC313X_APB1_TIMER0_OFFSET) - -#define LPC313X_TIMER1_VBASE (LPC313X_APB1_VADDR+LPC313X_APB1_TIMER1_OFFSET) -#define LPC313X_TIMER1_PBASE (LPC313X_APB1_PADDR+LPC313X_APB1_TIMER1_OFFSET) - -#define LPC313X_TIMER2_VBASE (LPC313X_APB1_VADDR+LPC313X_APB1_TIMER2_OFFSET) -#define LPC313X_TIMER2_PBASE (LPC313X_APB1_PADDR+LPC313X_APB1_TIMER2_OFFSET) - -#define LPC313X_TIMER3_VBASE (LPC313X_APB1_VADDR+LPC313X_APB1_TIMER3_OFFSET) -#define LPC313X_TIMER3_PBASE (LPC313X_APB1_PADDR+LPC313X_APB1_TIMER3_OFFSET) - -/* TIMER register offsets (with respect to the TIMERn base) *************************************/ - -#define LPC313X_TIMER_LOAD_OFFSET 0x00 /* Timer reload value */ -#define LPC313X_TIMER_VALUE_OFFSET 0x04 /* Current timer value */ -#define LPC313X_TIMER_CTRL_OFFSET 0x08 /* Timer nable/disable and pre-scale */ -#define LPC313X_TIMER_CLEAR_OFFSET 0x0c /* Clear timer interrupt */ - -/* TIMER register (virtual) addresses ***********************************************************/ - -#define LPC313X_TIMER0_LOAD (LPC313X_TIMER0_VBASE+LPC313X_TIMER_LOAD_OFFSET) -#define LPC313X_TIMER0_VALUE (LPC313X_TIMER0_VBASE+LPC313X_TIMER_VALUE_OFFSET) -#define LPC313X_TIMER0_CTRL (LPC313X_TIMER0_VBASE+LPC313X_TIMER_CTRL_OFFSET) -#define LPC313X_TIMER0_CLEAR (LPC313X_TIMER0_VBASE+LPC313X_TIMER_CLEAR_OFFSET) - -#define LPC313X_TIMER1_LOAD (LPC313X_TIMER1_VBASE+LPC313X_TIMER_LOAD_OFFSET) -#define LPC313X_TIMER1_VALUE (LPC313X_TIMER1_VBASE+LPC313X_TIMER_VALUE_OFFSET) -#define LPC313X_TIMER1_CTRL (LPC313X_TIMER1_VBASE+LPC313X_TIMER_CTRL_OFFSET) -#define LPC313X_TIMER1_CLEAR (LPC313X_TIMER1_VBASE+LPC313X_TIMER_CLEAR_OFFSET) - -#define LPC313X_TIMER2_LOAD (LPC313X_TIMER2_VBASE+LPC313X_TIMER_LOAD_OFFSET) -#define LPC313X_TIMER2_VALUE (LPC313X_TIMER2_VBASE+LPC313X_TIMER_VALUE_OFFSET) -#define LPC313X_TIMER2_CTRL (LPC313X_TIMER2_VBASE+LPC313X_TIMER_CTRL_OFFSET) -#define LPC313X_TIMER2_CLEAR (LPC313X_TIMER2_VBASE+LPC313X_TIMER_CLEAR_OFFSET) - -#define LPC313X_TIMER3_LOAD (LPC313X_TIMER3_VBASE+LPC313X_TIMER_LOAD_OFFSET) -#define LPC313X_TIMER3_VALUE (LPC313X_TIMER3_VBASE+LPC313X_TIMER_VALUE_OFFSET) -#define LPC313X_TIMER3_CTRL (LPC313X_TIMER3_VBASE+LPC313X_TIMER_CTRL_OFFSET) -#define LPC313X_TIMER3_CLEAR (LPC313X_TIMER3_VBASE+LPC313X_TIMER_CLEAR_OFFSET) - -/* TIMER register bit definitions ***************************************************************/ - -/* Timer Control register TIMER0_CTRL, address 0x13008008 TIMER1_CTRL, address 0x13008408 - * TIMER2_CTRL, address 0x13008808 TIMER3_CTRL, adddress 0x13008c08 - */ - -#define TIMER_CTRL_ENABLE (1 << 7) /* Bit 7: Timer enable */ -#define TIMER_CTRL_PERIODIC (1 << 6) /* Bit 6: Periodic timer mode */ -#define TIMER_CTRL_PRESCALE_SHIFT (2) /* Bits 2-3: Timer pre-scale */ -#define TIMER_CTRL_PRESCALE_MASK (3 << TIMER_CTRL_PRESCALE_SHIFT) -# define TIMER_CTRL_PRESCALE_DIV1 (0 << TIMER_CTRL_PRESCALE_SHIFT) /* Divider=1 Stages=0 */ -# define TIMER_CTRL_PRESCALE_DIV16 (1 << TIMER_CTRL_PRESCALE_SHIFT) /* Divider=16 Stages4 */ -# define TIMER_CTRL_PRESCALE_DIV256 (2 << TIMER_CTRL_PRESCALE_SHIFT) /* Divider=256 Stages=8 */ - -/************************************************************************************************ - * Public Types - ************************************************************************************************/ - -/************************************************************************************************ - * Public Data - ************************************************************************************************/ - -/************************************************************************************************ - * Public Functions - ************************************************************************************************/ - -#endif /* __ARCH_ARM_SRC_LPC313X_TIMER_H */ diff --git a/nuttx/arch/arm/src/lpc313x/lpc313x_timerisr.c b/nuttx/arch/arm/src/lpc313x/lpc313x_timerisr.c deleted file mode 100755 index 4893924ec..000000000 --- a/nuttx/arch/arm/src/lpc313x/lpc313x_timerisr.c +++ /dev/null @@ -1,162 +0,0 @@ -/**************************************************************************** - * arch/arm/src/lpc313x/lpc313x_timerisr.c - * - * Copyright (C) 2009 Gregory Nutt. All rights reserved. - * Author: Gregory Nutt - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name NuttX nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************/ - -/**************************************************************************** - * Included Files - ****************************************************************************/ - -#include - -#include -#include -#include - -#include -#include - -#include "clock_internal.h" -#include "up_internal.h" -#include "up_arch.h" - -#include "lpc313x_timer.h" -#include "lpc313x_internal.h" - -/**************************************************************************** - * Definitions - ****************************************************************************/ - -/**************************************************************************** - * 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. - * - ****************************************************************************/ - -int up_timerisr(int irq, uint32_t *regs) -{ - /* Clear the lattched timer interrupt (Writing any value to the CLEAR register - * clears the interrupt generated by the counter timer - */ - - putreg32(1, LPC313X_TIMER0_CLEAR); - - /* Process timer interrupt */ - - sched_process_timer(); - return 0; -} - -/**************************************************************************** - * Function: up_timerinit - * - * Description: - * This function is called during start-up to initialize - * the timer interrupt. - * - ****************************************************************************/ - -void up_timerinit(void) -{ - uint32_t regval; - uint64_t load; - uint64_t freq; - - /* Enable the timer0 system clock */ - - lpc313x_enableclock(CLKID_TIMER0PCLK); - - /* Soft reset the timer0 module so that we start in a known state */ - - lpc313x_softreset(RESETID_TIMER0RST); - - /* Set timer load register to 10mS (100Hz). First, get the frequency - * of the timer0 module clock (in the AHB0APB1_BASE domain (2)). - */ - - freq = (uint64_t)lpc313x_clkfreq(CLKID_TIMER0PCLK, DOMAINID_AHB0APB1); - - /* If the clock is >1MHz, use pre-dividers */ - - regval = getreg32(LPC313X_TIMER0_CTRL); - if (freq > 1000000) - { - /* Use the divide by 16 pre-divider */ - - regval &= ~TIMER_CTRL_PRESCALE_MASK; - regval |= TIMER_CTRL_PRESCALE_DIV16; - freq >>= 4; - } - - load =((freq * (uint64_t)10000) / 1000000); - putreg32((uint32_t)load, LPC313X_TIMER0_LOAD); - - /* Set periodic mode */ - - regval |= TIMER_CTRL_PERIODIC; - putreg32(regval, LPC313X_TIMER0_CTRL); - - /* Attach the timer interrupt vector */ - - (void)irq_attach(LPC313X_IRQ_TMR0, (xcpt_t)up_timerisr); - - /* Clear any latched timer interrupt (Writing any value to the CLEAR register - * clears the latched interrupt generated by the counter timer) - */ - - putreg32(1, LPC313X_TIMER0_CLEAR); - - /* Enable timers (starts counting) */ - - regval |= TIMER_CTRL_ENABLE; - putreg32(regval, LPC313X_TIMER0_CTRL); - - /* Enable timer match interrupts in the interrupt controller */ - - up_enable_irq(LPC313X_IRQ_TMR0); -} diff --git a/nuttx/arch/arm/src/lpc313x/lpc313x_uart.h b/nuttx/arch/arm/src/lpc313x/lpc313x_uart.h deleted file mode 100755 index f0c7aee2a..000000000 --- a/nuttx/arch/arm/src/lpc313x/lpc313x_uart.h +++ /dev/null @@ -1,263 +0,0 @@ -/************************************************************************************************ - * arch/arm/src/lpc313x/lpc313x_uart.h - * - * Copyright (C) 2009 Gregory Nutt. All rights reserved. - * Author: Gregory Nutt - * - * 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_LPC313X_UART_H -#define __ARCH_ARM_SRC_LPC313X_UART_H - -/************************************************************************************************ - * Included Files - ************************************************************************************************/ - -#include -#include "lpc313x_memorymap.h" - -/************************************************************************************************ - * Pre-processor Definitions - ************************************************************************************************/ - -/* UART register base address offset into the APB2 domain ***************************************/ - -#define LPC313X_UART_VBASE (LPC313X_APB2_VSECTION+LPC313X_APB2_UART_OFFSET) -#define LPC313X_UART_PBASE (LPC313X_APB2_PSECTION+LPC313X_APB2_UART_OFFSET) - -/* UART register offsets (with respect to the UART base) ****************************************/ - -#define LPC313X_UART_RBR_OFFSET 0x000 /* Receiver Buffer Register */ -#define LPC313X_UART_THR_OFFSET 0x000 /* Transmitter Holding Register */ -#define LPC313X_UART_DLL_OFFSET 0x000 /* Divisor Latch LSB */ -#define LPC313X_UART_DLM_OFFSET 0x004 /* Divisor Latch MSB */ -#define LPC313X_UART_IER_OFFSET 0x004 /* Interrupt Enable Register */ -#define LPC313X_UART_IIR_OFFSET 0x008 /* Interrupt Identification Register */ -#define LPC313X_UART_FCR_OFFSET 0x008 /* FIFO Control Register */ -#define LPC313X_UART_LCR_OFFSET 0x00c /* Line Control Register */ -#define LPC313X_UART_MCR_OFFSET 0x010 /* Modem Control Register */ -#define LPC313X_UART_LSR_OFFSET 0x014 /* Line Status Register */ -#define LPC313X_UART_MSR_OFFSET 0x018 /* Modem status Register */ -#define LPC313X_UART_SCR_OFFSET 0x01c /* Scratch Register */ - /* 0x020: Reserved */ -#define LPC313X_UART_ICR_OFFSET 0x024 /* IrDA Control Register */ -#define LPC313X_UART_FDR_OFFSET 0x028 /* Fractional Divider Register */ - /* 0x02c: Reserved */ -#define LPC313X_UART_POP_OFFSET 0x030 /* NHP Pop Register */ -#define LPC313X_UART_MODE_OFFSET 0x034 /* NHP Mode Selection Register */ - /* 0x038-0xfd4: Reserved */ -#define LPC313X_UART_INTCE_OFFSET 0xfd8 /* Interrupt Clear Enable Register */ -#define LPC313X_UART_INTSE_OFFSET 0xfdc /* Interrupt Set Enable Register */ -#define LPC313X_UART_INTS_OFFSET 0xfe0 /* Interrupt Status Register */ -#define LPC313X_UART_INTE_OFFSET 0xfe4 /* Interrupt Enable Register */ -#define LPC313X_UART_INTCS_OFFSET 0xfe8 /* Interrupt Clear Status Register */ -#define LPC313X_UART_INTSS_OFFSET 0xfec /* Interrupt Set Status Register */ - /* 0xff0-0xff8: Reserved */ - -/* UART register (virtual) addresses ************************************************************/ - -#define LPC313X_UART_RBR (LPC313X_UART_VBASE+LPC313X_UART_RBR_OFFSET) -#define LPC313X_UART_THR (LPC313X_UART_VBASE+LPC313X_UART_THR_OFFSET) -#define LPC313X_UART_DLL (LPC313X_UART_VBASE+LPC313X_UART_DLL_OFFSET) -#define LPC313X_UART_DLM (LPC313X_UART_VBASE+LPC313X_UART_DLM_OFFSET) -#define LPC313X_UART_IER (LPC313X_UART_VBASE+LPC313X_UART_IER_OFFSET) -#define LPC313X_UART_IIR (LPC313X_UART_VBASE+LPC313X_UART_IIR_OFFSET) -#define LPC313X_UART_FCR (LPC313X_UART_VBASE+LPC313X_UART_FCR_OFFSET) -#define LPC313X_UART_LCR (LPC313X_UART_VBASE+LPC313X_UART_LCR_OFFSET) -#define LPC313X_UART_MCR (LPC313X_UART_VBASE+LPC313X_UART_MCR_OFFSET) -#define LPC313X_UART_LSR (LPC313X_UART_VBASE+LPC313X_UART_LSR_OFFSET) -#define LPC313X_UART_MSR (LPC313X_UART_VBASE+LPC313X_UART_MSR_OFFSET) -#define LPC313X_UART_SCR (LPC313X_UART_VBASE+LPC313X_UART_SCR_OFFSET) -#define LPC313X_UART_ICR (LPC313X_UART_VBASE+LPC313X_UART_ICR_OFFSET) -#define LPC313X_UART_FDR (LPC313X_UART_VBASE+LPC313X_UART_FDR_OFFSET) -#define LPC313X_UART_POP (LPC313X_UART_VBASE+LPC313X_UART_POP_OFFSET) -#define LPC313X_UART_MODE (LPC313X_UART_VBASE+LPC313X_UART_MODE_OFFSET) -#define LPC313X_UART_INTCE (LPC313X_UART_VBASE+LPC313X_UART_INTCE_OFFSET) -#define LPC313X_UART_INTSE (LPC313X_UART_VBASE+LPC313X_UART_INTSE_OFFSET) -#define LPC313X_UART_INTS (LPC313X_UART_VBASE+LPC313X_UART_INTS_OFFSET) -#define LPC313X_UART_INTE (LPC313X_UART_VBASE+LPC313X_UART_INTE_OFFSET) -#define LPC313X_UART_INTCS (LPC313X_UART_VBASE+LPC313X_UART_INTCS_OFFSET) -#define LPC313X_UART_INTSS (LPC313X_UART_VBASE+LPC313X_UART_INTSS_OFFSET) - -/* UART register bit definitions ****************************************************************/ -/* Receive Buffer Register RBR, address 0x15001000 */ - -#define UART_RBR_SHIFT (0) /* Bits 0-7 */ -#define UART_RBR_MASK (0xff << UART_RBR_SHIFT) - -/* Transmitter Holding Register THR, address 0x15001000 */ - -#define UART_THR_SHIFT (0) /* Bits 0-7 */ -#define UART_THR_MASK (0xff << UART_THR_SHIFT) - -/* Divisor register Latch LSB DLL, address 0x15001000 */ - -#define UART_DLL_SHIFT (0) /* Bits 0-7 */ -#define UART_DLL_MASK (0xff << UART_DLL_SHIFT) - -/* Divisor latch register MSB DLM, address 0x15001004 */ - -#define UART_DLM_SHIFT (0) /* Bits 0-7 */ -#define UART_DLM_MASK (0xff << UART_DLM_SHIFT) - -/* Interrupt Enable Register IER, address 0x15001004 */ - -#define UART_IER_CTSINTEN (1 << 7) /* Bit 7: Enable modem status interrupt on CTS transition */ -#define UART_IER_MSINTEN (1 << 3) /* Bit 3: Enable Modem Status interrupt */ -#define UART_IER_RLSINTEN (1 << 2) /* Bit 2: Receiver Line Status interrupt enable */ -#define UART_IER_THREINTEN (1 << 1) /* Bit 1: Transmitter Holding Register Empty interrupt enable */ -#define UART_IER_RDAINTEN (1 << 0) /* Bit 0: Receive Data Available interrupt enable */ -#define UART_IER_ALLINTS (0x1f) - -/* Interrupt Identification Register IIR, address 0x15001008 */ - -#define UART_IIR_FIFOEN_SHIFT (6) /* Bits 6-7: Copies of FCR[0] */ -#define UART_IIR_FIFOEN_MASK (3 << UART_IIR_FIFOEN_SHIFT) -#define UART_IIR_INTID_SHIFT (1) /* Bits 1-3: Interrupt identification */ -#define UART_IIR_INTID_MASK (7 << UART_IIR_INTID_SHIFT) -# define UART_IIR_INTID_MS (0 << UART_IIR_INTID_SHIFT) /* Modem status */ -# define UART_IIR_INTID_THRE (1 << UART_IIR_INTID_SHIFT) /* Transmitter Holding Register empty */ -# define UART_IIR_INTID_RDA (2 << UART_IIR_INTID_SHIFT) /* Received Data Available */ -# define UART_IIR_INTID_RLS (3 << UART_IIR_INTID_SHIFT) /* Receiver Line Status */ -# define UART_IIR_INTID_TIMEOUT (6 << UART_IIR_INTID_SHIFT) /* Character time-out */ -#define UART_IIR_NOINT (1 << 0) /* Bit 0: Interrupt status, 1=no interrupt */ - -/* FIFO Control Register FCR, address 0x15001008 */ - -#define UART_FCR_RXTRIGLEVEL_SHIFT (6) /* Bits 6-7: 7:6 Receiver trigger level selection */ -#define UART_FCR_RXTRIGLEVEL_MASK (3 << UART_FCR_RXTRIGLEVEL_SHIFT) -# define UART_FCR_RXTRIGLEVEL_1 (0 << UART_FCR_RXTRIGLEVEL_SHIFT) /* Rx trigger at character 1 */ -# define UART_FCR_RXTRIGLEVEL_16 (1 << UART_FCR_RXTRIGLEVEL_SHIFT) /* Rx trigger at character 16 */ -# define UART_FCR_RXTRIGLEVEL_32 (2 << UART_FCR_RXTRIGLEVEL_SHIFT) /* Rx trigger at character 32 */ -# define UART_FCR_RXTRIGLEVEL_56 (3 << UART_FCR_RXTRIGLEVEL_SHIFT) /* Rx trigger at character 56 */ -#define UART_FCR_DMAMODE (1 << 3) /* Bit 3: DMA mode select */ -#define UART_FCR_TXFIFORST (1 << 2) /* Bit 2: Transmitter FIFO reset */ -#define UART_FCR_RXFIFORST (1 << 1) /* Bit 1: Receiver FIFO reset */ -#define UART_FCR_FIFOENABLE (1 << 0) /* Bit 0: Transmit and receive FIFO enable */ - -/* Line Control Register LCR, address 0x1500100c */ - -#define UART_LCR_DLAB (1 << 7) /* Bit 7: Divisor Latch Access bit */ -#define UART_LCR_BRKCTRL (1 << 6) /* Bit 6: Break control bit */ -#define UART_LCR_PARSTICK (1 << 5) /* Bit 5: Enable sticky parity mode */ -#define UART_LCR_PAREVEN (1 << 4) /* Bit 4: Select even parity */ -#define UART_LCR_PAREN (1 << 3) /* Bit 3: Parity enable */ -#define UART_LCR_NSTOPBITS (1 << 2) /* Bit 2: Number of stop bits selector */ -#define UART_LCR_WDLENSEL_SHIFT (0) /* Bits 0-1: Word length selector */ -#define UART_LCR_WDLENSEL_MASK (3 << UART_LCR_WDLENSEL_SHIFT) -# define UART_LCR_WDLENSEL_5BITS (0 << UART_LCR_WDLENSEL_SHIFT) /* Char length=5 stopbits=1 or 1.5*/ -# define UART_LCR_WDLENSEL_6BITS (1 << UART_LCR_WDLENSEL_SHIFT) /* Char length=6 stopbits=1 or 2 */ -# define UART_LCR_WDLENSEL_7BITS (2 << UART_LCR_WDLENSEL_SHIFT) /* Char length=7 stopbits=1 or 2 */ -# define UART_LCR_WDLENSEL_8BITS (3 << UART_LCR_WDLENSEL_SHIFT) /* Char length=8 stopbits=1 or 2 */ - -/* Modem Control Register MCR, address 0x15001010 */ - -#define UART_MCR_AUTOCTSEN (1 << 7) /* Bit 7: Auto-cts flow control enable */ -#define UART_MCR_AUTORTSEN (1 << 6) /* Bit 6: Auto-rts flow control enable */ -#define UART_MCR_LOOPEN (1 << 4) /* Bit 4: Loop-back mode enable */ -#define UART_MCR_RTS (1 << 1) /* Bit 1: Request To Send */ - -/* Line Status Register LSR, address 0x15001014 */ - -#define UART_LSR_RXER (1 << 7) /* Bit 7: Error in receiver FIFO */ -#define UART_LSR_TEMT (1 << 6) /* Bit 6: Transmitter empty (TSR and THR) */ -#define UART_LSR_THRE (1 << 5) /* Bit 5: Transmitter Holding Register empty */ -#define UART_LSR_BI (1 << 4) /* Bit 4: Break indication */ -#define UART_LSR_FE (1 << 3) /* Bit 3: Framing error */ -#define UART_LSR_PE (1 << 2) /* Bit 2: Parity error */ -#define UART_LSR_OE (1 << 1) /* Bit 1: Overrun error */ -#define UART_LSR_RDR (1 << 0) /* Bit 0: Read Data ready */ - -/* Modem Status Register MSR, address 0x15001018 */ - -#define UART_MSR_CTS (1 << 4) /* Bit 4: CTS is modem flow control signal */ -#define UART_MSR_DCTS (1 << 0) /* Bit 0: Delta Clear To Send */ - -/* Scratch Register SCR, address 0x1500101c */ - -#define UART_SCR_SCRVAL_SHIFT (0) /* Bits 0-7: Scratch Value */ -#define UART_SCR_SCRVAL_MASK (0xff << bb) - -/* IrDA Control Register ICR, address 0x15001024 */ - -#define UART_ICR_PULSEDIV_SHIFT (3) /* Bits 3-5: Configures fixed pulse width mode */ -#define UART_ICR_PULSEDIV_MASK (7 << UART_ICR_PULSEDIV_SHIFT) -#define UART_ICR_FIXPULSEEN (1 << 2) /* Bit 2: Enables IrDA fixed pulse width mode */ -#define UART_ICR_IRDAINV (1 << 1) /* Bit 1: Serial input is inverted */ -#define UART_ICR_IRDAEN (1 << 0) /* Bit 0: Enable IrDA */ - -/* Fractional Divider Register FDR, address 0x15001028 */ - -#define UART_FDR_MULVAL_SHIFT (4) /* Bits 4-7: Baud pre-scaler multiplier value */ -#define UART_FDR_MULVAL_MASK (15 << UART_FDR_MULVAL_SHIFT) -#define UART_FDR_DIVADDVAL_SHIFT (0) /* Bits 0-3: Baud pre-scaler divisor value */ -#define UART_FDR_DIVADDVAL_MASK (15 << UART_FDR_DIVADDVAL_SHIFT) - -/* NHP POP Register POP, address 0x15001030 */ - -#define UART_POP_POPRBR (1 << 0) /* Bit 0: Pop from RBR as if RBR read in non-NHP mode */ - -/* Mode Selection Register MODE, 0x15001034 */ - -#define UART_MODE_NHP (1 << 0) /* Bit 0: Enable UART NHP mode */ - -/* Interrupt Clear Enable Register INTCE, address 0x15001fd8 - * Interrupt Set Enable Register INTSE, address 0x15001fdc - * Interrupt Status Register INTS, address 0x15001fe0 - * Interrupt Enable Register INTE, address 0x15001fe4 - * Interrupt Clear Status Register INTCS, address 0x15001fe8 - * Interrupt Set Status Register INTSS, address 0x15001fec - */ - -#define UART_OEINT (1 << 15) /* Bit 15: Overrun Error Interrupt */ -#define UART_PEINT (1 << 14) /* Bit 14: Parity Error Interrupt (not INTSS) */ -#define UART_FEINT (1 << 13) /* Bit 13: Frame Error Interrupt (not INTSS) */ -#define UART_BIINT (1 << 12) /* Bit 12: Break Indication Interrupt (not INTSS) */ -#define UART_ABTOINT (1 << 9) /* Bit 9: Auto-Baud Time-Out Interrupt */ -#define UART_ABEOINT (1 << 8) /* Bit 8: End of Auto-Baud Interrupt */ -#define UART_RXDAINT (1 << 6) /* Bit 6: Receiver Data Available Interrupt (not INTSS) */ -#define UART_RXTOINT (1 << 5) /* Bit 5: Receiver Time-Out Interrupt (not INTCE) */ -#define UART_THREINT (1 << 4) /* Bit 4: Transmitter Holding Register Empty Interrupt */ -#define UART_DCTSINT (1 << 0) /* Bit 0: Delta Clear To Send Interrupt */ - - -/************************************************************************************************ - * Public Types - ************************************************************************************************/ - -/************************************************************************************************ - * Public Data - ************************************************************************************************/ - -/************************************************************************************************ - * Public Functions - ************************************************************************************************/ - -#endif /* __ARCH_ARM_SRC_LPC313X_UART_H */ diff --git a/nuttx/arch/arm/src/lpc313x/lpc313x_usbdev.c b/nuttx/arch/arm/src/lpc313x/lpc313x_usbdev.c deleted file mode 100755 index 5f8d48d3e..000000000 --- a/nuttx/arch/arm/src/lpc313x/lpc313x_usbdev.c +++ /dev/null @@ -1,2653 +0,0 @@ -/******************************************************************************* - * arch/arm/src/lpc313x/lpc313x_usbdev.c - * - * Author: Davide Hewson - * - * Part of the NuttX OS and based, in part, on the LPC2148 USB driver: - * - * Copyright (C) 2010 Gregory Nutt. All rights reserved. - * Author: Gregory Nutt - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name NuttX nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - *******************************************************************************/ - -/******************************************************************************* - * Included Files - *******************************************************************************/ - -#include - -#include -#include -#include -#include -#include -#include -#include - -#include -#include -#include -#include - -#include -#include - -#include "chip.h" -#include "up_arch.h" -#include "up_internal.h" - -#include "lpc313x_usbotg.h" -#include "lpc313x_evntrtr.h" -#include "lpc313x_syscreg.h" - -/******************************************************************************* - * Definitions - *******************************************************************************/ - -/* Configuration ***************************************************************/ - -#ifndef CONFIG_USBDEV_EP0_MAXSIZE -# define CONFIG_USBDEV_EP0_MAXSIZE 64 -#endif - -#ifndef CONFIG_USBDEV_MAXPOWER -# define CONFIG_USBDEV_MAXPOWER 100 /* mA */ -#endif - -/* Extremely detailed register debug that you would normally never want - * enabled. - */ - -#undef CONFIG_LPC313X_USBDEV_REGDEBUG - -/* Enable reading SOF from interrupt handler vs. simply reading on demand. Probably - * a bad idea... Unless there is some issue with sampling the SOF from hardware - * asynchronously. - */ - -#ifdef CONFIG_LPC313X_USBDEV_FRAME_INTERRUPT -# define USB_FRAME_INT USBDEV_USBINTR_SRE -#else -# define USB_FRAME_INT 0 -#endif - -#ifdef CONFIG_DEBUG -# define USB_ERROR_INT USBDEV_USBINTR_UEE -#else -# define USB_ERROR_INT 0 -#endif - -/* Debug ***********************************************************************/ - -/* Trace error codes */ - -#define LPC313X_TRACEERR_ALLOCFAIL 0x0001 -#define LPC313X_TRACEERR_BADCLEARFEATURE 0x0002 -#define LPC313X_TRACEERR_BADDEVGETSTATUS 0x0003 -#define LPC313X_TRACEERR_BADEPNO 0x0004 -#define LPC313X_TRACEERR_BADEPGETSTATUS 0x0005 -#define LPC313X_TRACEERR_BADEPTYPE 0x0006 -#define LPC313X_TRACEERR_BADGETCONFIG 0x0007 -#define LPC313X_TRACEERR_BADGETSETDESC 0x0008 -#define LPC313X_TRACEERR_BADGETSTATUS 0x0009 -#define LPC313X_TRACEERR_BADSETADDRESS 0x000a -#define LPC313X_TRACEERR_BADSETCONFIG 0x000b -#define LPC313X_TRACEERR_BADSETFEATURE 0x000c -#define LPC313X_TRACEERR_BINDFAILED 0x000d -#define LPC313X_TRACEERR_DISPATCHSTALL 0x000e -#define LPC313X_TRACEERR_DRIVER 0x000f -#define LPC313X_TRACEERR_DRIVERREGISTERED 0x0010 -#define LPC313X_TRACEERR_EP0SETUPSTALLED 0x0011 -#define LPC313X_TRACEERR_EPINNULLPACKET 0x0012 -#define LPC313X_TRACEERR_EPOUTNULLPACKET 0x0013 -#define LPC313X_TRACEERR_INVALIDCTRLREQ 0x0014 -#define LPC313X_TRACEERR_INVALIDPARMS 0x0015 -#define LPC313X_TRACEERR_IRQREGISTRATION 0x0016 -#define LPC313X_TRACEERR_NOEP 0x0017 -#define LPC313X_TRACEERR_NOTCONFIGURED 0x0018 -#define LPC313X_TRACEERR_REQABORTED 0x0019 - -/* Trace interrupt codes */ - -#define LPC313X_TRACEINTID_USB 0x0001 -#define LPC313X_TRACEINTID_CLEARFEATURE 0x0002 -#define LPC313X_TRACEINTID_DEVGETSTATUS 0x0003 -#define LPC313X_TRACEINTID_DEVRESET 0x0004 -#define LPC313X_TRACEINTID_DISPATCH 0x0005 -#define LPC313X_TRACEINTID_EP0COMPLETE 0x0006 -#define LPC313X_TRACEINTID_EP0NAK 0x0007 -#define LPC313X_TRACEINTID_EP0SETUP 0x0008 -#define LPC313X_TRACEINTID_EPGETSTATUS 0x0009 -#define LPC313X_TRACEINTID_EPIN 0x000a -#define LPC313X_TRACEINTID_EPINQEMPTY 0x000b -#define LPC313X_TRACEINTID_EP0INSETADDRESS 0x000c -#define LPC313X_TRACEINTID_EPOUT 0x000d -#define LPC313X_TRACEINTID_EPOUTQEMPTY 0x000e -#define LPC313X_TRACEINTID_EP0SETUPSETADDRESS 0x000f -#define LPC313X_TRACEINTID_FRAME 0x0010 -#define LPC313X_TRACEINTID_GETCONFIG 0x0011 -#define LPC313X_TRACEINTID_GETSETDESC 0x0012 -#define LPC313X_TRACEINTID_GETSETIF 0x0013 -#define LPC313X_TRACEINTID_GETSTATUS 0x0014 -#define LPC313X_TRACEINTID_IFGETSTATUS 0x0015 -#define LPC313X_TRACEINTID_SETCONFIG 0x0016 -#define LPC313X_TRACEINTID_SETFEATURE 0x0017 -#define LPC313X_TRACEINTID_SUSPENDCHG 0x0018 -#define LPC313X_TRACEINTID_SYNCHFRAME 0x0019 - -/* Hardware interface **********************************************************/ - -/* This represents a Endpoint Transfer Descriptor - note these must be 32 byte aligned */ -struct lpc313x_dtd_s -{ - volatile uint32_t nextdesc; /* Address of the next DMA descripto in RAM */ - volatile uint32_t config; /* Misc. bit encoded configuration information */ - uint32_t buffer0; /* Buffer start address */ - uint32_t buffer1; /* Buffer start address */ - uint32_t buffer2; /* Buffer start address */ - uint32_t buffer3; /* Buffer start address */ - uint32_t buffer4; /* Buffer start address */ - uint32_t xfer_len; /* Software only - transfer len that was queued */ -}; - -/* DTD nextdesc field*/ -#define DTD_NEXTDESC_INVALID (1 << 0) /* Bit 0 : Next Descriptor Invalid */ - -/* DTD config field */ -#define DTD_CONFIG_LENGTH(n) ((n) << 16) /* Bits 16-31 : Total bytes to transfer */ -#define DTD_CONFIG_IOC (1 << 15) /* Bit 15 : Interrupt on Completion */ -#define DTD_CONFIG_MULT_VARIABLE (0 << 10) /* Bits 10-11 : Number of packets executed per transacation descriptor (override) */ -#define DTD_CONFIG_MULT_NUM(n) ((n) << 10) -#define DTD_CONFIG_ACTIVE (1 << 7) /* Bit 7 : Status Active */ -#define DTD_CONFIG_HALTED (1 << 6) /* Bit 6 : Status Halted */ -#define DTD_CONFIG_BUFFER_ERROR (1 << 5) /* Bit 6 : Status Buffer Error */ -#define DTD_CONFIG_TRANSACTION_ERROR (1 << 3) /* Bit 3 : Status Transaction Error */ - -/* This represents a queue head - not these must be aligned to a 2048 byte boundary */ -struct lpc313x_dqh_s -{ - uint32_t capability; /* Endpoint capability */ - uint32_t currdesc; /* Current dTD pointer */ - struct lpc313x_dtd_s overlay; /* DTD overlay */ - volatile uint32_t setup[2]; /* Set-up buffer */ - uint32_t gap[4]; /* align to 64 bytes */ -}; - -/* DQH capability field */ -#define DQH_CAPABILITY_MULT_VARIABLE (0 << 30) /* Bits 30-31 : Number of packets executed per transaction descriptor */ -#define DQH_CAPABILITY_MULT_NUM(n) ((n) << 30) -#define DQH_CAPABILITY_ZLT (1 << 29) /* Bit 29 : Zero Length Termination Select */ -#define DQH_CAPABILITY_MAX_PACKET(n) ((n) << 16) /* Bits 16-29 : Maximum packet size of associated endpoint (<1024) */ -#define DQH_CAPABILITY_IOS (1 << 15) /* Bit 15 : Interrupt on Setup */ - -/* Endpoints ******************************************************************/ - -/* Number of endpoints */ -#define LPC313X_NLOGENDPOINTS (4) /* ep0-3 */ -#define LPC313X_NPHYSENDPOINTS (8) /* x2 for IN and OUT */ - -/* Odd physical endpoint numbers are IN; even are OUT */ -#define LPC313X_EPPHYIN(epphy) (((epphy)&1)!=0) -#define LPC313X_EPPHYOUT(epphy) (((epphy)&1)==0) - -#define LPC313X_EPPHYIN2LOG(epphy) (((uint8_t)(epphy)>>1)|USB_DIR_IN) -#define LPC313X_EPPHYOUT2LOG(epphy) (((uint8_t)(epphy)>>1)|USB_DIR_OUT) - -/* Endpoint 0 is special... */ -#define LPC313X_EP0_OUT (0) -#define LPC313X_EP0_IN (1) - -/* Each endpoint has somewhat different characteristics */ -#define LPC313X_EPALLSET (0xff) /* All endpoints */ -#define LPC313X_EPOUTSET (0x55) /* Even phy endpoint numbers are OUT EPs */ -#define LPC313X_EPINSET (0xaa) /* Odd endpoint numbers are IN EPs */ -#define LPC313X_EPCTRLSET (0x03) /* EP0 IN/OUT are control endpoints */ -#define LPC313X_EPINTRSET (0xa8) /* Interrupt endpoints */ -#define LPC313X_EPBULKSET (0xfc) /* Bulk endpoints */ -#define LPC313X_EPISOCSET (0xfc) /* Isochronous endpoints */ - -/* Maximum packet sizes for endpoints */ -#define LPC313X_EP0MAXPACKET (64) /* EP0 max packet size (1-64) */ -#define LPC313X_BULKMAXPACKET (512) /* Bulk endpoint max packet (8/16/32/64/512) */ -#define LPC313X_INTRMAXPACKET (1024) /* Interrupt endpoint max packet (1 to 1024) */ -#define LPC313X_ISOCMAXPACKET (512) /* Acutally 1..1023 */ - -/* The address of the endpoint control register */ -#define LPC313X_USBDEV_ENDPTCTRL(epphy) (LPC313X_USBDEV_ENDPTCTRL0 + ((epphy)>>1)*4) - -/* Endpoint bit position in SETUPSTAT, PRIME, FLUSH, STAT, COMPLETE registers */ -#define LPC313X_ENDPTSHIFT(epphy) (LPC313X_EPPHYIN(epphy) ? (16 + ((epphy) >> 1)) : ((epphy) >> 1)) -#define LPC313X_ENDPTMASK(epphy) (1 << LPC313X_ENDPTSHIFT(epphy)) -#define LPC313X_ENDPTMASK_ALL 0x000f000f - -/* Request queue operations ****************************************************/ - -#define lpc313x_rqempty(ep) ((ep)->head == NULL) -#define lpc313x_rqpeek(ep) ((ep)->head) - -/******************************************************************************* - * Private Types - *******************************************************************************/ - -/* A container for a request so that the request may be retained in a list */ - -struct lpc313x_req_s -{ - struct usbdev_req_s req; /* Standard USB request */ - struct lpc313x_req_s *flink; /* Supports a singly linked list */ -}; - -/* This is the internal representation of an endpoint */ - -struct lpc313x_ep_s -{ - /* Common endpoint fields. This must be the first thing defined in the - * structure so that it is possible to simply cast from struct usbdev_ep_s - * to struct lpc313x_ep_s. - */ - - struct usbdev_ep_s ep; /* Standard endpoint structure */ - - /* LPC313X-specific fields */ - - struct lpc313x_usbdev_s *dev; /* Reference to private driver data */ - struct lpc313x_req_s *head; /* Request list for this endpoint */ - struct lpc313x_req_s *tail; - uint8_t epphy; /* Physical EP address */ - uint8_t stalled:1; /* 1: Endpoint is stalled */ -}; - -/* This structure retains the state of the USB device controller */ - -struct lpc313x_usbdev_s -{ - /* Common device fields. This must be the first thing defined in the - * structure so that it is possible to simply cast from struct usbdev_s - * to struct lpc313x_usbdev_s. - */ - - struct usbdev_s usbdev; - - /* The bound device class driver */ - - struct usbdevclass_driver_s *driver; - - /* LPC313X-specific fields */ - - uint8_t ep0state; /* State of certain EP0 operations */ - uint8_t ep0buf[64]; /* buffer for EP0 short transfers */ - uint8_t paddr; /* Address assigned by SETADDRESS */ - uint8_t stalled:1; /* 1: Protocol stalled */ - uint8_t selfpowered:1; /* 1: Device is self powered */ - uint8_t paddrset:1; /* 1: Peripheral addr has been set */ - uint8_t attached:1; /* 1: Host attached */ - uint32_t softprio; /* Bitset of high priority interrupts */ - uint32_t epavail; /* Bitset of available endpoints */ -#ifdef CONFIG_LPC313X_USBDEV_FRAME_INTERRUPT - uint32_t sof; /* Last start-of-frame */ -#endif - - /* The endpoint list */ - struct lpc313x_ep_s eplist[LPC313X_NPHYSENDPOINTS]; -}; - -#define EP0STATE_IDLE 0 /* Idle State, leave on receiving a setup packet or epsubmit */ -#define EP0STATE_SETUP_OUT 1 /* Setup Packet received - SET/CLEAR */ -#define EP0STATE_SETUP_IN 2 /* Setup Packet received - GET */ -#define EP0STATE_SHORTWRITE 3 /* Short write without a usb_request */ -#define EP0STATE_WAIT_NAK_OUT 4 /* Waiting for Host to illicit status phase (GET) */ -#define EP0STATE_WAIT_NAK_IN 5 /* Waiting for Host to illicit status phase (SET/CLEAR) */ -#define EP0STATE_WAIT_STATUS_OUT 6 /* Wait for status phase to complete */ -#define EP0STATE_WAIT_STATUS_IN 7 /* Wait for status phase to complete */ -#define EP0STATE_DATA_IN 8 -#define EP0STATE_DATA_OUT 9 - -/******************************************************************************* - * Private Function Prototypes - *******************************************************************************/ - -/* Register operations ********************************************************/ - -#if defined(CONFIG_LPC313X_USBDEV_REGDEBUG) && defined(CONFIG_DEBUG) -static uint32_t lpc313x_getreg(uint32_t addr); -static void lpc313x_putreg(uint32_t val, uint32_t addr); -#else -# define lpc313x_getreg(addr) getreg32(addr) -# define lpc313x_putreg(val,addr) putreg32(val,addr) -#endif - -static inline void lpc313x_clrbits(uint32_t mask, uint32_t addr); -static inline void lpc313x_setbits(uint32_t mask, uint32_t addr); -static inline void lpc313x_chgbits(uint32_t mask, uint32_t val, uint32_t addr); - -/* Request queue operations ****************************************************/ - -static FAR struct lpc313x_req_s *lpc313x_rqdequeue(FAR struct lpc313x_ep_s *privep); -static bool lpc313x_rqenqueue(FAR struct lpc313x_ep_s *privep, - FAR struct lpc313x_req_s *req); - -/* Low level data transfers and request operations *****************************/ - -static inline void lpc313x_writedtd(struct lpc313x_dtd_s *dtd, const uint8_t *data, uint32_t nbytes); -static inline void lpc313x_queuedtd(uint8_t epphy, struct lpc313x_dtd_s *dtd); -static inline void lpc313x_ep0xfer(uint8_t epphy, uint8_t *data, uint32_t nbytes); -static void lpc313x_readsetup(uint8_t epphy, struct usb_ctrlreq_s *ctrl); - -static inline void lpc313x_set_address(struct lpc313x_usbdev_s *priv, uint16_t address); - -static void lpc313x_flushep(struct lpc313x_ep_s *privep); - -static int lpc313x_progressep(struct lpc313x_ep_s *privep); -static inline void lpc313x_abortrequest(struct lpc313x_ep_s *privep, - struct lpc313x_req_s *privreq, int16_t result); -static void lpc313x_reqcomplete(struct lpc313x_ep_s *privep, struct lpc313x_req_s *privreq, int16_t result); - -static void lpc313x_cancelrequests(struct lpc313x_ep_s *privep, int16_t status); - -/* Interrupt handling **********************************************************/ -static struct lpc313x_ep_s *lpc313x_epfindbyaddr(struct lpc313x_usbdev_s *priv, uint16_t eplog); -static void lpc313x_dispatchrequest(struct lpc313x_usbdev_s *priv, const struct usb_ctrlreq_s *ctrl); -static void lpc313x_ep0configure(struct lpc313x_usbdev_s *priv); -static void lpc313x_usbreset(struct lpc313x_usbdev_s *priv); - -static inline void lpc313x_ep0state(struct lpc313x_usbdev_s *priv, uint16_t state); -static void lpc313x_ep0setup(struct lpc313x_usbdev_s *priv); - -static void lpc313x_ep0complete(struct lpc313x_usbdev_s *priv, uint8_t epphy); -static void lpc313x_ep0nak(struct lpc313x_usbdev_s *priv, uint8_t epphy); -static bool lpc313x_epcomplete(struct lpc313x_usbdev_s *priv, uint8_t epphy); - -static int lpc313x_usbinterrupt(int irq, FAR void *context); - -/* Endpoint operations *********************************************************/ - -/* USB device controller operations ********************************************/ - -static int lpc313x_epconfigure(FAR struct usbdev_ep_s *ep, - const struct usb_epdesc_s *desc, bool last); -static int lpc313x_epdisable(FAR struct usbdev_ep_s *ep); -static FAR struct usbdev_req_s *lpc313x_epallocreq(FAR struct usbdev_ep_s *ep); -static void lpc313x_epfreereq(FAR struct usbdev_ep_s *ep, - FAR struct usbdev_req_s *); -static void *lpc313x_epallocbuffer(FAR struct usbdev_ep_s *ep, unsigned bytes); -static void lpc313_epfreebuffer(FAR struct usbdev_ep_s *ep, FAR void *buf); -static int lpc313x_epsubmit(FAR struct usbdev_ep_s *ep, - struct usbdev_req_s *req); -static int lpc313x_epcancel(FAR struct usbdev_ep_s *ep, - struct usbdev_req_s *req); -static int lpc313x_epstall(FAR struct usbdev_ep_s *ep, bool resume); - -static FAR struct usbdev_ep_s *lcp313x_allocep(FAR struct usbdev_s *dev, - uint8_t epno, bool in, uint8_t eptype); -static void lpc313x_freeep(FAR struct usbdev_s *dev, FAR struct usbdev_ep_s *ep); -static int lpc313x_getframe(struct usbdev_s *dev); -static int lpc313x_wakeup(struct usbdev_s *dev); -static int lpc313x_selfpowered(struct usbdev_s *dev, bool selfpowered); -static int lpc313x_pullup(struct usbdev_s *dev, bool enable); - -/******************************************************************************* - * Private Data - *******************************************************************************/ - -/* Since there is only a single USB interface, all status information can be - * be simply retained in a single global instance. - */ - -static struct lpc313x_usbdev_s g_usbdev; - -static struct lpc313x_dqh_s __attribute__((aligned(2048))) g_qh[LPC313X_NPHYSENDPOINTS]; -static struct lpc313x_dtd_s __attribute__((aligned(32))) g_td[LPC313X_NPHYSENDPOINTS]; - -static const struct usbdev_epops_s g_epops = -{ - .configure = lpc313x_epconfigure, - .disable = lpc313x_epdisable, - .allocreq = lpc313x_epallocreq, - .freereq = lpc313x_epfreereq, -#ifdef CONFIG_ARCH_USBDEV_DMA - .allocbuffer = lpc313x_epallocbuffer, - .freebuffer = lpc313x_epfreebuffer, -#endif - .submit = lpc313x_epsubmit, - .cancel = lpc313x_epcancel, - .stall = lpc313x_epstall, -}; - -static const struct usbdev_ops_s g_devops = -{ - .allocep = lcp313x_allocep, - .freeep = lpc313x_freeep, - .getframe = lpc313x_getframe, - .wakeup = lpc313x_wakeup, - .selfpowered = lpc313x_selfpowered, - .pullup = lpc313x_pullup, -}; - -/******************************************************************************* - * Public Data - *******************************************************************************/ - -/******************************************************************************* - * Private Functions - *******************************************************************************/ - -/******************************************************************************* - * Name: lpc313x_getreg - * - * Description: - * Get the contents of an LPC313x register - * - *******************************************************************************/ - -#if defined(CONFIG_LPC313X_USBDEV_REGDEBUG) && defined(CONFIG_DEBUG) -static uint32_t lpc313x_getreg(uint32_t addr) -{ - static uint32_t prevaddr = 0; - static uint32_t preval = 0; - static uint32_t count = 0; - - /* Read the value from the register */ - - uint32_t val = getreg32(addr); - - /* Is this the same value that we read from the same registe last time? Are - * we polling the register? If so, suppress some of the output. - */ - - if (addr == prevaddr && val == preval) - { - if (count == 0xffffffff || ++count > 3) - { - if (count == 4) - { - lldbg("...\n"); - } - return val; - } - } - - /* No this is a new address or value */ - - else - { - /* Did we print "..." for the previous value? */ - - if (count > 3) - { - /* Yes.. then show how many times the value repeated */ - - lldbg("[repeats %d more times]\n", count-3); - } - - /* Save the new address, value, and count */ - - prevaddr = addr; - preval = val; - count = 1; - } - - /* Show the register value read */ - - lldbg("%08x->%08x\n", addr, val); - return val; -} -#endif - -/******************************************************************************* - * Name: lpc313x_putreg - * - * Description: - * Set the contents of an LPC313x register to a value - * - *******************************************************************************/ - -#if defined(CONFIG_LPC313X_USBDEV_REGDEBUG) && defined(CONFIG_DEBUG) -static void lpc313x_putreg(uint32_t val, uint32_t addr) -{ - /* Show the register value being written */ - - lldbg("%08x<-%08x\n", addr, val); - - /* Write the value */ - - putreg32(val, addr); -} -#endif - -/******************************************************************************* - * Name: lpc313x_clrbits - * - * Description: - * Clear bits in a register - * - *******************************************************************************/ - -static inline void lpc313x_clrbits(uint32_t mask, uint32_t addr) -{ - uint32_t reg = lpc313x_getreg(addr); - reg &= ~mask; - lpc313x_putreg(reg, addr); -} - -/******************************************************************************* - * Name: lpc313x_setbits - * - * Description: - * Set bits in a register - * - *******************************************************************************/ - -static inline void lpc313x_setbits(uint32_t mask, uint32_t addr) -{ - uint32_t reg = lpc313x_getreg(addr); - reg |= mask; - lpc313x_putreg(reg, addr); -} - -/******************************************************************************* - * Name: lpc313x_chgbits - * - * Description: - * Change bits in a register - * - *******************************************************************************/ - -static inline void lpc313x_chgbits(uint32_t mask, uint32_t val, uint32_t addr) -{ - uint32_t reg = lpc313x_getreg(addr); - reg &= ~mask; - reg |= val; - lpc313x_putreg(reg, addr); -} - -/******************************************************************************* - * Name: lpc313x_rqdequeue - * - * Description: - * Remove a request from an endpoint request queue - * - *******************************************************************************/ - -static FAR struct lpc313x_req_s *lpc313x_rqdequeue(FAR struct lpc313x_ep_s *privep) -{ - FAR struct lpc313x_req_s *ret = privep->head; - - if (ret) - { - privep->head = ret->flink; - if (!privep->head) - { - privep->tail = NULL; - } - - ret->flink = NULL; - } - - return ret; -} - -/******************************************************************************* - * Name: lpc313x_rqenqueue - * - * Description: - * Add a request from an endpoint request queue - * - *******************************************************************************/ - -static bool lpc313x_rqenqueue(FAR struct lpc313x_ep_s *privep, - FAR struct lpc313x_req_s *req) -{ - bool is_empty = !privep->head; - - req->flink = NULL; - if (is_empty) - { - privep->head = req; - privep->tail = req; - } - else - { - privep->tail->flink = req; - privep->tail = req; - } - return is_empty; -} - -/******************************************************************************* - * Name: lpc313x_writedtd - * - * Description: - * Initialise a DTD to transfer the data - * - *******************************************************************************/ - -static inline void lpc313x_writedtd(struct lpc313x_dtd_s *dtd, const uint8_t *data, uint32_t nbytes) -{ - dtd->nextdesc = DTD_NEXTDESC_INVALID; - dtd->config = DTD_CONFIG_LENGTH(nbytes) | DTD_CONFIG_IOC | DTD_CONFIG_ACTIVE; - dtd->buffer0 = ((uint32_t) data); - dtd->buffer1 = (((uint32_t) data) + 0x1000) & 0xfffff000; - dtd->buffer2 = (((uint32_t) data) + 0x2000) & 0xfffff000; - dtd->buffer3 = (((uint32_t) data) + 0x3000) & 0xfffff000; - dtd->buffer4 = (((uint32_t) data) + 0x4000) & 0xfffff000; - dtd->xfer_len = nbytes; -} - -/******************************************************************************* - * Name: lpc313x_queuedtd - * - * Description: - * Add the DTD to the device list - * - *******************************************************************************/ - -static void lpc313x_queuedtd(uint8_t epphy, struct lpc313x_dtd_s *dtd) -{ - /* Queue the DTD onto the Endpoint */ - /* NOTE - this only works when no DTD is currently queued */ - - g_qh[epphy].overlay.nextdesc = (uint32_t) dtd; - g_qh[epphy].overlay.config &= ~(DTD_CONFIG_ACTIVE | DTD_CONFIG_HALTED); - - uint32_t bit = LPC313X_ENDPTMASK(epphy); - - lpc313x_setbits (bit, LPC313X_USBDEV_ENDPTPRIME); - - while (lpc313x_getreg (LPC313X_USBDEV_ENDPTPRIME) & bit) - ; -} - -/******************************************************************************* - * Name: lpc313x_ep0xfer - * - * Description: - * Schedule a short transfer for Endpoint 0 (IN or OUT) - * - *******************************************************************************/ - -static inline void lpc313x_ep0xfer(uint8_t epphy, uint8_t *buf, uint32_t nbytes) -{ - struct lpc313x_dtd_s *dtd = &g_td[epphy]; - - lpc313x_writedtd(dtd, buf, nbytes); - - lpc313x_queuedtd(epphy, dtd); -} - -/******************************************************************************* - * Name: lpc313x_readsetup - * - * Description: - * Read a Setup packet from the DTD. - * - *******************************************************************************/ -static void lpc313x_readsetup(uint8_t epphy, struct usb_ctrlreq_s *ctrl) -{ - struct lpc313x_dqh_s *dqh = &g_qh[epphy]; - int i; - - do { - /* Set the trip wire */ - lpc313x_setbits(USBDEV_USBCMD_SUTW, LPC313X_USBDEV_USBCMD); - - // copy the request... - for (i = 0; i < 8; i++) - ((uint8_t *) ctrl)[i] = ((uint8_t *) dqh->setup)[i]; - - } while (!(lpc313x_getreg(LPC313X_USBDEV_USBCMD) & USBDEV_USBCMD_SUTW)); - - /* Clear the trip wire */ - lpc313x_clrbits(USBDEV_USBCMD_SUTW, LPC313X_USBDEV_USBCMD); - - /* Clear the Setup Interrupt */ - lpc313x_putreg (LPC313X_ENDPTMASK(LPC313X_EP0_OUT), LPC313X_USBDEV_ENDPTSETUPSTAT); -} - -/******************************************************************************* - * Name: lpc313x_set_address - * - * Description: - * Set the devices USB address - * - *******************************************************************************/ - -static inline void lpc313x_set_address(struct lpc313x_usbdev_s *priv, uint16_t address) -{ - priv->paddr = address; - priv->paddrset = address != 0; - - lpc313x_chgbits(USBDEV_DEVICEADDR_MASK, priv->paddr << USBDEV_DEVICEADDR_SHIFT, - LPC313X_USBDEV_DEVICEADDR); -} - -/******************************************************************************* - * Name: lpc313x_flushep - * - * Description: - * Flush any primed descriptors from this ep - * - *******************************************************************************/ - -static void lpc313x_flushep(struct lpc313x_ep_s *privep) -{ - uint32_t mask = LPC313X_ENDPTMASK(privep->epphy); - do { - lpc313x_putreg (mask, LPC313X_USBDEV_ENDPTFLUSH); - while ((lpc313x_getreg(LPC313X_USBDEV_ENDPTFLUSH) & mask) != 0) - ; - } while ((lpc313x_getreg(LPC313X_USBDEV_ENDPTSTATUS) & mask) != 0); -} - - -/******************************************************************************* - * Name: lpc313x_progressep - * - * Description: - * Progress the Endpoint by priming the first request into the queue head - * - *******************************************************************************/ - -static int lpc313x_progressep(struct lpc313x_ep_s *privep) -{ - struct lpc313x_dtd_s *dtd = &g_td[privep->epphy]; - struct lpc313x_req_s *privreq; - - /* Check the request from the head of the endpoint request queue */ - - privreq = lpc313x_rqpeek(privep); - if (!privreq) - { - usbtrace(TRACE_INTDECODE(LPC313X_TRACEINTID_EPINQEMPTY), 0); - return OK; - } - - /* Ignore any attempt to send a zero length packet */ - - if (privreq->req.len == 0) - { - /* If the class driver is responding to a setup packet, then wait for the - * host to illicit thr response */ - - if (privep->epphy == LPC313X_EP0_IN && privep->dev->ep0state == EP0STATE_SETUP_OUT) - lpc313x_ep0state (privep->dev, EP0STATE_WAIT_NAK_IN); - else - { - if (LPC313X_EPPHYIN(privep->epphy)) - usbtrace(TRACE_DEVERROR(LPC313X_TRACEERR_EPINNULLPACKET), 0); - else - usbtrace(TRACE_DEVERROR(LPC313X_TRACEERR_EPOUTNULLPACKET), 0); - } - - lpc313x_reqcomplete(privep, lpc313x_rqdequeue(privep), OK); - return OK; - } - - if (privep->epphy == LPC313X_EP0_IN) - lpc313x_ep0state (privep->dev, EP0STATE_DATA_IN); - else if (privep->epphy == LPC313X_EP0_OUT) - lpc313x_ep0state (privep->dev, EP0STATE_DATA_OUT); - - int bytesleft = privreq->req.len - privreq->req.xfrd; - - if (LPC313X_EPPHYIN(privep->epphy)) - usbtrace(TRACE_WRITE(privep->epphy), privreq->req.xfrd); - else - usbtrace(TRACE_READ(privep->epphy), privreq->req.xfrd); - - /* Initialise the DTD to transfer the next chunk */ - - lpc313x_writedtd (dtd, privreq->req.buf + privreq->req.xfrd, bytesleft); - - /* then queue onto the DQH */ - lpc313x_queuedtd(privep->epphy, dtd); - - return OK; -} - -/******************************************************************************* - * Name: lpc313x_abortrequest - * - * Description: - * Discard a request - * - *******************************************************************************/ - -static inline void lpc313x_abortrequest(struct lpc313x_ep_s *privep, - struct lpc313x_req_s *privreq, - int16_t result) -{ - usbtrace(TRACE_DEVERROR(LPC313X_TRACEERR_REQABORTED), (uint16_t)privep->epphy); - - /* Save the result in the request structure */ - - privreq->req.result = result; - - /* Callback to the request completion handler */ - - privreq->req.callback(&privep->ep, &privreq->req); -} - -/******************************************************************************* - * Name: lpc313x_reqcomplete - * - * Description: - * Handle termination of the request at the head of the endpoint request queue. - * - *******************************************************************************/ - -static void lpc313x_reqcomplete(struct lpc313x_ep_s *privep, struct lpc313x_req_s *privreq, int16_t result) -{ - /* If endpoint 0, temporarily reflect the state of protocol stalled - * in the callback. - */ - - bool stalled = privep->stalled; - if (privep->epphy == LPC313X_EP0_IN) - privep->stalled = privep->dev->stalled; - - /* Save the result in the request structure */ - - privreq->req.result = result; - - /* Callback to the request completion handler */ - - privreq->req.callback(&privep->ep, &privreq->req); - - /* Restore the stalled indication */ - - privep->stalled = stalled; -} - -/******************************************************************************* - * Name: lpc313x_cancelrequests - * - * Description: - * Cancel all pending requests for an endpoint - * - *******************************************************************************/ - -static void lpc313x_cancelrequests(struct lpc313x_ep_s *privep, int16_t status) -{ - if (!lpc313x_rqempty(privep)) - lpc313x_flushep(privep); - - while (!lpc313x_rqempty(privep)) - { - // FIXME: the entry at the head should be sync'd with the DTD - // FIXME: only report the error status if the transfer hasn't completed - usbtrace(TRACE_COMPLETE(privep->epphy), - (lpc313x_rqpeek(privep))->req.xfrd); - lpc313x_reqcomplete(privep, lpc313x_rqdequeue(privep), status); - } -} - -/******************************************************************************* - * Name: lpc313x_epfindbyaddr - * - * Description: - * Find the physical endpoint structure corresponding to a logic endpoint - * address - * - *******************************************************************************/ - -static struct lpc313x_ep_s *lpc313x_epfindbyaddr(struct lpc313x_usbdev_s *priv, - uint16_t eplog) -{ - struct lpc313x_ep_s *privep; - int i; - - /* Endpoint zero is a special case */ - - if (USB_EPNO(eplog) == 0) - { - return &priv->eplist[0]; - } - - /* Handle the remaining */ - - for (i = 1; i < LPC313X_NPHYSENDPOINTS; i++) - { - privep = &priv->eplist[i]; - - /* Same logical endpoint number? (includes direction bit) */ - - if (eplog == privep->ep.eplog) - { - /* Return endpoint found */ - - return privep; - } - } - - /* Return endpoint not found */ - - return NULL; -} - -/******************************************************************************* - * Name: lpc313x_dispatchrequest - * - * Description: - * Provide unhandled setup actions to the class driver. This is logically part - * of the USB interrupt handler. - * - *******************************************************************************/ - -static void lpc313x_dispatchrequest(struct lpc313x_usbdev_s *priv, - const struct usb_ctrlreq_s *ctrl) -{ - int ret = -EIO; - - usbtrace(TRACE_INTDECODE(LPC313X_TRACEINTID_DISPATCH), 0); - if (priv->driver) - { - /* Forward to the control request to the class driver implementation */ - - ret = CLASS_SETUP(priv->driver, &priv->usbdev, ctrl); - } - - if (ret < 0) - { - /* Stall on failure */ - - usbtrace(TRACE_DEVERROR(LPC313X_TRACEERR_DISPATCHSTALL), 0); - priv->stalled = true; - } -} - -/******************************************************************************* - * Name: lpc313x_ep0configure - * - * Description: - * Reset Usb engine - * - *******************************************************************************/ - -static void lpc313x_ep0configure(struct lpc313x_usbdev_s *priv) -{ - /* Enable ep0 IN and ep0 OUT */ - g_qh[LPC313X_EP0_OUT].capability = (DQH_CAPABILITY_MAX_PACKET(CONFIG_USBDEV_EP0_MAXSIZE) | - DQH_CAPABILITY_IOS | - DQH_CAPABILITY_ZLT); - - g_qh[LPC313X_EP0_IN ].capability = (DQH_CAPABILITY_MAX_PACKET(CONFIG_USBDEV_EP0_MAXSIZE) | - DQH_CAPABILITY_IOS | - DQH_CAPABILITY_ZLT); - - g_qh[LPC313X_EP0_OUT].currdesc = DTD_NEXTDESC_INVALID; - g_qh[LPC313X_EP0_IN ].currdesc = DTD_NEXTDESC_INVALID; - - /* Enable EP0 */ - lpc313x_setbits (USBDEV_ENDPTCTRL0_RXE | USBDEV_ENDPTCTRL0_TXE, LPC313X_USBDEV_ENDPTCTRL0); -} - -/******************************************************************************* - * Name: lpc313x_usbreset - * - * Description: - * Reset Usb engine - * - *******************************************************************************/ - -static void lpc313x_usbreset(struct lpc313x_usbdev_s *priv) -{ - int epphy; - - /* Disable all endpoints */ - - lpc313x_clrbits (USBDEV_ENDPTCTRL_RXE | USBDEV_ENDPTCTRL_TXE, LPC313X_USBDEV_ENDPTCTRL0); - lpc313x_clrbits (USBDEV_ENDPTCTRL_RXE | USBDEV_ENDPTCTRL_TXE, LPC313X_USBDEV_ENDPTCTRL1); - lpc313x_clrbits (USBDEV_ENDPTCTRL_RXE | USBDEV_ENDPTCTRL_TXE, LPC313X_USBDEV_ENDPTCTRL2); - lpc313x_clrbits (USBDEV_ENDPTCTRL_RXE | USBDEV_ENDPTCTRL_TXE, LPC313X_USBDEV_ENDPTCTRL3); - - /* Clear all pending interrupts */ - - lpc313x_putreg (lpc313x_getreg(LPC313X_USBDEV_ENDPTNAK), LPC313X_USBDEV_ENDPTNAK); - lpc313x_putreg (lpc313x_getreg(LPC313X_USBDEV_ENDPTSETUPSTAT), LPC313X_USBDEV_ENDPTSETUPSTAT); - lpc313x_putreg (lpc313x_getreg(LPC313X_USBDEV_ENDPTCOMPLETE), LPC313X_USBDEV_ENDPTCOMPLETE); - - /* Wait for all prime operations to have completed and then flush all DTDs */ - while (lpc313x_getreg (LPC313X_USBDEV_ENDPTPRIME) != 0) - ; - lpc313x_putreg (LPC313X_ENDPTMASK_ALL, LPC313X_USBDEV_ENDPTFLUSH); - while (lpc313x_getreg (LPC313X_USBDEV_ENDPTFLUSH)) - ; - - /* Reset endpoints */ - for (epphy = 0; epphy < LPC313X_NPHYSENDPOINTS; epphy++) - { - struct lpc313x_ep_s *privep = &priv->eplist[epphy]; - - lpc313x_cancelrequests (privep, -ESHUTDOWN); - - /* Reset endpoint status */ - privep->stalled = false; - } - - /* Tell the class driver that we are disconnected. The class - * driver should then accept any new configurations. */ - - if (priv->driver) - CLASS_DISCONNECT(priv->driver, &priv->usbdev); - - /* Set the interrupt Threshold control interval to 0 */ - lpc313x_chgbits(USBDEV_USBCMD_ITC_MASK, USBDEV_USBCMD_ITCIMME, LPC313X_USBDEV_USBCMD); - - /* Zero out the Endpoint queue heads */ - memset ((void *) g_qh, 0, sizeof (g_qh)); - memset ((void *) g_td, 0, sizeof (g_td)); - - /* Set USB address to 0 */ - lpc313x_set_address (priv, 0); - - /* Initialise the Enpoint List Address */ - lpc313x_putreg ((uint32_t)g_qh, LPC313X_USBDEV_ENDPOINTLIST); - - /* EndPoint 0 initialization */ - lpc313x_ep0configure(priv); - - /* Enable Device interrupts */ - lpc313x_putreg(USB_FRAME_INT | USB_ERROR_INT | - USBDEV_USBINTR_NAKE | USBDEV_USBINTR_SLE | USBDEV_USBINTR_URE | USBDEV_USBINTR_PCE | USBDEV_USBINTR_UE, - LPC313X_USBDEV_USBINTR); -} - -/******************************************************************************* - * Name: lpc313x_setstate - * - * Description: - * Sets the EP0 state and manages the NAK interrupts - * - *******************************************************************************/ - -static inline void lpc313x_ep0state(struct lpc313x_usbdev_s *priv, uint16_t state) -{ - priv->ep0state = state; - - switch (state) - { - case EP0STATE_WAIT_NAK_IN: - lpc313x_putreg (LPC313X_ENDPTMASK(LPC313X_EP0_IN), LPC313X_USBDEV_ENDPTNAKEN); - break; - case EP0STATE_WAIT_NAK_OUT: - lpc313x_putreg (LPC313X_ENDPTMASK(LPC313X_EP0_OUT), LPC313X_USBDEV_ENDPTNAKEN); - break; - default: - lpc313x_putreg(0, LPC313X_USBDEV_ENDPTNAKEN); - break; - } -} - -/******************************************************************************* - * Name: lpc313x_ep0setup - * - * Description: - * USB Ctrl EP Setup Event. This is logically part of the USB interrupt - * handler. This event occurs when a setup packet is receive on EP0 OUT. - * - *******************************************************************************/ - -static inline void lpc313x_ep0setup(struct lpc313x_usbdev_s *priv) -{ - struct lpc313x_ep_s *privep; - struct usb_ctrlreq_s ctrl; - uint16_t value; - uint16_t index; - uint16_t len; - - /* Terminate any pending requests - since all DTDs will have been retired - * because of the setup packet */ - - lpc313x_cancelrequests(&priv->eplist[LPC313X_EP0_OUT], -EPROTO); - lpc313x_cancelrequests(&priv->eplist[LPC313X_EP0_IN], -EPROTO); - - /* Assume NOT stalled */ - - priv->eplist[LPC313X_EP0_OUT].stalled = false; - priv->eplist[LPC313X_EP0_IN].stalled = false; - priv->stalled = false; - - /* Read EP0 setup data */ - lpc313x_readsetup(LPC313X_EP0_OUT, &ctrl); - - /* Starting a control request - update state */ - lpc313x_ep0state (priv, (ctrl.type & USB_REQ_DIR_IN) ? EP0STATE_SETUP_IN : EP0STATE_SETUP_OUT); - - /* And extract the little-endian 16-bit values to host order */ - value = GETUINT16(ctrl.value); - index = GETUINT16(ctrl.index); - len = GETUINT16(ctrl.len); - - ullvdbg("type=%02x req=%02x value=%04x index=%04x len=%04x\n", - ctrl.type, ctrl.req, value, index, len); - - /* Dispatch any non-standard requests */ - if ((ctrl.type & USB_REQ_TYPE_MASK) != USB_REQ_TYPE_STANDARD) - lpc313x_dispatchrequest(priv, &ctrl); - else - { - /* Handle standard request. Pick off the things of interest to the USB - * device controller driver; pass what is left to the class driver */ - switch (ctrl.req) - { - case USB_REQ_GETSTATUS: - { - /* type: device-to-host; recipient = device, interface, endpoint - * value: 0 - * index: zero interface endpoint - * len: 2; data = status - */ - - usbtrace(TRACE_INTDECODE(LPC313X_TRACEINTID_GETSTATUS), 0); - if (!priv->paddrset || len != 2 || - (ctrl.type & USB_REQ_DIR_IN) == 0 || value != 0) - { - priv->stalled = true; - } - else - { - switch (ctrl.type & USB_REQ_RECIPIENT_MASK) - { - case USB_REQ_RECIPIENT_ENDPOINT: - { - usbtrace(TRACE_INTDECODE(LPC313X_TRACEINTID_EPGETSTATUS), 0); - privep = lpc313x_epfindbyaddr(priv, index); - if (!privep) - { - usbtrace(TRACE_DEVERROR(LPC313X_TRACEERR_BADEPGETSTATUS), 0); - priv->stalled = true; - } - else - { - if (privep->stalled) - priv->ep0buf[0] = 1; /* Stalled */ - else - priv->ep0buf[0] = 0; /* Not stalled */ - priv->ep0buf[1] = 0; - - lpc313x_ep0xfer (LPC313X_EP0_IN, priv->ep0buf, 2); - lpc313x_ep0state (priv, EP0STATE_SHORTWRITE); - } - } - break; - - case USB_REQ_RECIPIENT_DEVICE: - { - if (index == 0) - { - usbtrace(TRACE_INTDECODE(LPC313X_TRACEINTID_DEVGETSTATUS), 0); - - /* Features: Remote Wakeup=YES; selfpowered=? */ - - priv->ep0buf[0] = (priv->selfpowered << USB_FEATURE_SELFPOWERED) | - (1 << USB_FEATURE_REMOTEWAKEUP); - priv->ep0buf[1] = 0; - - lpc313x_ep0xfer(LPC313X_EP0_IN, priv->ep0buf, 2); - lpc313x_ep0state (priv, EP0STATE_SHORTWRITE); - } - else - { - usbtrace(TRACE_DEVERROR(LPC313X_TRACEERR_BADDEVGETSTATUS), 0); - priv->stalled = true; - } - } - break; - - case USB_REQ_RECIPIENT_INTERFACE: - { - usbtrace(TRACE_INTDECODE(LPC313X_TRACEINTID_IFGETSTATUS), 0); - priv->ep0buf[0] = 0; - priv->ep0buf[1] = 0; - - lpc313x_ep0xfer(LPC313X_EP0_IN, priv->ep0buf, 2); - lpc313x_ep0state (priv, EP0STATE_SHORTWRITE); - } - break; - - default: - { - usbtrace(TRACE_DEVERROR(LPC313X_TRACEERR_BADGETSTATUS), 0); - priv->stalled = true; - } - break; - } - } - } - break; - - case USB_REQ_CLEARFEATURE: - { - /* type: host-to-device; recipient = device, interface or endpoint - * value: feature selector - * index: zero interface endpoint; - * len: zero, data = none - */ - - usbtrace(TRACE_INTDECODE(LPC313X_TRACEINTID_CLEARFEATURE), 0); - if ((ctrl.type & USB_REQ_RECIPIENT_MASK) != USB_REQ_RECIPIENT_ENDPOINT) - { - lpc313x_dispatchrequest(priv, &ctrl); - } - else if (priv->paddrset != 0 && value == USB_FEATURE_ENDPOINTHALT && len == 0 && - (privep = lpc313x_epfindbyaddr(priv, index)) != NULL) - { - lpc313x_epstall(&privep->ep, true); - - lpc313x_ep0state (priv, EP0STATE_WAIT_NAK_IN); - } - else - { - usbtrace(TRACE_DEVERROR(LPC313X_TRACEERR_BADCLEARFEATURE), 0); - priv->stalled = true; - } - } - break; - - case USB_REQ_SETFEATURE: - { - /* type: host-to-device; recipient = device, interface, endpoint - * value: feature selector - * index: zero interface endpoint; - * len: 0; data = none - */ - - usbtrace(TRACE_INTDECODE(LPC313X_TRACEINTID_SETFEATURE), 0); - if (((ctrl.type & USB_REQ_RECIPIENT_MASK) == USB_REQ_RECIPIENT_DEVICE) && - value == USB_FEATURE_TESTMODE) - { - ullvdbg("test mode: %d\n", index); - } - else if ((ctrl.type & USB_REQ_RECIPIENT_MASK) != USB_REQ_RECIPIENT_ENDPOINT) - { - lpc313x_dispatchrequest(priv, &ctrl); - } - else if (priv->paddrset != 0 && value == USB_FEATURE_ENDPOINTHALT && len == 0 && - (privep = lpc313x_epfindbyaddr(priv, index)) != NULL) - { - lpc313x_epstall(&privep->ep, false); - - lpc313x_ep0state (priv, EP0STATE_WAIT_NAK_IN); - } - else - { - usbtrace(TRACE_DEVERROR(LPC313X_TRACEERR_BADSETFEATURE), 0); - priv->stalled = true; - } - } - break; - - case USB_REQ_SETADDRESS: - { - /* type: host-to-device; recipient = device - * value: device address - * index: 0 - * len: 0; data = none - */ - usbtrace(TRACE_INTDECODE(LPC313X_TRACEINTID_EP0SETUPSETADDRESS), value); - if ((ctrl.type & USB_REQ_RECIPIENT_MASK) == USB_REQ_RECIPIENT_DEVICE && - index == 0 && len == 0 && value < 128) - { - /* Save the address. We cannot actually change to the next address until - * the completion of the status phase. */ - - priv->paddr = ctrl.value[0]; - priv->paddrset = false; - - lpc313x_ep0state (priv, EP0STATE_WAIT_NAK_IN); - } - else - { - usbtrace(TRACE_DEVERROR(LPC313X_TRACEERR_BADSETADDRESS), 0); - priv->stalled = true; - } - } - break; - - case USB_REQ_GETDESCRIPTOR: - /* type: device-to-host; recipient = device - * value: descriptor type and index - * index: 0 or language ID; - * len: descriptor len; data = descriptor - */ - case USB_REQ_SETDESCRIPTOR: - /* type: host-to-device; recipient = device - * value: descriptor type and index - * index: 0 or language ID; - * len: descriptor len; data = descriptor - */ - { - usbtrace(TRACE_INTDECODE(LPC313X_TRACEINTID_GETSETDESC), 0); - if ((ctrl.type & USB_REQ_RECIPIENT_MASK) == USB_REQ_RECIPIENT_DEVICE) - { - lpc313x_dispatchrequest(priv, &ctrl); - } - else - { - usbtrace(TRACE_DEVERROR(LPC313X_TRACEERR_BADGETSETDESC), 0); - priv->stalled = true; - } - } - break; - - case USB_REQ_GETCONFIGURATION: - /* type: device-to-host; recipient = device - * value: 0; - * index: 0; - * len: 1; data = configuration value - */ - { - usbtrace(TRACE_INTDECODE(LPC313X_TRACEINTID_GETCONFIG), 0); - if (priv->paddrset && (ctrl.type & USB_REQ_RECIPIENT_MASK) == USB_REQ_RECIPIENT_DEVICE && - value == 0 && index == 0 && len == 1) - { - lpc313x_dispatchrequest(priv, &ctrl); - } - else - { - usbtrace(TRACE_DEVERROR(LPC313X_TRACEERR_BADGETCONFIG), 0); - priv->stalled = true; - } - } - break; - - case USB_REQ_SETCONFIGURATION: - /* type: host-to-device; recipient = device - * value: configuration value - * index: 0; - * len: 0; data = none - */ - { - usbtrace(TRACE_INTDECODE(LPC313X_TRACEINTID_SETCONFIG), 0); - if ((ctrl.type & USB_REQ_RECIPIENT_MASK) == USB_REQ_RECIPIENT_DEVICE && - index == 0 && len == 0) - { - lpc313x_dispatchrequest(priv, &ctrl); - } - else - { - usbtrace(TRACE_DEVERROR(LPC313X_TRACEERR_BADSETCONFIG), 0); - priv->stalled = true; - } - } - break; - - case USB_REQ_GETINTERFACE: - /* type: device-to-host; recipient = interface - * value: 0 - * index: interface; - * len: 1; data = alt interface - */ - case USB_REQ_SETINTERFACE: - /* type: host-to-device; recipient = interface - * value: alternate setting - * index: interface; - * len: 0; data = none - */ - { - usbtrace(TRACE_INTDECODE(LPC313X_TRACEINTID_GETSETIF), 0); - lpc313x_dispatchrequest(priv, &ctrl); - } - break; - - case USB_REQ_SYNCHFRAME: - /* type: device-to-host; recipient = endpoint - * value: 0 - * index: endpoint; - * len: 2; data = frame number - */ - { - usbtrace(TRACE_INTDECODE(LPC313X_TRACEINTID_SYNCHFRAME), 0); - } - break; - - default: - { - usbtrace(TRACE_DEVERROR(LPC313X_TRACEERR_INVALIDCTRLREQ), 0); - priv->stalled = true; - } - break; - } - } - - if (priv->stalled) - { - usbtrace(TRACE_DEVERROR(LPC313X_TRACEERR_EP0SETUPSTALLED), priv->ep0state); - lpc313x_epstall(&priv->eplist[LPC313X_EP0_IN].ep, false); - lpc313x_epstall(&priv->eplist[LPC313X_EP0_OUT].ep, false); - } -} - -/******************************************************************************* - * Name: lpc313x_ep0complete - * - * Description: - * Transfer complete handler for Endpoint 0 - * - *******************************************************************************/ - -static void lpc313x_ep0complete(struct lpc313x_usbdev_s *priv, uint8_t epphy) -{ - struct lpc313x_ep_s *privep = &priv->eplist[epphy]; - - usbtrace(TRACE_INTDECODE(LPC313X_TRACEINTID_EP0COMPLETE), (uint16_t)priv->ep0state); - - switch (priv->ep0state) - { - case EP0STATE_DATA_IN: - if (lpc313x_rqempty(privep)) - return; - - if (lpc313x_epcomplete (priv, epphy)) - lpc313x_ep0state (priv, EP0STATE_WAIT_NAK_OUT); - break; - - case EP0STATE_DATA_OUT: - if (lpc313x_rqempty(privep)) - return; - - if (lpc313x_epcomplete (priv, epphy)) - lpc313x_ep0state (priv, EP0STATE_WAIT_NAK_IN); - break; - - case EP0STATE_SHORTWRITE: - lpc313x_ep0state (priv, EP0STATE_WAIT_NAK_OUT); - break; - - case EP0STATE_WAIT_STATUS_IN: - lpc313x_ep0state (priv, EP0STATE_IDLE); - - /* If we've received a SETADDRESS packet, then we set the address - * now that the status phase has completed */ - if (! priv->paddrset && priv->paddr != 0) - { - usbtrace(TRACE_INTDECODE(LPC313X_TRACEINTID_EP0INSETADDRESS), (uint16_t)priv->paddr); - lpc313x_set_address (priv, priv->paddr); - } - break; - - case EP0STATE_WAIT_STATUS_OUT: - lpc313x_ep0state (priv, EP0STATE_IDLE); - break; - - default: -#ifdef CONFIG_DEBUG - DEBUGASSERT(priv->ep0state != EP0STATE_DATA_IN && - priv->ep0state != EP0STATE_DATA_OUT && - priv->ep0state != EP0STATE_SHORTWRITE && - priv->ep0state != EP0STATE_WAIT_STATUS_IN && - priv->ep0state != EP0STATE_WAIT_STATUS_OUT); -#endif - priv->stalled = true; - break; - } - - if (priv->stalled) - { - usbtrace(TRACE_DEVERROR(LPC313X_TRACEERR_EP0SETUPSTALLED), priv->ep0state); - lpc313x_epstall(&priv->eplist[LPC313X_EP0_IN].ep, false); - lpc313x_epstall(&priv->eplist[LPC313X_EP0_OUT].ep, false); - } -} - -/******************************************************************************* - * Name: lpc313x_ep0nak - * - * Description: - * Handle a NAK interrupt on EP0 - * - *******************************************************************************/ - -static void lpc313x_ep0nak(struct lpc313x_usbdev_s *priv, uint8_t epphy) -{ - usbtrace(TRACE_INTDECODE(LPC313X_TRACEINTID_EP0NAK), (uint16_t)priv->ep0state); - - switch (priv->ep0state) - { - case EP0STATE_WAIT_NAK_IN: - lpc313x_ep0xfer (LPC313X_EP0_IN, NULL, 0); - lpc313x_ep0state (priv, EP0STATE_WAIT_STATUS_IN); - break; - case EP0STATE_WAIT_NAK_OUT: - lpc313x_ep0xfer (LPC313X_EP0_OUT, NULL, 0); - lpc313x_ep0state (priv, EP0STATE_WAIT_STATUS_OUT); - break; - default: -#ifdef CONFIG_DEBUG - DEBUGASSERT(priv->ep0state != EP0STATE_WAIT_NAK_IN && - priv->ep0state != EP0STATE_WAIT_NAK_OUT); -#endif - priv->stalled = true; - break; - } - if (priv->stalled) - { - usbtrace(TRACE_DEVERROR(LPC313X_TRACEERR_EP0SETUPSTALLED), priv->ep0state); - lpc313x_epstall(&priv->eplist[LPC313X_EP0_IN].ep, false); - lpc313x_epstall(&priv->eplist[LPC313X_EP0_OUT].ep, false); - } -} - -/******************************************************************************* - * Name: lpc313x_epcomplete - * - * Description: - * Transfer complete handler for Endpoints other than 0 - * returns whether the request at the head has completed - * - *******************************************************************************/ - -bool -lpc313x_epcomplete(struct lpc313x_usbdev_s *priv, uint8_t epphy) -{ - struct lpc313x_ep_s *privep = &priv->eplist[epphy]; - struct lpc313x_req_s *privreq = privep->head; - struct lpc313x_dtd_s *dtd = &g_td[epphy]; - - if (privreq == NULL) /* This shouldn't really happen */ - { - if (LPC313X_EPPHYOUT(privep->epphy)) - usbtrace(TRACE_INTDECODE(LPC313X_TRACEINTID_EPINQEMPTY), 0); - else - usbtrace(TRACE_INTDECODE(LPC313X_TRACEINTID_EPOUTQEMPTY), 0); - return true; - } - - int xfrd = dtd->xfer_len - (dtd->config >> 16); - - privreq->req.xfrd += xfrd; - - bool complete = true; - if (LPC313X_EPPHYOUT(privep->epphy)) - { - /* read(OUT) completes when request filled, or a short transfer is received */ - - usbtrace(TRACE_INTDECODE(LPC313X_TRACEINTID_EPIN), complete); - } - else - { - /* write(IN) completes when request finished, unless we need to terminate with a ZLP */ - - bool need_zlp = (xfrd == privep->ep.maxpacket) && ((privreq->req.flags & USBDEV_REQFLAGS_NULLPKT) != 0); - - complete = (privreq->req.xfrd >= privreq->req.len && !need_zlp); - - usbtrace(TRACE_INTDECODE(LPC313X_TRACEINTID_EPOUT), complete); - } - - /* If the transfer is complete, then dequeue and progress any further queued requests */ - - if (complete) - { - privreq = lpc313x_rqdequeue (privep); - } - - if (!lpc313x_rqempty(privep)) - { - lpc313x_progressep(privep); - } - - /* Now it's safe to call the completion callback as it may well submit a new request */ - - if (complete) - { - usbtrace(TRACE_COMPLETE(privep->epphy), privreq->req.xfrd); - lpc313x_reqcomplete(privep, privreq, OK); - } - - return complete; -} - - -/******************************************************************************* - * Name: lpc313x_usbinterrupt - * - * Description: - * USB interrupt handler - * - *******************************************************************************/ - -static int lpc313x_usbinterrupt(int irq, FAR void *context) -{ - struct lpc313x_usbdev_s *priv = &g_usbdev; - uint32_t disr, portsc1, n; - - usbtrace(TRACE_INTENTRY(LPC313X_TRACEINTID_USB), 0); - - /* Read the interrupts and then clear them */ - disr = lpc313x_getreg(LPC313X_USBDEV_USBSTS); - lpc313x_putreg(disr, LPC313X_USBDEV_USBSTS); - - if (disr & USBDEV_USBSTS_URI) - { - usbtrace(TRACE_INTDECODE(LPC313X_TRACEINTID_DEVRESET),0); - - lpc313x_usbreset(priv); - - usbtrace(TRACE_INTEXIT(LPC313X_TRACEINTID_USB), 0); - return OK; - } - - if (disr & USBDEV_USBSTS_SLI) - { - // FIXME: what do we need to do here... - usbtrace(TRACE_INTDECODE(LPC313X_TRACEINTID_SUSPENDCHG),0); - } - - if (disr & USBDEV_USBSTS_PCI) - { - portsc1 = lpc313x_getreg(LPC313X_USBDEV_PORTSC1); - - if (portsc1 & USBDEV_PRTSC1_HSP) - priv->usbdev.speed = USB_SPEED_HIGH; - else - priv->usbdev.speed = USB_SPEED_FULL; - - if (portsc1 & USBDEV_PRTSC1_FPR) - { - /* FIXME: this occurs because of a J-to-K transition detected - * while the port is in SUSPEND state - presumambly this - * is where the host is resuming the device? - * - * - but do we need to "ack" the interrupt - */ - } - } - -#ifdef CONFIG_LPC313X_USBDEV_FRAME_INTERRUPT - if (disr & USBDEV_USBSTT_SRI) - { - usbtrace(TRACE_INTDECODE(LPC313X_TRACEINTID_FRAME), 0); - - priv->sof = (int)lpc313x_getreg(LPC313X_USBDEV_FRINDEX_OFFSET); - } -#endif - - if (disr & USBDEV_USBSTS_UEI) - { - /* FIXME: these occur when a transfer results in an error condition - * it is set alongside USBINT if the DTD also had its IOC - * bit set. */ - } - - if (disr & USBDEV_USBSTS_UI) - { - /* Handle completion interrupts */ - uint32_t mask = lpc313x_getreg (LPC313X_USBDEV_ENDPTCOMPLETE); - - if (mask) - { - // Clear any NAK interrupt and completion interrupts - lpc313x_putreg (mask, LPC313X_USBDEV_ENDPTNAK); - lpc313x_putreg (mask, LPC313X_USBDEV_ENDPTCOMPLETE); - - if (mask & LPC313X_ENDPTMASK(0)) - lpc313x_ep0complete(priv, 0); - if (mask & LPC313X_ENDPTMASK(1)) - lpc313x_ep0complete(priv, 1); - - for (n = 1; n < LPC313X_NLOGENDPOINTS; n++) - { - if (mask & LPC313X_ENDPTMASK((n<<1))) - lpc313x_epcomplete (priv, (n<<1)); - if (mask & LPC313X_ENDPTMASK((n<<1)+1)) - lpc313x_epcomplete(priv, (n<<1)+1); - } - } - - /* Handle setup interrupts */ - uint32_t setupstat = lpc313x_getreg(LPC313X_USBDEV_ENDPTSETUPSTAT); - if (setupstat) - { - /* Clear the endpoint complete CTRL OUT and IN when a Setup is received */ - lpc313x_putreg (LPC313X_ENDPTMASK(LPC313X_EP0_IN) | LPC313X_ENDPTMASK(LPC313X_EP0_OUT), - LPC313X_USBDEV_ENDPTCOMPLETE); - - if (setupstat & LPC313X_ENDPTMASK(LPC313X_EP0_OUT)) - { - usbtrace(TRACE_INTDECODE(LPC313X_TRACEINTID_EP0SETUP), setupstat); - lpc313x_ep0setup(priv); - } - } - } - - if (disr & USBDEV_USBSTS_NAKI) - { - uint32_t pending = lpc313x_getreg(LPC313X_USBDEV_ENDPTNAK) & lpc313x_getreg(LPC313X_USBDEV_ENDPTNAKEN); - if (pending) - { - /* We shouldn't see NAK interrupts except on Endpoint 0 */ - if (pending & LPC313X_ENDPTMASK(0)) - lpc313x_ep0nak(priv, 0); - if (pending & LPC313X_ENDPTMASK(1)) - lpc313x_ep0nak(priv, 1); - } - - // clear the interrupts - lpc313x_putreg(pending, LPC313X_USBDEV_ENDPTNAK); - } - usbtrace(TRACE_INTEXIT(LPC313X_TRACEINTID_USB), 0); - return OK; -} - -/******************************************************************************* - * Endpoint operations - *******************************************************************************/ - -/******************************************************************************* - * Name: lpc313x_epconfigure - * - * Description: - * Configure endpoint, making it usable - * - * Input Parameters: - * ep - the struct usbdev_ep_s instance obtained from allocep() - * desc - A struct usb_epdesc_s instance describing the endpoint - * last - true if this this last endpoint to be configured. Some hardware - * needs to take special action when all of the endpoints have been - * configured. - * - *******************************************************************************/ - -static int lpc313x_epconfigure(FAR struct usbdev_ep_s *ep, - FAR const struct usb_epdesc_s *desc, - bool last) -{ - FAR struct lpc313x_ep_s *privep = (FAR struct lpc313x_ep_s *)ep; - - usbtrace(TRACE_EPCONFIGURE, privep->epphy); - DEBUGASSERT(desc->addr == ep->eplog); - - // Initialise EP capabilities - - uint16_t maxsize = GETUINT16(desc->mxpacketsize); - if ((desc->attr & USB_EP_ATTR_XFERTYPE_MASK) == USB_EP_ATTR_XFER_ISOC) - { - g_qh[privep->epphy].capability = (DQH_CAPABILITY_MAX_PACKET(maxsize) | - DQH_CAPABILITY_IOS | - DQH_CAPABILITY_ZLT); - } - else - { - g_qh[privep->epphy].capability = (DQH_CAPABILITY_MAX_PACKET(maxsize) | - DQH_CAPABILITY_ZLT); - } - - /* Setup Endpoint Control Register */ - - if (LPC313X_EPPHYIN(privep->epphy)) - { - /* Reset the data toggles */ - uint32_t cfg = USBDEV_ENDPTCTRL_TXR; - - /* Set the endpoint type */ - switch (desc->attr & USB_EP_ATTR_XFERTYPE_MASK) - { - case USB_EP_ATTR_XFER_CONTROL: cfg |= USBDEV_ENDPTCTRL_TXT_CTRL; break; - case USB_EP_ATTR_XFER_ISOC: cfg |= USBDEV_ENDPTCTRL_TXT_ISOC; break; - case USB_EP_ATTR_XFER_BULK: cfg |= USBDEV_ENDPTCTRL_TXT_BULK; break; - case USB_EP_ATTR_XFER_INT: cfg |= USBDEV_ENDPTCTRL_TXT_INTR; break; - } - lpc313x_chgbits (0xFFFF0000, cfg, LPC313X_USBDEV_ENDPTCTRL(privep->epphy)); - } - else - { - /* Reset the data toggles */ - uint32_t cfg = USBDEV_ENDPTCTRL_RXR; - - /* Set the endpoint type */ - switch (desc->attr & USB_EP_ATTR_XFERTYPE_MASK) - { - case USB_EP_ATTR_XFER_CONTROL: cfg |= USBDEV_ENDPTCTRL_RXT_CTRL; break; - case USB_EP_ATTR_XFER_ISOC: cfg |= USBDEV_ENDPTCTRL_RXT_ISOC; break; - case USB_EP_ATTR_XFER_BULK: cfg |= USBDEV_ENDPTCTRL_RXT_BULK; break; - } - lpc313x_chgbits (0x0000FFFF, cfg, LPC313X_USBDEV_ENDPTCTRL(privep->epphy)); - } - - /* Reset endpoint status */ - privep->stalled = false; - - /* Enable the endpoint */ - if (LPC313X_EPPHYIN(privep->epphy)) - lpc313x_setbits (USBDEV_ENDPTCTRL_TXE, LPC313X_USBDEV_ENDPTCTRL(privep->epphy)); - else - lpc313x_setbits (USBDEV_ENDPTCTRL_RXE, LPC313X_USBDEV_ENDPTCTRL(privep->epphy)); - - return OK; -} - -/******************************************************************************* - * Name: lpc313x_epdisable - * - * Description: - * The endpoint will no longer be used - * - *******************************************************************************/ - -static int lpc313x_epdisable(FAR struct usbdev_ep_s *ep) -{ - FAR struct lpc313x_ep_s *privep = (FAR struct lpc313x_ep_s *)ep; - irqstate_t flags; - -#ifdef CONFIG_DEBUG - if (!ep) - { - usbtrace(TRACE_DEVERROR(LPC313X_TRACEERR_INVALIDPARMS), 0); - return -EINVAL; - } -#endif - usbtrace(TRACE_EPDISABLE, privep->epphy); - - flags = irqsave(); - - /* Disable Endpoint */ - if (LPC313X_EPPHYIN(privep->epphy)) - lpc313x_clrbits (USBDEV_ENDPTCTRL_TXE, LPC313X_USBDEV_ENDPTCTRL(privep->epphy)); - else - lpc313x_clrbits (USBDEV_ENDPTCTRL_RXE, LPC313X_USBDEV_ENDPTCTRL(privep->epphy)); - - privep->stalled = true; - - /* Cancel any ongoing activity */ - lpc313x_cancelrequests(privep, -ESHUTDOWN); - - irqrestore(flags); - return OK; -} - -/******************************************************************************* - * Name: lpc313x_epallocreq - * - * Description: - * Allocate an I/O request - * - *******************************************************************************/ - -static FAR struct usbdev_req_s *lpc313x_epallocreq(FAR struct usbdev_ep_s *ep) -{ - FAR struct lpc313x_req_s *privreq; - -#ifdef CONFIG_DEBUG - if (!ep) - { - usbtrace(TRACE_DEVERROR(LPC313X_TRACEERR_INVALIDPARMS), 0); - return NULL; - } -#endif - usbtrace(TRACE_EPALLOCREQ, ((FAR struct lpc313x_ep_s *)ep)->epphy); - - privreq = (FAR struct lpc313x_req_s *)malloc(sizeof(struct lpc313x_req_s)); - if (!privreq) - { - usbtrace(TRACE_DEVERROR(LPC313X_TRACEERR_ALLOCFAIL), 0); - return NULL; - } - - memset(privreq, 0, sizeof(struct lpc313x_req_s)); - - return &privreq->req; -} - -/******************************************************************************* - * Name: lpc313x_epfreereq - * - * Description: - * Free an I/O request - * - *******************************************************************************/ - -static void lpc313x_epfreereq(FAR struct usbdev_ep_s *ep, FAR struct usbdev_req_s *req) -{ - FAR struct lpc313x_req_s *privreq = (FAR struct lpc313x_req_s *)req; - -#ifdef CONFIG_DEBUG - if (!ep || !req) - { - usbtrace(TRACE_DEVERROR(LPC313X_TRACEERR_INVALIDPARMS), 0); - return; - } -#endif - - usbtrace(TRACE_EPFREEREQ, ((FAR struct lpc313x_ep_s *)ep)->epphy); - - free(privreq); -} - -/******************************************************************************* - * Name: lpc313x_epallocbuffer - * - * Description: - * Allocate an I/O buffer - * - *******************************************************************************/ - -#ifdef CONFIG_ARCH_USBDEV_DMA -static void *lpc313x_epallocbuffer(FAR struct usbdev_ep_s *ep, unsigned bytes) -{ - usbtrace(TRACE_EPALLOCBUFFER, privep->epphy); - return malloc(bytes) -} -#endif - -/******************************************************************************* - * Name: lpc313x_epfreebuffer - * - * Description: - * Free an I/O buffer - * - *******************************************************************************/ - -#ifdef CONFIG_LPC313x_USBDEV_DMA -static void lpc313x_epfreebuffer(FAR struct usbdev_ep_s *ep, FAR void *buf) -{ - usbtrace(TRACE_EPFREEBUFFER, privep->epphy); - free(buf); -} -#endif - -/******************************************************************************* - * Name: lpc313x_epsubmit - * - * Description: - * Submit an I/O request to the endpoint - * - *******************************************************************************/ - -static int lpc313x_epsubmit(FAR struct usbdev_ep_s *ep, FAR struct usbdev_req_s *req) -{ - FAR struct lpc313x_req_s *privreq = (FAR struct lpc313x_req_s *)req; - FAR struct lpc313x_ep_s *privep = (FAR struct lpc313x_ep_s *)ep; - FAR struct lpc313x_usbdev_s *priv; - irqstate_t flags; - int ret = OK; - -#ifdef CONFIG_DEBUG - if (!req || !req->callback || !req->buf || !ep) - { - usbtrace(TRACE_DEVERROR(LPC313X_TRACEERR_INVALIDPARMS), 0); - ullvdbg("req=%p callback=%p buf=%p ep=%p\n", req, req->callback, req->buf, ep); - return -EINVAL; - } -#endif - - usbtrace(TRACE_EPSUBMIT, privep->epphy); - priv = privep->dev; - - if (!priv->driver || priv->usbdev.speed == USB_SPEED_UNKNOWN) - { - usbtrace(TRACE_DEVERROR(LPC313X_TRACEERR_NOTCONFIGURED), priv->usbdev.speed); - return -ESHUTDOWN; - } - - /* Handle the request from the class driver */ - - req->result = -EINPROGRESS; - req->xfrd = 0; - - /* Disable Interrupts */ - - flags = irqsave(); - - /* If we are stalled, then drop all requests on the floor */ - - if (privep->stalled) - { - ret = -EBUSY; - } - else - { - /* Add the new request to the request queue for the endpoint */ - - if (LPC313X_EPPHYIN(privep->epphy)) - usbtrace(TRACE_INREQQUEUED(privep->epphy), privreq->req.len); - else - usbtrace(TRACE_OUTREQQUEUED(privep->epphy), privreq->req.len); - - if (lpc313x_rqenqueue(privep, privreq)) - { - lpc313x_progressep(privep); - } - } - - irqrestore(flags); - return ret; -} - -/******************************************************************************* - * Name: lpc313x_epcancel - * - * Description: - * Cancel an I/O request previously sent to an endpoint - * - *******************************************************************************/ - -static int lpc313x_epcancel(FAR struct usbdev_ep_s *ep, FAR struct usbdev_req_s *req) -{ - FAR struct lpc313x_ep_s *privep = (FAR struct lpc313x_ep_s *)ep; - FAR struct lpc313x_usbdev_s *priv; - irqstate_t flags; - -#ifdef CONFIG_DEBUG - if (!ep || !req) - { - usbtrace(TRACE_DEVERROR(LPC313X_TRACEERR_INVALIDPARMS), 0); - return -EINVAL; - } -#endif - - usbtrace(TRACE_EPCANCEL, privep->epphy); - priv = privep->dev; - - flags = irqsave(); - - /* FIXME: if the request is the first, then we need to flush the EP - * otherwise just remove it from the list - * - * but ... all other implementations cancel all requests ... - */ - - lpc313x_cancelrequests(privep, -ESHUTDOWN); - irqrestore(flags); - return OK; -} - -/******************************************************************************* - * Name: lpc313x_epstall - * - * Description: - * Stall or resume and endpoint - * - *******************************************************************************/ - -static int lpc313x_epstall(FAR struct usbdev_ep_s *ep, bool resume) -{ - FAR struct lpc313x_ep_s *privep = (FAR struct lpc313x_ep_s *)ep; - irqstate_t flags; - - /* STALL or RESUME the endpoint */ - - flags = irqsave(); - usbtrace(resume ? TRACE_EPRESUME : TRACE_EPSTALL, privep->epphy); - - uint32_t addr = LPC313X_USBDEV_ENDPTCTRL(privep->epphy); - uint32_t ctrl_xs = LPC313X_EPPHYIN(privep->epphy) ? USBDEV_ENDPTCTRL_TXS : USBDEV_ENDPTCTRL_RXS; - uint32_t ctrl_xr = LPC313X_EPPHYIN(privep->epphy) ? USBDEV_ENDPTCTRL_TXR : USBDEV_ENDPTCTRL_RXR; - - if (resume) - { - privep->stalled = false; - - /* Clear stall and reset the data toggle */ - - lpc313x_chgbits (ctrl_xs | ctrl_xr, ctrl_xr, addr); - } - else - { - privep->stalled = true; - - lpc313x_setbits (ctrl_xs, addr); - } - - irqrestore(flags); - return OK; -} - -/******************************************************************************* - * Device operations - *******************************************************************************/ - -/******************************************************************************* - * Name: lcp313x_allocep - * - * Description: - * Allocate an endpoint matching the parameters. - * - * Input Parameters: - * eplog - 7-bit logical endpoint number (direction bit ignored). Zero means - * that any endpoint matching the other requirements will suffice. The - * assigned endpoint can be found in the eplog field. - * in - true: IN (device-to-host) endpoint requested - * eptype - Endpoint type. One of {USB_EP_ATTR_XFER_ISOC, USB_EP_ATTR_XFER_BULK, - * USB_EP_ATTR_XFER_INT} - * - *******************************************************************************/ - -static FAR struct usbdev_ep_s *lcp313x_allocep(FAR struct usbdev_s *dev, uint8_t eplog, - bool in, uint8_t eptype) -{ - FAR struct lpc313x_usbdev_s *priv = (FAR struct lpc313x_usbdev_s *)dev; - uint32_t epset = LPC313X_EPALLSET & ~LPC313X_EPCTRLSET; - irqstate_t flags; - int epndx = 0; - - usbtrace(TRACE_DEVALLOCEP, (uint16_t)eplog); - - /* Ignore any direction bits in the logical address */ - - eplog = USB_EPNO(eplog); - - /* A logical address of 0 means that any endpoint will do */ - - if (eplog > 0) - { - /* Otherwise, we will return the endpoint structure only for the requested - * 'logical' endpoint. All of the other checks will still be performed. - * - * First, verify that the logical endpoint is in the range supported by - * by the hardware. - */ - - if (eplog >= LPC313X_NLOGENDPOINTS) - { - usbtrace(TRACE_DEVERROR(LPC313X_TRACEERR_BADEPNO), (uint16_t)eplog); - return NULL; - } - - /* Convert the logical address to a physical OUT endpoint address and - * remove all of the candidate endpoints from the bitset except for the - * the IN/OUT pair for this logical address. - */ - - epset &= 3 << (eplog << 1); - } - - /* Get the subset matching the requested direction */ - - if (in) - { - epset &= LPC313X_EPINSET; - } - else - { - epset &= LPC313X_EPOUTSET; - } - - /* Get the subset matching the requested type */ - - switch (eptype) - { - case USB_EP_ATTR_XFER_INT: /* Interrupt endpoint */ - epset &= LPC313X_EPINTRSET; - break; - - case USB_EP_ATTR_XFER_BULK: /* Bulk endpoint */ - epset &= LPC313X_EPBULKSET; - break; - - case USB_EP_ATTR_XFER_ISOC: /* Isochronous endpoint */ - epset &= LPC313X_EPISOCSET; - break; - - case USB_EP_ATTR_XFER_CONTROL: /* Control endpoint -- not a valid choice */ - default: - usbtrace(TRACE_DEVERROR(LPC313X_TRACEERR_BADEPTYPE), (uint16_t)eptype); - return NULL; - } - - /* Is the resulting endpoint supported by the LPC313x? */ - - if (epset) - { - /* Yes.. now see if any of the request endpoints are available */ - - flags = irqsave(); - epset &= priv->epavail; - if (epset) - { - /* Select the lowest bit in the set of matching, available endpoints */ - - for (epndx = 2; epndx < LPC313X_NPHYSENDPOINTS; epndx++) - { - uint32_t bit = 1 << epndx; - if ((epset & bit) != 0) - { - /* Mark the IN/OUT endpoint no longer available */ - - priv->epavail &= ~(3 << (bit & ~1)); - irqrestore(flags); - - /* And return the pointer to the standard endpoint structure */ - - return &priv->eplist[epndx].ep; - } - } - /* Shouldn't get here */ - } - irqrestore(flags); - } - - usbtrace(TRACE_DEVERROR(LPC313X_TRACEERR_NOEP), (uint16_t)eplog); - return NULL; -} - -/******************************************************************************* - * Name: lpc313x_freeep - * - * Description: - * Free the previously allocated endpoint - * - *******************************************************************************/ - -static void lpc313x_freeep(FAR struct usbdev_s *dev, FAR struct usbdev_ep_s *ep) -{ - FAR struct lpc313x_usbdev_s *priv = (FAR struct lpc313x_usbdev_s *)dev; - FAR struct lpc313x_ep_s *privep = (FAR struct lpc313x_ep_s *)ep; - irqstate_t flags; - - usbtrace(TRACE_DEVFREEEP, (uint16_t)privep->epphy); - - if (priv && privep) - { - /* Mark the endpoint as available */ - - flags = irqsave(); - priv->epavail |= (1 << privep->epphy); - irqrestore(flags); - } -} - -/******************************************************************************* - * Name: lpc313x_getframe - * - * Description: - * Returns the current frame number - * - *******************************************************************************/ - -static int lpc313x_getframe(struct usbdev_s *dev) -{ -#ifdef CONFIG_LPC313X_USBDEV_FRAME_INTERRUPT - FAR struct lpc313x_usbdev_s *priv = (FAR struct lpc313x_usbdev_s *)dev; - - /* Return last valid value of SOF read by the interrupt handler */ - - usbtrace(TRACE_DEVGETFRAME, (uint16_t)priv->sof); - return priv->sof; -#else - /* Return the last frame number detected by the hardware */ - - usbtrace(TRACE_DEVGETFRAME, 0); - - /* FIXME: this actually returns the micro frame number! */ - return (int)lpc313x_getreg(LPC313X_USBDEV_FRINDEX_OFFSET); -#endif -} - -/******************************************************************************* - * Name: lpc313x_wakeup - * - * Description: - * Tries to wake up the host connected to this device - * - *******************************************************************************/ - -static int lpc313x_wakeup(struct usbdev_s *dev) -{ - irqstate_t flags; - - usbtrace(TRACE_DEVWAKEUP, 0); - - flags = irqsave(); - lpc313x_setbits(USBDEV_PRTSC1_FPR, LPC313X_USBDEV_PORTSC1); - irqrestore(flags); - return OK; -} - -/******************************************************************************* - * Name: lpc313x_selfpowered - * - * Description: - * Sets/clears the device selfpowered feature - * - *******************************************************************************/ - -static int lpc313x_selfpowered(struct usbdev_s *dev, bool selfpowered) -{ - FAR struct lpc313x_usbdev_s *priv = (FAR struct lpc313x_usbdev_s *)dev; - - usbtrace(TRACE_DEVSELFPOWERED, (uint16_t)selfpowered); - -#ifdef CONFIG_DEBUG - if (!dev) - { - usbtrace(TRACE_DEVERROR(LPC313X_TRACEERR_INVALIDPARMS), 0); - return -ENODEV; - } -#endif - - priv->selfpowered = selfpowered; - return OK; -} - -/******************************************************************************* - * Name: lpc313x_pullup - * - * Description: - * Software-controlled connect to/disconnect from USB host - * - *******************************************************************************/ - -static int lpc313x_pullup(struct usbdev_s *dev, bool enable) -{ - usbtrace(TRACE_DEVPULLUP, (uint16_t)enable); - - irqstate_t flags = irqsave(); - if (enable) - lpc313x_setbits (USBDEV_USBCMD_RS, LPC313X_USBDEV_USBCMD); - else - lpc313x_clrbits (USBDEV_USBCMD_RS, LPC313X_USBDEV_USBCMD); - irqrestore(flags); - return OK; -} - -/******************************************************************************* - * Public Functions - *******************************************************************************/ - -/******************************************************************************* - * Name: up_usbinitialize - * - * Description: - * Initialize USB hardware. - * - * Assumptions: - * - This function is called very early in the initialization sequence - * - PLL and GIO pin initialization is not performed here but should been in - * the low-level boot logic: PLL1 must be configured for operation at 48MHz - * and P0.23 and PO.31 in PINSEL1 must be configured for Vbus and USB connect - * LED. - * - *******************************************************************************/ - -void up_usbinitialize(void) -{ - struct lpc313x_usbdev_s *priv = &g_usbdev; - int i; - - usbtrace(TRACE_DEVINIT, 0); - - /* Disable USB interrupts */ - - lpc313x_putreg(0, LPC313X_USBDEV_USBINTR); - - /* Initialize the device state structure */ - - memset(priv, 0, sizeof(struct lpc313x_usbdev_s)); - priv->usbdev.ops = &g_devops; - priv->usbdev.ep0 = &priv->eplist[LPC313X_EP0_IN].ep; - priv->epavail = LPC313X_EPALLSET; - - /* Initialize the endpoint list */ - - for (i = 0; i < LPC313X_NPHYSENDPOINTS; i++) - { - uint32_t bit = 1 << i; - - /* Set endpoint operations, reference to driver structure (not - * really necessary because there is only one controller), and - * the physical endpoint number (which is just the index to the - * endpoint). - */ - priv->eplist[i].ep.ops = &g_epops; - priv->eplist[i].dev = priv; - - /* The index, i, is the physical endpoint address; Map this - * to a logical endpoint address usable by the class driver. - */ - - priv->eplist[i].epphy = i; - if (LPC313X_EPPHYIN(i)) - { - priv->eplist[i].ep.eplog = LPC313X_EPPHYIN2LOG(i); - } - else - { - priv->eplist[i].ep.eplog = LPC313X_EPPHYOUT2LOG(i); - } - - /* The maximum packet size may depend on the type of endpoint */ - - if ((LPC313X_EPCTRLSET & bit) != 0) - { - priv->eplist[i].ep.maxpacket = LPC313X_EP0MAXPACKET; - } - else if ((LPC313X_EPINTRSET & bit) != 0) - { - priv->eplist[i].ep.maxpacket = LPC313X_INTRMAXPACKET; - } - else if ((LPC313X_EPBULKSET & bit) != 0) - { - priv->eplist[i].ep.maxpacket = LPC313X_BULKMAXPACKET; - } - else /* if ((LPC313X_EPISOCSET & bit) != 0) */ - { - priv->eplist[i].ep.maxpacket = LPC313X_ISOCMAXPACKET; - } - } - - /* Enable USB to AHB clock and to Event router*/ - - lpc313x_enableclock (CLKID_USBOTGAHBCLK); - lpc313x_enableclock (CLKID_EVENTROUTERPCLK); - - /* Reset USB block */ - - lpc313x_softreset (RESETID_USBOTGAHBRST); - - /* Enable USB OTG PLL and wait for lock */ - - lpc313x_putreg (0, LPC313X_SYSCREG_USB_ATXPLLPDREG); - - uint32_t bank = EVNTRTR_BANK(EVENTRTR_USBATXPLLLOCK); - uint32_t bit = EVNTRTR_BIT(EVENTRTR_USBATXPLLLOCK); - - while (! (lpc313x_getreg(LPC313X_EVNTRTR_RSR(bank)) & (1 << bit))) - ; - - /* Enable USB AHB clock */ - - lpc313x_enableclock (CLKID_USBOTGAHBCLK); - - /* Reset the controller */ - - lpc313x_putreg (USBDEV_USBCMD_RST, LPC313X_USBDEV_USBCMD); - while (lpc313x_getreg (LPC313X_USBDEV_USBCMD) & USBDEV_USBCMD_RST) - ; - - /* Attach USB controller interrupt handler */ - - if (irq_attach(LPC313X_IRQ_USBOTG, lpc313x_usbinterrupt) != 0) - { - usbtrace(TRACE_DEVERROR(LPC313X_TRACEERR_IRQREGISTRATION), - (uint16_t)LPC313X_IRQ_USBOTG); - goto errout; - } - - - /* Program the controller to be the USB device controller */ - - lpc313x_putreg (USBDEV_USBMODE_SDIS | USBDEV_USBMODE_SLOM | USBDEV_USBMODE_CMDEVICE, - LPC313X_USBDEV_USBMODE); - - /* Disconnect device */ - - lpc313x_pullup(&priv->usbdev, false); - - /* Reset/Re-initialize the USB hardware */ - - lpc313x_usbreset(priv); - - return; - -errout: - up_usbuninitialize(); -} - -/******************************************************************************* - * Name: up_usbuninitialize - *******************************************************************************/ - -void up_usbuninitialize(void) -{ - struct lpc313x_usbdev_s *priv = &g_usbdev; - irqstate_t flags; - - usbtrace(TRACE_DEVUNINIT, 0); - - if (priv->driver) - { - usbtrace(TRACE_DEVERROR(LPC313X_TRACEERR_DRIVERREGISTERED), 0); - usbdev_unregister(priv->driver); - } - - /* Disconnect device */ - - flags = irqsave(); - lpc313x_pullup(&priv->usbdev, false); - priv->usbdev.speed = USB_SPEED_UNKNOWN; - - /* Disable and detach IRQs */ - - up_disable_irq(LPC313X_IRQ_USBOTG); - irq_detach(LPC313X_IRQ_USBOTG); - - /* Reset the controller */ - - lpc313x_putreg (USBDEV_USBCMD_RST, LPC313X_USBDEV_USBCMD); - while (lpc313x_getreg (LPC313X_USBDEV_USBCMD) & USBDEV_USBCMD_RST) - ; - - /* Turn off USB power and clocking */ - - lpc313x_disableclock (CLKID_USBOTGAHBCLK); - lpc313x_disableclock (CLKID_EVENTROUTERPCLK); - - - irqrestore(flags); -} - -/******************************************************************************* - * Name: usbdev_register - * - * Description: - * Register a USB device class driver. The class driver's bind() method will be - * called to bind it to a USB device driver. - * - *******************************************************************************/ - -int usbdev_register(struct usbdevclass_driver_s *driver) -{ - int ret; - - usbtrace(TRACE_DEVREGISTER, 0); - -#ifdef CONFIG_DEBUG - if (!driver || !driver->ops->bind || !driver->ops->unbind || - !driver->ops->disconnect || !driver->ops->setup) - { - usbtrace(TRACE_DEVERROR(LPC313X_TRACEERR_INVALIDPARMS), 0); - return -EINVAL; - } - - if (g_usbdev.driver) - { - usbtrace(TRACE_DEVERROR(LPC313X_TRACEERR_DRIVER), 0); - return -EBUSY; - } -#endif - - /* First hook up the driver */ - - g_usbdev.driver = driver; - - /* Then bind the class driver */ - - ret = CLASS_BIND(driver, &g_usbdev.usbdev); - if (ret) - { - usbtrace(TRACE_DEVERROR(LPC313X_TRACEERR_BINDFAILED), (uint16_t)-ret); - g_usbdev.driver = NULL; - } - else - { - /* Enable USB controller interrupts */ - - up_enable_irq(LPC313X_IRQ_USBOTG); - - /* FIXME: nothing seems to call DEV_CONNECT(), but we need to set - * the RS bit to enable the controller. It kind of makes sense - * to do this after the class has bound to us... - * GEN: This bug is really in the class driver. It should make the - * soft connect when it is ready to be enumerated. I have added - * that logic to the class drivers but left this logic here. - */ - - lpc313x_pullup(&g_usbdev.usbdev, true); - } - return ret; -} - -/******************************************************************************* - * Name: usbdev_unregister - * - * Description: - * Un-register usbdev class driver.If the USB device is connected to a USB host, - * it will first disconnect(). The driver is also requested to unbind() and clean - * up any device state, before this procedure finally returns. - * - *******************************************************************************/ - -int usbdev_unregister(struct usbdevclass_driver_s *driver) -{ - usbtrace(TRACE_DEVUNREGISTER, 0); - -#ifdef CONFIG_DEBUG - if (driver != g_usbdev.driver) - { - usbtrace(TRACE_DEVERROR(LPC313X_TRACEERR_INVALIDPARMS), 0); - return -EINVAL; - } -#endif - - /* Unbind the class driver */ - - CLASS_UNBIND(driver, &g_usbdev.usbdev); - - /* Disable USB controller interrupts */ - - up_disable_irq(LPC313X_IRQ_USBOTG); - - /* Unhook the driver */ - - g_usbdev.driver = NULL; - return OK; -} - diff --git a/nuttx/arch/arm/src/lpc313x/lpc313x_usbotg.h b/nuttx/arch/arm/src/lpc313x/lpc313x_usbotg.h deleted file mode 100755 index b2ea9a3b2..000000000 --- a/nuttx/arch/arm/src/lpc313x/lpc313x_usbotg.h +++ /dev/null @@ -1,654 +0,0 @@ -/************************************************************************************************ - * arch/arm/src/lpc313x/lpc313x_usbotg.h - * - * Copyright (C) 2009-2010 Gregory Nutt. All rights reserved. - * Author: Gregory Nutt - * - * 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_LPC313X_USBOTG_H -#define __ARCH_ARM_SRC_LPC313X_USBOTG_H - -/************************************************************************************************ - * Included Files - ************************************************************************************************/ - -#include -#include "lpc313x_memorymap.h" - -/************************************************************************************************ - * Pre-processor Definitions - ************************************************************************************************/ - -/* USBOTG register base address offset into the USBOTG domain ***********************************/ - -#define LPC313X_USBOTG_VBASE (LPC313X_USBOTG_VSECTION) -#define LPC313X_USBOTG_PBASE (LPC313X_USBOTG_PSECTION) - -/* USBOTG register offsets (with respect to the base of the USBOTG domain) **********************/ - /* 0x000 - 0x0ff: Reserved */ -/* Device/host capability registers */ - -#define LPC313X_USBOTG_CAPLENGTH_OFFSET 0x100 /* Capability register length */ -#define LPC313X_USBHOST_HCIVERSION_OFFSET 0x102 /* Host interface version number */ -#define LPC313X_USBHOST_HCSPARAMS_OFFSET 0x104 /* Host controller structural parameters */ -#define LPC313X_USBHOST_HCCPARAMS_OFFSET 0x108 /* Host controller capability parameters */ -#define LPC313X_USBDEV_DCIVERSION_OFFSET 0x120 /* Device interface version number */ -#define LPC313X_USBDEV_DCCPARAMS_OFFSET 0x124 /* Device controller capability parameters */ - -/* Device/host/OTG operational registers */ - -#define LPC313X_USBOTG_USBCMD_OFFSET 0x140 /* USB command (both) */ -#define LPC313X_USBOTG_USBSTS_OFFSET 0x144 /* USB status (both) */ -#define LPC313X_USBOTG_USBINTR_OFFSET 0x148 /* USB interrupt enable (both) */ -#define LPC313X_USBOTG_FRINDEX_OFFSET 0x14C /* USB frame index (both) */ -#define LPC313X_USBOTG_PERIODICLIST_OFFSET 0x154 /* Frame list base address (host) */ -#define LPC313X_USBOTG_DEVICEADDR_OFFSET 0x154 /* USB device address (device) */ -#define LPC313X_USBOTG_ASYNCLISTADDR_OFFSET 0x158 /* Next asynchronous list address (host) */ -#define LPC313X_USBOTG_ENDPOINTLIST_OFFSET 0x158 /* Address of endpoint list in memory (device) */ -#define LPC313X_USBOTG_TTCTRL_OFFSET 0x15C /* Asynchronous buffer status for embedded TT (host) */ -#define LPC313X_USBOTG_BURSTSIZE_OFFSET 0x160 /* Programmable burst size (both) */ -#define LPC313X_USBOTG_TXFILLTUNING_OFFSET 0x164 /* Host transmit pre-buffer packet tuning (host) */ -#define LPC313X_USBOTG_BINTERVAL_OFFSET 0x174 /* Length of virtual frame (both) */ -#define LPC313X_USBOTG_ENDPTNAK_OFFSET 0x178 /* Endpoint NAK (device) */ -#define LPC313X_USBOTG_ENDPTNAKEN_OFFSET 0x17C /* Endpoint NAK Enable (device) */ -#define LPC313X_USBOTG_CONFIGFLAG_OFFSET 0x180 /* Configured flag register (not used in lpc313x) */ -#define LPC313X_USBOTG_PORTSC1_OFFSET 0x184 /* Port status/control 1 (both) */ -#define LPC313X_USBOTG_OTGSC_OFFSET 0x1A4 /* OTG status and control (otg) */ -#define LPC313X_USBOTG_USBMODE_OFFSET 0x1A8 /* USB device mode (both) */ - -#define LPC313X_USBDEV_USBCMD_OFFSET 0x140 /* USB command (both) */ -#define LPC313X_USBDEV_USBSTS_OFFSET 0x144 /* USB status (both) */ -#define LPC313X_USBDEV_USBINTR_OFFSET 0x148 /* USB interrupt enable (both) */ -#define LPC313X_USBDEV_FRINDEX_OFFSET 0x14C /* USB frame index (both) */ -#define LPC313X_USBDEV_DEVICEADDR_OFFSET 0x154 /* USB device address (device) */ -#define LPC313X_USBDEV_ENDPOINTLIST_OFFSET 0x158 /* Address of endpoint list in memory (device) */ -#define LPC313X_USBDEV_BURSTSIZE_OFFSET 0x160 /* Programmable burst size (both) */ -#define LPC313X_USBDEV_BINTERVAL_OFFSET 0x174 /* Length of virtual frame (both) */ -#define LPC313X_USBDEV_ENDPTNAK_OFFSET 0x178 /* Endpoint NAK (device) */ -#define LPC313X_USBDEV_ENDPTNAKEN_OFFSET 0x17C /* Endpoint NAK Enable (device) */ -#define LPC313X_USBDEV_PORTSC1_OFFSET 0x184 /* Port status/control 1 (both) */ -#define LPC313X_USBDEV_USBMODE_OFFSET 0x1A8 /* USB device mode (both) */ - -#define LPC313X_USBHOST_USBCMD_OFFSET 0x140 /* USB command (both) */ -#define LPC313X_USBHOST_USBSTS_OFFSET 0x144 /* USB status (both) */ -#define LPC313X_USBHOST_USBINTR_OFFSET 0x148 /* USB interrupt enable (both) */ -#define LPC313X_USBHOST_FRINDEX_OFFSET 0x14C /* USB frame index (both) */ -#define LPC313X_USBHOST_PERIODICLIST_OFFSET 0x154 /* Frame list base address (host) */ -#define LPC313X_USBHOST_ASYNCLISTADDR_OFFSET 0x158 /* Next asynchronous list address (host) */ -#define LPC313X_USBHOST_TTCTRL_OFFSET 0x15C /* Asynchronous buffer status for embedded TT (host) */ -#define LPC313X_USBHOST_BURSTSIZE_OFFSET 0x160 /* Programmable burst size (both) */ -#define LPC313X_USBHOST_TXFILLTUNING_OFFSET 0x164 /* Host transmit pre-buffer packet tuning (host) */ -#define LPC313X_USBHOST_BINTERVAL_OFFSET 0x174 /* Length of virtual frame (both) */ -#define LPC313X_USBHOST_PORTSC1_OFFSET 0x184 /* Port status/control 1 (both) */ -#define LPC313X_USBHOST_USBMODE_OFFSET 0x1A8 /* USB device mode (both) */ - -/* Device endpoint registers */ - -#define LPC313X_USBDEV_ENDPTSETUPSTAT_OFFSET 0x1AC /* Endpoint setup status */ -#define LPC313X_USBDEV_ENDPTPRIME_OFFSET 0x1B0 /* Endpoint initialization */ -#define LPC313X_USBDEV_ENDPTFLUSH_OFFSET 0x1B4 /* Endpoint de-initialization */ -#define LPC313X_USBDEV_ENDPTSTATUS_OFFSET 0x1B8 /* Endpoint status */ -#define LPC313X_USBDEV_ENDPTCOMPLETE_OFFSET 0x1BC /* Endpoint complete */ -#define LPC313X_USBDEV_ENDPTCTRL0_OFFSET 0x1C0 /* Endpoint control 0 */ -#define LPC313X_USBDEV_ENDPTCTRL1_OFFSET 0x1C4 /* Endpoint control 1 */ -#define LPC313X_USBDEV_ENDPTCTRL2_OFFSET 0x1C8 /* Endpoint control 2 */ -#define LPC313X_USBDEV_ENDPTCTRL3_OFFSET 0x1CC /* Endpoint control 3 */ - -/* USBOTG register (virtual) addresses **********************************************************/ - -/* Device/host capability registers */ - -#define LPC313X_USBOTG_CAPLENGTH (LPC313X_USBOTG_VBASE+LPC313X_USBOTG_CAPLENGTH_OFFSET) -#define LPC313X_USBHOST_HCIVERSION (LPC313X_USBOTG_VBASE+LPC313X_USBHOST_HCIVERSION_OFFSET) -#define LPC313X_USBHOST_HCSPARAMS (LPC313X_USBOTG_VBASE+LPC313X_USBHOST_HCSPARAMS_OFFSET) -#define LPC313X_USBHOST_HCCPARAMS (LPC313X_USBOTG_VBASE+LPC313X_USBHOST_HCCPARAMS_OFFSET) -#define LPC313X_USBDEV_DCIVERSION (LPC313X_USBOTG_VBASE+LPC313X_USBDEV_DCIVERSION_OFFSET) -#define LPC313X_USBDEV_DCCPARAMS (LPC313X_USBOTG_VBASE+LPC313X_USBDEV_DCCPARAMS_OFFSET) - -/* Device/host operational registers */ - -#define LPC313X_USBOTG_USBCMD (LPC313X_USBOTG_VBASE+LPC313X_USBOTG_USBCMD_OFFSET) -#define LPC313X_USBOTG_USBSTS (LPC313X_USBOTG_VBASE+LPC313X_USBOTG_USBSTS_OFFSET) -#define LPC313X_USBOTG_USBINTR (LPC313X_USBOTG_VBASE+LPC313X_USBOTG_USBINTR_OFFSET) -#define LPC313X_USBOTG_FRINDEX (LPC313X_USBOTG_VBASE+LPC313X_USBOTG_FRINDEX_OFFSET) -#define LPC313X_USBOTG_PERIODICLIST (LPC313X_USBOTG_VBASE+LPC313X_USBOTG_PERIODICLIST_OFFSET) -#define LPC313X_USBOTG_DEVICEADDR (LPC313X_USBOTG_VBASE+LPC313X_USBOTG_DEVICEADDR_OFFSET) -#define LPC313X_USBOTG_ASYNCLISTADDR (LPC313X_USBOTG_VBASE+LPC313X_USBOTG_ASYNCLISTADDR_OFFSET) -#define LPC313X_USBOTG_ENDPOINTLIST (LPC313X_USBOTG_VBASE+LPC313X_USBOTG_ENDPOINTLIST_OFFSET) -#define LPC313X_USBOTG_TTCTRL (LPC313X_USBOTG_VBASE+LPC313X_USBOTG_TTCTRL_OFFSET) -#define LPC313X_USBOTG_BURSTSIZE (LPC313X_USBOTG_VBASE+LPC313X_USBOTG_BURSTSIZE_OFFSET) -#define LPC313X_USBOTG_TXFILLTUNING (LPC313X_USBOTG_VBASE+LPC313X_USBOTG_TXFILLTUNING_OFFSET) -#define LPC313X_USBOTG_BINTERVAL (LPC313X_USBOTG_VBASE+LPC313X_USBOTG_BINTERVAL_OFFSET) -#define LPC313X_USBOTG_ENDPTNAK (LPC313X_USBOTG_VBASE+LPC313X_USBOTG_ENDPTNAK_OFFSET) -#define LPC313X_USBOTG_ENDPTNAKEN (LPC313X_USBOTG_VBASE+LPC313X_USBOTG_ENDPTNAKEN_OFFSET) -#define LPC313X_USBOTG_PORTSC1 (LPC313X_USBOTG_VBASE+LPC313X_USBOTG_PORTSC1_OFFSET) -#define LPC313X_USBOTG_OTGSC (LPC313X_USBOTG_VBASE+LPC313X_USBOTG_OTGSC_OFFSET) -#define LPC313X_USBOTG_USBMODE (LPC313X_USBOTG_VBASE+LPC313X_USBOTG_USBMODE_OFFSET) - -#define LPC313X_USBDEV_USBCMD (LPC313X_USBOTG_VBASE+LPC313X_USBDEV_USBCMD_OFFSET) -#define LPC313X_USBDEV_USBSTS (LPC313X_USBOTG_VBASE+LPC313X_USBDEV_USBSTS_OFFSET) -#define LPC313X_USBDEV_USBINTR (LPC313X_USBOTG_VBASE+LPC313X_USBDEV_USBINTR_OFFSET) -#define LPC313X_USBDEV_FRINDEX (LPC313X_USBOTG_VBASE+LPC313X_USBDEV_FRINDEX_OFFSET) -#define LPC313X_USBDEV_DEVICEADDR (LPC313X_USBOTG_VBASE+LPC313X_USBDEV_DEVICEADDR_OFFSET) -#define LPC313X_USBDEV_ENDPOINTLIST (LPC313X_USBOTG_VBASE+LPC313X_USBDEV_ENDPOINTLIST_OFFSET) -#define LPC313X_USBDEV_BURSTSIZE (LPC313X_USBOTG_VBASE+LPC313X_USBDEV_BURSTSIZE_OFFSET) -#define LPC313X_USBDEV_BINTERVAL (LPC313X_USBOTG_VBASE+LPC313X_USBDEV_BINTERVAL_OFFSET) -#define LPC313X_USBDEV_ENDPTNAK (LPC313X_USBOTG_VBASE+LPC313X_USBDEV_ENDPTNAK_OFFSET) -#define LPC313X_USBDEV_ENDPTNAKEN (LPC313X_USBOTG_VBASE+LPC313X_USBDEV_ENDPTNAKEN_OFFSET) -#define LPC313X_USBDEV_PORTSC1 (LPC313X_USBOTG_VBASE+LPC313X_USBDEV_PORTSC1_OFFSET) -#define LPC313X_USBDEV_USBMODE (LPC313X_USBOTG_VBASE+LPC313X_USBDEV_USBMODE_OFFSET) - -#define LPC313X_USBHOST_USBCMD (LPC313X_USBOTG_VBASE+LPC313X_USBHOST_USBCMD_OFFSET) -#define LPC313X_USBHOST_USBSTS (LPC313X_USBOTG_VBASE+LPC313X_USBHOST_USBSTS_OFFSET) -#define LPC313X_USBHOST_USBINTR (LPC313X_USBOTG_VBASE+LPC313X_USBHOST_USBINTR_OFFSET) -#define LPC313X_USBHOST_FRINDEX (LPC313X_USBOTG_VBASE+LPC313X_USBHOST_FRINDEX_OFFSET) -#define LPC313X_USBHOST_PERIODICLIST (LPC313X_USBOTG_VBASE+LPC313X_USBHOST_PERIODICLIST_OFFSET) -#define LPC313X_USBHOST_ASYNCLISTADDR (LPC313X_USBOTG_VBASE+LPC313X_USBHOST_ASYNCLISTADDR_OFFSET) -#define LPC313X_USBHOST_TTCTRL (LPC313X_USBOTG_VBASE+LPC313X_USBHOST_TTCTRL_OFFSET) -#define LPC313X_USBHOST_BURSTSIZE (LPC313X_USBOTG_VBASE+LPC313X_USBHOST_BURSTSIZE_OFFSET) -#define LPC313X_USBHOST_TXFILLTUNING (LPC313X_USBOTG_VBASE+LPC313X_USBHOST_TXFILLTUNING_OFFSET) -#define LPC313X_USBHOST_BINTERVAL (LPC313X_USBOTG_VBASE+LPC313X_USBHOST_BINTERVAL_OFFSET) -#define LPC313X_USBHOST_PORTSC1 (LPC313X_USBOTG_VBASE+LPC313X_USBHOST_PORTSC1_OFFSET) -#define LPC313X_USBHOST_USBMODE (LPC313X_USBOTG_VBASE+LPC313X_USBHOST_USBMODE_OFFSET) - -/* Device endpoint registers */ - -#define LPC313X_USBDEV_ENDPTSETUPSTAT (LPC313X_USBOTG_VBASE+LPC313X_USBDEV_ENDPTSETUPSTAT_OFFSET) -#define LPC313X_USBDEV_ENDPTPRIME (LPC313X_USBOTG_VBASE+LPC313X_USBDEV_ENDPTPRIME_OFFSET) -#define LPC313X_USBDEV_ENDPTFLUSH (LPC313X_USBOTG_VBASE+LPC313X_USBDEV_ENDPTFLUSH_OFFSET) -#define LPC313X_USBDEV_ENDPTSTATUS (LPC313X_USBOTG_VBASE+LPC313X_USBDEV_ENDPTSTATUS_OFFSET) -#define LPC313X_USBDEV_ENDPTCOMPLETE (LPC313X_USBOTG_VBASE+LPC313X_USBDEV_ENDPTCOMPLETE_OFFSET) -#define LPC313X_USBDEV_ENDPTCTRL0 (LPC313X_USBOTG_VBASE+LPC313X_USBDEV_ENDPTCTRL0_OFFSET) -#define LPC313X_USBDEV_ENDPTCTRL1 (LPC313X_USBOTG_VBASE+LPC313X_USBDEV_ENDPTCTRL1_OFFSET) -#define LPC313X_USBDEV_ENDPTCTRL2 (LPC313X_USBOTG_VBASE+LPC313X_USBDEV_ENDPTCTRL2_OFFSET) -#define LPC313X_USBDEV_ENDPTCTRL3 (LPC313X_USBOTG_VBASE+LPC313X_USBDEV_ENDPTCTRL3_OFFSET) - -/* USBOTG register bit definitions **************************************************************/ - -/* Device/host capability registers */ -/* CAPLENGTH (address 0x19000100) */ - -#define USBOTG_CAPLENGTH_SHIFT (0) /* Bits 0-7: Offset from register base to operational regs */ -#define USBOTG_CAPLENGTH_MASK (0xff << USBOTG_CAPLENGTH_SHIFT) - -/* HCIVERSION (address 0x19000102) */ - -#define USBHOST_HCIVERSION_SHIFT (0) /* Bits 0-15: BCD encoding of the EHCI revision number */ -#define USBHOST_HCIVERSION_MASK (0xffff << USBHOST_HCIVERSION_SHIFT) - -/* HCSPARAMS (address 0x19000104) */ - -#define USBHOST_HCSPARAMS_NTT_SHIFT (24) /* Bits 24-27: Number of Transaction Translators */ -#define USBHOST_HCSPARAMS_NTT_MASK (15 << USBHOST_HCSPARAMS_NTT_SHIFT) -#define USBHOST_HCSPARAMS_NPTT_SHIFT (20) /* Bits 20-23: Number of Ports per Transaction Translator */ -#define USBHOST_HCSPARAMS_NPTT_MASK (15 << USBHOST_HCSPARAMS_NPTT_SHIFT) -#define USBHOST_HCSPARAMS_PI (1 >> 16) /* Bit 16: Port indicators */ -#define USBHOST_HCSPARAMS_NCC_SHIFT (15) /* Bits 12-15: Number of Companion Controller */ -#define USBHOST_HCSPARAMS_NCC_MASK (15 << USBHOST_HCSPARAMS_NCC_SHIFT) -#define USBHOST_HCSPARAMS_NPCC_SHIFT (8) /* Bits 8-11: Number of Ports per Companion Controller */ -#define USBHOST_HCSPARAMS_NPCC_MASK (15 << USBHOST_HCSPARAMS_NPCC_SHIFT) -#define USBHOST_HCSPARAMS_PPC (1 >> 4) /* Bit 4: Port Power Control */ -#define USBHOST_HCSPARAMS_NPORTS_SHIF (0) /* Bits 0-3: Number of downstream ports */ -#define USBHOST_HCSPARAMS_NPORTS_MASK (15 << USBHOST_HCSPARAMS_NPORTS_SHIFT) - -/* HCCPARAMS (address 0x19000108) */ - -#define USBHOST_HCCPARAMS_EECP_SHIFT (8) /* Bits 8-15: EHCI Extended Capabilities Pointer */ -#define USBHOST_HCCPARAMS_EECP_MASK (255 << USBHOST_HCCPARAMS_EECP_SHIFT) -#define USBHOST_HCCPARAMS_IST_SHIFT (4) /* Bits 4-7: Isochronous Scheduling Threshold */ -#define USBHOST_HCCPARAMS_IST_MASK (15 << USBHOST_HCCPARAMS_IST_SHIFT) -#define USBHOST_HCCPARAMS_ASP (1 >> 2) /* Bit 2: Asynchronous Schedule Park Capability */ -#define USBHOST_HCCPARAMS_PFL (1 >> 1) /* Bit 1: Programmable Frame List Flag */ -#define USBHOST_HCCPARAMS_ADC (1 >> 0) /* Bit 0: 64-bit Addressing Capability */ - -/* DCIVERSION (address 0x19000120) */ - -#define USBDEV_DCIVERSION_SHIFT (0) /* Bits 0-15: BCD encoding of the device interface */ -#define USBDEV_DCIVERSION_MASK (0xffff << USBDEV_DCIVERSION_SHIFT) - -/* DCCPARAMS (address 0x19000124) */ - -#define USBDEV_DCCPARAMS_HC (1 >> 8) /* Bit 8: Host Capable */ -#define USBDEV_DCCPARAMS_DC (1 >> 7) /* Bit 7: Device Capable */ -#define USBDEV_DCCPARAMS_DEN_SHIFT (0) /* Bits 0-4: DEN Device Endpoint Number */ -#define USBDEV_DCCPARAMS_DEN_MASK (31 << USBDEV_DCCPARAMS_DEN_SHIFT) - -/* Device/host operational registers */ -/* USB Command register USBCMD (address 0x19000140) -- Device Mode */ - -#define USBDEV_USBCMD_ITC_SHIFT (16) /* Bits 16-23: Interrupt threshold control */ -#define USBDEV_USBCMD_ITC_MASK (255 << USBDEV_USBCMD_ITC_SHIFT) -# define USBDEV_USBCMD_ITCIMME (0 << USBDEV_USBCMD_ITC_SHIFT) /* Immediate (no threshold) */ -# define USBDEV_USBCMD_ITC1UF (1 << USBDEV_USBCMD_ITC_SHIFT) /* 1 micro frame */ -# define USBDEV_USBCMD_ITC2UF (2 << USBDEV_USBCMD_ITC_SHIFT) /* 2 micro frames */ -# define USBDEV_USBCMD_ITC4UF (4 << USBDEV_USBCMD_ITC_SHIFT) /* 4 micro frames */ -# define USBDEV_USBCMD_ITC8UF (8 << USBDEV_USBCMD_ITC_SHIFT) /* 8 micro frames */ -# define USBDEV_USBCMD_ITC16UF (16 << USBDEV_USBCMD_ITC_SHIFT) /* 16 micro frames */ -# define USBDEV_USBCMD_ITC32UF (32 << USBDEV_USBCMD_ITC_SHIFT) /* 32 micro frames */ -# define USBDEV_USBCMD_ITC64UF (64 << USBDEV_USBCMD_ITC_SHIFT) /* 64 micro frames */ -#define USBDEV_USBCMD_SUTW (1 << 13) /* Bit 13: Setup trip wire */ -#define USBDEV_USBCMD_ATDTW (1 << 12) /* Bit 12: Add dTD trip wire */ -#define USBDEV_USBCMD_RST (1 << 1) /* Bit 1: 1 Controller reset */ -#define USBDEV_USBCMD_RS (1 << 0) /* Bit 0: 0 Run/Stop */ - -/* USB Command register USBCMD (address 0x19000140) -- Host Mode */ - -#define USBHOST_USBCMD_ITC_SHIFT (16) /* Bits 16-13: Interrupt threshold control */ -#define USBHOST_USBCMD_ITC_MASK (255 << USBHOST_USBCMD_ITC_SHIFT) -# define USBHOST_USBCMD_ITCIMMED (0 << USBHOST_USBCMD_ITC_SHIFT) /* Immediate (no threshold) */ -# define USBHOST_USBCMD_ITC1UF (1 << USBHOST_USBCMD_ITC_SHIFT) /* 1 micro frame */ -# define USBHOST_USBCMD_ITC2UF (2 << USBHOST_USBCMD_ITC_SHIFT) /* 2 micro frames */ -# define USBHOST_USBCMD_ITC4UF (4 << USBHOST_USBCMD_ITC_SHIFT) /* 4 micro frames */ -# define USBHOST_USBCMD_ITC8UF (8 << USBHOST_USBCMD_ITC_SHIFT) /* 8 micro frames */ -# define USBHOST_USBCMD_ITC16UF (16 << USBHOST_USBCMD_ITC_SHIFT) /* 16 micro frames */ -# define USBHOST_USBCMD_ITC32UF (32 << USBHOST_USBCMD_ITC_SHIFT) /* 32 micro frames */ -# define USBHOST_USBCMD_ITC64UF (64 << USBHOST_USBCMD_ITC_SHIFT) /* 64 micro frames */ -#define USBHOST_USBCMD_FS2 (1 << 15) /* Bit 15: Bit 2 of the Frame List Size bits */ -#define USBHOST_USBCMD_ASPE (1 << 11) /* Bit 11: Asynchronous Schedule Park Mode Enable */ -#define USBHOST_USBCMD_ASP_SHIFT (8) /* Bits 8-9: Asynchronous schedule park mode */ -#define USBHOST_USBCMD_ASP_MASK (3 << USBHOST_USBCMD_ASP_SHIFT) -#define USBHOST_USBCMD_IAA (1 << 6) /* Bit 6: Interrupt next asynchronous schedule */ -#define USBHOST_USBCMD_ASE (1 << 5) /* Bit 5: Skips processing asynchronous schedule */ -#define USBHOST_USBCMD_PSE (1 << 4) /* Bit 4: Skips processing periodic schedule */ -#define USBHOST_USBCMD_FS1 (1 << 3) /* Bit 3: Bit 1 of the Frame List Size bits */ -#define USBHOST_USBCMD_FS0 (1 << 2) /* Bit 2: Bit 0 of the Frame List Size bits */ -#define USBHOST_USBCMD_RST (1 << 1) /* Bit 1: Controller reset */ -#define USBHOST_USBCMD_RS (1 << 0) /* Bit 0: Run/Stop */ - -/* USB Status register USBSTS (address 0x19000144) -- Device Mode */ - -#define USBDEV_USBSTS_NAKI (1 << 16) /* Bit 16: NAK interrupt bit */ -#define USBDEV_USBSTS_SLI (1 << 8) /* Bit 8: DCSuspend */ -#define USBDEV_USBSTS_SRI (1 << 7) /* Bit 7: SOF received */ -#define USBDEV_USBSTS_URI (1 << 6) /* Bit 6: USB reset received */ -#define USBDEV_USBSTS_PCI (1 << 2) /* Bit 2: Port change detect */ -#define USBDEV_USBSTS_UEI (1 << 1) /* Bit 1: USB error interrupt */ -#define USBDEV_USBSTS_UI (1 << 0) /* Bit 0: USB interrupt */ - -/* USB Status register USBSTS (address 0x19000144) -- Host Mode */ - -#define USBHOST_USBSTS_UPI (1 << 19) /* Bit 19: USB host periodic interrupt */ -#define USBHOST_USBSTS_UAI (1 << 18) /* Bit 18: USB host asynchronous interrupt */ -#define USBHOST_USBSTS_AS (1 << 15) /* Bit 15: Asynchronous schedule status */ -#define USBHOST_USBSTS_PS (1 << 14) /* Bit 14: Periodic schedule status */ -#define USBHOST_USBSTS_RCL (1 << 13) /* Bit 13: Reclamation */ -#define USBHOST_USBSTS_HCH (1 << 12) /* Bit 12: HCHalted */ -#define USBHOST_USBSTS_SRI (1 << 7) /* Bit 7: SOF received */ -#define USBHOST_USBSTS_AAI (1 << 5) /* Bit 5: Interrupt on async advance */ -#define USBHOST_USBSTS_FRI (1 << 3) /* Bit 3: Frame list roll-over */ -#define USBHOST_USBSTS_PCI (1 << 2) /* Bit 2: Port change detect */ -#define USBHOST_USBSTS_UEI (1 << 1) /* Bit 1: USB error interrupt */ -#define USBHOST_USBSTS_UI (1 << 0) /* Bit 0: USB interrupt */ - -/* USB interrupt register USBINTR (address 0x19000148) -- Device Mode */ - -#define USBDEV_USBINTR_NAKE (1 << 16) /* Bit 16: NAK interrupt enable */ -#define USBDEV_USBINTR_SLE (1 << 8) /* Bit 8: Sleep enable */ -#define USBDEV_USBINTR_SRE (1 << 7) /* Bit 7: SOF received enable */ -#define USBDEV_USBINTR_URE (1 << 6) /* Bit 6: USB reset enable */ -#define USBDEV_USBINTR_PCE (1 << 2) /* Bit 2: Port change detect enable */ -#define USBDEV_USBINTR_UEE (1 << 1) /* Bit 1: USB error interrupt enable */ -#define USBDEV_USBINTR_UE (1 << 0) /* Bit 0: USB interrupt enable */ - -/* USB interrupt register USBINTR (address 0x19000148) -- Host Mode */ - -#define USBHOST_USBINTR_UPIA (1 << 19) /* Bit 19: USB host periodic interrupt enable */ -#define USBHOST_USBINTR_UAIE (1 << 18) /* Bit 18: USB host asynchronous interrupt enable */ -#define USBHOST_USBINTR_SRE (1 << 7) /* Bit 7: SOF timer interrupt enable */ -#define USBHOST_USBINTR_AAE (1 << 5) /* Bit 5: Interrupt on asynchronous advance enable */ -#define USBHOST_USBINTR_FRE (1 << 3) /* Bit 3: Frame list rollover enable */ -#define USBHOST_USBINTR_PCE (1 << 2) /* Bit 2: Port change detect enable */ -#define USBHOST_USBINTR_UEE (1 << 1) /* Bit 1: USB error interrupt enable */ -#define USBHOST_USBINTR_UE (1 << 0) /* Bit 0: USB interrupt enable */ - -/* Frame index register FRINDEX (address 0x1900014c) -- Device Mode */ - -#define USBDEV_FRINDEX_LFN_SHIFT (3) /* Bits 3-13: Frame number of last frame transmitted */ -#define USBDEV_FRINDEX_LFN_MASK (0x7ff << USBDEV_FRINDEX_LFN_SHIFT) -#define USBDEV_FRINDEX_CUFN_SHIFT (0) /* Bits 0-2: Current micro frame number */ -#define USBDEV_FRINDEX_CUFN_MASK (7 << USBDEV_FRINDEX_CUFN_SHIFT) - -/* Frame index register FRINDEX (address 0x1900014c) -- Host Mode */ - -#define USBHOST_FRINDEX_FLI_SHIFT (3) /* Bits 3-(n+2): Frame list current index */ -#define USBHOST_FRINDEX_FLI_MASK(n) (0x7ff << ((n)+USBHOST_FRINDEX_FLI_SHIFT-1) -#define USBHOST_FRINDEX_CUFN_SHIFT (0) /* Bits 0-2: Current micro frame number */ -#define USBHOST_FRINDEX_CUFN_MASK (7 << USBHOST_FRINDEX_CUFN_SHIFT) - -/* USB Device Address register DEVICEADDR (address 0x19000154) -- Device Mode */ - -#define USBDEV_DEVICEADDR_SHIFT (25) /* Bits 25-31: USBADR USB device address */ -#define USBDEV_DEVICEADDR_MASK (0x3c << USBDEV_DEVICEADDR_SHIFT) -#define USBDEV_DEVICEADDR_USBADRA (1 << 24) /* Bit 24: Device address advance */ - -/* USB Periodic List Base register PERIODICLIST (address 0x19000154) -- Host Mode */ - -#define USBHOST_PERIODICLIST_PERBASE_SHIFT (12) /* Bits 12-31: Base Address (Low) */ -#define USBHOST_PERIODICLIST_PERBASE_MASK (0x000fffff << USBHOST_PERIODICLIST_PERBASE_SHIFT) - -/* USB Endpoint List Address register ENDPOINTLISTADDR (address 0x19000158) -- Device Mode */ - -#define USBDEV_ENDPOINTLIST_EPBASE_SHIFT (11) /* Bits 11-31: Endpoint list pointer (low) */ -#define USBDEV_ENDPOINTLIST_EPBASE_MASK (0x001fffff << USBDEV_ENDPOINTLIST_EPBASE_SHIFT) - -/* USB Asynchronous List Address register ASYNCLISTADDR- (address 0x19000158) -- Host Mode */ - -#define USBHOST_ASYNCLISTADDR_ASYBASE_SHIFT (5) /* Bits 5-31: Link pointer (Low) LPL */ -#define USBHOST_ASYNCLISTADDR_ASYBASE_MASK (0x07ffffff << USBHOST_ASYNCLISTADDR_ASYBASE_SHIFT) - -/* USB TT Control register TTCTRL (address 0x1900015c) -- Host Mode */ - -#define USBHOST_TTCTRL_TTHA_SHIFT (24) /* Bits 24-30: Hub address */ -#define USBHOST_TTCTRL_TTHA_MASK (0x7f << USBHOST_TTCTRL_TTHA_SHIFT) - -/* USB burst size register BURSTSIZE (address 0x19000160) -- Device/Host Mode */ - -#define USBDEV_BURSTSIZE_TXPBURST_SHIFT (8) /* Bits 8-15: Programmable TX burst length */ -#define USBDEV_BURSTSIZE_TXPBURST_MASK (255 << USBDEV_BURSTSIZE_TXPBURST_SHIFT) -#define USBDEV_BURSTSIZE_RXPBURST_SHIFT (0) /* Bits 0-7: RXPBURST Programmable RX burst length */ -#define USBDEV_BURSTSIZE_RXPBURST_MASK (255 << USBDEV_BURSTSIZE_RXPBURST_SHIFT) - -#define USBHOST_BURSTSIZE_TXPBURST_SHIFT (8) /* Bits 8-15: Programmable TX burst length */ -#define USBHOST_BURSTSIZE_TXPBURST_MASK (255 << USBHOST_BURSTSIZE_TXPBURST_SHIFT) -#define USBHOST_BURSTSIZE_RXPBURST_SHIFT (0) /* Bits 0-7: RXPBURST Programmable RX burst length */ -#define USBHOST_BURSTSIZE_RXPBURST_MASK (255 << USBHOST_BURSTSIZE_RXPBURST_SHIFT) - -/* USB Transfer buffer Fill Tuning register TXFIFOFILLTUNING (address 0x19000164) -- Host Mode */ - -#define USBHOST_TXFILLTUNING_FIFOTHRES_SHIFT (16) /* Bits 16-21: Scheduler overhead */ -#define USBHOST_TXFILLTUNING_FIFOTHRES_MASK (0x3c << USBHOST_TXFILLTUNING_FIFOTHRES_SHIFT) -#define USBHOST_TXFILLTUNING_SCHEATLTH_SHIFT (8) /* Bits 8-12: Scheduler health counter */ -#define USBHOST_TXFILLTUNING_SCHEATLTH_MASK (0x1f << USBHOST_TXFILLTUNING_SCHEATLTH_SHIFT) -#define USBHOST_TXFILLTUNING_SCHOH_SHIFT (0) /* Bits 0-7: FIFO burst threshold */ -#define USBHOST_TXFILLTUNING_SCHOH_MASK (0xff << USBHOST_TXFILLTUNING_SCHOH_SHIFT) - -/* USB BINTERVAL register BINTERVAL (address 0x19000174) -- Device/Host Mode */ - -#define USBDEV_BINTERVAL_SHIFT (0) /* Bits 0-3: bInterval value */ -#define USBDEV_BINTERVAL_MASK (15 << USBDEV_BINTERVAL_SHIFT) - -#define USBHOST_BINTERVAL_SHIFT (0) /* Bits 0-3: bInterval value */ -#define USBHOST_BINTERVAL_MASK (15 << USBHOST_BINTERVAL_SHIFT) - -/* USB endpoint NAK register ENDPTNAK (address 0x19000178) -- Device Mode */ - -#define USBDEV_ENDPTNAK_EPTN_SHIFT (16) /* Bits 16-19: Tx endpoint NAK */ -#define USBDEV_ENDPTNAK_EPTN_MASK (15 << USBDEV_ENDPTNAK_EPTN_SHIFT) -#define USBDEV_ENDPTNAK_EPRN_SHIFT (0) /* Bits 0-3: Rx endpoint NAK */ -#define USBDEV_ENDPTNAK_EPRN_MASK (15 << USBDEV_ENDPTNAK_EPRN_SHIFT) - -/* USB Endpoint NAK Enable register ENDPTNAKEN (address 0x1900017c) -- Device Mode */ - -#define USBDEV_ENDPTNAK_EPTNE_SHIFT (16) /* Bits 16-19: Tx endpoint NAK enable */ -#define USBDEV_ENDPTNAK_EPTNE_MASK (15 << USBDEV_ENDPTNAK_EPTNE_SHIFT) -#define USBDEV_ENDPTNAK_EPRNE_SHIFT (0) /* Bits 0-3: Rx endpoint NAK enable */ -#define USBDEV_ENDPTNAK_EPRNE_MASK (15 << USBDEV_ENDPTNAK_EPRNE_SHIFT) - -/* Port Status and Control register PRTSC1 (address 0x19000184) -- Device Mode */ - -#define USBDEV_PRTSC1_PSPD_SHIFT (26) /* Bits 26-27: Port speed */ -# define USBDEV_PRTSC1_PSPD_MASK (3 << USBDEV_PRTSC1_PSPD_SHIFT) -# define USBDEV_PRTSC1_PSPD_FS (0 << USBDEV_PRTSC1_PSPD_SHIFT) /* Full-speed */ -# define USBDEV_PRTSC1_PSPD_HS (2 << USBDEV_PRTSC1_PSPD_SHIFT) /* High-speed */ -# define USBDEV_PRTSC1_PFSC (1 << 24) /* Bit 24: Port force full speed connect */ -#define USBDEV_PRTSC1_PHCD (1 << 23) /* Bit 23: PHY low power suspend - clock disable (PLPSCD) */ -#define USBDEV_PRTSC1_PTC_SHIFT (16) /* Bits 16-19: 19: Port test control */ -#define USBDEV_PRTSC1_PTC_MASK (15 << USBDEV_PRTSC1_PTC_SHIFT) -# define USBDEV_PRTSC1_PTC_DISABLE (0 << USBDEV_PRTSC1_PTC_SHIFT) /* TEST_MODE_DISABLE */ -# define USBDEV_PRTSC1_PTC_JSTATE (1 << USBDEV_PRTSC1_PTC_SHIFT) /* J_STATE */ -# define USBDEV_PRTSC1_PTC_KSTATE (2 << USBDEV_PRTSC1_PTC_SHIFT) /* K_STATE */ -# define USBDEV_PRTSC1_PTC_SE0 (3 << USBDEV_PRTSC1_PTC_SHIFT) /* SE0 (host)/NAK (device) */ -# define USBDEV_PRTSC1_PTC_PACKET (4 << USBDEV_PRTSC1_PTC_SHIFT) /* Packet */ -# define USBDEV_PRTSC1_PTC_HS (5 << USBDEV_PRTSC1_PTC_SHIFT) /* FORCE_ENABLE_HS */ -# define USBDEV_PRTSC1_PTC_FS (6 << USBDEV_PRTSC1_PTC_SHIFT) /* FORCE_ENABLE_FS */ -#define USBDEV_PRTSC1_PIC_SHIFT (14) /* Bits 14-15: Port indicator control */ -#define USBDEV_PRTSC1_PIC_MASK (3 << USBDEV_PRTSC1_PIC_SHIFT) -# define USBDEV_PRTSC1_PIC_OFF (0 << USBDEV_PRTSC1_PIC_SHIFT) /* 00 Port indicators are off */ -# define USBDEV_PRTSC1_PIC_AMBER (1 << USBDEV_PRTSC1_PIC_SHIFT) /* 01 amber */ -# define USBDEV_PRTSC1_PIC_GREEN (2 << USBDEV_PRTSC1_PIC_SHIFT) /* 10 green */ -#define USBDEV_PRTSC1_HSP (1 << 9) /* Bit 9: High-speed status */ -#define USBDEV_PRTSC1_PR (1 << 8) /* Bit 8: Port reset */ -#define USBDEV_PRTSC1_SUSP (1 << 7) /* Bit 7: Suspend */ -#define USBDEV_PRTSC1_FPR (1 << 6) /* Bit 6: Force port resume */ -#define USBDEV_PRTSC1_PEC (1 << 3) /* Bit 3: Port enable/disable change */ -#define USBDEV_PRTSC1_PE (1 << 2) /* Bit 2: Port enable */ -#define USBDEV_PRTSC1_CCS (1 << 0) /* Bit 0: Current connect status */ - -/* Port Status and Control register PRTSC1 (address 0x19000184) -- Host Mode */ - -#define USBHOST_PRTSC1_PSPD_SHIFT (26) /* Bits 26-27: Port speed */ -#define USBHOST_PRTSC1_PSPD_MASK (3 << USBHOST_PRTSC1_PSPD_SHIFT) -# define USBHOST_PRTSC1_PSPD_FS (0 << USBHOST_PRTSC1_PSPD_SHIFT) /* Full-speed */ -# define USBHOST_PRTSC1_PSPD_LS (1 << USBHOST_PRTSC1_PSPD_SHIFT) /* Low-speed */ -# define USBHOST_PRTSC1_PSPD_HS (2 << USBHOST_PRTSC1_PSPD_SHIFT) /* High-speed */ -#define USBHOST_PRTSC1_PFSC (1 << 24) /* Bit 24: Port force full speed connect */ -#define USBHOST_PRTSC1_PHCD (1 << 23) /* Bit 23: PHY low power suspend - clock disable (PLPSCD) */ -#define USBHOST_PRTSC1_WKOC (1 << 22) /* Bit 22: Wake on over-current enable (WKOC_E) */ -#define USBHOST_PRTSC1_WKDC (1 << 21) /* Bit 21: Wake on disconnect enable (WKDSCNNT_E) */ -#define USBHOST_PRTSC1_WKCN (1 << 20) /* Bit 20: Wake on connect enable (WKCNNT_E) */ -#define USBHOST_PRTSC1_PTC_SHIFT (16) /* Bits 16-19: Port test control */ -#define USBHOST_PRTSC1_PTC_MASK (15 << USBHOST_PRTSC1_PTC_SHIFT) -# define USBHOST_PRTSC1_PTC_DISABLE (0 << USBHOST_PRTSC1_PTC_SHIFT) /* 0000 TEST_MODE_DISABLE */ -# define USBHOST_PRTSC1_PTC_JSTATE (1 << USBHOST_PRTSC1_PTC_SHIFT) /* 0001 J_STATE */ -# define USBHOST_PRTSC1_PTC_KSTATE (2 << USBHOST_PRTSC1_PTC_SHIFT) /* 0010 K_STATE */ -# define USBHOST_PRTSC1_PTC_SE0 (3 << USBHOST_PRTSC1_PTC_SHIFT) /* 0011 SE0 (host)/NAK (device) */ -# define USBHOST_PRTSC1_PTC_PACKET (4 << USBHOST_PRTSC1_PTC_SHIFT) /* 0100 Packet */ -# define USBHOST_PRTSC1_PTC_HS (5 << USBHOST_PRTSC1_PTC_SHIFT) /* 0101 FORCE_ENABLE_HS */ -# define USBHOST_PRTSC1_PTC_FS (6 << USBHOST_PRTSC1_PTC_SHIFT) /* 0110 FORCE_ENABLE_FS */ -# define USBHOST_PRTSC1_PTC_LS (7 << USBHOST_PRTSC1_PTC_SHIFT) /* 0111 FORCE_ENABLE_LS */ -#define USBHOST_PRTSC1_PIC_SHIFT (14) /* Bits 14-15: Port indicator control */ -#define USBHOST_PRTSC1_PIC_MASK (3 << USBHOST_PRTSC1_PIC_SHIFT) -# define USBHOST_PRTSC1_PIC_OFF (0 << USBHOST_PRTSC1_PIC_SHIFT) /* 00 Port indicators are off */ -# define USBHOST_PRTSC1_PIC_AMBER (1 << USBHOST_PRTSC1_PIC_SHIFT) /* 01 Amber */ -# define USBHOST_PRTSC1_PIC_GREEN (2 << USBHOST_PRTSC1_PIC_SHIFT) /* 10 Green */ -#define USBHOST_PRTSC1_PP (1 << 12) /* Bit 12: Port power control */ -#define USBHOST_PRTSC1_LS_SHIFT (10) /* Bits 10-11: Line status */ -#define USBHOST_PRTSC1_LS_MASK (3 << USBHOST_PRTSC1_LS_SHIFT) -# define USBHOST_PRTSC1_LS_SE0 (0 << USBHOST_PRTSC1_LS_SHIFT) /* SE0 (USB_DP and USB_DM LOW) */ -# define USBHOST_PRTSC1_LS_JSTATE (2 << USBHOST_PRTSC1_LS_SHIFT) /* J-state (USB_DP HIGH and USB_DM LOW) */ -# define USBHOST_PRTSC1_LS_KSTATE (1 << USBHOST_PRTSC1_LS_SHIFT) /* K-state (USB_DP LOW and USB_DM HIGH) */ -#define USBHOST_PRTSC1_HSP (1 << 9) /* Bit 9: High-speed status */ -#define USBHOST_PRTSC1_PR (1 << 8) /* Bit 8: Port reset */ -#define USBHOST_PRTSC1_SUSP (1 << 7) /* Bit 7: Suspend */ -#define USBHOST_PRTSC1_FPR (1 << 6) /* Bit 6: Force port resume */ -#define USBHOST_PRTSC1_OCC (1 << 5) /* Bit 5: Over-current change */ -#define USBHOST_PRTSC1_OCA (1 << 4) /* Bit 4: Over-current active */ -#define USBHOST_PRTSC1_PEC (1 << 3) /* Bit 3: Port disable/enable change */ -#define USBHOST_PRTSC1_PE (1 << 2) /* Bit 2: Port enable */ -#define USBHOST_PRTSC1_CSC (1 << 1) /* Bit 1: Connect status change */ -#define USBHOST_PRTSC1_CCS (1 << 0) /* Bit 0: Current connect status */ - -/* OTG Status and Control register (OTGSC - address 0x190001a4) */ - -/* OTG interrupt enable */ - -#define USBOTG_OTGSC_DPIE (1 << 30) /* Bit 30: Data pulse interrupt enable */ -#define USBOTG_OTGSC_1MSE (1 << 29) /* Bit 29: 1 millisecond timer interrupt enable */ -#define USBOTG_OTGSC_BSEIE (1 << 28) /* Bit 28: B-session end interrupt enable */ -#define USBOTG_OTGSC_BSVIE (1 << 27) /* Bit 27: B-session valid interrupt enable */ -#define USBOTG_OTGSC_ASVIE (1 << 26) /* Bit 26: A-session valid interrupt enable */ -#define USBOTG_OTGSC_AVVIE (1 << 25) /* Bit 25: A-VBUS valid interrupt enable */ -#define USBOTG_OTGSC_IDIE (1 << 24) /* Bit 24: USB ID interrupt enable */ - -/* OTG interrupt status */ - -#define USBOTG_OTGSC_DPIS (1 << 22) /* Bit 22: Data pulse interrupt status */ -#define USBOTG_OTGSC_1MSS (1 << 21) /* Bit 21: 1 millisecond timer interrupt status */ -#define USBOTG_OTGSC_BSEIS (1 << 20) /* Bit 20: B-Session end interrupt status */ -#define USBOTG_OTGSC_BSVIS (1 << 19) /* Bit 19: B-Session valid interrupt status */ -#define USBOTG_OTGSC_ASVIS (1 << 18) /* Bit 18: A-Session valid interrupt status */ -#define USBOTG_OTGSC_AVVIS (1 << 17) /* Bit 17: A-VBUS valid interrupt status */ -#define USBOTG_OTGSC_IDIS (1 << 16) /* Bit 16: USB ID interrupt status */ - -/* OTG status inputs */ - -#define USBOTG_OTGSC_DPS (1 << 14) /* Bit 14: Data bus pulsing status */ -#define USBOTG_OTGSC_1MST (1 << 13) /* Bit 13: 1 millisecond timer toggle */ -#define USBOTG_OTGSC_BSE (1 << 12) /* Bit 12: B-session end */ -#define USBOTG_OTGSC_BSV (1 << 11) /* Bit 11: B-session valid */ -#define USBOTG_OTGSC_ASV (1 << 10) /* Bit 10: A-session valid */ -#define USBOTG_OTGSC_AVV (1 << 9) /* Bit 9: A-VBUS valid */ -#define USBOTG_OTGSC_ID (1 << 8) /* Bit 8: USB ID */ - -/* OTG controls */ - -#define USBOTG_OTGSC_HABA (1 << 7) /* Bit 7: Hardware assist B-disconnect to A-connect */ -#define USBOTG_OTGSC_HADP (1 << 6) /* Bit 6: Hardware assist data pulse */ -#define USBOTG_OTGSC_IDPU (1 << 5) /* Bit 5: ID pull-up */ -#define USBOTG_OTGSC_DP (1 << 4) /* Bit 4: Data pulsing */ -#define USBOTG_OTGSC_OT (1 << 3) /* Bit 3: OTG termination */ -#define USBOTG_OTGSC_HAAR (1 << 2) /* Bit 2: Hardware assist auto_reset */ -#define USBOTG_OTGSC_VC (1 << 1) /* Bit 1: VBUS_Charge */ -#define USBOTG_OTGSC_VD (1 << 0) /* Bit 0: VBUS_Discharge */ - -/* USB Mode register USBMODE (address 0x190001a8) -- Device Mode */ - -#define USBDEV_USBMODE_SDIS (1 << 4) /* Bit 4: Stream disable mode */ -#define USBDEV_USBMODE_SLOM (1 << 3) /* Bit 3: Setup Lockout mode */ -#define USBDEV_USBMODE_ES (1 << 2) /* Bit 2: Endian select */ -#define USBDEV_USBMODE_CM_SHIFT (0) /* Bits 0-1: Controller mode */ -#define USBDEV_USBMODE_CM_MASK (3 << USBDEV_USBMODE_CM_SHIFT) -# define USBDEV_USBMODE_CMIDLE (0 << USBDEV_USBMODE_CM_SHIFT) /* Idle */ -# define USBDEV_USBMODE_CMDEVICE (2 << USBDEV_USBMODE_CM_SHIFT) /* Device controller */ -# define USBDEV_USBMODE_CMHOST (3 << USBDEV_USBMODE_CM_SHIFT) /* Host controller */ - -/* USB Mode register USBMODE (address 0x190001a8) -- Device Mode */ - -#define USBHOST_USBMODE_VBPS (1 << 5) /* Bit 5: VBUS power select */ -#define USBHOST_USBMODE_SDIS (1 << 4) /* Bit 4: Stream disable mode */ -#define USBHOST_USBMODE_ES (1 << 2) /* Bit 2: Endian select */ -#define USBHOST_USBMODE_CM_SHIFT (0) /* Bits 0-1: Controller mode */ -#define USBHOST_USBMODE_CM_MASK (3 << USBHOST_USBMODE_CM_SHIFT) -# define USBHOST_USBMODE_CMIDLE (0 << USBHOST_USBMODE_CM_SHIFT) /* Idle */ -# define USBHOST_USBMODE_CMDEVICE (2 << USBHOST_USBMODE_CM_SHIFT) /* Device controller */ -# define USBHOST_USBMODE_CMHOST (3 << USBHOST_USBMODE_CM_SHIFT) /* Host controller */ - -/* Device endpoint registers */ - -/* USB Endpoint Setup Status register ENDPTSETUPSTAT (address 0x190001ac) */ - -#define USBDEV_ENDPTSETSTAT_STAT3 (1 << 3) /* Bit 3: Setup EP status for logical EP 3 */ -#define USBDEV_ENDPTSETSTAT_STAT2 (1 << 2) /* Bit 2: Setup EP status for logical EP 2 */ -#define USBDEV_ENDPTSETSTAT_STAT1 (1 << 1) /* Bit 1: Setup EP status for logical EP 1 */ -#define USBDEV_ENDPTSETSTAT_STAT0 (1 << 0) /* Bit 0: Setup EP status for logical EP 0 */ - -/* USB Endpoint Prime register ENDPTPRIME (address 0x190001b0) */ - -#define USBDEV_ENDPTPRIM_PETB3 (1 << 19) /* Bit 19: Prime EP xmt buffer for physical IN EP 3 */ -#define USBDEV_ENDPTPRIM_PETB2 (1 << 18) /* Bit 18: Prime EP xmt buffer for physical IN EP 2 */ -#define USBDEV_ENDPTPRIM_PETB1 (1 << 17) /* Bit 17: Prime EP xmt buffer for physical IN EP 1 */ -#define USBDEV_ENDPTPRIM_PETB0 (1 << 16) /* Bit 16: Prime EP xmt buffer for physical IN EP 0 */ -#define USBDEV_ENDPTPRIM_PERB3 (1 << 3) /* Bit 3: Prime EP recv buffer for physical OUT EP 3 */ -#define USBDEV_ENDPTPRIM_PERB2 (1 << 2) /* Bit 2: Prime EP recv buffer for physical OUT EP 2 */ -#define USBDEV_ENDPTPRIM_PERB1 (1 << 1) /* Bit 1: Prime EP recv buffer for physical OUT EP 1 */ -#define USBDEV_ENDPTPRIM_PERB0 (1 << 0) /* Bit 0: Prime EP recv buffer for physical OUT EP 0 */ - -/* USB Endpoint Flush register ENDPTFLUSH(address 0x190001b4) */ - -#define USBDEV_ENDPTFLUSH_FETB3 (1 << 19) /* Bit 19: Flush EP xmt buffer for physical IN EP 3 */ -#define USBDEV_ENDPTFLUSH_FETB2 (1 << 18) /* Bit 18: Flush EP xmt buffer for physical IN EP 2 */ -#define USBDEV_ENDPTFLUSH_FETB1 (1 << 17) /* Bit 17: Flush EP xmt buffer for physical IN EP 1 */ -#define USBDEV_ENDPTFLUSH_FETB0 (1 << 16) /* Bit 16: Flush EP xmt buffer for physical IN EP 0 */ -#define USBDEV_ENDPTFLUSH_FERB3 (1 << 3) /* Bit 3: Flush EP recv buffer for physical OUT EP 3 */ -#define USBDEV_ENDPTFLUSH_FERB2 (1 << 2) /* Bit 2: Flush EP recv buffer for physical OUT EP 2 */ -#define USBDEV_ENDPTFLUSH_FERB1 (1 << 1) /* Bit 1: Flush EP recv buffer for physical OUT EP 1 */ -#define USBDEV_ENDPTFLUSH_FERB0 (1 << 0) /* Bit 0: Flush EP recv buffer for physical OUT EP 0 */ - -/* USB Endpoint Status register ENDPTSTATUS (address 0x190001b8) */ - -#define USBDEV_ENDPTSTATUS_ETBR3 (1 << 19) /* Bit 19: EP xmt buffer ready for physical IN EP 3 */ -#define USBDEV_ENDPTSTATUS_ETBR2 (1 << 18) /* Bit 18: EP xmt buffer ready for physical IN EP 2 */ -#define USBDEV_ENDPTSTATUS_ETBR1 (1 << 17) /* Bit 17: EP xmt buffer ready for physical IN EP 1 */ -#define USBDEV_ENDPTSTATUS_ETBR0 (1 << 16) /* Bit 16: EP xmt buffer ready for physical IN EP 0 */ -#define USBDEV_ENDPTSTATUS_ERBR3 (1 << 3) /* Bit 3: EP recv buffer ready for physical OUT EP 3 */ -#define USBDEV_ENDPTSTATUS_ERBR2 (1 << 2) /* Bit 2: EP recv buffer ready for physical OUT EP 2 */ -#define USBDEV_ENDPTSTATUS_ERBR1 (1 << 1) /* Bit 1: EP recv buffer ready for physical OUT EP 1 */ -#define USBDEV_ENDPTSTATUS_ERBR0 (1 << 0) /* Bit 0: EP recv buffer ready for physical OUT EP 0 */ - -/* USB Endpoint Complete register ENDPTCOMPLETE (address 0x190001bc) */ - -#define USBDEV_ENDPTCOMPLETE_ETCE3 (1 << 19) /* Bit 19: EP xmt complete event for physical IN EP 3 */ -#define USBDEV_ENDPTCOMPLETE_ETCE2 (1 << 18) /* Bit 18: EP xmt complete event for physical IN EP 2 */ -#define USBDEV_ENDPTCOMPLETE_ETCE1 (1 << 17) /* Bit 17: EP xmt complete event for physical IN EP 1 */ -#define USBDEV_ENDPTCOMPLETE_ETCE0 (1 << 16) /* Bit 16: EP xmt complete event for physical IN EP 0 */ -#define USBDEV_ENDPTCOMPLETE_ERCE3 (1 << 3) /* Bit 3: EP recv complete event for physical OUT EP 3 */ -#define USBDEV_ENDPTCOMPLETE_ERCE2 (1 << 2) /* Bit 2: EP recv complete event for physical OUT EP 2 */ -#define USBDEV_ENDPTCOMPLETE_ERCE1 (1 << 1) /* Bit 1: EP recv complete event for physical OUT EP 1 */ -#define USBDEV_ENDPTCOMPLETE_ERCE0 (1 << 0) /* Bit 0: EP recv complete event for physical OUT EP 0 */ - -/* USB Endpoint 0 Control register ENDPTCTRL0 (address 0x190001c0) */ - -#define USBDEV_ENDPTCTRL0_TXE (1 << 23) /* Bit 23: Tx endpoint enable */ -#define USBDEV_ENDPTCTRL0_TXT_SHIFT (18) /* Bits 18-19: Tx endpoint type */ -#define USBDEV_ENDPTCTRL0_TXT_MASK (3 << USBDEV_ENDPTCTRL0_TXT_SHIFT) -# define USBDEV_ENDPTCTRL0_TXT_CTRL (0 << USBDEV_ENDPTCTRL0_TXT_SHIFT) /* Control */ -#define USBDEV_ENDPTCTRL0_TXS (1 << 16) /* Bit 16: Tx endpoint stall */ -#define USBDEV_ENDPTCTRL0_RXE (1 << 7) /* Bit 7: Rx endpoint enable */ -#define USBDEV_ENDPTCTRL0_RXT_SHIFT (2) /* Bits 2-3: Endpoint type */ -#define USBDEV_ENDPTCTR0L_RXT_MASK (3 << USBDEV_ENDPTCTRL0_RXT_SHIFT) -# define USBDEV_ENDPTCTRL0_RXT_CTRL (0 << USBDEV_ENDPTCTRL0_RXT_SHIFT) /* Control */ -#define USBDEV_ENDPTCTRL0_RXS (1 << 0) /* Bit 0: Rx endpoint stall */ - -/* USB Endpoint 1-3 control registers ENDPTCTRL1-ENDPPTCTRL3 (address 0x190001c4-0x190001cc) */ - -#define USBDEV_ENDPTCTRL_TXE (1 << 23) /* Bit 23: Tx endpoint enable */ -#define USBDEV_ENDPTCTRL_TXR (1 << 22) /* Bit 22: Tx data toggle reset */ -#define USBDEV_ENDPTCTRL_TXI (1 << 21) /* Bit 21: Tx data toggle inhibit */ -#define USBDEV_ENDPTCTRL_TXT_SHIFT (18) /* Bits 18-19: Tx endpoint type */ -#define USBDEV_ENDPTCTRL_TXT_MASK (3 << USBDEV_ENDPTCTRL_TXT_SHIFT) -# define USBDEV_ENDPTCTRL_TXT_CTRL (0 << USBDEV_ENDPTCTRL_TXT_SHIFT) /* Control */ -# define USBDEV_ENDPTCTRL_TXT_ISOC (1 << USBDEV_ENDPTCTRL_TXT_SHIFT) /* Isochronous */ -# define USBDEV_ENDPTCTRL_TXT_BULK (2 << USBDEV_ENDPTCTRL_TXT_SHIFT) /* Bulk */ -# define USBDEV_ENDPTCTRL_TXT_INTR (3 << USBDEV_ENDPTCTRL_TXT_SHIFT) /* Interrupt */ -#define USBDEV_ENDPTCTRL_TXS (1 << 16) /* Bit 16: Tx endpoint stall */ -#define USBDEV_ENDPTCTRL_RXE (1 << 7) /* Bit 7: Rx endpoint enable */ -#define USBDEV_ENDPTCTRL_RXR (1 << 6) /* Bit 6: Rx data toggle reset */ -#define USBDEV_ENDPTCTRL_RXI (1 << 5) /* Bit 5: Rx data toggle inhibit */ -#define USBDEV_ENDPTCTRL_RXT_SHIFT (2) /* Bits 2-3: Endpoint type */ -#define USBDEV_ENDPTCTRL_RXT_MASK (3 << USBDEV_ENDPTCTRL_RXT_SHIFT) -# define USBDEV_ENDPTCTRL_RXT_CTRL (0 << USBDEV_ENDPTCTRL_RXT_SHIFT) /* Control */ -# define USBDEV_ENDPTCTRL_RXT_ISOC (1 << USBDEV_ENDPTCTRL_RXT_SHIFT) /* Isochronous */ -# define USBDEV_ENDPTCTRL_RXT_BULK (2 << USBDEV_ENDPTCTRL_RXT_SHIFT) /* Bulk */ -#define USBDEV_ENDPTCTRL_RXS (1 << 0) /* Bit 0: Rx endpoint stall */ - -/************************************************************************************************ - * Public Types - ************************************************************************************************/ - -/************************************************************************************************ - * Public Data - ************************************************************************************************/ - -/************************************************************************************************ - * Public Functions - ************************************************************************************************/ - -#endif /* __ARCH_ARM_SRC_LPC313X_USBOTG_H */ diff --git a/nuttx/arch/arm/src/lpc313x/lpc313x_wdt.h b/nuttx/arch/arm/src/lpc313x/lpc313x_wdt.h deleted file mode 100755 index f3652bd73..000000000 --- a/nuttx/arch/arm/src/lpc313x/lpc313x_wdt.h +++ /dev/null @@ -1,130 +0,0 @@ -/************************************************************************************************ - * arch/arm/src/lpc313x/lpc313x_wdt.h - * - * Copyright (C) 2009-2010 Gregory Nutt. All rights reserved. - * Author: Gregory Nutt - * - * 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_LPC313X_WDT_H -#define __ARCH_ARM_SRC_LPC313X_WDT_H - -/************************************************************************************************ - * Included Files - ************************************************************************************************/ - -#include -#include "lpc313x_memorymap.h" - -/************************************************************************************************ - * Pre-processor Definitions - ************************************************************************************************/ - -/* WDT register base address offset into the APB0 domain ****************************************/ - -#define LPC313X_WDT_VBASE (LPC313X_APB0_VADDR+LPC313X_APB0_WDT_OFFSET) -#define LPC313X_WDT_PBASE (LPC313X_APB0_PADDR+LPC313X_APB0_WDT_OFFSET) - -/* WDT register offsets (with respect to the WDT base) ******************************************/ - -#define LPC313X_WDT_IR_OFFSET 0x000 /* Interrupt Register */ -#define LPC313X_WDT_TCR_OFFSET 0x004 /* Timer Control Register */ -#define LPC313X_WDT_TC_OFFSET 0x008 /* Timer Counter */ -#define LPC313X_WDT_PR_OFFSET 0x00c /* Timer Prescale Register */ -#define LPC313X_WDT_PC_OFFSET 0x010 /* Prescale Counter */ -#define LPC313X_WDT_MCR_OFFSET 0x014 /* Match Control Register */ -#define LPC313X_WDT_MR0_OFFSET 0x018 /* Match Register 0 */ -#define LPC313X_WDT_MR1_OFFSET 0x01c /* Match Register 1 */ - /* 0x020-0x038: Reserved */ -#define LPC313X_WDT_EMR_OFFSET 0x03c /* External Match Register */ - -/* WDT register (virtual) addresses *************************************************************/ - -#define LPC313X_WDT_IR (LPC313X_WDT_VBASE+LPC313X_WDT_IR_OFFSET) -#define LPC313X_WDT_TCR (LPC313X_WDT_VBASE+LPC313X_WDT_TCR_OFFSET) -#define LPC313X_WDT_TC (LPC313X_WDT_VBASE+LPC313X_WDT_TC_OFFSET) -#define LPC313X_WDT_PR (LPC313X_WDT_VBASE+LPC313X_WDT_PR_OFFSET) -#define LPC313X_WDT_PC (LPC313X_WDT_VBASE+LPC313X_WDT_PC_OFFSET) -#define LPC313X_WDT_MCR (LPC313X_WDT_VBASE+LPC313X_WDT_MCR_OFFSET) -#define LPC313X_WDT_MR0 (LPC313X_WDT_VBASE+LPC313X_WDT_MR0_OFFSET) -#define LPC313X_WDT_MR1 (LPC313X_WDT_VBASE+LPC313X_WDT_MR1_OFFSET) -#define LPC313X_WDT_EMR (LPC313X_WDT_VBASE+LPC313X_WDT_EMR_OFFSET) - -/* WDT register bit definitions *****************************************************************/ - -/* Interrupt Register (IR), address 0x13002400 */ - -#define WDT_IR_INTRM1 (1 << 1) /* Bit 1: MR1 and TC match interrupt */ -#define WDT_IR_INTRM0 (1 << 0) /* Bit 0: MR0 and TC match interrupt */ - -/* Timer Control Register (TCR), address 0x13002404 */ - -#define WDT_TCR_RESET (1 << 1) /* Bit 1: Reset on the next WDOG_PCLK */ -#define WDT_TCR_ENABLE (1 << 0) /* Bit 0: Enable */ - -/* Match Control Register (MCR), address 0x1300 2414 */ - -#define WDT_MCR_MR1STOP (1 << 5) /* Bit 5: Stop counting when MR1=TC */ -#define WDT_MCR_MR1RESET (1 << 4) /* Bit 4: Reset TC if MR1=TC */ -#define WDT_MCR_MR1INT (1 << 3) /* Bit 3: System reset when MR1=TC */ -#define WDT_MCR_MR0STOP (1 << 2) /* Bit 2: Stop counting when MR0=TC */ -#define WDT_MCR_MR0RESET (1 << 1) /* Bit 1: Reset TC if MR0=TC */ -#define WDT_MCR_MR0INT (1 << 0) /* Bit 0: System reset when MR0=TC */ - -/* External Match Registers (EMR), address 0x1300 243c */ - -#define WDT_EMR_EXTMATCHCTRL1_SHIFT (6) /* Bits 6-7: Controls EXTMATCH1 when MR1=TC */ -#define WDT_EMR_EXTMATCHCTRL1_MASK (3 << WDT_EMR_EXTMATCHCTRL1_SHIFT) -# define WDT_EMR_EXTMATCHCTRL1_NOTHING (0 << WDT_EMR_EXTMATCHCTRL1_SHIFT) /* Do Nothing */ -# define WDT_EMR_EXTMATCHCTRL1_SETLOW (1 << WDT_EMR_EXTMATCHCTRL1_SHIFT) /* Set LOW */ -# define WDT_EMR_EXTMATCHCTRL1_SETHIGH (2 << WDT_EMR_EXTMATCHCTRL1_SHIFT) /* Set HIGH */ -# define WDT_EMR_EXTMATCHCTRL1_TOGGLE (3 << WDT_EMR_EXTMATCHCTRL1_SHIFT) /* Toggle */ -#define WDT_EMR_EXTMATCHCTRL0_SHIFT (4) /* Bits 4-5: Controls EXTMATCH0 when MR0=TC */ -#define WDT_EMR_EXTMATCHCTRL0_MASK (3 << WDT_EMR_EXTMATCHCTRL0_SHIFT) -# define WDT_EMR_EXTMATCHCTRL0_NOTHING (0 << WDT_EMR_EXTMATCHCTRL0_SHIFT) /* Do Nothing */ -# define WDT_EMR_EXTMATCHCTRL0_SETLOW (1 << WDT_EMR_EXTMATCHCTRL0_SHIFT) /* Set LOW */ -# define WDT_EMR_EXTMATCHCTRL0_SETHIGH (2 << WDT_EMR_EXTMATCHCTRL0_SHIFT) /* Set HIGH */ -# define WDT_EMR_EXTMATCHCTRL0_TOGGLE (3 << WDT_EMR_EXTMATCHCTRL0_SHIFT) /* Toggle */ -#define WDT_EMR_EXTMATCH1 (1 << 1) /* Bit 1: EXTMATCHCTRL1 controls behavior */ -#define WDT_EMR_EXTMATCH0 (1 << 0) /* Bit 0: EXTMATCHCTRL1 controls behavior */ - -/************************************************************************************************ - * Public Types - ************************************************************************************************/ - -/************************************************************************************************ - * Public Data - ************************************************************************************************/ - -/************************************************************************************************ - * Public Functions - ************************************************************************************************/ - -#endif /* __ARCH_ARM_SRC_LPC313X_WDT_H */ diff --git a/nuttx/arch/arm/src/lpc31xx/Make.defs b/nuttx/arch/arm/src/lpc31xx/Make.defs new file mode 100755 index 000000000..69af7726f --- /dev/null +++ b/nuttx/arch/arm/src/lpc31xx/Make.defs @@ -0,0 +1,67 @@ +############################################################################ +# arch/arm/lpc31xx/Make.defs +# +# Copyright (C) 2009-2011 Gregory Nutt. All rights reserved. +# Author: Gregory Nutt +# +# 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 Gregory Nutt 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 = up_head.S + +CMN_ASRCS = up_cache.S up_fullcontextrestore.S up_saveusercontext.S \ + up_vectors.S up_vectoraddrexcptn.S up_vectortab.S +CMN_CSRCS = 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_modifyreg8.c up_modifyreg16.c up_modifyreg32.c \ + up_prefetchabort.c up_releasepending.c up_releasestack.c \ + up_reprioritizertr.c up_schedulesigaction.c \ + up_sigdeliver.c up_syscall.c up_unblocktask.c \ + up_undefinedinsn.c up_usestack.c + +ifeq ($(CONFIG_PAGING),y) +CMN_CSRCS += up_pginitialize.c up_checkmapping.c up_allocpage.c up_va2pte.c +endif + +CGU_ASRCS = +CGU_CSRCS = lpc31_bcrndx.c lpc31_clkdomain.c lpc31_clkexten.c \ + lpc31_clkfreq.c lpc31_clkinit.c lpc31_defclk.c \ + lpc31_esrndx.c lpc31_fdcndx.c lpc31_fdivinit.c \ + lpc31_freqin.c lpc31_pllconfig.c lpc31_resetclks.c \ + lpc31_setfreqin.c lpc31_setfdiv.c lpc31_softreset.c + +CHIP_ASRCS = $(CGU_ASRCS) +CHIP_CSRCS = lpc31_allocateheap.c lpc31_boot.c lpc31_decodeirq.c \ + lpc31_irq.c lpc31_lowputc.c lpc31_serial.c lpc31_i2c.c \ + lpc31_spi.c lpc31_timerisr.c $(CGU_CSRCS) + +ifeq ($(CONFIG_USBDEV),y) +CHIP_CSRCS += lpc31_usbdev.c +endif diff --git a/nuttx/arch/arm/src/lpc31xx/chip.h b/nuttx/arch/arm/src/lpc31xx/chip.h new file mode 100755 index 000000000..35b6cd88b --- /dev/null +++ b/nuttx/arch/arm/src/lpc31xx/chip.h @@ -0,0 +1,62 @@ +/************************************************************************************ + * arch/arm/src/lpc31xx/chip.h + * + * Copyright (C) 2009 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * 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_LPC31XX_CHIP_H +#define __ARCH_ARM_SRC_LPC31XX_CHIP_H + +/************************************************************************************ + * Included Files + ************************************************************************************/ + +#include +#include "lpc31_memorymap.h" + +/************************************************************************************ + * Pre-processor Definitions + ************************************************************************************/ + +/************************************************************************************ + * Public Types + ************************************************************************************/ + +/************************************************************************************ + * Public Data + ************************************************************************************/ + +/************************************************************************************ + * Public Functions + ************************************************************************************/ + +#endif /* __ARCH_ARM_SRC_LPC31XX_CHIP_H */ diff --git a/nuttx/arch/arm/src/lpc31xx/lpc31_adc.h b/nuttx/arch/arm/src/lpc31xx/lpc31_adc.h new file mode 100755 index 000000000..f0231e255 --- /dev/null +++ b/nuttx/arch/arm/src/lpc31xx/lpc31_adc.h @@ -0,0 +1,132 @@ +/************************************************************************************************ + * arch/arm/src/lpc31xx/lpc31_adc.h + * + * Copyright (C) 2009-2010 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * 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_LPC31XX_LPC31_ADC_H +#define __ARCH_ARM_SRC_LPC31XX_LPC31_ADC_H + +/************************************************************************************************ + * Included Files + ************************************************************************************************/ + +#include +#include "lpc31_memorymap.h" + +/************************************************************************************************ + * Pre-processor Definitions + ************************************************************************************************/ + +/* ADC register base address offset into the APB0 domain ****************************************/ + +#define LPC31_ADC_VBASE (LPC31_APB0_VADDR+LPC31_APB0_ADC_OFFSET) +#define LPC31_ADC_PBASE (LPC31_APB0_PADDR+LPC31_APB0_ADC_OFFSET) + +/* ADC register offsets (with respect to the ADC base) ******************************************/ + +#define LPC31_ADC_R0_OFFSET 0x000 /* Data for analog input channel 0 */ +#define LPC31_ADC_R1_OFFSET 0x004 /* Data for analog input channel 1 */ +#define LPC31_ADC_R2_OFFSET 0x008 /* Data for analog input channel 2 */ +#define LPC31_ADC_R3_OFFSET 0x00c /* Data for analog input channel 3 */ + /* 0x010-0x01c: Reserved */ +#define LPC31_ADC_CON_OFFSET 0x020 /* ADC control register */ +#define LPC31_ADC_CSEL_OFFSET 0x024 /* Configure and select analog input channels */ +#define LPC31_ADC_INTEN_OFFSET 0x028 /* Enable ADC interrupts */ +#define LPC31_ADC_INTST_OFFSET 0x02C /* ADC interrupt status */ +#define LPC31_ADC_INTCLR_OFFSET 0x030 /* Clear ADC interrupt status */ + /* 0x034-: Reserved */ + +/* ADC register (virtual) addresses *************************************************************/ + +#define LPC31_ADC_R0 (LPC31_ADC_VBASE+LPC31_ADC_R0_OFFSET) +#define LPC31_ADC_R1 (LPC31_ADC_VBASE+LPC31_ADC_R1_OFFSET) +#define LPC31_ADC_R2 (LPC31_ADC_VBASE+LPC31_ADC_R2_OFFSET) +#define LPC31_ADC_R3 (LPC31_ADC_VBASE+LPC31_ADC_R3_OFFSET) +#define LPC31_ADC_CON (LPC31_ADC_VBASE+LPC31_ADC_CON_OFFSET) +#define LPC31_ADC_CSEL (LPC31_ADC_VBASE+LPC31_ADC_CSEL_OFFSET) +#define LPC31_ADC_INTEN (LPC31_ADC_VBASE+LPC31_ADC_INTEN_OFFSET) +#define LPC31_ADC_INTST (LPC31_ADC_VBASE+LPC31_ADC_INTST_OFFSET) +#define LPC31_ADC_INTCLR (LPC31_ADC_VBASE+LPC31_ADC_INTCLR_OFFSET) + +/* ADC register bit definitions *****************************************************************/ + +/* ADC_Rx (ADC_R0, address 0x13002000; ADC_R1, address 0x13002004, ADC_R2, address 0x13002008; + * ADC_R3, address 0x1300200c) + */ + +#define ADC_RX_SHIFT (0) /* Bits 0-9: Digital conversion data */ +#define ADC_RX_MASK (0x3ff << ADC_RX_SHIFT) + +/* ADC_CON, address 0x13002020 */ + +#define ADC_CON_STATUS (1 << 4) /* Bit 4: ADC Status */ +#define ADC_CON_START (1 << 3) /* Bit 3: Start command */ +#define ADC_CON_CSCAN (1 << 2) /* Bit 2: Continuous scan */ +#define ADC_CON_ENABLE (1 << 1) /* Bit 1: ADC enable */ + +/* ADC_CSEL, address 0x13002024 */ + +#define ADC_CSEL_CHAN3_SHIFT (12) /* Bits 12-15: Select and configure channel 3*/ +#define ADC_CSEL_CHAN3_MASK (15 << ADC_CSEL_CHAN3_SHIFT) +#define ADC_CSEL_CHAN2_SHIFT (8) /* Bits 8-10: Select and configure channel 2*/ +#define ADC_CSEL_CHAN2_MASK (15 << ADC_CSEL_CHAN2_SHIFT) +#define ADC_CSEL_CHAN1_SHIFT (4) /* Bits 4-7: Select and configure channel 1*/ +#define ADC_CSEL_CHAN1_MASK (15 << ADC_CSEL_CHAN1_SHIFT) +#define ADC_CSEL_CHAN0_SHIFT (0) /* Bits 0-3: Select and configure channel 0*/ +#define ADC_CSEL_CHAN0_MASK (15 << ADC_CSEL_CHAN0_SHIFT) + +/* ADC_INTEN, address 0x13002028 */ + +#define ADC_INTEN_ENABLE (1 << 0) + +/* ADC_INTST, address 0x1300202c */ + +#define ADC_INTST_PENDING (1 << 0) + +/* ADC_INTCLR, address 0x13002030 */ + +#define ADC_INTCLR_CLEAR (1 << 0) + +/************************************************************************************************ + * Public Types + ************************************************************************************************/ + +/************************************************************************************************ + * Public Data + ************************************************************************************************/ + +/************************************************************************************************ + * Public Functions + ************************************************************************************************/ + +#endif /* __ARCH_ARM_SRC_LPC31XX_LPC31_ADC_H */ diff --git a/nuttx/arch/arm/src/lpc31xx/lpc31_allocateheap.c b/nuttx/arch/arm/src/lpc31xx/lpc31_allocateheap.c new file mode 100755 index 000000000..0f68dcc0c --- /dev/null +++ b/nuttx/arch/arm/src/lpc31xx/lpc31_allocateheap.c @@ -0,0 +1,206 @@ +/************************************************************************ + * arch/arm/src/lpc31xx/lpc31_allocateheap.c + * + * Copyright (C) 2009-2010 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name NuttX nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ************************************************************************/ + +/************************************************************************ + * Included Files + ************************************************************************/ + +#include + +#include +#include + +#include +#include + +#include "arm.h" +#include "chip.h" +#include "up_arch.h" +#include "up_internal.h" +#include "lpc31_memorymap.h" + +#ifdef CONFIG_PAGING +# include +# include "pg_macros.h" +#endif + +/************************************************************************ + * Pre-processor Definitions + ************************************************************************/ + +/* Configuration ********************************************************/ + +/* Some sanity checking. If external memory regions are defined, verify + * that CONFIG_MM_REGIONS is set to match, exactly, the number of external + * memory regions that we have been asked to add to the heap. + */ + +#if defined(CONFIG_LPC31_EXTSRAM0) && defined(CONFIG_LPC31_EXTSRAM0HEAP) +# if defined(CONFIG_LPC31_EXTSRAM1) && defined(CONFIG_LPC31_EXTSRAM1HEAP) +# if defined(CONFIG_LPC31_EXTSDRAM) && defined(CONFIG_LPC31_EXTSDRAMHEAP) +# /* SRAM+EXTSRAM0+EXTSRAM1+EXTSDRAM */ +# define LPC31_NEXT_REGIONS 4 +# else +# /* SRAM+EXTSRAM0+EXTSRAM1 */ +# define LPC31_NEXT_REGIONS 3 +# endif +# elif defined(CONFIG_LPC31_EXTSDRAM) && defined(CONFIG_LPC31_EXTSDRAMHEAP) +# /* SRAM+EXTSRAM0+EXTSDRAM */ +# define LPC31_NEXT_REGIONS 3 +# else +# /* SRAM+EXTSRAM0 */ +# define LPC31_NEXT_REGIONS 2 +# endif +#elif defined(CONFIG_LPC31_EXTSRAM1) && defined(CONFIG_LPC31_EXTSRAM1HEAP) +# if defined(CONFIG_LPC31_EXTSDRAM) && defined(CONFIG_LPC31_EXTSDRAMHEAP) +# /* SRAM+EXTSRAM1+EXTSDRAM */ +# define LPC31_NEXT_REGIONS 3 +# else +# /* SRAM+EXTSRAM1 */ +# define LPC31_NEXT_REGIONS 2 +# endif +#elif defined(CONFIG_LPC31_EXTSDRAM) && defined(CONFIG_LPC31_EXTSDRAMHEAP) +# /* SRAM+EXTSDRAM */ +# define LPC31_NEXT_REGIONS 2 +#else +# /* SRAM */ +# define LPC31_NEXT_REGIONS 1 +#endif + +#if CONFIG_MM_REGIONS != LPC31_NEXT_REGIONS +# if CONFIG_MM_REGIONS < LPC31_NEXT_REGIONS +# error "CONFIG_MM_REGIONS is large enough for the selected memory regions" +# else +# error "CONFIG_MM_REGIONS is too large for the selected memory regions" +# endif +# if defined(CONFIG_LPC31_EXTSRAM0) && defined(CONFIG_LPC31_EXTSRAM0HEAP) +# error "External SRAM0 is selected for heap" +# endif +# if defined(CONFIG_LPC31_EXTSRAM1) && defined(CONFIG_LPC31_EXTSRAM1HEAP) +# error "External SRAM1 is selected for heap" +# endif +# if defined(CONFIG_LPC31_EXTSDRAM) && defined(CONFIG_LPC31_EXTSDRAMHEAP) +# error "External SRAM1 is selected for heap" +# endif +#endif + +/* The following determines the end+1 address the heap (in SRAM0 or SRAM1) + * and that, in turn, determines the size of the heap. Specifically, this + * logic it checks if a page table has been allocated at the end of SRAM + * and, if so, subtracts that the size of the page table from the end+1 + * address of heap. + * + * If the page table was not allocated at the end of SRAM, then this logic + * will let the heap run all the way to the end of SRAM. + */ + +#ifdef CONFIG_PAGING +# ifdef PGTABLE_IN_HIGHSRAM +# define LPC31_HEAP_VEND (PG_LOCKED_VBASE + PG_TOTAL_VSIZE - PGTABLE_SIZE) +# else +# define LPC31_HEAP_VEND (PG_LOCKED_VBASE + PG_TOTAL_VSIZE) +# endif +#else +# ifdef PGTABLE_IN_HIGHSRAM +# define LPC31_HEAP_VEND (LPC31_INTSRAM_VSECTION + LPC31_ISRAM_SIZE - PGTABLE_SIZE) +# else +# define LPC31_HEAP_VEND (LPC31_INTSRAM_VSECTION + LPC31_ISRAM_SIZE) +# endif +#endif + +/************************************************************************ + * Private Data + ************************************************************************/ + +/************************************************************************ + * Private Functions + ************************************************************************/ + +/************************************************************************ + * Public Functions + ************************************************************************/ + +/************************************************************************ + * Name: up_allocate_heap + * + * Description: + * The heap may be statically allocated by defining CONFIG_HEAP_BASE + * and CONFIG_HEAP_SIZE. If these are not defined, then this function + * will be called to dynamically set aside the heap region to the end + * of SRAM. + * + * SRAM layout: + * Start of SRAM: .data + * .bss + * IDLE thread stack + * End of SRAm: heap + * + * NOTE: Ignore the erroneous nomenclature DRAM and SDRAM. That names + * date back to an earlier platform that had SDRAM. + * + ************************************************************************/ + +void up_allocate_heap(FAR void **heap_start, size_t *heap_size) +{ + up_ledon(LED_HEAPALLOCATE); + *heap_start = (FAR void*)g_heapbase; + *heap_size = LPC31_HEAP_VEND - g_heapbase; +} + +/************************************************************************ + * Name: up_addregion + * + * Description: + * Memory may be added in non-contiguous chunks. Additional chunks are + * added by calling this function. + * + ************************************************************************/ + +#if CONFIG_MM_REGIONS > 1 +void up_addregion(void) +{ +#if defined(CONFIG_LPC31_EXTSRAM0) && defined(CONFIG_LPC31_EXTSRAM0HEAP) + mm_addregion((FAR void*)LPC31_EXTSRAM0_VSECTION, CONFIG_LPC31_EXTSRAM0SIZE); +#endif + +#if defined(CONFIG_LPC31_EXTSRAM1) && defined(CONFIG_LPC31_EXTSRAM1HEAP) + mm_addregion((FAR void*)LPC31_EXTSRAM1_VSECTION, CONFIG_LPC31_EXTSRAM1SIZE); +#endif + +#if defined(CONFIG_LPC31_EXTSDRAM) && defined(CONFIG_LPC31_EXTSDRAMHEAP) + mm_addregion((FAR void*)LPC31_EXTSDRAM_VSECTION, CONFIG_LPC31_EXTSDRAMSIZE); +#endif +} +#endif diff --git a/nuttx/arch/arm/src/lpc31xx/lpc31_bcrndx.c b/nuttx/arch/arm/src/lpc31xx/lpc31_bcrndx.c new file mode 100755 index 000000000..6da6aa55d --- /dev/null +++ b/nuttx/arch/arm/src/lpc31xx/lpc31_bcrndx.c @@ -0,0 +1,100 @@ +/************************************************************************ + * arch/arm/src/lpc31xx/lpc31_bcrndx.c + * + * Copyright (C) 2009-2010 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * References: + * - UM10314 LPC3130/31 User manual Rev. 1.01 — 9 September 2009 + * - lpc313x.cdl.drivers.zip example driver code + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name NuttX nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ************************************************************************/ + +/************************************************************************ + * Included Files + ************************************************************************/ + +#include +#include + +#include "up_arch.h" +#include "lpc31_cgudrvr.h" + +/************************************************************************ + * Pre-processor Definitions + ************************************************************************/ + +/************************************************************************ + * Private Data + ************************************************************************/ + +/************************************************************************ + * Private Functions + ************************************************************************/ + +/************************************************************************ + * Public Functions + ************************************************************************/ + +/************************************************************************ + * Name: lpc31_bcrndx + * + * Description: + * Only 5 of the 12 domains have an associated BCR register. This + * function returns the index to the associated BCR register (if any) + * or BCRNDX_INVALID otherwise. + * + ************************************************************************/ + +int lpc31_bcrndx(enum lpc31_domainid_e dmnid) +{ + switch (dmnid) + { + /* BCR0-3 correspond directly to domains 0-3 */ + + case DOMAINID_SYS: /* Domain 0: SYS_BASE */ + case DOMAINID_AHB0APB0: /* Domain 1: AHB0APB0_BASE */ + case DOMAINID_AHB0APB1: /* Domain 2: AHB0APB1_BASE */ + case DOMAINID_AHB0APB2: /* Domain 3: AHB0APB2_BASE */ + return (int)dmnid; + + /* There is a BCR register corresponding to domain 7, but it is at + * index 4 + */ + + case DOMAINID_CLK1024FS: /* Domain 7: CLK1024FS_BASE */ + return 4; + + default: /* There is no BCR register for the other + * domains. */ + break; + } + return BCRNDX_INVALID; +} diff --git a/nuttx/arch/arm/src/lpc31xx/lpc31_boot.c b/nuttx/arch/arm/src/lpc31xx/lpc31_boot.c new file mode 100755 index 000000000..42da03bbd --- /dev/null +++ b/nuttx/arch/arm/src/lpc31xx/lpc31_boot.c @@ -0,0 +1,397 @@ +/************************************************************************************ + * arch/arm/src/lpc31xx/lpc31_boot.c + * + * Copyright (C) 2009-2010 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name NuttX nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ************************************************************************************/ + +/************************************************************************************ + * Included Files + ************************************************************************************/ + +#include +#include + +#include + +#include "chip.h" +#include "arm.h" +#include "up_internal.h" +#include "up_arch.h" + +#include "lpc31_syscreg.h" +#include "lpc31_cgudrvr.h" +#include "lpc31_internal.h" + +#ifdef CONFIG_PAGING +# include +# include "pg_macros.h" +#endif + +/************************************************************************************ + * Private Types + ************************************************************************************/ + +/************************************************************************************ + * Private Types + ************************************************************************************/ + +struct section_mapping_s +{ + uint32_t physbase; /* Physical address of the region to be mapped */ + uint32_t virtbase; /* Virtual address of the region to be mapped */ + uint32_t mmuflags; /* MMU settings for the region (e.g., cache-able) */ + uint32_t nsections; /* Number of mappings in the region */ +}; + +/************************************************************************************ + * Public Variables + ************************************************************************************/ + +extern uint32_t _vector_start; /* Beginning of vector block */ +extern uint32_t _vector_end; /* End+1 of vector block */ + +/************************************************************************************ + * Private Variables + ************************************************************************************/ + +/* This table describes how to map a set of 1Mb pages to space the physical address + * space of the LPCD313x. + */ + +#ifndef CONFIG_ARCH_ROMPGTABLE +static const struct section_mapping_s section_mapping[] = +{ + { LPC31_SHADOWSPACE_PSECTION, LPC31_SHADOWSPACE_VSECTION, + LPC31_SHADOWSPACE_MMUFLAGS, LPC31_SHADOWSPACE_NSECTIONS}, +#ifndef CONFIG_PAGING /* SRAM is already fully mapped */ + { LPC31_INTSRAM_PSECTION, LPC31_INTSRAM_VSECTION, + LPC31_INTSRAM_MMUFLAGS, LPC31_INTSRAM_NSECTIONS}, +#endif +#ifdef CONFIG_ARCH_ROMPGTABLE + { LPC31_INTSROM0_PSECTION, LPC31_INTSROM0_VSECTION, + LPC31_INTSROM_MMUFLAGS, LPC31_INTSROM0_NSECTIONS}, +#endif + { LPC31_APB01_PSECTION, LPC31_APB01_VSECTION, + LPC31_APB01_MMUFLAGS, LPC31_APB01_NSECTIONS}, + { LPC31_APB2_PSECTION, LPC31_APB2_VSECTION, + LPC31_APB2_MMUFLAGS, LPC31_APB2_NSECTIONS}, + { LPC31_APB3_PSECTION, LPC31_APB3_VSECTION, + LPC31_APB3_MMUFLAGS, LPC31_APB3_NSECTIONS}, + { LPC31_APB4MPMC_PSECTION, LPC31_APB4MPMC_VSECTION, + LPC31_APB4MPMC_MMUFLAGS, LPC31_APB4MPMC_NSECTIONS}, + { LPC31_MCI_PSECTION, LPC31_MCI_VSECTION, + LPC31_MCI_MMUFLAGS, LPC31_MCI_NSECTIONS}, + { LPC31_USBOTG_PSECTION, LPC31_USBOTG_VSECTION, + LPC31_USBOTG_MMUFLAGS, LPC31_USBOTG_NSECTIONS}, +#if defined(CONFIG_LPC31_EXTSRAM0) && CONFIG_LPC31_EXTSRAM0SIZE > 0 + { LPC31_EXTSRAM_PSECTION, LPC31_EXTSRAM_VSECTION, + LPC31_EXTSDRAM_MMUFLAGS, LPC31_EXTSRAM_NSECTIONS}, +#endif +#if defined(CONFIG_LPC31_EXTSDRAM) && CONFIG_LPC31_EXTSDRAMSIZE > 0 + { LPC31_EXTSDRAM0_PSECTION, LPC31_EXTSDRAM0_VSECTION, + LPC31_EXTSDRAM_MMUFLAGS, LPC31_EXTSDRAM0_NSECTIONS}, +#endif + { LPC31_INTC_PSECTION, LPC31_INTC_VSECTION, + LPC31_INTC_MMUFLAGS, LPC31_INTC_NSECTIONS}, +#ifdef CONFIG_LPC31_EXTNAND + { LPC31_NAND_PSECTION, LPC31_NAND_VSECTION + LPC31_NAND_MMUFLAGS, LPC31_NAND_NSECTIONS}, +#endif +}; +#define NMAPPINGS (sizeof(section_mapping) / sizeof(struct section_mapping_s)) +#endif + +/************************************************************************************ + * Private Functions + ************************************************************************************/ + +/************************************************************************************ + * Name: up_setlevel1entry + ************************************************************************************/ + +#ifndef CONFIG_ARCH_ROMPGTABLE +static inline void up_setlevel1entry(uint32_t paddr, uint32_t vaddr, uint32_t mmuflags) +{ + uint32_t *pgtable = (uint32_t*)PGTABLE_BASE_VADDR; + uint32_t index = vaddr >> 20; + + /* Save the page table entry */ + + pgtable[index] = (paddr | mmuflags); +} +#endif + +/************************************************************************************ + * Name: up_setlevel2coarseentry + ************************************************************************************/ + +static inline void up_setlevel2coarseentry(uint32_t ctabvaddr, uint32_t paddr, + uint32_t vaddr, uint32_t mmuflags) +{ + uint32_t *ctable = (uint32_t*)ctabvaddr; + uint32_t index; + + /* The coarse table divides a 1Mb address space up into 256 entries, each + * corresponding to 4Kb of address space. The coarse page table index is + * related to the offset from the beginning of 1Mb region. + */ + + index = (vaddr & 0x000ff000) >> 12; + + /* Save the coarse table entry */ + + ctable[index] = (paddr | mmuflags); +} + +/************************************************************************************ + * Name: up_setupmappings + ************************************************************************************/ + +#ifndef CONFIG_ARCH_ROMPGTABLE +static void up_setupmappings(void) +{ + int i, j; + + for (i = 0; i < NMAPPINGS; i++) + { + uint32_t sect_paddr = section_mapping[i].physbase; + uint32_t sect_vaddr = section_mapping[i].virtbase; + uint32_t mmuflags = section_mapping[i].mmuflags; + + for (j = 0; j < section_mapping[i].nsections; j++) + { + up_setlevel1entry(sect_paddr, sect_vaddr, mmuflags); + sect_paddr += SECTION_SIZE; + sect_vaddr += SECTION_SIZE; + } + } +} +#endif + +/************************************************************************************ + * Name: up_vectorpermissions + * + * Description: + * Set permissions on the vector mapping. + * + ************************************************************************************/ + +#if !defined(CONFIG_ARCH_ROMPGTABLE) && defined(CONFIG_ARCH_LOWVECTORS) && defined(CONFIG_PAGING) +static void up_vectorpermissions(uint32_t mmuflags) +{ + /* The PTE for the beginning of ISRAM is at the base of the L2 page table */ + + uint32_t *ptr = (uint32_t*)PG_L2_VECT_VADDR; + uint32_t pte; + + /* The pte might be zero the first time this function is called. */ + + pte = *ptr; + if (pte == 0) + { + pte = PG_VECT_PBASE; + } + else + { + pte &= PG_L1_PADDRMASK; + } + + /* Update the MMU flags and save */ + + *ptr = pte | mmuflags; + + /* Invalid the TLB for this address */ + + tlb_invalidate_single(PG_L2_VECT_VADDR); +} +#endif + +/************************************************************************************ + * Name: up_vectormapping + * + * Description: + * Setup a special mapping for the interrupt vectors when (1) the interrupt + * vectors are not positioned in ROM, and when (2) the interrupt vectors are + * located at the high address, 0xffff0000. When the interrupt vectors are located + * in ROM, we just have to assume that they were set up correctly; When vectors + * are located in low memory, 0x00000000, the shadow memory region will be mapped + * to support them. + * + ************************************************************************************/ + +#if !defined(CONFIG_ARCH_ROMPGTABLE) && !defined(CONFIG_ARCH_LOWVECTORS) +static void up_vectormapping(void) +{ + uint32_t vector_paddr = LPC31_VECTOR_PADDR; + uint32_t vector_vaddr = LPC31_VECTOR_VADDR; + uint32_t end_paddr = vector_paddr + VECTOR_TABLE_SIZE; + + /* We want to keep our interrupt vectors and interrupt-related logic in zero-wait + * state internal RAM (IRAM). The DM320 has 16Kb of IRAM positioned at physical + * address 0x0000:0000; we need to map this to 0xffff:0000. + */ + + while (vector_paddr < end_paddr) + { + up_setlevel2coarseentry(PGTABLE_L2_COARSE_VBASE, vector_paddr, + vector_vaddr, MMU_L2_VECTORFLAGS); + vector_paddr += 4096; + vector_vaddr += 4096; + } + + /* Now set the level 1 descriptor to refer to the level 2 coarse page table. */ + + up_setlevel1entry(PGTABLE_L2_COARSE_PBASE, LPC31_VECTOR_VCOARSE, + MMU_L1_VECTORFLAGS); +} +#endif + +/************************************************************************************ + * Name: up_copyvectorblock + * + * Description: + * Copy the interrupt block to its final destination. + * + ************************************************************************************/ + +static void up_copyvectorblock(void) +{ + uint32_t *src; + uint32_t *end; + uint32_t *dest; + + /* If we are using vectors in low memory but RAM in that area has been marked + * read only, then temparily mark the mapping write-able (non-buffered). + */ + +#if !defined(CONFIG_ARCH_ROMPGTABLE) && defined(CONFIG_ARCH_LOWVECTORS) && defined(CONFIG_PAGING) + up_vectorpermissions(MMU_L2_VECTRWFLAGS); +#endif + + /* Copy the vectors into ISRAM at the address that will be mapped to the vector + * address: + * + * LPC31_VECTOR_PADDR - Unmapped, physical address of vector table in SRAM + * LPC31_VECTOR_VSRAM - Virtual address of vector table in SRAM + * LPC31_VECTOR_VADDR - Virtual address of vector table (0x00000000 or 0xffff0000) + */ + + src = (uint32_t*)&_vector_start; + end = (uint32_t*)&_vector_end; + dest = (uint32_t*)LPC31_VECTOR_VSRAM; + + while (src < end) + { + *dest++ = *src++; + } + + /* Make the vectors read-only, cacheable again */ + +#if !defined(CONFIG_ARCH_ROMPGTABLE) && defined(CONFIG_ARCH_LOWVECTORS) && defined(CONFIG_PAGING) + up_vectorpermissions(MMU_L2_VECTROFLAGS); +#endif + + /* Then set the LPC313x shadow register, LPC31_SYSCREG_ARM926SHADOWPTR, so that + * the vector table is mapped to address 0x0000:0000 - NOTE: that there is not yet + * full support for the vector table at address 0xffff0000. + */ + + putreg32(LPC31_VECTOR_PADDR, LPC31_SYSCREG_ARM926SHADOWPTR); +} + +/************************************************************************************ + * Public Functions + ************************************************************************************/ + +/************************************************************************************ + * Name: up_boot + * + * Description: + * Complete boot operations started in up_head.S + * + ************************************************************************************/ + +void up_boot(void) +{ + /* __start provided the basic MMU mappings for SRAM. Now provide mappings for all + * IO regions (Including the vector region). + */ + +#ifndef CONFIG_ARCH_ROMPGTABLE + up_setupmappings(); + + /* Provide a special mapping for the IRAM interrupt vector positioned in high + * memory. + */ + +#ifndef CONFIG_ARCH_LOWVECTORS + up_vectormapping(); +#endif +#endif /* CONFIG_ARCH_ROMPGTABLE */ + + /* Setup up vector block. _vector_start and _vector_end are exported from + * up_vector.S + */ + + up_copyvectorblock(); + + /* Reset all clocks */ + + lpc31_resetclks(); + + /* Initialize the PLLs */ + + lpc31_hp1pllconfig(); + lpc31_hp0pllconfig(); + + /* Initialize clocking to settings provided by board-specific logic */ + + lpc31_clkinit(&g_boardclks); + + /* Map first 4KB of ARM space to ISRAM area */ + + putreg32(LPC31_INTSRAM0_PADDR, LPC31_SYSCREG_ARM926SHADOWPTR); + + /* Perform common, low-level chip initialization (might do nothing) */ + + lpc31_lowsetup(); + + /* Perform early serial initialization if we are going to use the serial driver */ + +#ifdef CONFIG_USE_EARLYSERIALINIT + up_earlyserialinit(); +#endif + + /* Perform board-specific initialization */ + + lpc31_boardinitialize(); +} diff --git a/nuttx/arch/arm/src/lpc31xx/lpc31_cgu.h b/nuttx/arch/arm/src/lpc31xx/lpc31_cgu.h new file mode 100755 index 000000000..a50ec0cf8 --- /dev/null +++ b/nuttx/arch/arm/src/lpc31xx/lpc31_cgu.h @@ -0,0 +1,1626 @@ +/************************************************************************************************ + * arch/arm/src/lpc31xx/lpc31_cgu.h + * + * Copyright (C) 2009-2010 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * References: + * - UM10314 LPC3130/31 User manual Rev. 1.01 — 9 September 2009 + * + * 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_LPC31XX_LPC31_CGU_H +#define __ARCH_ARM_SRC_LPC31XX_LPC31_CGU_H + +/************************************************************************************************ + * Included Files + ************************************************************************************************/ + +#include +#include "lpc31_memorymap.h" + +/************************************************************************************************ + * Pre-processor Definitions + ************************************************************************************************/ + +/* CGU register base address offset into the APB0 domain ****************************************/ + +/* APB0 offsets to Clock Switch Box (CSB) and CGU Configuration (CFG) register groups */ + +#define LPC31_APB0_GCU_CSB_OFFSET (LPC31_APB0_GCU_OFFSET) +#define LPC31_APB0_GCU_CFG_OFFSET (LPC31_APB0_GCU_OFFSET+0x0c00) + +/* Virtual and physical base address of the CGU block and CSB and CFG register groups */ + +#define LPC31_CGU_VBASE (LPC31_APB0_VADDR+LPC31_APB0_CGU_OFFSET) +#define LPC31_CGU_PBASE (LPC31_APB0_PADDR+LPC31_APB0_CGU_OFFSET) + +#define LPC31_CGU_CSB_VBASE (LPC31_APB0_VADDR+LPC31_APB0_GCU_CSB_OFFSET) +#define LPC31_CGU_CSB_PBASE (LPC31_APB0_PADDR+LPC31_APB0_GCU_CSB_OFFSET) + +#define LPC31_CGU_CFG_VBASE (LPC31_APB0_VADDR+LPC31_APB0_GCU_CFG_OFFSET) +#define LPC31_CGU_CFG_PBASE (LPC31_APB0_PADDR+LPC31_APB0_GCU_CFG_OFFSET) + +/* CGU register offsets *************************************************************************/ +/* CGU clock switchbox register offsets (with respect to the CGU CSB register base) *************/ +/* Switch configuration registers (SCR) for base clocks */ + +#define LPC31_CGU_SCR_OFFSET(n) (0x000+((n)<<2)) +#define LPC31_CGU_SCR0_OFFSET 0x000 /* SYS base */ +#define LPC31_CGU_SCR1_OFFSET 0x004 /* AHB0_APB0 base */ +#define LPC31_CGU_SCR2_OFFSET 0x008 /* AHB0_APB1 base */ +#define LPC31_CGU_SCR3_OFFSET 0x00c /* AHB0_APB2 base */ +#define LPC31_CGU_SCR4_OFFSET 0x010 /* AHB0_APB3 base */ +#define LPC31_CGU_SCR5_OFFSET 0x014 /* PCM base */ +#define LPC31_CGU_SCR6_OFFSET 0x018 /* UART base */ +#define LPC31_CGU_SCR7_OFFSET 0x01c /* CLK1024FS base */ +#define LPC31_CGU_SCR8_OFFSET 0x020 /* I2SRX_BCK0 base */ +#define LPC31_CGU_SCR9_OFFSET 0x024 /* I2SRX_BCK1 base */ +#define LPC31_CGU_SCR10_OFFSET 0x028 /* SPI_CLK base */ +#define LPC31_CGU_SCR11_OFFSET 0x02c /* SYSCLK_O base */ + +/* Frequency select (FS) registers 1 for base clocks */ + +#define LPC31_CGU_FS1_OFFSET(n) (0x030+((n)<<2)) +#define LPC31_CGU_FS1_0_OFFSET 0x030 /* SYS base */ +#define LPC31_CGU_FS1_1_OFFSET 0x034 /* AHB0_APB0 base */ +#define LPC31_CGU_FS1_2_OFFSET 0x038 /* AHB0_APB1 base */ +#define LPC31_CGU_FS1_3_OFFSET 0x03c /* AHB0_APB2 base */ +#define LPC31_CGU_FS1_4_OFFSET 0x040 /* AHB0_APB3 base */ +#define LPC31_CGU_FS1_5_OFFSET 0x044 /* PCM base */ +#define LPC31_CGU_FS1_6_OFFSET 0x048 /* UART base */ +#define LPC31_CGU_FS1_7_OFFSET 0x04c /* CLK1024FS base */ +#define LPC31_CGU_FS1_8_OFFSET 0x050 /* I2SRX_BCK0 base */ +#define LPC31_CGU_FS1_9_OFFSET 0x054 /* I2SRX_BCK1 base */ +#define LPC31_CGU_FS1_10_OFFSET 0x058 /* SPI_CLK base */ +#define LPC31_CGU_FS1_11_OFFSET 0x05c /* SYSCLK_O base */ + +/* Frequency select (FS) registers 2 for base clocks */ + +#define LPC31_CGU_FS2_OFFSET(n) (0x060+((n)<<2)) +#define LPC31_CGU_FS2_0_OFFSET 0x060 /* SYS base */ +#define LPC31_CGU_FS2_1_OFFSET 0x064 /* AHB0_APB0 base */ +#define LPC31_CGU_FS2_2_OFFSET 0x068 /* AHB0_APB1 base */ +#define LPC31_CGU_FS2_3_OFFSET 0x06c /* AHB0_APB2 base */ +#define LPC31_CGU_FS2_4_OFFSET 0x070 /* AHB0_APB3 base */ +#define LPC31_CGU_FS2_5_OFFSET 0x074 /* PCM base */ +#define LPC31_CGU_FS2_6_OFFSET 0x078 /* UART base */ +#define LPC31_CGU_FS2_7_OFFSET 0x07c /* CLK1024FS base */ +#define LPC31_CGU_FS2_8_OFFSET 0x080 /* I2SRX_BCK0 base */ +#define LPC31_CGU_FS2_9_OFFSET 0x084 /* I2SRX_BCK1 base */ +#define LPC31_CGU_FS2_10_OFFSET 0x088 /* SPI_CLK base */ +#define LPC31_CGU_FS2_11_OFFSET 0x08c /* SYSCLK_O base */ + +/* Switch status registers (SSR) for base clocks */ + +#define LPC31_CGU_SSR_OFFSET(n) (0x090+((n)<<2)) +#define LPC31_CGU_SSR0_OFFSET 0x090 /* SYS base */ +#define LPC31_CGU_SSR1_OFFSET 0x094 /* AHB0_APB0 base */ +#define LPC31_CGU_SSR2_OFFSET 0x098 /* AHB0_APB1 base */ +#define LPC31_CGU_SSR3_OFFSET 0x09c /* AHB0_APB2 base */ +#define LPC31_CGU_SSR4_OFFSET 0x0a0 /* AHB0_APB3 base */ +#define LPC31_CGU_SSR5_OFFSET 0x0a4 /* PCM base */ +#define LPC31_CGU_SSR6_OFFSET 0x0a8 /* UART base */ +#define LPC31_CGU_SSR7_OFFSET 0x0ac /* CLK1024FS base */ +#define LPC31_CGU_SSR8_OFFSET 0x0b0 /* I2SRX_BCK0 base */ +#define LPC31_CGU_SSR9_OFFSET 0x0b4 /* I2SRX_BCK1 base */ +#define LPC31_CGU_SSR10_OFFSET 0x0b8 /* SPI_CLK base */ +#define LPC31_CGU_SSR11_OFFSET 0x0bc /* SYSCLK_O base */ + +/* Power control registers (PCR), spreading stage */ + +#define LPC31_CGU_PCR_OFFSET(n) (0x0c0+((n)<<2)) +#define LPC31_CGU_PCR0_OFFSET 0x0c0 /* APB0_CLK */ +#define LPC31_CGU_PCR1_OFFSET 0x0c4 /* APB1_CLK */ +#define LPC31_CGU_PCR2_OFFSET 0x0c8 /* APB2_CLK */ +#define LPC31_CGU_PCR3_OFFSET 0x0cc /* APB3_CLK */ +#define LPC31_CGU_PCR4_OFFSET 0x0d0 /* APB4_CLK */ +#define LPC31_CGU_PCR5_OFFSET 0x0d4 /* AHB_TO_INTC_CLK */ +#define LPC31_CGU_PCR6_OFFSET 0x0d8 /* AHB0_CLK */ +#define LPC31_CGU_PCR7_OFFSET 0x0dc /* EBI_CLK */ +#define LPC31_CGU_PCR8_OFFSET 0x0e0 /* DMA_PCLK */ +#define LPC31_CGU_PCR9_OFFSET 0x0e4 /* DMA_CLK_GATED */ +#define LPC31_CGU_PCR10_OFFSET 0x0e8 /* NANDFLASH_S0_CLK */ +#define LPC31_CGU_PCR11_OFFSET 0x0ec /* NANDFLASH_ECC_CLK */ +#define LPC31_CGU_PCR12_OFFSET 0x0f0 /* Reserved */ +#define LPC31_CGU_PCR13_OFFSET 0x0f4 /* NANDFLASH_NAND_CLK */ +#define LPC31_CGU_PCR14_OFFSET 0x0f8 /* NANDFLASH_PCLK */ +#define LPC31_CGU_PCR15_OFFSET 0x0fc /* CLOCK_OUT */ +#define LPC31_CGU_PCR16_OFFSET 0x100 /* ARM926_CORE_CLK */ +#define LPC31_CGU_PCR17_OFFSET 0x104 /* ARM926_BUSIF_CLK */ +#define LPC31_CGU_PCR18_OFFSET 0x108 /* ARM926_RETIME_CLK */ +#define LPC31_CGU_PCR19_OFFSET 0x10c /* SD_MMC_HCLK */ +#define LPC31_CGU_PCR20_OFFSET 0x110 /* SD_MMC_CCLK_IN */ +#define LPC31_CGU_PCR21_OFFSET 0x114 /* USB_OTG_AHB_CLK */ +#define LPC31_CGU_PCR22_OFFSET 0x118 /* ISRAM0_CLK */ +#define LPC31_CGU_PCR23_OFFSET 0x11c /* RED_CTL_RSCLK */ +#define LPC31_CGU_PCR24_OFFSET 0x120 /* ISRAM1_CLK (LPC313x only) */ +#define LPC31_CGU_PCR25_OFFSET 0x124 /* ISROM_CLK */ +#define LPC31_CGU_PCR26_OFFSET 0x128 /* MPMC_CFG_CLK */ +#define LPC31_CGU_PCR27_OFFSET 0x12c /* MPMC_CFG_CLK2 */ +#define LPC31_CGU_PCR28_OFFSET 0x130 /* MPMC_CFG_CLK3 */ +#define LPC31_CGU_PCR29_OFFSET 0x134 /* INTC_CLK */ +#define LPC31_CGU_PCR30_OFFSET 0x138 /* AHB_TO_APB0_PCLK */ +#define LPC31_CGU_PCR31_OFFSET 0x13c /* EVENT_ROUTER_PCLK */ +#define LPC31_CGU_PCR32_OFFSET 0x140 /* ADC_PCLK */ +#define LPC31_CGU_PCR33_OFFSET 0x144 /* ADC_CLK */ +#define LPC31_CGU_PCR34_OFFSET 0x148 /* WDOG_PCLK */ +#define LPC31_CGU_PCR35_OFFSET 0x14c /* IOCONF_PCLK */ +#define LPC31_CGU_PCR36_OFFSET 0x150 /* CGU_PCLK */ +#define LPC31_CGU_PCR37_OFFSET 0x154 /* SYSCREG_PCLK */ +#define LPC31_CGU_PCR38_OFFSET 0x158 /* Reserved */ +#define LPC31_CGU_PCR39_OFFSET 0x15c /* RNG_PCLK */ +#define LPC31_CGU_PCR40_OFFSET 0x160 /* AHB_TO_APB1_PCLK */ +#define LPC31_CGU_PCR41_OFFSET 0x164 /* TIMER0_PCLK */ +#define LPC31_CGU_PCR42_OFFSET 0x168 /* TIMER1_PCLK */ +#define LPC31_CGU_PCR43_OFFSET 0x16c /* TIMER2_PCLK */ +#define LPC31_CGU_PCR44_OFFSET 0x170 /* TIMER3_PCLK */ +#define LPC31_CGU_PCR45_OFFSET 0x174 /* PWM_PCLK */ +#define LPC31_CGU_PCR46_OFFSET 0x178 /* PWM_PCLK_REGS */ +#define LPC31_CGU_PCR47_OFFSET 0x17c /* PWM_CLK */ +#define LPC31_CGU_PCR48_OFFSET 0x180 /* I2C0_PCLK */ +#define LPC31_CGU_PCR49_OFFSET 0x184 /* I2C1_PCLK */ +#define LPC31_CGU_PCR50_OFFSET 0x188 /* AHB_TO_APB2_PCLK */ +#define LPC31_CGU_PCR51_OFFSET 0x18c /* PCM_PCLK */ +#define LPC31_CGU_PCR52_OFFSET 0x190 /* PCM_APB_PCLK */ +#define LPC31_CGU_PCR53_OFFSET 0x194 /* UART_APB_CLK */ +#define LPC31_CGU_PCR54_OFFSET 0x198 /* LCD_PCLK */ +#define LPC31_CGU_PCR55_OFFSET 0x19c /* LCD_CLK */ +#define LPC31_CGU_PCR56_OFFSET 0x1a0 /* SPI_PCLK */ +#define LPC31_CGU_PCR57_OFFSET 0x1a4 /* SPI_PCLK_GATED */ +#define LPC31_CGU_PCR58_OFFSET 0x1a8 /* AHB_TO_APB3_PCLK */ +#define LPC31_CGU_PCR59_OFFSET 0x1ac /* I2S_CFG_PCLK */ +#define LPC31_CGU_PCR60_OFFSET 0x1b0 /* EDGE_DET_PCLK */ +#define LPC31_CGU_PCR61_OFFSET 0x1b4 /* I2STX_FIFO_0_PCLK */ +#define LPC31_CGU_PCR62_OFFSET 0x1b8 /* I2STX_IF_0_PCLK */ +#define LPC31_CGU_PCR63_OFFSET 0x1bc /* I2STX_FIFO_1_PCLK */ +#define LPC31_CGU_PCR64_OFFSET 0x1c0 /* I2STX_IF_1_PCLK */ +#define LPC31_CGU_PCR65_OFFSET 0x1c4 /* I2SRX_FIFO_0_PCLK */ +#define LPC31_CGU_PCR66_OFFSET 0x1c8 /* I2SRX_IF_0_PCLK */ +#define LPC31_CGU_PCR67_OFFSET 0x1cc /* I2SRX_FIFO_1_PCLK */ +#define LPC31_CGU_PCR68_OFFSET 0x1d0 /* I2SRX_IF_1_PCLK */ +#define LPC31_CGU_PCR69_OFFSET 0x1d4 /* Reserved */ +#define LPC31_CGU_PCR70_OFFSET 0x1d8 /* Reserved */ +#define LPC31_CGU_PCR71_OFFSET 0x1dc /* PCM_CLK_IP */ +#define LPC31_CGU_PCR72_OFFSET 0x1e0 /* UART_U_CLK */ +#define LPC31_CGU_PCR73_OFFSET 0x1e4 /* I2S_EDGE_DETECT_CLK */ +#define LPC31_CGU_PCR74_OFFSET 0x1e8 /* I2STX_BCK0_N */ +#define LPC31_CGU_PCR75_OFFSET 0x1ec /* I2STX_WS0 */ +#define LPC31_CGU_PCR76_OFFSET 0x1f0 /* I2STX_CLK0 */ +#define LPC31_CGU_PCR77_OFFSET 0x1f4 /* I2STX_BCK1_N */ +#define LPC31_CGU_PCR78_OFFSET 0x1f8 /* I2STX_WS1 */ +#define LPC31_CGU_PCR79_OFFSET 0x1fc /* CLK_256FS */ +#define LPC31_CGU_PCR80_OFFSET 0x200 /* I2SRX_BCK0_N */ +#define LPC31_CGU_PCR81_OFFSET 0x204 /* I2SRX_WS0 */ +#define LPC31_CGU_PCR82_OFFSET 0x208 /* I2SRX_BCK1_N */ +#define LPC31_CGU_PCR83_OFFSET 0x20c /* I2SRX_WS1 */ +#define LPC31_CGU_PCR84_OFFSET 0x210 /* Reserved */ +#define LPC31_CGU_PCR85_OFFSET 0x214 /* Reserved */ +#define LPC31_CGU_PCR86_OFFSET 0x218 /* Reserved */ +#define LPC31_CGU_PCR87_OFFSET 0x21c /* I2SRX_BCK0 */ +#define LPC31_CGU_PCR88_OFFSET 0x220 /* I2SRX_BCK1 */ +#define LPC31_CGU_PCR89_OFFSET 0x224 /* SPI_CLK */ +#define LPC31_CGU_PCR90_OFFSET 0x228 /* SPI_CLK_GATED */ +#define LPC31_CGU_PCR91_OFFSET 0x22c /* SYSCLK_O */ + +/* Power status registers (PSR), spreading stage */ + +#define LPC31_CGU_PSR_OFFSET(n) (0x230+((n)<<2)) +#define LPC31_CGU_PSR0_OFFSET 0x230 /* PB0_CLK */ +#define LPC31_CGU_PSR1_OFFSET 0x234 /* PB1_CLK */ +#define LPC31_CGU_PSR2_OFFSET 0x238 /* PB2_CLK */ +#define LPC31_CGU_PSR3_OFFSET 0x23c /* PB3_CLK */ +#define LPC31_CGU_PSR4_OFFSET 0x240 /* PB4_CLK */ +#define LPC31_CGU_PSR5_OFFSET 0x244 /* HB_TO_INTC_CLK */ +#define LPC31_CGU_PSR6_OFFSET 0x248 /* HB0_CLK */ +#define LPC31_CGU_PSR7_OFFSET 0x24c /* EBI_CLK */ +#define LPC31_CGU_PSR8_OFFSET 0x250 /* DMA_PCLK */ +#define LPC31_CGU_PSR9_OFFSET 0x254 /* DMA_CLK_GATED */ +#define LPC31_CGU_PSR10_OFFSET 0x258 /* NANDFLASH_S0_CLK */ +#define LPC31_CGU_PSR11_OFFSET 0x25c /* NANDFLASH_ECC_CLK */ +#define LPC31_CGU_PSR12_OFFSET 0x260 /* Reserved */ +#define LPC31_CGU_PSR13_OFFSET 0x264 /* NANDFLASH_NAND_CLK */ +#define LPC31_CGU_PSR14_OFFSET 0x268 /* NANDFLASH_PCLK */ +#define LPC31_CGU_PSR15_OFFSET 0x26c /* CLOCK_OUT */ +#define LPC31_CGU_PSR16_OFFSET 0x270 /* RM926_CORE_CLK */ +#define LPC31_CGU_PSR17_OFFSET 0x274 /* RM926_BUSIF_CLK */ +#define LPC31_CGU_PSR18_OFFSET 0x278 /* RM926_RETIME_CLK */ +#define LPC31_CGU_PSR19_OFFSET 0x27c /* SD_MMC_HCLK */ +#define LPC31_CGU_PSR20_OFFSET 0x280 /* SD_MMC_CCLK_IN */ +#define LPC31_CGU_PSR21_OFFSET 0x284 /* USB_OTG_AHB_CLK */ +#define LPC31_CGU_PSR22_OFFSET 0x288 /* ISRAM0_CLK */ +#define LPC31_CGU_PSR23_OFFSET 0x28c /* RED_CTL_RSCLK */ +#define LPC31_CGU_PSR24_OFFSET 0x290 /* ISRAM1_CLK */ +#define LPC31_CGU_PSR25_OFFSET 0x294 /* ISROM_CLK */ +#define LPC31_CGU_PSR26_OFFSET 0x298 /* MPMC_CFG_CLK */ +#define LPC31_CGU_PSR27_OFFSET 0x29c /* MPMC_CFG_CLK2 */ +#define LPC31_CGU_PSR28_OFFSET 0x2a0 /* MPMC_CFG_CLK3 */ +#define LPC31_CGU_PSR29_OFFSET 0x2a4 /* INTC_CLK */ +#define LPC31_CGU_PSR30_OFFSET 0x2a8 /* HB_TO_APB0_PCLK */ +#define LPC31_CGU_PSR31_OFFSET 0x2ac /* EVENT_ROUTER_PCLK */ +#define LPC31_CGU_PSR32_OFFSET 0x2b0 /* DC_PCLK */ +#define LPC31_CGU_PSR33_OFFSET 0x2b4 /* DC_CLK */ +#define LPC31_CGU_PSR34_OFFSET 0x2b8 /* WDOG_PCLK */ +#define LPC31_CGU_PSR35_OFFSET 0x2bc /* IOCONF_PCLK */ +#define LPC31_CGU_PSR36_OFFSET 0x2c0 /* CGU_PCLK */ +#define LPC31_CGU_PSR37_OFFSET 0x2c4 /* SYSCREG_PCLK */ +#define LPC31_CGU_PSR38_OFFSET 0x2c8 /* Reserved */ +#define LPC31_CGU_PSR39_OFFSET 0x2cc /* RNG_PCLK */ +#define LPC31_CGU_PSR40_OFFSET 0x2d0 /* HB_TO_APB1_PCLK */ +#define LPC31_CGU_PSR41_OFFSET 0x2d4 /* TIMER0_PCLK */ +#define LPC31_CGU_PSR42_OFFSET 0x2d8 /* TIMER1_PCLK */ +#define LPC31_CGU_PSR43_OFFSET 0x2dc /* TIMER2_PCLK */ +#define LPC31_CGU_PSR44_OFFSET 0x2e0 /* TIMER3_PCLK */ +#define LPC31_CGU_PSR45_OFFSET 0x2e4 /* PWM_PCLK */ +#define LPC31_CGU_PSR46_OFFSET 0x2e8 /* PWM_PCLK_REGS */ +#define LPC31_CGU_PSR47_OFFSET 0x2ec /* PWM_CLK */ +#define LPC31_CGU_PSR48_OFFSET 0x2f0 /* I2C0_PCLK */ +#define LPC31_CGU_PSR49_OFFSET 0x2f4 /* I2C1_PCLK */ +#define LPC31_CGU_PSR50_OFFSET 0x2f8 /* HB_TO_APB2_PCLK */ +#define LPC31_CGU_PSR51_OFFSET 0x2fc /* PCM_PCLK */ +#define LPC31_CGU_PSR52_OFFSET 0x300 /* PCM_APB_PCLK */ +#define LPC31_CGU_PSR53_OFFSET 0x304 /* UART_APB_CLK */ +#define LPC31_CGU_PSR54_OFFSET 0x308 /* LCD_PCLK */ +#define LPC31_CGU_PSR55_OFFSET 0x30c /* LCD_CLK */ +#define LPC31_CGU_PSR56_OFFSET 0x310 /* SPI_PCLK */ +#define LPC31_CGU_PSR57_OFFSET 0x314 /* SPI_PCLK_GATED */ +#define LPC31_CGU_PSR58_OFFSET 0x318 /* HB_TO_APB3_PCLK */ +#define LPC31_CGU_PSR59_OFFSET 0x31c /* I2S_CFG_PCLK */ +#define LPC31_CGU_PSR60_OFFSET 0x320 /* EDGE_DET_PCLK */ +#define LPC31_CGU_PSR61_OFFSET 0x324 /* I2STX_FIFO_0_PCLK */ +#define LPC31_CGU_PSR62_OFFSET 0x328 /* I2STX_IF_0_PCLK */ +#define LPC31_CGU_PSR63_OFFSET 0x32c /* I2STX_FIFO_1_PCLK */ +#define LPC31_CGU_PSR64_OFFSET 0x330 /* I2STX_IF_1_PCLK */ +#define LPC31_CGU_PSR65_OFFSET 0x334 /* I2SRX_FIFO_0_PCLK */ +#define LPC31_CGU_PSR66_OFFSET 0x338 /* I2SRX_IF_0_PCLK */ +#define LPC31_CGU_PSR67_OFFSET 0x33c /* I2SRX_FIFO_1_PCLK */ +#define LPC31_CGU_PSR68_OFFSET 0x340 /* I2SRX_IF_1_PCLK */ +#define LPC31_CGU_PSR69_OFFSET 0x344 /* Reserved */ +#define LPC31_CGU_PSR70_OFFSET 0x348 /* Reserved */ +#define LPC31_CGU_PSR71_OFFSET 0x34c /* PCM_CLK_IP */ +#define LPC31_CGU_PSR72_OFFSET 0x350 /* UART_U_CLK */ +#define LPC31_CGU_PSR73_OFFSET 0x354 /* I2S_EDGE_DETECT_CLK */ +#define LPC31_CGU_PSR74_OFFSET 0x358 /* I2STX_BCK0_N */ +#define LPC31_CGU_PSR75_OFFSET 0x35c /* I2STX_WS0 */ +#define LPC31_CGU_PSR76_OFFSET 0x360 /* I2STX_CLK0 */ +#define LPC31_CGU_PSR77_OFFSET 0x364 /* I2STX_BCK1_N */ +#define LPC31_CGU_PSR78_OFFSET 0x368 /* I2STX_WS1 */ +#define LPC31_CGU_PSR79_OFFSET 0x36c /* CLK_256FS */ +#define LPC31_CGU_PSR80_OFFSET 0x370 /* I2SRX_BCK0_N */ +#define LPC31_CGU_PSR81_OFFSET 0x374 /* I2SRX_WS0 */ +#define LPC31_CGU_PSR82_OFFSET 0x378 /* I2SRX_BCK1_N */ +#define LPC31_CGU_PSR83_OFFSET 0x37c /* I2SRX_WS1 */ +#define LPC31_CGU_PSR84_OFFSET 0x380 /* Reserved */ +#define LPC31_CGU_PSR85_OFFSET 0x384 /* Reserved */ +#define LPC31_CGU_PSR86_OFFSET 0x388 /* Reserved */ +#define LPC31_CGU_PSR87_OFFSET 0x38c /* I2SRX_BCK0 */ +#define LPC31_CGU_PSR88_OFFSET 0x390 /* I2SRX_BCK1 */ +#define LPC31_CGU_PSR89_OFFSET 0x394 /* SPI_CLK */ +#define LPC31_CGU_PSR90_OFFSET 0x398 /* SPI_CLK_GATED */ +#define LPC31_CGU_PSR91_OFFSET 0x39c /* SYSCLK_O */ + +/* Enable select registers (ESR), spreading stage */ + +#define LPC31_CGU_ESR_OFFSET(n) (0x3a0+((n)<<2)) +#define LPC31_CGU_ESR0_OFFSET 0x3a0 /* APB0_CLK */ +#define LPC31_CGU_ESR1_OFFSET 0x3a4 /* APB1_CLK */ +#define LPC31_CGU_ESR2_OFFSET 0x3A8 /* APB2_CLK */ +#define LPC31_CGU_ESR3_OFFSET 0x3ac /* APB3_CLK */ +#define LPC31_CGU_ESR4_OFFSET 0x3b0 /* APB4_CLK */ +#define LPC31_CGU_ESR5_OFFSET 0x3b4 /* AHB_TO_INTC_CLK */ +#define LPC31_CGU_ESR6_OFFSET 0x3b8 /* AHB0_CLK */ +#define LPC31_CGU_ESR7_OFFSET 0x3bc /* EBI_CLK */ +#define LPC31_CGU_ESR8_OFFSET 0x3c0 /* DMA_PCLK */ +#define LPC31_CGU_ESR9_OFFSET 0x3c4 /* DMA_CLK_GATED */ +#define LPC31_CGU_ESR10_OFFSET 0x3c8 /* NANDFLASH_S0_CLK */ +#define LPC31_CGU_ESR11_OFFSET 0x3cc /* NANDFLASH_ECC_CLK */ +#define LPC31_CGU_ESR12_OFFSET 0x3d0 /* Reserved */ +#define LPC31_CGU_ESR13_OFFSET 0x3d4 /* NANDFLASH_NAND_CLK */ +#define LPC31_CGU_ESR14_OFFSET 0x3d8 /* NANDFLASH_PCLK */ +#define LPC31_CGU_ESR15_OFFSET 0x3dc /* CLOCK_OUT */ +#define LPC31_CGU_ESR16_OFFSET 0x3e0 /* ARM926_CORE_CLK */ +#define LPC31_CGU_ESR17_OFFSET 0x3e4 /* ARM926_BUSIF_CLK */ +#define LPC31_CGU_ESR18_OFFSET 0x3e8 /* ARM926_RETIME_CLK */ +#define LPC31_CGU_ESR19_OFFSET 0x3ec /* SD_MMC_HCLK */ +#define LPC31_CGU_ESR20_OFFSET 0x3f0 /* SD_MMC_CCLK_IN */ +#define LPC31_CGU_ESR21_OFFSET 0x3f4 /* USB_OTG_AHB_CLK */ +#define LPC31_CGU_ESR22_OFFSET 0x3f8 /* ISRAM0_CLK */ +#define LPC31_CGU_ESR23_OFFSET 0x3fc /* RED_CTL_RSCLK */ +#define LPC31_CGU_ESR24_OFFSET 0x400 /* ISRAM1_CLK */ +#define LPC31_CGU_ESR25_OFFSET 0x404 /* ISROM_CLK */ +#define LPC31_CGU_ESR26_OFFSET 0x408 /* MPMC_CFG_CLK */ +#define LPC31_CGU_ESR27_OFFSET 0x40c /* MPMC_CFG_CLK2 */ +#define LPC31_CGU_ESR28_OFFSET 0x410 /* MPMC_CFG_CLK3 */ +#define LPC31_CGU_ESR29_OFFSET 0x414 /* INTC_CLK */ +#define LPC31_CGU_ESR30_OFFSET 0x418 /* AHB_TO_APB0_PCLK */ +#define LPC31_CGU_ESR31_OFFSET 0x41c /* EVENT_ROUTER_PCLK */ +#define LPC31_CGU_ESR32_OFFSET 0x420 /* ADC_PCLK */ +#define LPC31_CGU_ESR33_OFFSET 0x424 /* ADC_CLK */ +#define LPC31_CGU_ESR34_OFFSET 0x428 /* WDOG_PCLK */ +#define LPC31_CGU_ESR35_OFFSET 0x42c /* IOCONF_PCLK */ +#define LPC31_CGU_ESR36_OFFSET 0x430 /* CGU_PCLK */ +#define LPC31_CGU_ESR37_OFFSET 0x434 /* SYSCREG_PCLK */ +#define LPC31_CGU_ESR38_OFFSET 0x438 /* Reserved */ +#define LPC31_CGU_ESR39_OFFSET 0x43c /* RNG_PCLK */ +#define LPC31_CGU_ESR40_OFFSET 0x440 /* AHB_TO_APB1_PCLK */ +#define LPC31_CGU_ESR41_OFFSET 0x444 /* TIMER0_PCLK */ +#define LPC31_CGU_ESR42_OFFSET 0x448 /* TIMER1_PCLK */ +#define LPC31_CGU_ESR43_OFFSET 0x44c /* TIMER2_PCLK */ +#define LPC31_CGU_ESR44_OFFSET 0x450 /* TIMER3_PCLK */ +#define LPC31_CGU_ESR45_OFFSET 0x454 /* PWM_PCLK */ +#define LPC31_CGU_ESR46_OFFSET 0x458 /* PWM_PCLK_REGS */ +#define LPC31_CGU_ESR47_OFFSET 0x45c /* PWM_CLK */ +#define LPC31_CGU_ESR48_OFFSET 0x460 /* I2C0_PCLK */ +#define LPC31_CGU_ESR49_OFFSET 0x464 /* I2C1_PCLK */ +#define LPC31_CGU_ESR50_OFFSET 0x468 /* AHB_TO_APB2_PCLK */ +#define LPC31_CGU_ESR51_OFFSET 0x46c /* PCM_PCLK */ +#define LPC31_CGU_ESR52_OFFSET 0x470 /* PCM_APB_PCLK */ +#define LPC31_CGU_ESR53_OFFSET 0x474 /* UART_APB_CLK */ +#define LPC31_CGU_ESR54_OFFSET 0x478 /* LCD_PCLK */ +#define LPC31_CGU_ESR55_OFFSET 0x47c /* LCD_CLK */ +#define LPC31_CGU_ESR56_OFFSET 0x480 /* SPI_PCLK */ +#define LPC31_CGU_ESR57_OFFSET 0x484 /* SPI_PCLK_GATED */ +#define LPC31_CGU_ESR58_OFFSET 0x488 /* AHB_TO_APB3_PCLK */ +#define LPC31_CGU_ESR59_OFFSET 0x48c /* I2S_CFG_PCLK */ +#define LPC31_CGU_ESR60_OFFSET 0x490 /* EDGE_DET_PCLK */ +#define LPC31_CGU_ESR61_OFFSET 0x494 /* I2STX_FIFO_0_PCLK */ +#define LPC31_CGU_ESR62_OFFSET 0x498 /* I2STX_IF_0_PCLK */ +#define LPC31_CGU_ESR63_OFFSET 0x49c /* I2STX_FIFO_1_PCLK */ +#define LPC31_CGU_ESR64_OFFSET 0x4a0 /* I2STX_IF_1_PCLK */ +#define LPC31_CGU_ESR65_OFFSET 0x4a4 /* I2SRX_FIFO_0_PCLK */ +#define LPC31_CGU_ESR66_OFFSET 0x4a8 /* I2SRX_IF_0_PCLK */ +#define LPC31_CGU_ESR67_OFFSET 0x4ac /* I2SRX_FIFO_1_PCLK */ +#define LPC31_CGU_ESR68_OFFSET 0x4b0 /* I2SRX_IF_1_PCLK */ +#define LPC31_CGU_ESR69_OFFSET 0x4b4 /* Reserved */ +#define LPC31_CGU_ESR70_OFFSET 0x4b8 /* Reserved */ +#define LPC31_CGU_ESR71_OFFSET 0x4bc /* PCM_CLK_IP */ +#define LPC31_CGU_ESR72_OFFSET 0x4c0 /* UART_U_CLK */ +#define LPC31_CGU_ESR73_OFFSET 0x4c4 /* I2S_EDGE_DETECT_CLK */ +#define LPC31_CGU_ESR74_OFFSET 0x4c8 /* R_I2STX_BCK0_N */ +#define LPC31_CGU_ESR75_OFFSET 0x4cc /* I2STX_WS0 */ +#define LPC31_CGU_ESR76_OFFSET 0x4d0 /* I2STX_CLK0 */ +#define LPC31_CGU_ESR77_OFFSET 0x4d4 /* I2STX_IF_BCK1_N */ +#define LPC31_CGU_ESR78_OFFSET 0x4d8 /* I2STX_WS1 */ +#define LPC31_CGU_ESR79_OFFSET 0x4dc /* CLK_256FS */ +#define LPC31_CGU_ESR80_OFFSET 0x4e0 /* I2SRX_BCK0_N */ +#define LPC31_CGU_ESR81_OFFSET 0x4e4 /* I2SRX_WS0 */ +#define LPC31_CGU_ESR82_OFFSET 0x4e8 /* I2SRX_BCK1_N */ +#define LPC31_CGU_ESR83_OFFSET 0x4ec /* I2SRX_WS1 */ +#define LPC31_CGU_ESR84_OFFSET 0x4f0 /* Reserved */ +#define LPC31_CGU_ESR85_OFFSET 0x4f4 /* Reserved */ +#define LPC31_CGU_ESR86_OFFSET 0x4f8 /* Reserved */ +#define LPC31_CGU_ESR87_OFFSET 0x4fc /* SPI_CLK */ +#define LPC31_CGU_ESR88_OFFSET 0x500 /* SPI_CLK_GATED */ + +/* Base control registers (BCR) for SYS base */ + +#define LPC31_CGU_BCR_OFFSET(n) (0x504+((n)<<2)) +#define LPC31_CGU_BCR0_OFFSET 0x504 /* SYS base */ +#define LPC31_CGU_BCR1_OFFSET 0x508 /* AHB0_APB0 base */ +#define LPC31_CGU_BCR2_OFFSET 0x50c /* AHB0_APB1 base */ +#define LPC31_CGU_BCR3_OFFSET 0x510 /* AHB0_APB2 base */ +#define LPC31_CGU_BCR7_OFFSET 0x514 /* CLK1024FS base */ + +/* Fractional divider configuration (FDC) registers */ + +#define LPC31_CGU_FDC_OFFSET(n) (0x518+((n)<<2)) +#define LPC31_CGU_FDC0_OFFSET 0x518 /* Fractional Divider 0 (SYS base) */ +#define LPC31_CGU_FDC1_OFFSET 0x51c /* Fractional Divider 1 (SYS base) */ +#define LPC31_CGU_FDC2_OFFSET 0x520 /* Fractional Divider 2 (SYS base) */ +#define LPC31_CGU_FDC3_OFFSET 0x524 /* Fractional Divider 3 (SYS base) */ +#define LPC31_CGU_FDC4_OFFSET 0x528 /* Fractional Divider 4 (SYS base) */ +#define LPC31_CGU_FDC5_OFFSET 0x52c /* Fractional Divider 5 (SYS base) */ +#define LPC31_CGU_FDC6_OFFSET 0x530 /* Fractional Divider 6 (SYS base) */ +#define LPC31_CGU_FDC7_OFFSET 0x534 /* Fractional Divider 7 (AHB0_APB0 base) */ +#define LPC31_CGU_FDC8_OFFSET 0x538 /* Fractional Divider 8 (AHB0_APB0 base) */ +#define LPC31_CGU_FDC9_OFFSET 0x53c /* Fractional Divider 9 (AHB0_APB1 base) */ +#define LPC31_CGU_FDC10_OFFSET 0x540 /* Fractional Divider 10 (AHB0_APB1 base) */ +#define LPC31_CGU_FDC11_OFFSET 0x544 /* Fractional Divider 11 (AHB0_APB2 base) */ +#define LPC31_CGU_FDC12_OFFSET 0x548 /* Fractional Divider 12 (AHB0_APB2 base) */ +#define LPC31_CGU_FDC13_OFFSET 0x54c /* Fractional Divider 13 (AHB0_APB2 base) */ +#define LPC31_CGU_FDC14_OFFSET 0x550 /* Fractional Divider 14 (AHB0_APB3 base) */ +#define LPC31_CGU_FDC15_OFFSET 0x554 /* Fractional Divider 15 (PCM base) */ +#define LPC31_CGU_FDC16_OFFSET 0x558 /* Fractional Divider 16 (UART base) */ +#define LPC31_CGU_FDC17_OFFSET 0x55c /* Fractional Divider 17 (CLK1024FS base) */ +#define LPC31_CGU_FDC18_OFFSET 0x560 /* Fractional Divider 18 (CLK1024FS base) */ +#define LPC31_CGU_FDC19_OFFSET 0x564 /* Fractional Divider 19 (CLK1024FS base) */ +#define LPC31_CGU_FDC20_OFFSET 0x568 /* Fractional Divider 20 (CLK1024FS base) */ +#define LPC31_CGU_FDC21_OFFSET 0x56c /* Fractional Divider 21 (CLK1024FS base) */ +#define LPC31_CGU_FDC22_OFFSET 0x570 /* Fractional Divider 22 (CLK1024FS base) */ +#define LPC31_CGU_FDC23_OFFSET 0x574 /* Fractional Divider 23 (SPI_CLK base) */ + +/* Dynamic fractional divider configuration (DYNFDC) registers (SYS base only) */ + +#define LPC31_CGU_DYNFDC_OFFSET(n) (0x578+((n)<<2)) +#define LPC31_CGU_DYNFDC0_OFFSET 0x578 /* Fractional Divider 0 (SYS base) */ +#define LPC31_CGU_DYNFDC1_OFFSET 0x57c /* Fractional Divider 1 (SYS base) */ +#define LPC31_CGU_DYNFDC2_OFFSET 0x580 /* Fractional Divider 2 (SYS base) */ +#define LPC31_CGU_DYNFDC3_OFFSET 0x584 /* Fractional Divider 3 (SYS base) */ +#define LPC31_CGU_DYNFDC4_OFFSET 0x588 /* Fractional Divider 4 (SYS base) */ +#define LPC31_CGU_DYNFDC5_OFFSET 0x58c /* Fractional Divider 5 (SYS base) */ +#define LPC31_CGU_DYNFDC6_OFFSET 0x590 /* Fractional Divider 6 (SYS base) */ + +/* Dynamic fractional divider selection (DYNSEL) registers (SYS base only) */ + +#define LPC31_CGU_DYNSEL_OFFSET(n) (0x594+((n)<<2)) +#define LPC31_CGU_DYNSEL0_OFFSET 0x594 /* Fractional Divider 0 (SYS base) */ +#define LPC31_CGU_DYNSEL1_OFFSET 0x598 /* Fractional Divider 1 (SYS base) */ +#define LPC31_CGU_DYNSEL2_OFFSET 0x59c /* Fractional Divider 2 (SYS base) */ +#define LPC31_CGU_DYNSEL3_OFFSET 0x5a0 /* Fractional Divider 3 (SYS base) */ +#define LPC31_CGU_DYNSEL4_OFFSET 0x5a4 /* Fractional Divider 4 (SYS base) */ +#define LPC31_CGU_DYNSEL5_OFFSET 0x5a8 /* Fractional Divider 5 (SYS base) */ +#define LPC31_CGU_DYNSEL6_OFFSET 0x5ac /* Fractional Divider 6 (SYS base) */ + +/* CGU configuration register offsets (with respect to the CGU CFG register base) ***************/ +/* Power and oscillator control */ + +#define LPC31_CGU_POWERMODE_OFFSET 0x000 /* Power mode register */ +#define LPC31_CGU_WDBARK_OFFSET 0x004 /* Watch dog bark register */ +#define LPC31_CGU_FFASTON_OFFSET 0x008 /* Activate fast oscillator register */ +#define LPC31_CGU_FFASTBYP_OFFSET 0x00c /* Bypass comparator register fast oscillator reset */ + +/* Reset control */ + +#define LPC31_CGU_SOFTRST_OFFSET(n) (0x010+((n)<<2)) +#define LPC31_CGU_APB0RST_OFFSET 0x010 /* Reset AHB part of AHB_TO_APB0 bridge */ +#define LPC31_CGU_AHB2APB0RST_OFFSET 0x014 /* Reset APB part of AHB_TO_APB0 bridge */ +#define LPC31_CGU_APB1RST_OFFSET 0x018 /* Reset AHB part of AHB_TO_APB1 bridge */ +#define LPC31_CGU_AHB2PB1RST_OFFSET 0x01c /* Reset APB part of AHB_TO_APB1 bridge */ +#define LPC31_CGU_APB2RST_OFFSET 0x020 /* Reset AHB part of AHB_TO_APB2 bridge */ +#define LPC31_CGU_AHB2APB2RST_OFFSET 0x024 /* Reset APB part of AHB_TO_APB2 bridge */ +#define LPC31_CGU_APB3RST_OFFSET 0x028 /* Reset AHB part of AHB_TO_APB3 bridge */ +#define LPC31_CGU_AHB2APB3RST_OFFSET 0x02c /* Reset APB part of AHB_TO_APB3 bridge */ +#define LPC31_CGU_APB4RST_OFFSET 0x030 /* Reset AHB_TO_APB4 bridge */ +#define LPC31_CGU_AHB2INTCRST_OFFSET 0x034 /* Reset AHB_TO_INTC */ +#define LPC31_CGU_AHB0RST_OFFSET 0x038 /* Reset AHB0 */ +#define LPC31_CGU_EBIRST_OFFSET 0x03c /* Reset EBI */ +#define LPC31_CGU_PCMAPBRST_OFFSET 0x040 /* Reset APB domain of PCM */ +#define LPC31_CGU_PCMCLKIPRST_OFFSET 0x044 /* Reset synchronous clk_ip domain of PCM */ +#define LPC31_CGU_PCMRSTASYNC_OFFSET 0x048 /* Reset asynchronous clk_ip domain of PCM */ +#define LPC31_CGU_TIMER0RST_OFFSET 0x04c /* Reset Timer0 */ +#define LPC31_CGU_TIMER1RST_OFFSET 0x050 /* Reset Timer1 */ +#define LPC31_CGU_TIMER2RST_OFFSET 0x054 /* Reset Timer2 */ +#define LPC31_CGU_TIMER3RST_OFFSET 0x058 /* Reset Timer3 */ +#define LPC31_CGU_ADCPRST_OFFSET 0x05c /* Reset controller of 10 bit ADC Interface */ +#define LPC31_CGU_ADCRST_OFFSET 0x060 /* Reset A/D converter of ADC Interface */ +#define LPC31_CGU_PWMRST_OFFSET 0x064 /* Reset PWM */ +#define LPC31_CGU_UARTRST_OFFSET 0x068 /* Reset UART/IrDA */ +#define LPC31_CGU_I2C0RST_OFFSET 0x06c /* Reset I2C0 */ +#define LPC31_CGU_I2C1RST_OFFSET 0x070 /* Reset I2C1 */ +#define LPC31_CGU_I2SCFGRST_OFFSET 0x074 /* Reset I2S_Config */ +#define LPC31_CGU_I2SNSOFRST_OFFSET 0x078 /* Reset NSOF counter of I2S_CONFIG */ +#define LPC31_CGU_EDGEDETRST_OFFSET 0x07c /* Reset Edge_det */ +#define LPC31_CGU_I2STXFF0RST_OFFSET 0x080 /* Reset I2STX_FIFO_0 */ +#define LPC31_CGU_I2STXIF0RST_OFFSET 0x084 /* Reset I2STX_IF_0 */ +#define LPC31_CGU_I2STXFF1RST_OFFSET 0x088 /* Reset I2STX_FIFO_1 */ +#define LPC31_CGU_I2STXIF1RST_OFFSET 0x08c /* Reset I2STX_IF_1 */ +#define LPC31_CGU_I2SRXFF0RST_OFFSET 0x090 /* Reset I2SRX_FIFO_0 */ +#define LPC31_CGU_I2SRXIF0RST_OFFSET 0x094 /* Reset I2SRX_IF_0 */ +#define LPC31_CGU_I2SRXFF1RST_OFFSET 0x098 /* Reset I2SRX_FIFO_1 */ +#define LPC31_CGU_I2SRXIF1RST_OFFSET 0x09c /* Reset I2SRX_IF_1 */ + /* 0x0a0 to 0x0b0: Reserved */ +#define LPC31_CGU_LCDRST_OFFSET 0x0b4 /* Reset LCD Interface */ +#define LPC31_CGU_SPIRSTAPB_OFFSET 0x0b8 /* Reset apb_clk domain of SPI */ +#define LPC31_CGU_SPIRSTIP_OFFSET 0x0bc /* Reset ip_clk domain of SPI */ +#define LPC31_CGU_DMARST_OFFSET 0x0c0 /* Reset DMA */ +#define LPC31_CGU_NANDECCRST_OFFSET 0x0c4 /* Reset Nandflash Controller ECC clock */ + /* 0x0c8: Reserved */ +#define LPC31_CGU_NANDCTRLRST_OFFSET 0x0cc /* Reset of Nandflash Controller */ +#define LPC31_CGU_RNGRST_OFFSET 0x0d0 /* Reset of RNG */ +#define LPC31_CGU_SDMMCRST_OFFSET 0x0d4 /* Reset MCI (on AHB clock) */ +#define LPC31_CGU_SDMMCRSTCKIN_OFFSET 0x0d8 /* Reset MCI synchronous (on IP clock) */ +#define LPC31_CGU_USBOTGAHBRST_OFFSET 0x0dc /* Reset USB_OTG */ +#define LPC31_CGU_REDCTLRST_OFFSET 0x0e0 /* Reset Redundancy Controller */ +#define LPC31_CGU_AHBMPMCHRST_OFFSET 0x0e4 /* Reset MPMC */ +#define LPC31_CGU_AHBMPMCRFRST_OFFSET 0x0e8 /* Reset refresh generator used for MPMC */ +#define LPC31_CGU_INTCRST_OFFSET 0x0ec /* Reset Interrupt Controller */ + +/* HP PLL controls */ + +#define LPC313x_CGU_HP0PLL_OFFSET 0x0f0 /* Base offset to HP0 PLL registers */ +#define LPC313x_CGU_HP1PLL_OFFSET 0x128 /* Base offset to HP1 PLL registers */ +#define CGU_HP0PLL 0 /* HP0 PLL selector */ +#define CGU_HP1PLL 1 /* HP1 PLL selector */ +#define LPC313x_CGU_HPPLL_OFFSET(n) ((n) ? LPC313x_CGU_HP1PLL_OFFSET : LPC313x_CGU_HP0PLL_OFFSET) + +#define LPC31_CGU_HPFINSEL_OFFSET 0x000 /* Register for selecting input to high HPPLL0/1 */ +#define LPC31_CGU_HPMDEC_OFFSET 0x004 /* M-divider register of HP0/1 PLL */ +#define LPC31_CGU_HPNDEC_OFFSET 0x008 /* N-divider register of HP0/1 PLL */ +#define LPC31_CGU_HPPDEC_OFFSET 0x00c /* P-divider register of HP0/1 PLL */ +#define LPC31_CGU_HPMODE_OFFSET 0x010 /* Mode register of HP0/1 PLL */ +#define LPC31_CGU_HPSTATUS_OFFSET 0x014 /* Status register of HP0/1 PLL */ +#define LPC31_CGU_HPACK_OFFSET 0x018 /* Ratio change acknowledge register of HP0/1 PLL */ +#define LPC31_CGU_HPREQ_OFFSET 0x01c /* Ratio change request register of HP0/1 PLL */ +#define LPC31_CGU_HPINSELR_OFFSET 0x020 /* Bandwidth selection register of HP0/1 PLL */ +#define LPC31_CGU_HPINSELI_OFFSET 0x024 /* Bandwidth selection register of HP0/1 PLL */ +#define LPC31_CGU_HPINSELP_OFFSET 0x028 /* Bandwidth selection register of HP0/1 PLL */ +#define LPC31_CGU_HPSELR_OFFSET 0x02c /* Bandwidth selection register of HP0/1 PLL */ +#define LPC31_CGU_HPSELI_OFFSET 0x030 /* Bandwidth selection register of HP0/1 PLL */ +#define LPC31_CGU_HPSELP_OFFSET 0x034 /* Bandwidth selection register of HP0/1 PLL */ + +/* HP0 PLL control (audio PLL) */ + +#define LPC31_CGU_HP0FINSEL_OFFSET 0x0f0 /* Register for selecting input to high HPPLL0 */ +#define LPC31_CGU_HP0MDEC_OFFSET 0x0f4 /* M-divider register of HP0 PLL */ +#define LPC31_CGU_HP0NDEC_OFFSET 0x0f8 /* N-divider register of HP0 PLL */ +#define LPC31_CGU_HP0PDEC_OFFSET 0x0fc /* P-divider register of HP0 PLL */ +#define LPC31_CGU_HP0MODE_OFFSET 0x100 /* Mode register of HP0 PLL */ +#define LPC31_CGU_HP0STATUS_OFFSET 0x104 /* Status register of HP0 PLL */ +#define LPC31_CGU_HP0ACK_OFFSET 0x108 /* Ratio change acknowledge register of HP0 PLL */ +#define LPC31_CGU_HP0REQ_OFFSET 0x10c /* Ratio change request register of HP0 PLL */ +#define LPC31_CGU_HP0INSELR_OFFSET 0x110 /* Bandwidth selection register of HP0 PLL */ +#define LPC31_CGU_HP0INSELI_OFFSET 0x114 /* Bandwidth selection register of HP0 PLL */ +#define LPC31_CGU_HP0INSELP_OFFSET 0x118 /* Bandwidth selection register of HP0 PLL */ +#define LPC31_CGU_HP0SELR_OFFSET 0x11c /* Bandwidth selection register of HP0 PLL */ +#define LPC31_CGU_HP0SELI_OFFSET 0x120 /* Bandwidth selection register of HP0 PLL */ +#define LPC31_CGU_HP0SELP_OFFSET 0x124 /* Bandwidth selection register of HP0 PLL */ + +/* HP1 PLL control (system PLL) */ + +#define LPC31_CGU_HP1FINSEL_OFFSET 0x128 /* Register for selecting input to high HP1 PLL */ +#define LPC31_CGU_HP1MDEC_OFFSET 0x12c /* M-divider register of HP1 PLL */ +#define LPC31_CGU_HP1NDEC_OFFSET 0x130 /* N-divider register of HP1 PLL */ +#define LPC31_CGU_HP1PDEC_OFFSET 0x134 /* P-divider register of HP1 PLL */ +#define LPC31_CGU_HP1MODE_OFFSET 0x138 /* Mode register of HP1 PLL */ +#define LPC31_CGU_HP1STATUS_OFFSET 0x13c /* Status register of HP1 PLL */ +#define LPC31_CGU_HP1ACK_OFFSET 0x140 /* Ratio change acknowledge register of HP1 PLL */ +#define LPC31_CGU_HP1REQ_OFFSET 0x144 /* Ratio change request register of HP1 PLL */ +#define LPC31_CGU_HP1INSELR_OFFSET 0x148 /* Bandwidth selection register of HP1 PLL */ +#define LPC31_CGU_HP1INSELI_OFFSET 0x14c /* Bandwidth selection register of HP1 PLL */ +#define LPC31_CGU_HP1INSELP_OFFSET 0x150 /* Bandwidth selection register of HP1 PLL */ +#define LPC31_CGU_HP1SELR_OFFSET 0x154 /* Bandwidth selection register of HP1 PLL */ +#define LPC31_CGU_HP1SELI_OFFSET 0x158 /* Bandwidth selection register of HP1 PLL */ +#define LPC31_CGU_HP1SELP_OFFSET 0x15c /* Bandwidth selection register of HP1 PLL */ + +/* CGU register (virtual) addresses *************************************************************/ +/* CGU clock switchbox (virtual) register addresses *********************************************/ +/* Switch configuration registers (SCR) for base clocks */ + +#define LPC31_CGU_SCR(n) (LPC31_CGU_CSB_VBASE+LPC31_CGU_SCR_OFFSET(n)) +#define LPC31_CGU_SCR0 (LPC31_CGU_CSB_VBASE+LPC31_CGU_SCR0_OFFSET) +#define LPC31_CGU_SCR1 (LPC31_CGU_CSB_VBASE+LPC31_CGU_SCR1_OFFSET) +#define LPC31_CGU_SCR2 (LPC31_CGU_CSB_VBASE+LPC31_CGU_SCR2_OFFSET) +#define LPC31_CGU_SCR3 (LPC31_CGU_CSB_VBASE+LPC31_CGU_SCR3_OFFSET) +#define LPC31_CGU_SCR4 (LPC31_CGU_CSB_VBASE+LPC31_CGU_SCR4_OFFSET) +#define LPC31_CGU_SCR5 (LPC31_CGU_CSB_VBASE+LPC31_CGU_SCR5_OFFSET) +#define LPC31_CGU_SCR6 (LPC31_CGU_CSB_VBASE+LPC31_CGU_SCR6_OFFSET) +#define LPC31_CGU_SCR7 (LPC31_CGU_CSB_VBASE+LPC31_CGU_SCR7_OFFSET) +#define LPC31_CGU_SCR8 (LPC31_CGU_CSB_VBASE+LPC31_CGU_SCR8_OFFSET) +#define LPC31_CGU_SCR9 (LPC31_CGU_CSB_VBASE+LPC31_CGU_SCR9_OFFSET) +#define LPC31_CGU_SCR10 (LPC31_CGU_CSB_VBASE+LPC31_CGU_SCR10_OFFSET) +#define LPC31_CGU_SCR11 (LPC31_CGU_CSB_VBASE+LPC31_CGU_SCR11_OFFSET) + +/* Frequency select (FS) registers 1 for base clocks */ + +#define LPC31_CGU_FS1(n) (LPC31_CGU_CSB_VBASE+LPC31_CGU_FS1_OFFSET(n)) +#define LPC31_CGU_FS1_0 (LPC31_CGU_CSB_VBASE+LPC31_CGU_FS1_0_OFFSET) +#define LPC31_CGU_FS1_1 (LPC31_CGU_CSB_VBASE+LPC31_CGU_FS1_1_OFFSET) +#define LPC31_CGU_FS1_2 (LPC31_CGU_CSB_VBASE+LPC31_CGU_FS1_2_OFFSET) +#define LPC31_CGU_FS1_3 (LPC31_CGU_CSB_VBASE+LPC31_CGU_FS1_3_OFFSET) +#define LPC31_CGU_FS1_4 (LPC31_CGU_CSB_VBASE+LPC31_CGU_FS1_4_OFFSET) +#define LPC31_CGU_FS1_5 (LPC31_CGU_CSB_VBASE+LPC31_CGU_FS1_5_OFFSET) +#define LPC31_CGU_FS1_6 (LPC31_CGU_CSB_VBASE+LPC31_CGU_FS1_6_OFFSET) +#define LPC31_CGU_FS1_7 (LPC31_CGU_CSB_VBASE+LPC31_CGU_FS1_7_OFFSET) +#define LPC31_CGU_FS1_8 (LPC31_CGU_CSB_VBASE+LPC31_CGU_FS1_8_OFFSET) +#define LPC31_CGU_FS1_9 (LPC31_CGU_CSB_VBASE+LPC31_CGU_FS1_9_OFFSET) +#define LPC31_CGU_FS1_10 (LPC31_CGU_CSB_VBASE+LPC31_CGU_FS1_10_OFFSET) +#define LPC31_CGU_FS1_11 (LPC31_CGU_CSB_VBASE+LPC31_CGU_FS1_11_OFFSET) + +/* Frequency select (FS) registers 2 for base clocks */ + +#define LPC31_CGU_FS2(n) (LPC31_CGU_CSB_VBASE+LPC31_CGU_FS2_OFFSET(n)) +#define LPC31_CGU_FS2_0 (LPC31_CGU_CSB_VBASE+LPC31_CGU_FS2_0_OFFSET) +#define LPC31_CGU_FS2_1 (LPC31_CGU_CSB_VBASE+LPC31_CGU_FS2_1_OFFSET) +#define LPC31_CGU_FS2_2 (LPC31_CGU_CSB_VBASE+LPC31_CGU_FS2_2_OFFSET) +#define LPC31_CGU_FS2_3 (LPC31_CGU_CSB_VBASE+LPC31_CGU_FS2_3_OFFSET) +#define LPC31_CGU_FS2_4 (LPC31_CGU_CSB_VBASE+LPC31_CGU_FS2_4_OFFSET) +#define LPC31_CGU_FS2_5 (LPC31_CGU_CSB_VBASE+LPC31_CGU_FS2_5_OFFSET) +#define LPC31_CGU_FS2_6 (LPC31_CGU_CSB_VBASE+LPC31_CGU_FS2_6_OFFSET) +#define LPC31_CGU_FS2_7 (LPC31_CGU_CSB_VBASE+LPC31_CGU_FS2_7_OFFSET) +#define LPC31_CGU_FS2_8 (LPC31_CGU_CSB_VBASE+LPC31_CGU_FS2_8_OFFSET) +#define LPC31_CGU_FS2_9 (LPC31_CGU_CSB_VBASE+LPC31_CGU_FS2_9_OFFSET) +#define LPC31_CGU_FS2_10 (LPC31_CGU_CSB_VBASE+LPC31_CGU_FS2_10_OFFSET) +#define LPC31_CGU_FS2_11 (LPC31_CGU_CSB_VBASE+LPC31_CGU_FS2_11_OFFSET) + +/* Switch status registers (SSR) for base clocks */ + +#define LPC31_CGU_SSR(n) (LPC31_CGU_CSB_VBASE+LPC31_CGU_SSR_OFFSET(n)) +#define LPC31_CGU_SSR0 (LPC31_CGU_CSB_VBASE+LPC31_CGU_SSR0_OFFSET) +#define LPC31_CGU_SSR1 (LPC31_CGU_CSB_VBASE+LPC31_CGU_SSR1_OFFSET) +#define LPC31_CGU_SSR2 (LPC31_CGU_CSB_VBASE+LPC31_CGU_SSR2_OFFSET) +#define LPC31_CGU_SSR3 (LPC31_CGU_CSB_VBASE+LPC31_CGU_SSR3_OFFSET) +#define LPC31_CGU_SSR4 (LPC31_CGU_CSB_VBASE+LPC31_CGU_SSR4_OFFSET) +#define LPC31_CGU_SSR5 (LPC31_CGU_CSB_VBASE+LPC31_CGU_SSR5_OFFSET) +#define LPC31_CGU_SSR6 (LPC31_CGU_CSB_VBASE+LPC31_CGU_SSR6_OFFSET) +#define LPC31_CGU_SSR7 (LPC31_CGU_CSB_VBASE+LPC31_CGU_SSR7_OFFSET) +#define LPC31_CGU_SSR8 (LPC31_CGU_CSB_VBASE+LPC31_CGU_SSR8_OFFSET) +#define LPC31_CGU_SSR9 (LPC31_CGU_CSB_VBASE+LPC31_CGU_SSR9_OFFSET) +#define LPC31_CGU_SSR10 (LPC31_CGU_CSB_VBASE+LPC31_CGU_SSR10_OFFSET) +#define LPC31_CGU_SSR11 (LPC31_CGU_CSB_VBASE+LPC31_CGU_SSR11_OFFSET) + +/* Power control registers (PCR), spreading stage */ + +#define LPC31_CGU_PCR(n) (LPC31_CGU_CSB_VBASE+LPC31_CGU_PCR_OFFSET(n)) +#define LPC31_CGU_PCR0 (LPC31_CGU_CSB_VBASE+LPC31_CGU_PCR0_OFFSET) +#define LPC31_CGU_PCR1 (LPC31_CGU_CSB_VBASE+LPC31_CGU_PCR1_OFFSET) +#define LPC31_CGU_PCR2 (LPC31_CGU_CSB_VBASE+LPC31_CGU_PCR2_OFFSET) +#define LPC31_CGU_PCR3 (LPC31_CGU_CSB_VBASE+LPC31_CGU_PCR3_OFFSET) +#define LPC31_CGU_PCR4 (LPC31_CGU_CSB_VBASE+LPC31_CGU_PCR4_OFFSET) +#define LPC31_CGU_PCR5 (LPC31_CGU_CSB_VBASE+LPC31_CGU_PCR5_OFFSET) +#define LPC31_CGU_PCR6 (LPC31_CGU_CSB_VBASE+LPC31_CGU_PCR6_OFFSET) +#define LPC31_CGU_PCR7 (LPC31_CGU_CSB_VBASE+LPC31_CGU_PCR7_OFFSET) +#define LPC31_CGU_PCR8 (LPC31_CGU_CSB_VBASE+LPC31_CGU_PCR8_OFFSET) +#define LPC31_CGU_PCR9 (LPC31_CGU_CSB_VBASE+LPC31_CGU_PCR9_OFFSET) +#define LPC31_CGU_PCR10 (LPC31_CGU_CSB_VBASE+LPC31_CGU_PCR10_OFFSET) +#define LPC31_CGU_PCR11 (LPC31_CGU_CSB_VBASE+LPC31_CGU_PCR11_OFFSET) +#define LPC31_CGU_PCR12 (LPC31_CGU_CSB_VBASE+LPC31_CGU_PCR12_OFFSET) +#define LPC31_CGU_PCR13 (LPC31_CGU_CSB_VBASE+LPC31_CGU_PCR13_OFFSET) +#define LPC31_CGU_PCR14 (LPC31_CGU_CSB_VBASE+LPC31_CGU_PCR14_OFFSET) +#define LPC31_CGU_PCR15 (LPC31_CGU_CSB_VBASE+LPC31_CGU_PCR15_OFFSET) +#define LPC31_CGU_PCR16 (LPC31_CGU_CSB_VBASE+LPC31_CGU_PCR16_OFFSET) +#define LPC31_CGU_PCR17 (LPC31_CGU_CSB_VBASE+LPC31_CGU_PCR17_OFFSET) +#define LPC31_CGU_PCR18 (LPC31_CGU_CSB_VBASE+LPC31_CGU_PCR18_OFFSET) +#define LPC31_CGU_PCR19 (LPC31_CGU_CSB_VBASE+LPC31_CGU_PCR19_OFFSET) +#define LPC31_CGU_PCR20 (LPC31_CGU_CSB_VBASE+LPC31_CGU_PCR20_OFFSET) +#define LPC31_CGU_PCR21 (LPC31_CGU_CSB_VBASE+LPC31_CGU_PCR21_OFFSET) +#define LPC31_CGU_PCR22 (LPC31_CGU_CSB_VBASE+LPC31_CGU_PCR22_OFFSET) +#define LPC31_CGU_PCR23 (LPC31_CGU_CSB_VBASE+LPC31_CGU_PCR23_OFFSET) +#define LPC31_CGU_PCR24 (LPC31_CGU_CSB_VBASE+LPC31_CGU_PCR24_OFFSET) +#define LPC31_CGU_PCR25 (LPC31_CGU_CSB_VBASE+LPC31_CGU_PCR25_OFFSET) +#define LPC31_CGU_PCR26 (LPC31_CGU_CSB_VBASE+LPC31_CGU_PCR26_OFFSET) +#define LPC31_CGU_PCR27 (LPC31_CGU_CSB_VBASE+LPC31_CGU_PCR27_OFFSET) +#define LPC31_CGU_PCR28 (LPC31_CGU_CSB_VBASE+LPC31_CGU_PCR28_OFFSET) +#define LPC31_CGU_PCR29 (LPC31_CGU_CSB_VBASE+LPC31_CGU_PCR29_OFFSET) +#define LPC31_CGU_PCR30 (LPC31_CGU_CSB_VBASE+LPC31_CGU_PCR30_OFFSET) +#define LPC31_CGU_PCR31 (LPC31_CGU_CSB_VBASE+LPC31_CGU_PCR31_OFFSET) +#define LPC31_CGU_PCR32 (LPC31_CGU_CSB_VBASE+LPC31_CGU_PCR32_OFFSET) +#define LPC31_CGU_PCR33 (LPC31_CGU_CSB_VBASE+LPC31_CGU_PCR33_OFFSET) +#define LPC31_CGU_PCR34 (LPC31_CGU_CSB_VBASE+LPC31_CGU_PCR34_OFFSET) +#define LPC31_CGU_PCR35 (LPC31_CGU_CSB_VBASE+LPC31_CGU_PCR35_OFFSET) +#define LPC31_CGU_PCR36 (LPC31_CGU_CSB_VBASE+LPC31_CGU_PCR36_OFFSET) +#define LPC31_CGU_PCR37 (LPC31_CGU_CSB_VBASE+LPC31_CGU_PCR37_OFFSET) +#define LPC31_CGU_PCR38 (LPC31_CGU_CSB_VBASE+LPC31_CGU_PCR38_OFFSET) +#define LPC31_CGU_PCR39 (LPC31_CGU_CSB_VBASE+LPC31_CGU_PCR39_OFFSET) +#define LPC31_CGU_PCR40 (LPC31_CGU_CSB_VBASE+LPC31_CGU_PCR40_OFFSET) +#define LPC31_CGU_PCR41 (LPC31_CGU_CSB_VBASE+LPC31_CGU_PCR41_OFFSET) +#define LPC31_CGU_PCR42 (LPC31_CGU_CSB_VBASE+LPC31_CGU_PCR42_OFFSET) +#define LPC31_CGU_PCR43 (LPC31_CGU_CSB_VBASE+LPC31_CGU_PCR43_OFFSET) +#define LPC31_CGU_PCR44 (LPC31_CGU_CSB_VBASE+LPC31_CGU_PCR44_OFFSET) +#define LPC31_CGU_PCR45 (LPC31_CGU_CSB_VBASE+LPC31_CGU_PCR45_OFFSET) +#define LPC31_CGU_PCR46 (LPC31_CGU_CSB_VBASE+LPC31_CGU_PCR46_OFFSET) +#define LPC31_CGU_PCR47 (LPC31_CGU_CSB_VBASE+LPC31_CGU_PCR47_OFFSET) +#define LPC31_CGU_PCR48 (LPC31_CGU_CSB_VBASE+LPC31_CGU_PCR48_OFFSET) +#define LPC31_CGU_PCR49 (LPC31_CGU_CSB_VBASE+LPC31_CGU_PCR49_OFFSET) +#define LPC31_CGU_PCR50 (LPC31_CGU_CSB_VBASE+LPC31_CGU_PCR50_OFFSET) +#define LPC31_CGU_PCR51 (LPC31_CGU_CSB_VBASE+LPC31_CGU_PCR51_OFFSET) +#define LPC31_CGU_PCR52 (LPC31_CGU_CSB_VBASE+LPC31_CGU_PCR52_OFFSET) +#define LPC31_CGU_PCR53 (LPC31_CGU_CSB_VBASE+LPC31_CGU_PCR53_OFFSET) +#define LPC31_CGU_PCR54 (LPC31_CGU_CSB_VBASE+LPC31_CGU_PCR54_OFFSET) +#define LPC31_CGU_PCR55 (LPC31_CGU_CSB_VBASE+LPC31_CGU_PCR55_OFFSET) +#define LPC31_CGU_PCR56 (LPC31_CGU_CSB_VBASE+LPC31_CGU_PCR56_OFFSET) +#define LPC31_CGU_PCR57 (LPC31_CGU_CSB_VBASE+LPC31_CGU_PCR57_OFFSET) +#define LPC31_CGU_PCR58 (LPC31_CGU_CSB_VBASE+LPC31_CGU_PCR58_OFFSET) +#define LPC31_CGU_PCR59 (LPC31_CGU_CSB_VBASE+LPC31_CGU_PCR59_OFFSET) +#define LPC31_CGU_PCR60 (LPC31_CGU_CSB_VBASE+LPC31_CGU_PCR60_OFFSET) +#define LPC31_CGU_PCR61 (LPC31_CGU_CSB_VBASE+LPC31_CGU_PCR61_OFFSET) +#define LPC31_CGU_PCR62 (LPC31_CGU_CSB_VBASE+LPC31_CGU_PCR62_OFFSET) +#define LPC31_CGU_PCR63 (LPC31_CGU_CSB_VBASE+LPC31_CGU_PCR63_OFFSET) +#define LPC31_CGU_PCR64 (LPC31_CGU_CSB_VBASE+LPC31_CGU_PCR64_OFFSET) +#define LPC31_CGU_PCR65 (LPC31_CGU_CSB_VBASE+LPC31_CGU_PCR65_OFFSET) +#define LPC31_CGU_PCR66 (LPC31_CGU_CSB_VBASE+LPC31_CGU_PCR66_OFFSET) +#define LPC31_CGU_PCR67 (LPC31_CGU_CSB_VBASE+LPC31_CGU_PCR67_OFFSET) +#define LPC31_CGU_PCR68 (LPC31_CGU_CSB_VBASE+LPC31_CGU_PCR68_OFFSET) +#define LPC31_CGU_PCR69 (LPC31_CGU_CSB_VBASE+LPC31_CGU_PCR69_OFFSET) +#define LPC31_CGU_PCR70 (LPC31_CGU_CSB_VBASE+LPC31_CGU_PCR70_OFFSET) +#define LPC31_CGU_PCR71 (LPC31_CGU_CSB_VBASE+LPC31_CGU_PCR71_OFFSET) +#define LPC31_CGU_PCR72 (LPC31_CGU_CSB_VBASE+LPC31_CGU_PCR72_OFFSET) +#define LPC31_CGU_PCR73 (LPC31_CGU_CSB_VBASE+LPC31_CGU_PCR73_OFFSET) +#define LPC31_CGU_PCR74 (LPC31_CGU_CSB_VBASE+LPC31_CGU_PCR74_OFFSET) +#define LPC31_CGU_PCR75 (LPC31_CGU_CSB_VBASE+LPC31_CGU_PCR75_OFFSET) +#define LPC31_CGU_PCR76 (LPC31_CGU_CSB_VBASE+LPC31_CGU_PCR76_OFFSET) +#define LPC31_CGU_PCR77 (LPC31_CGU_CSB_VBASE+LPC31_CGU_PCR77_OFFSET) +#define LPC31_CGU_PCR78 (LPC31_CGU_CSB_VBASE+LPC31_CGU_PCR78_OFFSET) +#define LPC31_CGU_PCR79 (LPC31_CGU_CSB_VBASE+LPC31_CGU_PCR79_OFFSET) +#define LPC31_CGU_PCR80 (LPC31_CGU_CSB_VBASE+LPC31_CGU_PCR80_OFFSET) +#define LPC31_CGU_PCR81 (LPC31_CGU_CSB_VBASE+LPC31_CGU_PCR81_OFFSET) +#define LPC31_CGU_PCR82 (LPC31_CGU_CSB_VBASE+LPC31_CGU_PCR82_OFFSET) +#define LPC31_CGU_PCR83 (LPC31_CGU_CSB_VBASE+LPC31_CGU_PCR83_OFFSET) +#define LPC31_CGU_PCR84 (LPC31_CGU_CSB_VBASE+LPC31_CGU_PCR84_OFFSET) +#define LPC31_CGU_PCR85 (LPC31_CGU_CSB_VBASE+LPC31_CGU_PCR85_OFFSET) +#define LPC31_CGU_PCR86 (LPC31_CGU_CSB_VBASE+LPC31_CGU_PCR86_OFFSET) +#define LPC31_CGU_PCR87 (LPC31_CGU_CSB_VBASE+LPC31_CGU_PCR87_OFFSET) +#define LPC31_CGU_PCR88 (LPC31_CGU_CSB_VBASE+LPC31_CGU_PCR88_OFFSET) +#define LPC31_CGU_PCR89 (LPC31_CGU_CSB_VBASE+LPC31_CGU_PCR89_OFFSET) +#define LPC31_CGU_PCR90 (LPC31_CGU_CSB_VBASE+LPC31_CGU_PCR90_OFFSET) +#define LPC31_CGU_PCR91 (LPC31_CGU_CSB_VBASE+LPC31_CGU_PCR91_OFFSET) + +/* Power status registers (PSR), spreading stage */ + +#define LPC31_CGU_PSR(n) (LPC31_CGU_CSB_VBASE+LPC31_CGU_PSR_OFFSET(n)) +#define LPC31_CGU_PSR0 (LPC31_CGU_CSB_VBASE+LPC31_CGU_PSR0_OFFSET) +#define LPC31_CGU_PSR1 (LPC31_CGU_CSB_VBASE+LPC31_CGU_PSR1_OFFSET) +#define LPC31_CGU_PSR2 (LPC31_CGU_CSB_VBASE+LPC31_CGU_PSR2_OFFSET) +#define LPC31_CGU_PSR3 (LPC31_CGU_CSB_VBASE+LPC31_CGU_PSR3_OFFSET) +#define LPC31_CGU_PSR4 (LPC31_CGU_CSB_VBASE+LPC31_CGU_PSR4_OFFSET) +#define LPC31_CGU_PSR5 (LPC31_CGU_CSB_VBASE+LPC31_CGU_PSR5_OFFSET) +#define LPC31_CGU_PSR6 (LPC31_CGU_CSB_VBASE+LPC31_CGU_PSR6_OFFSET) +#define LPC31_CGU_PSR7 (LPC31_CGU_CSB_VBASE+LPC31_CGU_PSR7_OFFSET) +#define LPC31_CGU_PSR8 (LPC31_CGU_CSB_VBASE+LPC31_CGU_PSR8_OFFSET) +#define LPC31_CGU_PSR9 (LPC31_CGU_CSB_VBASE+LPC31_CGU_PSR9_OFFSET) +#define LPC31_CGU_PSR10 (LPC31_CGU_CSB_VBASE+LPC31_CGU_PSR10_OFFSET) +#define LPC31_CGU_PSR11 (LPC31_CGU_CSB_VBASE+LPC31_CGU_PSR11_OFFSET) +#define LPC31_CGU_PSR12 (LPC31_CGU_CSB_VBASE+LPC31_CGU_PSR12_OFFSET) +#define LPC31_CGU_PSR13 (LPC31_CGU_CSB_VBASE+LPC31_CGU_PSR13_OFFSET) +#define LPC31_CGU_PSR14 (LPC31_CGU_CSB_VBASE+LPC31_CGU_PSR14_OFFSET) +#define LPC31_CGU_PSR15 (LPC31_CGU_CSB_VBASE+LPC31_CGU_PSR15_OFFSET) +#define LPC31_CGU_PSR16 (LPC31_CGU_CSB_VBASE+LPC31_CGU_PSR16_OFFSET) +#define LPC31_CGU_PSR17 (LPC31_CGU_CSB_VBASE+LPC31_CGU_PSR17_OFFSET) +#define LPC31_CGU_PSR18 (LPC31_CGU_CSB_VBASE+LPC31_CGU_PSR18_OFFSET) +#define LPC31_CGU_PSR19 (LPC31_CGU_CSB_VBASE+LPC31_CGU_PSR19_OFFSET) +#define LPC31_CGU_PSR20 (LPC31_CGU_CSB_VBASE+LPC31_CGU_PSR20_OFFSET) +#define LPC31_CGU_PSR21 (LPC31_CGU_CSB_VBASE+LPC31_CGU_PSR21_OFFSET) +#define LPC31_CGU_PSR22 (LPC31_CGU_CSB_VBASE+LPC31_CGU_PSR22_OFFSET) +#define LPC31_CGU_PSR23 (LPC31_CGU_CSB_VBASE+LPC31_CGU_PSR23_OFFSET) +#define LPC31_CGU_PSR24 (LPC31_CGU_CSB_VBASE+LPC31_CGU_PSR24_OFFSET) +#define LPC31_CGU_PSR25 (LPC31_CGU_CSB_VBASE+LPC31_CGU_PSR25_OFFSET) +#define LPC31_CGU_PSR26 (LPC31_CGU_CSB_VBASE+LPC31_CGU_PSR26_OFFSET) +#define LPC31_CGU_PSR27 (LPC31_CGU_CSB_VBASE+LPC31_CGU_PSR27_OFFSET) +#define LPC31_CGU_PSR28 (LPC31_CGU_CSB_VBASE+LPC31_CGU_PSR28_OFFSET) +#define LPC31_CGU_PSR29 (LPC31_CGU_CSB_VBASE+LPC31_CGU_PSR29_OFFSET) +#define LPC31_CGU_PSR30 (LPC31_CGU_CSB_VBASE+LPC31_CGU_PSR30_OFFSET) +#define LPC31_CGU_PSR31 (LPC31_CGU_CSB_VBASE+LPC31_CGU_PSR31_OFFSET) +#define LPC31_CGU_PSR32 (LPC31_CGU_CSB_VBASE+LPC31_CGU_PSR32_OFFSET) +#define LPC31_CGU_PSR33 (LPC31_CGU_CSB_VBASE+LPC31_CGU_PSR33_OFFSET) +#define LPC31_CGU_PSR34 (LPC31_CGU_CSB_VBASE+LPC31_CGU_PSR34_OFFSET) +#define LPC31_CGU_PSR35 (LPC31_CGU_CSB_VBASE+LPC31_CGU_PSR35_OFFSET) +#define LPC31_CGU_PSR36 (LPC31_CGU_CSB_VBASE+LPC31_CGU_PSR36_OFFSET) +#define LPC31_CGU_PSR37 (LPC31_CGU_CSB_VBASE+LPC31_CGU_PSR37_OFFSET) +#define LPC31_CGU_PSR38 (LPC31_CGU_CSB_VBASE+LPC31_CGU_PSR38_OFFSET) +#define LPC31_CGU_PSR39 (LPC31_CGU_CSB_VBASE+LPC31_CGU_PSR39_OFFSET) +#define LPC31_CGU_PSR40 (LPC31_CGU_CSB_VBASE+LPC31_CGU_PSR40_OFFSET) +#define LPC31_CGU_PSR41 (LPC31_CGU_CSB_VBASE+LPC31_CGU_PSR41_OFFSET) +#define LPC31_CGU_PSR42 (LPC31_CGU_CSB_VBASE+LPC31_CGU_PSR42_OFFSET) +#define LPC31_CGU_PSR43 (LPC31_CGU_CSB_VBASE+LPC31_CGU_PSR43_OFFSET) +#define LPC31_CGU_PSR44 (LPC31_CGU_CSB_VBASE+LPC31_CGU_PSR44_OFFSET) +#define LPC31_CGU_PSR45 (LPC31_CGU_CSB_VBASE+LPC31_CGU_PSR45_OFFSET) +#define LPC31_CGU_PSR46 (LPC31_CGU_CSB_VBASE+LPC31_CGU_PSR46_OFFSET) +#define LPC31_CGU_PSR47 (LPC31_CGU_CSB_VBASE+LPC31_CGU_PSR47_OFFSET) +#define LPC31_CGU_PSR48 (LPC31_CGU_CSB_VBASE+LPC31_CGU_PSR48_OFFSET) +#define LPC31_CGU_PSR49 (LPC31_CGU_CSB_VBASE+LPC31_CGU_PSR49_OFFSET) +#define LPC31_CGU_PSR50 (LPC31_CGU_CSB_VBASE+LPC31_CGU_PSR50_OFFSET) +#define LPC31_CGU_PSR51 (LPC31_CGU_CSB_VBASE+LPC31_CGU_PSR51_OFFSET) +#define LPC31_CGU_PSR52 (LPC31_CGU_CSB_VBASE+LPC31_CGU_PSR52_OFFSET) +#define LPC31_CGU_PSR53 (LPC31_CGU_CSB_VBASE+LPC31_CGU_PSR53_OFFSET) +#define LPC31_CGU_PSR54 (LPC31_CGU_CSB_VBASE+LPC31_CGU_PSR54_OFFSET) +#define LPC31_CGU_PSR55 (LPC31_CGU_CSB_VBASE+LPC31_CGU_PSR55_OFFSET) +#define LPC31_CGU_PSR56 (LPC31_CGU_CSB_VBASE+LPC31_CGU_PSR56_OFFSET) +#define LPC31_CGU_PSR57 (LPC31_CGU_CSB_VBASE+LPC31_CGU_PSR57_OFFSET) +#define LPC31_CGU_PSR58 (LPC31_CGU_CSB_VBASE+LPC31_CGU_PSR58_OFFSET) +#define LPC31_CGU_PSR59 (LPC31_CGU_CSB_VBASE+LPC31_CGU_PSR59_OFFSET) +#define LPC31_CGU_PSR60 (LPC31_CGU_CSB_VBASE+LPC31_CGU_PSR60_OFFSET) +#define LPC31_CGU_PSR61 (LPC31_CGU_CSB_VBASE+LPC31_CGU_PSR61_OFFSET) +#define LPC31_CGU_PSR62 (LPC31_CGU_CSB_VBASE+LPC31_CGU_PSR62_OFFSET) +#define LPC31_CGU_PSR63 (LPC31_CGU_CSB_VBASE+LPC31_CGU_PSR63_OFFSET) +#define LPC31_CGU_PSR64 (LPC31_CGU_CSB_VBASE+LPC31_CGU_PSR64_OFFSET) +#define LPC31_CGU_PSR65 (LPC31_CGU_CSB_VBASE+LPC31_CGU_PSR65_OFFSET) +#define LPC31_CGU_PSR66 (LPC31_CGU_CSB_VBASE+LPC31_CGU_PSR66_OFFSET) +#define LPC31_CGU_PSR67 (LPC31_CGU_CSB_VBASE+LPC31_CGU_PSR67_OFFSET) +#define LPC31_CGU_PSR68 (LPC31_CGU_CSB_VBASE+LPC31_CGU_PSR68_OFFSET) +#define LPC31_CGU_PSR69 (LPC31_CGU_CSB_VBASE+LPC31_CGU_PSR69_OFFSET) +#define LPC31_CGU_PSR70 (LPC31_CGU_CSB_VBASE+LPC31_CGU_PSR70_OFFSET) +#define LPC31_CGU_PSR71 (LPC31_CGU_CSB_VBASE+LPC31_CGU_PSR71_OFFSET) +#define LPC31_CGU_PSR72 (LPC31_CGU_CSB_VBASE+LPC31_CGU_PSR72_OFFSET) +#define LPC31_CGU_PSR73 (LPC31_CGU_CSB_VBASE+LPC31_CGU_PSR73_OFFSET) +#define LPC31_CGU_PSR74 (LPC31_CGU_CSB_VBASE+LPC31_CGU_PSR74_OFFSET) +#define LPC31_CGU_PSR75 (LPC31_CGU_CSB_VBASE+LPC31_CGU_PSR75_OFFSET) +#define LPC31_CGU_PSR76 (LPC31_CGU_CSB_VBASE+LPC31_CGU_PSR76_OFFSET) +#define LPC31_CGU_PSR77 (LPC31_CGU_CSB_VBASE+LPC31_CGU_PSR77_OFFSET) +#define LPC31_CGU_PSR78 (LPC31_CGU_CSB_VBASE+LPC31_CGU_PSR78_OFFSET) +#define LPC31_CGU_PSR79 (LPC31_CGU_CSB_VBASE+LPC31_CGU_PSR79_OFFSET) +#define LPC31_CGU_PSR80 (LPC31_CGU_CSB_VBASE+LPC31_CGU_PSR80_OFFSET) +#define LPC31_CGU_PSR81 (LPC31_CGU_CSB_VBASE+LPC31_CGU_PSR81_OFFSET) +#define LPC31_CGU_PSR82 (LPC31_CGU_CSB_VBASE+LPC31_CGU_PSR82_OFFSET) +#define LPC31_CGU_PSR83 (LPC31_CGU_CSB_VBASE+LPC31_CGU_PSR83_OFFSET) +#define LPC31_CGU_PSR84 (LPC31_CGU_CSB_VBASE+LPC31_CGU_PSR84_OFFSET) +#define LPC31_CGU_PSR85 (LPC31_CGU_CSB_VBASE+LPC31_CGU_PSR85_OFFSET) +#define LPC31_CGU_PSR86 (LPC31_CGU_CSB_VBASE+LPC31_CGU_PSR86_OFFSET) +#define LPC31_CGU_PSR87 (LPC31_CGU_CSB_VBASE+LPC31_CGU_PSR87_OFFSET) +#define LPC31_CGU_PSR88 (LPC31_CGU_CSB_VBASE+LPC31_CGU_PSR88_OFFSET) +#define LPC31_CGU_PSR89 (LPC31_CGU_CSB_VBASE+LPC31_CGU_PSR89_OFFSET) +#define LPC31_CGU_PSR90 (LPC31_CGU_CSB_VBASE+LPC31_CGU_PSR90_OFFSET) +#define LPC31_CGU_PSR91 (LPC31_CGU_CSB_VBASE+LPC31_CGU_PSR91_OFFSET) + +/* Enable select registers (ESR), spreading stage */ + +#define LPC31_CGU_ESR(n) (LPC31_CGU_CSB_VBASE+LPC31_CGU_ESR_OFFSET(n)) +#define LPC31_CGU_ESR0 (LPC31_CGU_CSB_VBASE+LPC31_CGU_ESR0_OFFSET) +#define LPC31_CGU_ESR1 (LPC31_CGU_CSB_VBASE+LPC31_CGU_ESR1_OFFSET) +#define LPC31_CGU_ESR2 (LPC31_CGU_CSB_VBASE+LPC31_CGU_ESR2_OFFSET) +#define LPC31_CGU_ESR3 (LPC31_CGU_CSB_VBASE+LPC31_CGU_ESR3_OFFSET) +#define LPC31_CGU_ESR4 (LPC31_CGU_CSB_VBASE+LPC31_CGU_ESR4_OFFSET) +#define LPC31_CGU_ESR5 (LPC31_CGU_CSB_VBASE+LPC31_CGU_ESR5_OFFSET) +#define LPC31_CGU_ESR6 (LPC31_CGU_CSB_VBASE+LPC31_CGU_ESR6_OFFSET) +#define LPC31_CGU_ESR7 (LPC31_CGU_CSB_VBASE+LPC31_CGU_ESR7_OFFSET) +#define LPC31_CGU_ESR8 (LPC31_CGU_CSB_VBASE+LPC31_CGU_ESR8_OFFSET) +#define LPC31_CGU_ESR9 (LPC31_CGU_CSB_VBASE+LPC31_CGU_ESR9_OFFSET) +#define LPC31_CGU_ESR10 (LPC31_CGU_CSB_VBASE+LPC31_CGU_ESR10_OFFSET) +#define LPC31_CGU_ESR11 (LPC31_CGU_CSB_VBASE+LPC31_CGU_ESR11_OFFSET) +#define LPC31_CGU_ESR12 (LPC31_CGU_CSB_VBASE+LPC31_CGU_ESR12_OFFSET) +#define LPC31_CGU_ESR13 (LPC31_CGU_CSB_VBASE+LPC31_CGU_ESR13_OFFSET) +#define LPC31_CGU_ESR14 (LPC31_CGU_CSB_VBASE+LPC31_CGU_ESR14_OFFSET) +#define LPC31_CGU_ESR15 (LPC31_CGU_CSB_VBASE+LPC31_CGU_ESR15_OFFSET) +#define LPC31_CGU_ESR16 (LPC31_CGU_CSB_VBASE+LPC31_CGU_ESR16_OFFSET) +#define LPC31_CGU_ESR17 (LPC31_CGU_CSB_VBASE+LPC31_CGU_ESR17_OFFSET) +#define LPC31_CGU_ESR18 (LPC31_CGU_CSB_VBASE+LPC31_CGU_ESR18_OFFSET) +#define LPC31_CGU_ESR19 (LPC31_CGU_CSB_VBASE+LPC31_CGU_ESR19_OFFSET) +#define LPC31_CGU_ESR20 (LPC31_CGU_CSB_VBASE+LPC31_CGU_ESR20_OFFSET) +#define LPC31_CGU_ESR21 (LPC31_CGU_CSB_VBASE+LPC31_CGU_ESR21_OFFSET) +#define LPC31_CGU_ESR22 (LPC31_CGU_CSB_VBASE+LPC31_CGU_ESR22_OFFSET) +#define LPC31_CGU_ESR23 (LPC31_CGU_CSB_VBASE+LPC31_CGU_ESR23_OFFSET) +#define LPC31_CGU_ESR24 (LPC31_CGU_CSB_VBASE+LPC31_CGU_ESR24_OFFSET) +#define LPC31_CGU_ESR25 (LPC31_CGU_CSB_VBASE+LPC31_CGU_ESR25_OFFSET) +#define LPC31_CGU_ESR26 (LPC31_CGU_CSB_VBASE+LPC31_CGU_ESR26_OFFSET) +#define LPC31_CGU_ESR27 (LPC31_CGU_CSB_VBASE+LPC31_CGU_ESR27_OFFSET) +#define LPC31_CGU_ESR28 (LPC31_CGU_CSB_VBASE+LPC31_CGU_ESR28_OFFSET) +#define LPC31_CGU_ESR29 (LPC31_CGU_CSB_VBASE+LPC31_CGU_ESR29_OFFSET) +#define LPC31_CGU_ESR30 (LPC31_CGU_CSB_VBASE+LPC31_CGU_ESR30_OFFSET) +#define LPC31_CGU_ESR31 (LPC31_CGU_CSB_VBASE+LPC31_CGU_ESR31_OFFSET) +#define LPC31_CGU_ESR32 (LPC31_CGU_CSB_VBASE+LPC31_CGU_ESR32_OFFSET) +#define LPC31_CGU_ESR33 (LPC31_CGU_CSB_VBASE+LPC31_CGU_ESR33_OFFSET) +#define LPC31_CGU_ESR34 (LPC31_CGU_CSB_VBASE+LPC31_CGU_ESR34_OFFSET) +#define LPC31_CGU_ESR35 (LPC31_CGU_CSB_VBASE+LPC31_CGU_ESR35_OFFSET) +#define LPC31_CGU_ESR36 (LPC31_CGU_CSB_VBASE+LPC31_CGU_ESR36_OFFSET) +#define LPC31_CGU_ESR37 (LPC31_CGU_CSB_VBASE+LPC31_CGU_ESR37_OFFSET) +#define LPC31_CGU_ESR38 (LPC31_CGU_CSB_VBASE+LPC31_CGU_ESR38_OFFSET) +#define LPC31_CGU_ESR39 (LPC31_CGU_CSB_VBASE+LPC31_CGU_ESR39_OFFSET) +#define LPC31_CGU_ESR40 (LPC31_CGU_CSB_VBASE+LPC31_CGU_ESR40_OFFSET) +#define LPC31_CGU_ESR41 (LPC31_CGU_CSB_VBASE+LPC31_CGU_ESR41_OFFSET) +#define LPC31_CGU_ESR42 (LPC31_CGU_CSB_VBASE+LPC31_CGU_ESR42_OFFSET) +#define LPC31_CGU_ESR43 (LPC31_CGU_CSB_VBASE+LPC31_CGU_ESR43_OFFSET) +#define LPC31_CGU_ESR44 (LPC31_CGU_CSB_VBASE+LPC31_CGU_ESR44_OFFSET) +#define LPC31_CGU_ESR45 (LPC31_CGU_CSB_VBASE+LPC31_CGU_ESR45_OFFSET) +#define LPC31_CGU_ESR46 (LPC31_CGU_CSB_VBASE+LPC31_CGU_ESR46_OFFSET) +#define LPC31_CGU_ESR47 (LPC31_CGU_CSB_VBASE+LPC31_CGU_ESR47_OFFSET) +#define LPC31_CGU_ESR48 (LPC31_CGU_CSB_VBASE+LPC31_CGU_ESR48_OFFSET) +#define LPC31_CGU_ESR49 (LPC31_CGU_CSB_VBASE+LPC31_CGU_ESR49_OFFSET) +#define LPC31_CGU_ESR50 (LPC31_CGU_CSB_VBASE+LPC31_CGU_ESR50_OFFSET) +#define LPC31_CGU_ESR51 (LPC31_CGU_CSB_VBASE+LPC31_CGU_ESR51_OFFSET) +#define LPC31_CGU_ESR52 (LPC31_CGU_CSB_VBASE+LPC31_CGU_ESR52_OFFSET) +#define LPC31_CGU_ESR53 (LPC31_CGU_CSB_VBASE+LPC31_CGU_ESR53_OFFSET) +#define LPC31_CGU_ESR54 (LPC31_CGU_CSB_VBASE+LPC31_CGU_ESR54_OFFSET) +#define LPC31_CGU_ESR55 (LPC31_CGU_CSB_VBASE+LPC31_CGU_ESR55_OFFSET) +#define LPC31_CGU_ESR56 (LPC31_CGU_CSB_VBASE+LPC31_CGU_ESR56_OFFSET) +#define LPC31_CGU_ESR57 (LPC31_CGU_CSB_VBASE+LPC31_CGU_ESR57_OFFSET) +#define LPC31_CGU_ESR58 (LPC31_CGU_CSB_VBASE+LPC31_CGU_ESR58_OFFSET) +#define LPC31_CGU_ESR59 (LPC31_CGU_CSB_VBASE+LPC31_CGU_ESR59_OFFSET) +#define LPC31_CGU_ESR60 (LPC31_CGU_CSB_VBASE+LPC31_CGU_ESR60_OFFSET) +#define LPC31_CGU_ESR61 (LPC31_CGU_CSB_VBASE+LPC31_CGU_ESR61_OFFSET) +#define LPC31_CGU_ESR62 (LPC31_CGU_CSB_VBASE+LPC31_CGU_ESR62_OFFSET) +#define LPC31_CGU_ESR63 (LPC31_CGU_CSB_VBASE+LPC31_CGU_ESR63_OFFSET) +#define LPC31_CGU_ESR64 (LPC31_CGU_CSB_VBASE+LPC31_CGU_ESR64_OFFSET) +#define LPC31_CGU_ESR65 (LPC31_CGU_CSB_VBASE+LPC31_CGU_ESR65_OFFSET) +#define LPC31_CGU_ESR66 (LPC31_CGU_CSB_VBASE+LPC31_CGU_ESR66_OFFSET) +#define LPC31_CGU_ESR67 (LPC31_CGU_CSB_VBASE+LPC31_CGU_ESR67_OFFSET) +#define LPC31_CGU_ESR68 (LPC31_CGU_CSB_VBASE+LPC31_CGU_ESR68_OFFSET) +#define LPC31_CGU_ESR69 (LPC31_CGU_CSB_VBASE+LPC31_CGU_ESR69_OFFSET) +#define LPC31_CGU_ESR70 (LPC31_CGU_CSB_VBASE+LPC31_CGU_ESR70_OFFSET) +#define LPC31_CGU_ESR71 (LPC31_CGU_CSB_VBASE+LPC31_CGU_ESR71_OFFSET) +#define LPC31_CGU_ESR72 (LPC31_CGU_CSB_VBASE+LPC31_CGU_ESR72_OFFSET) +#define LPC31_CGU_ESR73 (LPC31_CGU_CSB_VBASE+LPC31_CGU_ESR73_OFFSET) +#define LPC31_CGU_ESR74 (LPC31_CGU_CSB_VBASE+LPC31_CGU_ESR74_OFFSET) +#define LPC31_CGU_ESR75 (LPC31_CGU_CSB_VBASE+LPC31_CGU_ESR75_OFFSET) +#define LPC31_CGU_ESR76 (LPC31_CGU_CSB_VBASE+LPC31_CGU_ESR76_OFFSET) +#define LPC31_CGU_ESR77 (LPC31_CGU_CSB_VBASE+LPC31_CGU_ESR77_OFFSET) +#define LPC31_CGU_ESR78 (LPC31_CGU_CSB_VBASE+LPC31_CGU_ESR78_OFFSET) +#define LPC31_CGU_ESR79 (LPC31_CGU_CSB_VBASE+LPC31_CGU_ESR79_OFFSET) +#define LPC31_CGU_ESR80 (LPC31_CGU_CSB_VBASE+LPC31_CGU_ESR80_OFFSET) +#define LPC31_CGU_ESR81 (LPC31_CGU_CSB_VBASE+LPC31_CGU_ESR81_OFFSET) +#define LPC31_CGU_ESR82 (LPC31_CGU_CSB_VBASE+LPC31_CGU_ESR82_OFFSET) +#define LPC31_CGU_ESR83 (LPC31_CGU_CSB_VBASE+LPC31_CGU_ESR83_OFFSET) +#define LPC31_CGU_ESR84 (LPC31_CGU_CSB_VBASE+LPC31_CGU_ESR84_OFFSET) +#define LPC31_CGU_ESR85 (LPC31_CGU_CSB_VBASE+LPC31_CGU_ESR85_OFFSET) +#define LPC31_CGU_ESR86 (LPC31_CGU_CSB_VBASE+LPC31_CGU_ESR86_OFFSET) +#define LPC31_CGU_ESR87 (LPC31_CGU_CSB_VBASE+LPC31_CGU_ESR87_OFFSET) +#define LPC31_CGU_ESR88 (LPC31_CGU_CSB_VBASE+LPC31_CGU_ESR88_OFFSET) + +/* Base control registers (BCR) for SYS base */ + +#define LPC31_CGU_BCR(n) (LPC31_CGU_CSB_VBASE+LPC31_CGU_BCR_OFFSET(n)) +#define LPC31_CGU_BCR0 (LPC31_CGU_CSB_VBASE+LPC31_CGU_BCR0_OFFSET) +#define LPC31_CGU_BCR1 (LPC31_CGU_CSB_VBASE+LPC31_CGU_BCR1_OFFSET) +#define LPC31_CGU_BCR2 (LPC31_CGU_CSB_VBASE+LPC31_CGU_BCR2_OFFSET) +#define LPC31_CGU_BCR3 (LPC31_CGU_CSB_VBASE+LPC31_CGU_BCR3_OFFSET) +#define LPC31_CGU_BCR7 (LPC31_CGU_CSB_VBASE+LPC31_CGU_BCR7_OFFSET) + +/* Fractional divider configuration (FDC) registers */ + +#define LPC31_CGU_FDC(n) (LPC31_CGU_CSB_VBASE+LPC31_CGU_FDC_OFFSET(n)) +#define LPC31_CGU_FDC0 (LPC31_CGU_CSB_VBASE+LPC31_CGU_FDC0_OFFSET) +#define LPC31_CGU_FDC1 (LPC31_CGU_CSB_VBASE+LPC31_CGU_FDC1_OFFSET) +#define LPC31_CGU_FDC2 (LPC31_CGU_CSB_VBASE+LPC31_CGU_FDC2_OFFSET) +#define LPC31_CGU_FDC3 (LPC31_CGU_CSB_VBASE+LPC31_CGU_FDC3_OFFSET) +#define LPC31_CGU_FDC4 (LPC31_CGU_CSB_VBASE+LPC31_CGU_FDC4_OFFSET) +#define LPC31_CGU_FDC5 (LPC31_CGU_CSB_VBASE+LPC31_CGU_FDC5_OFFSET) +#define LPC31_CGU_FDC6 (LPC31_CGU_CSB_VBASE+LPC31_CGU_FDC6_OFFSET) +#define LPC31_CGU_FDC7 (LPC31_CGU_CSB_VBASE+LPC31_CGU_FDC7_OFFSET) +#define LPC31_CGU_FDC8 (LPC31_CGU_CSB_VBASE+LPC31_CGU_FDC8_OFFSET) +#define LPC31_CGU_FDC9 (LPC31_CGU_CSB_VBASE+LPC31_CGU_FDC9_OFFSET) +#define LPC31_CGU_FDC10 (LPC31_CGU_CSB_VBASE+LPC31_CGU_FDC10_OFFSET) +#define LPC31_CGU_FDC11 (LPC31_CGU_CSB_VBASE+LPC31_CGU_FDC11_OFFSET) +#define LPC31_CGU_FDC12 (LPC31_CGU_CSB_VBASE+LPC31_CGU_FDC12_OFFSET) +#define LPC31_CGU_FDC13 (LPC31_CGU_CSB_VBASE+LPC31_CGU_FDC13_OFFSET) +#define LPC31_CGU_FDC14 (LPC31_CGU_CSB_VBASE+LPC31_CGU_FDC14_OFFSET) +#define LPC31_CGU_FDC15 (LPC31_CGU_CSB_VBASE+LPC31_CGU_FDC15_OFFSET) +#define LPC31_CGU_FDC16 (LPC31_CGU_CSB_VBASE+LPC31_CGU_FDC16_OFFSET) +#define LPC31_CGU_FDC17 (LPC31_CGU_CSB_VBASE+LPC31_CGU_FDC17_OFFSET) +#define LPC31_CGU_FDC18 (LPC31_CGU_CSB_VBASE+LPC31_CGU_FDC18_OFFSET) +#define LPC31_CGU_FDC19 (LPC31_CGU_CSB_VBASE+LPC31_CGU_FDC19_OFFSET) +#define LPC31_CGU_FDC20 (LPC31_CGU_CSB_VBASE+LPC31_CGU_FDC20_OFFSET) +#define LPC31_CGU_FDC21 (LPC31_CGU_CSB_VBASE+LPC31_CGU_FDC21_OFFSET) +#define LPC31_CGU_FDC22 (LPC31_CGU_CSB_VBASE+LPC31_CGU_FDC22_OFFSET) +#define LPC31_CGU_FDC23 (LPC31_CGU_CSB_VBASE+LPC31_CGU_FDC23_OFFSET) + +/* Dynamic fractional divider configuration (DYNFDC) registers (SYS base only) */ + +#define LPC31_CGU_DYNFDC(n) (LPC31_CGU_CSB_VBASE+LPC31_CGU_DYNFDC_OFFSET(n)) +#define LPC31_CGU_DYNFDC0 (LPC31_CGU_CSB_VBASE+LPC31_CGU_DYNFDC0_OFFSET) +#define LPC31_CGU_DYNFDC1 (LPC31_CGU_CSB_VBASE+LPC31_CGU_DYNFDC1_OFFSET) +#define LPC31_CGU_DYNFDC2 (LPC31_CGU_CSB_VBASE+LPC31_CGU_DYNFDC2_OFFSET) +#define LPC31_CGU_DYNFDC3 (LPC31_CGU_CSB_VBASE+LPC31_CGU_DYNFDC3_OFFSET) +#define LPC31_CGU_DYNFDC4 (LPC31_CGU_CSB_VBASE+LPC31_CGU_DYNFDC4_OFFSET) +#define LPC31_CGU_DYNFDC5 (LPC31_CGU_CSB_VBASE+LPC31_CGU_DYNFDC5_OFFSET) +#define LPC31_CGU_DYNFDC6 (LPC31_CGU_CSB_VBASE+LPC31_CGU_DYNFDC6_OFFSET) + +/* Dynamic fractional divider selection (DYNSEL) registers (SYS base only) */ + +#define LPC31_CGU_DYNSEL(n) (LPC31_CGU_CSB_VBASE+LPC31_CGU_DYNSEL_OFFSET(n)) +#define LPC31_CGU_DYNSEL0 (LPC31_CGU_CSB_VBASE+LPC31_CGU_DYNSEL0_OFFSET) +#define LPC31_CGU_DYNSEL1 (LPC31_CGU_CSB_VBASE+LPC31_CGU_DYNSEL1_OFFSET) +#define LPC31_CGU_DYNSEL2 (LPC31_CGU_CSB_VBASE+LPC31_CGU_DYNSEL2_OFFSET) +#define LPC31_CGU_DYNSEL3 (LPC31_CGU_CSB_VBASE+LPC31_CGU_DYNSEL3_OFFSET) +#define LPC31_CGU_DYNSEL4 (LPC31_CGU_CSB_VBASE+LPC31_CGU_DYNSEL4_OFFSET) +#define LPC31_CGU_DYNSEL5 (LPC31_CGU_CSB_VBASE+LPC31_CGU_DYNSEL5_OFFSET) +#define LPC31_CGU_DYNSEL6 (LPC31_CGU_CSB_VBASE+LPC31_CGU_DYNSEL6_OFFSET) + +/* CGU configuration (virtural) register address ************************************************/ +/* Power and oscillator control */ + +#define LPC31_CGU_POWERMODE (LPC31_CGU_CFG_VBASE+LPC31_CGU_POWERMODE_OFFSET) +#define LPC31_CGU_WDBARK (LPC31_CGU_CFG_VBASE+LPC31_CGU_WDBARK_OFFSET) +#define LPC31_CGU_FFASTON (LPC31_CGU_CFG_VBASE+LPC31_CGU_FFASTON_OFFSET) +#define LPC31_CGU_FFASTBYP (LPC31_CGU_CFG_VBASE+LPC31_CGU_FFASTBYP_OFFSET) + +/* Reset control */ + +#define LPC31_CGU_SOFTRST(n) (LPC31_CGU_CFG_VBASE+LPC31_CGU_SOFTRST_OFFSET(n)) +#define LPC31_CGU_APB0RST (LPC31_CGU_CFG_VBASE+LPC31_CGU_APB0RST_OFFSET) +#define LPC31_CGU_AHB2APB0RST (LPC31_CGU_CFG_VBASE+LPC31_CGU_AHB2APB0RST_OFFSET) +#define LPC31_CGU_APB1RST (LPC31_CGU_CFG_VBASE+LPC31_CGU_APB1RST_OFFSET) +#define LPC31_CGU_AHB2PB1RST (LPC31_CGU_CFG_VBASE+LPC31_CGU_AHB2PB1RST_OFFSET) +#define LPC31_CGU_APB2RST (LPC31_CGU_CFG_VBASE+LPC31_CGU_APB2RST_OFFSET) +#define LPC31_CGU_AHB2APB2RST (LPC31_CGU_CFG_VBASE+LPC31_CGU_AHB2APB2RST_OFFSET) +#define LPC31_CGU_APB3RST (LPC31_CGU_CFG_VBASE+LPC31_CGU_APB3RST_OFFSET) +#define LPC31_CGU_AHB2APB3RST (LPC31_CGU_CFG_VBASE+LPC31_CGU_AHB2APB3RST_OFFSET) +#define LPC31_CGU_APB4RST (LPC31_CGU_CFG_VBASE+LPC31_CGU_APB4RST_OFFSET) +#define LPC31_CGU_AHB2INTCRST (LPC31_CGU_CFG_VBASE+LPC31_CGU_AHB2INTCRST_OFFSET) +#define LPC31_CGU_AHB0RST (LPC31_CGU_CFG_VBASE+LPC31_CGU_AHB0RST_OFFSET) +#define LPC31_CGU_EBIRST (LPC31_CGU_CFG_VBASE+LPC31_CGU_EBIRST_OFFSET) +#define LPC31_CGU_PCMAPBRST (LPC31_CGU_CFG_VBASE+LPC31_CGU_PCMAPBRST_OFFSET) +#define LPC31_CGU_PCMCLKIPRST (LPC31_CGU_CFG_VBASE+LPC31_CGU_PCMCLKIPRST_OFFSET) +#define LPC31_CGU_PCMRSTASYNC (LPC31_CGU_CFG_VBASE+LPC31_CGU_PCMRSTASYNC_OFFSET) +#define LPC31_CGU_TIMER0RST (LPC31_CGU_CFG_VBASE+LPC31_CGU_TIMER0RST_OFFSET) +#define LPC31_CGU_TIMER1RST (LPC31_CGU_CFG_VBASE+LPC31_CGU_TIMER1RST_OFFSET) +#define LPC31_CGU_TIMER2RST (LPC31_CGU_CFG_VBASE+LPC31_CGU_TIMER2RST_OFFSET) +#define LPC31_CGU_TIMER3RST (LPC31_CGU_CFG_VBASE+LPC31_CGU_TIMER3RST_OFFSET) +#define LPC31_CGU_ADCPRST (LPC31_CGU_CFG_VBASE+LPC31_CGU_ADCPRST_OFFSET) +#define LPC31_CGU_ADCRST (LPC31_CGU_CFG_VBASE+LPC31_CGU_ADCRST_OFFSET) +#define LPC31_CGU_PWMRST (LPC31_CGU_CFG_VBASE+LPC31_CGU_PWMRST_OFFSET) +#define LPC31_CGU_UARTRST (LPC31_CGU_CFG_VBASE+LPC31_CGU_UARTRST_OFFSET) +#define LPC31_CGU_I2C0RST (LPC31_CGU_CFG_VBASE+LPC31_CGU_I2C0RST_OFFSET) +#define LPC31_CGU_I2C1RST (LPC31_CGU_CFG_VBASE+LPC31_CGU_I2C1RST_OFFSET) +#define LPC31_CGU_I2SCFGRST (LPC31_CGU_CFG_VBASE+LPC31_CGU_I2SCFGRST_OFFSET) +#define LPC31_CGU_I2SNSOFRST (LPC31_CGU_CFG_VBASE+LPC31_CGU_I2SNSOFRST_OFFSET) +#define LPC31_CGU_EDGEDETRST (LPC31_CGU_CFG_VBASE+LPC31_CGU_EDGEDETRST_OFFSET) +#define LPC31_CGU_I2STXFF0RST (LPC31_CGU_CFG_VBASE+LPC31_CGU_I2STXFF0RST_OFFSET) +#define LPC31_CGU_I2STXIF0RST (LPC31_CGU_CFG_VBASE+LPC31_CGU_I2STXIF0RST_OFFSET) +#define LPC31_CGU_I2STXFF1RST (LPC31_CGU_CFG_VBASE+LPC31_CGU_I2STXFF1RST_OFFSET) +#define LPC31_CGU_I2STXIF1RST (LPC31_CGU_CFG_VBASE+LPC31_CGU_I2STXIF1RST_OFFSET) +#define LPC31_CGU_I2SRXFF0RST (LPC31_CGU_CFG_VBASE+LPC31_CGU_I2SRXFF0RST_OFFSET) +#define LPC31_CGU_I2SRXIF0RST (LPC31_CGU_CFG_VBASE+LPC31_CGU_I2SRXIF0RST_OFFSET) +#define LPC31_CGU_I2SRXFF1RST (LPC31_CGU_CFG_VBASE+LPC31_CGU_I2SRXFF1RST_OFFSET) +#define LPC31_CGU_I2SRXIF1RST (LPC31_CGU_CFG_VBASE+LPC31_CGU_I2SRXIF1RST_OFFSET) +#define LPC31_CGU_LCDRST (LPC31_CGU_CFG_VBASE+LPC31_CGU_LCDRST_OFFSET) +#define LPC31_CGU_SPIRSTAPB (LPC31_CGU_CFG_VBASE+LPC31_CGU_SPIRSTAPB_OFFSET) +#define LPC31_CGU_SPIRSTIP (LPC31_CGU_CFG_VBASE+LPC31_CGU_SPIRSTIP_OFFSET) +#define LPC31_CGU_DMARST (LPC31_CGU_CFG_VBASE+LPC31_CGU_DMARST_OFFSET) +#define LPC31_CGU_NANDECCRST (LPC31_CGU_CFG_VBASE+LPC31_CGU_NANDECCRST_OFFSET) +#define LPC31_CGU_NANDCTRLRST (LPC31_CGU_CFG_VBASE+LPC31_CGU_NANDCTRLRST_OFFSET) +#define LPC31_CGU_SDMMCRST (LPC31_CGU_CFG_VBASE+LPC31_CGU_SDMMCRST_OFFSET) +#define LPC31_CGU_SDMMCRSTCKIN (LPC31_CGU_CFG_VBASE+LPC31_CGU_SDMMCRSTCKIN_OFFSET) +#define LPC31_CGU_USBOTGAHBRST (LPC31_CGU_CFG_VBASE+LPC31_CGU_USBOTGAHBRST_OFFSET) +#define LPC31_CGU_REDCTLRST (LPC31_CGU_CFG_VBASE+LPC31_CGU_REDCTLRST_OFFSET) +#define LPC31_CGU_AHBMPMCHRST (LPC31_CGU_CFG_VBASE+LPC31_CGU_AHBMPMCHRST_OFFSET) +#define LPC31_CGU_AHBMPMCRFRST (LPC31_CGU_CFG_VBASE+LPC31_CGU_AHBMPMCRFRST_OFFSET) +#define LPC31_CGU_INTCRST (LPC31_CGU_CFG_VBASE+LPC31_CGU_INTCRST_OFFSET) + +/* HP PLL controls */ + +#define LPC313x_CGU_HP0PLL (LPC31_CGU_CFG_VBASE+LPC313x_CGU_HP0PLL_OFFSET) +#define LPC313x_CGU_HP1PLL (LPC31_CGU_CFG_VBASE+LPC313x_CGU_HP1PLL_OFFSET) +#define LPC313x_CGU_HPPLL(n) ((n) ? LPC313x_CGU_HP1PLL : LPC313x_CGU_HP0PLL) + +/* HPO PLL control (audio PLL) */ + +#define LPC31_CGU_HP0FINSEL (LPC31_CGU_CFG_VBASE+LPC31_CGU_HP0FINSEL_OFFSET) +#define LPC31_CGU_HP0MDEC (LPC31_CGU_CFG_VBASE+LPC31_CGU_HP0MDEC_OFFSET) +#define LPC31_CGU_HP0NDEC (LPC31_CGU_CFG_VBASE+LPC31_CGU_HP0NDEC_OFFSET) +#define LPC31_CGU_HP0PDEC (LPC31_CGU_CFG_VBASE+LPC31_CGU_HP0PDEC_OFFSET) +#define LPC31_CGU_HP0MODE (LPC31_CGU_CFG_VBASE+LPC31_CGU_HP0MODE_OFFSET) +#define LPC31_CGU_HP0STATUS (LPC31_CGU_CFG_VBASE+LPC31_CGU_HP0STATUS_OFFSET) +#define LPC31_CGU_HP0ACK (LPC31_CGU_CFG_VBASE+LPC31_CGU_HP0ACK_OFFSET) +#define LPC31_CGU_HP0REQ (LPC31_CGU_CFG_VBASE+LPC31_CGU_HP0REQ_OFFSET) +#define LPC31_CGU_HP0INSELR (LPC31_CGU_CFG_VBASE+LPC31_CGU_HP0INSELR_OFFSET) +#define LPC31_CGU_HP0INSELI (LPC31_CGU_CFG_VBASE+LPC31_CGU_HP0INSELI_OFFSET) +#define LPC31_CGU_HP0INSELP (LPC31_CGU_CFG_VBASE+LPC31_CGU_HP0INSELP_OFFSET) +#define LPC31_CGU_HP0SELR (LPC31_CGU_CFG_VBASE+LPC31_CGU_HP0SELR_OFFSET) +#define LPC31_CGU_HP0SELI (LPC31_CGU_CFG_VBASE+LPC31_CGU_HP0SELI_OFFSET) +#define LPC31_CGU_HP0SELP (LPC31_CGU_CFG_VBASE+LPC31_CGU_HP0SELP_OFFSET) + +/* HP1 PLL control (system PLL) */ + +#define LPC31_CGU_HP1FINSEL (LPC31_CGU_CFG_VBASE+LPC31_CGU_HP1FINSEL_OFFSET) +#define LPC31_CGU_HP1MDEC (LPC31_CGU_CFG_VBASE+LPC31_CGU_HP1MDEC_OFFSET) +#define LPC31_CGU_HP1NDEC (LPC31_CGU_CFG_VBASE+LPC31_CGU_HP1NDEC_OFFSET) +#define LPC31_CGU_HP1PDEC (LPC31_CGU_CFG_VBASE+LPC31_CGU_HP1PDEC_OFFSET) +#define LPC31_CGU_HP1MODE (LPC31_CGU_CFG_VBASE+LPC31_CGU_HP1MODE_OFFSET) +#define LPC31_CGU_HP1STATUS (LPC31_CGU_CFG_VBASE+LPC31_CGU_HP1STATUS_OFFSET) +#define LPC31_CGU_HP1ACK (LPC31_CGU_CFG_VBASE+LPC31_CGU_HP1ACK_OFFSET) +#define LPC31_CGU_HP1REQ (LPC31_CGU_CFG_VBASE+LPC31_CGU_HP1REQ_OFFSET) +#define LPC31_CGU_HP1INSELR (LPC31_CGU_CFG_VBASE+LPC31_CGU_HP1INSELR_OFFSET) +#define LPC31_CGU_HP1INSELI (LPC31_CGU_CFG_VBASE+LPC31_CGU_HP1INSELI_OFFSET) +#define LPC31_CGU_HP1INSELP (LPC31_CGU_CFG_VBASE+LPC31_CGU_HP1INSELP_OFFSET) +#define LPC31_CGU_HP1SELR (LPC31_CGU_CFG_VBASE+LPC31_CGU_HP1SELR_OFFSET) +#define LPC31_CGU_HP1SELI (LPC31_CGU_CFG_VBASE+LPC31_CGU_HP1SELI_OFFSET) +#define LPC31_CGU_HP1SELP (LPC31_CGU_CFG_VBASE+LPC31_CGU_HP1SELP_OFFSET) + +/* CGU register bit definitions *****************************************************************/ + +/* Frequency inputs */ + +#define CGU_FREQIN_FFAST 0 /* ffast 12 MHz */ +#define CGU_FREQIN_I2SRXBCK0 1 /* I2SRX_BCK0 */ +#define CGU_FREQIN_I2SRXWS0 2 /* I2SRX_WS0 */ +#define CGU_FREQIN_I2SRXBCK1 3 /* I2SRX_BCK1 */ +#define CGU_FREQIN_I2SRXWS1 4 /* I2SRX_WS1 */ +#define CGU_FREQIN_HPPLL0 5 /* HPPLL0 (Audio/I2S PLL) */ +#define CGU_FREQIN_HPPLL1 6 /* HPPLL1 (System PLL) */ +#define CGU_NFREQIN 7 + +/* CGU clock switchbox register bit definitions *************************************************/ + +/* Switch configuration register SCR0 to SCR11, addresses 0x13004000 to 0x1300402c */ + +#define CGU_SCR_STOP (1 << 3) /* Bit 3: Forces switch in disable mode */ +#define CGU_SCR_RESET (1 << 2) /* Bit 2: Asynchronous reset of both switches */ +#define CGU_SCR_ENF2 (1 << 1) /* Bit 1: Enable side #2 of switch */ +#define CGU_SCR_ENF1 (1 << 0) /* Bit 0: Enable side #1 of switch */ + +/* Frequency select register 1 FS1_0 to FS1_11, addresses 0x13004030 to 0x1300405c, + * Frequency Select register 2 FS2_0 to FS2_11, addresses 0x13004060 to 0x1300408c + */ + +#define CGU_FS_SHIFT (0) /* Bits 0-2: Selects input frequency for either side of frequency switch */ +#define CGU_FS_MASK (7 << CGU_FS_SHIFT) +# define CGU_FS_FFAST (CGU_FREQIN_FFAST << CGU_FS_SHIFT) /* ffast 12 MHz */ +# define CGU_FS_I2SRXBCK0 (CGU_FREQIN_I2SRXBCK0 << CGU_FS_SHIFT) /* I2SRX_BCK0 */ +# define CGU_FS_I2SRXWS0 (CGU_FREQIN_I2SRXWS0 << CGU_FS_SHIFT) /* I2SRX_WS0 */ +# define CGU_FS_I2SRXBCK1 (CGU_FREQIN_I2SRXBCK1 << CGU_FS_SHIFT) /* I2SRX_BCK1 */ +# define CGU_FS_I2SRXWS1 (CGU_FREQIN_I2SRXWS1 << CGU_FS_SHIFT) /* I2SRX_WS1 */ +# define CGU_FS_HPPLL0 (CGU_FREQIN_HPPLL0 << CGU_FS_SHIFT) /* HPPLL0 (Audio/I2S PLL) */ +# define CGU_FS_HPPLL1 (CGU_FREQIN_HPPLL1 << CGU_FS_SHIFT) /* HPPLL1 (System PLL) */ + +/* Switch Status register SSR0 to SSR11, addresses 0x13004090 to 0x1300 40bc */ + +#define CGU_SSR_FS_SHIFT (2) /* Bits 2-4: Feedback of current frequency selection */ +#define CGU_SSR_FS_MASK (7 << CGU_SSR_FS_SHIFT) +# define CGU_SSR_FFAST (CGU_FREQIN_FFAST << CGU_SSR_FS_SHIFT) /* ffast 12 MHz */ +# define CGU_SSR_I2SRXBCK0 (CGU_FREQIN_I2SRXBCK0 << CGU_SSR_FS_SHIFT) /* I2SRX_BCK0 */ +# define CGU_SSR_I2SRXWS0 (CGU_FREQIN_I2SRXWS0 << CGU_SSR_FS_SHIFT) /* I2SRX_WS0 */ +# define CGU_SSR_I2SRXBCK1 (CGU_FREQIN_I2SRXBCK1 << CGU_SSR_FS_SHIFT) /* I2SRX_BCK1 */ +# define CGU_SSR_I2SRXWS1 (CGU_FREQIN_I2SRXWS1 << CGU_SSR_FS_SHIFT) /* I2SRX_WS1 */ +# define CGU_SSR_HPPLL0 (CGU_FREQIN_HPPLL0 << CGU_SSR_FS_SHIFT) /* HPPLL0 (Audio/I2S PLL) */ +# define CGU_SSR_HPPLL1 (CGU_FREQIN_HPPLL1 << CGU_SSR_FS_SHIFT) /* HPPLL1 (System PLL) */ +#define CGU_SSR_FS2STAT (1 << 1) /* Bit 1: Enable side #2 of the frequency switch */ +#define CGU_SSR_FS1STAT (1 << 0) /* Bit 0: Enable side #1 of the frequency switch */ + +/* Power Control register PCR0 to PCR91, addresses 0x130040c0 to 0x1300422c */ + +#define CGU_PCR_ENOUTEN (1 << 4) /* Bit 4: Enable clock preview signal */ +#define CGU_PCR_EXTENEN (1 << 3) /* Bit 3: Enable external enabling */ +#define CGU_PCR_WAKEEN (1 << 2) /* Bit 2: Enable central wakeup */ +#define CGU_PCR_AUTO (1 << 1) /* Bit 1: Enable wakeup and external enable */ +#define CGU_PCR_RUN (1 << 0) /* Bit 0: Enable clocks */ + +/* Power Status register PSR0 to PSR91, addresses 0x13004230 to 0x1300439c */ + +#define CGU_PSR_WAKEUP (1 << 1) /* Bit 1: Clock wakeup condition */ +#define CGU_PSR_ACTIVE (1 << 0) /* Bit 0: Indicates clock is active */ + +/* Enable Select register ESR0 to ESR88, addresses 0x130043a0 to 0x13004500 */ +/* The ESR_SEL varies according to the selected clock */ + +#define CGU_ESR_ESRSEL_SHIFT (1) /* Bits 1-n: Common shift value */ +#define CGU_ESR0_29_ESRSEL_SHIFT (1) /* Bits 1-3: Selection of fractional dividers */ +#define CGU_ESR0_29_ESRSEL_MASK (7 << CGU_ESR0_29_ESRSEL_SHIFT) +# define CGU_ESR0_29_ESRSEL_FDC0 (0 << CGU_ESR0_29_ESRSEL_SHIFT) /* Selects FDC0 */ +# define CGU_ESR0_29_ESRSEL_FDC1 (1 << CGU_ESR0_29_ESRSEL_SHIFT) /* Selects FDC1 */ +# define CGU_ESR0_29_ESRSEL_FDC2 (2 << CGU_ESR0_29_ESRSEL_SHIFT) /* Selects FDC2 */ +# define CGU_ESR0_29_ESRSEL_FDC3 (3 << CGU_ESR0_29_ESRSEL_SHIFT) /* Selects FDC3 */ +# define CGU_ESR0_29_ESRSEL_FDC4 (4 << CGU_ESR0_29_ESRSEL_SHIFT) /* Selects FDC4 */ +# define CGU_ESR0_29_ESRSEL_FDC5 (5 << CGU_ESR0_29_ESRSEL_SHIFT) /* Selects FDC5 */ +# define CGU_ESR0_29_ESRSEL_FDC6 (6 << CGU_ESR0_29_ESRSEL_SHIFT) /* Selects FDC6 */ + +#define CGU_ESR30_39_ESRSEL_FDC7 (0) /* Bit 1=0 selects FDC7 */ +#define CGU_ESR30_39_ESRSEL_FDC8 (1 << 1) /* Bit 1=1 selects FDC8 */ + +#define CGU_ESR40_49_ESRSEL_FDC9 (0) /* Bit 1=0 selects FDC9 */ +#define CGU_ESR40_49_ESRSEL_FDC10 (1 << 1) /* Bit 1=1 selects FDC10 */ + +#define CGU_ESR50_57_ESRSEL_SHIFT (1) /* Bits 1-3: Selection of fractional dividers */ +#define CGU_ESR50_57_ESRSEL_MASK (3 << CGU_ESR50_57_ESRSEL_SHIFT) +# define CGU_ESR50_57_ESRSEL_FDC11 (0 << CGU_ESR50_57_ESRSEL_SHIFT) /* Selects FDC11 */ +# define CGU_ESR50_57_ESRSEL_FDC12 (1 << CGU_ESR50_57_ESRSEL_SHIFT) /* Selects FDC12 */ +# define CGU_ESR50_57_ESRSEL_FDC13 (2 << CGU_ESR50_57_ESRSEL_SHIFT) /* Selects FDC13 */ + +#define CGU_ESR58_70_ESRSEL_FDC14 (0) /* Only option */ +#define CGU_ESR71_ESRSEL_FDC15 (0) /* Only option */ +#define CGU_ESR72_ESRSEL_FDC16 (0) /* Only option */ + +#define CGU_ESR73_86_ESRSEL_SHIFT (1) /* Bits 1-3: Selection of fractional dividers */ +#define CGU_ESR73_86_ESRSEL_MASK (7 << CGU_ESR73_86_ESRSEL_SHIFT) +# define CGU_ESR73_86_ESRSEL_FDC17 (0 << CGU_ESR73_86_ESRSEL_SHIFT) /* Selects FDC17 */ +# define CGU_ESR73_86_ESRSEL_FDC18 (1 << CGU_ESR73_86_ESRSEL_SHIFT) /* Selects FDC18 */ +# define CGU_ESR73_86_ESRSEL_FDC19 (2 << CGU_ESR73_86_ESRSEL_SHIFT) /* Selects FDC19 */ +# define CGU_ESR73_86_ESRSEL_FDC20 (3 << CGU_ESR73_86_ESRSEL_SHIFT) /* Selects FDC20 */ +# define CGU_ESR73_86_ESRSEL_FDC21 (4 << CGU_ESR73_86_ESRSEL_SHIFT) /* Selects FDC21 */ +# define CGU_ESR73_86_ESRSEL_FDC22 (5 << CGU_ESR73_86_ESRSEL_SHIFT) /* Selects FDC22 */ + +#define CGU_ESR87_88_ESRSEL_FDC23 (0) /* Only option */ + +#define CGU_ESR_ESREN (1 << 0) /* Bit 0: Enable from FD selected by ESRSEL */ + +/* Base control registers 0 BCR0 to BCR7, addresses 0x13004504 to 0x13004514 */ + +#define CGU_BCR_FDRUN (1 << 0) /* Bit 0: Enable fractional dividers */ + +/* Fractional divider register 0 to 23 FDC0 to FDC23 (except FDC17) addresses 0x13004518 to 0x13004574 */ + +#define CGU_FDC_MSUB_SHIFT (11) /* Bits 11-18: Modulo subtraction value */ +#define CGU_FDC_MSUB_MASK (0x000000ff << CGU_FDC_MSUB_SHIFT) +#define CGU_FDC_MSUB_EXTEND (0xffffff00) +#define CGU_FDC_MADD_SHIFT (3) /* Bits 3-10: Modulo addition value */ +#define CGU_FDC_MADD_MASK (0x000000ff << CGU_FDC_MADD_SHIFT) +#define CGU_FDC_STRETCH (1 << 2) /* Bit 2: Enables the stretching option */ +#define CGU_FDC_RESET (1 << 1) /* Bit 1: Reset fractional divider */ +#define CGU_FDC_RUN (1 << 0) /* Bit 0: Enable fractional divider */ + +#define CGU_FDC17_MSUB_SHIFT (16) /* Bits 16-28: Modulo subtraction value */ +#define CGU_FDC17_MSUB_MASK (0x00001fff << CGU_FDC17_MSUB_SHIFT) +#define CGU_FDC17_MSUB_EXTEND (0xffffe000) +#define CGU_FDC17_MADD_SHIFT (3) /* Bits 3-15: Modulo addition value */ +#define CGU_FDC17_MADD_MASK (0x00001fff << CGU_FDC17_MADD_SHIFT) +#define CGU_FDC17_STRETCH (1 << 2) /* Bit 2: Enables the stretching option */ +#define CGU_FDC17_RESET (1 << 1) /* Bit 1: Reset fractional divider */ +#define CGU_FDC17_RUN (1 << 0) /* Bit 0: Enable fractional divider */ + +#define CGU_FDC_FIELDWIDTH 8 /* MSUB and MADD fields are 8-bits in width */ +#define CGU_FDC17_FIELDWIDTH 13 /* Exept for FDC17 which is 13-bits in width */ + +/* Dynamic Fractional Divider registers DYNFDC0 to DYNFDC6, addresses 0x13004578 to 0x13004590 */ + +#define CGU_DYNFDC_STOPAUTORST (1 << 19) /* Bit 19: Disable auto reset of fractional divider */ +#define CGU_DYNFDC_MSUB_SHIFT (11) /* Bits 11-18: Modulo subtraction value */ +#define CGU_DYNFDC_MSUB_MASK (255 << CGU_DYNFDC_MSUB_SHIFT) +#define CGU_DYNFDC_MADD_SHIFT (3) /* Bits 3-10: Modulo addition value */ +#define CGU_DYNFDC_MADD_MASK (255 << CGU_DYNFDC_MADD_SHIFT) +#define CGU_DYNFDC_STRETCH (1 << 2) /* Bit 2: Enables the stretching option */ +#define CGU_DYNFDC_ALLOW (1 << 1) /* Bit 1: Enable dynamic fractional divider */ +#define CGU_DYNFDC_RUN (1 << 0) /* Bit 0: Enable the fractional divider during low speeds */ + +/* Dynamic Fractional Divider Selection register DYNSEL0 to DYNSEL6, addresses 0x13004594 to 0x130045ac */ + +#define CGU_DYNSEL_MPMCREFRESHREQ (1 << 8) /* Bit 8: Ext SDRAM refresh can enable high speed */ +#define CGU_DYNSEL_ECCRAMBUSY (1 << 7) /* Bit 7: Hispeed mode during NAND ECC */ +#define CGU_DYNSEL_USBOTGMSTTRANS (1 << 6) /* Bit 6: USB OTG transfers can enable high speed */ +#define CGU_DYNSEL_ARM926LPDREADY (1 << 5) /* Bit 5: ARM926 data transfers can enable high-speed */ +#define CGU_DYNSEL_ARM926LPDTRANS (1 << 4) /* Bit 4: ARM926 data transfers can enable high-speed */ +#define CGU_DYNSEL_ARM926LPIREADY (1 << 3) /* Bit 3: ARM926 instr last transfers can enable high-speed */ +#define CGU_DYNSEL_ARM926LPITRANS (1 << 2) /* Bit 2: ARM926 instr transfers can enable high-speed */ +#define CGU_DYNSEL_DMAREADY (1 << 1) /* Bit 1: dma last transfers can enable high-speed */ +#define CGU_DYNSEL_DMATRANS (1 << 0) /* Bit 0: dma transfers can enable high-speed */ +#define CGU_DYNSEL_ALLBITS (0x1ff) + +/* CGU configuration register bit definitions ***************************************************/ +/* Power and oscillator control registers */ +/* Powermode register POWERMODE, address 0x13004c00 */ + +#define CGU_POWERMODE_SHIFT (0) /* Bits 0-1: Powermode */ +#define CGU_POWERMODE_MASK (3 << bb) +#define CGU_POWERMODE_NORMAL (1 << bb) /* Normal operational mode */ +#define CGU_POWERMODE_WAKEUP (3 << bb) /* Wakeup clocks disabled until wakeup event */ + +/* Watchdog Bark register WDBARK, address 0x13004c04 */ + +#define CGU_WDBARK_RESET (1 << 0) /* Bit 0: Set when a watchdog reset has occurred */ + +/* Fast Oscillator activate register FFASTON, 0x13004c08 */ + +#define CGU_FFASTON_ACTIVATE (1 << 0) /* Bit 0: Activate fast oscillator */ + +/* Fast Oscillator Bypass comparator register FFASTBYP, 0x13004c0c */ + +#define CGU_FFASTBYP_TESTMODE (1 << 0) /* Bit 0: Oscillator test mode */ + +/* Reset control registers */ + +#define CGU_SOFTRESET (1 << 0) /* Bit 0: in all of the reset control registers */ + +/* APB0_RESETN_SOFT register, address 0x13004c10 */ + +#define CGU_APB0RST_RESET (1 << 0) /* Bit 0: Reserved */ + +/* AHB_TO_APB0_PNRES_SOFT register, address 0x13004c14 */ + +#define CGU_AHB2APB0RST_RESET (1 << 0) /* Bit 0: Reserved */ + +/* APB1_RESETN_SOFT register, address 0x13004c18 */ + +#define CGU_APB1RST_RESET (1 << 0) /* Bit 0: Reset for AHB part of AHB_TO_APB1 bridge */ + +/* AHB_TO_APB1_PNRES_SOFT register, address 0x13004c1c */ + +#define CGU_AHB2PB1RST_RESET (1 << 0) /* Bit 0: Reset for APB part of AHB_TO_APB1 bridge */ + +/* APB2_RESETN_SOFT register, address 0x13004c20 */ + +#define CGU_APB2RST_RESET (1 << 0) /* Bit 0: Reset for AHB part of AHB_TO_APB2 bridge */ + +/* AHB_TO_APB2_PNRES_SOFT register, address 0x13004c24 */ + +#define CGU_AHB2APB2RST_RESET (1 << 0) /* Bit 0: Reset for APB part of AHB_TO_APB2 bridge */ + +/* APB3_RESETN_SOFT register, address 0x13004c28 */ + +#define CGU_APB3RST_RESET (1 << 0) /* Bit 0: Reset for AHB part of AHB_TO_APB3 bridge */ + +/* AHB_TO_APB3_PNRES_SOFT register, address 0x13004c2c */ + +#define CGU_AHB2APB3RST_RESET (1 << 0) /* Bit 0: Reset for APB part of AHB_TO_APB3 bridge */ + +/* APB4_RESETN_SOFT register, address 0x13004c30 */ + +#define CGU_APB4RST_RESET (1 << 0) /* Bit 0: Reset for AHB part of AHB_TO_APB4 bridge */ + +/* AHB_TO_INTC_RESETN_SOFT register, address 0x13004c34 */ + +#define CGU_AHB2INTCRST_RESET (1 << 0) /* Bit 0: Reset for AHB_TO_INTC */ + +/* AHB0_RESETN_SOFT register, address 0x13004c38 */ + +#define CGU_AHB0RST_RESET (1 << 0) /* Bit 0: Reserved */ + +/* EBI_RESETN_SOFT register, address 0x13004c2c */ + +#define CGU_EBIRST_RESET (1 << 0) /* Bit 0: Reset for EBI */ + +/* PCM_PNRES_SOFT UNIT register, address 0x13004c40 */ + +#define CGU_PCMAPBRST_RESET (1 << 0) /* Bit 0: Reset for APB domain of PCM */ + +/* PCM_RESET_N_SOFT register, address 0x13004c44 */ + +#define CGU_PCMCLKIPRST_RESET (1 << 0) /* Bit 0: Reset for synchronous clk_ip domain of PCM */ + +/* PCM_RESET_ASYNC_N_SOFT register, address 0x13004c48 */ + +#define CGU_PCMRSTASYNC_RESET (1 << 0) /* Bit 0: Reset for asynchronous clk_ip domain of PCM */ + +/* TIMER0_PNRES_SOFT register, address 0x13004c4c */ + +#define CGU_TIMER0RST_RESET (1 << 0) /* Bit 0: Reset for Timer0 */ + +/* TIMER1_PNRES_SOFT register, address 0x13004c50 */ + +#define CGU_TIMER1RST_RESET (1 << 0) /* Bit 0: Reset for Timer1 */ + +/* TIMER2_PNRES_SOFT register, address 0x13004c54 */ + +#define CGU_TIMER2RST_RESET (1 << 0) /* Bit 0: Reset for Timer2 */ + +/* TIMER3_PNRES_SOFT register, address 0x13004c58 */ + +#define CGU_TIMER3RST_RESET (1 << 0) /* Bit 0: Reset for Timer3 */ + +/* ADC_PRESETN_SOFT register, address 0x13004c5c */ + +#define CGU_ADCPRST_RESET (1 << 0) /* Bit 0: Reset for controller of 10 bit ADC Interface */ + +/* ADC_RESETN_ADC10BITS_SOFT register, address 0x1300 4c60 */ + +#define CGU_ADCRST_RESET (1 << 0) /* Bit 0: Reset for A/D converter of ADC Interface */ + +/* PWM_RESET_AN_SOFT register, address 0x13004c64 */ + +#define CGU_PWMRST_RESET (1 << 0) /* Bit 0: Reset for PWM */ + +/* UART_SYS_RST_AN_SOFT register, address 0x13004c68 */ + +#define CGU_UARTRST_RESET (1 << 0) /* Bit 0: Reset for UART/IrDA */ + +/* I2C0_PNRES_SOFT register, address 0x13004c6c */ + +#define CGU_I2C0RST_RESET (1 << 0) /* Bit 0: Reset for I2C0 */ + +/* I2C1_PNRES_SOFT register, address 0x13004c70 */ + +#define CGU_I2C1RST_RESET (1 << 0) /* Bit 0: Reset for I2C1 */ + +/* I2S_CFG_RST_N_SOFT register, address 0x13004c74 */ + +#define CGU_I2SCFGRST_RESET (1 << 0) /* Bit 0: Reset for I2S_Config */ + +/* I2S_NSOF_RST_N_SOFT register, address 0x13004c78 */ + +#define CGU_I2SNSOFRST_RESET (1 << 0) /* Bit 0: Reset for NSOF counter of I2S_CONFIG */ + +/* EDGE_DET_RST_N_SOFT register, address 0x13004c7c */ + +#define CGU_EDGEDETRST_RESET (1 << 0) /* Bit 0: Reset for Edge_det */ + +/* I2STX_FIFO_0_RST_N_SOFT register, address 0x13004c80 */ + +#define CGU_I2STXFF0RST_RESET (1 << 0) /* Bit 0: Reset for I2STX_FIFO_0 */ + +/* I2STX_IF_0_RST_N_SOFT register, address 0x13004c84 */ + +#define CGU_I2STXIF0RST_RESET (1 << 0) /* Bit 0: Reset for I2STX_IF_0 */ + +/* I2STX_FIFO_1_RST_N_SOFT register, address 0x13004c88 */ + +#define CGU_I2STXFF1RST_RESET (1 << 0) /* Bit 0: Reset for I2STX_FIFO_1 */ + +/* I2STX_IF_1_RST_N_SOFT register, address 0x13004c8c */ + +#define CGU_I2STXIF1RST_RESET (1 << 0) /* Bit 0: Reset for I2STX_IF_1 */ + +/* I2SRX_FIFO_0_RST_N_SOFT register, address 0x13004c90 */ + +#define CGU_I2SRXFF0RST_RESET (1 << 0) /* Bit 0: Reset for I2SRX_FIFO_0 */ + +/* I2SRX_IF_0_RST_N_SOFT register, address 0x13004c94 */ + +#define CGU_I2SRXIF0RST_RESET (1 << 0) /* Bit 0: Reset for I2SRX_IF_0 */ + +/* I2SRX_FIFO_1_RST_N_SOFT register, address 0x13004c98 */ + +#define CGU_I2SRXFF1RST_RESET (1 << 0) /* Bit 0: Reset for I2SRX_FIFO_1 */ + +/* I2SRX_IF_1_RST_N_SOFT register, address 0x13004c9c */ + +#define CGU_I2SRXIF1RST_RESET (1 << 0) /* Bit 0: Reset for I2SRX_IF_1 */ + +/* LCD_PNRES_SOFT register, address 0x13004cB4 */ + +#define CGU_LCDRST_RESET (1 << 0) /* Bit 0: Reset for LCD Interface */ + +/* SPI_PNRES_APB_SOFT register, address 0x13004cb8 */ + +#define CGU_SPIRSTAPB_RESET (1 << 0) /* Bit 0: Reset register for apb_clk domain of SPI */ + +/* SPI_PNRES_IP_SOFT register, address 0x13004cbc */ + +#define CGU_SPIRSTIP_RESET (1 << 0) /* Bit 0: Reset for ip_clk domain of SPI */ + +/* DMA_PNRES_SOFT register, address 0x13004cc0 */ + +#define CGU_DMARST_RESET (1 << 0) /* Bit 0: Reset for DMA */ + +/* NANDFLASH_CTRL_ECC_RESET_N_SOFT register, address 0x13004cc4 */ + +#define CGU_NANDECCRST_RESET (1 << 0) /* Bit 0: Reset for ECC clock domain of Nandflash Controller */ + +/* NANDFLASH_CTRL_NAND_RESET_N_SOFT register, address 0x13004ccc */ + +#define CGU_NANDCTRLRST_RESET (1 << 0) /* Bit 0: Reset for Nandflash Controller */ + +/* SD_MMC_PNRES_SOFT register, address 0x13004cd4 */ + +#define CGU_SDMMCRST_RESET (1 << 0) /* Bit 0: Reset for MCI synchronous with AHB clock */ + +/* SD_MMC_NRES_CCLK_IN_SOFT register, address 0x1300 4cd8 */ + +#define CGU_SDMMCRSTCKIN_RESET (1 << 0) /* Bit 0: Reset register for MCI synchronous with IP clock */ + +/* USB_OTG_AHB_RST_N_SOFT, address 0x13004cdc */ + +#define CGU_USBOTGAHBRST_RESET (1 << 0) /* Bit 0: Reset for USB_OTG */ + +/* RED_CTL_RESET_N_SOFT, address 0x13004ce0 */ + +#define CGU_REDCTLRST_RESET (1 << 0) /* Bit 0: Reset for Redundancy Controller */ + +/* AHB_MPMC_HRESETN_SOFT, address 0x13004ce4 */ + +#define CGU_AHBMPMCHRST_RESET (1 << 0) /* Bit 0: Reset for MPMC */ + +/* AHB_MPMC_REFRESH_RESETN_SOFT, address 0x13004ce8 */ + +#define CGU_AHBMPMCRFRST_RESET (1 << 0) /* Bit 0: Reset for refresh generator used for MPMC */ + +/* INTC_RESETN_SOFT, address 0x13004cec */ + +#define CGU_INTCRST_RESET (1 << 0) /* Bit 0: Reset for Interrupt Controller */ + +/* PLL control registers */ +/* HP0 Frequency Input Select register HP0_FIN_SELECT, address 0x13004cf0, + * HP1 Frequency Input Select register HP1_FIN_SELECT, address 0x13004d28 + */ + +#define CGU_HPFINSEL_SHIFT (0) /* Bits 0-3: Select input to high HPPLL0 */ +#define CGU_HPFINSEL_MASK (15 << CGU_HPFINSEL_SHIFT) +# define CGU_HPFINSEL_FFAST (CGU_FREQIN_FFAST << CGU_HPFINSEL_SHIFT) /* ffast (12 Mhz) */ +# define CGU_HPFINSEL_I2SRXBCK0 (CGU_FREQIN_I2SRXBCK0 << CGU_HPFINSEL_SHIFT) /* I2SRX_BCK0 */ +# define CGU_HPFINSEL_I2SRXWS0 (CGU_FREQIN_I2SRXWS0 << CGU_HPFINSEL_SHIFT) /* I2SRX_WS0 */ +# define CGU_HPFINSEL_I2SRXBCK1 (CGU_FREQIN_I2SRXBCK1 << CGU_HPFINSEL_SHIFT) /* I2SRX_BCK1 */ +# define CGU_HPFINSEL_I2SRXWS1 (CGU_FREQIN_I2SRXWS1 << CGU_HPFINSEL_SHIFT) /* I2SRX_WS1 */ +# define CGU_HPFINSEL_HP0FOUT (CGU_FREQIN_HPPLL0 << CGU_HPFINSEL_SHIFT) /* HP0_FOUT */ +# define CGU_HPFINSEL_HP1FOUT (CGU_FREQIN_HPPLL1 << CGU_HPFINSEL_SHIFT) /* HP1_FOUT */ + +/* HP0 M-divider register HP0_MDEC, address 0x13004cF4, + * HP1 M-divider register HP1_MDEC, address 0x13004d2C + */ + +#define CGU_HPMDEC_SHIFT (0) /* Bits 0-16: Decoded divider ratio for M-divider */ +#define CGU_HPMDEC_MASK (0x1ffff << CGU_HPMDEC_SHIFT) + +/* HP0 N-divider register HP0_NDEC, address 0x13004cf8, + * HP1 N-divider register HP1_NDEC, address 0x13004D30 + */ + +#define CGU_HPNDEC_SHIFT (0) /* Bits 0-9: Decoded divider ratio for N-divider */ +#define CGU_HPNDEC_MASK (0x3ff << CGU_HPNDEC_SHIFT) + +/* HP0 P-divider register HP0_PDEC, address 0x13004cfc. + * HP1 P-divider register HP1_PDEC, address 0x13004D34 + */ + +#define CGU_HPPDEC_SHIFT (0) /* Bits 0-6: Decoded divider ratio for P-divider */ +#define CGU_HPPDEC_MASK (0x7F << CGU_HPPDEC_SHIFT) + +/* HP0 Mode register HP0_MODE, address 0x13004d00, + * HP1 Mode register HP1_MODE, address 0x13004d38 + */ + +#define CGU_HPMODE_BYPASS (1 << 8) /* Bit 8: Bypass mode */ +#define CGU_HPMODE_LIMUPOFF (1 << 7) /* Bit 7: Up limiter */ +#define CGU_HPMODE_BANDSEL (1 << 6) /* Bit 6: Bandwidth adjustment pin */ +#define CGU_HPMODE_FRM (1 << 5) /* Bit 5: Free Running Mode */ +#define CGU_HPMODE_DIRECTI (1 << 4) /* Bit 4: Normal operation with DIRECTO */ +#define CGU_HPMODE_DIRECTO (1 << 3) /* Bit 3: Normal operation with DIRECTI */ +#define CGU_HPMODE_PD (1 << 2) /* Bit 2: Power down mode */ +#define CGU_HPMODE_SKEWEN (1 << 1) /* Bit 1: Skew mode */ +#define CGU_HPMODE_CLKEN (1 << 0) /* Bit 0: Enable mode */ + +/* HP0 Status register HP0_STATUS, address 0x13004d04, + * HP1 Status register HP1_STATUS, address 0x13004d3c + */ + +#define CGU_HPSTATUS_FR (1 << 1) /* Bit 1: Free running detector */ +#define CGU_HPSTATUS_LOCK (1 << 0) /* Bit 0: Lock detector */ + +/* HP0 Acknowledge register HP0_ACK, address 0x13004d08, + * HP1 Acknowledge register HP1_ACK, address 0x13004d40 + */ + +#define CGU_HPACK_P (1 << 2) /* Bit 2: Post-divider ratio change acknowledge */ +#define CGU_HPACK_N (1 << 1) /* Bit 1: Pre-divider ratio change acknowledge */ +#define CGU_HPACK_M (1 << 0) /* Bit 0: Feedback divider ratio change acknowledge */ + +/* HP0 request register HP0_REQ, address 0x13004d0c, + * HP1 Request register HP1_REQ, address 0x13004d44 + */ + +#define CGU_HPREQ_P (1 << 2) /* Bit 2: Post-divider ratio change request */ +#define CGU_HPREQ_N (1 << 1) /* Bit 1: Pre-divider ratio change request */ +#define CGU_HPREQ_M (1 << 0) /* Bit 0: Feedback divider ratio change request */ + +/* HP0 Bandwith Selection register HP0_INSELR, address 0x13004d10, + * HP1 bandwith Selection register HP1_INSELR, address 0x13004d48 + */ + +#define CGU_HPINSELR_SHIFT (0) /* Bits 0-3: Pins to select the bandwidth */ +#define CGU_HPINSELR_MASK (15 << CGU_HPINSELR_SHIFT) + +/* HP0 Bandwith Selection register HP0_INSELI, address 0x13004d14, + * HP1 bandwith Selection register HP1_INSELI, address 0x13004d4c + */ + +#define CGU_HPINSELI_SHIFT (0) /* Bits 0-5: Bandwidth selection register of HP0/1 PLL */ +#define CGU_HPINSELI_MASK (63 << CGU_HPINSELI_SHIFT) + + +/* HP0 Bandwith Selection register HP0_INSELP, address 0x13004d18, + * HP1 bandwith Selection register HP1_INSELP, address 0x13004d50 + */ + +#define CGU_HPINSELP_SHIFT (0) /* Bits 0-4: Bandwidth selection register of HP0/1 PLL */ +#define CGU_HPINSELP_MASK (31 << CGU_HPINSELP_SHIFT) + +/* HP0 Bandwith Selection register HP0_SELR, address 0x13004d1c, + * HP1 bandwith Selection register HP1_SELR, address 0x13004d54 + */ + +#define CGU_HPSELR_SHIFT (0) /* Bits 0-3: Bandwidth selection register of HP0/1 PLL */ +#define CGU_HPSELR_MASK (15 << CGU_HPSELR_SHIFT) + +/* HP0 Bandwith Selection register HP0_SELI, address 0x13004d20 + * HP1 bandwith Selection register HP1_SELI, address 0x13004d58 + */ + +#define CGU_HPSELI_SHIFT (0) /* Bits 0-5: Bandwidth selection register of HP0/1 PLL */ +#define CGU_HPSELI_MASK (63 << CGU_HPSELI_SHIFT) + +/* HP0 Bandwith Selection register HP0_SELP, address 0x13004d24, + * HP1 bandwith Selection register HP1_SELP, address 0x13004d5c + */ + +#define CGU_HPSELP_SHIFT (0) /* Bits 0-4: Bandwidth selection register of HP0/1 PLL */ +#define CGU_HPIELP_MASK (31 << CGU_HPSELP_SHIFT) + +/************************************************************************************************ + * Public Types + ************************************************************************************************/ + +#ifndef __ASSEMBLY__ + +/************************************************************************************************ + * Public Data + ************************************************************************************************/ + +/************************************************************************************************ + * Inline Functions + ************************************************************************************************/ + +/************************************************************************************************ + * Public Functions + ************************************************************************************************/ + +#endif /* __ASSEMBLY__ */ +#endif /* __ARCH_ARM_SRC_LPC31XX_LPC31_CGU_H */ diff --git a/nuttx/arch/arm/src/lpc31xx/lpc31_cgudrvr.h b/nuttx/arch/arm/src/lpc31xx/lpc31_cgudrvr.h new file mode 100755 index 000000000..fc589c893 --- /dev/null +++ b/nuttx/arch/arm/src/lpc31xx/lpc31_cgudrvr.h @@ -0,0 +1,819 @@ +/************************************************************************ + * arch/arm/src/lpc31xx/lpc31_cgudrvr.h + * + * Copyright (C) 2009-2010 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * References: + * - NXP UM10314 LPC3130/31 User manual Rev. 1.01 — 9 September 2009 + * - NXP lpc313x.cdl.drivers.zip example driver code + * + * 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_LPC31XX_LPC31_CGUDRVR_H +#define __ARCH_ARM_SRC_LPC31XX_LPC31_CGUDRVR_H + +/************************************************************************ + * Included Files + ************************************************************************/ + +#include + +#include +#include + +#include "up_arch.h" +#include "lpc31_cgu.h" + +/************************************************************************ + * Pre-processor Definitions + ************************************************************************/ + +/* Maps a valid, x, relative to a base value, b, and converts that to a bit position */ + +#define _RBIT(x,b) (1<<((x)-(b))) + +/* Clock ID ranges (see enum lpc31_clockid_e) *************************************************/ + +#define CLKID_FIRST CLKID_APB0CLK +#define CLKID_SYSBASE_FIRST CLKID_APB0CLK /* Domain 0: SYS_BASE */ +#define CLKID_SYSBASE_LAST CLKID_INTCCLK +#define _D0B(id) _RBIT(id,CLKID_SYSBASE_FIRST) + +#define CLKID_AHB0APB0_FIRST CLKID_AHB2APB0PCLK /* Domain 1: AHB0APB0_BASE */ +#define CLKID_AHB0APB0_LAST CLKID_RNGPCLK +#define _D1B(id) _RBIT(id,CLKID_AHB0APB0_FIRST) + +#define CLKID_AHB0APB1_FIRST CLKID_AHB2APB1PCLK /* Domain 2: AHB0APB1_BASE */ +#define CLKID_AHB0APB1_LAST CLKID_I2C1PCLK +#define _D2B(id) _RBIT(id,CLKID_AHB0APB1_FIRST) + +#define CLKID_AHB0APB2_FIRST CLKID_AHB2APB2PCLK /* Domain 3: AHB0APB2_BASE */ +#define CLKID_AHB0APB2_LAST CLKID_SPIPCLKGATED +#define _D3B(id) _RBIT(id,CLKID_AHB0APB2_FIRST) + +#define CLKID_AHB0APB3_FIRST CLKID_AHB2APB3PCLK /* Domain 4: AHB0APB3_BASE */ +#define CLKID_AHB0APB3_LAST CLKID_RESERVED70 +#define _D4B(id) _RBIT(id,CLKID_AHB0APB3_FIRST) + +#define CLKID_PCM_FIRST CLKID_PCMCLKIP /* Domain 5: PCM_BASE */ +#define CLKID_PCM_LAST CLKID_PCMCLKIP +#define _D5B(id) _RBIT(id,CLKID_PCM_FIRST) + +#define CLKID_UART_FIRST CLKID_UARTUCLK /* Domain 6: UART_BASE */ +#define CLKID_UART_LAST CLKID_UARTUCLK +#define _D6B(id) _RBIT(id,CLKID_UART_FIRST) + +#define CLKID_CLK1024FS_FIRST CLKID_I2SEDGEDETECTCLK /* Domain 7: CLK1024FS_BASE */ +#define CLKID_CLK1024FS_LAST CLKID_RESERVED86 +#define _D7B(id) _RBIT(id,CLKID_CLK1024FS_FIRST) + +#define CLKID_I2SRXBCK0_FIRST CLKID_I2SRXBCK0 /* Domain 8: BCK0_BASE */ +#define CLKID_I2SRXBCK0_LAST CLKID_I2SRXBCK0 +#define _D8B(id) _RBIT(id,CLKID_I2SRXBCK0_FIRST) + +#define CLKID_I2SRXBCK1_FIRST CLKID_I2SRXBCK1 /* Domain 9: BCK1_BASE */ +#define CLKID_I2SRXBCK1_LAST CLKID_I2SRXBCK1 +#define _D9B(id) _RBIT(id,CLKID_SYSBASE_FIRST) + +#define CLKID_SPI_FIRST CLKID_SPICLK /* Domain 10: SPI_BASE */ +#define CLKID_SPI_LAST CLKID_SPICLKGATED +#define _D10B(id) _RBIT(id,CLKID_I2SRXBCK1_FIRST) + +#define CLKID_SYSCLKO_FIRST CLKID_SYSCLKO /* Domain 11: SYSCLKO_BASE */ +#define CLKID_SYSCLKO_LAST CLKID_SYSCLKO +#define _D11B(id) _RBIT(id,CLKID_SYSCLKO_FIRST) +#define CLKID_LAST CLKID_SYSCLKO + +#define CGU_NDOMAINS 12 /* The number of clock domains */ +#define CLKID_INVALIDCLK -1 /* Indicates and invalid clock ID */ +#define DOMAINID_INVALID -1 /* Indicates an invalid domain ID */ +#define ESRNDX_INVALID -1 /* Indicates an invalid ESR register index */ +#define BCRNDX_INVALID -1 /* Indicates an invalid BCR register index */ + +/* There are 24 fractional dividers, indexed 0 to 23. The following definitions + * provide (1) the number of fractional dividers available for each base frequency, + * (2) start and end indices, and (3) extraction info for sub elements from the + * fractional divider configuration register + */ + +#define FRACDIV_BASE0_CNT 7 /* 7 fractional dividers available */ +#define FRACDIV_BASE0_LOW 0 /* First is index 0 */ +#define FRACDIV_BASE0_HIGH 6 /* Last is index 6 */ +#define FRACDIV_BASE0_FDIV0W 8 + +#define FRACDIV_BASE1_CNT 2 /* 2 fractional dividers available */ +#define FRACDIV_BASE1_LOW 7 /* First is index 7 */ +#define FRACDIV_BASE1_HIGH 8 /* Last is index 8 */ +#define FRACDIV_BASE1_FDIV0W 8 + +#define FRACDIV_BASE2_CNT 2 /* 2 fractional dividers available */ +#define FRACDIV_BASE2_LOW 9 /* First is index 9 */ +#define FRACDIV_BASE2_HIGH 10 /* Last is index 10 */ +#define FRACDIV_BASE2_FDIV0W 8 + +#define FRACDIV_BASE3_CNT 3 /* 3 fractional dividers available */ +#define FRACDIV_BASE3_LOW 11 /* First is index 11 */ +#define FRACDIV_BASE3_HIGH 13 /* Last is index 12 */ +#define FRACDIV_BASE3_FDIV0W 8 + +#define FRACDIV_BASE4_CNT 1 /* 1 fractional divider available */ +#define FRACDIV_BASE4_LOW 14 /* First is index 14 */ +#define FRACDIV_BASE4_HIGH 14 /* Last is index 14 */ +#define FRACDIV_BASE4_FDIV0W 8 + +#define FRACDIV_BASE5_CNT 1 /* 1 fractional divider available */ +#define FRACDIV_BASE5_LOW 15 /* First is index 15 */ +#define FRACDIV_BASE5_HIGH 15 /* Last is index 15 */ +#define FRACDIV_BASE5_FDIV0W 8 + +#define FRACDIV_BASE6_CNT 1 /* 1 fractional divider available */ +#define FRACDIV_BASE6_LOW 16 /* First is index 16 */ +#define FRACDIV_BASE6_HIGH 16 /* Last is index 16 */ +#define FRACDIV_BASE6_FDIV0W 8 + +#define FRACDIV_BASE7_CNT 6 /* 6 fractional dividers available */ +#define FRACDIV_BASE7_LOW 17 /* First is index 17 */ +#define FRACDIV_BASE7_HIGH 22 /* Last is index 22 */ +#define FRACDIV_BASE7_FDIV0W 13 + +#define FRACDIV_BASE8_CNT 0 /* No fractional divider available */ +#define FRACDIV_BASE9_CNT 0 /* No fractional divider available */ + +#define FRACDIV_BASE10_CNT 1 /* 1 fractional divider available */ +#define FRACDIV_BASE10_LOW 23 /* First is index 23 */ +#define FRACDIV_BASE10_HIGH 23 /* Last is index 23 */ +#define FRACDIV_BASE10_FDIV0W 8 + +#define FRACDIV_BASE11_CNT 0 /* No fractional divider available */ + +#define CGU_NFRACDIV 24 /* Number of fractional dividers: 0-23 */ +#define CGU_NDYNFRACDIV 7 /* Number of dynamic fractional dividers: 0-6 */ +#define FDCNDX_INVALID -1 /* Indicates an invalid fractional + * divider index */ + +/************************************************************************ + * Public Types + ************************************************************************/ + +#ifndef __ASSEMBLY__ +#ifdef __cplusplus +#define EXTERN extern "C" +extern "C" { +#else +#define EXTERN extern +#endif + +/* Clock domains */ + +enum lpc31_domainid_e +{ + DOMAINID_SYS = 0, /* Domain 0: SYS_BASE */ + DOMAINID_AHB0APB0, /* Domain 1: AHB0APB0_BASE */ + DOMAINID_AHB0APB1, /* Domain 2: AHB0APB1_BASE */ + DOMAINID_AHB0APB2, /* Domain 3: AHB0APB2_BASE */ + DOMAINID_AHB0APB3, /* Domain 4: AHB0APB3_BASE */ + DOMAINID_PCM, /* Domain 5: PCM_BASE */ + DOMAINID_UART, /* Domain 6: UART_BASE */ + DOMAINID_CLK1024FS, /* Domain 7: CLK1024FS_BASE */ + DOMAINID_BCK0, /* Domain 8: BCK0_BASE */ + DOMAINID_BCK1, /* Domain 9: BCK1_BASE */ + DOMAINID_SPI, /* Domain 10: SPI_BASE */ + DOMAINID_SYSCLKO /* Domain 11: SYSCLKO_BASE */ +}; + +/* Clock IDs -- These are indices must correspond to the register + * offsets in lpc31_cgu.h + */ + +enum lpc31_clockid_e +{ + /* Domain 0: SYS_BASE */ + + CLKID_APB0CLK = 0, /* 0 APB0_CLK */ + CLKID_APB1CLK, /* 1 APB1_CLK */ + CLKID_APB2CLK, /* 2 APB2_CLK */ + CLKID_APB3CLK, /* 3 APB3_CLK */ + CLKID_APB4CLK, /* 4 APB4_CLK */ + CLKID_AHB2INTCCLK, /* 5 AHB_TO_INTC_CLK */ + CLKID_AHB0CLK, /* 6 AHB0_CLK */ + CLKID_EBICLK, /* 7 EBI_CLK */ + CLKID_DMAPCLK, /* 8 DMA_PCLK */ + CLKID_DMACLKGATED, /* 9 DMA_CLK_GATED */ + CLKID_NANDFLASHS0CLK, /* 10 NANDFLASH_S0_CLK */ + CLKID_NANDFLASHECCCLK, /* 11 NANDFLASH_ECC_CLK */ + CLKID_NANDFLASHAESCLK, /* 12 NANDFLASH_AES_CLK (Reserved on LPC313x) */ + CLKID_NANDFLASHNANDCLK, /* 13 NANDFLASH_NAND_CLK */ + CLKID_NANDFLASHPCLK, /* 14 NANDFLASH_PCLK */ + CLKID_CLOCKOUT, /* 15 CLOCK_OUT */ + CLKID_ARM926CORECLK, /* 16 ARM926_CORE_CLK */ + CLKID_ARM926BUSIFCLK, /* 17 ARM926_BUSIF_CLK */ + CLKID_ARM926RETIMECLK, /* 18 ARM926_RETIME_CLK */ + CLKID_SDMMCHCLK, /* 19 SD_MMC_HCLK */ + CLKID_SDMMCCCLKIN, /* 20 SD_MMC_CCLK_IN */ + CLKID_USBOTGAHBCLK, /* 21 USB_OTG_AHB_CLK */ + CLKID_ISRAM0CLK, /* 22 ISRAM0_CLK */ + CLKID_REDCTLRSCLK, /* 23 RED_CTL_RSCLK */ + CLKID_ISRAM1CLK, /* 24 ISRAM1_CLK (LPC313x only) */ + CLKID_ISROMCLK, /* 25 ISROM_CLK */ + CLKID_MPMCCFGCLK, /* 26 MPMC_CFG_CLK */ + CLKID_MPMCCFGCLK2, /* 27 MPMC_CFG_CLK2 */ + CLKID_MPMCCFGCLK3, /* 28 MPMC_CFG_CLK3 */ + CLKID_INTCCLK, /* 29 INTC_CLK */ + + /* Domain 1: AHB0APB0_BASE */ + + CLKID_AHB2APB0PCLK, /* 30 AHB_TO_APB0_PCLK */ + CLKID_EVENTROUTERPCLK, /* 31 EVENT_ROUTER_PCLK */ + CLKID_ADCPCLK, /* 32 ADC_PCLK */ + CLKID_ADCCLK, /* 33 ADC_CLK */ + CLKID_WDOGPCLK, /* 34 WDOG_PCLK */ + CLKID_IOCONFPCLK, /* 35 IOCONF_PCLK */ + CLKID_CGUPCLK, /* 36 CGU_PCLK */ + CLKID_SYSCREGPCLK, /* 37 SYSCREG_PCLK */ + CLKID_OTPPCLK, /* 38 OTP_PCLK (Reserved on LPC313X) */ + CLKID_RNGPCLK, /* 39 RNG_PCLK */ + + /* Domain 2: AHB0APB1_BASE */ + + CLKID_AHB2APB1PCLK, /* 40 AHB_TO_APB1_PCLK */ + CLKID_TIMER0PCLK, /* 41 TIMER0_PCLK */ + CLKID_TIMER1PCLK, /* 42 TIMER1_PCLK */ + CLKID_TIMER2PCLK, /* 43 TIMER2_PCLK */ + CLKID_TIMER3PCLK, /* 44 TIMER3_PCLK */ + CLKID_PWMPCLK, /* 45 PWM_PCLK */ + CLKID_PWMPCLKREGS, /* 46 PWM_PCLK_REGS */ + CLKID_PWMCLK, /* 47 PWM_CLK */ + CLKID_I2C0PCLK, /* 48 I2C0_PCLK */ + CLKID_I2C1PCLK, /* 49 I2C1_PCLK */ + + /* Domain 3: AHB0APB2_BASE */ + + CLKID_AHB2APB2PCLK, /* 50 AHB_TO_APB2_PCLK */ + CLKID_PCMPCLK, /* 51 PCM_PCLK */ + CLKID_PCMAPBPCLK, /* 52 PCM_APB_PCLK */ + CLKID_UARTAPBCLK, /* 53 UART_APB_CLK */ + CLKID_LCDPCLK, /* 54 LCD_PCLK */ + CLKID_LCDCLK, /* 55 LCD_CLK */ + CLKID_SPIPCLK, /* 56 SPI_PCLK */ + CLKID_SPIPCLKGATED, /* 57 SPI_PCLK_GATED */ + + /* Domain 4: AHB0APB3BASE */ + CLKID_AHB2APB3PCLK, /* 58 AHB_TO_APB3_PCLK */ + CLKID_I2SCFGPCLK, /* 59 I2S_CFG_PCLK */ + CLKID_EDGEDETPCLK, /* 60 EDGE_DET_PCLK */ + CLKID_I2STXFIFO0PCLK, /* 61 I2STX_FIFO_0_PCLK */ + CLKID_I2STXIF0PCLK, /* 62 I2STX_IF_0_PCLK */ + CLKID_I2STXFIFO1PCLK, /* 63 I2STX_FIFO_1_PCLK */ + CLKID_I2STXIF1PCLK, /* 64 I2STX_IF_1_PCLK */ + CLKID_I2SRXFIFO0PCLK, /* 65 I2SRX_FIFO_0_PCLK */ + CLKID_I2SRXIF0PCLK, /* 66 I2SRX_IF_0_PCLK */ + CLKID_I2SRXFIFO1PCLK, /* 67 I2SRX_FIFO_1_PCLK */ + CLKID_I2SRXIF1PCLK, /* 68 I2SRX_IF_1_PCLK */ + CLKID_RESERVED69, /* 69 Reserved */ + CLKID_RESERVED70, /* 70 Reserved */ + + /* Domain 5: PCM_BASE */ + + CLKID_PCMCLKIP, /* 71 PCM_CLK_IP */ + + /* Domain 6: UART_BASE */ + + CLKID_UARTUCLK, /* 72 UART_U_CLK */ + + /* Domain 7: CLK1024FS_BASE */ + + CLKID_I2SEDGEDETECTCLK, /* 73 I2S_EDGE_DETECT_CLK */ + CLKID_I2STXBCK0N, /* 74 I2STX_BCK0_N */ + CLKID_I2STXWS0, /* 75 I2STX_WS0 */ + CLKID_I2STXCLK0, /* 76 I2STX_CLK0 */ + CLKID_I2STXBCK1N, /* 77 I2STX_BCK1_N */ + CLKID_I2STXWS1, /* 78 I2STX_WS1 */ + CLKID_CLK256FS, /* 79 CLK_256FS */ + CLKID_I2SRXBCK0N, /* 80 I2SRX_BCK0_N */ + CLKID_I2SRXWS0, /* 81 I2SRX_WS0 */ + CLKID_I2SRXBCK1N, /* 82 I2SRX_BCK1_N */ + CLKID_I2SRXWS1, /* 83 I2SRX_WS1 */ + CLKID_RESERVED84, /* 84 Reserved */ + CLKID_RESERVED85, /* 85 Reserved */ + CLKID_RESERVED86, /* 86 Reserved */ + + /* Domain 8: BCK0_BASE */ + + CLKID_I2SRXBCK0, /* 87 I2SRX_BCK0 */ + + /* Domain 9: BCK1_BASE */ + + CLKID_I2SRXBCK1, /* 88 I2SRX_BCK1 */ + + /* Domain 10: SPI_BASE */ + + CLKID_SPICLK, /* 89 SPI_CLK */ + CLKID_SPICLKGATED, /* 90 SPI_CLK_GATED */ + + /* Domain 11: SYSCLKO_BASE */ + + CLKID_SYSCLKO /* 91 SYSCLK_O */ +}; + +/* Indices into the CGU configuration reset control registers */ + +enum lpc31_resetid_e +{ + RESETID_APB0RST, /* 0 AHB part of AHB_TO_APB0 bridge (Reserved) */ + RESETID_AHB2APB0RST, /* 1 APB part of AHB_TO_APB0 bridge (Reserved) */ + RESETID_APB1RST, /* 2 AHB part of AHB_TO_APB1 bridge */ + RESETID_AHB2PB1RST, /* 3 APB part of AHB_TO_APB1 bridge */ + RESETID_APB2RST, /* 4 AHB part of AHB_TO_APB2 bridge */ + RESETID_AHB2APB2RST, /* 5 APB part of AHB_TO_APB2 bridge */ + RESETID_APB3RST, /* 6 AHB part of AHB_TO_APB3 bridge */ + RESETID_AHB2APB3RST, /* 7 APB part of AHB_TO_APB3 bridge */ + RESETID_APB4RST, /* 8 AHB_TO_APB4 bridge */ + RESETID_AHB2INTCRST, /* 9 AHB_TO_INTC */ + RESETID_AHB0RST, /* 10 AHB0 */ + RESETID_EBIRST, /* 11 EBI */ + RESETID_PCMAPBRST, /* 12 APB domain of PCM */ + RESETID_PCMCLKIPRST, /* 13 synchronous clk_ip domain of PCM */ + RESETID_PCMRSTASYNC, /* 14 asynchronous clk_ip domain of PCM */ + RESETID_TIMER0RST, /* 15 Timer0 */ + RESETID_TIMER1RST, /* 16 Timer1 */ + RESETID_TIMER2RST, /* 17 Timer2 */ + RESETID_TIMER3RST, /* 18 Timer3 */ + RESETID_ADCPRST, /* 19 controller of 10 bit ADC Interface */ + RESETID_ADCRST, /* 20 A/D converter of ADC Interface */ + RESETID_PWMRST, /* 21 PWM */ + RESETID_UARTRST, /* 22 UART/IrDA */ + RESETID_I2C0RST, /* 23 I2C0 */ + RESETID_I2C1RST, /* 24 I2C1 */ + RESETID_I2SCFGRST, /* 25 I2S_Config */ + RESETID_I2SNSOFRST, /* 26 NSOF counter of I2S_CONFIG */ + RESETID_EDGEDETRST, /* 27 Edge_det */ + RESETID_I2STXFF0RST, /* 28 I2STX_FIFO_0 */ + RESETID_I2STXIF0RST, /* 29 I2STX_IF_0 */ + RESETID_I2STXFF1RST, /* 30 I2STX_FIFO_1 */ + RESETID_I2STXIF1RST, /* 31 I2STX_IF_1 */ + RESETID_I2SRXFF0RST, /* 32 I2SRX_FIFO_0 */ + RESETID_I2SRXIF0RST, /* 33 I2SRX_IF_0 */ + RESETID_I2SRXFF1RST, /* 34 I2SRX_FIFO_1 */ + RESETID_I2SRXIF1RST, /* 35 I2SRX_IF_1 */ + RESETID_RESERVED40, /* 36 Reserved */ + RESETID_RESERVED41, /* 37 Reserved */ + RESETID_RESERVED42, /* 38 Reserved */ + RESETID_RESERVED43, /* 39 Reserved */ + RESETID_RESERVED44, /* 40 Reserved */ + RESETID_LCDRST, /* 41 LCD Interface */ + RESETID_SPIRSTAPB, /* 42 apb_clk domain of SPI */ + RESETID_SPIRSTIP, /* 43 ip_clk domain of SPI */ + RESETID_DMARST, /* 44 DMA */ + RESETID_NANDECCRST, /* 45 Nandflash Controller ECC clock */ + RESETID_NANDAESRST, /* 46 Nandflash Controller AES clock (reserved for lpc313x) */ + RESETID_NANDCTRLRST, /* 47 Nandflash Controller */ + RESETID_RNG, /* 48 RNG */ + RESETID_SDMMCRST, /* 49 MCI (on AHB clock) */ + RESETID_SDMMCRSTCKIN, /* 50 CI synchronous (on IP clock) */ + RESETID_USBOTGAHBRST, /* 51 USB_OTG */ + RESETID_REDCTLRST, /* 52 Redundancy Controller */ + RESETID_AHBMPMCHRST, /* 53 MPMC */ + RESETID_AHBMPMCRFRST, /* 54 refresh generator used for MPMC */ + RESETID_INTCRST, /* 55 Interrupt Controller */ +}; + +/* This structure describes one CGU fractional divider configuration */ + +struct lpc31_fdivconfig_s +{ + uint8_t stretch; /* Fractional divider stretch enable. */ + uint8_t n; /* Fractional divider nominal nominator */ + uint16_t m; /* Fractional divider nominal denominator */ +}; + +/* The structure describes the configuration of one CGU sub-domain */ + +struct lpc31_subdomainconfig_s +{ + struct lpc31_fdivconfig_s fdiv; /* Fractional divider settings */ + uint32_t clkset; /* Bitset of all clocks in the sub-domain */ +}; + +/* CGU clock initilization structure. Describes the platform-specific + * configuration of every clock domain. + */ + +struct lpc31_clkinit_s +{ + struct + { + uint8_t finsel; + struct lpc31_subdomainconfig_s sub[FRACDIV_BASE0_CNT]; + } domain0; + + struct + { + uint8_t finsel; + struct lpc31_subdomainconfig_s sub[FRACDIV_BASE1_CNT]; + } domain1; + + struct + { + uint8_t finsel; + struct lpc31_subdomainconfig_s sub[FRACDIV_BASE2_CNT]; + } domain2; + + struct + { + uint8_t finsel; + struct lpc31_subdomainconfig_s sub[FRACDIV_BASE3_CNT]; + } domain3; + + struct + { + uint8_t finsel; + struct lpc31_subdomainconfig_s sub[FRACDIV_BASE4_CNT]; + } domain4; + + struct + { + uint8_t finsel; + struct lpc31_subdomainconfig_s sub[FRACDIV_BASE5_CNT]; + } domain5; + + struct + { + uint8_t finsel; + struct lpc31_subdomainconfig_s sub[FRACDIV_BASE6_CNT]; + } domain6; + + struct + { + uint8_t finsel; + struct lpc31_subdomainconfig_s sub[FRACDIV_BASE7_CNT]; + } domain7; + + struct + { + uint8_t finsel; + } domain8; + + struct + { + uint8_t finsel; + } domain9; + + struct + { + uint8_t finsel; + struct lpc31_subdomainconfig_s sub[FRACDIV_BASE10_CNT]; + } domain10; + + struct + { + uint8_t finsel; + } domain11; + +#if 0 /* Dynamic fractional divider initialization not implemented */ + struct + { + uint16_t sel; + struct lpc31_fdivconfig_s cfg; + } dynfdiv[CGU_NDYNFRACDIV]; +#endif +}; + +/* This structure is used to pass PLL configuration data to + * lpc31_pllconfig() + */ + +struct lpc31_pllconfig_s +{ + uint8_t hppll; /* PLL selection: 0=HPLL0 1=HPLL1 */ + uint8_t pdec; /* PLL P-divider value: 0-0x7f */ + uint8_t selr; /* SELR bandwidth selection: 0-15 */ + uint8_t seli; /* SELI bandwidth selection: 0-63 */ + uint8_t selp; /* SELP bandwidth selection: 0-31 */ + uint16_t ndec; /* PLL N-divider value: 0-0x3ff */ + uint16_t mode; /* PLL mode: 9-bits */ + uint32_t freq; /* Frequency of the PLL in MHz */ + uint32_t finsel; /* Frequency input selection: CGU_HPFINSEL_* */ + uint32_t mdec; /* PLL M-divider value: 0-0x1ffff */ +}; + +/************************************************************************ + * Public Data + ************************************************************************/ + +/* This array is managed by the chip-specific logic and provides the + * programmed frequency of every input source + */ + +EXTERN uint32_t g_boardfreqin[CGU_NFREQIN]; + +/* This instance of the lpc31_clkinit_s structure provides the initial, + * default clock configuration for the board. Every board must provide + * an implementation of g_boardclks. This rather complex structure is + * used by the boot-up logic to configure initial lpc31xx clocking. + */ + +EXTERN const struct lpc31_clkinit_s g_boardclks; + +/************************************************************************ + * Inline Functions + ************************************************************************/ + +/************************************************************************ + * Name: lpc31_getbasefreq + * + * Description: + * Return the base frequency associated with a clock domain + * + ************************************************************************/ + +static inline uint32_t lpc31_getbasefreq(enum lpc31_domainid_e dmnid) +{ + uint32_t regval; + int ndx; + + /* Fetch the SSR register associated with this clock domain */ + + regval = getreg32(LPC31_CGU_SSR((int)dmnid)); + + /* Extract the last frequency input selection */ + + ndx = (regval & CGU_SSR_FS_MASK) >> CGU_SSR_FS_SHIFT; + + /* And return the user-supplied value for that frequency input */ + + return g_boardfreqin[ndx]; +} + +/************************************************************************ + * Name: lpc31_enableclock + * + * Description: + * Enable the specified clock + * + ************************************************************************/ + +static inline void lpc31_enableclock(enum lpc31_clockid_e clkid) +{ + uint32_t address = LPC31_CGU_PCR((int)clkid); + uint32_t regval = getreg32(address); + + regval |= CGU_PCR_RUN; + putreg32(regval, address); +} + +/************************************************************************ + * Name: lpc31_disableclock + * + * Description: + * Disable the specified clock + * + ************************************************************************/ + +static inline void lpc31_disableclock(enum lpc31_clockid_e clkid) +{ + uint32_t address = LPC31_CGU_PCR((int)clkid); + uint32_t regval = getreg32(address); + + regval &= ~CGU_PCR_RUN; + putreg32(regval, address); +} + +/************************************************************************ + * Public Functions + ************************************************************************/ + +/**************************************************************************** + * Name: lpc31_defclk + * + * Description: + * Enable the specified clock if it is one of the default clocks needed + * by the board. + * + ****************************************************************************/ + +EXTERN bool lpc31_defclk(enum lpc31_clockid_e clkid); + +/**************************************************************************** + * Name: lpc31_resetclks + * + * Description: + * Put all clocks into a known, initial state + * + ****************************************************************************/ + +EXTERN void lpc31_resetclks(void); + +/************************************************************************ + * Name: lpc31_clkinit + * + * Description: + * Initialize all clock domains based on board-specific clock + * configuration data + * + ************************************************************************/ + +EXTERN void lpc31_clkinit(const struct lpc31_clkinit_s* cfg); + +/************************************************************************ + * Name: lpc31_fdivinit + * + * Description: + * Enable and configure (or disable) a fractional divider. For + * internal us only... see lpc31_setfdiv() the externally usable + * function. + * + ************************************************************************/ + +EXTERN uint32_t lpc31_fdivinit(int fdcndx, + const struct lpc31_fdivconfig_s *fdiv, + bool enable); + +/************************************************************************ + * Name: lpc31_setfdiv + * + * Description: + * Set/reset subdomain frequency containing the specified clock using + * the provided divider settings + * + ************************************************************************/ + +EXTERN void lpc31_setfdiv(enum lpc31_domainid_e dmnid, + enum lpc31_clockid_e clkid, + const struct lpc31_fdivconfig_s *fdiv); + +/**************************************************************************** + * Name: lpc31_pllconfig + * + * Description: + * Re-onfigure the PLL according to the provided selections. + * + ****************************************************************************/ + +EXTERN void lpc31_pllconfig(const struct lpc31_pllconfig_s * const cfg); + +/************************************************************************ + * Name: lpc31_hp0pllconfig + * + * Description: + * Configure the HP0 PLL according to the board.h default selections. + * + ************************************************************************/ + +EXTERN void lpc31_hp0pllconfig(void); + +/************************************************************************ + * Name: lpc31_hp1pllconfig + * + * Description: + * Configure the HP1 PLL according to the board.h default selections. + * + ************************************************************************/ + +EXTERN void lpc31_hp1pllconfig(void); + +/************************************************************************ + * Name: lpc31_softreset + * + * Description: + * Perform a soft reset on the specified module. + * + ************************************************************************/ + +EXTERN void lpc31_softreset(enum lpc31_resetid_e resetid); + +/************************************************************************ + * Name: lpc31_clkdomain + * + * Description: + * Given a clock ID, return the ID of the domain in which the clock + * resides. + * + ************************************************************************/ + +EXTERN enum lpc31_domainid_e lpc31_clkdomain(enum lpc31_clockid_e clkid); + +/************************************************************************ + * Name: lpc31_esrndx + * + * Description: + * Given a clock ID, return the index of the corresponding ESR + * register (or ESRNDX_INVALID if there is no ESR associated with + * this clock ID). Indexing of ESRs differs slightly from the clock + * ID: There are 92 clock IDs but only 89 ESR regisers. There are no + * ESR registers for : + * + * + * CLKID_I2SRXBCK0 Clock ID 87: I2SRX_BCK0 + * CLKID_I2SRXBCK1, Clock ID 88: I2SRX_BCK1 + * + * and + * + * CLKID_SYSCLKO Clock ID 91: SYSCLK_O + * + ************************************************************************/ + +EXTERN int lpc31_esrndx(enum lpc31_clockid_e clkid); + +/************************************************************************ + * Name: lpc31_bcrndx + * + * Description: + * Only 5 of the 12 domains have an associated BCR register. This + * function returns the index to the associated BCR register (if any) + * or BCRNDX_INVALID otherwise. + * + ************************************************************************/ + +EXTERN int lpc31_bcrndx(enum lpc31_domainid_e dmnid); + +/************************************************************************ + * Name: lpc31_fdcndx + * + * Description: + * Given a clock ID and its domain ID, return the index of the + * corresponding fractional divider register (or FDCNDX_INVALID if + * there is no fractional divider associated with this clock). + * + ************************************************************************/ + +EXTERN int lpc31_fdcndx(enum lpc31_clockid_e clkid, + enum lpc31_domainid_e dmnid); + +/************************************************************************ + * Name: lpc31_selectfreqin + * + * Description: + * Set the base frequency source selection for with a clock domain + * + ************************************************************************/ + +EXTERN void lpc31_selectfreqin(enum lpc31_domainid_e dmnid, + uint32_t finsel); + +/************************************************************************ + * Name: lpc31_clkfreq + * + * Description: + * Given a clock ID and its domain ID, return the frequency of the + * clock. + * + ************************************************************************/ + +EXTERN uint32_t lpc31_clkfreq(enum lpc31_clockid_e clkid, + enum lpc31_domainid_e dmnid); + +/************************************************************************ + * Name: lpc31_enableexten + * + * Description: + * Enable external enabling for the the specified possible clocks. + * + ************************************************************************/ + +EXTERN void lpc31_enableexten(enum lpc31_clockid_e clkid); + +/************************************************************************ + * Name: lpc31_disableexten + * + * Description: + * Disable external enabling for the the specified possible clocks. + * + ************************************************************************/ + +EXTERN void lpc31_disableexten(enum lpc31_clockid_e clkid); + +#undef EXTERN +#ifdef __cplusplus +} +#endif + +#endif /* __ASSEMBLY__ */ +#endif /* __ARCH_ARM_SRC_LPC31XX_LPC31_CGUDRVR_H */ diff --git a/nuttx/arch/arm/src/lpc31xx/lpc31_clkdomain.c b/nuttx/arch/arm/src/lpc31xx/lpc31_clkdomain.c new file mode 100755 index 000000000..98014bb28 --- /dev/null +++ b/nuttx/arch/arm/src/lpc31xx/lpc31_clkdomain.c @@ -0,0 +1,125 @@ +/************************************************************************ + * arch/arm/src/lpc31xx/lpc31_clkdomain.c + * + * Copyright (C) 2009 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * References: + * - UM10314 LPC3130/31 User manual Rev. 1.01 — 9 September 2009 + * - lpc313x.cdl.drivers.zip example driver code + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name NuttX nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ************************************************************************/ + +/************************************************************************ + * Included Files + ************************************************************************/ + +#include +#include + +#include "up_arch.h" +#include "lpc31_cgudrvr.h" + +/************************************************************************ + * Pre-processor Definitions + ************************************************************************/ + +/************************************************************************ + * Private Data + ************************************************************************/ + +/************************************************************************ + * Private Functions + ************************************************************************/ + +/************************************************************************ + * Public Functions + ************************************************************************/ + +/************************************************************************ + * Name: lpc31_clkdomain + * + * Description: + * Given a clock ID, return the ID of the domain in which the clock + * resides. + * + ************************************************************************/ + +enum lpc31_domainid_e lpc31_clkdomain(enum lpc31_clockid_e clkid) +{ + if (clkid <= CLKID_SYSBASE_LAST) /* Domain 0: SYS_BASE */ + { + return DOMAINID_SYS; + } + else if (clkid <= CLKID_AHB0APB0_LAST) /* Domain 1: AHB0APB0_BASE */ + { + return DOMAINID_AHB0APB0; + } + else if (clkid <= CLKID_AHB0APB1_LAST) /* Domain 2: AHB0APB1_BASE */ + { + return DOMAINID_AHB0APB1; + } + else if (clkid <= CLKID_AHB0APB2_LAST) /* Domain 3: AHB0APB2_BASE */ + { + return DOMAINID_AHB0APB2; + } + else if (clkid <= CLKID_AHB0APB3_LAST) /* Domain 4: AHB0APB3_BASE */ + { + return DOMAINID_AHB0APB3; + } + else if (clkid <= CLKID_PCM_LAST) /* Domain 5: PCM_BASE */ + { + return DOMAINID_PCM; + } + else if (clkid <= CLKID_UART_LAST) /* Domain 6: UART_BASE */ + { + return DOMAINID_UART; + } + else if (clkid <= CLKID_CLK1024FS_LAST) /* Domain 7: CLK1024FS_BASE */ + { + return DOMAINID_CLK1024FS; + } + else if (clkid <= CLKID_I2SRXBCK0_LAST) /* Domain 8: BCK0_BASE */ + { + return DOMAINID_BCK0; + } + else if (clkid <= CLKID_I2SRXBCK1_LAST) /* Domain 9: BCK1_BASE */ + { + return DOMAINID_BCK1; + } + else if (clkid <= CLKID_SPI_LAST) /* Domain 10: SPI_BASE */ + { + return DOMAINID_SPI; + } + else /* if (clkid <= CLKID_SYSCLKO_LAST) */ /* Domain 11: SYSCLKO_BASE */ + { + return DOMAINID_SYSCLKO; + } +} diff --git a/nuttx/arch/arm/src/lpc31xx/lpc31_clkexten.c b/nuttx/arch/arm/src/lpc31xx/lpc31_clkexten.c new file mode 100755 index 000000000..1024c1035 --- /dev/null +++ b/nuttx/arch/arm/src/lpc31xx/lpc31_clkexten.c @@ -0,0 +1,152 @@ +/**************************************************************************** + * arch/arm/src/lpc31xx/lpc31_exten.c + * + * Copyright (C) 2009 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name NuttX nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include + +#include + +#include "lpc31_cgudrvr.h" + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +/**************************************************************************** + * Public Data + ****************************************************************************/ + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: lpc31_enableexten + * + * Description: + * Enable external enabling for the the specified possible clocks. + * + ****************************************************************************/ + +void lpc31_enableexten(enum lpc31_clockid_e clkid) +{ + uint32_t regaddr; + uint32_t regval; + + switch (clkid) + { + case CLKID_DMACLKGATED: /* 9 DMA_CLK_GATED */ + case CLKID_EVENTROUTERPCLK: /* 31 EVENT_ROUTER_PCLK */ + case CLKID_ADCPCLK: /* 32 ADC_PCLK */ + case CLKID_IOCONFPCLK: /* 35 IOCONF_PCLK */ + case CLKID_CGUPCLK: /* 36 CGU_PCLK */ + case CLKID_SYSCREGPCLK: /* 37 SYSCREG_PCLK */ + case CLKID_OTPPCLK: /* 38 OTP_PCLK (Reserved on LPC313X) */ + case CLKID_PWMPCLKREGS: /* 46 PWM_PCLK_REGS */ + case CLKID_PCMAPBPCLK: /* 52 PCM_APB_PCLK */ + case CLKID_SPIPCLKGATED: /* 57 SPI_PCLK_GATED */ + case CLKID_SPICLKGATED: /* 90 SPI_CLK_GATED */ + case CLKID_PCMCLKIP: /* 71 PCM_CLK_IP */ + regaddr = LPC31_CGU_PCR(clkid); + regval = getreg32(regaddr); + regval |= CGU_PCR_EXTENEN; + putreg32(regval, regaddr); + break; + + /* Otherwise, force disable for the clocks. NOTE that a larger set will + * be disabled than will be enabled. + */ + + default: + lpc31_disableexten(clkid); + break; + } +} + +/**************************************************************************** + * Name: lpc31_disableexten + * + * Description: + * Disable external enabling for the the specified possible clocks. + * + ****************************************************************************/ + +void lpc31_disableexten(enum lpc31_clockid_e clkid) +{ + uint32_t regaddr; + uint32_t regval; + + switch (clkid) + { + case CLKID_DMACLKGATED: /* 9 DMA_CLK_GATED */ + case CLKID_EVENTROUTERPCLK: /* 31 EVENT_ROUTER_PCLK */ + case CLKID_ADCPCLK: /* 32 ADC_PCLK */ + case CLKID_WDOGPCLK: /* 34 WDOG_PCLK */ + case CLKID_IOCONFPCLK: /* 35 IOCONF_PCLK */ + case CLKID_CGUPCLK: /* 36 CGU_PCLK */ + case CLKID_SYSCREGPCLK: /* 37 SYSCREG_PCLK */ + case CLKID_OTPPCLK: /* 38 OTP_PCLK (Reserved on LPC313X) */ + case CLKID_PWMPCLKREGS: /* 46 PWM_PCLK_REGS */ + case CLKID_I2C0PCLK: /* 48 I2C0_PCLK */ + case CLKID_I2C1PCLK: /* 49 I2C1_PCLK */ + case CLKID_PCMAPBPCLK: /* 52 PCM_APB_PCLK */ + case CLKID_UARTAPBCLK: /* 53 UART_APB_CLK */ + case CLKID_SPIPCLKGATED: /* 57 SPI_PCLK_GATED */ + case CLKID_SPICLKGATED: /* 90 SPI_CLK_GATED */ + case CLKID_PCMCLKIP: /* 71 PCM_CLK_IP */ + case CLKID_LCDPCLK: /* 54 LCD_PCLK */ + regaddr = LPC31_CGU_PCR(clkid); + regval = getreg32(regaddr); + regval &= ~CGU_PCR_EXTENEN; + putreg32(regval, regaddr); + break; + + default: + break; + } +} diff --git a/nuttx/arch/arm/src/lpc31xx/lpc31_clkfreq.c b/nuttx/arch/arm/src/lpc31xx/lpc31_clkfreq.c new file mode 100755 index 000000000..845dc5602 --- /dev/null +++ b/nuttx/arch/arm/src/lpc31xx/lpc31_clkfreq.c @@ -0,0 +1,177 @@ +/************************************************************************ + * arch/arm/src/lpc31xx/lpc31_clkfreq.c + * + * Copyright (C) 2009-2010 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * References: + * - UM10314 LPC3130/31 User manual Rev. 1.01 — 9 September 2009 + * - lpc313x.cdl.drivers.zip example driver code + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name NuttX nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ************************************************************************/ + +/************************************************************************ + * Included Files + ************************************************************************/ + +#include +#include + +#include "up_arch.h" +#include "lpc31_cgudrvr.h" + +/************************************************************************ + * Pre-processor Definitions + ************************************************************************/ + +/************************************************************************ + * Private Data + ************************************************************************/ + +/************************************************************************ + * Private Functions + ************************************************************************/ + +/************************************************************************ + * Public Functions + ************************************************************************/ + +/************************************************************************ + * Name: lpc31_fdcndx + * + * Description: + * Given a clock ID and its domain ID, return the frequency of the + * clock. + * + ************************************************************************/ + +uint32_t lpc31_clkfreq(enum lpc31_clockid_e clkid, + enum lpc31_domainid_e dmnid) +{ + uint32_t freq = 0; + uint32_t fdcndx; + uint32_t regval; + + /* Get then fractional divider register index for this clock */ + + fdcndx = lpc31_fdcndx(clkid, dmnid); + + /* Get base frequency for the domain */ + + freq = lpc31_getbasefreq(dmnid); + + /* If there is no fractional divider associated with the clodk, then the + * connection is directo and we just return the base frequency. + */ + + if (fdcndx == FDCNDX_INVALID) + { + return freq; + } + + /* Read fractional divider control (FDC) register value and double check that + * it is enabled (not necessary since lpc31_fdcndx() also does this check + */ + + regval = getreg32(LPC31_CGU_FDC(fdcndx)); + if ((regval & CGU_ESR_ESREN) != 0) + { + int32_t msub; + int32_t madd; + int32_t n; + int32_t m; + + /* Yes, extract modulo subtraction and addition values, msub and madd. + * Fractional divider 17 is a special case because its msub and madd + * fields have greater range. + */ + + if (fdcndx == 17) + { + /* Range is 0-0x1fff for both */ + + msub = ((regval & CGU_FDC17_MSUB_MASK) >> CGU_FDC17_MSUB_SHIFT) | CGU_FDC17_MSUB_EXTEND; + madd = (regval & CGU_FDC17_MADD_MASK) >> CGU_FDC17_MADD_SHIFT; + } + else + { + /* Range is 0-255 for both */ + + msub = ((regval & CGU_FDC_MSUB_MASK) >> CGU_FDC_MSUB_SHIFT) | CGU_FDC_MSUB_EXTEND; + madd = (regval & CGU_FDC_MADD_MASK) >> CGU_FDC_MADD_SHIFT; + } + + /* Handle a corner case that would result in an infinite loop below */ + + if (msub == 0 && madd == 0) + { + return 0; + } + + /* Reduce to the greatest common power-of-2 denominator. To minimize + * power consumption, the lpc313x user manual recommends that madd and msub + * be shifted right to have as many trailing zero's as possible. The + * following undoes that shift. + */ + + while ((msub & 1) == 0 && (madd & 1) == 0) + { + madd = madd >> 1; + msub = msub >> 1; + } + + /* Then compute n and m values: + * + * fout = n/m * fin + * + * where + * + * madd = m - n + * msub = -n + */ + + n = -msub; + m = madd + n; + + /* Check that both m and n are non-zero values */ + + if ((n == 0) || (m == 0)) + { + return 0; + } + + /* Finally, calculate the frequency based on m and n values */ + + freq = (freq * n) / m ; + } + + return freq; +} + diff --git a/nuttx/arch/arm/src/lpc31xx/lpc31_clkinit.c b/nuttx/arch/arm/src/lpc31xx/lpc31_clkinit.c new file mode 100755 index 000000000..5e3e8ae4c --- /dev/null +++ b/nuttx/arch/arm/src/lpc31xx/lpc31_clkinit.c @@ -0,0 +1,298 @@ +/************************************************************************************ + * arch/arm/src/lpc31xx/lpc31_clkinit.c + * + * Copyright (C) 2009-2010 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name NuttX nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ************************************************************************************/ + +/************************************************************************************ + * Included Files + ************************************************************************************/ + +#include + +#include + +#include + +#include "lpc31_cgu.h" +#include "lpc31_cgudrvr.h" + +/************************************************************************************ + * Pre-processor Definitions + ************************************************************************************/ + +/************************************************************************************ + * Private Types + ************************************************************************************/ + +/* This structure describes the configuration of one domain */ + +struct lpc31_domainconfig_s +{ + enum lpc31_domainid_e dmnid; /* Domain ID */ + uint32_t finsel; /* Frequency input selection */ + uint32_t clk1; /* ID of first clock in the domain */ + uint32_t nclks; /* Number of clocks in the domain */ + uint32_t fdiv1; /* First frequency divider in the domain */ + uint32_t nfdiv; /* Number of frequency dividers in the domain */ + const struct lpc31_subdomainconfig_s* sub; /* Sub=domain array */ +}; + +/************************************************************************************ + * Private Data + ************************************************************************************/ + +/************************************************************************************ + * Public Data + ************************************************************************************/ + +/************************************************************************************ + * Private Functions + ************************************************************************************/ + +/************************************************************************************ + * Name: lpc31_domaininit + * + * Description: + * Initialize one clock domain based on board-specific clock configuration data + * + ************************************************************************************/ + +static void lpc31_domaininit(struct lpc31_domainconfig_s* dmn) +{ + const struct lpc31_subdomainconfig_s * sub = dmn->sub; + uint32_t fdivcfg; + uint32_t regaddr; + uint32_t regval; + int fdndx; + int clkndx; + int bcrndx = lpc31_bcrndx(dmn->dmnid); + int esrndx; + + if (bcrndx != BCRNDX_INVALID) + { + /* Disable BCR for domain */ + + regaddr = LPC31_CGU_BCR(bcrndx); + putreg32(0, regaddr); + } + + /* Configure the fractional dividers in this domain */ + + for (fdndx = 0; fdndx < dmn->nfdiv; fdndx++, sub++) + { + /* Set fractional divider confiruation but don't enable it yet */ + + fdivcfg = lpc31_fdivinit(fdndx + dmn->fdiv1, &sub->fdiv, false); + + /* Enable frac divider only if it has valid settings */ + + if (fdivcfg != 0) + { + /* Select the fractional dividir for each clock in this + * sub domain. + */ + + for (clkndx = 0; clkndx <= dmn->nclks; clkndx++) + { + /* Does this clock have an ESR register? */ + + esrndx = lpc31_esrndx((enum lpc31_clockid_e)(clkndx + dmn->clk1)); + if (esrndx != ESRNDX_INVALID) + { + /* Yes.. Check if this clock belongs to this sub-domain */ + + if (sub->clkset & (1 << clkndx)) + { + /* Yes.. configure the clock to use this fractional divider */ + + regaddr = LPC31_CGU_ESR(esrndx); + putreg32((fdndx << CGU_ESR_ESRSEL_SHIFT) | CGU_ESR_ESREN, regaddr); + } + } + } + + /* Enable the fractional divider */ + + regaddr = LPC31_CGU_FDC(fdndx + dmn->fdiv1); + regval = getreg32(regaddr); + regval |= CGU_FDC_RUN; + putreg32(regval, regaddr); + } + } + + if (bcrndx != BCRNDX_INVALID) + { + /* Enable the BCR for domain */ + + regaddr = LPC31_CGU_BCR(bcrndx); + putreg32(CGU_BCR_FDRUN, regaddr); + } + + /* Select input base clock for domain*/ + + lpc31_selectfreqin(dmn->dmnid, dmn->finsel); +} + +/************************************************************************************ + * Public Functions + ************************************************************************************/ + +/************************************************************************************ + * Name: lpc31_clkinit + * + * Description: + * Initialize all clock domains based on board-specific clock configuration data + * + ************************************************************************************/ + +void lpc31_clkinit(const struct lpc31_clkinit_s* cfg) +{ + struct lpc31_domainconfig_s domain; + + /* Reset all clocks and connect them to FFAST */ + + lpc31_resetclks(); + + /* Initialize Domain0 = SYS_BASE clocks */ + + domain.dmnid = DOMAINID_SYS; + domain.finsel = cfg->domain0.finsel; + domain.clk1 = CLKID_SYSBASE_FIRST; + domain.nclks = (CLKID_SYSBASE_LAST - CLKID_SYSBASE_FIRST) + 1; + domain.fdiv1 = FRACDIV_BASE0_LOW; + domain.nfdiv = FRACDIV_BASE0_CNT; + domain.sub = cfg->domain0.sub; + lpc31_domaininit(&domain); + + /* Initialize Domain1 = AHB0APB0_BASE clocks */ + + domain.dmnid = DOMAINID_AHB0APB0; + domain.finsel = cfg->domain1.finsel; + domain.clk1 = CLKID_AHB0APB0_FIRST; + domain.nclks = (CLKID_AHB0APB0_LAST - CLKID_AHB0APB0_FIRST) + 1; + domain.fdiv1 = FRACDIV_BASE1_LOW; + domain.nfdiv = FRACDIV_BASE1_CNT; + domain.sub = cfg->domain1.sub; + lpc31_domaininit(&domain); + + /* Initialize Domain2 = AHB0APB1_BASE clocks */ + + domain.dmnid = DOMAINID_AHB0APB1; + domain.finsel = cfg->domain2.finsel; + domain.clk1 = CLKID_AHB0APB1_FIRST; + domain.nclks = (CLKID_AHB0APB1_LAST - CLKID_AHB0APB1_FIRST) + 1; + domain.fdiv1 = FRACDIV_BASE2_LOW; + domain.nfdiv = FRACDIV_BASE2_CNT; + domain.sub = cfg->domain2.sub; + lpc31_domaininit(&domain); + + /* Initialize Domain3 = AHB0APB2_BASE clocks */ + + domain.dmnid = DOMAINID_AHB0APB2; + domain.finsel = cfg->domain3.finsel; + domain.clk1 = CLKID_AHB0APB2_FIRST; + domain.nclks = (CLKID_AHB0APB2_LAST - CLKID_AHB0APB2_FIRST) + 1; + domain.fdiv1 = FRACDIV_BASE3_LOW; + domain.nfdiv = FRACDIV_BASE3_CNT; + domain.sub = cfg->domain3.sub; + lpc31_domaininit(&domain); + + /* Initialize Domain4 = AHB0APB3_BASE clocks */ + + domain.dmnid = DOMAINID_AHB0APB3; + domain.finsel = cfg->domain4.finsel; + domain.clk1 = CLKID_AHB0APB3_FIRST; + domain.nclks = (CLKID_AHB0APB3_LAST - CLKID_AHB0APB3_FIRST) + 1; + domain.fdiv1 = FRACDIV_BASE4_LOW; + domain.nfdiv = FRACDIV_BASE4_CNT; + domain.sub = cfg->domain4.sub; + lpc31_domaininit(&domain); + + /* Initialize Domain5 = PCM_BASE clocks */ + + domain.dmnid = DOMAINID_PCM; + domain.finsel = cfg->domain5.finsel; + domain.clk1 = CLKID_PCM_FIRST; + domain.nclks = 1; + domain.fdiv1 = FRACDIV_BASE5_LOW; + domain.nfdiv = FRACDIV_BASE5_CNT; + domain.sub = cfg->domain5.sub; + lpc31_domaininit(&domain); + + /* Initialize Domain6 = UART_BASE clocks */ + + domain.dmnid = DOMAINID_UART; + domain.finsel = cfg->domain6.finsel; + domain.clk1 = CLKID_UART_FIRST; + domain.nclks = 1; + domain.fdiv1 = FRACDIV_BASE6_LOW; + domain.nfdiv = FRACDIV_BASE6_CNT; + domain.sub = cfg->domain6.sub; + lpc31_domaininit(&domain); + + /* Initialize Domain7 = CLK1024FS_BASE clocks */ + + domain.dmnid = DOMAINID_CLK1024FS; + domain.finsel = cfg->domain7.finsel; + domain.clk1 = CLKID_CLK1024FS_FIRST; + domain.nclks = (CLKID_CLK1024FS_LAST - CLKID_CLK1024FS_FIRST) + 1; + domain.fdiv1 = FRACDIV_BASE7_LOW; + domain.nfdiv = FRACDIV_BASE7_CNT; + domain.sub = cfg->domain7.sub; + lpc31_domaininit(&domain); + + /* Initialize Domain8 = I2SRX_BCK0_BASE clocks */ + + lpc31_selectfreqin(DOMAINID_BCK0, cfg->domain8.finsel); + + /* Initialize Domain9 = I2SRX_BCK1_BASE clocks */ + + lpc31_selectfreqin(DOMAINID_BCK1, cfg->domain9.finsel); + + /* Initialize Domain10 = SPI_BASE clocks */ + + domain.dmnid = DOMAINID_SPI; + domain.finsel = cfg->domain10.finsel; + domain.clk1 = CLKID_SPI_FIRST; + domain.nclks = (CLKID_SPI_LAST - CLKID_SPI_FIRST) + 1; + domain.fdiv1 = FRACDIV_BASE10_LOW; + domain.nfdiv = FRACDIV_BASE10_CNT; + domain.sub = cfg->domain10.sub; + lpc31_domaininit(&domain); + + /* Initialize Domain11 = SYSCLK_O_BASE clocks */ + + lpc31_selectfreqin(DOMAINID_SYSCLKO, cfg->domain11.finsel); + + /* Initialize Dynamic fractional dividers -- to be provided */ +} diff --git a/nuttx/arch/arm/src/lpc31xx/lpc31_decodeirq.c b/nuttx/arch/arm/src/lpc31xx/lpc31_decodeirq.c new file mode 100755 index 000000000..9a417f9eb --- /dev/null +++ b/nuttx/arch/arm/src/lpc31xx/lpc31_decodeirq.c @@ -0,0 +1,137 @@ +/******************************************************************************** + * arch/arm/src/lpc31xx/lpc31_decodeirq.c + * arch/arm/src/chip/lpc31_decodeirq.c + * + * Copyright (C) 2009 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name NuttX nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ********************************************************************************/ + +/******************************************************************************** + * Included Files + ********************************************************************************/ + +#include + +#include +#include +#include +#include +#include + +#include "chip.h" +#include "up_arch.h" + +#include "os_internal.h" +#include "up_internal.h" + +#include "lpc31_intc.h" + +/******************************************************************************** + * Pre-processor Definitions + ********************************************************************************/ + +/******************************************************************************** + * Public Data + ********************************************************************************/ + +/******************************************************************************** + * Private Data + ********************************************************************************/ + +/******************************************************************************** + * Private Functions + ********************************************************************************/ + +/******************************************************************************** + * Public Functions + ********************************************************************************/ + +void up_decodeirq(uint32_t *regs) +{ +#ifdef CONFIG_SUPPRESS_INTERRUPTS + lib_lowprintf("Unexpected IRQ\n"); + current_regs = regs; + PANIC(OSERR_ERREXCEPTION); +#else + int index; + int irq; + + /* Read the IRQ vector status register. Bits 3-10 provide the IRQ number + * of the interrupt (the TABLE_ADDR was initialized to zero, so the + * following masking should be unnecessary) + */ + + index = getreg32(LPC31_INTC_VECTOR0) & INTC_VECTOR_INDEX_MASK; + if (index != 0) + { + /* Shift the index so that the range of IRQ numbers are in bits 0-7 (values + * 1-127) and back off the IRQ number by 1 so that the numbering is zero-based + */ + + irq = (index >> INTC_VECTOR_INDEX_SHIFT) -1; + + /* Verify that the resulting IRQ number is valid */ + + if ((unsigned)irq < NR_IRQS) + { + uint32_t* savestate; + + /* Mask and acknowledge the interrupt */ + + up_maskack_irq(irq); + + /* Current regs non-zero indicates that we are processing an interrupt; + * current_regs is also used to manage interrupt level context switches. + */ + + savestate = (uint32_t*)current_regs; + current_regs = regs; + + /* Deliver the IRQ */ + + irq_dispatch(irq, regs); + + /* Restore the previous value of current_regs. NULL would indicate that + * we are no longer in an interrupt handler. It will be non-NULL if we + * are returning from a nested interrupt. + */ + + current_regs = savestate; + + /* Unmask the last interrupt (global interrupts are still + * disabled). + */ + + up_enable_irq(irq); + } + } +#endif +} diff --git a/nuttx/arch/arm/src/lpc31xx/lpc31_defclk.c b/nuttx/arch/arm/src/lpc31xx/lpc31_defclk.c new file mode 100755 index 000000000..8e13df20d --- /dev/null +++ b/nuttx/arch/arm/src/lpc31xx/lpc31_defclk.c @@ -0,0 +1,119 @@ +/**************************************************************************** + * arch/arm/src/lpc31xx/lpc31_defclk.c + * + * Copyright (C) 2009 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name NuttX nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include + +#include + +#include "lpc31_cgudrvr.h" + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +/**************************************************************************** + * Public Data + ****************************************************************************/ + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: lpc31_defclk + * + * Description: + * Enable the specified clock if it is one of the default clocks needed + * by the board. + * + ****************************************************************************/ + +bool lpc31_defclk(enum lpc31_clockid_e clkid) +{ + + uint32_t regaddr; + uint32_t regval; + bool enable; + + /* Check if this clock should be enabled. This is determined by + * 3 bitsets provided by board-specific logic in board/board.h. + */ + + if ((int)clkid < 32) + { + enable = ((BOARD_CLKS_0_31 & (1 << (int)clkid)) != 0); + } + else if ((int)clkid < 64) + { + enable = ((BOARD_CLKS_32_63 & (1 << ((int)clkid - 32))) != 0); + } + else + { + enable = ((BOARD_CLKS_64_92 & (1 << ((int)clkid - 64))) != 0); + } + + /* Then set/clear the RUN bit in the PCR register for this clock + * accordingly. + */ + + regaddr = LPC31_CGU_PCR((int)clkid); + regval = getreg32(regaddr); + if (enable) + { + regval |= CGU_PCR_RUN; + } + else + { + regval &= ~CGU_PCR_RUN; + } + putreg32(regval, regaddr); + return enable; +} + diff --git a/nuttx/arch/arm/src/lpc31xx/lpc31_dma.h b/nuttx/arch/arm/src/lpc31xx/lpc31_dma.h new file mode 100755 index 000000000..ffbc75242 --- /dev/null +++ b/nuttx/arch/arm/src/lpc31xx/lpc31_dma.h @@ -0,0 +1,423 @@ +/************************************************************************************************ + * arch/arm/src/lpc31xx/lpc31_dma.h + * + * Copyright (C) 2009 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * 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_LPC31XX_LPC31_DMA_H +#define __ARCH_ARM_SRC_LPC31XX_LPC31_DMA_H + +/************************************************************************************************ + * Included Files + ************************************************************************************************/ + +#include +#include "lpc31_memorymap.h" + +/************************************************************************************************ + * Pre-processor Definitions + ************************************************************************************************/ + +/* DMA register base address offset into the APB4 domain ****************************************/ + +#define LPC31_DMA_VBASE (LPC31_APB4_VADDR+LPC31_APB4_DMA_OFFSET) +#define LPC31_DMA_PBASE (LPC31_APB4_PADDR+LPC31_APB4_DMA_OFFSET) + +/* DMA channel offsets (with respect to the DMA register base address) **************************/ + +#define LPC31_DMACHAN_OFFSET(n) ((n)*0x020) +#define LPC31_DMACHAN0_OFFSET 0x000 +#define LPC31_DMACHAN1_OFFSET 0x020 +#define LPC31_DMACHAN2_OFFSET 0x040 +#define LPC31_DMACHAN3_OFFSET 0x060 +#define LPC31_DMACHAN4_OFFSET 0x080 +#define LPC31_DMACHAN5_OFFSET 0x0a0 +#define LPC31_DMACHAN6_OFFSET 0x0c0 +#define LPC31_DMACHAN7_OFFSET 0x0e0 +#define LPC31_DMACHAN8_OFFSET 0x100 +#define LPC31_DMACHAN9_OFFSET 0x120 +#define LPC31_DMACHAN10_OFFSET 0x140 +#define LPC31_DMACHAN11_OFFSET 0x160 + +#define LPC31_DMACHAN_ALT_OFFSET(n) (0x200+((n)*0x020)) +#define LPC31_DMACHAN0_ALT_OFFSET 0x200 +#define LPC31_DMACHAN1_ALT_OFFSET 0x220 +#define LPC31_DMACHAN2_ALT_OFFSET 0x240 +#define LPC31_DMACHAN3_ALT_OFFSET 0x260 +#define LPC31_DMACHAN4_ALT_OFFSET 0x280 +#define LPC31_DMACHAN5_ALT_OFFSET 0x2a0 +#define LPC31_DMACHAN6_ALT_OFFSET 0x2c0 +#define LPC31_DMACHAN7_ALT_OFFSET 0x2e0 +#define LPC31_DMACHAN8_ALT_OFFSET 0x300 +#define LPC31_DMACHAN9_ALT_OFFSET 0x320 +#define LPC31_DMACHAN10_ALT_OFFSET 0x340 +#define LPC31_DMACHAN11_ALT_OFFSET 0x360 + +/* DMA channel virtual base addresses ***********************************************************/ + +#define LPC31_DMACHAN_VBASE(n) (LPC31_DMA_VBASE+LPC31_DMACHAN_OFFSET(n)) +#define LPC31_DMACHAN0_VBASE (LPC31_DMA_VBASE+LPC31_DMACHAN0_OFFSET) +#define LPC31_DMACHAN1_VBASE (LPC31_DMA_VBASE+LPC31_DMACHAN1_OFFSET) +#define LPC31_DMACHAN2_VBASE (LPC31_DMA_VBASE+LPC31_DMACHAN2_OFFSET) +#define LPC31_DMACHAN3_VBASE (LPC31_DMA_VBASE+LPC31_DMACHAN3_OFFSET) +#define LPC31_DMACHAN4_VBASE (LPC31_DMA_VBASE+LPC31_DMACHAN4_OFFSET) +#define LPC31_DMACHAN5_VBASE (LPC31_DMA_VBASE+LPC31_DMACHAN5_OFFSET) +#define LPC31_DMACHAN6_VBASE (LPC31_DMA_VBASE+LPC31_DMACHAN6_OFFSET) +#define LPC31_DMACHAN7_VBASE (LPC31_DMA_VBASE+LPC31_DMACHAN7_OFFSET) +#define LPC31_DMACHAN8_VBASE (LPC31_DMA_VBASE+LPC31_DMACHAN8_OFFSET) +#define LPC31_DMACHAN9_VBASE (LPC31_DMA_VBASE+LPC31_DMACHAN9_OFFSET) +#define LPC31_DMACHAN10_VBASE (LPC31_DMA_VBASE+LPC31_DMACHAN10_OFFSET) +#define LPC31_DMACHAN11_VBASE (LPC31_DMA_VBASE+LPC31_DMACHAN11_OFFSET) + +#define LPC31_DMACHAN_ALT_VBASE(n) (LPC31_DMA_VBASE+LPC31_DMACHAN_ALT_OFFSET(n)) +#define LPC31_DMACHAN0_VBASE (LPC31_DMA_VBASE+LPC31_DMACHAN0_ALT_OFFSET) +#define LPC31_DMACHAN1_VBASE (LPC31_DMA_VBASE+LPC31_DMACHAN1_ALT_OFFSET) +#define LPC31_DMACHAN2_VBASE (LPC31_DMA_VBASE+LPC31_DMACHAN2_ALT_OFFSET) +#define LPC31_DMACHAN3_VBASE (LPC31_DMA_VBASE+LPC31_DMACHAN3_ALT_OFFSET) +#define LPC31_DMACHAN4_VBASE (LPC31_DMA_VBASE+LPC31_DMACHAN4_ALT_OFFSET) +#define LPC31_DMACHAN5_VBASE (LPC31_DMA_VBASE+LPC31_DMACHAN5_ALT_OFFSET) +#define LPC31_DMACHAN6_VBASE (LPC31_DMA_VBASE+LPC31_DMACHAN6_ALT_OFFSET) +#define LPC31_DMACHAN7_VBASE (LPC31_DMA_VBASE+LPC31_DMACHAN7_ALT_OFFSET) +#define LPC31_DMACHAN8_VBASE (LPC31_DMA_VBASE+LPC31_DMACHAN8_ALT_OFFSET) +#define LPC31_DMACHAN9_VBASE (LPC31_DMA_VBASE+LPC31_DMACHAN9_ALT_OFFSET) +#define LPC31_DMACHAN10_VBASE (LPC31_DMA_VBASE+LPC31_DMACHAN10_ALT_OFFSET) +#define LPC31_DMACHAN11_VBASE (LPC31_DMA_VBASE+LPC31_DMACHAN11_ALT_OFFSET) + +/* DMA channel register offsets (with respect to the DMA channel register base) *****************/ + +#define LPC31_DMACHAN_SRCADDR_OFFSET 0x000 /* Source address register of DMA channel */ +#define LPC31_DMACHAN_DESTADDR_OFFSET 0X004 /* Destination address register of DMA channel */ +#define LPC31_DMACHAN_XFERLEN_OFFSET 0X008 /* Transfer length register for DMA channel */ +#define LPC31_DMACHAN_CONFIG_OFFSET 0x00c /* Configuration register for DMA channel */ +#define LPC31_DMACHAN_ENABLE_OFFSET 0x010 /* Enable register for DMA channel */ +#define LPC31_DMACHAN_XFERCOUNT_OFFSET 0x01c /* Transfer counter register for DMA channel */ + +/* DMA global register offsets (with respect to the DMA register base) *************************/ + +#define LPC31_DMA_ALTENABLE_OFFSET 0x400 /* Alternative enable register */ +#define LPC31_DMA_IRQSTATUSCLR_OFFSET 0x404 /* IRQ status clear register */ +#define LPC31_DMA_IRQMASK_OFFSET 0x408 /* IRQ mask register */ +#define LPC31_DMA_TESTSTATUS_OFFSET 0x40c /* Test FIFO response status register */ +#define LPC31_DMA_SOFTINT_OFFSET 0x410 /* Software interrupt register */ + +/* DMA channel register (virtual) addresses *****************************************************/ + +#define LPC31_DMACHAN_SRCADDR(n) (LPC31_DMACHAN_VBASE(n)+LPC31_DMACHAN_SRCADDR_OFFSET) +#define LPC31_DMACHAN_DESTADDR(n) (LPC31_DMACHAN_VBASE(n)+LPC31_DMACHAN_DESTADDR_OFFSET) +#define LPC31_DMACHAN_XFERLEN(n) (LPC31_DMACHAN_VBASE(n)+LPC31_DMACHAN_XFERLEN_OFFSET) +#define LPC31_DMACHAN_CONFIG(n) (LPC31_DMACHAN_VBASE(n)+LPC31_DMACHAN_CONFIG_OFFSET) +#define LPC31_DMACHAN_ENABLE(n) (LPC31_DMACHAN_VBASE(n)+LPC31_DMACHAN_ENABLE_OFFSET) +#define LPC31_DMACHAN_XFERCOUNT(n) (LPC31_DMACHAN_VBASE(n)+LPC31_DMACHAN_XFERCOUNT_OFFSET) + +#define LPC31_DMACHAN0_SRCADDR (LPC31_DMACHAN0_VBASE+LPC31_DMACHAN_SRCADDR_OFFSET) +#define LPC31_DMACHAN0_DESTADDR (LPC31_DMACHAN0_VBASE+LPC31_DMACHAN_DESTADDR_OFFSET) +#define LPC31_DMACHAN0_XFERLEN (LPC31_DMACHAN0_VBASE+LPC31_DMACHAN_XFERLEN_OFFSET) +#define LPC31_DMACHAN0_CONFIG (LPC31_DMACHAN0_VBASE+LPC31_DMACHAN_CONFIG_OFFSET) +#define LPC31_DMACHAN0_ENABLE (LPC31_DMACHAN0_VBASE+LPC31_DMACHAN_ENABLE_OFFSET) +#define LPC31_DMACHAN0_XFERCOUNT (LPC31_DMACHAN0_VBASE+LPC31_DMACHAN_XFERCOUNT_OFFSET) + +#define LPC31_DMACHAN1_SRCADDR (LPC31_DMACHAN1_VBASE+LPC31_DMACHAN_SRCADDR_OFFSET) +#define LPC31_DMACHAN1_DESTADDR (LPC31_DMACHAN1_VBASE+LPC31_DMACHAN_DESTADDR_OFFSET) +#define LPC31_DMACHAN1_XFERLEN (LPC31_DMACHAN1_VBASE+LPC31_DMACHAN_XFERLEN_OFFSET) +#define LPC31_DMACHAN1_CONFIG (LPC31_DMACHAN1_VBASE+LPC31_DMACHAN_CONFIG_OFFSET) +#define LPC31_DMACHAN1_ENABLE (LPC31_DMACHAN1_VBASE+LPC31_DMACHAN_ENABLE_OFFSET) +#define LPC31_DMACHAN1_XFERCOUNT (LPC31_DMACHAN1_VBASE+LPC31_DMACHAN_XFERCOUNT_OFFSET) + +#define LPC31_DMACHAN2_SRCADDR (LPC31_DMACHAN2_VBASE+LPC31_DMACHAN_SRCADDR_OFFSET) +#define LPC31_DMACHAN2_DESTADDR (LPC31_DMACHAN2_VBASE+LPC31_DMACHAN_DESTADDR_OFFSET) +#define LPC31_DMACHAN2_XFERLEN (LPC31_DMACHAN2_VBASE+LPC31_DMACHAN_XFERLEN_OFFSET) +#define LPC31_DMACHAN2_CONFIG (LPC31_DMACHAN2_VBASE+LPC31_DMACHAN_CONFIG_OFFSET) +#define LPC31_DMACHAN2_ENABLE (LPC31_DMACHAN2_VBASE+LPC31_DMACHAN_ENABLE_OFFSET) +#define LPC31_DMACHAN2_XFERCOUNT (LPC31_DMACHAN2_VBASE+LPC31_DMACHAN_XFERCOUNT_OFFSET) + +#define LPC31_DMACHAN3_SRCADDR (LPC31_DMACHAN3_VBASE+LPC31_DMACHAN_SRCADDR_OFFSET) +#define LPC31_DMACHAN3_DESTADDR (LPC31_DMACHAN3_VBASE+LPC31_DMACHAN_DESTADDR_OFFSET) +#define LPC31_DMACHAN3_XFERLEN (LPC31_DMACHAN3_VBASE+LPC31_DMACHAN_XFERLEN_OFFSET) +#define LPC31_DMACHAN3_CONFIG (LPC31_DMACHAN3_VBASE+LPC31_DMACHAN_CONFIG_OFFSET) +#define LPC31_DMACHAN3_ENABLE (LPC31_DMACHAN3_VBASE+LPC31_DMACHAN_ENABLE_OFFSET) +#define LPC31_DMACHAN3_XFERCOUNT (LPC31_DMACHAN3_VBASE+LPC31_DMACHAN_XFERCOUNT_OFFSET) + +#define LPC31_DMACHAN4_SRCADDR (LPC31_DMACHAN4_VBASE+LPC31_DMACHAN_SRCADDR_OFFSET) +#define LPC31_DMACHAN4_DESTADDR (LPC31_DMACHAN4_VBASE+LPC31_DMACHAN_DESTADDR_OFFSET) +#define LPC31_DMACHAN4_XFERLEN (LPC31_DMACHAN4_VBASE+LPC31_DMACHAN_XFERLEN_OFFSET) +#define LPC31_DMACHAN4_CONFIG (LPC31_DMACHAN4_VBASE+LPC31_DMACHAN_CONFIG_OFFSET) +#define LPC31_DMACHAN4_ENABLE (LPC31_DMACHAN4_VBASE+LPC31_DMACHAN_ENABLE_OFFSET) +#define LPC31_DMACHAN4_XFERCOUNT (LPC31_DMACHAN4_VBASE+LPC31_DMACHAN_XFERCOUNT_OFFSET) + +#define LPC31_DMACHAN5_SRCADDR (LPC31_DMACHAN5_VBASE+LPC31_DMACHAN_SRCADDR_OFFSET) +#define LPC31_DMACHAN5_DESTADDR (LPC31_DMACHAN5_VBASE+LPC31_DMACHAN_DESTADDR_OFFSET) +#define LPC31_DMACHAN5_XFERLEN (LPC31_DMACHAN5_VBASE+LPC31_DMACHAN_XFERLEN_OFFSET) +#define LPC31_DMACHAN5_CONFIG (LPC31_DMACHAN5_VBASE+LPC31_DMACHAN_CONFIG_OFFSET) +#define LPC31_DMACHAN5_ENABLE (LPC31_DMACHAN5_VBASE+LPC31_DMACHAN_ENABLE_OFFSET) +#define LPC31_DMACHAN5_XFERCOUNT (LPC31_DMACHAN5_VBASE+LPC31_DMACHAN_XFERCOUNT_OFFSET) + +#define LPC31_DMACHAN6_SRCADDR (LPC31_DMACHAN6_VBASE+LPC31_DMACHAN_SRCADDR_OFFSET) +#define LPC31_DMACHAN6_DESTADDR (LPC31_DMACHAN6_VBASE+LPC31_DMACHAN_DESTADDR_OFFSET) +#define LPC31_DMACHAN6_XFERLEN (LPC31_DMACHAN6_VBASE+LPC31_DMACHAN_XFERLEN_OFFSET) +#define LPC31_DMACHAN6_CONFIG (LPC31_DMACHAN6_VBASE+LPC31_DMACHAN_CONFIG_OFFSET) +#define LPC31_DMACHAN6_ENABLE (LPC31_DMACHAN6_VBASE+LPC31_DMACHAN_ENABLE_OFFSET) +#define LPC31_DMACHAN6_XFERCOUNT (LPC31_DMACHAN6_VBASE+LPC31_DMACHAN_XFERCOUNT_OFFSET) + +#define LPC31_DMACHAN7_SRCADDR (LPC31_DMACHAN7_VBASE+LPC31_DMACHAN_SRCADDR_OFFSET) +#define LPC31_DMACHAN7_DESTADDR (LPC31_DMACHAN7_VBASE+LPC31_DMACHAN_DESTADDR_OFFSET) +#define LPC31_DMACHAN7_XFERLEN (LPC31_DMACHAN7_VBASE+LPC31_DMACHAN_XFERLEN_OFFSET) +#define LPC31_DMACHAN7_CONFIG (LPC31_DMACHAN7_VBASE+LPC31_DMACHAN_CONFIG_OFFSET) +#define LPC31_DMACHAN7_ENABLE (LPC31_DMACHAN7_VBASE+LPC31_DMACHAN_ENABLE_OFFSET) +#define LPC31_DMACHAN7_XFERCOUNT (LPC31_DMACHAN7_VBASE+LPC31_DMACHAN_XFERCOUNT_OFFSET)7 + +#define LPC31_DMACHAN8_SRCADDR (LPC31_DMACHAN8_VBASE+LPC31_DMACHAN_SRCADDR_OFFSET) +#define LPC31_DMACHAN8_DESTADDR (LPC31_DMACHAN8_VBASE+LPC31_DMACHAN_DESTADDR_OFFSET) +#define LPC31_DMACHAN8_XFERLEN (LPC31_DMACHAN8_VBASE+LPC31_DMACHAN_XFERLEN_OFFSET) +#define LPC31_DMACHAN8_CONFIG (LPC31_DMACHAN8_VBASE+LPC31_DMACHAN_CONFIG_OFFSET) +#define LPC31_DMACHAN8_ENABLE (LPC31_DMACHAN8_VBASE+LPC31_DMACHAN_ENABLE_OFFSET) +#define LPC31_DMACHAN8_XFERCOUNT (LPC31_DMACHAN8_VBASE+LPC31_DMACHAN_XFERCOUNT_OFFSET) + +#define LPC31_DMACHAN9_SRCADDR (LPC31_DMACHAN9_VBASE+LPC31_DMACHAN_SRCADDR_OFFSET) +#define LPC31_DMACHAN9_DESTADDR (LPC31_DMACHAN9_VBASE+LPC31_DMACHAN_DESTADDR_OFFSET) +#define LPC31_DMACHAN9_XFERLEN (LPC31_DMACHAN9_VBASE+LPC31_DMACHAN_XFERLEN_OFFSET) +#define LPC31_DMACHAN9_CONFIG (LPC31_DMACHAN9_VBASE+LPC31_DMACHAN_CONFIG_OFFSET) +#define LPC31_DMACHAN9_ENABLE (LPC31_DMACHAN9_VBASE+LPC31_DMACHAN_ENABLE_OFFSET) +#define LPC31_DMACHAN9_XFERCOUNT (LPC31_DMACHAN9_VBASE+LPC31_DMACHAN_XFERCOUNT_OFFSET) + +#define LPC31_DMACHAN10_SRCADDR (LPC31_DMACHAN10_VBASE+LPC31_DMACHAN_SRCADDR_OFFSET) +#define LPC31_DMACHAN10_DESTADDR (LPC31_DMACHAN10_VBASE+LPC31_DMACHAN_DESTADDR_OFFSET) +#define LPC31_DMACHAN10_XFERLEN (LPC31_DMACHAN10_VBASE+LPC31_DMACHAN_XFERLEN_OFFSET) +#define LPC31_DMACHAN10_CONFIG (LPC31_DMACHAN10_VBASE+LPC31_DMACHAN_CONFIG_OFFSET) +#define LPC31_DMACHAN10_ENABLE (LPC31_DMACHAN10_VBASE+LPC31_DMACHAN_ENABLE_OFFSET) +#define LPC31_DMACHAN10_XFERCOUNT (LPC31_DMACHAN10_VBASE+LPC31_DMACHAN_XFERCOUNT_OFFSET) + +#define LPC31_DMACHAN11_SRCADDR (LPC31_DMACHAN11_VBASE+LPC31_DMACHAN_SRCADDR_OFFSET) +#define LPC31_DMACHAN11_DESTADDR (LPC31_DMACHAN11_VBASE+LPC31_DMACHAN_DESTADDR_OFFSET) +#define LPC31_DMACHAN11_XFERLEN (LPC31_DMACHAN11_VBASE+LPC31_DMACHAN_XFERLEN_OFFSET) +#define LPC31_DMACHAN11_CONFIG (LPC31_DMACHAN11_VBASE+LPC31_DMACHAN_CONFIG_OFFSET) +#define LPC31_DMACHAN11_ENABLE (LPC31_DMACHAN11_VBASE+LPC31_DMACHAN_ENABLE_OFFSET) +#define LPC31_DMACHAN11_XFERCOUNT (LPC31_DMACHAN11_VBASE+LPC31_DMACHAN_XFERCOUNT_OFFSET) + +#define LPC31_DMACHAN_ALT_SRCADDR(n) (LPC31_DMACHAN_ALT_VBASE(n)+LPC31_DMACHAN_SRCADDR_OFFSET) +#define LPC31_DMACHAN_ALT_DESTADDR(n) (LPC31_DMACHAN_ALT_VBASE(n)+LPC31_DMACHAN_DESTADDR_OFFSET) +#define LPC31_DMACHAN_ALT_XFERLEN(n) (LPC31_DMACHAN_ALT_VBASE(n)+LPC31_DMACHAN_XFERLEN_OFFSET) +#define LPC31_DMACHAN_ALT_CONFIG(n) (LPC31_DMACHAN_ALT_VBASE(n)+LPC31_DMACHAN_CONFIG_OFFSET) + +#define LPC31_DMACHAN0_ALT_SRCADDR (LPC31_DMACHAN0_ALT_VBASE+LPC31_DMACHAN_SRCADDR_OFFSET) +#define LPC31_DMACHAN0_ALT_DESTADDR (LPC31_DMACHAN0_ALT_VBASE+LPC31_DMACHAN_DESTADDR_OFFSET) +#define LPC31_DMACHAN0_ALT_XFERLEN (LPC31_DMACHAN0_ALT_VBASE+LPC31_DMACHAN_XFERLEN_OFFSET) +#define LPC31_DMACHAN0_ALT_CONFIG (LPC31_DMACHAN0_ALT_VBASE+LPC31_DMACHAN_CONFIG_OFFSET) + +#define LPC31_DMACHAN1_ALT_SRCADDR (LPC31_DMACHAN1_ALT_VBASE+LPC31_DMACHAN_SRCADDR_OFFSET) +#define LPC31_DMACHAN1_ALT_DESTADDR (LPC31_DMACHAN1_ALT_VBASE+LPC31_DMACHAN_DESTADDR_OFFSET) +#define LPC31_DMACHAN1_ALT_XFERLEN (LPC31_DMACHAN1_ALT_VBASE+LPC31_DMACHAN_XFERLEN_OFFSET) +#define LPC31_DMACHAN1_ALT_CONFIG (LPC31_DMACHAN1_ALT_VBASE+LPC31_DMACHAN_CONFIG_OFFSET) + +#define LPC31_DMACHAN2_ALT_SRCADDR (LPC31_DMACHAN2_ALT_VBASE+LPC31_DMACHAN_SRCADDR_OFFSET) +#define LPC31_DMACHAN2_ALT_DESTADDR (LPC31_DMACHAN2_ALT_VBASE+LPC31_DMACHAN_DESTADDR_OFFSET) +#define LPC31_DMACHAN2_ALT_XFERLEN (LPC31_DMACHAN2_ALT_VBASE+LPC31_DMACHAN_XFERLEN_OFFSET) +#define LPC31_DMACHAN2_ALT_CONFIG (LPC31_DMACHAN2_ALT_VBASE+LPC31_DMACHAN_CONFIG_OFFSET) + +#define LPC31_DMACHAN3_ALT_SRCADDR (LPC31_DMACHAN3_ALT_VBASE+LPC31_DMACHAN_SRCADDR_OFFSET) +#define LPC31_DMACHAN3_ALT_DESTADDR (LPC31_DMACHAN3_ALT_VBASE+LPC31_DMACHAN_DESTADDR_OFFSET) +#define LPC31_DMACHAN3_ALT_XFERLEN (LPC31_DMACHAN3_ALT_VBASE+LPC31_DMACHAN_XFERLEN_OFFSET) +#define LPC31_DMACHAN3_ALT_CONFIG (LPC31_DMACHAN3_ALT_VBASE+LPC31_DMACHAN_CONFIG_OFFSET) + +#define LPC31_DMACHAN4_ALT_SRCADDR (LPC31_DMACHAN4_ALT_VBASE+LPC31_DMACHAN_SRCADDR_OFFSET) +#define LPC31_DMACHAN4_ALT_DESTADDR (LPC31_DMACHAN4_ALT_VBASE+LPC31_DMACHAN_DESTADDR_OFFSET) +#define LPC31_DMACHAN4_ALT_XFERLEN (LPC31_DMACHAN4_ALT_VBASE+LPC31_DMACHAN_XFERLEN_OFFSET) +#define LPC31_DMACHAN4_ALT_CONFIG (LPC31_DMACHAN4_ALT_VBASE+LPC31_DMACHAN_CONFIG_OFFSET) + +#define LPC31_DMACHAN5_ALT_SRCADDR (LPC31_DMACHAN5_ALT_VBASE+LPC31_DMACHAN_SRCADDR_OFFSET) +#define LPC31_DMACHAN5_ALT_DESTADDR (LPC31_DMACHAN5_ALT_VBASE+LPC31_DMACHAN_DESTADDR_OFFSET) +#define LPC31_DMACHAN5_ALT_XFERLEN (LPC31_DMACHAN5_ALT_VBASE+LPC31_DMACHAN_XFERLEN_OFFSET) +#define LPC31_DMACHAN5_ALT_CONFIG (LPC31_DMACHAN5_ALT_VBASE+LPC31_DMACHAN_CONFIG_OFFSET) + +#define LPC31_DMACHAN6_ALT_SRCADDR (LPC31_DMACHAN6_ALT_VBASE+LPC31_DMACHAN_SRCADDR_OFFSET) +#define LPC31_DMACHAN6_ALT_DESTADDR (LPC31_DMACHAN6_ALT_VBASE+LPC31_DMACHAN_DESTADDR_OFFSET) +#define LPC31_DMACHAN6_ALT_XFERLEN (LPC31_DMACHAN6_ALT_VBASE+LPC31_DMACHAN_XFERLEN_OFFSET) +#define LPC31_DMACHAN6_ALT_CONFIG (LPC31_DMACHAN6_ALT_VBASE+LPC31_DMACHAN_CONFIG_OFFSET) + +#define LPC31_DMACHAN7_ALT_SRCADDR (LPC31_DMACHAN7_ALT_VBASE+LPC31_DMACHAN_SRCADDR_OFFSET) +#define LPC31_DMACHAN7_ALT_DESTADDR (LPC31_DMACHAN7_ALT_VBASE+LPC31_DMACHAN_DESTADDR_OFFSET) +#define LPC31_DMACHAN7_ALT_XFERLEN (LPC31_DMACHAN7_ALT_VBASE+LPC31_DMACHAN_XFERLEN_OFFSET) +#define LPC31_DMACHAN7_ALT_CONFIG (LPC31_DMACHAN7_ALT_VBASE+LPC31_DMACHAN_CONFIG_OFFSET) + +#define LPC31_DMACHAN8_ALT_SRCADDR (LPC31_DMACHAN8_ALT_VBASE+LPC31_DMACHAN_SRCADDR_OFFSET) +#define LPC31_DMACHAN8_ALT_DESTADDR (LPC31_DMACHAN8_ALT_VBASE+LPC31_DMACHAN_DESTADDR_OFFSET) +#define LPC31_DMACHAN8_ALT_XFERLEN (LPC31_DMACHAN8_ALT_VBASE+LPC31_DMACHAN_XFERLEN_OFFSET) +#define LPC31_DMACHAN8_ALT_CONFIG (LPC31_DMACHAN8_ALT_VBASE+LPC31_DMACHAN_CONFIG_OFFSET) + +#define LPC31_DMACHAN9_ALT_SRCADDR (LPC31_DMACHAN9_ALT_VBASE+LPC31_DMACHAN_SRCADDR_OFFSET) +#define LPC31_DMACHAN9_ALT_DESTADDR (LPC31_DMACHAN9_ALT_VBASE+LPC31_DMACHAN_DESTADDR_OFFSET) +#define LPC31_DMACHAN9_ALT_XFERLEN (LPC31_DMACHAN9_ALT_VBASE+LPC31_DMACHAN_XFERLEN_OFFSET) +#define LPC31_DMACHAN9_ALT_CONFIG (LPC31_DMACHAN9_ALT_VBASE+LPC31_DMACHAN_CONFIG_OFFSET) + +#define LPC31_DMACHAN10_ALT_SRCADDR (LPC31_DMACHAN10_ALT_VBASE+LPC31_DMACHAN_SRCADDR_OFFSET) +#define LPC31_DMACHAN10_ALT_DESTADDR (LPC31_DMACHAN10_ALT_VBASE+LPC31_DMACHAN_DESTADDR_OFFSET) +#define LPC31_DMACHAN10_ALT_XFERLEN (LPC31_DMACHAN10_ALT_VBASE+LPC31_DMACHAN_XFERLEN_OFFSET) +#define LPC31_DMACHAN10_ALT_CONFIG (LPC31_DMACHAN10_ALT_VBASE+LPC31_DMACHAN_CONFIG_OFFSET) + +#define LPC31_DMACHAN11_ALT_SRCADDR (LPC31_DMACHAN11_ALT_VBASE+LPC31_DMACHAN_SRCADDR_OFFSET) +#define LPC31_DMACHAN11_ALT_DESTADDR (LPC31_DMACHAN11_ALT_VBASE+LPC31_DMACHAN_DESTADDR_OFFSET) +#define LPC31_DMACHAN11_ALT_XFERLEN (LPC31_DMACHAN11_ALT_VBASE+LPC31_DMACHAN_XFERLEN_OFFSET) +#define LPC31_DMACHAN11_ALT_CONFIG (LPC31_DMACHAN11_ALT_VBASE+LPC31_DMACHAN_CONFIG_OFFSET) + +/* DMA global register (virtual) addresses ******************************************************/ + +#define LPC31_DMA_ALTENABLE (LPC31_DMA_VBASE+LPC31_DMA_ALTENABLE_OFFSET) +#define LPC31_DMA_IRQSTATUSCLR (LPC31_DMA_VBASE+LPC31_DMA_IRQSTATUSCLR_OFFSET) +#define LPC31_DMA_IRQMASK (LPC31_DMA_VBASE+LPC31_DMA_IRQMASK_OFFSET) +#define LPC31_DMA_TESTSTATUS (LPC31_DMA_VBASE+LPC31_DMA_TESTSTATUS_OFFSET) +#define LPC31_DMA_SOFTINT (LPC31_DMA_VBASE+LPC31_DMA_SOFTINT_OFFSET) + +/* DMA channel register bit definitions *********************************************************/ + +/* TRANSFER_LENGTH (addresses 0x17000008 (channel 0) to 0x17000168 (channel 11)) */ + +#define DMACHAN_XFRLEN_SHIFT (0) /* Bits 0-20: Transfer length */ +#define DMACHAN_XFRLEN_MASK (0x001fffff << DMACHAN_XFRLEN_SHIFT) + +/* CONFIGURATION (addresses 0x1700000c (channel 0) to 0x1700016c (channel 11)) */ + +#define DMACHAN_CONFIG_CIRC (1 << 18) /* Bit 18: Enable circular buffer */ +#define DMACHAN_CONFIG_COMPCHENABLE (1 << 17) /* Bit 17: Enable companion channel */ +#define DMACHAN_CONFIG_COMPCHNR_SHIFT (13) /* Bits 13-15: Companion channel number */ +#define DMACHAN_CONFIG_COMPCHNR_MASK (7 << DMACHAN_CONFIG_COMPCHNR_SHIFT) +#define DMACHAN_CONFIG_INVENDIAN (1 << 12) /* Bit 12: Invert endian-ness */ +#define DMACHAN_CONFIG_XFERSIZE_SHIFT (10) /* Bits 10-11: Transfer size */ +#define DMACHAN_CONFIG_XFERSIZE_MASK (3 << DMACHAN_CONFIG_XFERSIZE_SHIFT) +# define DMACHAN_CONFIG_XFERSIZE_WORDS (0 << DMACHAN_CONFIG_XFERSIZE_SHIFT) /* Transfer words */ +# define DMACHAN_CONFIG_XFERSIZE_HWORDS (1 << DMACHAN_CONFIG_XFERSIZE_SHIFT) /* Transfer half-words */ +# define DMACHAN_CONFIG_XFERSIZE_BYTES (2 << DMACHAN_CONFIG_XFERSIZE_SHIFT) /* Transfer bytes */ +# define DMACHAN_CONFIG_XFERSIZE_BURSTS (3 << DMACHAN_CONFIG_XFERSIZE_SHIFT) /* Transfer bursts */ +#define DMACHAN_CONFIG_RDSLAVENR_SHIFT (5) /* Bits 5-9: Read slave enable */ +#define DMACHAN_CONFIG_RDSLAVENR_MASK (31 << DMACHAN_CONFIG_RDSLAVENR_SHIFT) +#define DMACHAN_CONFIG_WRSLAVENR_SHIFT (0) /* Bits 0-4: Write slave enable */ +#define DMACHAN_CONFIG_WRSLAVENR_MASK (31 << DMACHAN_CONFIG_WRSLAVENR_SHIFT) + +/* ENABLE (addresses 0x17000010 (channel 0) to 0x17000170 (channel 11)) */ + +#define DMACHAN_ENABLE_BIT (1 << 0) /* Bit 0: Enable */ + +/* TRANSFER_COUNTER (addresses 0x1700001v (channel 0) to 0x1700017c (channel 11)) */ + +#define DMACHAN_XFRCOUNT_SHIFT (0) /* Bits 0-20: Transfer count */ +#define DMACHAN_XFRCOUNT_MASK (0x001fffff << DMACHAN_XFRCOUNT_SHIFT) + +/* DMA global register bit definitions **********************************************************/ + +/* ALT_ENABLE (address 0x17000400) */ + +#define DMA_ALTENABLE_CHAN11 (1 << 11) /* Bit 11: Enable channel 11 */ +#define DMA_ALTENABLE_CHAN10 (1 << 10) /* Bit 10: Enable channel 10 */ +#define DMA_ALTENABLE_CHAN9 (1 << 9) /* Bit 9: Enable channel 9 */ +#define DMA_ALTENABLE_CHAN8 (1 << 8) /* Bit 8: Enable channel 8 */ +#define DMA_ALTENABLE_CHAN7 (1 << 7) /* Bit 7: Enable channel 7 */ +#define DMA_ALTENABLE_CHAN6 (1 << 6) /* Bit 6: Enable channel 6 */ +#define DMA_ALTENABLE_CHAN5 (1 << 5) /* Bit 5: Enable channel 5 */ +#define DMA_ALTENABLE_CHAN4 (1 << 4) /* Bit 4: Enable channel 4 */ +#define DMA_ALTENABLE_CHAN3 (1 << 3) /* Bit 3: Enable channel 3 */ +#define DMA_ALTENABLE_CHAN2 (1 << 2) /* Bit 2: Enable channel 2 */ +#define DMA_ALTENABLE_CHAN1 (1 << 1) /* Bit 1: Enable channel 1 */ +#define DMA_ALTENABLE_CHAN0 (1 << 0) /* Bit 0: Enable channel 0 */ + +/* IRQ_STATUS_CLR (address 0x17000404) */ + +#define DMA_IRQSTATUSCLR_DMAABORT (1 << 31) /* Bit 31: DMA abort */ +#define DMA_IRQSTATUSCLR_SOFTINT (1 << 30) /* Bit 30: Soft interrupt, scatter gather */ +#define DMA_IRQSTATUSCLR_HALFWAY11 (1 << 23) /* Bit 23: Chan 11 more than half finished */ +#define DMA_IRQSTATUSCLR_FINISHED11 (1 << 22) /* Bit 22: Chan 11 finished */ +#define DMA_IRQSTATUSCLR_HALFWAY10 (1 << 21) /* Bit 21: Chan 10 more than half finished */ +#define DMA_IRQSTATUSCLR_FINISHED10 (1 << 20) /* Bit 20: Chan 10 finished */ +#define DMA_IRQSTATUSCLR_HALFWAY9 (1 << 19) /* Bit 19: Chan 9 more than half finished */ +#define DMA_IRQSTATUSCLR_FINISHED9 (1 << 18) /* Bit 18: Chan 9 finished */ +#define DMA_IRQSTATUSCLR_HALFWAY8 (1 << 17) /* Bit 17: Chan 8 more than half finished */ +#define DMA_IRQSTATUSCLR_FINISHED8 (1 << 16) /* Bit 16: Chan 8 finished */ +#define DMA_IRQSTATUSCLR_HALFWAY7 (1 << 15) /* Bit 15: Chan 7 more than half finished */ +#define DMA_IRQSTATUSCLR_FINISHED7 (1 << 14) /* Bit 14: Chan 7 finished */ +#define DMA_IRQSTATUSCLR_HALFWAY6 (1 << 13) /* Bit 13: Chan 6 more than half finished */ +#define DMA_IRQSTATUSCLR_FINISHED6 (1 << 12) /* Bit 12: Chan 6 finished */ +#define DMA_IRQSTATUSCLR_HALFWAY5 (1 << 11) /* Bit 11: Chan 5 more than half finished */ +#define DMA_IRQSTATUSCLR_FINISHED5 (1 << 10) /* Bit 10: Chan 5 finished */ +#define DMA_IRQSTATUSCLR_HALFWAY4 (1 << 9) /* Bit 9: Chan 4 more than half finished */ +#define DMA_IRQSTATUSCLR_FINISHED4 (1 << 8) /* Bit 8: Chan 4 finished */ +#define DMA_IRQSTATUSCLR_HALFWAY3 (1 << 7) /* Bit 7: Chan 3 more than half finished */ +#define DMA_IRQSTATUSCLR_FINISHED3 (1 << 6) /* Bit 6: Chan 3 finished */ +#define DMA_IRQSTATUSCLR_HALFWAY2 (1 << 5) /* Bit 5: Chan 2 more than half finished */ +#define DMA_IRQSTATUSCLR_FINISHED2 (1 << 4) /* Bit 4: Chan 2 finished */ +#define DMA_IRQSTATUSCLR_HALFWAY1 (1 << 3) /* Bit 3: Chan 1 more than half finished */ +#define DMA_IRQSTATUSCLR_FINISHED1 (1 << 2) /* Bit 2: Chan 1 finished */ +#define DMA_IRQSTATUSCLR_HALFWAY0 (1 << 1) /* Bit 1: Chan 0 more than half finished */ +#define DMA_IRQSTATUSCLR_FINISHED0 (1 << 0) /* Bit 0: Chan 0 finished */ + +/* IRQ_MASK (address 0x17000404) */ + +#define DMA_IRQMASK_DMAABORT (1 << 31) /* Bit 31: DMA abort */ +#define DMA_IRQMASK_SOFTINT (1 << 30) /* Bit 30: Soft interrupt, scatter gather */ +#define DMA_IRQMASK_HALFWAY11 (1 << 23) /* Bit 23: Chan 11 more than half finished */ +#define DMA_IRQMASK_FINISHED11 (1 << 22) /* Bit 22: Chan 11 finished */ +#define DMA_IRQMASK_HALFWAY10 (1 << 21) /* Bit 21: Chan 10 more than half finished */ +#define DMA_IRQMASK_FINISHED10 (1 << 20) /* Bit 20: Chan 10 finished */ +#define DMA_IRQMASK_HALFWAY9 (1 << 19) /* Bit 19: Chan 9 more than half finished */ +#define DMA_IRQMASK_FINISHED9 (1 << 18) /* Bit 18: Chan 9 finished */ +#define DMA_IRQMASK_HALFWAY8 (1 << 17) /* Bit 17: Chan 8 more than half finished */ +#define DMA_IRQMASK_FINISHED8 (1 << 16) /* Bit 16: Chan 8 finished */ +#define DMA_IRQMASK_HALFWAY7 (1 << 15) /* Bit 15: Chan 7 more than half finished */ +#define DMA_IRQMASK_FINISHED7 (1 << 14) /* Bit 14: Chan 7 finished */ +#define DMA_IRQMASK_HALFWAY6 (1 << 13) /* Bit 13: Chan 6 more than half finished */ +#define DMA_IRQMASK_FINISHED6 (1 << 12) /* Bit 12: Chan 6 finished */ +#define DMA_IRQMASK_HALFWAY5 (1 << 11) /* Bit 11: Chan 5 more than half finished */ +#define DMA_IRQMASK_FINISHED5 (1 << 10) /* Bit 10: Chan 5 finished */ +#define DMA_IRQMASK_HALFWAY4 (1 << 9) /* Bit 9: Chan 4 more than half finished */ +#define DMA_IRQMASK_FINISHED4 (1 << 8) /* Bit 8: Chan 4 finished */ +#define DMA_IRQMASK_HALFWAY3 (1 << 7) /* Bit 7: Chan 3 more than half finished */ +#define DMA_IRQMASK_FINISHED3 (1 << 6) /* Bit 6: Chan 3 finished */ +#define DMA_IRQMASK_HALFWAY2 (1 << 5) /* Bit 5: Chan 2 more than half finished */ +#define DMA_IRQMASK_FINISHED2 (1 << 4) /* Bit 4: Chan 2 finished */ +#define DMA_IRQMASK_HALFWAY1 (1 << 3) /* Bit 3: Chan 1 more than half finished */ +#define DMA_IRQMASK_FINISHED1 (1 << 2) /* Bit 2: Chan 1 finished */ +#define DMA_IRQMASK_HALFWAY0 (1 << 1) /* Bit 1: Chan 0 more than half finished */ +#define DMA_IRQMASK_FINISHED0 (1 << 0) /* Bit 0: Chan 0 finished */ + +/* SOFT_INT (address 0x1700040c) */ + +#define DMA_SOFTINT_ENABLE (1 << 0) /* Bit 0: Enable soft interrupt */ + +/************************************************************************************************ + * Public Types + ************************************************************************************************/ + +/************************************************************************************************ + * Public Data + ************************************************************************************************/ + +/************************************************************************************************ + * Public Functions + ************************************************************************************************/ + +#endif /* __ARCH_ARM_SRC_LPC31XX_LPC31_DMA_H */ diff --git a/nuttx/arch/arm/src/lpc31xx/lpc31_esrndx.c b/nuttx/arch/arm/src/lpc31xx/lpc31_esrndx.c new file mode 100755 index 000000000..802b63f33 --- /dev/null +++ b/nuttx/arch/arm/src/lpc31xx/lpc31_esrndx.c @@ -0,0 +1,134 @@ +/************************************************************************ + * arch/arm/src/lpc31xx/lpc31_esrndx.c + * + * Copyright (C) 2009-2010 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * References: + * - UM10314 LPC3130/31 User manual Rev. 1.01 — 9 September 2009 + * - lpc313x.cdl.drivers.zip example driver code + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name NuttX nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ************************************************************************/ + +/************************************************************************ + * Included Files + ************************************************************************/ + +#include +#include + +#include "up_arch.h" +#include "lpc31_cgudrvr.h" + +/************************************************************************ + * Pre-processor Definitions + ************************************************************************/ + +/************************************************************************ + * Private Data + ************************************************************************/ + +/************************************************************************ + * Private Functions + ************************************************************************/ + +/************************************************************************ + * Public Functions + ************************************************************************/ + +/************************************************************************ + * Name: lpc31_esrndx + * + * Description: + * Given a clock ID, return the index of the corresponding ESR + * register (or ESRNDX_INVALID if there is no ESR associated with + * this clock ID). Indexing of ESRs differs slightly from the clock + * ID: There are 92 clock IDs but only 89 ESR regisers. There are no + * ESR registers for : + * + * + * CLKID_I2SRXBCK0 Clock ID 87: I2SRX_BCK0 + * CLKID_I2SRXBCK1, Clock ID 88: I2SRX_BCK1 + * + * and + * + * CLKID_SYSCLKO Clock ID 91: SYSCLK_O + * + ************************************************************************/ + +int lpc31_esrndx(enum lpc31_clockid_e clkid) +{ + int esrndx = (int)clkid; + + /* There ar 89 Enable Select Registers (ESR). Indexing for these + * registers is identical to indexing to other registers (like PCR), + * except that there are no ESR registers for + * + * + * CLKID_I2SRXBCK0 Clock ID 87: I2SRX_BCK0 + * CLKID_I2SRXBCK1, Clock ID 88: I2SRX_BCK1 + * + * and + * + * CLKID_SYSCLKO Clock ID 91: SYSCLK_O + */ + + switch (clkid) + { + /* There are no ESR registers corresponding to the following + * three clocks: + */ + + case CLKID_I2SRXBCK0: + case CLKID_I2SRXBCK1: + case CLKID_SYSCLKO: + esrndx = ESRNDX_INVALID; + break; + + /* These clock IDs are a special case and need to be adjusted + * by two: + * + * CLKID_SPICLK Clock ID 89, ESR index 87 + * CLKID_SPICLKGATED Clock ID 90, ESR index 88 + */ + + case CLKID_SPICLK: + case CLKID_SPICLKGATED: + esrndx = esrndx - 2; + break; + + /* The rest of the indices match up and we don't have to do anything. */ + + default: + break; + } + + return esrndx; +} diff --git a/nuttx/arch/arm/src/lpc31xx/lpc31_evntrtr.h b/nuttx/arch/arm/src/lpc31xx/lpc31_evntrtr.h new file mode 100755 index 000000000..aa24c755b --- /dev/null +++ b/nuttx/arch/arm/src/lpc31xx/lpc31_evntrtr.h @@ -0,0 +1,264 @@ +/******************************************************************************************************** + * arch/arm/src/lpc31xx/lpc31_evntrtr.h + * + * Copyright (C) 2009-2010 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * 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_LPC31XX_LPC31_EVNTRTR_H +#define __ARCH_ARM_SRC_LPC31XX_LPC31_EVNTRTR_H + +/******************************************************************************************************** + * Included Files + ********************************************************************************************************/ + +#include +#include "lpc31_memorymap.h" + +/******************************************************************************************************** + * Pre-processor Definitions + ********************************************************************************************************/ + +/* EVNTRTR register base address offset into the APB0 domain ********************************************/ + +#define LPC31_EVNTRTR_VBASE (LPC31_APB0_VADDR+LPC31_APB0_EVNTRTR_OFFSET) +#define LPC31_EVNTRTR_PBASE (LPC31_APB0_PADDR+LPC31_APB0_EVNTRTR_OFFSET) + +/* Sizes of things */ + +#define LPC31_EVNTRTR_NBANKS 4 /* Banks b=0-3 */ +#define LPC31_EVNTRTR_NOUTPUTS 5 /* Outputs o=0-4 (incl CGU Wakeup) */ +#define LPC31_EVNTRTR_NEVENTS (32*LPC31_EVNTRTR_NBANKS) + +#define _B(b) ((b)<<2) /* Maps bank number 0-3 to word offset */ +#define _O(o) ((o)<<5) /* Maps output to bank group offset */ +#define _OB(o,b) (_O(o)+_B(b)) /* Mqpw output and bank to word offset */ + +#define EVNTRTR_EVENT(bank,bit) ((bank)<<5|bit) /* Makes a event number from a bank and bit */ +#define EVNTRTR_BANK(e) ((e)>>5) /* Maps a event to a bank */ +#define EVNTRTR_BIT(e) ((e)&0x1f) /* Maps a event to a bit */ + +/* EVNTRTR register offsets (with respect to the EVNTRTR base) ******************************************/ + + /* 0x0000-0x0bff: Reserved */ +#define LPC31_EVNTRTR_PEND_OFFSET(b) (0x0c00+_B(b)) /* Input event pending */ +#define LPC31_EVNTRTR_INTCLR_OFFSET(b) (0x0c20+_B(b)) /* Input event clear */ +#define LPC31_EVNTRTR_INTSET_OFFSET(b) (0x0c40+_B(b)) /* Input event set */ +#define LPC31_EVNTRTR_MASK_OFFSET(b) (0x0c60+_B(b)) /* Input event mask */ +#define LPC31_EVNTRTR_MASKCLR_OFFSET(b) (0x0c80+_B(b)) /* Input event mask clear */ +#define LPC31_EVNTRTR_MASKSET_OFFSET(b) (0x0ca0+_B(b)) /* Input event mask set */ +#define LPC31_EVNTRTR_APR_OFFSET(b) (0x0cc0+_B(b)) /* Input event activation polarity */ +#define LPC31_EVNTRTR_ATR_OFFSET(b) (0x0ce0+_B(b)) /* Input event activation type */ +#define LPC31_EVNTRTR_RSR_OFFSET(b) (0x0d20+_B(b)) /* Input event raw status */ +#define LPC31_EVNTRTR_INTOUT_OFFSET 0x0d40 /* State of interrupt output pins */ + /* 0x0e00-0x0ffc: Reserved */ +#define LPC31_EVNTRTR_INTOUTPEND_OFFSET(o,b) (0x1000+_OB(o,b)) /* Interrupt output 'o' pending */ +#define LPC31_EVNTRTR_CGUWKUPPEND_OFFSET(b) (0x1000+_OB(4,b)) /* cgu_wakeup pending */ +#define LPC31_EVNTRTR_INTOUTMASK_OFFSET(o,b) (0x1400+_OB(o,b)) /* Interrupt output 'o' mask */ +#define LPC31_EVNTRTR_CGUWKUPMASK_OFFSET(b) (0x1400+_OB(4,b)) /* cgu_wakeup mask */ +#define LPC31_EVNTRTR_INTOUTMASKCLR_OFFSET(o,b) (0x1800+_OB(o,b)) /* Interrupt output 'o' mask clear */ +#define LPC31_EVNTRTR_CGUWKUPMASKCLR_OFFSET(b) (0x1800+_OB(4,b)) /* cgu_wakeup mask clear */ +#define LPC31_EVNTRTR_INTOUTMASKSET_OFFSET(o,b) (0x1c00+_OB(o,b)) /* Interrupt output 'o' mask set */ +#define LPC31_EVNTRTR_CGUWKUPMASKSET_OFFSET(b) (0x1c00+_OB(4,b)) /* cgu_wakeup mask set */ + +/* EVNTRTR register (virtual) addresses *********************************************************************/ + +#define LPC31_EVNTRTR_PEND(b) (LPC31_EVNTRTR_VBASE+LPC31_EVNTRTR_PEND_OFFSET(b)) +#define LPC31_EVNTRTR_INTCLR(b) (LPC31_EVNTRTR_VBASE+LPC31_EVNTRTR_INTCLR_OFFSET(b)) +#define LPC31_EVNTRTR_INTSET(b) (LPC31_EVNTRTR_VBASE+LPC31_EVNTRTR_INTSET_OFFSET(b)) +#define LPC31_EVNTRTR_MASK(b) (LPC31_EVNTRTR_VBASE+LPC31_EVNTRTR_MASK_OFFSET(b)) +#define LPC31_EVNTRTR_MASKCLR(b) (LPC31_EVNTRTR_VBASE+LPC31_EVNTRTR_MASKCLR_OFFSET(b)) +#define LPC31_EVNTRTR_MASKSET(b) (LPC31_EVNTRTR_VBASE+LPC31_EVNTRTR_MASKSET_OFFSET(b)) +#define LPC31_EVNTRTR_APR(b) (LPC31_EVNTRTR_VBASE+LPC31_EVNTRTR_APR_OFFSET(b)) +#define LPC31_EVNTRTR_ATR(b) (LPC31_EVNTRTR_VBASE+LPC31_EVNTRTR_ATR_OFFSET(b)) +#define LPC31_EVNTRTR_RSR(b) (LPC31_EVNTRTR_VBASE+LPC31_EVNTRTR_RSR_OFFSET(b)) +#define LPC31_EVNTRTR_INTOUT (LPC31_EVNTRTR_VBASE+LPC31_EVNTRTR_INTOUT_OFFSET) +#define LPC31_EVNTRTR_INTOUTPEND(o,b) (LPC31_EVNTRTR_VBASE+LPC31_EVNTRTR_INTOUTPEND_OFFSET(o,b)) +#define LPC31_EVNTRTR_CGUWKUPPEND(b) (LPC31_EVNTRTR_VBASE+LPC31_EVNTRTR_CGUWKUPPEND_OFFSET(b)) +#define LPC31_EVNTRTR_INTOUTMASK(o,b) (LPC31_EVNTRTR_VBASE+LPC31_EVNTRTR_INTOUTMASK_OFFSET(o,b)) +#define LPC31_EVNTRTR_CGUWKUPMASK(b) (LPC31_EVNTRTR_VBASE+LPC31_EVNTRTR_CGUWKUPMASK_OFFSET(b)) +#define LPC31_EVNTRTR_INTOUTMASKCLR(o,b) (LPC31_EVNTRTR_VBASE+LPC31_EVNTRTR_INTOUTMASKCLR_OFFSET(o,b)) +#define LPC31_EVNTRTR_CGUWKUPMASKCLR(b) (LPC31_EVNTRTR_VBASE+LPC31_EVNTRTR_CGUWKUPMASKCLR_OFFSET(b)) +#define LPC31_EVNTRTR_INTOUTMASKSET(o,b) (LPC31_EVNTRTR_VBASE+LPC31_EVNTRTR_INTOUTMASKSET_OFFSET(o,b)) +#define LPC31_EVNTRTR_CGUWKUPMASKSET(b) (LPC31_EVNTRTR_VBASE+LPC31_EVNTRTR_CGUWKUPMASKSET_OFFSET(b) + +/* EVNTRTR event definitions ********************************************************************************/ +/* Bank 0 */ + +#define EVENTRTR_EBID6 EVNTRTR_EVENT(0,31) /* Input event from GPIO pin */ +#define EVENTRTR_EBID5 EVNTRTR_EVENT(0,30) /* Input event from GPIO pin */ +#define EVENTRTR_EBID4 EVNTRTR_EVENT(0,29) /* Input event from GPIO pin */ +#define EVENTRTR_EBID3 EVNTRTR_EVENT(0,28) /* Input event from GPIO pin */ +#define EVENTRTR_EBID2 EVNTRTR_EVENT(0,27) /* Input event from GPIO pin */ +#define EVENTRTR_EBID1 EVNTRTR_EVENT(0,26) /* Input event from GPIO pin */ +#define EVENTRTR_EBID0 EVNTRTR_EVENT(0,25) /* Input event from GPIO pin */ +#define EVENTRTR_MNANDRYBN3 EVNTRTR_EVENT(0,24) /* Input event from GPIO pin */ +#define EVENTRTR_MNANDRYBN2 EVNTRTR_EVENT(0,23) /* Input event from GPIO pin */ +#define EVENTRTR_MNANDRYBN1 EVNTRTR_EVENT(0,22) /* Input event from GPIO pin */ +#define EVENTRTR_MNANDRYBN0 EVNTRTR_EVENT(0,21) /* Input event from GPIO pin */ +#define EVENTRTR_MLCDRWWR EVNTRTR_EVENT(0,20) /* Input event from GPIO pin */ +#define EVENTRTR_MLCDERD EVNTRTR_EVENT(0,19) /* Input event from GPIO pin */ +#define EVENTRTR_MLCDCSB EVNTRTR_EVENT(0,18) /* Input event from GPIO pin */ +#define EVENTRTR_MLCDRS EVNTRTR_EVENT(0,17) /* Input event from GPIO pin */ +#define EVENTRTR_MLCDDB15 EVNTRTR_EVENT(0,16) /* Input event from GPIO pin */ +#define EVENTRTR_MLCDDB14 EVNTRTR_EVENT(0,15) /* Input event from GPIO pin */ +#define EVENTRTR_MLCDDB13 EVNTRTR_EVENT(0,14) /* Input event from GPIO pin */ +#define EVENTRTR_MLCDDB12 EVNTRTR_EVENT(0,13) /* Input event from GPIO pin */ +#define EVENTRTR_MLCDDB11 EVNTRTR_EVENT(0,12) /* Input event from GPIO pin */ +#define EVENTRTR_MLCDDB10 EVNTRTR_EVENT(0,11) /* Input event from GPIO pin */ +#define EVENTRTR_MLCDDB9 EVNTRTR_EVENT(0,10) /* Input event from GPIO pin */ +#define EVENTRTR_MLCDDB8 EVNTRTR_EVENT(0,9) /* Input event from GPIO pin */ +#define EVENTRTR_MLCDDB7 EVNTRTR_EVENT(0,8) /* Input event from GPIO pin */ +#define EVENTRTR_MLCDDB6 EVNTRTR_EVENT(0,7) /* Input event from GPIO pin */ +#define EVENTRTR_MLCDDB5 EVNTRTR_EVENT(0,6) /* Input event from GPIO pin */ +#define EVENTRTR_MLCDDB4 EVNTRTR_EVENT(0,5) /* Input event from GPIO pin */ +#define EVENTRTR_MLCDDB3 EVNTRTR_EVENT(0,4) /* Input event from GPIO pin */ +#define EVENTRTR_MLCDDB2 EVNTRTR_EVENT(0,3) /* Input event from GPIO pin */ +#define EVENTRTR_MLCDDB1 EVNTRTR_EVENT(0,2) /* Input event from GPIO pin */ +#define EVENTRTR_MLCDDB0 EVNTRTR_EVENT(0,1) /* Input event from GPIO pin */ +#define EVENTRTR_PCMINT EVNTRTR_EVENT(0,0) /* Input event from PCM */ + +/* Bank 1 */ + +#define EVENTRTR_GPIO16 EVNTRTR_EVENT(1,31) /* Input event from GPIO pin */ +#define EVENTRTR_GPIO15 EVNTRTR_EVENT(1,30) /* Input event from GPIO pin */ +#define EVENTRTR_GPIO14 EVNTRTR_EVENT(1,29) /* Input event from GPIO pin */ +#define EVENTRTR_GPIO13 EVNTRTR_EVENT(1,28) /* Input event from GPIO pin */ +#define EVENTRTR_GPIO12 EVNTRTR_EVENT(1,27) /* Input event from GPIO pin */ +#define EVENTRTR_GPIO11 EVNTRTR_EVENT(1,26) /* Input event from GPIO pin */ +#define EVENTRTR_MGPIO10 EVNTRTR_EVENT(1,25) /* Input event from GPIO pin */ +#define EVENTRTR_MGPIO9 EVNTRTR_EVENT(1,24) /* Input event from GPIO pin */ +#define EVENTRTR_MGPIO8 EVNTRTR_EVENT(1,23) /* Input event from GPIO pin */ +#define EVENTRTR_MGPIO7 EVNTRTR_EVENT(1,22) /* Input event from GPIO pin */ +#define EVENTRTR_MGPIO6 EVNTRTR_EVENT(1,21) /* Input event from GPIO pin */ +#define EVENTRTR_MGPIO5 EVNTRTR_EVENT(1,20) /* Input event from GPIO pin */ +#define EVENTRTR_GPIO4 EVNTRTR_EVENT(1,19) /* Input event from GPIO pin */ +#define EVENTRTR_GPIO3 EVNTRTR_EVENT(1,18) /* Input event from GPIO pin */ +#define EVENTRTR_GPIO2 EVNTRTR_EVENT(1,17) /* Input event from GPIO pin */ +#define EVENTRTR_GPIO1 EVNTRTR_EVENT(1,16) /* Input event from GPIO pin */ +#define EVENTRTR_GPIO0 EVNTRTR_EVENT(1,15) /* Input event from GPIO pin */ +#define EVENTRTR_EBINRASBLOUT1 EVNTRTR_EVENT(1,14) /* Input event from GPIO pin */ +#define EVENTRTR_EBINCASBLOUT0 EVNTRTR_EVENT(1,13) /* Input event from GPIO pin */ +#define EVENTRTR_EBIDQM0NOE EVNTRTR_EVENT(1,12) /* Input event from GPIO pin */ +#define EVENTRTR_EBIA1CLE EVNTRTR_EVENT(1,11) /* Input event from GPIO pin */ +#define EVENTRTR_EBIA0ALE EVNTRTR_EVENT(1,10) /* Input event from GPIO pin */ +#define EVENTRTR_EBINWE EVNTRTR_EVENT(1,9) /* Input event from GPIO pin */ +#define EVENTRTR_EBID15 EVNTRTR_EVENT(1,8) /* Input event from GPIO pin */ +#define EVENTRTR_EBID14 EVNTRTR_EVENT(1,7) /* Input event from GPIO pin */ +#define EVENTRTR_EBID13 EVNTRTR_EVENT(1,6) /* Input event from GPIO pin */ +#define EVENTRTR_EBID12 EVNTRTR_EVENT(1,5) /* Input event from GPIO pin */ +#define EVENTRTR_EBID11 EVNTRTR_EVENT(1,4) /* Input event from GPIO pin */ +#define EVENTRTR_EBID10 EVNTRTR_EVENT(1,3) /* Input event from GPIO pin */ +#define EVENTRTR_EBID9 EVNTRTR_EVENT(1,2) /* Input event from GPIO pin */ +#define EVENTRTR_EBID8 EVNTRTR_EVENT(1,1) /* Input event from GPIO pin */ +#define EVENTRTR_EBID7 EVNTRTR_EVENT(1,0) /* Input event from GPIO pin */ + +/* Bank 2 */ + +#define EVENTRTR_PWMDATA EVNTRTR_EVENT(2,31) /* Input event from GPIO pin */ +#define EVENTRTR_I2CSCL1 EVNTRTR_EVENT(2,30) /* Input event from GPIO pin */ +#define EVENTRTR_I2CSDA1 EVNTRTR_EVENT(2,29) /* Input event from GPIO pin */ +#define EVENTRTR_CLK256FSO EVNTRTR_EVENT(2,28) /* Input event from GPIO pin */ +#define EVENTRTR_I2STXWS1 EVNTRTR_EVENT(2,27) /* Input event from GPIO pin */ +#define EVENTRTR_I2STXBCK1 EVNTRTR_EVENT(2,26) /* Input event from GPIO pin */ +#define EVENTRTR_I2STXDATA1 EVNTRTR_EVENT(2,25) /* Input event from GPIO pin */ +#define EVENTRTR_I2SRXWS1 EVNTRTR_EVENT(2,24) /* Input event from GPIO pin */ +#define EVENTRTR_I2SRXBCK1 EVNTRTR_EVENT(2,23) /* Input event from GPIO pin */ +#define EVENTRTR_I2SRXDATA1 EVNTRTR_EVENT(2,22) /* Input event from GPIO pin */ +#define EVENTRTR_I2SRXWS0 EVNTRTR_EVENT(2,21) /* Input event from GPIO pin */ +#define EVENTRTR_I2SRXDATA0 EVNTRTR_EVENT(2,20) /* Input event from GPIO pin */ +#define EVENTRTR_I2SRXBCK0 EVNTRTR_EVENT(2,19) /* Input event from GPIO pin */ +#define EVENTRTR_MI2STXWS0 EVNTRTR_EVENT(2,18) /* Input event from GPIO pin */ +#define EVENTRTR_MI2STXDATA0 EVNTRTR_EVENT(2,17) /* Input event from GPIO pin */ +#define EVENTRTR_MI2STXBCK0 EVNTRTR_EVENT(2,16) /* Input event from GPIO pin */ +#define EVENTRTR_MI2STXCLK0 EVNTRTR_EVENT(2,15) /* Input event from GPIO pin */ +#define EVENTRTR_MUARTRTSN EVNTRTR_EVENT(2,14) /* Input event from GPIO pin */ +#define EVENTRTR_MUARTCTSN EVNTRTR_EVENT(2,13) /* Input event from GPIO pin */ +#define EVENTRTR_UARTTXD EVNTRTR_EVENT(2,12) /* Input event from GPIO pin */ +#define EVENTRTR_UARTRXD EVNTRTR_EVENT(2,11) /* Input event from GPIO pin */ +#define EVENTRTR_SPICSOUT0 EVNTRTR_EVENT(2,10) /* Input event from GPIO pin */ +#define EVENTRTR_SPISCK EVNTRTR_EVENT(2,9) /* Input event from GPIO pin */ +#define EVENTRTR_SPICSIN EVNTRTR_EVENT(2,8) /* Input event from GPIO pin */ +#define EVENTRTR_SPIMOSI EVNTRTR_EVENT(2,7) /* Input event from GPIO pin */ +#define EVENTRTR_SPIMISO EVNTRTR_EVENT(2,6) /* Input event from GPIO pin */ +#define EVENTRTR_NANDNCS3 EVNTRTR_EVENT(2,5) /* Input event from GPIO pin */ +#define EVENTRTR_NANDNCS2 EVNTRTR_EVENT(2,4) /* Input event from GPIO pin */ +#define EVENTRTR_NANDNCS1 EVNTRTR_EVENT(2,3) /* Input event from GPIO pin */ +#define EVENTRTR_NANDNCS0 EVNTRTR_EVENT(2,2) /* Input event from GPIO pin */ +#define EVENTRTR_GPIO18 EVNTRTR_EVENT(2,1) /* Input event from GPIO pin */ +#define EVENTRTR_GPIO17 EVNTRTR_EVENT(2,0) /* Input event from GPIO pin */ + +/* Bank 3 */ + /* 30-31: Reserved */ +#define EVENTRTR_ISRAM1MRCFINISHED EVNTRTR_EVENT(3,29) /* ISRAM1 redundancy controller event */ +#define EVENTRTR_ISRAM0MRCFINISHED EVNTRTR_EVENT(3,28) /* ISRAM0 redundancy controller event */ +#define EVENTRTR_USBID EVNTRTR_EVENT(3,27) /* Input event from GPIO pin */ +#define EVENTRTR_USBOTGVBUSPWREN EVNTRTR_EVENT(3,26) /* Input event from USB */ +#define EVENTRTR_USBATXPLLLOCK EVNTRTR_EVENT(3,25) /* USB PLL lock event */ +#define EVENTRTR_USBOTGAHBNEEDCLK EVNTRTR_EVENT(3,24) /* Input event from USB */ +#define EVENTRTR_USBVBUS EVNTRTR_EVENT(3,23) /* Input event from USB VBUS pin */ +#define EVENTRTR_MCICLK EVNTRTR_EVENT(3,22) /* Input event from GPIO pin */ +#define EVENTRTR_MCICMD EVNTRTR_EVENT(3,21) /* Input event from GPIO pin */ +#define EVENTRTR_MCIDAT7 EVNTRTR_EVENT(3,20) /* Input event from GPIO pin */ +#define EVENTRTR_MCIDAT6 EVNTRTR_EVENT(3,19) /* Input event from GPIO pin */ +#define EVENTRTR_MCIDAT5 EVNTRTR_EVENT(3,18) /* Input event from GPIO pin */ +#define EVENTRTR_MCIDAT4 EVNTRTR_EVENT(3,17) /* Input event from GPIO pin */ +#define EVENTRTR_MCIDAT3 EVNTRTR_EVENT(3,16) /* Input event from GPIO pin */ +#define EVENTRTR_MCIDAT2 EVNTRTR_EVENT(3,15) /* Input event from GPIO pin */ +#define EVENTRTR_MCIDAT1 EVNTRTR_EVENT(3,14) /* Input event from GPIO pin */ +#define EVENTRTR_MCIDAT0 EVNTRTR_EVENT(3,13) /* Input event from GPIO pin */ +#define EVENTRTR_ARM926LPNIRQ EVNTRTR_EVENT(3,12) /* Reflects nIRQ signal to ARM core */ +#define EVENTRTR_ARM926LPNFIQ EVNTRTR_EVENT(3,11) /* Reflects nFIQ signal to ARM core */ +#define EVENTRTR_I2C1SCLN EVNTRTR_EVENT(3,10) /* Input event from I2C1 */ +#define EVENTRTR_I2C0SCLN EVNTRTR_EVENT(3,9) /* Input event from I2C0 */ +#define EVENTRTR_UART EVNTRTR_EVENT(3,8) /* Input event from UART */ +#define EVENTRTR_WDOGM0 EVNTRTR_EVENT(3,7) /* Input event from Watchdog Timer */ +#define EVENTRTR_ADCINT EVNTRTR_EVENT(3,6) /* Input event from ADC */ +#define EVENTRTR_TIMER3INTCT1 EVNTRTR_EVENT(3,5) /* Input event from Timer 3 */ +#define EVENTRTR_TIMER2INTCT1 EVNTRTR_EVENT(3,4) /* Input event from Timer 2 */ +#define EVENTRTR_TIMER1INTCT1 EVNTRTR_EVENT(3,3) /* Input event from Timer 1 */ +#define EVENTRTR_TIMER0INTCT1 EVNTRTR_EVENT(3,2) /* Input event from Timer 0 */ +#define EVENTRTR_GPIO20 EVNTRTR_EVENT(3,1) /* Input event from GPIO20 */ +#define EVENTRTR_GPIO19 EVNTRTR_EVENT(3,0) /* Input event from GPIO19 */ + +/******************************************************************************************************** + * Public Types + ********************************************************************************************************/ + +/******************************************************************************************************** + * Public Data + ********************************************************************************************************/ + +/******************************************************************************************************** + * Public Functions + ********************************************************************************************************/ + +#endif /* __ARCH_ARM_SRC_LPC31XX_LPC31_EVNTRTR_H */ diff --git a/nuttx/arch/arm/src/lpc31xx/lpc31_fdcndx.c b/nuttx/arch/arm/src/lpc31xx/lpc31_fdcndx.c new file mode 100755 index 000000000..546705eec --- /dev/null +++ b/nuttx/arch/arm/src/lpc31xx/lpc31_fdcndx.c @@ -0,0 +1,127 @@ +/************************************************************************ + * arch/arm/src/lpc31xx/lpc31_fdcndx.c + * + * Copyright (C) 2009-2010 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * References: + * - UM10314 LPC3130/31 User manual Rev. 1.01 — 9 September 2009 + * - lpc313x.cdl.drivers.zip example driver code + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name NuttX nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ************************************************************************/ + +/************************************************************************ + * Included Files + ************************************************************************/ + +#include +#include + +#include "up_arch.h" +#include "lpc31_cgudrvr.h" + +/************************************************************************ + * Pre-processor Definitions + ************************************************************************/ + +/* The select register in the ESR registers vary in width from 1-3 bits. + * Below is a macro to select the widest case (which is OK because the + * undefined bits will be read as zero). Within the field, bits 0-7 to + * indicate the offset from the base FDC index. + */ + +#define CGU_ESRSEL(n) (((n)>>1)&7) + +/************************************************************************ + * Private Data + ************************************************************************/ + +static const uint8_t g_fdcbase[CGU_NDOMAINS] = +{ + FRACDIV_BASE0_LOW, /* Domain 0: SYS_BASE */ + FRACDIV_BASE1_LOW, /* Domain 1: AHB0APB0_BASE */ + FRACDIV_BASE2_LOW, /* Domain 2: AHB0APB1_BASE */ + FRACDIV_BASE3_LOW, /* Domain 3: AHB0APB2_BASE */ + FRACDIV_BASE4_LOW, /* Domain 4: AHB0APB3_BASE */ + FRACDIV_BASE5_LOW, /* Domain 5: PCM_BASE */ + FRACDIV_BASE6_LOW, /* Domain 6: UART_BASE */ + FRACDIV_BASE7_LOW, /* Domain 7: CLK1024FS_BASE */ + 0, /* Domain 8: BCK0_BASE (no ESR register) */ + 0, /* Domain 9: BCK1_BASE (no ESR register) */ + FRACDIV_BASE10_LOW, /* Domain 10: SPI_BASE */ + 0, /* Domain 11: SYSCLKO_BASE (no ESR register) */ +}; + +/************************************************************************ + * Private Functions + ************************************************************************/ + +/************************************************************************ + * Public Functions + ************************************************************************/ + +/************************************************************************ + * Name: lpc31_fdcndx + * + * Description: + * Given a clock ID and its domain ID, return the index of the + * corresponding fractional divider register (or FDCNDX_INVALID if + * there is no fractional divider associated with this clock). + * + ************************************************************************/ + +int lpc31_fdcndx(enum lpc31_clockid_e clkid, enum lpc31_domainid_e dmnid) +{ + int esrndx; + int fdcndx = FDCNDX_INVALID; + + /* Check if there is an ESR register associate with this clock ID */ + + esrndx = lpc31_esrndx(clkid); + if (esrndx != ESRNDX_INVALID) + { + /* Read the clock's ESR to get the fractional divider */ + + uint32_t regval = getreg32(LPC31_CGU_ESR(esrndx)); + + /* Check if any fractional divider is enabled for this clock. */ + + if ((regval & CGU_ESR_ESREN) != 0) + { + /* Yes.. The FDC index is an offset from this fractional + * divider base for this domain. + */ + + fdcndx = CGU_ESRSEL(regval) + (int)g_fdcbase[dmnid]; + } + } + return fdcndx; +} + diff --git a/nuttx/arch/arm/src/lpc31xx/lpc31_fdivinit.c b/nuttx/arch/arm/src/lpc31xx/lpc31_fdivinit.c new file mode 100755 index 000000000..27a31152d --- /dev/null +++ b/nuttx/arch/arm/src/lpc31xx/lpc31_fdivinit.c @@ -0,0 +1,204 @@ +/**************************************************************************** + * arch/arm/src/lpc31xx/lpc31_fdivinit.c + * + * Copyright (C) 2009 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name NuttX nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include + +#include + +#include "lpc31_cgu.h" +#include "lpc31_cgudrvr.h" + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +/**************************************************************************** + * Public Data + ****************************************************************************/ + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: lpc31_bitwidth + * + * Description: + * Find the bit width of a msub or madd value. This will be use to + * extend the msub or madd values. To minimize power consumption, the + * lpc313x user manual recommends that madd and msub be shifted right + * to have as many trailing zero's as possible. This function detmines + * the pre-shifted with of one of the msub or madd values. + * + * EXAMPLE: + * + * Say an input frequency of 13 MHz is given while a frequency of 12 + * MHz is required. In this case we want a frequency + * + * f’ = 12/13 × f + * + * So n = 12 and m = 13. This then gives + * + * madd = m - n = 13 - 12 = 1 + * msub = -n = -12 + * + * In order to minimize power consumption madd and msub must be as + * large as possible. The limit of their values is determined by the + * madd/msub bit width. In this case msub is the largest value, + * in order to express -12, five bits are required. However since msub is + * always negative the fractional divider does not need the sign bit, leaving + * 4 bits. If madd/msub bit width has been set to say 8 bits, it is allowed + * to shift 4 bits, giving: + * + * msub’ = -(12<<4)= -12 × 24 = -12 × 16 = -192 + * madd’ = 1<<4 = 24 = 16 + * + ****************************************************************************/ + +static inline unsigned int +lpc31_bitwidth(unsigned int value, unsigned int fdwid) +{ + unsigned int width = 0; + int bit; + + /* Examine bits from the most significant down */ + + for (bit = fdwid-1; bit >= 0; bit--) + { + /* Is this bit set? If so, then the width of the value is 0 to bit, + * or bit+1. + */ + + if ((value & (1 << bit)) != 0) + { + width = bit + 1; + break; + } + } + return width; +} + +/**************************************************************************** + * Public Functions + ****************************************************************************/ +/**************************************************************************** + * Name: lpc31_fdivinit + * + * Description: + * Enable and configure (or disable) a fractional divider. + * + ****************************************************************************/ + +uint32_t lpc31_fdivinit(int fdcndx, + const struct lpc31_fdivconfig_s *fdiv, bool enable) +{ + uint32_t regaddr; + uint32_t regval; + unsigned int fdshift; + unsigned int fdwid; + unsigned int fdmask; + unsigned int maddshift; + unsigned int msubshift; + int madd; + int msub; + + /* Calculating the (unshifted) divider values.To minimize power + * consumption, the lpc313x user manual recommends that madd and msub + * be shifted right to have as many trailing zero's as possible. + */ + + madd = fdiv->m - fdiv->n; + msub = -fdiv->n; + + /* Determine the width of the madd and msub fields in the fractional divider + * register. They are all 8-bits in width except for fractional divider 17. + */ + + fdwid = CGU_FDC_FIELDWIDTH; + maddshift = CGU_FDC_MADD_SHIFT; + msubshift = CGU_FDC_MSUB_SHIFT; + + if (fdcndx == 17) + { + /* For fractional divider 17, the msub/madd field width is 13 */ + + fdwid = CGU_FDC17_FIELDWIDTH; + maddshift = CGU_FDC17_MADD_SHIFT; + msubshift = CGU_FDC17_MSUB_SHIFT; + } + + /* Find maximum bit width of madd & msub. Here we calculate the width of the OR + * of the two values. The width of the OR will be the width of the wider value + */ + + fdshift = fdwid - lpc31_bitwidth((unsigned int)madd | (unsigned int)fdiv->n, fdwid); + + /* Calculate the fractional divider register values */ + + fdmask = (1 << fdwid) - 1; + madd = (madd << fdshift) & fdmask; + msub = (msub << fdshift) & fdmask; + regval = (madd << maddshift) | (msub << msubshift); + + /* Check if 50% duty cycle is needed for this divider */ + + if (fdiv->stretch) + { + regval |= CGU_FDC_STRETCH; + } + + /* Check if we should enable the divider immediately */ + + if (enable) + { + regval |= CGU_FDC_RUN; + } + + /* Finally configure the divider */ + + regaddr = LPC31_CGU_FDC(fdcndx); + putreg32(regval, regaddr); + return regval; +} diff --git a/nuttx/arch/arm/src/lpc31xx/lpc31_freqin.c b/nuttx/arch/arm/src/lpc31xx/lpc31_freqin.c new file mode 100755 index 000000000..7e6bd3b3d --- /dev/null +++ b/nuttx/arch/arm/src/lpc31xx/lpc31_freqin.c @@ -0,0 +1,82 @@ +/**************************************************************************** + * arch/arm/src/lpc31xx/lpc31_freqin.c + * + * Copyright (C) 2009 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name NuttX nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include + +#include + +#include "lpc31_cgudrvr.h" + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +/**************************************************************************** + * Public Data + ****************************************************************************/ + +/* This array provides the programmed frequency of every input source. The + * board FFAST input crystal frequency is the only value known initially. + * Additional frequencies will be added to the table as they are determined + */ + +uint32_t g_boardfreqin[CGU_NFREQIN] = +{ + BOARD_FREQIN_FFAST, /* Index=CGU_FREQIN_FFAST */ + 0, /* Index=CGU_FREQIN_I2SRXBCK0 */ + 0, /* Index=CGU_FREQIN_I2SRXWS0 */ + 0, /* Index=CGU_FREQIN_I2SRXBCK1 */ + 0, /* Index=CGU_FREQIN_I2SRXWS1 */ + 0, /* Index=CGU_FREQIN_HPPLL0 (Audio/I2S PLL) */ + 0 /* Index=CGU_FREQIN_HPPLL1 (System PLL) */ +}; + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ diff --git a/nuttx/arch/arm/src/lpc31xx/lpc31_i2c.c b/nuttx/arch/arm/src/lpc31xx/lpc31_i2c.c new file mode 100644 index 000000000..52777dbb6 --- /dev/null +++ b/nuttx/arch/arm/src/lpc31xx/lpc31_i2c.c @@ -0,0 +1,608 @@ +/******************************************************************************* + * arch/arm/src/lpc31xx/lpc31_i2c.c + * + * Author: David Hewson + * + * Copyright (C) 2010-2011 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name NuttX nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + *******************************************************************************/ + +/******************************************************************************* + * Included Files + *******************************************************************************/ + +#include + +#include +#include +#include +#include +#include +#include +#include + +#include +#include + +#include +#include + +#include "wdog.h" +#include "chip.h" +#include "up_arch.h" +#include "up_internal.h" + +#include "lpc31_i2c.h" +#include "lpc31_evntrtr.h" +#include "lpc31_syscreg.h" + +/******************************************************************************* + * Definitions + *******************************************************************************/ + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +#define I2C_TIMEOUT ((20 * CLK_TCK) / 1000) /* 20 mS */ + +/**************************************************************************** + * Private Data + ****************************************************************************/ +struct lpc31_i2cdev_s +{ + struct i2c_dev_s dev; /* Generic I2C device */ + struct i2c_msg_s msg; /* a single message for legacy read/write */ + unsigned int base; /* Base address of registers */ + uint16_t clkid; /* Clock for this device */ + uint16_t rstid; /* Reset for this device */ + uint16_t irqid; /* IRQ for this device */ + + sem_t mutex; /* Only one thread can access at a time */ + + sem_t wait; /* Place to wait for state machine completion */ + volatile uint8_t state; /* State of state machine */ + WDOG_ID timeout; /* watchdog to timeout when bus hung */ + + struct i2c_msg_s *msgs; /* remaining transfers - first one is in progress */ + unsigned int nmsg; /* number of transfer remaining */ + + uint16_t header[3]; /* I2C address header */ + uint16_t hdrcnt; /* number of bytes of header */ + uint16_t wrcnt; /* number of bytes sent to tx fifo */ + uint16_t rdcnt; /* number of bytes read from rx fifo */ +}; + +#define I2C_STATE_DONE 0 +#define I2C_STATE_START 1 +#define I2C_STATE_HEADER 2 +#define I2C_STATE_TRANSFER 3 + +static struct lpc31_i2cdev_s i2cdevices[2]; + +/**************************************************************************** + * Private Functions + ****************************************************************************/ +static int i2c_interrupt (int irq, FAR void *context); +static void i2c_progress (struct lpc31_i2cdev_s *priv); +static void i2c_timeout (int argc, uint32_t arg, ...); +static void i2c_reset (struct lpc31_i2cdev_s *priv); + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * I2C device operations + ****************************************************************************/ + +static uint32_t i2c_setfrequency(FAR struct i2c_dev_s *dev, uint32_t frequency); +static int i2c_setaddress(FAR struct i2c_dev_s *dev, int addr, int nbits); +static int i2c_write(FAR struct i2c_dev_s *dev, const uint8_t *buffer, int buflen); +static int i2c_read(FAR struct i2c_dev_s *dev, uint8_t *buffer, int buflen); +static int i2c_transfer(FAR struct i2c_dev_s *dev, FAR struct i2c_msg_s *msgs, int count); + +struct i2c_ops_s lpc31_i2c_ops = { + .setfrequency = i2c_setfrequency, + .setaddress = i2c_setaddress, + .write = i2c_write, + .read = i2c_read, +#ifdef CONFIG_I2C_TRANSFER + .transfer = i2c_transfer +#endif +}; + +/******************************************************************************* + * Name: up_i2cinitialize + * + * Description: + * Initialise an I2C device + * + *******************************************************************************/ + +struct i2c_dev_s *up_i2cinitialize(int port) +{ + struct lpc31_i2cdev_s *priv = &i2cdevices[port]; + + priv->base = (port == 0) ? LPC31_I2C0_VBASE : LPC31_I2C1_VBASE; + priv->clkid = (port == 0) ? CLKID_I2C0PCLK : CLKID_I2C1PCLK; + priv->rstid = (port == 0) ? RESETID_I2C0RST : RESETID_I2C1RST; + priv->irqid = (port == 0) ? LPC31_IRQ_I2C0 : LPC31_IRQ_I2C1; + + sem_init (&priv->mutex, 0, 1); + sem_init (&priv->wait, 0, 0); + + /* Enable I2C system clocks */ + + lpc31_enableclock (priv->clkid); + + /* Reset I2C blocks */ + + lpc31_softreset (priv->rstid); + + /* Soft reset the device */ + + i2c_reset (priv); + + /* Allocate a watchdog timer */ + priv->timeout = wd_create(); + + DEBUGASSERT(priv->timeout != 0); + + /* Attach Interrupt Handler */ + irq_attach (priv->irqid, i2c_interrupt); + + /* Enable Interrupt Handler */ + up_enable_irq(priv->irqid); + + /* Install our operations */ + priv->dev.ops = &lpc31_i2c_ops; + + return &priv->dev; +} + +/******************************************************************************* + * Name: up_i2cuninitalize + * + * Description: + * Uninitialise an I2C device + * + *******************************************************************************/ + +void up_i2cuninitalize (struct lpc31_i2cdev_s *priv) +{ + /* Disable All Interrupts, soft reset the device */ + + i2c_reset (priv); + + /* Detach Interrupt Handler */ + + irq_detach (priv->irqid); + + /* Reset I2C blocks */ + + lpc31_softreset (priv->rstid); + + /* Disable I2C system clocks */ + + lpc31_disableclock (priv->clkid); +} + +/******************************************************************************* + * Name: lpc31_i2c_setfrequency + * + * Description: + * Set the frequence for the next transfer + * + *******************************************************************************/ + +static uint32_t i2c_setfrequency(FAR struct i2c_dev_s *dev, uint32_t frequency) +{ + struct lpc31_i2cdev_s *priv = (struct lpc31_i2cdev_s *) dev; + + uint32_t freq = lpc31_clkfreq (priv->clkid, DOMAINID_AHB0APB1); + + if (freq > 100000) + { + /* asymetric per 400Khz I2C spec */ + putreg32 (((47 * freq) / (83 + 47)) / frequency, priv->base + LPC31_I2C_CLKHI_OFFSET); + putreg32 (((83 * freq) / (83 + 47)) / frequency, priv->base + LPC31_I2C_CLKLO_OFFSET); + } + else + { + /* 50/50 mark space ratio */ + putreg32 (((50 * freq) / 100) / frequency, priv->base + LPC31_I2C_CLKLO_OFFSET); + putreg32 (((50 * freq) / 100) / frequency, priv->base + LPC31_I2C_CLKHI_OFFSET); + } + + /* FIXME: This function should return the actual selected frequency */ + return frequency; +} + +/******************************************************************************* + * Name: lpc31_i2c_setaddress + * + * Description: + * Set the I2C slave address for a subsequent read/write + * + *******************************************************************************/ +static int i2c_setaddress(FAR struct i2c_dev_s *dev, int addr, int nbits) +{ + struct lpc31_i2cdev_s *priv = (struct lpc31_i2cdev_s *) dev; + + DEBUGASSERT(dev != NULL); + DEBUGASSERT(nbits == 7 || nbits == 10); + + priv->msg.addr = addr; + priv->msg.flags = (nbits == 7) ? 0 : I2C_M_TEN; + + return OK; +} + +/******************************************************************************* + * Name: lpc31_i2c_write + * + * Description: + * Send a block of data on I2C using the previously selected I2C + * frequency and slave address. + * + *******************************************************************************/ +static int i2c_write(FAR struct i2c_dev_s *dev, const uint8_t *buffer, int buflen) +{ + struct lpc31_i2cdev_s *priv = (struct lpc31_i2cdev_s *) dev; + int ret; + + DEBUGASSERT (dev != NULL); + + priv->msg.flags &= ~I2C_M_READ; + priv->msg.buffer = (uint8_t*)buffer; + priv->msg.length = buflen; + + ret = i2c_transfer (dev, &priv->msg, 1); + + return ret == 1 ? OK : -ETIMEDOUT; +} + +/******************************************************************************* + * Name: lpc31_i2c_read + * + * Description: + * Receive a block of data on I2C using the previously selected I2C + * frequency and slave address. + * + *******************************************************************************/ +static int i2c_read(FAR struct i2c_dev_s *dev, uint8_t *buffer, int buflen) +{ + struct lpc31_i2cdev_s *priv = (struct lpc31_i2cdev_s *) dev; + int ret; + + DEBUGASSERT (dev != NULL); + + priv->msg.flags |= I2C_M_READ; + priv->msg.buffer = buffer; + priv->msg.length = buflen; + + ret = i2c_transfer (dev, &priv->msg, 1); + + return ret == 1 ? OK : -ETIMEDOUT; +} + +/******************************************************************************* + * Name: i2c_transfer + * + * Description: + * Perform a sequence of I2C transfers + * + *******************************************************************************/ + +static int i2c_transfer (FAR struct i2c_dev_s *dev, FAR struct i2c_msg_s *msgs, int count) +{ + struct lpc31_i2cdev_s *priv = (struct lpc31_i2cdev_s *) dev; + irqstate_t flags; + int ret; + + sem_wait (&priv->mutex); + flags = irqsave(); + + priv->state = I2C_STATE_START; + priv->msgs = msgs; + priv->nmsg = count; + + i2c_progress (priv); + + /* start a watchdog to timeout the transfer if + * the bus is locked up... */ + wd_start (priv->timeout, I2C_TIMEOUT, i2c_timeout, 1, (uint32_t)priv); + + while (priv->state != I2C_STATE_DONE) + { + sem_wait (&priv->wait); + } + + wd_cancel (priv->timeout); + + ret = count - priv->nmsg; + + irqrestore (flags); + sem_post (&priv->mutex); + + return ret; +} + +/******************************************************************************* + * Name: i2c_interrupt + * + * Description: + * The I2C Interrupt Handler + * + *******************************************************************************/ + +static int i2c_interrupt (int irq, FAR void *context) +{ + if (irq == LPC31_IRQ_I2C0) + { + i2c_progress (&i2cdevices[0]); + } + + if (irq == LPC31_IRQ_I2C1) + { + i2c_progress (&i2cdevices[1]); + } + + return OK; +} + +/******************************************************************************* + * Name: i2c_progress + * + * Description: + * Progress any remaining I2C transfers + * + *******************************************************************************/ + +static void i2c_progress (struct lpc31_i2cdev_s *priv) +{ + struct i2c_msg_s *msg; + uint32_t stat, ctrl; + + stat = getreg32 (priv->base + LPC31_I2C_STAT_OFFSET); + + /* Were there arbitration problems? */ + if ((stat & I2C_STAT_AFI) != 0) + { + /* Perform a soft reset */ + i2c_reset (priv); + + /* FIXME: automatic retry? */ + + priv->state = I2C_STATE_DONE; + sem_post (&priv->wait); + return; + } + + while (priv->nmsg > 0) + { + ctrl = I2C_CTRL_NAIE | I2C_CTRL_AFIE | I2C_CTRL_TDIE; + msg = priv->msgs; + + switch (priv->state) + { + case I2C_STATE_START: + if ((msg->flags & I2C_M_TEN) != 0) + { + priv->header[0] = I2C_TX_START | 0xF0 | ((msg->addr & 0x300) >> 7); + priv->header[1] = msg->addr & 0xFF; + priv->hdrcnt = 2; + if (msg->flags & I2C_M_READ) + { + priv->header[2] = priv->header[0] | 1; + priv->hdrcnt++; + } + } + else + { + priv->header[0] = I2C_TX_START | (msg->addr << 1) | (msg->flags & I2C_M_READ); + priv->hdrcnt = 1; + } + + putreg32 (ctrl, priv->base + LPC31_I2C_CTRL_OFFSET); + + priv->state = I2C_STATE_HEADER; + priv->wrcnt = 0; + /* DROP THROUGH */ + + case I2C_STATE_HEADER: + while ((priv->wrcnt != priv->hdrcnt) && (stat & I2C_STAT_TFF) == 0) + { + putreg32(priv->header[priv->wrcnt], priv->base + LPC31_I2C_TX_OFFSET); + priv->wrcnt++; + + stat = getreg32 (priv->base + LPC31_I2C_STAT_OFFSET); + } + + if (priv->wrcnt < priv->hdrcnt) + { + /* Enable Tx FIFO Not Full Interrupt */ + putreg32 (ctrl | I2C_CTRL_TFFIE, priv->base + LPC31_I2C_CTRL_OFFSET); + goto out; + } + + priv->state = I2C_STATE_TRANSFER; + priv->wrcnt = 0; + priv->rdcnt = 0; + /* DROP THROUGH */ + + case I2C_STATE_TRANSFER: + if (msg->flags & I2C_M_READ) + { + while ((priv->rdcnt != msg->length) && (stat & I2C_STAT_RFE) == 0) + { + msg->buffer[priv->rdcnt] = getreg32 (priv->base + LPC31_I2C_RX_OFFSET); + priv->rdcnt++; + + stat = getreg32 (priv->base + LPC31_I2C_STAT_OFFSET); + } + + if (priv->rdcnt < msg->length) + { + /* Not all data received, fill the Tx FIFO with more dummies */ + while ((priv->wrcnt != msg->length) && (stat & I2C_STAT_TFF) == 0) + { + if ((priv->wrcnt + 1) == msg->length && priv->nmsg == 1) + putreg32 (I2C_TX_STOP, priv->base + LPC31_I2C_TX_OFFSET); + else + putreg32 (0, priv->base + LPC31_I2C_TX_OFFSET); + priv->wrcnt++; + + stat = getreg32 (priv->base + LPC31_I2C_STAT_OFFSET); + } + + if (priv->wrcnt < msg->length) + { + /* Enable Tx FIFO not full and Rx Fifo Avail Interrupts */ + putreg32 (ctrl | I2C_CTRL_TFFIE | I2C_CTRL_RFDAIE, priv->base + LPC31_I2C_CTRL_OFFSET); + } + else + { + /* Enable Rx Fifo Avail Interrupts */ + putreg32 (ctrl | I2C_CTRL_RFDAIE, priv->base + LPC31_I2C_CTRL_OFFSET); + } + goto out; + } + } + else /* WRITE */ + { + while ((priv->wrcnt != msg->length) && (stat & I2C_STAT_TFF) == 0) + { + if ((priv->wrcnt + 1) == msg->length && priv->nmsg == 1) + putreg32 (I2C_TX_STOP | msg->buffer[priv->wrcnt], priv->base + LPC31_I2C_TX_OFFSET); + else + putreg32 (msg->buffer[priv->wrcnt], priv->base + LPC31_I2C_TX_OFFSET); + + priv->wrcnt++; + + stat = getreg32 (priv->base + LPC31_I2C_STAT_OFFSET); + } + + if (priv->wrcnt < msg->length) + { + /* Enable Tx Fifo not full Interrupt */ + putreg32 (ctrl | I2C_CTRL_TFFIE, priv->base + LPC31_I2C_CTRL_OFFSET); + goto out; + } + } + + /* Transfer completed, move onto the next one */ + priv->state = I2C_STATE_START; + + if (--priv->nmsg == 0) + { + /* Final transfer, wait for Transmit Done Interrupt */ + putreg32 (ctrl, priv->base + LPC31_I2C_CTRL_OFFSET); + goto out; + } + priv->msgs++; + break; + } + } + +out: + if (stat & I2C_STAT_TDI) + { + putreg32 (I2C_STAT_TDI, priv->base + LPC31_I2C_STAT_OFFSET); + + /* You'd expect the NAI bit to be set when no acknowledge was + * received - but it gets cleared whenever a write it done to + * the TXFIFO - so we've gone and cleared it while priming the + * rest of the transfer! */ + if ((stat = getreg32 (priv->base + LPC31_I2C_TXFL_OFFSET)) != 0) + { + if (priv->nmsg == 0) + priv->nmsg++; + i2c_reset (priv); + } + + priv->state = I2C_STATE_DONE; + sem_post (&priv->wait); + } +} + +/******************************************************************************* + * Name: i2c_timeout + * + * Description: + * Watchdog timer for timeout of I2C operation + * + *******************************************************************************/ + +static void i2c_timeout (int argc, uint32_t arg, ...) +{ + struct lpc31_i2cdev_s *priv = (struct lpc31_i2cdev_s *) arg; + + irqstate_t flags = irqsave(); + + if (priv->state != I2C_STATE_DONE) + { + /* If there's data remaining in the TXFIFO, then ensure at least + * one transfer has failed to complete.. */ + + if (getreg32 (priv->base + LPC31_I2C_TXFL_OFFSET) != 0) + { + if (priv->nmsg == 0) + priv->nmsg++; + } + + /* Soft reset the USB controller */ + i2c_reset (priv); + + /* Mark the transfer as finished */ + priv->state = I2C_STATE_DONE; + sem_post (&priv->wait); + } + + irqrestore (flags); +} + +/******************************************************************************* + * Name: i2c_reset + * + * Description: + * Perform a soft reset of the I2C controller + * + *******************************************************************************/ +static void i2c_reset (struct lpc31_i2cdev_s *priv) +{ + putreg32 (I2C_CTRL_RESET, priv->base + LPC31_I2C_CTRL_OFFSET); + + /* Wait for Reset to complete */ + while ((getreg32 (priv->base + LPC31_I2C_CTRL_OFFSET) & I2C_CTRL_RESET) != 0) + ; +} diff --git a/nuttx/arch/arm/src/lpc31xx/lpc31_i2c.h b/nuttx/arch/arm/src/lpc31xx/lpc31_i2c.h new file mode 100755 index 000000000..d2425db3a --- /dev/null +++ b/nuttx/arch/arm/src/lpc31xx/lpc31_i2c.h @@ -0,0 +1,207 @@ +/************************************************************************************************ + * arch/arm/src/lpc31xx/lpc31_i2c.h + * + * Copyright (C) 2009-2010 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * 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_LPC31XX_LPC31_I2C_H +#define __ARCH_ARM_SRC_LPC31XX_LPC31_I2C_H + +/************************************************************************************************ + * Included Files + ************************************************************************************************/ + +#include +#include "lpc31_memorymap.h" + +/************************************************************************************************ + * Pre-processor Definitions + ************************************************************************************************/ + +/* I2C register base address offset into the APB1 domain ****************************************/ + +#define LPC31_I2C0_VBASE (LPC31_APB1_VADDR+LPC31_APB1_I2C0_OFFSET) +#define LPC31_I2C0_PBASE (LPC31_APB1_PADDR+LPC31_APB1_I2C0_OFFSET) + +#define LPC31_I2C1_VBASE (LPC31_APB1_VADDR+LPC31_APB1_I2C1_OFFSET) +#define LPC31_I2C1_PBASE (LPC31_APB1_PADDR+LPC31_APB1_I2C1_OFFSET) + +/* I2C register offsets (with respect to the I2C base) ******************************************/ + +#define LPC31_I2C_RX_OFFSET 0x00 /* I2C RX Data FIFO */ +#define LPC31_I2C_TX_OFFSET 0x00 /* I2C TX Data FIFO */ +#define LPC31_I2C_STAT_OFFSET 0x04 /* I2C Status Register */ +#define LPC31_I2C_CTRL_OFFSET 0x08 /* I2C Control Register */ +#define LPC31_I2C_CLKHI_OFFSET 0x0c /* I2C Clock Divider high */ +#define LPC31_I2C_CLKLO_OFFSET 0x10 /* I2C Clock Divider low */ +#define LPC31_I2C_ADR_OFFSET 0x14 /* I2C Slave Address */ +#define LPC31_I2C_RXFL_OFFSET 0x18 /* I2C Rx FIFO level */ +#define LPC31_I2C_TXFL_OFFSET 0x1c /* I2C Tx FIFO level */ +#define LPC31_I2C_RXB_OFFSET 0x20 /* I2C Number of bytes received */ +#define LPC31_I2C_TXB_OFFSET 0x24 /* I2C Number of bytes transmitted */ +#define LPC31_I2C_STX_OFFSET 0x28 /* Slave Transmit FIFO */ +#define LPC31_I2C_STXFL_OFFSET 0x2c /* Slave Transmit FIFO level */ + +/* I2C register (virtual) addresses *************************************************************/ + +#define LPC31_I2C0_RX (LPC31_I2C0_VBASE+LPC31_I2C_RX_OFFSET) +#define LPC31_I2C0_TX (LPC31_I2C0_VBASE+LPC31_I2C_TX_OFFSET) +#define LPC31_I2C0_STAT (LPC31_I2C0_VBASE+LPC31_I2C_STAT_OFFSET) +#define LPC31_I2C0_CTRL (LPC31_I2C0_VBASE+LPC31_I2C_CTRL_OFFSET) +#define LPC31_I2C0_CLKHI (LPC31_I2C0_VBASE+LPC31_I2C_CLKHI_OFFSET) +#define LPC31_I2C0_CLKLO (LPC31_I2C0_VBASE+LPC31_I2C_CLKLO_OFFSET) +#define LPC31_I2C0_ADR (LPC31_I2C0_VBASE+LPC31_I2C_ADR_OFFSET) +#define LPC31_I2C0_RXFL (LPC31_I2C0_VBASE+LPC31_I2C_RXFL_OFFSET) +#define LPC31_I2C0_TXFL (LPC31_I2C0_VBASE+LPC31_I2C_TXFL_OFFSET) +#define LPC31_I2C0_RXB (LPC31_I2C0_VBASE+LPC31_I2C_RXB_OFFSET) +#define LPC31_I2C0_TXB (LPC31_I2C0_VBASE+LPC31_I2C_TXB_OFFSET) +#define LPC31_I2C0_STX (LPC31_I2C0_VBASE+LPC31_I2C_STX_OFFSET) +#define LPC31_I2C0_STXFL (LPC31_I2C0_VBASE+LPC31_I2C_STXFL_OFFSET) + +#define LPC31_I2C1_RX (LPC31_I2C1_VBASE+LPC31_I2C_RX_OFFSET) +#define LPC31_I2C1_TX (LPC31_I2C1_VBASE+LPC31_I2C_TX_OFFSET) +#define LPC31_I2C1_STAT (LPC31_I2C1_VBASE+LPC31_I2C_STAT_OFFSET) +#define LPC31_I2C1_CTRL (LPC31_I2C1_VBASE+LPC31_I2C_CTRL_OFFSET) +#define LPC31_I2C1_CLKHI (LPC31_I2C1_VBASE+LPC31_I2C_CLKHI_OFFSET) +#define LPC31_I2C1_CLKLO (LPC31_I2C1_VBASE+LPC31_I2C_CLKLO_OFFSET) +#define LPC31_I2C1_ADR (LPC31_I2C1_VBASE+LPC31_I2C_ADR_OFFSET) +#define LPC31_I2C1_RXFL (LPC31_I2C1_VBASE+LPC31_I2C_RXFL_OFFSET) +#define LPC31_I2C1_TXFL (LPC31_I2C1_VBASE+LPC31_I2C_TXFL_OFFSET) +#define LPC31_I2C1_RXB (LPC31_I2C1_VBASE+LPC31_I2C_RXB_OFFSET) +#define LPC31_I2C1_TXB (LPC31_I2C1_VBASE+LPC31_I2C_TXB_OFFSET) +#define LPC31_I2C1_STX (LPC31_I2C1_VBASE+LPC31_I2C_STX_OFFSET) +#define LPC31_I2C1_STXFL (LPC31_I2C1_VBASE+LPC31_I2C_STXFL_OFFSET) + +/* I2C register bit definitions *****************************************************************/ + +/* I2Cn RX Data FIFO I2C0_RX, address 0x1300a000, I2C1_RX, address 0x1300a400 */ + +#define I2C_RX_DATA_SHIFT (0) /* Bits 0-7: RxData Receive FIFO data bits */ +#define I2C_RX_DATA_MASK (0xff << I2C_RX_DATA_HIFT) + +/* I2Cn TX Data FIFO I2C0_TX, 0x1300a000, I2C1_TX, address 0x1300a400 */ + +#define I2C_TX_STOP (1 << 9) /* Bit 9: Issue STOP condition after transmitting byte */ +#define I2C_TX_START (1 << 8) /* Bit 8: Issue START condition before transmitting byte */ +#define I2C_TX_DATA_SHIFT (0) /* Bits 0-7: TxData Transmit FIFO data bits */ +#define I2C_TX_DATA_MASK (0xff << I2C_TX_DATA_SHIFT) + +/* I2Cn Status register I2C0_STAT, address 0x1300a004, I2C1_STAT, address 0x1300a404 */ + +#define I2C_STAT_TFES (1 << 13) /* Bit 13: Slave Transmit FIFO Empty */ +#define I2C_STAT_TFFS (1 << 12) /* Bit 12: Slave Transmit FIFO Full */ +#define I2C_STAT_TFE (1 << 11) /* Bit 11: Transmit FIFO Empty */ +#define I2C_STAT_TFF (1 << 10) /* Bit 10: Transmit FIFO Full */ +#define I2C_STAT_RFE (1 << 9) /* Bit 9: Receive FIFO Empty */ +#define I2C_STAT_RFF (1 << 8) /* Bit 8: Receive FIFO Full */ +#define I2C_STAT_SDA (1 << 7) /* Bit 7: The current value of the SDA signal */ +#define I2C_STAT_SCL (1 << 6) /* Bit 6: The current value of the SCL signal */ +#define I2C_STAT_ACTIVE (1 << 5) /* Bit 5: Indicates whether the bus is busy */ +#define I2C_STAT_DRSI (1 << 4) /* Bit 4: Slave Data Request Interrupt */ +#define I2C_STAT_DRMI (1 << 3) /* Bit 3: Master Data Request Interrupt */ +#define I2C_STAT_NAI (1 << 2) /* Bit 2: No Acknowledge Interrupt */ +#define I2C_STAT_AFI (1 << 1) /* Bit 1: Arbitration Failure Interrupt */ +#define I2C_STAT_TDI (1 << 0) /* Bit 0: Transaction Done Interrupt */ + +/* I2Cn Control register I2C0_CTRL, address 0x1300a008, I2C1_CTRL, address 0x1300a408 */ + +#define I2C_CTRL_TFFSIE (1 << 10) /* Bit 10: Slave Transmit FIFO Not Full Interrupt Enable */ +#define I2C_CTRL_SEVEN (1 << 9) /* Bit 9: Seven-bit slave address */ +#define I2C_CTRL_RESET (1 << 8) /* Bit 8: Soft Reset */ +#define I2C_CTRL_TFFIE (1 << 7) /* Bit 7: Transmit FIFO Not Full Interrupt Enable */ +#define I2C_CTRL_RFDAIE (1 << 6) /* Bit 6: Receive FIFO Data Available Interrupt Enable */ +#define I2C_CTRL_RFFIE (1 << 5) /* Bit 5: Receive FIFO Full Interrupt Enable */ +#define I2C_CTRL_DRSIE (1 << 4) /* Bit 4: Data Request Slave Transmitter Interrupt Enable */ +#define I2C_CTRL_DRMIE (1 << 3) /* Bit 3: Data Request Master Transmitter Interrupt Enable */ +#define I2C_CTRL_NAIE (1 << 2) /* Bit 2: Transmitter No Acknowledge Interrupt Enable */ +#define I2C_CTRL_AFIE (1 << 1) /* Bit 1: Transmitter Arbitration Failure Interrupt Enable */ +#define I2C_CTRL_TDIE (1 << 0) /* Bit 0: Transmit Done Interrupt Enable */ + +/* I2Cn Clock Divider High I2C0_CLKHI, address 0x1300a00c, I2C1_CLKHI, address 0x1300a40c */ + +#define I2C_CLKHI_SHIFT (0) /* Bits 0-9: Clock Divisor High */ +#define I2C_CLKHI_MASK (0x3ff << I2C_CLKHI_SHIFT) + +/* I2Cn Clock Divider Low I2C0_CLKLO, address 0x1300a010, I2C1_CLKLO, address 0x1300a410 */ + +#define I2C_CLKLO_SHIFT (0) /* Bits 0-9: Clock Divisor Low */ +#define I2C_CLKLO_MASK (0x3ff << I2C_CLKLO_SHIFT) + + +/* I2Cn Slave Addres I2C0_ADDR, address 0x1300a014, I2C1_ADDR, address 0x1300a414 */ + +#define I2C_ADR_SHIFT (0) /* Bits 0-9: I2C bus slave address */ +#define I2C_ADR_MASK (0x3ff << I2C_ADR_SHIFT) + +/* I2Cn RX FIFO level I2C0_RXFL, address 0x1300a018, I2C1_RXFL, address 0x1300a018 */ + +#define I2C_RXFL_SHIFT (0) /* Bits 0-1: Receive FIFO level */ +#define I2C_RXFL_MASK (3 << I2C_RXFL_SHIFT) + +/* I2Cn TX FIFO level I2C0_TXFL, address 0x1300a01c, I2C1_TXFL, address 0x1300a01c */ + +#define I2C_TXFL_SHIFT (0) /* Bits 0-1: Receive FIFO level */ +#define I2C_TXFL_MASK (3 << I2C_TXFL_SHIFT) + +/* I2Cn RX byte count I2C0_RXB, address 0x1300a020, I2C1_RXB, address 0x1300a420 */ + +#define I2C_RXB_SHIFT (0) /* Bits 0-15: Number of bytes received */ +#define I2C_RXB_MASK (0xffff << I2C_RXB_SHIFT) + +/* I2Cn TX byte count I2C0_TXB, address 0x1300a024, I2C1_TXB, address 0x1300a424 */ + +#define I2C_TXB_SHIFT (0) /* Bits 0-15: Number of bytes sent */ +#define I2C_TXB_MASK (0xffff << I2C_TXB_SHIFT) + +/* I2Cn Slave TX Data FIFO I2C0_STX, address 0x1300a028, I2C1_STX, 0x1300a428 */ + +#define I2C_STX_SHIFT (0) /* Bits 0-7: Slave Transmit FIFO data */ +#define I2C_STX_MASK (0xff << I2C_STX_SHIFT) + +/* I2Cn Slave TX FIFO level I2C0_STXFL, address 0x1300a02c, I2C1_STXFL, address 0x1300a42c */ + +#define I2C_STXFL_SHIFT (0) /* Bits 0-1: Slave Transmit FIFO level */ +#define I2C_STXFL_MASK (3 << I2C_STXFL_SHIFT) + +/************************************************************************************************ + * Public Types + ************************************************************************************************/ + +/************************************************************************************************ + * Public Data + ************************************************************************************************/ + +/************************************************************************************************ + * Public Functions + ************************************************************************************************/ + +#endif /* __ARCH_ARM_SRC_LPC31XX_LPC31_I2C_H */ diff --git a/nuttx/arch/arm/src/lpc31xx/lpc31_i2s.h b/nuttx/arch/arm/src/lpc31xx/lpc31_i2s.h new file mode 100755 index 000000000..4d07dcc8f --- /dev/null +++ b/nuttx/arch/arm/src/lpc31xx/lpc31_i2s.h @@ -0,0 +1,315 @@ +/************************************************************************************************ + * arch/arm/src/lpc31xx/lpc31_i2s.h + * + * Copyright (C) 2009 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * 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_LPC31XX_LPC31_I2S_H +#define __ARCH_ARM_SRC_LPC31XX_LPC31_I2S_H + +/************************************************************************************************ + * Included Files + ************************************************************************************************/ + +#include +#include "lpc31_memorymap.h" + +/************************************************************************************************ + * Pre-processor Definitions + ************************************************************************************************/ + +/* I2S register base address offset into the APB3 domain ****************************************/ + +#define LPC31_I2SCONFIG_VBASE (LPC31_APB3_VSECTION+LPC31_APB3_I2SCONFIG_OFFSET) +#define LPC31_I2SCONFIG_PBASE (LPC31_APB3_PSECTION+LPC31_APB3_I2SCONFIG_OFFSET) + +#define LPC31_I2STX0_VBASE (LPC31_APB3_VSECTION+LPC31_APB3_I2STX0_OFFSET) +#define LPC31_I2STX0_PBASE (LPC31_APB3_PSECTION+LPC31_APB3_I2STX0_OFFSET) + +#define LPC31_I2STX1_VBASE (LPC31_APB3_VSECTION+LPC31_APB3_I2STX1_OFFSET) +#define LPC31_I2STX1_PBASE (LPC31_APB3_PSECTION+LPC31_APB3_I2STX1_OFFSET) + +#define LPC31_I2SRX0_VBASE (LPC31_APB3_VSECTION+LPC31_APB3_I2SRX0_OFFSET) +#define LPC31_I2SRX0_PBASE (LPC31_APB3_PSECTION+LPC31_APB3_I2SRX0_OFFSET) + +#define LPC31_I2SRX1_VBASE (LPC31_APB3_VSECTION+LPC31_APB3_I2SRX1_OFFSET) +#define LPC31_I2SRX1_PBASE (LPC31_APB3_PSECTION+LPC31_APB3_I2SRX1_OFFSET) + +/* I2S register offsets (with respect to the I2S base) ******************************************/ +/* I2S configuration module offset */ + +#define LPC31_I2SCONFIG_FORMAT_OFFSET 0x000 /* I2S formats */ +#define LPC31_I2SCONFIG_CFGMUX_OFFSET 0x004 /* Misc controls */ + /* 0x008-0x00c: Reserved */ +#define LPC31_I2SCONFIG_NSOFCNTR_OFFSET 0x010 /* NSOF counter control */ + +/* I2STX0, I2STX1, I2SRX0, and I2SRX1 module offsets */ + +#define LPC31_I2S_L16BIT_OFFSET 0x000 /* 16 bits left channel data */ +#define LPC31_I2S_R16BIT_OFFSET 0x004 /* 16 bits right channel data */ +#define LPC31_I2S_L24BIT_OFFSET 0x008 /* 24 bits left channel data */ +#define LPC31_I2S_R24BIT_OFFSET 0x00c /* 24 bits right channel data */ +#define LPC31_I2S_INTSTATUS_OFFSET 0x010 /* FIFO status register */ +#define LPC31_I2S_INTMASK_OFFSET 0x014 /* Interrupt Mask register */ +#define LPC31_I2S_L32BIT_OFFSET(n) (0x020+((n)<<2)) +#define LPC31_I2S_L32BIT0_OFFSET 0x020 /* 2x16 bits left channel data */ +#define LPC31_I2S_L32BIT1_OFFSET 0x024 /* " " " " " " " " " " */ +#define LPC31_I2S_L32BIT2_OFFSET 0x028 /* " " " " " " " " " " */ +#define LPC31_I2S_L32BIT3_OFFSET 0x02c /* " " " " " " " " " " */ +#define LPC31_I2S_L32BIT4_OFFSET 0x030 /* " " " " " " " " " " */ +#define LPC31_I2S_L32BIT5_OFFSET 0x034 /* " " " " " " " " " " */ +#define LPC31_I2S_L32BIT6_OFFSET 0x038 /* " " " " " " " " " " */ +#define LPC31_I2S_L32BIT7_OFFSET 0x03c /* " " " " " " " " " " */ +#define LPC31_I2S_R32BIT_OFFSET(n) (0x040+((n)<<2)) +#define LPC31_I2S_R32BIT0_OFFSET 0x040 /* 2x16 bits right channel data */ +#define LPC31_I2S_R32BIT1_OFFSET 0x044 /* " " " " " " " " " " */ +#define LPC31_I2S_R32BIT2_OFFSET 0x048 /* " " " " " " " " " " */ +#define LPC31_I2S_R32BIT3_OFFSET 0x04c /* " " " " " " " " " " */ +#define LPC31_I2S_R32BIT4_OFFSET 0x050 /* " " " " " " " " " " */ +#define LPC31_I2S_R32BIT5_OFFSET 0x054 /* " " " " " " " " " " */ +#define LPC31_I2S_R32BIT6_OFFSET 0x058 /* " " " " " " " " " " */ +#define LPC31_I2S_R32BIT7_OFFSET 0x05c /* " " " " " " " " " " */ +#define LPC31_I2S_ILVD_OFFSET(n) (0x060+((n)<<2)) +#define LPC31_I2S_ILVD0_OFFSET 0x060 /* Interleaved data */ +#define LPC31_I2S_ILVD1_OFFSET 0x064 /* " " " " */ +#define LPC31_I2S_ILVD2_OFFSET 0x068 /* " " " " */ +#define LPC31_I2S_ILVD3_OFFSET 0x06c /* " " " " */ +#define LPC31_I2S_ILVD4_OFFSET 0x070 /* " " " " */ +#define LPC31_I2S_ILVD5_OFFSET 0x074 /* " " " " */ +#define LPC31_I2S_ILVD6_OFFSET 0x078 /* " " " " */ +#define LPC31_I2S_ILVD7_OFFSET 0x07c /* " " " " */ + +/* I2S register (virtual) addresses *************************************************************/ +/* I2S configuration module registers */ + +#define LPC31_I2SCONFIG_FORMAT (LPC31_I2SCONFIG_VBASE+lPC313X_I2SCONFIG_FORMAT_OFFSET) +#define LPC31_I2SCONFIG_CFGMUX (LPC31_I2SCONFIG_VBASE+LPC31_I2SCONFIG_CFGMUX_OFFSET) +#define LPC31_I2SCONFIG_NSOFCNTR (LPC31_I2SCONFIG_VBASE+LPC31_I2SCONFIG_NSOFCNTR_OFFSET) + +/* I2STX0 module registers */ + +#define LPC31_I2STX0_L16BIT (LPC31_I2STX0_VBASE+LPC31_I2S_L16BIT_OFFSET) +#define LPC31_I2STX0_R16BIT (LPC31_I2STX0_VBASE+LPC31_I2S_R16BIT_OFFSET) +#define LPC31_I2STX0_L24BIT (LPC31_I2STX0_VBASE+LPC31_I2S_L24BIT_OFFSET) +#define LPC31_I2STX0_R24BIT (LPC31_I2STX0_VBASE+LPC31_I2S_R24BIT_OFFSET) +#define LPC31_I2STX0_INTSTATUS (LPC31_I2STX0_VBASE+LPC31_I2S_INTSTATUS_OFFSET) +#define LPC31_I2STX0_INTMASK (LPC31_I2STX0_VBASE+LPC31_I2S_INTMASK_OFFSET) +#define LPC31_I2STX0_L32BIT(n) (LPC31_I2STX0_VBASE+LPC31_I2S_L32BIT_OFFSET(n)) +#define LPC31_I2STX0_L32BIT0 (LPC31_I2STX0_VBASE+LPC31_I2S_L32BIT0_OFFSET) +#define LPC31_I2STX0_L32BIT1 (LPC31_I2STX0_VBASE+LPC31_I2S_L32BIT1_OFFSET) +#define LPC31_I2STX0_L32BIT2 (LPC31_I2STX0_VBASE+LPC31_I2S_L32BIT2_OFFSET) +#define LPC31_I2STX0_L32BIT3 (LPC31_I2STX0_VBASE+LPC31_I2S_L32BIT3_OFFSET) +#define LPC31_I2STX0_L32BIT4 (LPC31_I2STX0_VBASE+LPC31_I2S_L32BIT4_OFFSET) +#define LPC31_I2STX0_L32BIT5 (LPC31_I2STX0_VBASE+LPC31_I2S_L32BIT5_OFFSET) +#define LPC31_I2STX0_L32BIT6 (LPC31_I2STX0_VBASE+LPC31_I2S_L32BIT6_OFFSET) +#define LPC31_I2STX0_L32BIT7 (LPC31_I2STX0_VBASE+LPC31_I2S_L32BIT7_OFFSET) +#define LPC31_I2STX0_R32BIT(n) (LPC31_I2STX0_VBASE+LPC31_I2S_R32BIT_OFFSET(n)) +#define LPC31_I2STX0_R32BIT0 (LPC31_I2STX0_VBASE+LPC31_I2S_R32BIT0_OFFSET) +#define LPC31_I2STX0_R32BIT1 (LPC31_I2STX0_VBASE+LPC31_I2S_R32BIT1_OFFSET) +#define LPC31_I2STX0_R32BIT2 (LPC31_I2STX0_VBASE+LPC31_I2S_R32BIT2_OFFSET) +#define LPC31_I2STX0_R32BIT3 (LPC31_I2STX0_VBASE+LPC31_I2S_R32BIT3_OFFSET) +#define LPC31_I2STX0_R32BIT4 (LPC31_I2STX0_VBASE+LPC31_I2S_R32BIT4_OFFSET) +#define LPC31_I2STX0_R32BIT5 (LPC31_I2STX0_VBASE+LPC31_I2S_R32BIT5_OFFSET) +#define LPC31_I2STX0_R32BIT6 (LPC31_I2STX0_VBASE+LPC31_I2S_R32BIT6_OFFSET) +#define LPC31_I2STX0_R32BIT7 (LPC31_I2STX0_VBASE+LPC31_I2S_R32BIT7_OFFSET) +#define LPC31_I2STX0_ILVD(n) (LPC31_I2STX0_VBASE+LPC31_I2S_ILVD_OFFSET(n)) +#define LPC31_I2STX0_ILVD0 (LPC31_I2STX0_VBASE+LPC31_I2S_ILVD0_OFFSET) +#define LPC31_I2STX0_ILVD1 (LPC31_I2STX0_VBASE+LPC31_I2S_ILVD1_OFFSET) +#define LPC31_I2STX0_ILVD2 (LPC31_I2STX0_VBASE+LPC31_I2S_ILVD2_OFFSET) +#define LPC31_I2STX0_ILVD3 (LPC31_I2STX0_VBASE+LPC31_I2S_ILVD3_OFFSET) +#define LPC31_I2STX0_ILVD4 (LPC31_I2STX0_VBASE+LPC31_I2S_ILVD4_OFFSET) +#define LPC31_I2STX0_ILVD5 (LPC31_I2STX0_VBASE+LPC31_I2S_ILVD5_OFFSET) +#define LPC31_I2STX0_ILVD6 (LPC31_I2STX0_VBASE+LPC31_I2S_ILVD6_OFFSET) +#define LPC31_I2STX0_ILVD7 (LPC31_I2STX0_VBASE+LPC31_I2S_ILVD7_OFFSET) + +/* I2STX1 module registers */ + +#define LPC31_I2STX1_L16BIT (LPC31_I2STX1_VBASE+LPC31_I2S_L16BIT_OFFSET) +#define LPC31_I2STX1_R16BIT (LPC31_I2STX1_VBASE+LPC31_I2S_R16BIT_OFFSET) +#define LPC31_I2STX1_L24BIT (LPC31_I2STX1_VBASE+LPC31_I2S_L24BIT_OFFSET) +#define LPC31_I2STX1_R24BIT (LPC31_I2STX1_VBASE+LPC31_I2S_R24BIT_OFFSET) +#define LPC31_I2STX1_INTSTATUS (LPC31_I2STX1_VBASE+LPC31_I2S_INTSTATUS_OFFSET) +#define LPC31_I2STX1_INTMASK (LPC31_I2STX1_VBASE+LPC31_I2S_INTMASK_OFFSET) +#define LPC31_I2STX1_L32BIT(n) (LPC31_I2STX1_VBASE+LPC31_I2S_L32BIT_OFFSET(n)) +#define LPC31_I2STX1_L32BIT0 (LPC31_I2STX1_VBASE+LPC31_I2S_L32BIT0_OFFSET) +#define LPC31_I2STX1_L32BIT1 (LPC31_I2STX1_VBASE+LPC31_I2S_L32BIT1_OFFSET) +#define LPC31_I2STX1_L32BIT2 (LPC31_I2STX1_VBASE+LPC31_I2S_L32BIT2_OFFSET) +#define LPC31_I2STX1_L32BIT3 (LPC31_I2STX1_VBASE+LPC31_I2S_L32BIT3_OFFSET) +#define LPC31_I2STX1_L32BIT4 (LPC31_I2STX1_VBASE+LPC31_I2S_L32BIT4_OFFSET) +#define LPC31_I2STX1_L32BIT5 (LPC31_I2STX1_VBASE+LPC31_I2S_L32BIT5_OFFSET) +#define LPC31_I2STX1_L32BIT6 (LPC31_I2STX1_VBASE+LPC31_I2S_L32BIT6_OFFSET) +#define LPC31_I2STX1_L32BIT7 (LPC31_I2STX1_VBASE+LPC31_I2S_L32BIT7_OFFSET) +#define LPC31_I2STX1_R32BIT(n) (LPC31_I2STX1_VBASE+LPC31_I2S_R32BIT_OFFSET(n)) +#define LPC31_I2STX1_R32BIT0 (LPC31_I2STX1_VBASE+LPC31_I2S_R32BIT0_OFFSET) +#define LPC31_I2STX1_R32BIT1 (LPC31_I2STX1_VBASE+LPC31_I2S_R32BIT1_OFFSET) +#define LPC31_I2STX1_R32BIT2 (LPC31_I2STX1_VBASE+LPC31_I2S_R32BIT2_OFFSET) +#define LPC31_I2STX1_R32BIT3 (LPC31_I2STX1_VBASE+LPC31_I2S_R32BIT3_OFFSET) +#define LPC31_I2STX1_R32BIT4 (LPC31_I2STX1_VBASE+LPC31_I2S_R32BIT4_OFFSET) +#define LPC31_I2STX1_R32BIT5 (LPC31_I2STX1_VBASE+LPC31_I2S_R32BIT5_OFFSET) +#define LPC31_I2STX1_R32BIT6 (LPC31_I2STX1_VBASE+LPC31_I2S_R32BIT6_OFFSET) +#define LPC31_I2STX1_R32BIT7 (LPC31_I2STX1_VBASE+LPC31_I2S_R32BIT7_OFFSET) +#define LPC31_I2STX1_ILVD(n) (LPC31_I2STX1_VBASE+LPC31_I2S_ILVD_OFFSET(n)) +#define LPC31_I2STX1_ILVD0 (LPC31_I2STX1_VBASE+LPC31_I2S_ILVD0_OFFSET) +#define LPC31_I2STX1_ILVD1 (LPC31_I2STX1_VBASE+LPC31_I2S_ILVD1_OFFSET) +#define LPC31_I2STX1_ILVD2 (LPC31_I2STX1_VBASE+LPC31_I2S_ILVD2_OFFSET) +#define LPC31_I2STX1_ILVD3 (LPC31_I2STX1_VBASE+LPC31_I2S_ILVD3_OFFSET) +#define LPC31_I2STX1_ILVD4 (LPC31_I2STX1_VBASE+LPC31_I2S_ILVD4_OFFSET) +#define LPC31_I2STX1_ILVD5 (LPC31_I2STX1_VBASE+LPC31_I2S_ILVD5_OFFSET) +#define LPC31_I2STX1_ILVD6 (LPC31_I2STX1_VBASE+LPC31_I2S_ILVD6_OFFSET) +#define LPC31_I2STX1_ILVD7 (LPC31_I2STX1_VBASE+LPC31_I2S_ILVD7_OFFSET) + +/* I2SRX0 module registers */ + +#define LPC31_I2SRX0_L16BIT (LPC31_I2SRX0_VBASE+LPC31_I2S_L16BIT_OFFSET) +#define LPC31_I2SRX0_R16BIT (LPC31_I2SRX0_VBASE+LPC31_I2S_R16BIT_OFFSET) +#define LPC31_I2SRX0_L24BIT (LPC31_I2SRX0_VBASE+LPC31_I2S_L24BIT_OFFSET) +#define LPC31_I2SRX0_R24BIT (LPC31_I2SRX0_VBASE+LPC31_I2S_R24BIT_OFFSET) +#define LPC31_I2SRX0_INTSTATUS (LPC31_I2SRX0_VBASE+LPC31_I2S_INTSTATUS_OFFSET) +#define LPC31_I2SRX0_INTMASK (LPC31_I2SRX0_VBASE+LPC31_I2S_INTMASK_OFFSET) +#define LPC31_I2SRX0_L32BIT(n) (LPC31_I2SRX0_VBASE+LPC31_I2S_L32BIT_OFFSET(n)) +#define LPC31_I2SRX0_L32BIT0 (LPC31_I2SRX0_VBASE+LPC31_I2S_L32BIT0_OFFSET) +#define LPC31_I2SRX0_L32BIT1 (LPC31_I2SRX0_VBASE+LPC31_I2S_L32BIT1_OFFSET) +#define LPC31_I2SRX0_L32BIT2 (LPC31_I2SRX0_VBASE+LPC31_I2S_L32BIT2_OFFSET) +#define LPC31_I2SRX0_L32BIT3 (LPC31_I2SRX0_VBASE+LPC31_I2S_L32BIT3_OFFSET) +#define LPC31_I2SRX0_L32BIT4 (LPC31_I2SRX0_VBASE+LPC31_I2S_L32BIT4_OFFSET) +#define LPC31_I2SRX0_L32BIT5 (LPC31_I2SRX0_VBASE+LPC31_I2S_L32BIT5_OFFSET) +#define LPC31_I2SRX0_L32BIT6 (LPC31_I2SRX0_VBASE+LPC31_I2S_L32BIT6_OFFSET) +#define LPC31_I2SRX0_L32BIT7 (LPC31_I2SRX0_VBASE+LPC31_I2S_L32BIT7_OFFSET) +#define LPC31_I2SRX0_R32BIT(n) (LPC31_I2SRX0_VBASE+LPC31_I2S_R32BIT_OFFSET(n)) +#define LPC31_I2SRX0_R32BIT0 (LPC31_I2SRX0_VBASE+LPC31_I2S_R32BIT0_OFFSET) +#define LPC31_I2SRX0_R32BIT1 (LPC31_I2SRX0_VBASE+LPC31_I2S_R32BIT1_OFFSET) +#define LPC31_I2SRX0_R32BIT2 (LPC31_I2SRX0_VBASE+LPC31_I2S_R32BIT2_OFFSET) +#define LPC31_I2SRX0_R32BIT3 (LPC31_I2SRX0_VBASE+LPC31_I2S_R32BIT3_OFFSET) +#define LPC31_I2SRX0_R32BIT4 (LPC31_I2SRX0_VBASE+LPC31_I2S_R32BIT4_OFFSET) +#define LPC31_I2SRX0_R32BIT5 (LPC31_I2SRX0_VBASE+LPC31_I2S_R32BIT5_OFFSET) +#define LPC31_I2SRX0_R32BIT6 (LPC31_I2SRX0_VBASE+LPC31_I2S_R32BIT6_OFFSET) +#define LPC31_I2SRX0_R32BIT7 (LPC31_I2SRX0_VBASE+LPC31_I2S_R32BIT7_OFFSET) +#define LPC31_I2SRX0_ILVD(n) (LPC31_I2SRX0_VBASE+LPC31_I2S_ILVD_OFFSET(n)) +#define LPC31_I2SRX0_ILVD0 (LPC31_I2SRX0_VBASE+LPC31_I2S_ILVD0_OFFSET) +#define LPC31_I2SRX0_ILVD1 (LPC31_I2SRX0_VBASE+LPC31_I2S_ILVD1_OFFSET) +#define LPC31_I2SRX0_ILVD2 (LPC31_I2SRX0_VBASE+LPC31_I2S_ILVD2_OFFSET) +#define LPC31_I2SRX0_ILVD3 (LPC31_I2SRX0_VBASE+LPC31_I2S_ILVD3_OFFSET) +#define LPC31_I2SRX0_ILVD4 (LPC31_I2SRX0_VBASE+LPC31_I2S_ILVD4_OFFSET) +#define LPC31_I2SRX0_ILVD5 (LPC31_I2SRX0_VBASE+LPC31_I2S_ILVD5_OFFSET) +#define LPC31_I2SRX0_ILVD6 (LPC31_I2SRX0_VBASE+LPC31_I2S_ILVD6_OFFSET) +#define LPC31_I2SRX0_ILVD7 (LPC31_I2SRX0_VBASE+LPC31_I2S_ILVD7_OFFSET) + +/* I2SRX1 module registers */ + +#define LPC31_I2SRX1_L16BIT (LPC31_I2SRX1_VBASE+LPC31_I2S_L16BIT_OFFSET) +#define LPC31_I2SRX1_R16BIT (LPC31_I2SRX1_VBASE+LPC31_I2S_R16BIT_OFFSET) +#define LPC31_I2SRX1_L24BIT (LPC31_I2SRX1_VBASE+LPC31_I2S_L24BIT_OFFSET) +#define LPC31_I2SRX1_R24BIT (LPC31_I2SRX1_VBASE+LPC31_I2S_R24BIT_OFFSET) +#define LPC31_I2SRX1_INTSTATUS (LPC31_I2SRX1_VBASE+LPC31_I2S_INTSTATUS_OFFSET) +#define LPC31_I2SRX1_INTMASK (LPC31_I2SRX1_VBASE+LPC31_I2S_INTMASK_OFFSET) +#define LPC31_I2SRX1_L32BIT(n) (LPC31_I2SRX1_VBASE+LPC31_I2S_L32BIT_OFFSET(n)) +#define LPC31_I2SRX1_L32BIT0 (LPC31_I2SRX1_VBASE+LPC31_I2S_L32BIT0_OFFSET) +#define LPC31_I2SRX1_L32BIT1 (LPC31_I2SRX1_VBASE+LPC31_I2S_L32BIT1_OFFSET) +#define LPC31_I2SRX1_L32BIT2 (LPC31_I2SRX1_VBASE+LPC31_I2S_L32BIT2_OFFSET) +#define LPC31_I2SRX1_L32BIT3 (LPC31_I2SRX1_VBASE+LPC31_I2S_L32BIT3_OFFSET) +#define LPC31_I2SRX1_L32BIT4 (LPC31_I2SRX1_VBASE+LPC31_I2S_L32BIT4_OFFSET) +#define LPC31_I2SRX1_L32BIT5 (LPC31_I2SRX1_VBASE+LPC31_I2S_L32BIT5_OFFSET) +#define LPC31_I2SRX1_L32BIT6 (LPC31_I2SRX1_VBASE+LPC31_I2S_L32BIT6_OFFSET) +#define LPC31_I2SRX1_L32BIT7 (LPC31_I2SRX1_VBASE+LPC31_I2S_L32BIT7_OFFSET) +#define LPC31_I2SRX1_R32BIT(n) (LPC31_I2SRX1_VBASE+LPC31_I2S_R32BIT_OFFSET(n)) +#define LPC31_I2SRX1_R32BIT0 (LPC31_I2SRX1_VBASE+LPC31_I2S_R32BIT0_OFFSET) +#define LPC31_I2SRX1_R32BIT1 (LPC31_I2SRX1_VBASE+LPC31_I2S_R32BIT1_OFFSET) +#define LPC31_I2SRX1_R32BIT2 (LPC31_I2SRX1_VBASE+LPC31_I2S_R32BIT2_OFFSET) +#define LPC31_I2SRX1_R32BIT3 (LPC31_I2SRX1_VBASE+LPC31_I2S_R32BIT3_OFFSET) +#define LPC31_I2SRX1_R32BIT4 (LPC31_I2SRX1_VBASE+LPC31_I2S_R32BIT4_OFFSET) +#define LPC31_I2SRX1_R32BIT5 (LPC31_I2SRX1_VBASE+LPC31_I2S_R32BIT5_OFFSET) +#define LPC31_I2SRX1_R32BIT6 (LPC31_I2SRX1_VBASE+LPC31_I2S_R32BIT6_OFFSET) +#define LPC31_I2SRX1_R32BIT7 (LPC31_I2SRX1_VBASE+LPC31_I2S_R32BIT7_OFFSET) +#define LPC31_I2SRX1_ILVD(n) (LPC31_I2SRX1_VBASE+LPC31_I2S_ILVD_OFFSET(n)) +#define LPC31_I2SRX1_ILVD0 (LPC31_I2SRX1_VBASE+LPC31_I2S_ILVD0_OFFSET) +#define LPC31_I2SRX1_ILVD1 (LPC31_I2SRX1_VBASE+LPC31_I2S_ILVD1_OFFSET) +#define LPC31_I2SRX1_ILVD2 (LPC31_I2SRX1_VBASE+LPC31_I2S_ILVD2_OFFSET) +#define LPC31_I2SRX1_ILVD3 (LPC31_I2SRX1_VBASE+LPC31_I2S_ILVD3_OFFSET) +#define LPC31_I2SRX1_ILVD4 (LPC31_I2SRX1_VBASE+LPC31_I2S_ILVD4_OFFSET) +#define LPC31_I2SRX1_ILVD5 (LPC31_I2SRX1_VBASE+LPC31_I2S_ILVD5_OFFSET) +#define LPC31_I2SRX1_ILVD6 (LPC31_I2SRX1_VBASE+LPC31_I2S_ILVD6_OFFSET) +#define LPC31_I2SRX1_ILVD7 (LPC31_I2SRX1_VBASE+LPC31_I2S_ILVD7_OFFSET) + +/* I2S register bit definitions *****************************************************************/ +/* I2S configuration module offset */ + +/* I2SCONFIG_FORMAT address 0x16000000 */ + +#define I2SCONFIG_FORMAT_I2SRX1_SHIFT (9) /* Bits 9-11: I2SRX1 I2S output format */ +#define I2SCONFIG_FORMAT_I2SRX1_MASK (7 << I2SCONFIG_FORMAT_I2SRX1_SHIFT) +# define I2SCONFIG_FORMAT_I2SRX1_I2S (3 << I2SCONFIG_FORMAT_I2SRX1_SHIFT) /* I2S */ +# define I2SCONFIG_FORMAT_I2SRX1_16BIT (4 << I2SCONFIG_FORMAT_I2SRX1_SHIFT) /* LSB justified 16 bits */ +# define I2SCONFIG_FORMAT_I2SRX1_18BIT (5 << I2SCONFIG_FORMAT_I2SRX1_SHIFT) /* LSB justified 18 bits */ +# define I2SCONFIG_FORMAT_I2SRX1_20BIT (6 << I2SCONFIG_FORMAT_I2SRX1_SHIFT) /* LSB justified 20 bits */ +# define I2SCONFIG_FORMAT_I2SRX1_24BIT (7 << I2SCONFIG_FORMAT_I2SRX1_SHIFT) /* LSB justified 24 bits */ +#define I2SCONFIG_FORMAT_I2SRX0_SHIFT (6) /* Bits 6-8: I2SRX0 I2S output format */ +#define I2SCONFIG_FORMAT_I2SRX0_MASK (7 << I2SCONFIG_FORMAT_I2SRX0_SHIFT) +# define I2SCONFIG_FORMAT_I2SRX0_I2S (3 << I2SCONFIG_FORMAT_I2SRX0_SHIFT) /* I2S */ +# define I2SCONFIG_FORMAT_I2SRX0_16BIT (4 << I2SCONFIG_FORMAT_I2SRX0_SHIFT) /* LSB justified 16 bits */ +# define I2SCONFIG_FORMAT_I2SRX0_18BIT (5 << I2SCONFIG_FORMAT_I2SRX0_SHIFT) /* LSB justified 18 bits */ +# define I2SCONFIG_FORMAT_I2SRX0_20BIT (6 << I2SCONFIG_FORMAT_I2SRX0_SHIFT) /* LSB justified 20 bits */ +# define I2SCONFIG_FORMAT_I2SRX0_24BIT (7 << I2SCONFIG_FORMAT_I2SRX0_SHIFT) /* LSB justified 24 bits */ +#define I2SCONFIG_FORMAT_I2STX1_SHIFT (3) /* Bits 3-5: 2STX1 I2S input format */ +#define I2SCONFIG_FORMAT_I2STX1_MASK (7 << I2SCONFIG_FORMAT_I2STX1_SHIFT) +# define I2SCONFIG_FORMAT_I2STX1_I2S (3 << I2SCONFIG_FORMAT_I2STX1_SHIFT) /* I2S */ +# define I2SCONFIG_FORMAT_I2STX1_16BIT (4 << I2SCONFIG_FORMAT_I2STX1_SHIFT) /* LSB justified 16 bits */ +# define I2SCONFIG_FORMAT_I2STX1_18BIT (5 << I2SCONFIG_FORMAT_I2STX1_SHIFT) /* LSB justified 18 bits */ +# define I2SCONFIG_FORMAT_I2STX1_20BIT (6 << I2SCONFIG_FORMAT_I2STX1_SHIFT) /* LSB justified 20 bits */ +# define I2SCONFIG_FORMAT_I2STX1_24BIT (7 << I2SCONFIG_FORMAT_I2STX1_SHIFT) /* LSB justified 24 bits */ +#define I2SCONFIG_FORMAT_I2STX0_SHIFT (0) /* Bits 0-2: I2STX0 I2S input format */ +#define I2SCONFIG_FORMAT_I2STX0_MASK (7 << I2SCONFIG_FORMAT_I2STX0_SHIFT) +# define I2SCONFIG_FORMAT_I2STX0_I2S (3 << I2SCONFIG_FORMAT_I2STX0_SHIFT) /* I2S */ +# define I2SCONFIG_FORMAT_I2STX0_16BIT (4 << I2SCONFIG_FORMAT_I2STX0_SHIFT) /* LSB justified 16 bits */ +# define I2SCONFIG_FORMAT_I2STX0_18BIT (5 << I2SCONFIG_FORMAT_I2STX0_SHIFT) /* LSB justified 18 bits */ +# define I2SCONFIG_FORMAT_I2STX0_20BIT (6 << I2SCONFIG_FORMAT_I2STX0_SHIFT) /* LSB justified 20 bits */ +# define I2SCONFIG_FORMAT_I2STX0_24BIT (7 << I2SCONFIG_FORMAT_I2STX0_SHIFT) /* LSB justified 24 bits */ + +/* II2SCONFIG_CFGMUX address 0x16000004 */ + +#define I2SCONFIG_CFGMUX_I2SRX1OEN (1 << 2) /* Bit 2: Selects faster mode for I2SRX1 */ +#define I2SCONFIG_CFGMUX_I2SRX0OEN (1 << 1) /* Bit 1: Slects master mode for I2SRX0 */ + +/* I2SCONFIG_NSOFCNT address 0x16000010 */ + +/************************************************************************************************ + * Public Types + ************************************************************************************************/ + +/************************************************************************************************ + * Public Data + ************************************************************************************************/ + +/************************************************************************************************ + * Public Functions + ************************************************************************************************/ + +#endif /* __ARCH_ARM_SRC_LPC31XX_LPC31_I2S_H */ diff --git a/nuttx/arch/arm/src/lpc31xx/lpc31_intc.h b/nuttx/arch/arm/src/lpc31xx/lpc31_intc.h new file mode 100755 index 000000000..204ff7555 --- /dev/null +++ b/nuttx/arch/arm/src/lpc31xx/lpc31_intc.h @@ -0,0 +1,198 @@ +/************************************************************************************************ + * arch/arm/src/lpc31xx/lpc31_intc.h + * + * Copyright (C) 2009-2010 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * 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_LPC31XX_LPC31_INTC_H +#define __ARCH_ARM_SRC_LPC31XX_LPC31_INTC_H + +/************************************************************************************************ + * Included Files + ************************************************************************************************/ + +#include +#include "lpc31_memorymap.h" + +/************************************************************************************************ + * Pre-processor Definitions + ************************************************************************************************/ + +/* INTC register base address *******************************************************************/ + +#define LPC31_INTC_VBASE (LPC31_INTC_VSECTION) +#define LPC31_INTC_PBASE (LPC31_INTC_PSECTION) + +/* INTC register offsets (with respect to the base of the INTC domain) **************************/ + +#define LPC31_INTC_PRIORITYMASK0_OFFSET 0x000 /* Interrupt target 0 priority threshold */ +#define LPC31_INTC_PRIORITYMASK1_OFFSET 0x004 /* Interrupt target 0 priority threshold */ +#define LPC31_INTC_VECTOR0_OFFSET 0x100 /* Vector register for target 0 => nIRQ */ +#define LPC31_INTC_VECTOR1_OFFSET 0x104 /* Vector register for target 1 => nFIQ */ +#define LPC31_INTC_PENDING_OFFSET 0x200 /* Status of interrupt request 1..29 */ +#define LPC31_INTC_FEATURES_OFFSET 0x300 /* Interrupt controller configuration */ +#define LPC31_INTC_REQUEST_OFFSET(n) (0x400+((n) << 2)) +#define LPC31_INTC_REQUEST1_OFFSET 0x404 /* Interrupt request 1 configuration */ +#define LPC31_INTC_REQUEST2_OFFSET 0x408 /* Interrupt request 2 configuration */ +#define LPC31_INTC_REQUEST3_OFFSET 0x40c /* Interrupt request 3 configuration */ +#define LPC31_INTC_REQUEST4_OFFSET 0x410 /* Interrupt request 4 configuration */ +#define LPC31_INTC_REQUEST5_OFFSET 0x414 /* Interrupt request 5 configuration */ +#define LPC31_INTC_REQUEST6_OFFSET 0x418 /* Interrupt request 6 configuration */ +#define LPC31_INTC_REQUEST7_OFFSET 0x41c /* Interrupt request 7 configuration */ +#define LPC31_INTC_REQUEST8_OFFSET 0x420 /* Interrupt request 8 configuration */ +#define LPC31_INTC_REQUEST9_OFFSET 0x424 /* Interrupt request 9 configuration */ +#define LPC31_INTC_REQUEST10_OFFSET 0x428 /* Interrupt request 10 configuration */ +#define LPC31_INTC_REQUEST11_OFFSET 0x42c /* Interrupt request 11 configuration */ +#define LPC31_INTC_REQUEST12_OFFSET 0x430 /* Interrupt request 12 configuration */ +#define LPC31_INTC_REQUEST13_OFFSET 0x434 /* Interrupt request 13 configuration */ +#define LPC31_INTC_REQUEST14_OFFSET 0x438 /* Interrupt request 14 configuration */ +#define LPC31_INTC_REQUEST15_OFFSET 0x43c /* Interrupt request 15 configuration */ +#define LPC31_INTC_REQUEST16_OFFSET 0x440 /* Interrupt request 16 configuration */ +#define LPC31_INTC_REQUEST17_OFFSET 0x444 /* Interrupt request 17 configuration */ +#define LPC31_INTC_REQUEST18_OFFSET 0x448 /* Interrupt request 18 configuration */ +#define LPC31_INTC_REQUEST19_OFFSET 0x44c /* Interrupt request 19 configuration */ +#define LPC31_INTC_REQUEST20_OFFSET 0x450 /* Interrupt request 20 configuration */ +#define LPC31_INTC_REQUEST21_OFFSET 0x454 /* Interrupt request 21 configuration */ +#define LPC31_INTC_REQUEST22_OFFSET 0x458 /* Interrupt request 22 configuration */ +#define LPC31_INTC_REQUEST23_OFFSET 0x45c /* Interrupt request 23 configuration */ +#define LPC31_INTC_REQUEST24_OFFSET 0x460 /* Interrupt request 24 configuration */ +#define LPC31_INTC_REQUEST25_OFFSET 0x464 /* Interrupt request 25 configuration */ +#define LPC31_INTC_REQUEST26_OFFSET 0x468 /* Interrupt request 26 configuration */ +#define LPC31_INTC_REQUEST27_OFFSET 0x46c /* Interrupt request 27 configuration */ +#define LPC31_INTC_REQUEST28_OFFSET 0x470 /* Interrupt request 28 configuration */ +#define LPC31_INTC_REQUEST29_OFFSET 0x474 /* Interrupt request 29 configuration */ + +/* INTC register (virtual) addresses ************************************************************/ + +#define LPC31_INTC_PRIORITYMASK0 (LPC31_INTC_VBASE+LPC31_INTC_PRIORITYMASK0_OFFSET) +#define LPC31_INTC_PRIORITYMASK1 (LPC31_INTC_VBASE+LPC31_INTC_PRIORITYMASK1_OFFSET) +#define LPC31_INTC_VECTOR0 (LPC31_INTC_VBASE+LPC31_INTC_VECTOR0_OFFSET) +#define LPC31_INTC_VECTOR1 (LPC31_INTC_VBASE+LPC31_INTC_VECTOR1_OFFSET) +#define LPC31_INTC_PENDING (LPC31_INTC_VBASE+LPC31_INTC_PENDING_OFFSET) +#define LPC31_INTC_FEATURES (LPC31_INTC_VBASE+LPC31_INTC_FEATURES_OFFSET) +#define LPC31_INTC_REQUEST(n) (LPC31_INTC_VBASE+LPC31_INTC_REQUEST_OFFSET(n)) +#define LPC31_INTC_REQUEST1 (LPC31_INTC_VBASE+LPC31_INTC_REQUEST1_OFFSET) +#define LPC31_INTC_REQUEST2 (LPC31_INTC_VBASE+LPC31_INTC_REQUEST2_OFFSET) +#define LPC31_INTC_REQUEST3 (LPC31_INTC_VBASE+LPC31_INTC_REQUEST3_OFFSET) +#define LPC31_INTC_REQUEST4 (LPC31_INTC_VBASE+LPC31_INTC_REQUEST4_OFFSET) +#define LPC31_INTC_REQUEST5 (LPC31_INTC_VBASE+LPC31_INTC_REQUEST5_OFFSET) +#define LPC31_INTC_REQUEST6 (LPC31_INTC_VBASE+LPC31_INTC_REQUEST6_OFFSET) +#define LPC31_INTC_REQUEST7 (LPC31_INTC_VBASE+LPC31_INTC_REQUEST7_OFFSET) +#define LPC31_INTC_REQUEST8 (LPC31_INTC_VBASE+LPC31_INTC_REQUEST8_OFFSET) +#define LPC31_INTC_REQUEST9 (LPC31_INTC_VBASE+LPC31_INTC_REQUEST9_OFFSET) +#define LPC31_INTC_REQUEST10 (LPC31_INTC_VBASE+LPC31_INTC_REQUEST10_OFFSET) +#define LPC31_INTC_REQUEST11 (LPC31_INTC_VBASE+LPC31_INTC_REQUEST11_OFFSET) +#define LPC31_INTC_REQUEST12 (LPC31_INTC_VBASE+LPC31_INTC_REQUEST12_OFFSET) +#define LPC31_INTC_REQUEST13 (LPC31_INTC_VBASE+LPC31_INTC_REQUEST13_OFFSET) +#define LPC31_INTC_REQUEST14 (LPC31_INTC_VBASE+LPC31_INTC_REQUEST14_OFFSET) +#define LPC31_INTC_REQUEST15 (LPC31_INTC_VBASE+LPC31_INTC_REQUEST15_OFFSET) +#define LPC31_INTC_REQUEST16 (LPC31_INTC_VBASE+LPC31_INTC_REQUEST16_OFFSET) +#define LPC31_INTC_REQUEST17 (LPC31_INTC_VBASE+LPC31_INTC_REQUEST17_OFFSET) +#define LPC31_INTC_REQUEST18 (LPC31_INTC_VBASE+LPC31_INTC_REQUEST18_OFFSET) +#define LPC31_INTC_REQUEST19 (LPC31_INTC_VBASE+LPC31_INTC_REQUEST19_OFFSET) +#define LPC31_INTC_REQUEST20 (LPC31_INTC_VBASE+LPC31_INTC_REQUEST20_OFFSET) +#define LPC31_INTC_REQUEST21 (LPC31_INTC_VBASE+LPC31_INTC_REQUEST21_OFFSET) +#define LPC31_INTC_REQUEST22 (LPC31_INTC_VBASE+LPC31_INTC_REQUEST22_OFFSET) +#define LPC31_INTC_REQUEST23 (LPC31_INTC_VBASE+LPC31_INTC_REQUEST23_OFFSET) +#define LPC31_INTC_REQUEST24 (LPC31_INTC_VBASE+LPC31_INTC_REQUEST24_OFFSET) +#define LPC31_INTC_REQUEST25 (LPC31_INTC_VBASE+LPC31_INTC_REQUEST25_OFFSET) +#define LPC31_INTC_REQUEST26 (LPC31_INTC_VBASE+LPC31_INTC_REQUEST26_OFFSET) +#define LPC31_INTC_REQUEST27 (LPC31_INTC_VBASE+LPC31_INTC_REQUEST27_OFFSET) +#define LPC31_INTC_REQUEST28 (LPC31_INTC_VBASE+LPC31_INTC_REQUEST28_OFFSET) +#define LPC31_INTC_REQUEST29 (LPC31_INTC_VBASE+LPC31_INTC_REQUEST29_OFFSET) + +/* INTC register bit definitions ****************************************************************/ + +/* Interrupt priority mask register (INT_PRIORITYMASK0 address 0x60000000 and + * INTC_PRIORITYMASK1 address 0x60000004) + */ + +#define INTC_PRIORITYMASK_PRIOLIMIT_SHIFT (0) /* Bits 0-7: Priority threshold for interrupts */ +#define INTC_PRIORITYMASK_PRIOLIMIT_MASK (255 << INTC_PRIORITYMASK_PRIOLIMIT_MASK) + +/* Interrupt vector registers (INTC_VECTOR0 address 0x60000100 and INTC_VECTOR1 address + * 0x60000104) + */ + +#define INTC_VECTOR_TABLEADDR_SHIFT (11) /* Bits 11-31: Table start address */ +#define INTC_VECTOR_TABLEADDR_MASK (0x001fffff << INTC_VECTOR_TABLEADDR_SHIFT) +#define INTC_VECTOR_INDEX_SHIFT (3) /* Bits 3-10: IRQ number of interrupt */ +#define INTC_VECTOR_INDEX_MASK (255 << INTC_VECTOR_INDEX_SHIFT) + +/* Interrupt pending register (INT_PENDING1_31, address 0x60000200) */ + +#define INTC_PENDING_SHIFT (1) /* Bits 1-29: Pending interrupt request */ +#define INTC_PENDING_MASK (0x1fffffff << INTC_PENDING_SHIFT) + +/* Interrupt controller features register (INT_FEATURES, address 0x60000300) */ + +#define INTC_FEATURES_T_SHIFT (16) /* Bits 16-21: Number interrupt targets supported (+1) */ +#define INTC_FEATURES_T_MASK (63 << INTC_FEATURES_T_SHIFT) +#define INTC_FEATURES_P_SHIFT (8) /* Bits 8-15: Number priority levels supported */ +#define INTC_FEATURES_P_MASK (255 << INTC_FEATURES_P_SHIFT) +#define INTC_FEATURES_N_SHIFT (0) /* Bits 0-7: Number interrupt request inputs */ +#define INTC_FEATURES_N_MASK (255 << INTC_FEATURES_N_SHIFT) + +/* Interrupt request registers (INT_REQUEST1 address 0x60000404 to INTC_REQUEST29 address + * 0x60000474) + */ + +#define INTC_REQUEST_PENDING (1 << 31) /* Bit 31: Pending interrupt request */ +#define INTC_REQUEST_SETSWINT (1 << 30) /* Bit 30: Set software interrupt request */ +#define INTC_REQUEST_CLRSWINT (1 << 29) /* Bit 29: Clear software interrupt request */ +#define INTC_REQUEST_WEPRIO (1 << 28) /* Bit 28: Write Enable PRIORITY_LEVEL */ +#define INTC_REQUEST_WETARGET (1 << 27) /* Bit 27: Write Enable TARGET */ +#define INTC_REQUEST_WEENABLE (1 << 26) /* Bit 26: Write Enable ENABLE */ +#define INTC_REQUEST_WEACTLOW (1 << 25) /* Bit 25: Write Enable ACTIVE_LOW */ +#define INTC_REQUEST_ACTLOW (1 << 17) /* Bit 17: Active Low */ +#define INTC_REQUEST_ENABLE (1 << 16) /* Bit 16: Enable interrupt request */ +#define INTC_REQUEST_TARGET_SHIFT (8) /* Bits 8-13: Interrupt target */ +#define INTC_REQUEST_TARGET_MASK (63 << INTC_REQUEST_TARGET_SHIFT) +# define INTC_REQUEST_TARGET_IRQ (INTC_REQUEST_WETARGET | (0 << INTC_REQUEST_TARGET_SHIFT)) /* Proc interrupt request 0: IRQ */ +# define INTC_REQUEST_TARGET_FIQ (INTC_REQUEST_WETARGET | (1 << INTC_REQUEST_TARGET_SHIFT)) /* Proc interrupt request 1: FIQ */ +#define INTC_REQUEST_PRIOLEVEL_SHIFT (0) /* Bits 0-7: Priority level */ +#define INTC_REQUEST_PRIOLEVEL_MASK (255 << INTC_REQUEST_PRIOLEVEL_SHIFT) +# define INTC_REQUEST_PRIOLEVEL(n) (((n) << INTC_REQUEST_PRIOLEVEL_SHIFT) & INTC_REQUEST_PRIOLEVEL_MASK) + +/************************************************************************************************ + * Public Types + ************************************************************************************************/ + +/************************************************************************************************ + * Public Data + ************************************************************************************************/ + +/************************************************************************************************ + * Public Functions + ************************************************************************************************/ + +#endif /* __ARCH_ARM_SRC_LPC31XX_LPC31_INTC_H */ diff --git a/nuttx/arch/arm/src/lpc31xx/lpc31_internal.h b/nuttx/arch/arm/src/lpc31xx/lpc31_internal.h new file mode 100755 index 000000000..d91f3a2e1 --- /dev/null +++ b/nuttx/arch/arm/src/lpc31xx/lpc31_internal.h @@ -0,0 +1,300 @@ +/************************************************************************************ + * arch/arm/src/lpc31xx/lpc31_internal.h + * + * Copyright (C) 2009-2011 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * 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_LPC31XX_LPC31_INTERNAL_H +#define __ARCH_ARM_SRC_LPC31XX_LPC31_INTERNAL_H + +/************************************************************************************ + * Included Files + ************************************************************************************/ + +#include + +#include +#include +#include + +#include "up_internal.h" +#include "up_arch.h" +#include "chip.h" +#include "lpc31_ioconfig.h" + +/************************************************************************************ + * Definitions + ************************************************************************************/ + +/* Configuration ********************************************************************/ + +/* NVIC priority levels *************************************************************/ + +/************************************************************************************ + * Public Types + ************************************************************************************/ + +/************************************************************************************ + * Inline Functions + ************************************************************************************/ + +#ifndef __ASSEMBLY__ + +/************************************************************************************ + * Public Data + ************************************************************************************/ + +#undef EXTERN +#if defined(__cplusplus) +#define EXTERN extern "C" +extern "C" { +#else +#define EXTERN extern +#endif + +/************************************************************************************ + * Inline Functions + ************************************************************************************/ + +/* Configure a pin as an input */ + +static inline void gpio_configinput(uint32_t ioconfig, uint32_t bit) +{ + uint32_t regaddr; + + regaddr = ioconfig + LPC31_IOCONFIG_MODE0RESET_OFFSET; + putreg32(bit, regaddr); + + regaddr = ioconfig + LPC31_IOCONFIG_MODE1RESET_OFFSET; + putreg32(bit, regaddr); +} + +/* Return the current state of an input GPIO pin */ + +static inline bool lpc31_gpioread(uint32_t ioconfig, uint32_t bit) +{ + uint32_t regaddr = ioconfig + LPC31_IOCONFIG_PINS_OFFSET; + return (getreg32(regaddr) & bit) != 0; +} + +/* Configure the pin so that it is driven by the device */ + +static inline void gpio_configdev(uint32_t ioconfig, uint32_t bit) +{ + uint32_t regaddr; + + regaddr = ioconfig + LPC31_IOCONFIG_MODE1RESET_OFFSET; + putreg32(bit, regaddr); + + regaddr = ioconfig + LPC31_IOCONFIG_MODE0SET_OFFSET; + putreg32(bit, regaddr); +} + +/* Configure a pin as a low output */ + +static inline void gpio_outputlow(uint32_t ioconfig, uint32_t bit) +{ + uint32_t regaddr; + + regaddr = ioconfig + LPC31_IOCONFIG_MODE1SET_OFFSET; + putreg32(bit, regaddr); + + regaddr = ioconfig + LPC31_IOCONFIG_MODE0RESET_OFFSET; + putreg32(bit, regaddr); +} + +/* Configure a pin as a high output */ + +static inline void gpio_outputhigh(uint32_t ioconfig, uint32_t bit) +{ + uint32_t regaddr; + + regaddr = ioconfig + LPC31_IOCONFIG_MODE1SET_OFFSET; + putreg32(bit, regaddr); + + regaddr = ioconfig + LPC31_IOCONFIG_MODE0SET_OFFSET; + putreg32(bit, regaddr); +} + +/************************************************************************************ + * Public Function Prototypes + ************************************************************************************/ + +/************************************************************************************ + * Name: lpc31_lowsetup + * + * Description: + * Called early in up_boot. Performs chip-common low level initialization. + * + ************************************************************************************/ + +EXTERN void lpc31_lowsetup(void); + +/************************************************************************************ + * Name: lpc31_clockconfig + * + * Description: + * Called to change to new clock based on settings in board.h + * + ************************************************************************************/ + +EXTERN void lpc31_clockconfig(void); + +/************************************************************************************ + * Name: lpc31_spiselect and lpc31_spistatus + * + * Description: + * The external functions, lpc31_spiselect, lpc31_spistatus, and + * lpc31_spicmddata must be provided by board-specific logic. These are + * implementations of the select, status, and cmddata methods of the SPI interface + * defined by struct spi_ops_s (see include/nuttx/spi.h). All other methods + * (including up_spiinitialize()) are provided by common LPC31XX logic. To use + * this common SPI logic on your board: + * + * 1. Provide logic in lpc31_boardinitialize() to configure SPI chip select + * pins. + * 2. Provide lpc31_spiselect() and lpc31_spistatus() functions in your + * board-specific logic. These functions will perform chip selection and + * status operations using GPIOs in the way your board is configured. + * 3. If CONFIG_SPI_CMDDATA is selected in your NuttX configuration, provide + * the lpc31_spicmddata() function in your board-specific logic. This + * function will perform cmd/data selection operations using GPIOs in the + * way your board is configured. + * 4. Add a calls to up_spiinitialize() in your low level application + * initialization logic + * 5. The handle returned by up_spiinitialize() may then be used to bind the + * SPI driver to higher level logic (e.g., calling + * mmcsd_spislotinitialize(), for example, will bind the SPI driver to + * the SPI MMC/SD driver). + * + ************************************************************************************/ + +struct spi_dev_s; +enum spi_dev_e; +EXTERN void lpc31_spiselect(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected); +EXTERN uint8_t lpc31_spistatus(FAR struct spi_dev_s *dev, enum spi_dev_e devid); +#ifdef CONFIG_SPI_CMDDATA +EXTERN int lpc31_spicmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd); +#endif + +/************************************************************************************ + * Name: lpc31_usbpullup + * + * Description: + * If USB is supported and the board supports a pullup via GPIO (for USB software + * connect and disconnect), then the board software must provide lpc31_pullup. + * See include/nuttx/usb/usbdev.h for additional description of this method. + * Alternatively, if no pull-up GPIO the following EXTERN can be redefined to be + * NULL. + * + ************************************************************************************/ + +struct usbdev_s; +EXTERN int lpc31_usbpullup(FAR struct usbdev_s *dev, bool enable); + +/************************************************************************************ + * Name: lpc31_usbsuspend + * + * Description: + * Board logic must provide the lpc31_usbsuspend logic if the USBDEV driver is + * used. This function is called whenever the USB enters or leaves suspend mode. + * This is an opportunity for the board logic to shutdown clocks, power, etc. + * while the USB is suspended. + * + ************************************************************************************/ + +struct usbdev_s; +EXTERN void lpc31_usbsuspend(FAR struct usbdev_s *dev, bool resume); + +/**************************************************************************** + * Name: sdio_initialize + * + * Description: + * Initialize SDIO for operation. + * + * Input Parameters: + * slotno - Not used. + * + * Returned Values: + * A reference to an SDIO interface structure. NULL is returned on failures. + * + ****************************************************************************/ + +struct sdio_dev_s; /* See include/nuttx/sdio.h */ +EXTERN FAR struct sdio_dev_s *sdio_initialize(int slotno); + +/**************************************************************************** + * Name: sdio_mediachange + * + * Description: + * Called by board-specific logic -- posssible from an interrupt handler -- + * in order to signal to the driver that a card has been inserted or + * removed from the slot + * + * Input Parameters: + * dev - An instance of the SDIO driver device state structure. + * cardinslot - true is a card has been detected in the slot; false if a + * card has been removed from the slot. Only transitions + * (inserted->removed or removed->inserted should be reported) + * + * Returned Values: + * None + * + ****************************************************************************/ + +EXTERN void sdio_mediachange(FAR struct sdio_dev_s *dev, bool cardinslot); + +/**************************************************************************** + * Name: sdio_wrprotect + * + * Description: + * Called by board-specific logic to report if the card in the slot is + * mechanically write protected. + * + * Input Parameters: + * dev - An instance of the SDIO driver device state structure. + * wrprotect - true is a card is writeprotected. + * + * Returned Values: + * None + * + ****************************************************************************/ + +EXTERN void sdio_wrprotect(FAR struct sdio_dev_s *dev, bool wrprotect); + +#undef EXTERN +#if defined(__cplusplus) +} +#endif + +#endif /* __ASSEMBLY__ */ +#endif /* __ARCH_ARM_SRC_LPC31XX_LPC31_INTERNAL_H */ diff --git a/nuttx/arch/arm/src/lpc31xx/lpc31_ioconfig.h b/nuttx/arch/arm/src/lpc31xx/lpc31_ioconfig.h new file mode 100755 index 000000000..491943fd6 --- /dev/null +++ b/nuttx/arch/arm/src/lpc31xx/lpc31_ioconfig.h @@ -0,0 +1,357 @@ +/************************************************************************************************ + * arch/arm/src/lpc31xx/lpc31_ioconfig.h + * + * Copyright (C) 2009-2010 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * 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_LPC31XX_LPC31_IOCONFIG_H +#define __ARCH_ARM_SRC_LPC31XX_LPC31_IOCONFIG_H + +/************************************************************************************************ + * Included Files + ************************************************************************************************/ + +#include +#include "lpc31_memorymap.h" + +/************************************************************************************************ + * Pre-processor Definitions + ************************************************************************************************/ + +/* IOCONFIG register base address offset into the APB0 domain ***********************************/ + +#define LPC31_IOCONFIG_VBASE (LPC31_APB0_VADDR+LPC31_APB0_IOCONFIG_OFFSET) +#define LPC31_IOCONFIG_PBASE (LPC31_APB0_PADDR+LPC31_APB0_IOCONFIG_OFFSET) + +/* IOCONFIG function block offsets (with respect to the IOCONFIG register base address) *********/ + +#define LPC31_IOCONFIG_EBIMCI_OFFSET 0x000 /* First set of 32 multiplexed pads */ +#define LPC31_IOCONFIG_EBII2STX0_OFFSET 0X040 /* Second set of 32 of multiplexed pads */ +#define LPC31_IOCONFIG_CGU_OFFSET 0X080 /* Clock Generation Unit function block */ +#define LPC31_IOCONFIG_I2SRX0_OFFSET 0x0c0 /* I2SRX function block 0 */ +#define LPC31_IOCONFIG_I2SRX1_OFFSET 0x100 /* I2SRX function block 1 */ +#define LPC31_IOCONFIG_I2STX1_OFFSET 0x140 /* I2STX function block 1 */ +#define LPC31_IOCONFIG_EBI_OFFSET 0x180 /* External Bus Interface function block */ +#define LPC31_IOCONFIG_GPIO_OFFSET 0x1c0 /* General purpose IO */ +#define LPC31_IOCONFIG_I2C1_OFFSET 0x200 /* I2C function block */ +#define LPC31_IOCONFIG_SPI_OFFSET 0x240 /* SPI function block */ +#define LPC31_IOCONFIG_NAND_OFFSET 0x280 /* NANDFLASH function block */ +#define LPC31_IOCONFIG_PWM_OFFSET 0x2c0 /* PWM function block */ +#define LPC31_IOCONFIG_UART_OFFSET 0x300 /* UART function block */ + +/* IOCONFIG register offsets (with respect to any funcion block base address) *******************/ + +#define LPC31_IOCONFIG_PINS_OFFSET 0x000 /* WR: RD: Input pin state */ + /* 0x004-0x00c: Reserved */ +#define LPC31_IOCONFIG_MODE0_OFFSET 0x010 /* WR:Load RD: */ +#define LPC31_IOCONFIG_MODE0SET_OFFSET 0x014 /* WR:Set Bits RD:Read Mode 0 */ +#define LPC31_IOCONFIG_MODE0RESET_OFFSET 0x018 /* WR:Reset Bits RD: */ + /* 0x01c: Reserved */ +#define LPC31_IOCONFIG_MODE1_OFFSET 0x020 /* WR:Load RD: */ +#define LPC31_IOCONFIG_MODE1SET_OFFSET 0x024 /* WR:Set Bits RD:Read Mode 1 */ +#define LPC31_IOCONFIG_MODE1RESET_OFFSET 0x028 /* WR:Reset Bits RD: */ + /* 0x02c-0x3c: Reserved */ + +/* IOCONFIG function block (virtual) base addresses *********************************************/ + +#define LPC31_IOCONFIG_EBIMCI (LPC31_IOCONFIG_VBASE+LPC31_IOCONFIG_EBIMCI_OFFSET) +#define LPC31_IOCONFIG_EBII2STX0 (LPC31_IOCONFIG_VBASE+LPC31_IOCONFIG_EBII2STX0_OFFSET) +#define LPC31_IOCONFIG_CGU (LPC31_IOCONFIG_VBASE+LPC31_IOCONFIG_CGU_OFFSET) +#define LPC31_IOCONFIG_I2SRX0 (LPC31_IOCONFIG_VBASE+LPC31_IOCONFIG_I2SRX0_OFFSET) +#define LPC31_IOCONFIG_I2SRX1 (LPC31_IOCONFIG_VBASE+LPC31_IOCONFIG_I2SRX1_OFFSET) +#define LPC31_IOCONFIG_I2STX1 (LPC31_IOCONFIG_VBASE+LPC31_IOCONFIG_I2STX1_OFFSET) +#define LPC31_IOCONFIG_EBI (LPC31_IOCONFIG_VBASE+LPC31_IOCONFIG_EBI_OFFSET) +#define LPC31_IOCONFIG_GPIO (LPC31_IOCONFIG_VBASE+LPC31_IOCONFIG_GPIO_OFFSET) +#define LPC31_IOCONFIG_I2C1 (LPC31_IOCONFIG_VBASE+LPC31_IOCONFIG_I2C1_OFFSET) +#define LPC31_IOCONFIG_SPI (LPC31_IOCONFIG_VBASE+LPC31_IOCONFIG_SPI_OFFSET) +#define LPC31_IOCONFIG_NAND (LPC31_IOCONFIG_VBASE+LPC31_IOCONFIG_NAND_OFFSET) +#define LPC31_IOCONFIG_PWM (LPC31_IOCONFIG_VBASE+LPC31_IOCONFIG_PWM_OFFSET) +#define LPC31_IOCONFIG_UART (LPC31_IOCONFIG_VBASE+LPC31_IOCONFIG_UART_OFFSET) + +/* IOCONFIG register (virtual) addresses ********************************************************/ + +#define LPC31_IOCONFIG_EBIMCI_PINS (LPC31_IOCONFIG_EBIMCI+LPC31_IOCONFIG_PINS_OFFSET) +#define LPC31_IOCONFIG_EBIMCI_MODE0 (LPC31_IOCONFIG_EBIMCI+LPC31_IOCONFIG_MODE0_OFFSET) +#define LPC31_IOCONFIG_EBIMCI_MODE0SET (LPC31_IOCONFIG_EBIMCI+LPC31_IOCONFIG_MODE0SET_OFFSET) +#define LPC31_IOCONFIG_EBIMCI_MODE0RESET (LPC31_IOCONFIG_EBIMCI+LPC31_IOCONFIG_MODE0RESET_OFFSET) +#define LPC31_IOCONFIG_EBIMCI_MODE1 (LPC31_IOCONFIG_EBIMCI+LPC31_IOCONFIG_MODE1_OFFSET) +#define LPC31_IOCONFIG_EBIMCI_MODE1SET (LPC31_IOCONFIG_EBIMCI+LPC31_IOCONFIG_MODE1SET_OFFSET) +#define LPC31_IOCONFIG_EBIMCI_MODE1RESET (LPC31_IOCONFIG_EBIMCI+LPC31_IOCONFIG_MODE1RESET_OFFSET) + +#define LPC31_IOCONFIG_EBII2STX0_PINS (LPC31_IOCONFIG_EBII2STX0+LPC31_IOCONFIG_PINS_OFFSET) +#define LPC31_IOCONFIG_EBII2STX0_MODE0 (LPC31_IOCONFIG_EBII2STX0+LPC31_IOCONFIG_MODE0_OFFSET) +#define LPC31_IOCONFIG_EBII2STX0_MODE0SET (LPC31_IOCONFIG_EBII2STX0+LPC31_IOCONFIG_MODE0SET_OFFSET) +#define LPC31_IOCONFIG_EBII2STX0_MODE0RESET (LPC31_IOCONFIG_EBII2STX0+LPC31_IOCONFIG_MODE0RESET_OFFSET) +#define LPC31_IOCONFIG_EBII2STX0_MODE1 (LPC31_IOCONFIG_EBII2STX0+LPC31_IOCONFIG_MODE1_OFFSET) +#define LPC31_IOCONFIG_EBII2STX0_MODE1SET (LPC31_IOCONFIG_EBII2STX0+LPC31_IOCONFIG_MODE1SET_OFFSET) +#define LPC31_IOCONFIG_EBII2STX0_MODE1RESET (LPC31_IOCONFIG_EBII2STX0+LPC31_IOCONFIG_MODE1RESET_OFFSET) + +#define LPC31_IOCONFIG_CGU_PINS (LPC31_IOCONFIG_CGU+LPC31_IOCONFIG_PINS_OFFSET) +#define LPC31_IOCONFIG_CGU_MODE0 (LPC31_IOCONFIG_CGU+LPC31_IOCONFIG_MODE0_OFFSET) +#define LPC31_IOCONFIG_CGU_MODE0SET (LPC31_IOCONFIG_CGU+LPC31_IOCONFIG_MODE0SET_OFFSET) +#define LPC31_IOCONFIG_CGU_MODE0RESET (LPC31_IOCONFIG_CGU+LPC31_IOCONFIG_MODE0RESET_OFFSET) +#define LPC31_IOCONFIG_CGU_MODE1 (LPC31_IOCONFIG_CGU+LPC31_IOCONFIG_MODE1_OFFSET) +#define LPC31_IOCONFIG_CGU_MODE1SET (LPC31_IOCONFIG_CGU+LPC31_IOCONFIG_MODE1SET_OFFSET) +#define LPC31_IOCONFIG_CGU_MODE1RESET (LPC31_IOCONFIG_CGU+LPC31_IOCONFIG_MODE1RESET_OFFSET) + +#define LPC31_IOCONFIG_I2SRX0_PINS (LPC31_IOCONFIG_I2SRX0+LPC31_IOCONFIG_PINS_OFFSET) +#define LPC31_IOCONFIG_I2SRX0_MODE0 (LPC31_IOCONFIG_I2SRX0+LPC31_IOCONFIG_MODE0_OFFSET) +#define LPC31_IOCONFIG_I2SRX0_MODE0SET (LPC31_IOCONFIG_I2SRX0+LPC31_IOCONFIG_MODE0SET_OFFSET) +#define LPC31_IOCONFIG_I2SRX0_MODE0RESET (LPC31_IOCONFIG_I2SRX0+LPC31_IOCONFIG_MODE0RESET_OFFSET) +#define LPC31_IOCONFIG_I2SRX0_MODE1 (LPC31_IOCONFIG_I2SRX0+LPC31_IOCONFIG_MODE1_OFFSET) +#define LPC31_IOCONFIG_I2SRX0_MODE1SET (LPC31_IOCONFIG_I2SRX0+LPC31_IOCONFIG_MODE1SET_OFFSET) +#define LPC31_IOCONFIG_I2SRX0_MODE1RESET (LPC31_IOCONFIG_I2SRX0+LPC31_IOCONFIG_MODE1RESET_OFFSET) + +#define LPC31_IOCONFIG_I2SRX1_PINS (LPC31_IOCONFIG_I2SRX1+LPC31_IOCONFIG_PINS_OFFSET) +#define LPC31_IOCONFIG_I2SRX1_MODE0 (LPC31_IOCONFIG_I2SRX1+LPC31_IOCONFIG_MODE0_OFFSET) +#define LPC31_IOCONFIG_I2SRX1_MODE0SET (LPC31_IOCONFIG_I2SRX1+LPC31_IOCONFIG_MODE0SET_OFFSET) +#define LPC31_IOCONFIG_I2SRX1_MODE0RESET (LPC31_IOCONFIG_I2SRX1+LPC31_IOCONFIG_MODE0RESET_OFFSET) +#define LPC31_IOCONFIG_I2SRX1_MODE1 (LPC31_IOCONFIG_I2SRX1+LPC31_IOCONFIG_MODE1_OFFSET) +#define LPC31_IOCONFIG_I2SRX1_MODE1SET (LPC31_IOCONFIG_I2SRX1+LPC31_IOCONFIG_MODE1SET_OFFSET) +#define LPC31_IOCONFIG_I2SRX1_MODE1RESET (LPC31_IOCONFIG_I2SRX1+LPC31_IOCONFIG_MODE1RESET_OFFSET) + +#define LPC31_IOCONFIG_I2STX1_PINS (LPC31_IOCONFIG_I2STX1+LPC31_IOCONFIG_PINS_OFFSET) +#define LPC31_IOCONFIG_I2STX1_MODE0 (LPC31_IOCONFIG_I2STX1+LPC31_IOCONFIG_MODE0_OFFSET) +#define LPC31_IOCONFIG_I2STX1_MODE0SET (LPC31_IOCONFIG_I2STX1+LPC31_IOCONFIG_MODE0SET_OFFSET) +#define LPC31_IOCONFIG_I2STX1_MODE0RESET (LPC31_IOCONFIG_I2STX1+LPC31_IOCONFIG_MODE0RESET_OFFSET) +#define LPC31_IOCONFIG_I2STX1_MODE1 (LPC31_IOCONFIG_I2STX1+LPC31_IOCONFIG_MODE1_OFFSET) +#define LPC31_IOCONFIG_I2STX1_MODE1SET (LPC31_IOCONFIG_I2STX1+LPC31_IOCONFIG_MODE1SET_OFFSET) +#define LPC31_IOCONFIG_I2STX1_MODE1RESET (LPC31_IOCONFIG_I2STX1+LPC31_IOCONFIG_MODE1RESET_OFFSET) + +#define LPC31_IOCONFIG_EBI_PINS (LPC31_IOCONFIG_EBI+LPC31_IOCONFIG_PINS_OFFSET) +#define LPC31_IOCONFIG_EBI_MODE0 (LPC31_IOCONFIG_EBI+LPC31_IOCONFIG_MODE0_OFFSET) +#define LPC31_IOCONFIG_EBI_MODE0SET (LPC31_IOCONFIG_EBI+LPC31_IOCONFIG_MODE0SET_OFFSET) +#define LPC31_IOCONFIG_EBI_MODE0RESET (LPC31_IOCONFIG_EBI+LPC31_IOCONFIG_MODE0RESET_OFFSET) +#define LPC31_IOCONFIG_EBI_MODE1 (LPC31_IOCONFIG_EBI+LPC31_IOCONFIG_MODE1_OFFSET) +#define LPC31_IOCONFIG_EBI_MODE1SET (LPC31_IOCONFIG_EBI+LPC31_IOCONFIG_MODE1SET_OFFSET) +#define LPC31_IOCONFIG_EBI_MODE1RESET (LPC31_IOCONFIG_EBI+LPC31_IOCONFIG_MODE1RESET_OFFSET) + +#define LPC31_IOCONFIG_GPIO_PINS (LPC31_IOCONFIG_GPIO+LPC31_IOCONFIG_PINS_OFFSET) +#define LPC31_IOCONFIG_GPIO_MODE0 (LPC31_IOCONFIG_GPIO+LPC31_IOCONFIG_MODE0_OFFSET) +#define LPC31_IOCONFIG_GPIO_MODE0SET (LPC31_IOCONFIG_GPIO+LPC31_IOCONFIG_MODE0SET_OFFSET) +#define LPC31_IOCONFIG_GPIO_MODE0RESET (LPC31_IOCONFIG_GPIO+LPC31_IOCONFIG_MODE0RESET_OFFSET) +#define LPC31_IOCONFIG_GPIO_MODE1 (LPC31_IOCONFIG_GPIO+LPC31_IOCONFIG_MODE1_OFFSET) +#define LPC31_IOCONFIG_GPIO_MODE1SET (LPC31_IOCONFIG_GPIO+LPC31_IOCONFIG_MODE1SET_OFFSET) +#define LPC31_IOCONFIG_GPIO_MODE1RESET (LPC31_IOCONFIG_GPIO+LPC31_IOCONFIG_MODE1RESET_OFFSET) + +#define LPC31_IOCONFIG_I2C1_PINS (LPC31_IOCONFIG_I2C1+LPC31_IOCONFIG_PINS_OFFSET) +#define LPC31_IOCONFIG_I2C1_MODE0 (LPC31_IOCONFIG_I2C1+LPC31_IOCONFIG_MODE0_OFFSET) +#define LPC31_IOCONFIG_I2C1_MODE0SET (LPC31_IOCONFIG_I2C1+LPC31_IOCONFIG_MODE0SET_OFFSET) +#define LPC31_IOCONFIG_I2C1_MODE0RESET (LPC31_IOCONFIG_I2C1+LPC31_IOCONFIG_MODE0RESET_OFFSET) +#define LPC31_IOCONFIG_I2C1_MODE1 (LPC31_IOCONFIG_I2C1+LPC31_IOCONFIG_MODE1_OFFSET) +#define LPC31_IOCONFIG_I2C1_MODE1SET (LPC31_IOCONFIG_I2C1+LPC31_IOCONFIG_MODE1SET_OFFSET) +#define LPC31_IOCONFIG_I2C1_MODE1RESET (LPC31_IOCONFIG_I2C1+LPC31_IOCONFIG_MODE1RESET_OFFSET) + +#define LPC31_IOCONFIG_SPI_PINS (LPC31_IOCONFIG_SPI+LPC31_IOCONFIG_PINS_OFFSET) +#define LPC31_IOCONFIG_SPI_MODE0 (LPC31_IOCONFIG_SPI+LPC31_IOCONFIG_MODE0_OFFSET) +#define LPC31_IOCONFIG_SPI_MODE0SET (LPC31_IOCONFIG_SPI+LPC31_IOCONFIG_MODE0SET_OFFSET) +#define LPC31_IOCONFIG_SPI_MODE0RESET (LPC31_IOCONFIG_SPI+LPC31_IOCONFIG_MODE0RESET_OFFSET) +#define LPC31_IOCONFIG_SPI_MODE1 (LPC31_IOCONFIG_SPI+LPC31_IOCONFIG_MODE1_OFFSET) +#define LPC31_IOCONFIG_SPI_MODE1SET (LPC31_IOCONFIG_SPI+LPC31_IOCONFIG_MODE1SET_OFFSET) +#define LPC31_IOCONFIG_SPI_MODE1RESET (LPC31_IOCONFIG_SPI+LPC31_IOCONFIG_MODE1RESET_OFFSET) + +#define LPC31_IOCONFIG_NAND_PINS (LPC31_IOCONFIG_NAND+LPC31_IOCONFIG_PINS_OFFSET) +#define LPC31_IOCONFIG_NAND_MODE0 (LPC31_IOCONFIG_NAND+LPC31_IOCONFIG_MODE0_OFFSET) +#define LPC31_IOCONFIG_NAND_MODE0SET (LPC31_IOCONFIG_NAND+LPC31_IOCONFIG_MODE0SET_OFFSET) +#define LPC31_IOCONFIG_NAND_MODE0RESET (LPC31_IOCONFIG_NAND+LPC31_IOCONFIG_MODE0RESET_OFFSET) +#define LPC31_IOCONFIG_NAND_MODE1 (LPC31_IOCONFIG_NAND+LPC31_IOCONFIG_MODE1_OFFSET) +#define LPC31_IOCONFIG_NAND_MODE1SET (LPC31_IOCONFIG_NAND+LPC31_IOCONFIG_MODE1SET_OFFSET) +#define LPC31_IOCONFIG_NAND_MODE1RESET (LPC31_IOCONFIG_NAND+LPC31_IOCONFIG_MODE1RESET_OFFSET) + +#define LPC31_IOCONFIG_PWM_PINS (LPC31_IOCONFIG_PWM+LPC31_IOCONFIG_PINS_OFFSET) +#define LPC31_IOCONFIG_PWM_MODE0 (LPC31_IOCONFIG_PWM+LPC31_IOCONFIG_MODE0_OFFSET) +#define LPC31_IOCONFIG_PWM_MODE0SET (LPC31_IOCONFIG_PWM+LPC31_IOCONFIG_MODE0SET_OFFSET) +#define LPC31_IOCONFIG_PWM_MODE0RESET (LPC31_IOCONFIG_PWM+LPC31_IOCONFIG_MODE0RESET_OFFSET) +#define LPC31_IOCONFIG_PWM_MODE1 (LPC31_IOCONFIG_PWM+LPC31_IOCONFIG_MODE1_OFFSET) +#define LPC31_IOCONFIG_PWM_MODE1SET (LPC31_IOCONFIG_PWM+LPC31_IOCONFIG_MODE1SET_OFFSET) +#define LPC31_IOCONFIG_PWM_MODE1RESET (LPC31_IOCONFIG_PWM+LPC31_IOCONFIG_MODE1RESET_OFFSET) + +#define LPC31_IOCONFIG_UART_PINS (LPC31_IOCONFIG_UART+LPC31_IOCONFIG_PINS_OFFSET) +#define LPC31_IOCONFIG_UART_MODE0 (LPC31_IOCONFIG_UART+LPC31_IOCONFIG_MODE0_OFFSET) +#define LPC31_IOCONFIG_UART_MODE0SET (LPC31_IOCONFIG_UART+LPC31_IOCONFIG_MODE0SET_OFFSET) +#define LPC31_IOCONFIG_UART_MODE0RESET (LPC31_IOCONFIG_UART+LPC31_IOCONFIG_MODE0RESET_OFFSET) +#define LPC31_IOCONFIG_UART_MODE1 (LPC31_IOCONFIG_UART+LPC31_IOCONFIG_MODE1_OFFSET) +#define LPC31_IOCONFIG_UART_MODE1SET (LPC31_IOCONFIG_UART+LPC31_IOCONFIG_MODE1SET_OFFSET) +#define LPC31_IOCONFIG_UART_MODE1RESET (LPC31_IOCONFIG_UART+LPC31_IOCONFIG_MODE1RESET_OFFSET) + +/* IOCONFIG register bit definitions ************************************************************/ +/* EBI_MCI register bit definitions (all registers) */ + + +#define IOCONFIG_EBIMCI_MGPIO9 (1 << 0) +#define IOCONFIG_EBIMCI_MGPIO6 (1 << 1) +#define IOCONFIG_EBIMCI_MLCDDB7 (1 << 2) +#define IOCONFIG_EBIMCI_MLCDDB4 (1 << 3) +#define IOCONFIG_EBIMCI_MLCDDB2 (1 << 4) +#define IOCONFIG_EBIMCI_MNANDRYBN0 (1 << 5) +#define IOCONFIG_EBIMCI_MI2STXCLK0 (1 << 6) +#define IOCONFIG_EBIMCI_MI2STXBCK0 (1 << 7) +#define IOCONFIG_EBIMCI_EBIA1CLE (1 << 8) +#define IOCONFIG_EBIMCI_EBINCASBLOUT0 (1 << 9) +#define IOCONFIG_EBIMCI_MLCDDB0 (1 << 10) +#define IOCONFIG_EBIMCI_EBIDQM0NOE (1 << 11) +#define IOCONFIG_EBIMCI_MLCDCSB (1 << 12) +#define IOCONFIG_EBIMCI_MLCDDB1 (1 << 13) +#define IOCONFIG_EBIMCI_MLCDERD (1 << 14) +#define IOCONFIG_EBIMCI_MLCDRS (1 << 15) +#define IOCONFIG_EBIMCI_MLCDRWWR (1 << 16) +#define IOCONFIG_EBIMCI_MLCDDB3 (1 << 17) +#define IOCONFIG_EBIMCI_MLCDDB5 (1 << 18) +#define IOCONFIG_EBIMCI_MLCDDB6 (1 << 19) +#define IOCONFIG_EBIMCI_MLCDDB8 (1 << 20) +#define IOCONFIG_EBIMCI_MLCDDB9 (1 << 21) +#define IOCONFIG_EBIMCI_MLCDDB10 (1 << 22) +#define IOCONFIG_EBIMCI_MLCDDB11 (1 << 23) +#define IOCONFIG_EBIMCI_MLCDDB12 (1 << 24) +#define IOCONFIG_EBIMCI_MLCDDB13 (1 << 25) +#define IOCONFIG_EBIMCI_MLCDDB14 (1 << 26) +#define IOCONFIG_EBIMCI_MLCDDB15 (1 << 27) +#define IOCONFIG_EBIMCI_MGPIO5 (1 << 28) +#define IOCONFIG_EBIMCI_MGPIO7 (1 << 29) +#define IOCONFIG_EBIMCI_MGPIO8 (1 << 30) +#define IOCONFIG_EBIMCI_MGPIO10 (1 << 31) + +/* EBI_I2STX_0 register bit definitions (all registers) */ + +#define IOCONFIG_EBII2STX0_MNANDRYBN1 (1 << 0) +#define IOCONFIG_EBII2STX0_MNANDRYBN2 (1 << 1) +#define IOCONFIG_EBII2STX0_MNANDRYBN3 (1 << 2) +#define IOCONFIG_EBII2STX0_MUARTCTSN (1 << 3) +#define IOCONFIG_EBII2STX0_MUARTRTSN (1 << 4) +#define IOCONFIG_EBII2STX0_MI2STXDATA0 (1 << 5) +#define IOCONFIG_EBII2STX0_MI2STXWS0 (1 << 6) +#define IOCONFIG_EBII2STX0_EBINRASBLOUT1 (1 << 7) +#define IOCONFIG_EBII2STX0_EBIA0ALE (1 << 8) +#define IOCONFIG_EBII2STX0_EBINWE (1 << 9) + +/* CGU register bit definitions (all registers) */ + +#define IOCONFIG_CGU_SYSCLKO (1 << 0) + +/* I2SRX_0 register bit definitions (all registers) */ + +#define IOCONFIG_I2SRX0_BCK (1 << 0) +#define IOCONFIG_I2SRX0_DATA (1 << 1) +#define IOCONFIG_I2SRX0_WS (1 << 2) + +/* I2SRX_1 register bit definitions (all registers) */ + +#define IOCONFIG_I2SRX1_DATA (1 << 0) +#define IOCONFIG_I2SRX1_BCK (1 << 1) +#define IOCONFIG_I2SRX1_WS (1 << 2) + +/* I2STX_1 register bit definitions (all registers) */ + +#define IOCONFIG_I2STX1_DATA (1 << 0) +#define IOCONFIG_I2STX1_BCK (1 << 1) +#define IOCONFIG_I2STX1_WS (1 << 2) +#define IOCONFIG_I2STX1_256FSO (1 << 3) + +/* EBI register bit definitions (all registers) */ + +#define IOCONFIG_EBI_D9 (1 << 0) +#define IOCONFIG_EBI_D10 (1 << 1) +#define IOCONFIG_EBI_D11 (1 << 2) +#define IOCONFIG_EBI_D12 (1 << 3) +#define IOCONFIG_EBI_D13 (1 << 4) +#define IOCONFIG_EBI_D14 (1 << 5) +#define IOCONFIG_EBI_D4 (1 << 6) +#define IOCONFIG_EBI_D0 (1 << 7) +#define IOCONFIG_EBI_D1 (1 << 8) +#define IOCONFIG_EBI_D2 (1 << 9) +#define IOCONFIG_EBI_D3 (1 << 10) +#define IOCONFIG_EBI_D5 (1 << 11) +#define IOCONFIG_EBI_D6 (1 << 12) +#define IOCONFIG_EBI_D7 (1 << 13) +#define IOCONFIG_EBI_D8 (1 << 14) +#define IOCONFIG_EBI_D15 (1 << 15) + +/* GPIO register bit definitions (all registers) */ + +#define IOCONFIG_GPIO_GPIO1 (1 << 0) +#define IOCONFIG_GPIO_GPIO0 (1 << 1) +#define IOCONFIG_GPIO_GPIO2 (1 << 2) +#define IOCONFIG_GPIO_GPIO3 (1 << 3) +#define IOCONFIG_GPIO_GPIO4 (1 << 4) +#define IOCONFIG_GPIO_GPIO11 (1 << 5) +#define IOCONFIG_GPIO_GPIO12 (1 << 6) +#define IOCONFIG_GPIO_GPIO13 (1 << 7) +#define IOCONFIG_GPIO_GPIO14 (1 << 8) +#define IOCONFIG_GPIO_GPIO15 (1 << 9) +#define IOCONFIG_GPIO_GPIO16 (1 << 10) +#define IOCONFIG_GPIO_GPIO17 (1 << 11) +#define IOCONFIG_GPIO_GPIO18 (1 << 12) +#define IOCONFIG_GPIO_GPIO19 (1 << 13) +#define IOCONFIG_GPIO_GPIO20 (1 << 14) + +/* I2C1 register bit definitions (all registers) */ + +#define IOCONFIG_I2C1_SDA1 (1 << 0) +#define IOCONFIG_I2C1_SCL1 (1 << 1) + +/* SPI register bit definitions (all registers) */ + +#define IOCONFIG_SPI_MISO (1 << 0) +#define IOCONFIG_SPI_MOSI (1 << 1) +#define IOCONFIG_SPI_CSIN (1 << 2) +#define IOCONFIG_SPI_SCK (1 << 3) +#define IOCONFIG_SPI_CSOUT0 (1 << 4) + +/* NAND register bit definitions (all registers) */ + +#define IOCONFIG_NAND_NCS3 (1 << 0) +#define IOCONFIG_NAND_NCS0 (1 << 1) +#define IOCONFIG_NAND_NCS1 (1 << 2) +#define IOCONFIG_NAND_NCS2 (1 << 3) + +/* PWM register bit definitions (all registers) */ + +#define IOCONFIG_PWM_DATA (1 << 0) + +/* UART register bit definitions (all registers) */ + +#define IOCONFIG_UART_RXD (1 << 0) +#define IOCONFIG_UART_TXD (1 << 1) + +/************************************************************************************************ + * Public Types + ************************************************************************************************/ + +/************************************************************************************************ + * Public Data + ************************************************************************************************/ + +/************************************************************************************************ + * Public Functions + ************************************************************************************************/ + +#endif /* __ARCH_ARM_SRC_LPC31XX_LPC31_IOCONFIG_H */ diff --git a/nuttx/arch/arm/src/lpc31xx/lpc31_irq.c b/nuttx/arch/arm/src/lpc31xx/lpc31_irq.c new file mode 100755 index 000000000..69cddda6e --- /dev/null +++ b/nuttx/arch/arm/src/lpc31xx/lpc31_irq.c @@ -0,0 +1,218 @@ +/**************************************************************************** + * arch/arm/src/lpc31xx/lpc31_irq.c + * arch/arm/src/chip/lpc31_irq.c + * + * Copyright (C) 2009-2011 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name NuttX nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include + +#include +#include +#include + +#include "arm.h" +#include "up_arch.h" +#include "os_internal.h" +#include "up_internal.h" + +#include "lpc31_intc.h" +#include "lpc31_cgudrvr.h" +#include "lpc31_internal.h" + +/**************************************************************************** + * Definitions + ****************************************************************************/ + +/**************************************************************************** + * Public Data + ****************************************************************************/ + +volatile uint32_t *current_regs; + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: up_irqinitialize + ****************************************************************************/ + +void up_irqinitialize(void) +{ + int irq; + + /* Enable clock to interrupt controller */ + + lpc31_enableclock(CLKID_AHB2INTCCLK); /* AHB_TO_INTC_CLK */ + lpc31_enableclock(CLKID_INTCCLK); /* INTC_CLK */ + + /* Set the vector base. We don't use direct vectoring, so these are set to 0. */ + + putreg32(0, LPC31_INTC_VECTOR0); + putreg32(0, LPC31_INTC_VECTOR1); + + /* Set the priority treshold to 0, i.e. don't mask any interrupt on the + * basis of priority level, for both targets (IRQ/FIQ) + */ + + putreg32(0, LPC31_INTC_PRIORITYMASK0); /* Proc interrupt request 0: IRQ */ + putreg32(0, LPC31_INTC_PRIORITYMASK1); /* Proc interrupt request 1: FIQ */ + + /* Disable all interrupts. Start from index 1 since 0 is unused.*/ + + for (irq = 0; irq < NR_IRQS; irq++) + { + /* Initialize as high-active, disable the interrupt, set target to IRQ, + * Set priority level to 1 (= lowest) for all the interrupt lines + */ + + uint32_t address = LPC31_INTC_REQUEST(irq+1); + putreg32(INTC_REQUEST_WEACTLOW|INTC_REQUEST_WEENABLE|INTC_REQUEST_TARGET_IRQ| + INTC_REQUEST_PRIOLEVEL(1)|INTC_REQUEST_WEPRIO, address); + + } + + /* currents_regs is non-NULL only while processing an interrupt */ + + current_regs = NULL; + + /* And finally, enable interrupts */ + +#ifndef CONFIG_SUPPRESS_INTERRUPTS + irqrestore(SVC_MODE | PSR_F_BIT); +#endif +} + +/**************************************************************************** + * Name: up_disable_irq + * + * Description: + * Disable the IRQ specified by 'irq' + * + ****************************************************************************/ + +void up_disable_irq(int irq) +{ + /* Get the address of the request register corresponding to this + * interrupt source + */ + + uint32_t address = LPC31_INTC_REQUEST(irq+1); + + /* Clear the ENABLE bit with WE_ENABLE=1. Configuration settings will be + * preserved because WE_TARGET is zero. + */ + + putreg32(INTC_REQUEST_WEENABLE, address); +} + +/**************************************************************************** + * Name: up_enable_irq + * + * Description: + * Enable the IRQ specified by 'irq' + * + ****************************************************************************/ + +void up_enable_irq(int irq) +{ + /* Get the address of the request register corresponding to this + * interrupt source + */ + + uint32_t address = LPC31_INTC_REQUEST(irq+1); + + /* Set the ENABLE bit with WE_ENABLE=1. Configuration settings will be + * preserved because WE_TARGET is zero. + */ + + putreg32(INTC_REQUEST_ENABLE|INTC_REQUEST_WEENABLE, address); +} + +/**************************************************************************** + * Name: up_maskack_irq + * + * Description: + * Mask the IRQ and acknowledge it + * + ****************************************************************************/ + +void up_maskack_irq(int irq) +{ + /* Get the address of the request register corresponding to this + * interrupt source + */ + + uint32_t address = LPC31_INTC_REQUEST(irq+1); + + /* Clear the pending interrupt (INTC_REQUEST_CLRSWINT=1) AND disable interrupts + * (ENABLE=0 && WE_ENABLE=1). Configuration settings will be preserved because + * WE_TARGET is zero. + */ + + putreg32(INTC_REQUEST_CLRSWINT|INTC_REQUEST_WEENABLE, address); +} + +/**************************************************************************** + * Name: up_prioritize_irq + * + * Description: + * Set the priority of an IRQ. + * + * Since this API is not supported on all architectures, it should be + * avoided in common implementations where possible. + * + ****************************************************************************/ + +#ifdef CONFIG_ARCH_IRQPRIO +int up_prioritize_irq(int irq, int priority) +{ +#warning "Not implemented" + return OK; +} +#endif diff --git a/nuttx/arch/arm/src/lpc31xx/lpc31_lcd.h b/nuttx/arch/arm/src/lpc31xx/lpc31_lcd.h new file mode 100755 index 000000000..2f659827a --- /dev/null +++ b/nuttx/arch/arm/src/lpc31xx/lpc31_lcd.h @@ -0,0 +1,161 @@ +/************************************************************************************************ + * arch/arm/src/lpc31xx/lpc31_lcd.h + * + * Copyright (C) 2009 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * 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_LPC31XX_LPC31_LCD_H +#define __ARCH_ARM_SRC_LPC31XX_LPC31_LCD_H + +/************************************************************************************************ + * Included Files + ************************************************************************************************/ + +#include +#include "lpc31_memorymap.h" + +/************************************************************************************************ + * Pre-processor Definitions + ************************************************************************************************/ + +/* LCD register base address offset into the APB2 domain ****************************************/ + +#define LPC31_LCD_VBASE (LPC31_APB2_VSECTION+LPC31_APB2_LCD_OFFSET) +#define LPC31_LCD_PBASE (LPC31_APB2_PSECTION+LPC31_APB2_LCD_OFFSET) + +/* LCD register offsets (with respect to the LCD base) ******************************************/ + +#define LPC31_LCD_STATUS_OFFSET 0x000 /* Status register */ +#define LPC31_LCD_CONTROL_OFFSET 0x004 /* Control register */ +#define LPC31_LCD_INTRAW_OFFSET 0x008 /* Interrupt Raw register */ +#define LPC31_LCD_INTCLEAR_OFFSET 0x00c /* Interrupt Clear register */ +#define LPC31_LCD_INTMASK_OFFSET 0x010 /* Interrupt Mask Register */ +#define LPC31_LCD_READCMD_OFFSET 0x014 /* Read Command register */ +#define LPC31_LCD_INSTBYTE_OFFSET 0x020 /* Instruction Byte Register */ +#define LPC31_LCD_DATABYTE_OFFSET 0x030 /* Data Byte Register */ +#define LPC31_LCD_INSTWORD_OFFSET 0x040 /* Instruction Word register */ +#define LPC31_LCD_DATAWORD_OFFSET 0x080 /* Data Word register */ + +/* LCD register (virtual) addresses *************************************************************/ + +#define LPC31_LCD_STATUS (LPC31_LCD_VBASE+LPC31_LCD_STATUS_OFFSET) +#define LPC31_LCD_CONTROL (LPC31_LCD_VBASE+LPC31_LCD_CONTROL_OFFSET) +#define LPC31_LCD_INTRAW (LPC31_LCD_VBASE+LPC31_LCD_INTRAW_OFFSET) +#define LPC31_LCD_INTCLEAR (LPC31_LCD_VBASE+LPC31_LCD_INTCLEAR_OFFSET) +#define LPC31_LCD_INTMASK (LPC31_LCD_VBASE+LPC31_LCD_INTMASK_OFFSET) +#define LPC31_LCD_READCMD (LPC31_LCD_VBASE+LPC31_LCD_READCMD_OFFSET) +#define LPC31_LCD_INSTBYTE (LPC31_LCD_VBASE+LPC31_LCD_INSTBYTE_OFFSET) +#define LPC31_LCD_DATABYTE (LPC31_LCD_VBASE+LPC31_LCD_DATABYTE_OFFSET) +#define LPC31_LCD_INSTWORD (LPC31_LCD_VBASE+LPC31_LCD_INSTWORD_OFFSET) +#define LPC31_LCD_DATAWORD (LPC31_LCD_VBASE+LPC31_LCD_DATAWORD_OFFSET) + +/* LCD register bit definitions *****************************************************************/ +/* LCD interface Status Register LCD_STATUS, address 0x15000400 */ + +#define LCD_STATUS_COUNTER_SHIFT (5) /* Bits 5-9: Current value of the FIFO counter */ +#define LCD_STATUS_COUNTER_MASK (0x1f << LCD_STATUS_COUNTER_SHIFT) +#define LCD_STATUS_INTERFACEBUSY (1 << 4) /* Bit 4: LCD interface still reading value */ +#define LCD_STATUS_INTREADVALID (1 << 3) /* Bit 3: Value read from the LCD controller is valid */ +#define LCD_STATUS_INTFIFOOVERRUN (1 << 2) /* Bit 2: Value written is larger than the FIFO can hold */ +#define LCD_STATUS_INTFIFOHALFEMPTY (1 << 1) /* Bit 1: FIFO is less then half full */ +#define LCD_STATUS_INTFIFOEMPTY (1 << 0) /* Bit 0: FIFO is empty */ + +/* LCD interface Control register LCD_CONTROL, address 0x15000404 */ + +#define LCD_CONTROL_BYASYNCRELCLK (1 << 20) /* Bit 20: Bypass PCLK & LCDLCOK asynch logic */ +#define LCD_CONTROL_IF16 (1 << 19) /* Bit 19: Interface to 16 bit LCD-Controller*/ +#define LCD_CONTROL_LOOPBACK (1 << 18) /* Bit 18: LCD Interface in Loopback mode*/ +#define LCD_CONTROL_MSBFIRST (1 << 17) /* Bit 17: Send multi-byte data MSB first*/ +#define LCD_CONTROL_INVERTERD (1 << 16) /* Bit 16: Invert polarity of E_RD*/ +#define LCD_CONTROL_INVERTCS (1 << 15) /* Bit 15: Invert CS*/ +#define LCD_CONTROL_BUSYRSVALUE (1 << 14) /* Bit 14: Busy check on RS=1*/ +#define LCD_CONTROL_BUSYBITNR_SHIFT (10) /* Bits 10-13: Bit that represents busy flag*/ +#define LCD_CONTROL_BUSYBITNR_MASK (15 << LCD_CONTROL_BUSYBITNR_SHIFT) +#define LCD_CONTROL_BUSYVALUE (1 << 9) /* Bit 9: LCD controller is busy if bit=1*/ +#define LCD_CONTROL_BUSYFLAGCHECK (1 << 8) /* Bit 8: Enable the busy-flag-checking*/ +#define LCD_CONTROL_SERRDPOSS_SHIFT (9) /* Bits 6-7: 7:6 Serial sample mode*/ +#define LCD_CONTROL_SERRDPOSS_MASK (3 << LCD_CONTROL_SERRDPOSS_SHIFT) +# define LCD_CONTROL_SERRDPOSS_START (0 << LCD_CONTROL_SERRDPOSS_SHIFT) /* Sample at beginning of cycle*/ +# define LCD_CONTROL_SERRDPOSS_FOURTH (1 << LCD_CONTROL_SERRDPOSS_SHIFT) /* Sample at 0.25 * cycle*/ +# define LCD_CONTROL_SERRDPOSS_HALF (2 << LCD_CONTROL_SERRDPOSS_SHIFT) /* Sample at 0.5 * cycle*/ +# define LCD_CONTROL_SERRDPOSS_3FOURTHS (3 << LCD_CONTROL_SERRDPOSS_SHIFT) /* Sample at 0.75 * cycle*/ +#define LCD_CONTROL_SERCLKSHIFT_SHIFT (4) /* Bits 4-5: Serial clock mode*/ +#define LCD_CONTROL_SERCLKSHIFT_MASK (3 << LCD_CONTROL_SERCLKSHIFT_SHIFT) +# define LCD_CONTROL_SERCLKSHIFT_MODE0 (0 << LCD_CONTROL_SERCLKSHIFT_SHIFT) /* Clock mode 0*/ +# define LCD_CONTROL_SERCLKSHIFT_MODE1 (1 << LCD_CONTROL_SERCLKSHIFT_SHIFT) /* Clock mode 1*/ +# define LCD_CONTROL_SERCLKSHIFT_MODE2 (2 << LCD_CONTROL_SERCLKSHIFT_SHIFT) /* Clock mode 2*/ +# define LCD_CONTROL_SERCLKSHIFT_MODE3 (3 << LCD_CONTROL_SERCLKSHIFT_SHIFT) /* Clock mode 3*/ +#define LCD_CONTROL_4BIT (1 << 3) /* Bit 2: LCD interface 4 bit mode (vs 8)*/ +#define LCD_CONTROL_MI (1 << 2) /* Bit 2: LCD interface 6800 mode (vs 8080 mode)*/ +#define LCD_CONTROL_PS (1 << 1) /* Bit 1: LCD interface serial mode (vs parallel)*/ + +/* LCD interface Interrupt Raw register LCD_INTRAW, address 0x15000408 + * LCD interface Interrupt Clear register LCD_INTCLEAR, address 0x1500040c + * LCD interface Interrupt Mask register LCD_INTMASK, address 0x15000410 + */ + +#define LCD_INT_READVALID (1 << 3) /* Bit 3: Value that has been read from the LCD controller */ +#define LCD_INT_OVERRUN (1 << 2) /* Bit 2: FIFO overrun */ +#define LCD_INT_FIFOHALFEMPTY (1 << 1) /* Bit 1: FIFO is less then half full */ +#define LCD_INT_FIFO_EMPTY (1 << 0) /* Bit 0: FIFO is empty */ + +/* LCD interface Read Command register LCD_READCMD, address 0x15000414 */ + +#define LCD_READCMD_DATABYTE (1 << 0) /* Bit 0: Read in DATA byte (vs INST) */ + +/* LCD interface Instruction Byte register LCD_INSTBYTE, address 0x15000420 */ + +#define LCD_INSTBYTE_WORD_SHIFT (0) /* Bits 0-15: 16 bit mode = 15:0 Instruction */ +#define LCD_INSTBYTE_WORD_MASK (0xffff << LCD_INSTBYTE_WORD_SHIFT) +#define LCD_INSTBYTE_BYTE_SHIFT (0) /* Bits 0-7: 8 bit mode = 7:0 Instruction */ +#define LCD_INSTBYTE_BYTE_MASK (0xff << LCD_INSTBYTE_BYTE_SHIFT) + +/* LCD interface Data Byte register LCD_DATABYTE, address 0x15000430 */ + +#define LCD_DATABYTE_WORD_SHIFT (0) /* Bits 0-15: 16 bit mode = 15:0 Instruction */ +#define LCD_DATABYTE_WORD_MASK (0xffff << LCD_IDATABYTE_WORD_SHIFT) +#define LCD_DATABYTE_BYTE_SHIFT (0) /* Bits 0-7: 8 bit mode = 7:0 Instruction */ +#define LCD_DATABYTE_BYTE_MASK (0xff << LCD_IDATABYTE_BYTE_SHIFT) + +/************************************************************************************************ + * Public Types + ************************************************************************************************/ + +/************************************************************************************************ + * Public Data + ************************************************************************************************/ + +/************************************************************************************************ + * Public Functions + ************************************************************************************************/ + +#endif /* __ARCH_ARM_SRC_LPC31XX_LPC31_LCD_H */ diff --git a/nuttx/arch/arm/src/lpc31xx/lpc31_lowputc.c b/nuttx/arch/arm/src/lpc31xx/lpc31_lowputc.c new file mode 100755 index 000000000..7d8a7cc32 --- /dev/null +++ b/nuttx/arch/arm/src/lpc31xx/lpc31_lowputc.c @@ -0,0 +1,356 @@ +/**************************************************************************** + * arch/arm/src/lpc31xx/lpc31_lowputc.c + * + * Copyright (C) 2009-2010 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name NuttX nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include +#include + +#include + +#include "up_arch.h" +#include "up_internal.h" + +#include "lpc31_cgudrvr.h" +#include "lpc31_uart.h" + +/**************************************************************************** + * Definitions + ****************************************************************************/ + +/* Configuration ************************************************************/ + +/* Is the UART enabled? */ + +#ifdef CONFIG_LPC31_UART +# define HAVE_UART 1 + +/* Is it a serial console? */ + +# ifdef CONFIG_UART_SERIAL_CONSOLE +# define HAVE_CONSOLE 1 + + /* Is initialization performed by up_earlyserialinit()? Or is UART + * initialization suppressed? + */ + +# if defined(CONFIG_USE_EARLYSERIALINIT) || defined(CONFIG_SUPPRESS_LPC31_UART_CONFIG) +# undef NEED_LOWSETUP +# else +# define NEED_LOWSETUP 1 +# endif +# else +# undef HAVE_CONSOLE +# undef NEED_LOWSETUP +# endif + +#else +# undef HAVE_UART +# undef HAVE_CONSOLE +# undef NEED_LOWSETUP +#endif + +/**************************************************************************** + * Private Types + ****************************************************************************/ + +/**************************************************************************** + * Private Variables + ****************************************************************************/ + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: up_waittxready + ****************************************************************************/ + +#ifdef HAVE_CONSOLE +static inline void up_waittxready(void) +{ + 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 ((getreg32(LPC31_UART_LSR) & UART_LSR_THRE) != 0) + { + /* The THR is empty, return */ + + break; + } + } +} +#endif + +/**************************************************************************** + * Name: up_configbaud + ****************************************************************************/ + +#ifdef NEED_LOWSETUP +static inline void up_configbaud(void) +{ + /* 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_LPC31_UART_MULVAL + uint32_t qtrclk; + uint32_t regval; + + /* 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 = lpc31_clkfreq(CLKID_UARTUCLK, DOMAINID_UART) >> 4; + + /* 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 + (CONFIG_UART_BAUD>>1)) / CONFIG_UART_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 <= CONFIG_UART_BAUD) + { + terr = CONFIG_UART_BAUD - actualbaud; + } + else + { + terr = actualbaud - CONFIG_UART_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; + } + } + } + } + + /* Set the Divisor Latch Access Bit (DLAB) to enable DLL/DLM access */ + + regval = getreg32(LPC31_UART_LCR); + regval |= UART_LCR_DLAB; + putreg32(regval, LPC31_UART_LCR); + + /* Configure the MS and LS DLAB registers */ + + putreg32(div & UART_DLL_MASK, LPC31_UART_DLL); + putreg32((div >> 8) & UART_DLL_MASK, LPC31_UART_DLM); + + regval &= ~UART_LCR_DLAB; + putreg32(regval, LPC31_UART_LCR); + + /* Configure the Fractional Divider Register (FDR) */ + + putreg32((mulval << UART_FDR_MULVAL_SHIFT) | + (divaddval << UART_FDR_DIVADDVAL_SHIFT), + LPC31_UART_FDR); +#else + /* Set the Divisor Latch Access Bit (DLAB) to enable DLL/DLM access */ + + regval = getreg32(LPC31_UART_LCR); + regval |= UART_LCR_DLAB; + putreg32(regval, LPC31_UART_LCR); + + /* Configure the MS and LS DLAB registers */ + + putreg32(CONFIG_LPC31_UART_DIVISOR & UART_DLL_MASK, LPC31_UART_DLL); + putreg32((CONFIG_LPC31_UART_DIVISOR >> 8) & UART_DLL_MASK, LPC31_UART_DLM); + + regval &= ~UART_LCR_DLAB; + putreg32(regval, LPC31_UART_LCR); + + /* Configure the Fractional Divider Register (FDR) */ + + putreg32((CONFIG_LPC31_UART_MULVAL << UART_FDR_MULVAL_SHIFT) | + (CONFIG_LPC31_UART_DIVADDVAL << UART_FDR_DIVADDVAL_SHIFT), + LPC31_UART_FDR); +#endif +} +#endif + +/**************************************************************************** + * Public Functions + ****************************************************************************/ +/**************************************************************************** + * Name: lpc31_lowsetup + * + * Description: + * Called early in up_boot. Performs chip-common low level initialization. + * + ****************************************************************************/ + +void lpc31_lowsetup(void) +{ +#ifdef NEED_LOWSETUP + uint32_t regval; + + /* Enable UART system clock */ + + lpc31_enableclock(CLKID_UARTAPBCLK); + lpc31_enableclock(CLKID_UARTUCLK); + + /* Clear fifos */ + + putreg32((UART_FCR_RXFIFORST|UART_FCR_TXFIFORST), LPC31_UART_FCR); + + /* Set trigger */ + + putreg32((UART_FCR_FIFOENABLE|UART_FCR_RXTRIGLEVEL_16), LPC31_UART_FCR); + + /* Set up the LCR */ + + regval = 0; + +#if CONFIG_UART_BITS == 5 + regval |= UART_LCR_WDLENSEL_5BITS; +#elif CONFIG_UART_BITS == 6 + regval |= UART_LCR_WDLENSEL_6BITS; +#elif CONFIG_UART_BITS == 7 + regval |= UART_LCR_WDLENSEL_7BITS; +#else + regval |= UART_LCR_WDLENSEL_8BITS; +#endif + +#if CONFIG_UART_2STOP > 0 + regval |= UART_LCR_NSTOPBITS; +#endif + +#if CONFIG_UART_PARITY == 1 + regval |= UART_LCR_PAREN; +#elif CONFIG_UART_PARITY == 2 + regval |= (UART_LCR_PAREVEN|UART_LCR_PAREN); +#endif + putreg32(regval, LPC31_UART_LCR); + + /* Set the BAUD divisor */ + + up_configbaud(); + + /* Configure the FIFOs */ + + putreg32((UART_FCR_RXTRIGLEVEL_16|UART_FCR_TXFIFORST| + UART_FCR_RXFIFORST|UART_FCR_FIFOENABLE), + LPC31_UART_FCR); + + /* The NuttX serial driver waits for the first THRE interrrupt before + * sending serial data... However, it appears that the lpc313x hardware + * 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. + */ + + putreg32('\0', LPC31_UART_THR); +#endif +} + +/**************************************************************************** + * Name: up_lowputc + * + * Description: + * Provide priority, low-level access to support OS debug writes + * + ****************************************************************************/ + +void up_lowputc(char ch) +{ +#ifdef HAVE_CONSOLE + up_waittxready(); + putreg32((uint32_t)ch, LPC31_UART_THR); +#endif +} diff --git a/nuttx/arch/arm/src/lpc31xx/lpc31_mci.h b/nuttx/arch/arm/src/lpc31xx/lpc31_mci.h new file mode 100755 index 000000000..252061826 --- /dev/null +++ b/nuttx/arch/arm/src/lpc31xx/lpc31_mci.h @@ -0,0 +1,270 @@ +/************************************************************************************************ + * arch/arm/src/lpc31xx/lpc31_mci.h + * + * Copyright (C) 2009 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * 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_LPC31XX_LPC31_MCI_H +#define __ARCH_ARM_SRC_LPC31XX_LPC31_MCI_H + +/************************************************************************************************ + * Included Files + ************************************************************************************************/ + +#include +#include "lpc31_memorymap.h" + +/************************************************************************************************ + * Pre-processor Definitions + ************************************************************************************************/ + +/* MCI register base address offset into the MCI domain *****************************************/ + +#define LPC31_MCI_VBASE (LPC31_MCI_VSECTION) +#define LPC31_MCI_PBASE (LPC31_MCI_PSECTION) + +/* MCI register offsets (with respect to the MCI base) ******************************************/ + +#define LPC31_MCI_CTRL_OFFSET 0x000 /* Control register */ +#define LPC31_MCI_PWREN_OFFSET 0x004 /* Reserved */ +#define LPC31_MCI_CLKDIV_OFFSET 0x008 /* Clock-divider register */ +#define LPC31_MCI_CLKSRC_OFFSET 0x00c /* Clock-source register */ +#define LPC31_MCI_CLKENA_OFFSET 0x010 /* Clock-enable register */ +#define LPC31_MCI_TMOUT_OFFSET 0x014 /* Time-out register */ +#define LPC31_MCI_CTYPE_OFFSET 0x018 /* Card-type register */ +#define LPC31_MCI_BLKSIZ_OFFSET 0x01c /* Block-size register */ +#define LPC31_MCI_BYTCNT_OFFSET 0x020 /* Byte-count register */ +#define LPC31_MCI_INTMASK_OFFSET 0x024 /* Interrupt-mask register */ +#define LPC31_MCI_CMDARG_OFFSET 0x028 /* Command-argument register */ +#define LPC31_MCI_CMD_OFFSET 0x02c /* Command register */ +#define LPC31_MCI_RESP0_OFFSET 0x030 /* Response-0 register */ +#define LPC31_MCI_RESP1_OFFSET 0x034 /* Response-1register */ +#define LPC31_MCI_RESP2_OFFSET 0x038 /* Response-2 register */ +#define LPC31_MCI_RESP3_OFFSET 0x03c /* Response-3 register */ +#define LPC31_MCI_MINTSTS_OFFSET 0x040 /* Masked interrupt-status register */ +#define LPC31_MCI_RINTSTS_OFFSET 0x044 /* Raw interrupt-status register */ +#define LPC31_MCI_STATUS_OFFSET 0x048 /* Status register */ +#define LPC31_MCI_FIFOTH_OFFSET 0x04c /* FIFO threshold register */ +#define LPC31_MCI_CDETECT_OFFSET 0x050 /* Card-detect register value */ +#define LPC31_MCI_WRTPRT_OFFSET 0x054 /* Write-protect register */ + /* 0x58: Reserved */ +#define LPC31_MCI_TCBCNT_OFFSET 0x05c /* Transferred CIU card byte count */ +#define LPC31_MCI_TBBCNT_OFFSET 0x060 /* Transferred cpu/DMA to/from BIU-FIFO byte count */ + /* 0x064-0x0ff: Reserved */ +#define LPC31_MCI_DATA_OFFSET 0x100 /* Data FIFO read/write (>=) */ + +/* MCI register (virtual) addresses *************************************************************/ + +#define LPC31_MCI_CTRL (LPC31_MCI_VBASE+LPC31_MCI_CTRL_OFFSET) +#define LPC31_MCI_PWREN (LPC31_MCI_VBASE+LPC31_MCI_PWREN_OFFSET) +#define LPC31_MCI_CLKDIV (LPC31_MCI_VBASE+LPC31_MCI_CLKDIV_OFFSET) +#define LPC31_MCI_CLKSRC (LPC31_MCI_VBASE+LPC31_MCI_CLKSRC_OFFSET) +#define LPC31_MCI_CLKENA (LPC31_MCI_VBASE+LPC31_MCI_CLKENA_OFFSET) +#define LPC31_MCI_TMOUT (LPC31_MCI_VBASE+LPC31_MCI_TMOUT_OFFSET) +#define LPC31_MCI_CTYPE (LPC31_MCI_VBASE+LPC31_MCI_CTYPE_OFFSET) +#define LPC31_MCI_BLKSIZ (LPC31_MCI_VBASE+LPC31_MCI_BLKSIZ_OFFSET) +#define LPC31_MCI_BYTCNT (LPC31_MCI_VBASE+LPC31_MCI_BYTCNT_OFFSET) +#define LPC31_MCI_INTMASK (LPC31_MCI_VBASE+LPC31_MCI_INTMASK_OFFSET) +#define LPC31_MCI_CMDARG (LPC31_MCI_VBASE+LPC31_MCI_CMDARG_OFFSET) +#define LPC31_MCI_CMD (LPC31_MCI_VBASE+LPC31_MCI_CMD_OFFSET) +#define LPC31_MCI_RESP0 (LPC31_MCI_VBASE+LPC31_MCI_RESP0_OFFSET) +#define LPC31_MCI_RESP1 (LPC31_MCI_VBASE+LPC31_MCI_RESP1_OFFSET) +#define LPC31_MCI_RESP2 (LPC31_MCI_VBASE+LPC31_MCI_RESP2_OFFSET) +#define LPC31_MCI_RESP3 (LPC31_MCI_VBASE+LPC31_MCI_RESP3_OFFSET) +#define LPC31_MCI_MINTSTS (LPC31_MCI_VBASE+LPC31_MCI_MINTSTS_OFFSET) +#define LPC31_MCI_RINTSTS (LPC31_MCI_VBASE+LPC31_MCI_RINTSTS_OFFSET) +#define LPC31_MCI_STATUS (LPC31_MCI_VBASE+LPC31_MCI_STATUS_OFFSET) +#define LPC31_MCI_FIFOTH (LPC31_MCI_VBASE+LPC31_MCI_FIFOTH_OFFSET) +#define LPC31_MCI_CDETECT (LPC31_MCI_VBASE+LPC31_MCI_CDETECT_OFFSET) +#define LPC31_MCI_WRTPRT (LPC31_MCI_VBASE+LPC31_MCI_WRTPRT_OFFSET) +#define LPC31_MCI_TCBCNT (LPC31_MCI_VBASE+LPC31_MCI_TCBCNT_OFFSET) +#define LPC31_MCI_TBBCNT (LPC31_MCI_VBASE+LPC31_MCI_TBBCNT_OFFSET) +#define LPC31_MCI_DATA (LPC31_MCI_VBASE+LPC31_MCI_DATA_OFFSET) + +/* MCI register bit definitions *****************************************************************/ + +/* Control register CTRL, address 0x18000000 */ + +#define MCI_CTRL_CEATAINT (1 << 11) /* Bit 11: CE-ATA device interrupts enabled */ +#define MCI_CTRL_AUTOSTOP (1 << 10) /* Bit 10: Send STOP after CCSD to CE-ATA device */ +#define MCI_CTRL_SENDCCSD (1 << 9) /* Bit 9: Send CCSD to CE-ATA device */ +#define MCI_CTRL_ABORTREAD (1 << 8) /* Bit 8: Reset data state-machine (suspend sequence) */ +#define MCI_CTRL_SENDIRQRESP (1 << 7) /* Bit 7: Send auto IRQ response */ +#define MCI_CTRL_READWAIT (1 << 6) /* Bit 6: Assert read wait */ +#define MCI_CTRL_DMAENABLE (1 << 5) /* Bit 5: Enable DMA transfer mode */ +#define MCI_CTRL_INTENABLE (1 << 4) /* Bit 4: Enable interrupts */ +#define MCI_CTRL_DMARESET (1 << 2) /* Bit 2: Reset internal DMA interface control logic */ +#define MCI_CTRL_FIFORESET (1 << 1) /* Bit 1: Reset to data FIFO To reset FIFO pointers */ +#define MCI_CTRL_CNTLRRESET (1 << 0) /* Bit 0: Reset Module controller */ + +/* Clock divider register CLKDIV, address 0x18000008 */ + +#define MCI_CLKDIV_SHIFT (0) /* Bits 0-7: Clock divider */ +#define MCI_CLKDIV_MASK (255 << MCI_CLKDIV_SHIFT) + +/* Clock source register CLKSRC, address 0x1800000c */ + +#define MCI_CLKSRC_SHIFT (0) /* Bits 0-1: Must be zero */ +#define MCI_CLKSRC_MASK (3 << MCI_CLKSRC_SHIFT) + +/* Clock enable register CLKENA, address 0x18000010 */ + +#define MCI_CLKENA_LOWPOWER (1 << 16) /* Bit 16: Low-power mode */ +#define MCI_CLKENA_EMABLE (1 << 0) /* Bit 0: Clock enable */ + +/*Timeout register TMOUT, address 0x18000014 */ + +#define MCI_TMOUT_DATA_SHIFT (8) /* Bits 8-31: Data Read Timeout value */ +#define MCI_TMOUT_DATA_MASK (0x00ffffff << MCI_TMOUT_DATA_SHIFT) +#define MCI_TMOUT_RESPONSE_SHIFT (0) /* Bits 0-7: Response timeout value */ +#define MCI_TMOUT_RESPONSE_MASK (255 << MCI_TMOUT_RESPONSE_SHIFT) + +/* Card type register CTYPE, address 0x18000018 */ + +#define MCI_CTYPE_WIDTH8 (1 << 16) /* Bit 16: 8-bit mode */ +#define MCI_CTYPE_WIDTH4 (1 << 0) /* Bit 0: 4-bit mode */ + +/* Blocksize register BLKSIZ, address 0x1800001c */ + +#define MCI_BLKSIZ_SHIFT (0) /* Bits 0-15: Block size */ +#define MCI_BLKSIZ_MASK (0xffff << MCI_BLKSIZ_SHIFT) + +/* Interrupt mask register INTMASK, address 0x18000024 + * Masked interrupt status register MINTSTS, address 0x18000040 + * Raw interrupt status register RINTSTS, address 0x18000044 + */ + +#define MCI_INT_SDIO (1 << 16) /* Bit 16: Mask SDIO interrupt */ +#define MCI_INT_EBE (1 << 15) /* Bit 15: End-bit error (read)/Write no CRC */ +#define MCI_INT_ACD (1 << 14) /* Bit 14: Auto command done */ +#define MCI_INT_SBE (1 << 13) /* Bit 13: Start-bit error */ +#define MCI_INT_HLE (1 << 12) /* Bit 12: Hardware locked write error */ +#define MCI_INT_FRUN (1 << 11) /* Bit 11: FIFO underrun/overrun error */ +#define MCI_INT_HTO (1 << 10) /* Bit 10: Data starvation-by-cpu timeout */ +#define MCI_INT_DRTO (1 << 9) /* Bit 9: Data read timeout */ +#define MCI_INT_RTO (1 << 8) /* Bit 8: Response timeout */ +#define MCI_INT_DCRC (1 << 7) /* Bit 7: Data CRC error */ +#define MCI_INT_RCRC (1 << 6) /* Bit 6: Response CRC error */ +#define MCI_INT_RXDR (1 << 5) /* Bit 5: Receive FIFO data request */ +#define MCI_INT_TXDR (1 << 4) /* Bit 4: Transmit FIFO data request */ +#define MCI_INT_DTO (1 << 3) /* Bit 3: Data transfer over */ +#define MCI_INT_CD (1 << 2) /* Bit 2: Command done */ +#define MCI_INT_RE (1 << 1) /* Bit 1: Response error */ +#define MCI_INT_CD (1 << 0) /* Bit 0: Card detect */ +#define MCI_INT_ALL (0x1ffff) + +/* Command register CMD, address 0x1800002c */ + +#define MCI_CMD_STARTCMD (1 << 31) /* Bit 31: Start command */ +#define MCI_CMD_CCSEXPTD (1 << 23) /* Bit 23: Expect command completion from CE-ATA device */ +#define MCI_CMD_READCEATA (1 << 22) /* Bit 22: Performing read access on CE-ATA device */ +#define MCI_CMD_UPDCLOCK (1 << 21) /* Bit 21: Update clock register value (no command) */ +#define MCI_CMD_SENDINIT (1 << 15) /* Bit 15: Send initialization sequence before command */ +#define MCI_CMD_STOPABORT (1 << 14) /* Bit 14: Stop current data transfer */ +#define MCI_CMD_WAITPREV (1 << 13) /* Bit 13: Wait previous transfer complete before sending */ +#define MCI_CMD_AUTOSTOP (1 << 12) /* Bit 12: Send stop command at end of data transfer */ +#define MCI_CMD_XFRMODE (1 << 11) /* Bit 11: Stream data transfer command */ +#define MCI_CMD_WRITE (1 << 10) /* Bit 10: Write to card */ +#define MCI_CMD_DATAXFREXPTD (1 << 9) /* Bit 9: Data transfer expected (read/write) */ +#define MCI_CMD_RESPCRC (1 << 8) /* Bit 8: Check response CRC */ +#define MCI_CMD_LONGRESP (1 << 7) /* Bit 7: Long response expected from card */ +#define MCI_CMD_RESPONSE (1 << 6) /* Bit 6: Response expected from card */ +#define MCI_CMD_CMDINDEX_SHIFT (0) /* Bits 0-5: 5:0 Command index */ +#define MCI_CMD_CMDINDEX_MASK (63 << MCI_CMD_CMDINDEX_SHIFT) + +/* Status register STATUS, address 0x18000048 */ + +#define MCI_STATUS_DMAREQ (1 << 31) /* Bit 31: DMA request signal state */ +#define MCI_STATUS_DMAACK (1 << 30) /* Bit 30: DMA acknowledge signal state */ +#define MCI_STATUS_FIFOCOUNT_SHIFT (17) /* Bits 17-29: FIFO count */ +#define MCI_STATUS_FIFOCOUNT_MASK (0x1fff << MCI_STATUS_FIFOCOUNT_SHIFT) +#define MCI_STATUS_RESPINDEX_SHIFT (11) /* Bits 11-16: Index of previous response */ +#define MCI_STATUS_RESPINDEX_MASK (63 << MCI_STATUS_RESPINDEX_SHIFT) +#define MCI_STATUS_MCBUSY (1 << 10) /* Bit 10: Data transmit/receive state machine busy */ +#define MCI_STATUS_DATABUSY (1 << 9) /* Bit 9: Card data busy */ +#define MCI_STATUS_DAT3 (1 << 8) /* Bit 8: DAT3=1: Card present */ +#define MCI_STATUS_FSMSTATE_SHIFT (4) /* Bits 4-7: 7:4 Command FSM states */ +#define MCI_STATUS_FSMSTATE_MASK (15 << MCI_STATUS_FSMSTATE_SHIFT) +# define MCI_STATUS_FSMSTATE_IDLE (0 << MCI_STATUS_FSMSTATE_SHIFT) /* Idle */ +# define MCI_STATUS_FSMSTATE_INIT (1 << MCI_STATUS_FSMSTATE_SHIFT) /* Send init sequence */ +# define MCI_STATUS_FSMSTATE_TXSTART (2 << MCI_STATUS_FSMSTATE_SHIFT) /* Tx cmd start bit */ +# define MCI_STATUS_FSMSTATE_TXTXBIT (3 << MCI_STATUS_FSMSTATE_SHIFT) /* Tx cmd tx bit */ +# define MCI_STATUS_FSMSTATE_TXCMDARG (4 << MCI_STATUS_FSMSTATE_SHIFT) /* Tx cmd index + arg */ +# define MCI_STATUS_FSMSTATE_TXCMDCRC (5 << MCI_STATUS_FSMSTATE_SHIFT) /* Tx cmd crc7 */ +# define MCI_STATUS_FSMSTATE_TXEND (6 << MCI_STATUS_FSMSTATE_SHIFT) /* Tx cmd end bit */ +# define MCI_STATUS_FSMSTATE_RXSTART (7 << MCI_STATUS_FSMSTATE_SHIFT) /* Rx resp start bit */ +# define MCI_STATUS_FSMSTATE_RXIRQ (8 << MCI_STATUS_FSMSTATE_SHIFT) /* Rx resp IRQ response */ +# define MCI_STATUS_FSMSTATE_RXTXBIT (9 << MCI_STATUS_FSMSTATE_SHIFT) /* Rx resp tx bit */ +# define MCI_STATUS_FSMSTATE_RXCMD (10 << MCI_STATUS_FSMSTATE_SHIFT) /* Rx resp cmd idx */ +# define MCI_STATUS_FSMSTATE_RXRESP (11 << MCI_STATUS_FSMSTATE_SHIFT) /* Rx resp data */ +# define MCI_STATUS_FSMSTATE_RXRESPCRC (12 << MCI_STATUS_FSMSTATE_SHIFT) /* Rx resp crc7 */ +# define MCI_STATUS_FSMSTATE_RXEND (13 << MCI_STATUS_FSMSTATE_SHIFT) /* Rx resp end bit */ +# define MCI_STATUS_FSMSTATE_WAITNCC (14 << MCI_STATUS_FSMSTATE_SHIFT) /* Cmd path wait NCC */ +# define MCI_STATUS_FSMSTATE_WAITTURN (15 << MCI_STATUS_FSMSTATE_SHIFT) /* Wait; CMD-to-response turnaround */ +#define MCI_STATUS_FIFOFULL (1 << 3) /* Bit 3: FIFO is full */ +#define MCI_STATUS_FIFOEMPTY (1 << 2) /* Bit 2: FIFO is empty */ +#define MCI_STATUS_TXWMARK (1 << 1) /* Bit 1: FIFO reached Transmit watermark level */ +#define MCI_STATUS_RXWMARK (1 << 0) /* Bit 0: FIFO reached Receive watermark level */ + +/* FIFO threshold register FIFOTH, address 0x1800004c */ + +#define MCI_FIFOTH_DMABURST_SHIFT (28) /* Bits 28-30: Burst size for multiple transaction */ +#define MCI_FIFOTH_DMABURST_MASK (7 << MCI_FIFOTH_DMABURST_SHIFT) + define MCI_FIFOTH_DMABURST_1XFR (0 << MCI_FIFOTH_DMABURST_SHIFT) /* 1 transfer */ +# define MCI_FIFOTH_DMABURST_4XFRS (1 << MCI_FIFOTH_DMABURST_SHIFT) /* 4 transfers */ +# define MCI_FIFOTH_DMABURST_8XFRS (2 << MCI_FIFOTH_DMABURST_SHIFT) /* 8 transfers */ +#define MCI_FIFOTH_RXWMARK_SHIFT (16) /* Bits 16-27: FIFO threshold level when receiving */ +#define MCI_FIFOTH_RXWMARK_MASK (0xfff << MCI_FIFOTH_RXWMARK_SHIFT) +#define MCI_FIFOTH_TXWMARK_SHIFT (0) /* Bits 0-11: FIFO threshold level when transmitting */ +#define MCI_FIFOTH_TXWMARK_MASK (0xfff << MCI_FIFOTH_TXWMARK_SHIFT) + +/* Card detect register CDETECT, address 0x18000050 */ + +#define MCI_CDETECT_NOTPRESENT (1 << 0) + +/* Write protect register WRTPRT, address 0x18000054 */ + +#define MCI_WRTPRT_PROTECTED (1 << 0) + +/************************************************************************************************ + * Public Types + ************************************************************************************************/ + +/************************************************************************************************ + * Public Data + ************************************************************************************************/ + +/************************************************************************************************ + * Public Functions + ************************************************************************************************/ + +#endif /* __ARCH_ARM_SRC_LPC31XX_LPC31_MCI_H */ diff --git a/nuttx/arch/arm/src/lpc31xx/lpc31_memorymap.h b/nuttx/arch/arm/src/lpc31xx/lpc31_memorymap.h new file mode 100755 index 000000000..db140cc98 --- /dev/null +++ b/nuttx/arch/arm/src/lpc31xx/lpc31_memorymap.h @@ -0,0 +1,414 @@ +/************************************************************************************ + * arch/arm/src/lpc31xx/lpc31_memorymap.h + * + * Copyright (C) 2009-2010 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * 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_LPC31XX_LPC31_MEMORYMAP_H +#define __ARCH_ARM_SRC_LPC31XX_LPC31_MEMORYMAP_H + +/************************************************************************************ + * Included Files + ************************************************************************************/ + +#include + +/************************************************************************************ + * Pre-processor Definitions + ************************************************************************************/ + +/* LPC31XX Physical (unmapped) Memory Map */ + +#define LPC31_FIRST_PSECTION 0x00000000 /* Beginning of the physical address space */ +#define LPC31_SHADOWSPACE_PSECTION 0x00000000 /* 0x00000000-0x00000fff: Shadow Area 4Kb */ + /* 0x00001000-0xff027fff: Reserved */ +#define LPC31_INTSRAM_PSECTION 0x11028000 /* Internal SRAM 0+1 192Kb */ +# define LPC31_INTSRAM0_PADDR 0x11028000 /* 0x11028000-0x1103ffff: Internal SRAM 0 96Kb */ +# define LPC31_INTSRAM1_PADDR 0x11040000 /* 0x11040000-0x11057fff: Internal SRAM 1 96Kb */ + /* 0x11058000-11ffffffff: Reserved */ +#define LPC31_INTSROM0_PSECTION 0x12000000 /* 0x12000000-0x1201ffff: Internal SROM 0 128Kb */ + /* 0x12020000-0x12ffffff: Reserved */ +#define LPC31_APB01_PSECTION 0x13000000 /* 0x13000000-0x1300bfff: APB0 32Kb APB1 16Kb */ +# define LPC31_APB0_PADDR 0x13000000 /* 0x13000000-0x13007fff: APB0 32Kb */ +# define LPC31_APB1_PADDR 0x13008000 /* 0x13008000-0x1300bfff: APB1 16Kb */ + /* 0x1300c000-0x14ffffff: Reserved */ +#define LPC31_APB2_PSECTION 0x15000000 /* 0x15000000-0x15003fff: APB2 16Kb */ +#define LPC31_APB3_PSECTION 0x16000000 /* 0x16000000-0x160003ff: APB3 1Kb */ +#define LPC31_APB4MPMC_PSECTION 0x17000000 /* 8Kb */ +# define LPC31_APB4_PADDR 0x17000000 /* 0x17000000-0x17000fff: APB4 4Kb */ +# define LPC31_MPMC_PADDR 0x17008000 /* 0x17008000-0x17008fff: MPMC cfg 4Kb */ + /* 0x17009000-0x17ffffff: Reserved */ +#define LPC31_MCI_PSECTION 0x18000000 /* 0x18000000 0x180003ff: MCI/SD/SDIO 1Kb */ + /* 0x18000900-0x18ffffff: Reserved */ +#define LPC31_USBOTG_PSECTION 0x19000000 /* 0x19000000-0x19000fff: USB OTG 4Kb */ + /* 0x19001000-0x1fffffff: Reserved */ +#define LPC31_EXTSRAM_PSECTION 0x20000000 /* 64-128Kb */ +# define LPC31_EXTSRAM0_PADDR 0x20000000 /* 0x20000000-0x2001ffff: External SRAM 0 64-128Kb */ +# define LPC31_EXTSRAM1_PADDR 0x20020000 /* 0x20020000-0x2003ffff: External SRAM 1 64-128Kb */ +#define LPC31_EXTSDRAM0_PSECTION 0x30000000 /* 0x30000000-0x37ffffff: External SDRAM 0 128Mb */ + /* 0x40000000-0x5fffffff: Reserved */ +#define LPC31_INTC_PSECTION 0x60000000 /* 0x60000000-0x60000fff: Interrupt controller 4Kb */ + /* 0x60001000-0x6fffffff: Reserved */ +#define LPC31_NAND_PSECTION 0x70000000 /* 0x70000000-0x700007ff: NANDFLASH Ctrl 2Kb */ + /* 0x70000800-0xffffffff: Reserved */ +#ifdef CONFIG_LPC31_EXTNAND /* End of the physical address space */ +# define LPC31_LAST_PSECTION (LPC31_NAND_PSECTION + (1 << 20)) +#else +# define LPC31_LAST_PSECTION (LPC31_INTC_PSECTION + (1 << 20)) +#endif + +/* APB0-4 Domain Offsets */ + +#define LPC31_APB0_EVNTRTR_OFFSET 0x00000000 /* Event Router */ +#define LPC31_APB0_ADC_OFFSET 0x00002000 /* ADC 10-bit */ +#define LPC31_APB0_WDT_OFFSET 0x00002400 /* WDT */ +#define LPC31_APB0_SYSCREG_OFFSET 0x00002800 /* SYSCREG block */ +#define LPC31_APB0_IOCONFIG_OFFSET 0x00003000 /* IOCONFIG */ +#define LPC31_APB0_GCU_OFFSET 0x00004000 /* GCU */ + /* 0x00005000 Reserved */ +#define LPC31_APB0_RNG_OFFSET 0x00006000 /* RNG */ + +#define LPC31_APB1_TIMER0_OFFSET 0x00000000 /* TIMER0 */ +#define LPC31_APB1_TIMER1_OFFSET 0x00000400 /* TIMER1 */ +#define LPC31_APB1_TIMER2_OFFSET 0x00000800 /* TIMER2 */ +#define LPC31_APB1_TIMER3_OFFSET 0x00000c00 /* TIMER3 */ +#define LPC31_APB1_PWM_OFFSET 0x00001000 /* PWM */ +#define LPC31_APB1_I2C0_OFFSET 0x00002000 /* I2C0 */ +#define LPC31_APB1_I2C1_OFFSET 0x00002400 /* I2C1 */ + +#define LPC31_APB2_PCM_OFFSET 0x00000000 /* PCM */ +#define LPC31_APB2_LCD_OFFSET 0x00000400 /* LCD */ + /* 0x00000800 Reserved */ +#define LPC31_APB2_UART_OFFSET 0x00001000 /* UART */ +#define LPC31_APB2_SPI_OFFSET 0x00002000 /* SPI */ + /* 0x00003000 Reserved */ + +#define LPC31_APB3_I2SCONFIG_OFFSET 0x00000000 /* I2S System Configuration */ +#define LPC31_APB3_I2STX0_OFFSET 0x00000080 /* I2S TX0 */ +#define LPC31_APB3_I2STX1_OFFSET 0x00000100 /* I2S TX1 */ +#define LPC31_APB3_I2SRX0_OFFSET 0x00000180 /* I2S RX0 */ +#define LPC31_APB3_I2SRX1_OFFSET 0x00000200 /* I2S RX1 */ + /* 0x00000280 Reserved */ + +#define LPC31_APB4_DMA_OFFSET 0x00000000 /* DMA */ +#define LPC31_APB4_NAND_OFFSET 0x00000800 /* NAND FLASH Controller */ + /* 0x00001000 Reserved */ + +/* Sizes of memory regions in bytes */ + +#define LPC31_SHADOWSPACE_SIZE (4*1024) +#define LPC31_INTSRAM0_SIZE (96*1024) +#define LPC31_INTSRAM1_SIZE (96*1024) +#define LPC31_INTSROM0_SIZE (128*1024) +#define LPC31_APB0_SIZE (32*1024) +#define LPC31_APB1_SIZE (16*1024) +#define LPC31_APB2_SIZE (16*1024) +#define LPC31_APB3_SIZE (1*1024) +#define LPC31_APB4_SIZE (4*1024) +#define LPC31_MPMC_SIZE (4*1024) +#define LPC31_APB4MPMC_SIZE (LPC31_APB4_SIZE+LPC31_MPMC_SIZE) +#define LPC31_MCI_SIZE (1*1024) +#define LPC31_USBOTG_SIZE (4*1024) +#define LPC31_INTC_SIZE (4*1024) +#define LPC31_NAND_SIZE (2*1024) + +#if defined(CONFIG_ARCH_CHIP_LPC3131) +# define LPC31_ISRAM_SIZE (LPC31_INTSRAM0_SIZE+LPC31_INTSRAM1_SIZE) +#elif defined(CONFIG_ARCH_CHIP_LPC3130) +# define LPC31_ISRAM_SIZE LPC31_INTSRAM0_SIZE +#else +# error "Unsupported LPC31XX architecture" +#endif + +/* Convert size in bytes to number of sections (in Mb). */ + +#define _NSECTIONS(b) (((b)+0x000fffff) >> 20) + +/* Sizes of sections/regions. The boot logic in lpc31_boot.c, will select + * 1Mb level 1 MMU mappings to span the entire physical address space. + * The definitiions below specifiy the number of 1Mb entries that are + * required to span a particular address region. + */ + +#define LPC31_SHADOWSPACE_NSECTIONS 1 /* 4Kb - <1 section */ +#define LPC31_INTSRAM_NSECTIONS 1 /* 96 or 192Kb - <1 section */ +#define LPC31_APB01_NSECTIONS 1 /* 32Kb - <1 section */ +#define LPC31_INTSROM0_NSECTIONS 1 /* 128Kb - <1 section */ +#define LPC31_APB1_NSECTIONS 1 /* 16Kb - <1 section */ +#define LPC31_APB2_NSECTIONS 1 /* 16Kb - <1 section */ +#define LPC31_APB3_NSECTIONS 1 /* 1Kb - <1 section */ +#define LPC31_APB4MPMC_NSECTIONS 1 /* 8Kb - <1 section */ +#define LPC31_MCI_NSECTIONS 1 /* 1Kb - <1 section */ +#define LPC31_USBOTG_NSECTIONS 1 /* 4Kb - <1 section */ +#define LPC31_EXTSRAM_NSECTIONS 1 /* 64-128Kb - <1 section */ +#define LPC31_INTC_NSECTIONS 1 /* 4Kb - <1 section */ +#define LPC31_NAND_NSECTIONS 1 /* 2Kb - <1 section */ + +/* External SDRAM is a special case -- the number of sections depends upon + * the size of the SDRAM installed. + */ + +#if defined(CONFIG_LPC31_EXTSDRAM) && CONFIG_LPC31_EXTSDRAMSIZE > 0 +# define LPC31_EXTSDRAM0_NSECTIONS _NSECTIONS(CONFIG_LPC31_EXTSDRAMSIZE) +#endif + +/* Section MMU Flags */ + +#define LPC31_SHADOWSPACE_MMUFLAGS MMU_ROMFLAGS +#define LPC31_INTSRAM_MMUFLAGS MMU_MEMFLAGS +#define LPC31_INTSROM_MMUFLAGS MMU_MEMFLAGS +#define LPC31_APB01_MMUFLAGS MMU_IOFLAGS +#define LPC31_APB2_MMUFLAGS MMU_IOFLAGS +#define LPC31_APB3_MMUFLAGS MMU_IOFLAGS +#define LPC31_APB4MPMC_MMUFLAGS MMU_IOFLAGS +#define LPC31_MCI_MMUFLAGS MMU_IOFLAGS +#define LPC31_USBOTG_MMUFLAGS MMU_IOFLAGS +#define LPC31_EXTSRAM_MMUFLAGS MMU_MEMFLAGS +#define LPC31_EXTSDRAM_MMUFLAGS MMU_MEMFLAGS +#define LPC31_INTC_MMUFLAGS MMU_IOFLAGS +#define LPC31_NAND_MMUFLAGS MMU_IOFLAGS + +/* board_memorymap.h contains special mappings that are needed when a ROM + * memory map is used. It is included in this odd location becaue it depends + * on some the virtual address definitions provided above. + */ + +#include + +/* LPC31XX Virtual (mapped) Memory Map. These are the mappings that will + * be created if the page table lies in RAM. If the platform has another, + * read-only, pre-initialized page table (perhaps in ROM), then the board.h + * file must provide these definitions. + */ + +#ifndef CONFIG_ARCH_ROMPGTABLE +# define LPC31_FIRST_VSECTION 0x00000000 /* Beginning of the virtual address space */ +# define LPC31_SHADOWSPACE_VSECTION 0x00000000 /* 0x00000000-0x00000fff: Shadow Area 4Kb */ +# define LPC31_INTSRAM_VSECTION 0x11028000 /* Internal SRAM 96Kb-192Kb */ +# define LPC31_INTSRAM0_VADDR 0x11028000 /* 0x11028000-0x1103ffff: Internal SRAM 0 96Kb */ +# define LPC31_INTSRAM1_VADDR 0x11040000 /* 0x11040000-0x11057fff: Internal SRAM 1 96Kb */ +# define LPC31_INTSROM0_VSECTION 0x12000000 /* 0x12000000-0x1201ffff: Internal SROM 0 128Kb */ +# define LPC31_APB01_VSECTION 0x13000000 /* 0x13000000-0x1300bfff: APB0 32Kb APB0 32Kb */ +# define LPC31_APB0_VADDR 0x13000000 /* 0x13000000-0x13007fff: APB0 32Kb */ +# define LPC31_APB1_VADDR 0x13008000 /* 0x13008000-0x1300bfff: APB1 16Kb */ +# define LPC31_APB2_VSECTION 0x15000000 /* 0x15000000-0x15003fff: APB2 16Kb */ +# define LPC31_APB3_VSECTION 0x16000000 /* 0x16000000-0x160003ff: APB3 1Kb */ +# define LPC31_APB4MPMC_VSECTION 0x17000000 /* 8Kb */ +# define LPC31_APB4_VADDR 0x17000000 /* 0x17000000-0x17000fff: APB4 4Kb */ +# define LPC31_MPMC_VADDR 0x17008000 /* 0x17008000-0x17008fff: MPMC cfg 4Kb */ +# define LPC31_MCI_VSECTION 0x18000000 /* 0x18000000 0x180003ff: MCI/SD/SDIO 1Kb */ +# define LPC31_USBOTG_VSECTION 0x19000000 /* 0x19000000-0x19000fff: USB OTG 4Kb */ +# define LPC31_EXTSRAM_VSECTION 0x20020000 /* 64-128Kb */ +# define LPC31_EXTSRAM0_VADDR 0x20000000 /* 0x20000000-0x2001ffff: External SRAM 0 64-128Kb */ +# define LPC31_EXTSRAM1_VADDR 0x20020000 /* 0x20020000-0x2003ffff: External SRAM 1 64-128Kb */ +# define LPC31_EXTSDRAM0_VSECTION 0x30000000 /* 0x30000000-0x37ffffff: External SDRAM 0 128Mb */ +# define LPC31_INTC_VSECTION 0x60000000 /* 0x60000000-0x60000fff: Interrupt controller 4Kb */ +# define LPC31_NAND_VSECTION 0x70000000 /* 0x70000000-0x700007ff: NANDFLASH Ctrl 2Kb */ +# +# ifdef CONFIG_LPC31_EXTNAND /* End of the virtual address space */ +# define LPC31_LAST_VSECTION (LPC31_NAND_VSECTION + (1 << 20)) +# else +# define LPC31_LAST_VSECTION (LPC31_INTC_VSECTION + (1 << 20)) +# endif +#endif + +/* The boot logic will create a temporarily mapping based on where NuttX is + * executing in memory. In this case, NuttX could be running from NOR FLASH, + * SDRAM, external SRAM, or ISRAM. + */ + +#if defined(CONFIG_BOOT_RUNFROMFLASH) +# define NUTTX_START_VADDR LPC31_MPMC_VADDR +#elif defined(CONFIG_BOOT_RUNFROMSDRAM) +# define NUTTX_START_VADDR LPC31_EXTSDRAM0_VSECTION +#elif defined(CONFIG_BOOT_RUNFROMEXTSRAM) +# define NUTTX_START_VADDR LPC31_EXTSRAM0_VADDR +#else /* CONFIG_BOOT_RUNFROMISRAM, CONFIG_PAGING */ +# define NUTTX_START_VADDR LPC31_INTSRAM0_VADDR +#endif + +/* Determine the address of the MMU page table. We will try to place that page + * table at the beginng of ISRAM0 if the vectors are at the high address, 0xffff:0000 + * or at the end of ISRAM1 (or ISRAM0 on a LPC3130) if the vectors are at 0x0000:0000 + * + * Or... the user may specify the address of the page table explicitly be defining + * CONFIG_PGTABLE_VADDR and CONFIG_PGTABLE_PADDR in the configuration or board.h file. + */ + +#undef PGTABLE_IN_HIGHSRAM +#undef PGTABLE_IN_LOWSRAM + +#if !defined(PGTABLE_BASE_PADDR) || !defined(PGTABLE_BASE_VADDR) + + /* Sanity check.. if one is undefined, both should be undefined */ + +# if defined(PGTABLE_BASE_PADDR) || defined(PGTABLE_BASE_VADDR) +# error "Only one of PGTABLE_BASE_PADDR or PGTABLE_BASE_VADDR is defined" +# endif + + /* A sanity check, if the configuration says that the page table is read-only + * and pre-initialized (maybe ROM), then it should have also defined both of + * the page table base addresses. + */ + +# ifdef CONFIG_ARCH_ROMPGTABLE +# error "CONFIG_ARCH_ROMPGTABLE defined; PGTABLE_BASE_P/VADDR not defined" +# else + + /* If CONFIG_PAGING is selected, then parts of the 1-to-1 virtual memory + * map probably do not apply because paging logic will probably partition + * the SRAM section differently. In particular, if the page table is located + * at the end of SRAM, then the virtual page table address defined below + * will probably be in error. + * + * We work around this header file interdependency by (1) insisting that + * pg_macros.h be included AFTER this header file, then (2) allowing the + * pg_macros.h header file to redefine PGTABLE_BASE_VADDR. + */ + +# if defined(CONFIG_PAGING) && defined(__ARCH_ARM_SRC_ARM_PG_MACROS_H) +# error "pg_macros.h must be included AFTER this header file" +# endif + + + /* We must declare the page table in ISRAM0 or 1. We decide depending upon + * where the vector table was place. + */ + +# ifdef CONFIG_ARCH_LOWVECTORS /* Vectors located at 0x0000:0000 */ + + /* In this case, ISRAM0 will be shadowed at address 0x0000:0000. The page + * table must lie at the top 16Kb of ISRAM1 (or ISRAM0 if this is a LPC3130) + */ + +# if CONFIG_ARCH_CHIP_LPC3131 +# define PGTABLE_BASE_PADDR (LPC31_INTSRAM1_PADDR+LPC31_INTSRAM1_SIZE-PGTABLE_SIZE) +# define PGTABLE_BASE_VADDR (LPC31_INTSRAM1_VADDR+LPC31_INTSRAM1_SIZE-PGTABLE_SIZE) +# else +# define PGTABLE_BASE_PADDR (LPC31_INTSRAM0_PADDR+LPC31_INTSRAM0_SIZE-PGTABLE_SIZE) +# define PGTABLE_BASE_VADDR (LPC31_INTSRAM0_VADDR+LPC31_INTSRAM0_SIZE-PGTABLE_SIZE) +# endif +# define PGTABLE_IN_HIGHSRAM 1 + + /* If CONFIG_PAGING is defined, insist that pg_macros.h assign the virtual + * address of the page table. + */ + +# ifdef CONFIG_PAGING +# undef PGTABLE_BASE_VADDR +# endif +# else + + /* Otherwise, ISRAM1 (or ISRAM0 for the LPC3130) will be mapped so that + * the end of the SRAM region will provide memory for the vectors. The page + * table will then be places at the first 16Kb of ISRAM0 (which will be in + * the shadow memory region. + */ + +# define PGTABLE_BASE_PADDR LPC31_SHADOWSPACE_PSECTION +# define PGTABLE_BASE_VADDR LPC31_SHADOWSPACE_VSECTION +# define PGTABLE_IN_LOWSRAM 1 +# endif +# endif +#endif + +/* Page table start addresses: + * + * 16Kb of memory is reserved hold the page table for the virtual mappings. A + * portion of this table is not accessible in the virtual address space (for + * normal operation). We will reuse this memory for coarse page tables as follows: + * + * NOTE: If CONFIG_PAGING is defined, pg_macros.h will re-assign the virtual + * address of the page table. + */ + +#define PGTABLE_L2_COARSE_OFFSET ((((LPC31_LAST_PSECTION >> 20) + 255) & ~255) << 2) +#define PGTABLE_L2_COARSE_PBASE (PGTABLE_BASE_PADDR+PGTABLE_L2_COARSE_OFFSET) +#define PGTABLE_L2_COARSE_VBASE (PGTABLE_BASE_VADDR+PGTABLE_L2_COARSE_OFFSET) + +#define PGTABLE_L2_FINE_OFFSET ((((LPC31_LAST_PSECTION >> 20) + 1023) & ~1023) << 2) +#define PGTABLE_L2_FINE_PBASE (PGTABLE_BASE_PADDR+PGTABLE_L2_FINE_OFFSET) +#define PGTABLE_L2_FINE_VBASE (PGTABLE_BASE_VADDR+PGTABLE_L2_FINE_OFFSET) + +/* Page table end addresses: */ + +#define PGTABLE_L2_END_PADDR (PGTABLE_BASE_PADDR+PGTABLE_SIZE) +#define PGTABLE_L2_END_VADDR (PGTABLE_BASE_VADDR+PGTABLE_SIZE) + +/* Page table sizes */ + +#define PGTABLE_L2_COARSE_ALLOC (PGTABLE_L2_END_VADDR-PGTABLE_L2_COARSE_VBASE) +#define PGTABLE_COARSE_TABLE_SIZE (4*256) +#define PGTABLE_NCOARSE_TABLES (PGTABLE_L2_COARSE_ALLOC / PGTABLE_COARSE_TABLE_SIZE) + +#define PGTABLE_L2_FINE_ALLOC (PGTABLE_L2_END_VADDR-PGTABLE_L2_FINE_VBASE) +#define PGTABLE_FINE_TABLE_SIZE (4*1024) +#define PGTABLE_NFINE_TABLES (PGTABLE_L2_FINE_ALLOC / PGTABLE_FINE_TABLE_SIZE) + +/* Determine the base address of the vector table: + * + * LPC31_VECTOR_PADDR - Unmapped, physical address of vector table in SRAM + * LPC31_VECTOR_VSRAM - Virtual address of vector table in SRAM + * LPC31_VECTOR_VADDR - Virtual address of vector table (0x00000000 or 0xffff0000) + */ + +#define VECTOR_TABLE_SIZE 0x00010000 +#ifdef CONFIG_ARCH_LOWVECTORS /* Vectors located at 0x0000:0000 */ +# define LPC31_VECTOR_PADDR LPC31_INTSRAM0_PADDR +# define LPC31_VECTOR_VSRAM LPC31_INTSRAM0_VADDR +# define LPC31_VECTOR_VADDR 0x00000000 +# define LPC31_VECTOR_VCOARSE 0x00000000 +#else /* Vectors located at 0xffff:0000 -- this probably does not work */ +# if CONFIG_ARCH_CHIP_LPC3131 +# define LPC31_VECTOR_PADDR (LPC31_INTSRAM1_PADDR+LPC31_INTSRAM1_SIZE-VECTOR_TABLE_SIZE) +# define LPC31_VECTOR_VSRAM (LPC31_INTSRAM1_VADDR+LPC31_INTSRAM1_SIZE-VECTOR_TABLE_SIZE) +# else +# define LPC31_VECTOR_PADDR (LPC31_INTSRAM0_PADDR+LPC31_INTSRAM0_SIZE-VECTOR_TABLE_SIZE) +# define LPC31_VECTOR_VSRAM (LPC31_INTSRAM0_VADDR+LPC31_INTSRAM0_SIZE-VECTOR_TABLE_SIZE) +# endif +# define LPC31_VECTOR_VADDR 0xffff0000 +# define LPC31_VECTOR_VCOARSE 0xfff00000 +#endif + +/************************************************************************************ + * Public Types + ************************************************************************************/ + +/************************************************************************************ + * Public Data + ************************************************************************************/ + +/************************************************************************************ + * Public Functions + ************************************************************************************/ + +#endif /* __ARCH_ARM_SRC_LPC31XX_LPC31_MEMORYMAP_H */ diff --git a/nuttx/arch/arm/src/lpc31xx/lpc31_mpmc.h b/nuttx/arch/arm/src/lpc31xx/lpc31_mpmc.h new file mode 100755 index 000000000..5e927159d --- /dev/null +++ b/nuttx/arch/arm/src/lpc31xx/lpc31_mpmc.h @@ -0,0 +1,340 @@ +/************************************************************************************************ + * arch/arm/src/lpc31xx/lpc31_mpmc.h + * + * Copyright (C) 2009 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * 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_LPC31XX_LPC31_MPMC_H +#define __ARCH_ARM_SRC_LPC31XX_LPC31_MPMC_H + +/************************************************************************************************ + * Included Files + ************************************************************************************************/ + +#include +#include "lpc31_memorymap.h" + +/************************************************************************************************ + * Pre-processor Definitions + ************************************************************************************************/ + +/* MPMC register base address offset into the MPMC domain ***************************************/ + +#define LPC31_MPMC_VBASE (LPC31_MPMC_VADDR) +#define LPC31_MPMC_PBASE (LPC31_MPMC_PADDR) + +/* MPMC register offsets (with respect to the base of the MPMC domain) **************************/ + +#define LPC31_MPMC_CONTROL_OFFSET 0x000 /* Control Register */ +#define LPC31_MPMC_STATUS_OFFSET 0x004 /* Status Register */ +#define LPC31_MPMC_CONFIG_OFFSET 0x008 /* Configuration register */ +#define LPC31_MPMC_DYNCONTROL_OFFSET 0x020 /* Dynamic Memory Control Register */ +#define LPC31_MPMC_DYNREFRESH_OFFSET 0x024 /* Dynamic Memory Refresh Timer Register */ +#define LPC31_MPMC_DYNREADCONFIG_OFFSET 0x028 /* Dynamic Memory Read Configuration Register */ +#define LPC31_MPMC_DYNTRP_OFFSET 0x030 /* Dynamic Memory Precharge Command Period Register */ +#define LPC31_MPMC_DYNTRAS_OFFSET 0x034 /* Dynamic Memory Active To Precharge Command Period Register */ +#define LPC31_MPMC_DYNTSREX_OFFSET 0x038 /* Dynamic Memory Self-refresh Exit Time Register */ +#define LPC31_MPMC_DYNTAPR_OFFSET 0x03c /* Dynamic Memory Last Data Out To Active Time Register */ +#define LPC31_MPMC_DYNTDAL_OFFSET 0x040 /* Dynamic Memory Data-in To Active Command Time Register */ +#define LPC31_MPMC_DYNTWR_OFFSET 0x044 /* Dynamic Memory Write Recovery Time Register */ +#define LPC31_MPMC_DYNTRC_OFFSET 0x048 /* Dynamic Memory Active To Active Command Period Register */ +#define LPC31_MPMC_DYNTRFC_OFFSET 0x04c /* Dynamic Memory Auto-refresh Period Register */ +#define LPC31_MPMC_DYNTXSR_OFFSET 0x050 /* Dynamic Memory Exit Self-refresh Register */ +#define LPC31_MPMC_DYNTRRD_OFFSET 0x054 /* Dynamic Memory Active Bank A to Active Bank B Time Register */ +#define LPC31_MPMC_DYNTMRD_OFFSET 0x058 /* Dynamic Memory Load Mode Register To Active Command Time Register */ +#define LPC31_MPMC_STEXTWAIT_OFFSET 0x080 /* Static Memory Extended Wait Register */ +#define LPC31_MPMC_DYNCONFIG0_OFFSET 0x100 /* Dynamic Memory Configuration Registers 0 */ +#define LPC31_MPMC_DYNRASCAS0_OFFSET 0x104 /* Dynamic Memory RAS and CAS Delay Registers 0 */ + /* 0x120-0x164: reserved */ +#define LPC31_MPMC_STCONFIG0_OFFSET 0x200 /* Static Memory Configuration Registers 0 */ +#define LPC31_MPMC_STWAITWEN0_OFFSET 0x204 /* Static Memory Write Enable Delay Registers 0 */ +#define LPC31_MPMC_STWAITOEN0_OFFSET 0x208 /* Static Memory Output Enable Delay Registers 0 */ +#define LPC31_MPMC_STWAITRD0_OFFSET 0x20c /* Static Memory Read Delay Registers 0 */ +#define LPC31_MPMC_STWAITPAGE0_OFFSET 0x210 /* Static Memory Page Mode Read Delay Registers 0 */ +#define LPC31_MPMC_STWAITWR0_OFFSET 0x214 /* Static Memory Write Delay Registers 0 */ +#define LPC31_MPMC_STWAITTURN0_OFFSET 0x218 /* Static Memory Turn Round Delay Registers 0 */ +#define LPC31_MPMC_STCONFIG1_OFFSET 0x220 /* tatic Memory Configuration Registers 1 */ +#define LPC31_MPMC_STWAITWEN1_OFFSET 0x224 /* Static Memory Write Enable Delay Registers 1 */ +#define LPC31_MPMC_STWAITOEN1_OFFSET 0x228 /* Static Memory Output Enable Delay Registers 1 */ +#define LPC31_MPMC_STWAITRD1_OFFSET 0x22c /* Static Memory Read Delay Registers 1 */ +#define LPC31_MPMC_STWAITPAGE1_OFFSET 0x230 /* Static Memory Page Mode Read Delay Registers 1 */ +#define LPC31_MPMC_STWAITWR1_OFFSET 0x234 /* Static Memory Write Delay Registers 1 */ +#define LPC31_MPMC_STWAITTURN1_OFFSET 0x238 /* Static Memory Turn Round Delay Registers 1 */ + /* 0x240-0x278: Reserverd */ + +/* MPMC register (virtual) addresses ************************************************************/ + +#define LPC31_MPMC_CONTROL (LPC31_MPMC_VBASE+LPC31_MPMC_CONTROL_OFFSET) +#define LPC31_MPMC_STATUS (LPC31_MPMC_VBASE+LPC31_MPMC_STATUS_OFFSET) +#define LPC31_MPMC_CONFIG (LPC31_MPMC_VBASE+LPC31_MPMC_CONFIG_OFFSET) +#define LPC31_MPMC_DYNCONTROL (LPC31_MPMC_VBASE+LPC31_MPMC_DYNCONTROL_OFFSET) +#define LPC31_MPMC_DYNREFRESH (LPC31_MPMC_VBASE+LPC31_MPMC_DYNREFRESH_OFFSET) +#define LPC31_MPMC_DYNREADCONFIG (LPC31_MPMC_VBASE+LPC31_MPMC_DYNREADCONFIG_OFFSET) +#define LPC31_MPMC_DYNTRP (LPC31_MPMC_VBASE+LPC31_MPMC_DYNTRP_OFFSET) +#define LPC31_MPMC_DYNTRAS (LPC31_MPMC_VBASE+LPC31_MPMC_DYNTRAS_OFFSET) +#define LPC31_MPMC_DYNTSREX (LPC31_MPMC_VBASE+LPC31_MPMC_DYNTSREX_OFFSET) +#define LPC31_MPMC_DYNTAPR (LPC31_MPMC_VBASE+LPC31_MPMC_DYNTAPR_OFFSET) +#define LPC31_MPMC_DYNTDAL (LPC31_MPMC_VBASE+LPC31_MPMC_DYNTDAL_OFFSET) +#define LPC31_MPMC_DYNTWR (LPC31_MPMC_VBASE+LPC31_MPMC_DYNTWR_OFFSET) +#define LPC31_MPMC_DYNTRC (LPC31_MPMC_VBASE+LPC31_MPMC_DYNTRC_OFFSET) +#define LPC31_MPMC_DYNTRFC (LPC31_MPMC_VBASE+LPC31_MPMC_DYNTRFC_OFFSET) +#define LPC31_MPMC_DYNTXSR (LPC31_MPMC_VBASE+LPC31_MPMC_DYNTXSR_OFFSET) +#define LPC31_MPMC_DYNTRRD (LPC31_MPMC_VBASE+LPC31_MPMC_DYNTRRD_OFFSET) +#define LPC31_MPMC_DYNTMRD (LPC31_MPMC_VBASE+LPC31_MPMC_DYNTMRD_OFFSET) +#define LPC31_MPMC_STEXTWAIT (LPC31_MPMC_VBASE+LPC31_MPMC_STEXTWAIT_OFFSET) +#define LPC31_MPMC_DYNCONFIG0 (LPC31_MPMC_VBASE+LPC31_MPMC_DYNCONFIG0_OFFSET) +#define LPC31_MPMC_DYNRASCAS0 (LPC31_MPMC_VBASE+LPC31_MPMC_DYNRASCAS0_OFFSET) +#define LPC31_MPMC_STCONFIG0 (LPC31_MPMC_VBASE+LPC31_MPMC_STCONFIG0_OFFSET) +#define LPC31_MPMC_STWAITWEN0 (LPC31_MPMC_VBASE+LPC31_MPMC_STWAITWEN0_OFFSET) +#define LPC31_MPMC_STWAITOEN0 (LPC31_MPMC_VBASE+LPC31_MPMC_STWAITOEN0_OFFSET) +#define LPC31_MPMC_STWAITRD0 (LPC31_MPMC_VBASE+LPC31_MPMC_STWAITRD0_OFFSET) +#define LPC31_MPMC_STWAITPAGE0 (LPC31_MPMC_VBASE+LPC31_MPMC_STWAITPAGE0_OFFSET) +#define LPC31_MPMC_STWAITWR0 (LPC31_MPMC_VBASE+LPC31_MPMC_STWAITWR0_OFFSET) +#define LPC31_MPMC_STWAITTURN0 (LPC31_MPMC_VBASE+LPC31_MPMC_STWAITTURN0_OFFSET) +#define LPC31_MPMC_STCONFIG1 (LPC31_MPMC_VBASE+LPC31_MPMC_STCONFIG1_OFFSET) +#define LPC31_MPMC_STWAITWEN1 (LPC31_MPMC_VBASE+LPC31_MPMC_STWAITWEN1_OFFSET) +#define LPC31_MPMC_STWAITOEN1 (LPC31_MPMC_VBASE+LPC31_MPMC_STWAITOEN1_OFFSET) +#define LPC31_MPMC_STWAITRD1 (LPC31_MPMC_VBASE+LPC31_MPMC_STWAITRD1_OFFSET) +#define LPC31_MPMC_STWAITPAGE1 (LPC31_MPMC_VBASE+LPC31_MPMC_STWAITPAGE1_OFFSET) +#define LPC31_MPMC_STWAITWR1 (LPC31_MPMC_VBASE+LPC31_MPMC_STWAITWR1_OFFSET) +#define LPC31_MPMC_STWAITTURN1 (LPC31_MPMC_VBASE+LPC31_MPMC_STWAITTURN1_OFFSET) + +/* MPMC register bit definitions ****************************************************************/ +/* MPMCControl (address 0x17008000) */ + +#define MPMC_CONTROL_L (1 << 2) /* Bit 2: Indicates normal or low-power mode */ +#define MPMC_CONTROL_M (1 << 1) /* Bit 1: Indicates normal or reset memory map */ +#define MPMC_CONTROL_E (1 << 0) /* Bit 0: Indicates when the MPMC is enabled or disabled */ + +/* MPMCStatus (address 0x17008004) */ + +#define MPMC_STATUS_SA (1 << 2) /* Bit 2: Indicates the operating self-refresh mode */ +#define MPMC_STATUS_S (1 << 1) /* Bit 1: Write buffer status */ +#define MPMC_STATUS_B (1 << 0) /* Bit 0: MPMC is busy performing memory transactions */ + +/* MPMCConfig (address 0x17008008) */ + +#define MPMC_CONFIG_CLK (1 << 8) /* Bit 8: Indicates Clock ratio 1:2 */ +#define MPMC_CONFIG_N (1 << 0) /* Bit 0: Indicates big-endian mode */ + +/* MPMCDynamicControl (address 0x17008020) */ + +#define MPMC_DYNCONTROL_DP (1 << 13) /* Bit 13: Low-power SDRAM deep-sleep mode */ +#define MPMC_DYNCONTROL_I_SHIFT (8) /* Bits 7-8: I SDRAM initialization */ +#define MPMC_DYNCONTROL_I_MASK (3 << MPMC_DYNCONTROL_I_SHIFT) +# define MPMC_DYNCONTROL_INORMAL (0 << MPMC_DYNCONTROL_I_SHIFT) /* SDRAM NORMAL operation command */ +# define MPMC_DYNCONTROL_IMODE (1 << MPMC_DYNCONTROL_I_SHIFT) /* SDRAM MODE command */ +# define MPMC_DYNCONTROL_IPALL (2 << MPMC_DYNCONTROL_I_SHIFT) /* SDRAM PALL (pre charge all) */ +# define MPMC_DYNCONTROL_INOP (3 << MPMC_DYNCONTROL_I_SHIFT) /* SDRAM NOP (no operation) */ +#define MPMC_DYNCONTROL_MMC (1 << 5) /* Bit 5: Memory clock control */ +#define MPMC_DYNCONTROL_SR (1 << 2) /* Bit 2: Self-refresh request */ +#define MPMC_DYNCONTROL_CS (1 << 1) /* Bit 1: Dynamic-memory clock control */ +#define MPMC_DYNCONTROL_CE (1 << 0) /* Bit 0: Dynamic-memory clock enable */ + +/* MPMCDynamicRefresh (address 0x17008024) */ + +#define MPMC_DYNREFRESH_TIMER_SHIFT (0) /* Bits 0-10: Refresh timer */ +#define MPMC_DYNREFRESH_TIMER_MASK (0x07ff << MPMC_DYNREFRESH_TIMER_SHIFT) + +/* MPMCDynamicReadConfig (address 0x17008028) */ + +#define MPMC_DYNREADCONFIG_RD_SHIFT (0) /* Bits 0-1: Read data strategy */ +#define MPMC_DYNREADCONFIG_RD_MASK (2 << MPMC_DYNREADCONFIG_RD_SHIFT) +# define MPMC_DYNREADCONFIG_CLKOUTDEL (0 << MPMC_DYNREADCONFIG_RD_SHIFT) /* Clock out delay */ +# define MPMC_DYNREADCONFIG_CMDDEL (1 << MPMC_DYNREADCONFIG_RD_SHIFT) /* Command delay */ +# define MPMC_DYNREADCONFIG_CMDDELP1 (2 << MPMC_DYNREADCONFIG_RD_SHIFT) /* Command delay plus 1*/ +# define MPMC_DYNREADCONFIG_CMDDELP2 (3 << MPMC_DYNREADCONFIG_RD_SHIFT) /* Command delay plus 2 */ + +/* MPMCDynamictRP (address 0x17008030) */ + +#define MPMC_DYNTRP_SHIFT (0) /* Bits 0-3: Precharge command period */ +#define MPMC_DYNTRP_MASK (15 << MPMC_DYNTRP_SHIFT) + +/* MPMCDynamictRAS (address 0x17008034) */ + +#define MPMC_DYNTRAS_SHIFT (0) /* Bits 0-3: Active to pre charge command period */ +#define MPMC_DYNTRAS_MASK (15 << MPMC_DYNTRAS_SHIFT) + +/* MPMCDynamictSREX (address 0x17008038) */ + +#define MPMC_DYNTSREX_SHIFT (0) /* Bits 0-3: Self-refresh exit time */ +#define MPMC_DYNTSREX_MASK (15 << MPMC_DYNTSREX_SHIFT) + +/* MPMCDynamictAPR (address 0x1700803c) */ + +#define MPMC_DYNTAPR_SHIFT (0) /* Bits 0-3: Last-data-out to active command time */ +#define MPMC_DYNTAPR_MASK (15 << MPMC_DYNTAPR_SHIFT) + +/* MPMCDynamictDAL (address 0x17008040) */ + +#define MPMC_DYNTDAL_SHIFT (0) /* Bits 0-3: Data-in to active command */ +#define MPMC_DYNTDAL_MASK (15 << MPMC_DYNTDAL_SHIFT) + +/* MPMCDynamictWR (address 0x17008044) */ + +#define MPMC_DYNTWR_SHIFT (0) /* Bits 0-3: Write recovery time */ +#define MPMC_DYNTWR_MASK (15 << MPMC_DYNTWR_SHIFT) + +/* MPMCDynamictRC (address 0x17008048) */ + +#define MPMC_DYNTRC_SHIFT (0) /* Bits 0-4: Active to active command period */ +#define MPMC_DYNTRC_MASK (31 << MPMC_DYNTRC_SHIFT) + +/* MPMCDynamictRFC (address 0x1700804c) */ + +#define MPMC_DYNTRFC_SHIFT (0) /* Bits 0-4: Auto-refresh period and auto-refresh to active command period, */ +#define MPMC_DYNTRFC_MASK (31 << MPMC_DYNTRFC_SHIFT) + +/* MPMCDynamictXSR (address 0x1700804c) */ + +#define MPMC_DYNTXSR_SHIFT (0) /* Bits 0-4: Exit self-refresh to active command time */ +#define MPMC_DYNTXSR_MASK (31 << MPMC_DYNTXSR_SHIFT) + +/* MPMCDynamictRRD (address 0x17008050) */ + +#define MPMC_DYNTRRD_SHIFT (0) /* Bits 0-3: Active bank A to active bank B latency */ +#define MPMC_DYNTRRD_MASK (15 << MPMC_DYNTRRD_SHIFT) + +/* MPMCDynamictMRD (address 0x17008054) */ + +#define MPMC_DYNTMRD_SHIFT (0) /* Bits 0-3: Load mode register to active command time */ +#define MPMC_DYNTMRD_MASK (15 << MPMC_DYNTMRD_SHIFT) + +/* MPMCStaticExtendedWait (address 0x17008080) */ + +#define MPMC_DYNSTEXTWAIT_SHIFT (0) /* Bits 0-9: External wait time out */ +#define MPMC_DYNSTEXTWAIT_MASK (0x03ff << MPMC_DYNSTEXTWAIT_SHIFT) + +/* MPMCDynamicConfig0 (address 0x17008100) */ + +#define MPMC_DYNCONFIG0_P (1 << 20) /* Bit 20: Write protect */ +#define MPMC_DYNCONFIG0_B (1 << 19) /* Bit 19: Buffer enable */ +#define MPMC_DYNCONFIG0_AM (1 << 14) /* Bit 14: Address mapping */ +#define MPMC_DYNCONFIG0_AM_SHIFT (7) /* Bits 7-12: Address mapping */ +#define MPMC_DYNCONFIG0_AM_MASK (0x3c << MPMC_DYNCONFIG0_AM_SHIFT) + /* 16-bit external bus high-performance address mapping */ +# define MPMC_DYNCONFIG_HP16_2MX8 (0x00 << MPMC_DYNCONFIG0_AM_SHIFT) /* 16Mb (2Mx8), 2 banks, row length=11, column length=9 */ +# define MPMC_DYNCONFIG_HP16_1MX16 (0x01 << MPMC_DYNCONFIG0_AM_SHIFT) /* 16Mb (1Mx16), 2 banks, row length=11, column length=8 */ +# define MPMC_DYNCONFIG_HP16_8MX8 (0x04 << MPMC_DYNCONFIG0_AM_SHIFT) /* 64Mb (8Mx8), 4 banks, row length=12, column length=9 */ +# define MPMC_DYNCONFIG_HP16_4MX16 (0x05 << MPMC_DYNCONFIG0_AM_SHIFT) /* 64Mb (4Mx16), 4 banks, row length=12, column length=8 */ +# define MPMC_DYNCONFIG_HP16_16MX8 (0x08 << MPMC_DYNCONFIG0_AM_SHIFT) /* 128Mb (16Mx8), 4 banks, row length=12, column length=10 */ +# define MPMC_DYNCONFIG_HP16_8MX16 (0x09 << MPMC_DYNCONFIG0_AM_SHIFT) /* 128Mb (8Mx16), 4 banks, row length=12, column length=9 */ +# define MPMC_DYNCONFIG_HP16_32MX8 (0x0c << MPMC_DYNCONFIG0_AM_SHIFT) /* 256Mb (32Mx8), 4 banks, row length=13, column length=10 */ +# define MPMC_DYNCONFIG_HP16_16MX16 (0x0d << MPMC_DYNCONFIG0_AM_SHIFT) /* 256Mb (16Mx16), 4 banks, row length=13, column length=9 */ +# define MPMC_DYNCONFIG_HP16_64MX8 (0x10 << MPMC_DYNCONFIG0_AM_SHIFT) /* 512Mb (64Mx8), 4 banks, row length=13, column length=11 */ +# define MPMC_DYNCONFIG_HP16_32MX16 (0x11 << MPMC_DYNCONFIG0_AM_SHIFT) /* 512Mb (32Mx16), 4 banks, row length=13, column length=10 */ + /* 16-bit external bus low power SDRAM address mapping */ +# define MPMC_DYNCONFIG_LP16_2MX8 (0x20 << MPMC_DYNCONFIG0_AM_SHIFT) /* 6Mb (2Mx8), 2 banks, row length=11, column length=9 */ +# define MPMC_DYNCONFIG_LP16_1MX16 (0x21 << MPMC_DYNCONFIG0_AM_SHIFT) /* 16Mb (1Mx16), 2 banks, row length=11, column length=8 */ +# define MPMC_DYNCONFIG_LP16_8MX8 (0x24 << MPMC_DYNCONFIG0_AM_SHIFT) /* 64Mb (8Mx8), 4 banks, row length=12, column length=9 */ +# define MPMC_DYNCONFIG_LP16_4MX16 (0x25 << MPMC_DYNCONFIG0_AM_SHIFT) /* 64Mb (4Mx16), 4 banks, row length=12, column length=8 */ +# define MPMC_DYNCONFIG_LP16_16MX8 (0x28 << MPMC_DYNCONFIG0_AM_SHIFT) /* 128Mb (16Mx8), 4 banks, row length=12, column length=10 */ +# define MPMC_DYNCONFIG_LP16_8MX16 (0x29 << MPMC_DYNCONFIG0_AM_SHIFT) /* 128Mb (8Mx16), 4 banks, row length=12, column length=9 */ +# define MPMC_DYNCONFIG_LP16_32MX8 (0x2c << MPMC_DYNCONFIG0_AM_SHIFT) /* 256Mb (32Mx8), 4 banks, row length=13, column length=10 */ +# define MPMC_DYNCONFIG_LP16_16MX16 (0x2d << MPMC_DYNCONFIG0_AM_SHIFT) /* 256Mb (16Mx16), 4 banks, row length=13, column length=9 */ +# define MPMC_DYNCONFIG_LP16_64MX8 (0x30 << MPMC_DYNCONFIG0_AM_SHIFT) /* 512Mb (64Mx8), 4 banks, row length=13, column length=11 */ +# define MPMC_DYNCONFIG_LP16_32MX16 (0x31 << MPMC_DYNCONFIG0_AM_SHIFT) /* 512Mb (32Mx16), 4 banks, row length=13, column length=10 */ +#define MPMC_DYNCONFIG0_MD_SHIFT (3) /* Bits 3-4: Memory device */ +#define MPMC_DYNCONFIG0_MD_MASK (3 << MPMC_DYNCONFIG0_MD_SHIFT) +# define MPMC_DYNCONFIG0_MDSDRAM (0 << MPMC_DYNCONFIG0_MD_SHIFT) /* SDRAM */ +# define MPMC_DYNCONFIG0_MDLPSDRAM (1 << MPMC_DYNCONFIG0_MD_SHIFT) /* low-power SDRAM */ +# define MPMC_DYNCONFIG0_MDMSF (2 << MPMC_DYNCONFIG0_MD_SHIFT) /* Micron SyncFlash */ + +/* MPMCDynamicRasCas0 (address 0x17008104) */ + +#define MPMC_DYNRASCAS0_CAS_SHIFT (8) /* Bits 8-9: CAS latency */ +#define MPMC_DYNRASCAS0_CAS_MASK (3 << MPMC_DYNRASCAS0_CAS_SHIFT) +# define MPMC_DYNRASCAS0_CAS1CLK (1 << MPMC_DYNRASCAS0_CAS_SHIFT) /* one clock cycle */ +# define MPMC_DYNRASCAS0_CAS2CLK (2 << MPMC_DYNRASCAS0_CAS_SHIFT) /* two clock cycles */ +# define MPMC_DYNRASCAS0_CAS3CLK (3 << MPMC_DYNRASCAS0_CAS_SHIFT) /* three clock cycles */ +#define MPMC_DYNRASCAS0_RAS_SHIFT (0) /* Bits 0-1: RAS latency */ +#define MPMC_DYNRASCAS0_RAS_MASK (3 << MPMC_DYNRASCAS0_RAS_SHIFT) +# define MPMC_DYNRASCAS0_RAS1CLK (1 << MPMC_DYNRASCAS0_RAS_SHIFT) /* one clock cycle */ +# define MPMC_DYNRASCAS0_RAS2CLK (2 << MPMC_DYNRASCAS0_RAS_SHIFT) /* two clock cycles */ +# define MPMC_DYNRASCAS0_RAS3CLK (3 << MPMC_DYNRASCAS0_RAS_SHIFT) /* three clock cycles */ + +/* MPMCStaticConfig0 (address 0x17008120) and MPMCStaticConfig1 (address 0x17008220) */ + +#define MPMC_STCONFIG_WP (1 << 20) /* Bit 20: Write protect */ +#define MPMC_STCONFIG_B (1 << 19) /* Bit 19: Buffer enable */ +#define MPMC_STCONFIG_EW (1 << 8) /* Bit 8: Extended wait */ +#define MPMC_STCONFIG_BLS (1 << 7) /* Bit 7: BLS EBI_NCAS_BLOUT_0/1 EBI_nWE config */ +#define MPMC_STCONFIG_PC (1 << 6) /* Bit 6: Chip select polarity */ +#define MPMC_STCONFIG_PM (1 << 63 /* Bit 3: Page mode */ +#define MPMC_STCONFIG_MW_SHIFT (0) /* Bits 0-1: Memory width */ +#define MPMC_STCONFIG_MW_MASK (3 << MPMC_STCONFIG_MW_SHIFT) +# define MPMC_STCONFIG_MW8BIT (0 << MPMC_STCONFIG_MW_SHIFT) /* 8-bit */ +# define MPMC_STCONFIG_MW16BIT (1 << MPMC_STCONFIG_MW_SHIFT) /* 16-bit */ + +/* MPMCStaticWaitWen0 (address 0x17008204) and MPMCStaticWaitWen1 (address 0x17008224) */ + +#define MPMC_STWAITWEN_SHIFT (0) /* WAITWEN Delay from chip select to write enable */ +#define MPMC_STWAITWEN_MASK (15 << MPMC_STWAITWEN_SHIFT) + +/* MPMCStaticWaitOen (address 0x17008208) and MPMCStaticWaitOen1 (address 0x17008228) */ + +#define MPMC_STWAITOEN_SHIFT (0) /* WAITOEN Delay from chip select to output enable */ +#define MPMC_STWAITOEN_MASK (15 << MPMC_STWAITOEN_SHIFT) + +/* MPMCStaticWaitRd0 (address 0x1700820c) and MPMCStaticWaitRd1 (address 0x17008022c) */ + +#define MPMC_STWAITRD_SHIFT (0) /* Read first access wait state */ +#define MPMC_STWAITRD_MASK (31 << MPMC_STWAITRD_SHIFT) + +/* MPMCStaticWaitPage0 (address 0x17008210) and MPMCStaticWaitPage1 (address 0x17008230) */ + +#define MPMC_STWAITPAGE_SHIFT (0) /* Read after the first read wait states */ +#define MPMC_STWAITPAGE_MASK (31 << MPMC_STWAITPAGE_SHIFT) + +/* MPMCStaticWaitWr0 (address 0x17008214) and MPMCStaticWaitWr1 (address 0x17008234) */ + +#define MPMC_STWAITWR_SHIFT (0) /* Time for write accesses after the first read */ +#define MPMC_STWAITWR_MASK (31 << MPMC_STWAITWR_SHIFT) + +/* MPMCStaticWaitTurn0 (address 0x17008218) and MPMCStaticWaitTurn1 (address 0x17008238) */ + +#define MPMC_STWAITTURN_SHIFT (0) /* Bus turnaround cycles */ +#define MPMC_STWAITTURN_MASK (15 << MPMC_STWAITTURN_SHIFT) + +/************************************************************************************************ + * Public Types + ************************************************************************************************/ + +/************************************************************************************************ + * Public Data + ************************************************************************************************/ + +/************************************************************************************************ + * Public Functions + ************************************************************************************************/ + +#endif /* __ARCH_ARM_SRC_LPC31XX_LPC31_MPMC_H */ diff --git a/nuttx/arch/arm/src/lpc31xx/lpc31_nand.h b/nuttx/arch/arm/src/lpc31xx/lpc31_nand.h new file mode 100755 index 000000000..56ce099e1 --- /dev/null +++ b/nuttx/arch/arm/src/lpc31xx/lpc31_nand.h @@ -0,0 +1,378 @@ +/************************************************************************************************ + * arch/arm/src/lpc31xx/lpc31_nand.h + * + * Copyright (C) 2009 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * 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_LPC31XX_LPC31_NAND_H +#define __ARCH_ARM_SRC_LPC31XX_LPC31_NAND_H + +/************************************************************************************************ + * Included Files + ************************************************************************************************/ + +#include +#include "lpc31_memorymap.h" + +/************************************************************************************************ + * Pre-processor Definitions + ************************************************************************************************/ + +/* NAND FLASH controller register base address offset into the APB4 domain **********************/ + +#define LPC31_NAND_VBASE (LPC31_APB4_VADDR+LPC31_APB4_NAND_OFFSET) +#define LPC31_NAND_PBASE (LPC31_APB4_PADDR+LPC31_APB4_NAND_OFFSET) + +/* NAND FLASH controller register offsets (with respect to the base of the APB4 domain) *********/ + +#define LPC31_NAND_IRQSTATUS1_OFFSET 0x00 /* Interrrupt status register (first 32-bits) */ +#define LPC31_NAND_IRQMASK1_OFFSET 0x04 /* Interrupt mask register (first 32-bits) */ +#define LPC31_NAND_IRQSTATUSRAW1_OFFSET 0x08 /* Unmasked register status (first 32-bits) */ +#define LPC31_NAND_CONFIG_OFFSET 0x0c /* NAND Flash controller configuration register */ +#define LPC31_NAND_IOCONFIG_OFFSET 0x10 /* Default value settings for IO signals */ +#define LPC31_NAND_TIMING1_OFFSET 0x14 /* First NAND FLASH controller timing register */ +#define LPC31_NAND_TIMING2_OFFSET 0x18 /* Second NAND FLASH controller timing register */ +#define LPC31_NAND_SETCMD_OFFSET 0x20 /* NAND FLASH device command register */ +#define LPC31_NAND_SETADDR_OFFSET 0x24 /* NAND FLASH device address register */ +#define LPC31_NAND_WRITEDATA_OFFSET 0x28 /* NAND FLASH device write data register */ +#define LPC31_NAND_SETCE_OFFSET 0x2c /* Set all CE and WP_n signals */ +#define LPC31_NAND_READDATA_OFFSET 0x30 /* NAND FLASH device read data register */ +#define LPC31_NAND_CHECKSTS_OFFSET 0x34 /* Check status of interrupts */ +#define LPC31_NAND_CONTROLFLOW_OFFSET 0x38 /* Commands to read and write pages */ +#define LPC31_NAND_GPIO1_OFFSET 0x40 /* Program IO pins that can be used as GPIO */ +#define LPC31_NAND_GPIO2_OFFSET 0x44 /* Program IO pins that can be used as GPIO */ +#define LPC31_NAND_IRQSTATUS2_OFFSET 0x48 /* Interrrupt status register (second 32-bits) */ +#define LPC31_NAND_IRQMASK3_OFFSET 0x4c /* Interrupt mask register (second 32-bits) */ +#define LPC31_NAND_IRQSTATUSRAW2_OFFSET 0x50 /* Unmasked register status (second 32-bits) */ +#define LPC31_NAND_ECCERRSTATUS_OFFSET 0x78 /* ECC error status register */ + +/* NAND FLASH controller register (virtual) addresses *******************************************/ + +#define LPC31_NAND_IRQSTATUS1 (LPC31_NAND_VBASE+LPC31_NAND_IRQSTATUS1_OFFSET) +#define LPC31_NAND_IRQMASK1 (LPC31_NAND_VBASE+LPC31_NAND_IRQMASK1_OFFSET) +#define LPC31_NAND_IRQSTATUSRAW1 (LPC31_NAND_VBASE+LPC31_NAND_IRQSTATUSRAW1_OFFSET) +#define LPC31_NAND_CONFIG (LPC31_NAND_VBASE+LPC31_NAND_CONFIG_OFFSET) +#define LPC31_NAND_IOCONFIG (LPC31_NAND_VBASE+LPC31_NAND_IOCONFIG_OFFSET) +#define LPC31_NAND_TIMING1 (LPC31_NAND_VBASE+LPC31_NAND_TIMING1_OFFSET) +#define LPC31_NAND_TIMING2 (LPC31_NAND_VBASE+LPC31_NAND_TIMING2_OFFSET) +#define LPC31_NAND_SETCMD (LPC31_NAND_VBASE+LPC31_NAND_SETCMD_OFFSET) +#define LPC31_NAND_SETADDR (LPC31_NAND_VBASE+LPC31_NAND_SETADDR_OFFSET) +#define LPC31_NAND_WRITEDATA (LPC31_NAND_VBASE+LPC31_NAND_WRITEDATA_OFFSET) +#define LPC31_NAND_SETCE (LPC31_NAND_VBASE+LPC31_NAND_SETCE_OFFSET) +#define LPC31_NAND_READDATA (LPC31_NAND_VBASE+LPC31_NAND_READDATA_OFFSET) +#define LPC31_NAND_CHECKSTS (LPC31_NAND_VBASE+LPC31_NAND_CHECKSTS_OFFSET) +#define LPC31_NAND_CONTROLFLOW (LPC31_NAND_VBASE+LPC31_NAND_CONTROLFLOW_OFFSET) +#define LPC31_NAND_GPIO1 (LPC31_NAND_VBASE+LPC31_NAND_GPIO1_OFFSET) +#define LPC31_NAND_GPIO2 (LPC31_NAND_VBASE+LPC31_NAND_GPIO2_OFFSET) +#define LPC31_NAND_IRQSTATUS2 (LPC31_NAND_VBASE+LPC31_NAND_IRQSTATUS2_OFFSET) +#define LPC31_NAND_IRQMASK3 (LPC31_NAND_VBASE+LPC31_NAND_IRQMASK3_OFFSET) +#define LPC31_NAND_IRQSTATUSRAW2 (LPC31_NAND_VBASE+LPC31_NAND_IRQSTATUSRAW2_OFFSET) +#define LPC31_NAND_ECCERRSTATUS (LPC31_NAND_VBASE+LPC31_NAND_ECCERRSTATUS_OFFSET) + +/* NAND FLASH controller register bit definitions ***********************************************/ +/* NandIRQStatus1 register description (NandIRQStatus1, address 0x17000800) */ + +#define NAND_IRQSTATUS1_MNANDRYBN3 (1 << 31) /* Bit 31: mNAND_RYBN3 positive edge */ +#define NAND_IRQSTATUS1_MNANDRYBN2 (1 << 30) /* Bit 30: mNAND_RYBN2 positive edge */ +#define NAND_IRQSTATUS1_MNANDRYBN1 (1 << 29) /* Bit 29: mNAND_RYBN1 positive edge */ +#define NAND_IRQSTATUS1_MNANDRYBN0 (1 << 28) /* Bit 28: mNAND_RYBN0 positive edge */ +#define NAND_IRQSTATUS1_RAM1ERASED (1 << 27) /* Bit 27: RAM 1 erased */ +#define NAND_IRQSTATUS1_RAM0ERASED (1 << 26) /* Bit 26: RAM 0 erased */ +#define NAND_IRQSTATUS1_WRPG1DONE (1 << 25) /* Bit 25: Write page 1 done */ +#define NAND_IRQSTATUS1_WRPG0DONE (1 << 24) /* Bit 24: Write page 0 done */ +#define NAND_IRQSTATUS1_RDPG1DONE (1 << 23) /* Bit 23: Read page 1 done */ +#define NAND_IRQSTATUS1_RDPG0DONE (1 << 22) /* Bit 22: Read page 0 done */ +#define NAND_IRQSTATUS1_RAM0DECODE (1 << 21) /* Bit 21: RAM 0 decoded */ +#define NAND_IRQSTATUS1_RAM0ENCODE (1 << 20) /* Bit 20: RAM 0 encoded */ +#define NAND_IRQSTATUS1_RAM1DECODE (1 << 19) /* Bit 19: RAM 1 decoded */ +#define NAND_IRQSTATUS1_RAM1ENCODE (1 << 18) /* Bit 18: RAM 1 encoded */ +#define NAND_IRQSTATUS1_RAM00ERRS (1 << 17) /* Bit 17: RAM 0 decoded with 0 errors */ +#define NAND_IRQSTATUS1_RAM01ERR (1 << 16) /* Bit 16: RAM 0 decoded with 1 error (depends on mode) */ +#define NAND_IRQSTATUS1_RAM02ERR (1 << 15) /* Bit 15: RAM 0 decoded with 2 error */ +#define NAND_IRQSTATUS1_RAM03ERR (1 << 14) /* Bit 14: RAM 0 decoded with 3 error */ +#define NAND_IRQSTATUS1_RAM04ERR (1 << 13) /* Bit 13: RAM 0 decoded with 4 error */ +#define NAND_IRQSTATUS1_RAM05ERR (1 << 12) /* Bit 12: RAM 0 decoded with 5 error */ +#define NAND_IRQSTATUS1_RAM0UNCORR (1 << 11) /* Bit 11: RAM 0 uncorrectable */ +#define NAND_IRQSTATUS1_RAM10ERR (1 << 10) /* Bit 10: RAM 1 decoded with 0 errors */ +#define NAND_IRQSTATUS1_RAM11ERR (1 << 9) /* Bit 9: RAM 1 decoded with 1 error (depends on mode) */ +#define NAND_IRQSTATUS1_RAM12ERR (1 << 8) /* Bit 8: RAM 1 decoded with 2 error */ +#define NAND_IRQSTATUS1_RAM13ERR (1 << 7) /* Bit 7: RAM 1 decoded with 3 error */ +#define NAND_IRQSTATUS1_RAM14ERR (1 << 6) /* Bit 6: RAM 1 decoded with 4 error */ +#define NAND_IRQSTATUS1_RAM15ERR (1 << 5) /* Bit 5: RAM 1 decoded with 5 error */ +#define NAND_IRQSTATUS1_RAM1UNCORR (1 << 4) /* Bit 4: RAM 1 uncorrectable */ + +/* NandIRQMask1 register description (NandIRQMask1, address 0x17000804) */ + +#define NAND_IRQIRQMASK1_MNANDRYBN3 (1 << 31) /* Bit 31: mNAND_RYBN3 positive edge */ +#define NAND_IRQIRQMASK1_MNANDRYBN2 (1 << 30) /* Bit 30: mNAND_RYBN2 positive edge */ +#define NAND_IRQIRQMASK1_MNANDRYBN1 (1 << 29) /* Bit 29: mNAND_RYBN1 positive edge */ +#define NAND_IRQIRQMASK1_MNANDRYBN0 (1 << 28) /* Bit 28: mNAND_RYBN0 positive edge */ +#define NAND_IRQIRQMASK1_RAM1ERASED (1 << 27) /* Bit 27: RAM 1 erased */ +#define NAND_IRQIRQMASK1_RAM0ERASED (1 << 26) /* Bit 26: RAM 0 erased */ +#define NAND_IRQIRQMASK1_WRPG1DONE (1 << 25) /* Bit 25: Write page 1 done */ +#define NAND_IRQIRQMASK1_WRPG0DONE (1 << 24) /* Bit 24: Write page 0 done */ +#define NAND_IRQIRQMASK1_RDPG1DONE (1 << 23) /* Bit 23: Read page 1 done */ +#define NAND_IRQIRQMASK1_RDPG0DONE (1 << 22) /* Bit 22: Read page 0 done */ +#define NAND_IRQIRQMASK1_RAM0DECODE (1 << 21) /* Bit 21: RAM 0 decoded */ +#define NAND_IRQIRQMASK1_RAM0ENCODE (1 << 20) /* Bit 20: RAM 0 encoded */ +#define NAND_IRQIRQMASK1_RAM1DECODE (1 << 19) /* Bit 19: RAM 1 decoded */ +#define NAND_IRQIRQMASK1_RAM1ENCODE (1 << 18) /* Bit 18: RAM 1 encoded */ +#define NAND_IRQIRQMASK1_RAM00ERRS (1 << 17) /* Bit 17: RAM 0 decoded with 0 errors */ +#define NAND_IRQIRQMASK1_RAM01ERR (1 << 16) /* Bit 16: RAM 0 decoded with 1 error (depends on mode) */ +#define NAND_IRQIRQMASK1_RAM02ERR (1 << 15) /* Bit 15: RAM 0 decoded with 2 error */ +#define NAND_IRQIRQMASK1_RAM03ERR (1 << 14) /* Bit 14: RAM 0 decoded with 3 error */ +#define NAND_IRQIRQMASK1_RAM04ERR (1 << 13) /* Bit 13: RAM 0 decoded with 4 error */ +#define NAND_IRQIRQMASK1_RAM05ERR (1 << 12) /* Bit 12: RAM 0 decoded with 5 error */ +#define NAND_IRQIRQMASK1_RAM0UNCORR (1 << 11) /* Bit 11: RAM 0 uncorrectable */ +#define NAND_IRQIRQMASK1_RAM10ERR (1 << 10) /* Bit 10: RAM 1 decoded with 0 errors */ +#define NAND_IRQIRQMASK1_RAM11ERR (1 << 9) /* Bit 9: RAM 1 decoded with 1 error (depends on mode) */ +#define NAND_IRQIRQMASK1_RAM12ERR (1 << 8) /* Bit 8: RAM 1 decoded with 2 error */ +#define NAND_IRQIRQMASK1_RAM13ERR (1 << 7) /* Bit 7: RAM 1 decoded with 3 error */ +#define NAND_IRQIRQMASK1_RAM14ERR (1 << 6) /* Bit 6: RAM 1 decoded with 4 error */ +#define NAND_IRQIRQMASK1_RAM15ERR (1 << 5) /* Bit 5: RAM 1 decoded with 5 error */ +#define NAND_IRQIRQMASK1_RAM1UNCORR (1 << 4) /* Bit 4: RAM 1 uncorrectable */ + +/* NandIRQStatusRaw1 register description (NandIRQStatusRaw1, address 0x17000808) */ + +#define NAND_IRQSTATUSRAW1_MNANDRYBN3 (1 << 31) /* Bit 31: mNAND_RYBN3 positive edge */ +#define NAND_IRQSTATUSRAW1_MNANDRYBN2 (1 << 30) /* Bit 30: mNAND_RYBN2 positive edge */ +#define NAND_IRQSTATUSRAW1_MNANDRYBN1 (1 << 29) /* Bit 29: mNAND_RYBN1 positive edge */ +#define NAND_IRQSTATUSRAW1_MNANDRYBN0 (1 << 28) /* Bit 28: mNAND_RYBN0 positive edge */ +#define NAND_IRQSTATUSRAW1_RAM1ERASED (1 << 27) /* Bit 27: RAM 1 erased */ +#define NAND_IRQSTATUSRAW1_RAM0ERASED (1 << 26) /* Bit 26: RAM 0 erased */ +#define NAND_IRQSTATUSRAW1_WRPG1DONE (1 << 25) /* Bit 25: Write page 1 done */ +#define NAND_IRQSTATUSRAW1_WRPG0DONE (1 << 24) /* Bit 24: Write page 0 done */ +#define NAND_IRQSTATUSRAW1_RDPG1DONE (1 << 23) /* Bit 23: Read page 1 done */ +#define NAND_IRQSTATUSRAW1_RDPG0DONE (1 << 22) /* Bit 22: Read page 0 done */ +#define NAND_IRQSTATUSRAW1_RAM0DECODE (1 << 21) /* Bit 21: RAM 0 decoded */ +#define NAND_IRQSTATUSRAW1_RAM0ENCODE (1 << 20) /* Bit 20: RAM 0 encoded */ +#define NAND_IRQSTATUSRAW1_RAM1DECODE (1 << 19) /* Bit 19: RAM 1 decoded */ +#define NAND_IRQSTATUSRAW1_RAM1ENCODE (1 << 18) /* Bit 18: RAM 1 encoded */ +#define NAND_IRQSTATUSRAW1_RAM00ERRS (1 << 17) /* Bit 17: RAM 0 decoded with 0 errors */ +#define NAND_IRQSTATUSRAW1_RAM01ERR (1 << 16) /* Bit 16: RAM 0 decoded with 1 error (depends on mode) */ +#define NAND_IRQSTATUSRAW1_RAM02ERR (1 << 15) /* Bit 15: RAM 0 decoded with 2 error */ +#define NAND_IRQSTATUSRAW1_RAM03ERR (1 << 14) /* Bit 14: RAM 0 decoded with 3 error */ +#define NAND_IRQSTATUSRAW1_RAM04ERR (1 << 13) /* Bit 13: RAM 0 decoded with 4 error */ +#define NAND_IRQSTATUSRAW1_RAM05ERR (1 << 12) /* Bit 12: RAM 0 decoded with 5 error */ +#define NAND_IRQSTATUSRAW1_RAM0UNCORR (1 << 11) /* Bit 11: RAM 0 uncorrectable */ +#define NAND_IRQSTATUSRAW1_RAM10ERR (1 << 10) /* Bit 10: RAM 1 decoded with 0 errors */ +#define NAND_IRQSTATUSRAW1_RAM11ERR (1 << 9) /* Bit 9: RAM 1 decoded with 1 error (depends on mode) */ +#define NAND_IRQSTATUSRAW1_RAM12ERR (1 << 8) /* Bit 8: RAM 1 decoded with 2 error */ +#define NAND_IRQSTATUSRAW1_RAM13ERR (1 << 7) /* Bit 7: RAM 1 decoded with 3 error */ +#define NAND_IRQSTATUSRAW1_RAM14ERR (1 << 6) /* Bit 6: RAM 1 decoded with 4 error */ +#define NAND_IRQSTATUSRAW1_RAM15ERR (1 << 5) /* Bit 5: RAM 1 decoded with 5 error */ +#define NAND_IRQSTATUSRAW1_RAM1UNCORR (1 << 4) /* Bit 4: RAM 1 uncorrectable */ + +/* NandConfig register description (NandConfig, address 0x1700080c) */ + +#define NAND_CONFIG_ECC_MODE (1 << 12) /* Bit 12: ECC mode 0 */ +#define NAND_CONFIG_TL_SHIFT (10) /* Bits 10-11: Transfer limit */ +#define NAND_CONFIG_TL_MASK (3 < + * + * 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_LPC31XX_LPC31_PCM_H +#define __ARCH_ARM_SRC_LPC31XX_LPC31_PCM_H + +/************************************************************************************************ + * Included Files + ************************************************************************************************/ + +#include +#include "lpc31_memorymap.h" + +/************************************************************************************************ + * Pre-processor Definitions + ************************************************************************************************/ + +/* PCM register base address offset into the APB2 domain ****************************************/ + +#define LPC31_PCM_VBASE (LPC31_APB2_VSECTION+LPC31_APB2_PCM_OFFSET) +#define LPC31_PCM_PBASE (LPC31_APB2_PSECTION+LPC31_APB2_PCM_OFFSET) + +/* PCM register offsets (with respect to the PCM base) ******************************************/ + +#define LPC31_PCM_GLOBAL_OFFSET 0x000 /* Global register */ +#define LPC31_PCM_CNTL0_OFFSET 0x004 /* Control register 0 */ +#define LPC31_PCM_CNTL1_OFFSET 0x008 /* Control register 1 */ +#define LPC31_PCM_HPOUT_OFFSET(n) (0x00c+((n)<<2)) /* Transmit data register n */ +#define LPC31_PCM_HPOUT0_OFFSET 0x00c /* Transmit data register 0 */ +#define LPC31_PCM_HPOUT1_OFFSET 0x010 /* Transmit data register 1 */ +#define LPC31_PCM_HPOUT2_OFFSET 0x014 /* Transmit data register 2 */ +#define LPC31_PCM_HPOUT3_OFFSET 0x018 /* Transmit data register 3 */ +#define LPC31_PCM_HPOUT4_OFFSET 0x01c /* Transmit data register 4 */ +#define LPC31_PCM_HPOUT5_OFFSET 0x020 /* Transmit data register 5 */ +#define LPC31_PCM_HPIN_OFFSET(n) (0x024+((n)<<2)) /* Transmit data register n */ +#define LPC31_PCM_HPIN0_OFFSET 0x024 /* Receive data register 0 */ +#define LPC31_PCM_HPIN1_OFFSET 0x028 /* Receive data register 1 */ +#define LPC31_PCM_HPIN2_OFFSET 0x02c /* Receive data register 2 */ +#define LPC31_PCM_HPIN3_OFFSET 0x030 /* Receive data register 3 */ +#define LPC31_PCM_HPIN4_OFFSET 0x034 /* Receive data register 4 */ +#define LPC31_PCM_HPIN5_OFFSET 0x038 /* Receive data register 5 */ +#define LPC31_PCM_CNTL2_OFFSET 0x03c /* Control register 2 */ + +/* PCM register (virtual) addresses *************************************************************/ + +#define LPC31_PCM_GLOBAL (LPC31_PCM_VBASE+LPC31_PCM_GLOBAL_OFFSET) +#define LPC31_PCM_CNTL0 (LPC31_PCM_VBASE+LPC31_PCM_CNTL0_OFFSET) +#define LPC31_PCM_CNTL1 (LPC31_PCM_VBASE+LPC31_PCM_CNTL1_OFFSET) +#define LPC31_PCM_HPOUT(n) (LPC31_PCM_VBASE+LPC31_PCM_HPOUT_OFFSET(n)) +#define LPC31_PCM_HPOUT0 (LPC31_PCM_VBASE+LPC31_PCM_HPOUT0_OFFSET) +#define LPC31_PCM_HPOUT1 (LPC31_PCM_VBASE+LPC31_PCM_HPOUT1_OFFSET) +#define LPC31_PCM_HPOUT2 (LPC31_PCM_VBASE+LPC31_PCM_HPOUT2_OFFSET) +#define LPC31_PCM_HPOUT3 (LPC31_PCM_VBASE+LPC31_PCM_HPOUT3_OFFSET) +#define LPC31_PCM_HPOUT4 (LPC31_PCM_VBASE+LPC31_PCM_HPOUT4_OFFSET) +#define LPC31_PCM_HPOUT5 (LPC31_PCM_VBASE+LPC31_PCM_HPOUT5_OFFSET) +#define LPC31_PCM_HPIN(n) (LPC31_PCM_VBASE+LPC31_PCM_HPIN_OFFSET(n)) +#define LPC31_PCM_HPIN0 (LPC31_PCM_VBASE+LPC31_PCM_HPIN0_OFFSET) +#define LPC31_PCM_HPIN1 (LPC31_PCM_VBASE+LPC31_PCM_HPIN1_OFFSET) +#define LPC31_PCM_HPIN2 (LPC31_PCM_VBASE+LPC31_PCM_HPIN2_OFFSET) +#define LPC31_PCM_HPIN3 (LPC31_PCM_VBASE+LPC31_PCM_HPIN3_OFFSET) +#define LPC31_PCM_HPIN4 (LPC31_PCM_VBASE+LPC31_PCM_HPIN4_OFFSET) +#define LPC31_PCM_HPIN5 (LPC31_PCM_VBASE+LPC31_PCM_HPIN5_OFFSET) +#define LPC31_PCM_CNTL2 (LPC31_PCM_VBASE+LPC31_PCM_CNTL2_OFFSET) + +/* PCM register bit definitions *****************************************************************/ + +/* GLOBAL register, address 0x15000000 */ + +#define PCM_GLOBAL_DMARXENABLE (1 << 4) /* Bit 4: Enable DMA RX */ +#define PCM_GLOBAL_DMATXENABLE (1 << 3) /* Bit 3: Enable DMA TX */ +#define PCM_GLOBAL_NORMAL (1 << 2) /* Bit 2: Slave/Normal mode */ +#define PCM_GLOBAL_ONOFF (1 << 0) /* Bit 0: IPINT active */ + +/* CNTL0 register, address 0x15000004 */ + +#define PCM_CNTL0_MASTER (1 << 14) /* Bit 14: PCM/IOM master mode */ +#define PCM_CNTL0_LOOPBACK (1 << 11) /* Bit 11: Internal loop-back mode */ +#define PCM_CNTL0_TYPOD (1 << 10) /* Bit 10: Type of PCM_FCS and PCM_DCLK output port */ +#define PCM_CNTL0_TYPDOIP_SHIFT (8) /* Bits 8-9: Type of PCM/IOM data output ports */ +#define PCM_CNTL0_TYPDOIP_MASK (3 << PCM_CNTL0_TYPDOIP_SHIFT) +#define PCM_CNTL0_TYPFRMSYNC_SHIFT (6) /* Bits 6-7: Shape of frame synchronization signal */ +#define PCM_CNTL0_TYPFRMSYNC_MASK (3 << PCM_CNTL0_TYPFRMSYNC_SHIFT) +#define PCM_CNTL0_CLKSPD_SHIFT (3) /* Bits 3-5: Port frequency selection */ +#define PCM_CNTL0_CLKSPD_MASK (7 << PCM_CNTL0_CLKSPD_SHIFT) + +/* CNTL1 register, address 0x15000008 */ + +#define PCM_CNTL1_ENSLT_SHIFT (0) /* Bits 0-11: Enable PCM/IOM Slots, one per slot */ +#define PCM_CNTL1_ENSLT_MASK (0xfff << PCM_CNTL1_ENSLT_SHIFT) +# define PCM_CNTL1_ENSLT0 (0x001 << PCM_CNTL1_ENSLT_SHIFT) +# define PCM_CNTL1_ENSLT1 (0x002 << PCM_CNTL1_ENSLT_SHIFT) +# define PCM_CNTL1_ENSLT2 (0x004 << PCM_CNTL1_ENSLT_SHIFT) +# define PCM_CNTL1_ENSLT3 (0x008 << PCM_CNTL1_ENSLT_SHIFT) +# define PCM_CNTL1_ENSLT4 (0x010 << PCM_CNTL1_ENSLT_SHIFT) +# define PCM_CNTL1_ENSLT5 (0x020 << PCM_CNTL1_ENSLT_SHIFT) +# define PCM_CNTL1_ENSLT6 (0x040 << PCM_CNTL1_ENSLT_SHIFT) +# define PCM_CNTL1_ENSLT7 (0x080 << PCM_CNTL1_ENSLT_SHIFT) +# define PCM_CNTL1_ENSLT8 (0x100 << PCM_CNTL1_ENSLT_SHIFT) +# define PCM_CNTL1_ENSLT9 (0x200 << PCM_CNTL1_ENSLT_SHIFT) +# define PCM_CNTL1_ENSLT10 (0x400 << PCM_CNTL1_ENSLT_SHIFT) +# define PCM_CNTL1_ENSLT11 (0x800 << PCM_CNTL1_ENSLT_SHIFT) + +/* HPOUTn registers, addresses 0x1500000c to 0x15000020 (two per slot) */ + +#define PCM_HPOUT_SHIFT (0) /* Bits 0-15: Transmit data register */ +#define PCM_HPOUT_MASK (0xffff << PCM_HPOUT_SHIFT) + +/* HPINn registers, addresses 0x15000024 to 0x15000038 (two per slot) */ + +#define PCM_HPIN_SHIFT (0) /* Bits 0-15: Receive data register */ +#define PCM_HPIN_MASK (0xffff << PCM_HPIN_SHIFT) + +/* CNTL2 register, address 0x1500003c */ + +#define PCM_CNTL2_SLOTDIRINV_SHIFT (0) /* Bits 0-11: PCM A/B port configuration, one per slot */ +#define PCM_CNTL2_SLOTDIRINV_MASK (0xfff << PCM_CNTL2_SLOTDIRINV_SHIFT) +# define PCM_CNTL2_SLOTDIRINV0 (0x001 << PCM_CNTL2_SLOTDIRINV_SHIFT) +# define PCM_CNTL2_SLOTDIRINV1 (0x002 << PCM_CNTL2_SLOTDIRINV_SHIFT) +# define PCM_CNTL2_SLOTDIRINV2 (0x004 << PCM_CNTL2_SLOTDIRINV_SHIFT) +# define PCM_CNTL2_SLOTDIRINV3 (0x008 << PCM_CNTL2_SLOTDIRINV_SHIFT) +# define PCM_CNTL2_SLOTDIRINV4 (0x010 << PCM_CNTL2_SLOTDIRINV_SHIFT) +# define PCM_CNTL2_SLOTDIRINV5 (0x020 << PCM_CNTL2_SLOTDIRINV_SHIFT) +# define PCM_CNTL2_SLOTDIRINV6 (0x040 << PCM_CNTL2_SLOTDIRINV_SHIFT) +# define PCM_CNTL2_SLOTDIRINV7 (0x080 << PCM_CNTL2_SLOTDIRINV_SHIFT) +# define PCM_CNTL2_SLOTDIRINV8 (0x100 << PCM_CNTL2_SLOTDIRINV_SHIFT) +# define PCM_CNTL2_SLOTDIRINV9 (0x200 << PCM_CNTL2_SLOTDIRINV_SHIFT) +# define PCM_CNTL2_SLOTDIRINV10 (0x400 << PCM_CNTL2_SLOTDIRINV_SHIFT) +# define PCM_CNTL2_SLOTDIRINV11 (0x800 << PCM_CNTL2_SLOTDIRINV_SHIFT) + +/************************************************************************************************ + * Public Types + ************************************************************************************************/ + +/************************************************************************************************ + * Public Data + ************************************************************************************************/ + +/************************************************************************************************ + * Public Functions + ************************************************************************************************/ + +#endif /* __ARCH_ARM_SRC_LPC31XX_LPC31_PCM_H */ diff --git a/nuttx/arch/arm/src/lpc31xx/lpc31_pllconfig.c b/nuttx/arch/arm/src/lpc31xx/lpc31_pllconfig.c new file mode 100755 index 000000000..dba4d25b6 --- /dev/null +++ b/nuttx/arch/arm/src/lpc31xx/lpc31_pllconfig.c @@ -0,0 +1,267 @@ +/**************************************************************************** + * arch/arm/src/lpc31xx/lpc31_pllconfig.c + * + * Copyright (C) 2009-2010 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * References: + * - NXP UM10314 LPC3130/31 User manual Rev. 1.01 — 9 September 2009 + * - NXP lpc313x.cdl.drivers.zip example driver code + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name NuttX nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include + +#include + +#include "lpc31_cgudrvr.h" + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/**************************************************************************** + * Private Types + ****************************************************************************/ + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: lpc31_switchdomains + * + * Description: + * Temporarily switch the referemce clock of all domains whose selected + * input is the PLL-to-be configured . + * + ****************************************************************************/ + +static inline uint16_t +lpc31_switchdomains(const struct lpc31_pllconfig_s * const cfg) +{ + uint32_t hppll = (cfg->hppll ? CGU_SSR_HPPLL1 : CGU_SSR_HPPLL0); + uint32_t address; + uint32_t regval; + uint16_t dmnset = 0; + int i; + + /* Check each domain */ + + for (i = 0; i < CGU_NDOMAINS; i++) + { + /* Get the switch status registers (SSR) for this frequency input domain */ + + address = LPC31_CGU_SSR(i); + regval = getreg32(address); + + /* Check if the current frequency selection is the PLL-to-be-configured */ + + if ((regval & CGU_SSR_FS_MASK) == hppll) + { + /* Yes.. switch reference clock in to FFAST */ + + lpc31_selectfreqin((enum lpc31_domainid_e)i, CGU_FS_FFAST); + + /* Add the domain to the set to be restored after the PLL is configured */ + + dmnset |= (1 << i); + } + } + + return dmnset; +} + +/**************************************************************************** + * Name: lpc31_restoredomains + * + * Description: + * Restore the PLL reference clock to the domains that were temporarily + switched to FFAST by lpc31_switchdomains. + * + ****************************************************************************/ + +static inline void +lpc31_restoredomains(const struct lpc31_pllconfig_s * const cfg, + uint16_t dmnset) +{ + uint32_t finsel = (cfg->hppll ? CGU_FS_HPPLL1 : CGU_FS_HPPLL0); + int i; + + /* Check each domain */ + + for (i = 0; i < CGU_NDOMAINS; i++) + { + /* Was this one switched? */ + + if ((dmnset & (1 << i)) != 0) + { + /* Switch input reference clock to newly configured HPLL */ + + lpc31_selectfreqin((enum lpc31_domainid_e)i, finsel); + } + } +} + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: lpc31_pllconfig + * + * Description: + * Configure the PLL according to the provided selections. + * + ****************************************************************************/ + +void lpc31_pllconfig(const struct lpc31_pllconfig_s * const cfg) +{ + uint32_t pllbase; + uint16_t dmnset = 0; + + /* Switch domains connected to HPLL to FFAST */ + + dmnset = lpc31_switchdomains(cfg); + + /* Get the PLL register base address */ + + pllbase = LPC313x_CGU_HPPLL(cfg->hppll); + + /* Disable clock, disable skew enable, power down pll, (dis/en)able post + * divider, (dis/en)able pre-divider, disable free running mode, disable bandsel, + * enable up limmiter, disable bypass + */ + + putreg32(CGU_HPMODE_PD, pllbase + LPC31_CGU_HPMODE_OFFSET); + + /* Select PLL input frequency source */ + + putreg32(cfg->finsel, pllbase + LPC31_CGU_HPFINSEL_OFFSET); + + /* Set M divider */ + + putreg32(cfg->mdec & CGU_HPMDEC_MASK, pllbase + LPC31_CGU_HPMDEC_OFFSET); + + /* Set N divider */ + + putreg32(cfg->ndec & CGU_HPNDEC_MASK, pllbase + LPC31_CGU_HPNDEC_OFFSET); + + /* Set P divider */ + + putreg32(cfg->pdec & CGU_HPPDEC_MASK, pllbase + LPC31_CGU_HPPDEC_OFFSET); + + /* Set bandwidth */ + + putreg32(cfg->selr, pllbase + LPC31_CGU_HPSELR_OFFSET); + putreg32(cfg->seli, pllbase + LPC31_CGU_HPSELI_OFFSET); + putreg32(cfg->selp, pllbase + LPC31_CGU_HPSELP_OFFSET); + + /* Power up pll */ + + putreg32((cfg->mode & ~CGU_HPMODE_PD) | CGU_HPMODE_CLKEN, pllbase + LPC31_CGU_HPMODE_OFFSET); + + /* Save the estimated freq in driver data for future clk calcs */ + + g_boardfreqin[CGU_FREQIN_HPPLL0 + cfg->hppll] = cfg->freq; + + /* Wait for PLL to lock */ + + while ((getreg32(pllbase + LPC31_CGU_HPSTATUS_OFFSET) & CGU_HPSTATUS_LOCK) == 0); + + /* Switch the domains that were temporarily switched to FFAST back to the HPPLL */ + + lpc31_restoredomains(cfg, dmnset); +} + +/************************************************************************ + * Name: lpc31_hp0pllconfig + * + * Description: + * Configure the HP0 PLL according to the board.h selections. + * + ************************************************************************/ + +void lpc31_hp0pllconfig(void) +{ + struct lpc31_pllconfig_s cfg = + { + .hppll = CGU_HP0PLL, + .finsel = BOARD_HPLL0_FINSEL, + .ndec = BOARD_HPLL0_NDEC, + .mdec = BOARD_HPLL0_MDEC, + .pdec = BOARD_HPLL0_PDEC, + .selr = BOARD_HPLL0_SELR, + .seli = BOARD_HPLL0_SELI, + .selp = BOARD_HPLL0_SELP, + .mode = BOARD_HPLL0_MODE, + .freq = BOARD_HPLL0_FREQ + }; + + lpc31_pllconfig(&cfg); +} + +/************************************************************************ + * Name: lpc31_hp1pllconfig + * + * Description: + * Configure the HP1 PLL according to the board.h selections. + * + ************************************************************************/ + +void lpc31_hp1pllconfig(void) +{ + struct lpc31_pllconfig_s cfg = + { + .hppll = CGU_HP1PLL, + .finsel = BOARD_HPLL1_FINSEL, + .ndec = BOARD_HPLL1_NDEC, + .mdec = BOARD_HPLL1_MDEC, + .pdec = BOARD_HPLL1_PDEC, + .selr = BOARD_HPLL1_SELR, + .seli = BOARD_HPLL1_SELI, + .selp = BOARD_HPLL1_SELP, + .mode = BOARD_HPLL1_MODE, + .freq = BOARD_HPLL1_FREQ + }; + + lpc31_pllconfig(&cfg); +} + diff --git a/nuttx/arch/arm/src/lpc31xx/lpc31_pwm.h b/nuttx/arch/arm/src/lpc31xx/lpc31_pwm.h new file mode 100755 index 000000000..9263c99d3 --- /dev/null +++ b/nuttx/arch/arm/src/lpc31xx/lpc31_pwm.h @@ -0,0 +1,97 @@ +/************************************************************************************************ + * arch/arm/src/lpc31xx/lpc31_pwm.h + * + * Copyright (C) 2009-2010 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * 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_LPC31XX_LPC31_PWM_H +#define __ARCH_ARM_SRC_LPC31XX_LPC31_PWM_H + +/************************************************************************************************ + * Included Files + ************************************************************************************************/ + +#include +#include "lpc31_memorymap.h" + +/************************************************************************************************ + * Pre-processor Definitions + ************************************************************************************************/ + +/* PWM register base address offset into the APB1 domain ****************************************/ + +#define LPC31_PWM_VBASE (LPC31_APB1_VADDR+LPC31_APB1_PWM_OFFSET) +#define LPC31_PWM_PBASE (LPC31_APB1_PADDR+LPC31_APB1_PWM_OFFSET) + +/* PWM register offsets (with respect to the PWM base) ******************************************/ + +#define LPC31_PWM_TMR_OFFSET 0x000 /* Timer Register */ +#define LPC31_PWM_CNTL_OFFSET 0x004 /* Control Register */ + +/* PWM register (virtual) addresses *************************************************************/ + +#define LPC31_PWM_TMR (LPC31_PWM_VBASE+LPC31_PWM_TMR_OFFSET) +#define LPC31_PWM_CNTL (LPC31_PWM_VBASE+LPC31_PWM_CNTL_OFFSET) + +/* PWM register bit definitions *****************************************************************/ + +/* Timer register TMR, address 0x13009000 */ + +#define PWM_TMR_SHIFT (0) /* Bits 0-11: Timer used for PWM and PDM */ +#define PWM_TMR_MASK (0xfff << PWM_TMR_SHIFT) + +/* Control register CNTL, address 0x13009004 */ + +#define PWM_CNTL_PDM (1 << 7) /* Bit 7: PDM Select PDM mode */ +#define PWM_CNTL_LOOP (1 << 6) /* Bit 6: Output inverted with top 4 TMR bits */ +#define PWM_CNTL_HI (1 << 4) /* Bit 4: PWM output forced high */ + /* Bits 2-3: Reserved */ +#define PWM_CNTL_CLK_SHIFT (0) /* Bits 0-1: Configure PWM_CLK for output pulses */ +#define PWM_CNTL_CLK_MASK (3 << PWM_CNTL_CLK_SHIFT) +# define PWM_CNTL_CLKDIV1 (0 << PWM_CNTL_CLK_SHIFT) /* PWM_CLK */ +# define PWM_CNTL_CLKDIV2 (1 << PWM_CNTL_CLK_SHIFT) /* PWM_CLK/2 */ +# define PWM_CNTL_CLKDIV4 (2 << PWM_CNTL_CLK_SHIFT) /* PWM_CLK/4 */ +# define PWM_CNTL_CLKDIV8 (3 << PWM_CNTL_CLK_SHIFT) /* PWM_CLK/8 */ + +/************************************************************************************************ + * Public Types + ************************************************************************************************/ + +/************************************************************************************************ + * Public Data + ************************************************************************************************/ + +/************************************************************************************************ + * Public Functions + ************************************************************************************************/ + +#endif /* __ARCH_ARM_SRC_LPC31XX_LPC31_PWM_H */ diff --git a/nuttx/arch/arm/src/lpc31xx/lpc31_resetclks.c b/nuttx/arch/arm/src/lpc31xx/lpc31_resetclks.c new file mode 100755 index 000000000..0f24957f0 --- /dev/null +++ b/nuttx/arch/arm/src/lpc31xx/lpc31_resetclks.c @@ -0,0 +1,151 @@ +/**************************************************************************** + * arch/arm/src/lpc31xx/lpc31_resetclks.c + * + * Copyright (C) 2009 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name NuttX nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include + +#include + +#include "lpc31_cgudrvr.h" + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +/**************************************************************************** + * Public Data + ****************************************************************************/ + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: lpc31_resetclks + * + * Description: + * Put all clocks into a known, initial state + * + ****************************************************************************/ + +void lpc31_resetclks(void) +{ + uint32_t regaddr; + uint32_t regval; + int bcrndx; + int esrndx; + int i; + + /* Switch all domain reference clocks to FFAST */ + + for (i = 0; i < CGU_NDOMAINS; i++) + { + /* Switch reference clock in to FFAST */ + + lpc31_selectfreqin((enum lpc31_domainid_e)i, CGU_FS_FFAST); + + /* Check if the domain has a BCR */ + + bcrndx = lpc31_bcrndx((enum lpc31_domainid_e)i); + if (bcrndx != BCRNDX_INVALID) + { + /* Yes.. disable all BCRs */ + + putreg32(0, LPC31_CGU_BCR(bcrndx)); + } + } + + /* Disable all clocks except those that are necessary */ + + for (i = CLKID_FIRST; i <= CLKID_LAST; i++) + { + /* Check if this clock has an ESR register */ + + esrndx = lpc31_esrndx((enum lpc31_clockid_e)i); + if (esrndx != ESRNDX_INVALID) + { + /* Yes.. Clear the clocks ESR to deselect fractional divider */ + + putreg32(0, LPC31_CGU_ESR(esrndx)); + } + + /* Enable external enabling for all possible clocks to conserve power */ + + lpc31_enableexten((enum lpc31_clockid_e)i); + + /* Set enable-out's for only the following clocks */ + + regaddr = LPC31_CGU_PCR(i); + regval = getreg32(regaddr); + if (i == (int)CLKID_ARM926BUSIFCLK || i == (int)CLKID_MPMCCFGCLK) + { + regval |= CGU_PCR_ENOUTEN; + } + else + { + regval &= ~CGU_PCR_ENOUTEN; + } + putreg32(regval, regaddr); + + /* Set/clear the RUN bit in the PCR regiser of all clocks, depending + * upon if the clock is needed by the board logic or not + */ + + (void)lpc31_defclk((enum lpc31_clockid_e)i); + } + + /* Disable all fractional dividers */ + + for (i = 0; i < CGU_NFRACDIV; i++) + { + regaddr = LPC31_CGU_FDC(i); + regval = getreg32(regaddr); + regval &= ~CGU_FDC_RUN; + putreg32(regval, regaddr); + } +} diff --git a/nuttx/arch/arm/src/lpc31xx/lpc31_rng.h b/nuttx/arch/arm/src/lpc31xx/lpc31_rng.h new file mode 100755 index 000000000..585a4b497 --- /dev/null +++ b/nuttx/arch/arm/src/lpc31xx/lpc31_rng.h @@ -0,0 +1,85 @@ +/************************************************************************************************ + * arch/arm/src/lpc31xx/lpc31_rng.h + * + * Copyright (C) 2009-2010 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * 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_LPC31XX_LPC31_RNG_H +#define __ARCH_ARM_SRC_LPC31XX_LPC31_RNG_H + +/************************************************************************************************ + * Included Files + ************************************************************************************************/ + +#include +#include "lpc31_memorymap.h" + +/************************************************************************************************ + * Pre-processor Definitions + ************************************************************************************************/ + +/* RNG register base address offset into the APB0 domain ****************************************/ + +#define LPC31_RNG_VBASE (LPC31_APB0_VADDR+LPC31_APB0_RNG_OFFSET) +#define LPC31_RNG_PBASE (LPC31_APB0_PADDR+LPC31_APB0_RNG_OFFSET) + +/* RNG register offsets (with respect to the RNG base) ******************************************/ + +#define LPC31_RNG_RAND_OFFSET 0x0000 /* Random number */ +#define LPC31_RNG_PWRDWN_OFFSET 0x0ff4 /* Power-down mode */ + +/* RNG register (virtual) addresses *************************************************************/ + +#define LPC31_RNG_RAND (LPC31_RNG_VBASE+LPC31_RNG_RAND_OFFSET) +#define LPC31_RNG_PWRDWN (LPC31_RNG_VBASE+LPC31_RNG_PWRDWN_OFFSET) + +/* RNG register bit definitions *****************************************************************/ + +/* POWERDOWN, address 0x13006ff4 */ + +#define RNG_PWRDWN_PWRDWN (1 << 2) /* Block all accesses to standard registers */ +#define RNG_PWRDWN_FORCERST (1 << 1) /* With SOFTRST forces immediate RNG reset */ +#define RNG_PWRDWN_SOFTRST (1 << 0) /* Software RNG reset (delayed) */ + +/************************************************************************************************ + * Public Types + ************************************************************************************************/ + +/************************************************************************************************ + * Public Data + ************************************************************************************************/ + +/************************************************************************************************ + * Public Functions + ************************************************************************************************/ + +#endif /* __ARCH_ARM_SRC_LPC31XX_LPC31_RNG_H */ diff --git a/nuttx/arch/arm/src/lpc31xx/lpc31_serial.c b/nuttx/arch/arm/src/lpc31xx/lpc31_serial.c new file mode 100755 index 000000000..ceb15d6a2 --- /dev/null +++ b/nuttx/arch/arm/src/lpc31xx/lpc31_serial.c @@ -0,0 +1,856 @@ +/**************************************************************************** + * arch/arm/src/lpc31xx/lpc31_serial.c + * + * Copyright (C) 2009 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name NuttX nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include +#include +#include +#include +#include +#include +#include + +#include +#include +#include +#include + +#include "up_arch.h" +#include "os_internal.h" +#include "up_internal.h" + +#include "lpc31_cgudrvr.h" +#include "lpc31_uart.h" + +#ifdef CONFIG_USE_SERIALDRIVER + +/**************************************************************************** + * Definitions + ****************************************************************************/ + +/**************************************************************************** + * Private Types + ****************************************************************************/ + +struct up_dev_s +{ + uint8_t ier; /* Saved IER value */ +}; + +/**************************************************************************** + * Private Function Prototypes + ****************************************************************************/ + +static inline void up_disableuartint(struct up_dev_s *priv, uint8_t *ier); +static inline void up_restoreuartint(struct up_dev_s *priv, uint8_t ier); +static inline void up_enablebreaks(void); +static inline void up_disablebreaks(void); +static inline void up_configbaud(void); + +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_rxbuffer[CONFIG_UART_RXBUFSIZE]; +static char g_txbuffer[CONFIG_UART_TXBUFSIZE]; + +/* This describes the state of the single LPC313XX uart port. */ + +static struct up_dev_s g_uartpriv; +static uart_dev_t g_uartport = +{ + .recv = + { + .size = CONFIG_UART_RXBUFSIZE, + .buffer = g_rxbuffer, + }, + .xmit = + { + .size = CONFIG_UART_TXBUFSIZE, + .buffer = g_txbuffer, + }, + .ops = &g_uart_ops, + .priv = &g_uartpriv, +}; + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: up_disableuartint + ****************************************************************************/ + +static inline void up_disableuartint(struct up_dev_s *priv, uint8_t *ier) +{ + if (ier) + { + *ier = priv->ier & UART_IER_ALLINTS; + } + + priv->ier &= ~UART_IER_ALLINTS; + putreg32((uint32_t)priv->ier, LPC31_UART_IER); +} + +/**************************************************************************** + * Name: up_restoreuartint + ****************************************************************************/ + +static inline void up_restoreuartint(struct up_dev_s *priv, uint8_t ier) +{ + priv->ier |= ier & UART_IER_ALLINTS; + putreg32((uint32_t)priv->ier, LPC31_UART_IER); +} + +/**************************************************************************** + * Name: up_enablebreaks + ****************************************************************************/ + +static inline void up_enablebreaks(void) +{ + uint32_t lcr = getreg32(LPC31_UART_LCR); + lcr |= UART_LCR_BRKCTRL; + putreg32(lcr, LPC31_UART_LCR); +} + +/**************************************************************************** + * Name: up_disablebreaks + ****************************************************************************/ + +static inline void up_disablebreaks(void) +{ + uint32_t lcr = getreg32(LPC31_UART_LCR); + lcr &= ~UART_LCR_BRKCTRL; + putreg32(lcr, LPC31_UART_LCR); +} + +/**************************************************************************** + * Name: up_configbaud + ****************************************************************************/ + +static inline void up_configbaud(void) +{ + /* 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_LPC31_UART_MULVAL + uint32_t qtrclk; + uint32_t regval; + + /* 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 = lpc31_clkfreq(CLKID_UARTUCLK, DOMAINID_UART) >> 4; + + /* 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 + (CONFIG_UART_BAUD>>1)) / CONFIG_UART_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 <= CONFIG_UART_BAUD) + { + terr = CONFIG_UART_BAUD - actualbaud; + } + else + { + terr = actualbaud - CONFIG_UART_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; + } + } + } + } + + /* Set the Divisor Latch Access Bit (DLAB) to enable DLL/DLM access */ + + regval = getreg32(LPC31_UART_LCR); + regval |= UART_LCR_DLAB; + putreg32(regval, LPC31_UART_LCR); + + /* Configure the MS and LS DLAB registers */ + + putreg32(div & UART_DLL_MASK, LPC31_UART_DLL); + putreg32((div >> 8) & UART_DLL_MASK, LPC31_UART_DLM); + + regval &= ~UART_LCR_DLAB; + putreg32(regval, LPC31_UART_LCR); + + /* Configure the Fractional Divider Register (FDR) */ + + putreg32((mulval << UART_FDR_MULVAL_SHIFT) | + (divaddval << UART_FDR_DIVADDVAL_SHIFT), + LPC31_UART_FDR); +#else + /* Set the Divisor Latch Access Bit (DLAB) to enable DLL/DLM access */ + + regval = getreg32(LPC31_UART_LCR); + regval |= UART_LCR_DLAB; + putreg32(regval, LPC31_UART_LCR); + + /* Configure the MS and LS DLAB registers */ + + putreg32(CONFIG_LPC31_UART_DIVISOR & UART_DLL_MASK, LPC31_UART_DLL); + putreg32((CONFIG_LPC31_UART_DIVISOR >> 8) & UART_DLL_MASK, LPC31_UART_DLM); + + regval &= ~UART_LCR_DLAB; + putreg32(regval, LPC31_UART_LCR); + + /* Configure the Fractional Divider Register (FDR) */ + + putreg32((CONFIG_LPC31_UART_MULVAL << UART_FDR_MULVAL_SHIFT) | + (CONFIG_LPC31_UART_DIVADDVAL << UART_FDR_DIVADDVAL_SHIFT), + LPC31_UART_FDR); +#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_LPC31_UART_CONFIG + struct up_dev_s *priv = (struct up_dev_s*)dev->priv; + uint32_t regval; + + /* Clear fifos */ + + putreg32((UART_FCR_RXFIFORST|UART_FCR_TXFIFORST), LPC31_UART_FCR); + + /* Set trigger */ + + putreg32((UART_FCR_FIFOENABLE|UART_FCR_RXTRIGLEVEL_16), LPC31_UART_FCR); + + /* Set up the IER */ + + priv->ier = getreg32(LPC31_UART_IER); + + /* Set up the LCR */ + + regval = 0; + +#if CONFIG_UART_BITS == 5 + regval |= UART_LCR_WDLENSEL_5BITS; +#elif CONFIG_UART_BITS == 6 + regval |= UART_LCR_WDLENSEL_6BITS; +#elif CONFIG_UART_BITS == 7 + regval |= UART_LCR_WDLENSEL_7BITS; +#else + regval |= UART_LCR_WDLENSEL_8BITS; +#endif + +#if CONFIG_UART_2STOP > 0 + regval |= UART_LCR_NSTOPBITS; +#endif + +#if CONFIG_UART_PARITY == 1 + regval |= UART_LCR_PAREN; +#elif CONFIG_UART_PARITY == 2 + regval |= (UART_LCR_PAREVEN|UART_LCR_PAREN); +#endif + putreg32(regval, LPC31_UART_LCR); + + /* Set the BAUD divisor */ + + up_configbaud(); + + /* Configure the FIFOs */ + + putreg32((UART_FCR_RXTRIGLEVEL_16|UART_FCR_TXFIFORST| + UART_FCR_RXFIFORST|UART_FCR_FIFOENABLE), + LPC31_UART_FCR); + + /* The NuttX serial driver waits for the first THRE interrrupt before + * sending serial data... However, it appears that the lpc313x hardware + * 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. + */ + + putreg32('\0', LPC31_UART_THR); +#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 + * he the setup() method is called, however, the serial console may operate in + * 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 + * and TX interrupts are not enabled until the txint() and rxint() methods + * are called. + * + ****************************************************************************/ + +static int up_attach(struct uart_dev_s *dev) +{ + int ret; + + /* Attach and enable the IRQ */ + + ret = irq_attach(LPC31_IRQ_UART, up_interrupt); + if (ret == OK) + { + /* Enable the interrupt (RX and TX interrupts are still disabled + * in the UART + */ + + up_enable_irq(LPC31_IRQ_UART); + } + 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) +{ + up_disable_irq(LPC31_IRQ_UART); + irq_detach(LPC31_IRQ_UART); +} + +/**************************************************************************** + * Name: up_interrupt + * + * Description: + * This is the UART interrupt handler. It will be invoked when an + * interrupt received on the UART irq. It should call uart_transmitchars + * or uart_receivechar to perform the appropriate data transfers. + * + ****************************************************************************/ + +static int up_interrupt(int irq, void *context) +{ + struct uart_dev_s *dev = &g_uartport; + uint8_t status; + int passes; + + /* 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 = getreg32(LPC31_UART_IIR); + + /* The NO INTERRUPT should be zero if there are pending + * interrupts + */ + + if ((status & UART_IIR_NOINT) != 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 & UART_IIR_INTID_MASK) + { + /* Handle incoming, receive bytes (with or without timeout) */ + + case UART_IIR_INTID_RDA: /* Received Data Available */ + case UART_IIR_INTID_TIMEOUT: /* Character time-out */ + { + uart_recvchars(dev); + break; + } + + /* Handle outgoing, transmit bytes */ + + case UART_IIR_INTID_THRE: /* Transmitter Holding Register empty */ + { + uart_xmitchars(dev); + break; + } + + /* Just clear modem status interrupts */ + + case UART_IIR_INTID_MS: /* Modem status */ + { + /* Read the modem status register (MSR) to clear */ + + status = getreg32(LPC31_UART_MSR); + fvdbg("MSR: %02x\n", status); + break; + } + + /* Just clear any line status interrupts */ + + case UART_IIR_INTID_RLS: /* Receiver Line Status */ + { + /* Read the line status register (LSR) to clear */ + + status = getreg32(LPC31_UART_LSR); + fvdbg("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; + int ret = OK; + + switch (cmd) + { + case TIOCSERGSTRUCT: + { + struct up_dev_s *user = (struct up_dev_s*)arg; + if (!user) + { + ret = -EINVAL; + } + else + { + memcpy(user, dev, sizeof(struct up_dev_s)); + } + } + break; + + case TIOCSBRK: /* BSD compatibility: Turn break on, unconditionally */ + { + irqstate_t flags = irqsave(); + up_enablebreaks(); + irqrestore(flags); + } + break; + + case TIOCCBRK: /* BSD compatibility: Turn break off, unconditionally */ + { + irqstate_t flags; + flags = irqsave(); + up_disablebreaks(); + irqrestore(flags); + } + break; + + default: + errno = 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) +{ + uint32_t rbr; + + *status = getreg32(LPC31_UART_LSR); + rbr = getreg32(LPC31_UART_RBR); + return rbr & 0xff; +} + +/**************************************************************************** + * 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 |= UART_IER_RDAINTEN; +#endif + } + else + { + priv->ier &= ~UART_IER_RDAINTEN; + } + putreg32(priv->ier, LPC31_UART_IER); +} + +/**************************************************************************** + * Name: up_rxavailable + * + * Description: + * Return true if the receive fifo is not empty + * + ****************************************************************************/ + +static bool up_rxavailable(struct uart_dev_s *dev) +{ + return ((getreg32(LPC31_UART_LSR) & UART_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) +{ + putreg32((uint32_t)ch, LPC31_UART_THR); +} + +/**************************************************************************** + * 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 |= UART_IER_THREINTEN; +#endif + } + else + { + priv->ier &= ~UART_IER_THREINTEN; + } + putreg32(priv->ier, LPC31_UART_IER); +} + +/**************************************************************************** + * Name: up_txready + * + * Description: + * Return true if the tranmsit fifo is not full + * + ****************************************************************************/ + +static bool up_txready(struct uart_dev_s *dev) +{ + return ((getreg32(LPC31_UART_LSR) & UART_LSR_THRE) != 0); +} + +/**************************************************************************** + * Name: up_txempty + * + * Description: + * Return true if the transmit fifo is empty + * + ****************************************************************************/ + +static bool up_txempty(struct uart_dev_s *dev) +{ + return ((getreg32(LPC31_UART_LSR) & UART_LSR_TEMT) != 0); +} + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: up_earlyserialinit + * + * Description: + * Performs the low level UART initialization early in debug so that the + * serial console will be available during bootup (via up_putc). This must + * be called before up_serialinit. + * + ****************************************************************************/ + +void up_earlyserialinit(void) +{ + /* Enable UART system clock */ + + lpc31_enableclock(CLKID_UARTAPBCLK); + lpc31_enableclock(CLKID_UARTUCLK); + + /* Disable UART interrupts */ + + up_disableuartint(g_uartport.priv, NULL); + + /* Configuration the serial console */ + +#if defined(CONFIG_UART_SERIAL_CONSOLE) + g_uartport.isconsole = true; + up_setup(&g_uartport); +#endif +} + +/**************************************************************************** + * Name: up_serialinit + * + * Description: + * Register serial console and serial ports. This assumes that + * up_earlyserialinit was called previously. + * + ****************************************************************************/ + +void up_serialinit(void) +{ +#if defined(CONFIG_UART_SERIAL_CONSOLE) + (void)uart_register("/dev/console", &g_uartport); +#endif + (void)uart_register("/dev/ttyS0", &g_uartport); +} + +/**************************************************************************** + * Name: up_putc + * + * Description: + * Provide priority, low-level access to support OS debug writes + * + ****************************************************************************/ + +int up_putc(int ch) +{ + struct up_dev_s *priv = &g_uartpriv; + uint8_t ier; + + /* Keep UART interrupts disabled so that we do not interfere with the + * serial driver. + */ + + up_disableuartint(priv, &ier); + + /* Check for LF */ + + if (ch == '\n') + { + /* Add CR */ + + up_lowputc('\r'); + } + + /* Output the character */ + + up_lowputc(ch); + 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'); + } + + /* Output the character */ + + up_lowputc(ch); + return ch; +} + +#endif /* CONFIG_USE_SERIALDRIVER */ diff --git a/nuttx/arch/arm/src/lpc31xx/lpc31_setfdiv.c b/nuttx/arch/arm/src/lpc31xx/lpc31_setfdiv.c new file mode 100755 index 000000000..4ed1d855a --- /dev/null +++ b/nuttx/arch/arm/src/lpc31xx/lpc31_setfdiv.c @@ -0,0 +1,135 @@ +/**************************************************************************** + * arch/arm/src/lpc31xx/lpc31_setfdiv.c + * + * Copyright (C) 2009-2010 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name NuttX nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include + +#include + +#include "lpc31_cgu.h" +#include "lpc31_cgudrvr.h" + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +/**************************************************************************** + * Public Data + ****************************************************************************/ + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: lpc31_setfdiv + * + * Description: + * Set/reset subdomain frequency containing the specified clock using the + * provided divider settings + * + ****************************************************************************/ + +void lpc31_setfdiv(enum lpc31_domainid_e dmnid, + enum lpc31_clockid_e clkid, + const struct lpc31_fdivconfig_s *fdiv) +{ + uint32_t regaddr; + unsigned int basefreq; + int fdcndx; + int bcrndx; + + /* Get the frequency divider associated with this clock */ + + fdcndx = lpc31_fdcndx(clkid, dmnid); + + /* Does this clock have a frequency divicer? */ + + if (fdcndx != FDCNDX_INVALID) + { + /* Yes.. Save the current reference frequency selection */ + + regaddr = LPC31_CGU_SSR((int)dmnid); + basefreq = (getreg32(regaddr) & CGU_SSR_FS_MASK) >> CGU_SSR_FS_SHIFT; + + /* Switch domain to FFAST input */ + + lpc31_selectfreqin(dmnid, CGU_FS_FFAST); + + /* Get the index of the associated BCR register. Does this domain + * have a BCR? + */ + + bcrndx = lpc31_bcrndx(dmnid); + if (bcrndx != BCRNDX_INVALID) + { + + /* Yes... Disable the BCR */ + + regaddr = LPC31_CGU_BCR(bcrndx); + putreg32(0, regaddr); + } + + /* Change fractional divider to the provided settings */ + + lpc31_fdivinit(fdcndx, fdiv, true); + + /* Re-enable the BCR (if one is associated with this domain) */ + + if (bcrndx != BCRNDX_INVALID) + { + regaddr = LPC31_CGU_BCR(bcrndx); + putreg32(CGU_BCR_FDRUN, regaddr); + } + + /* Switch the domain back to its original base frequency */ + + lpc31_selectfreqin(dmnid, basefreq); + } +} diff --git a/nuttx/arch/arm/src/lpc31xx/lpc31_setfreqin.c b/nuttx/arch/arm/src/lpc31xx/lpc31_setfreqin.c new file mode 100755 index 000000000..b247af403 --- /dev/null +++ b/nuttx/arch/arm/src/lpc31xx/lpc31_setfreqin.c @@ -0,0 +1,119 @@ +/**************************************************************************** + * arch/arm/src/lpc31xx/lpc31_setfreqin.c + * + * Copyright (C) 2009-2010 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * References: + * - NXP UM10314 LPC3130/31 User manual Rev. 1.01 — 9 September 2009 + * - NXP lpc313x.cdl.drivers.zip example driver code + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name NuttX nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include + +#include + +#include "lpc31_cgudrvr.h" + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +/**************************************************************************** + * Public Data + ****************************************************************************/ + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: lpc31_selectfreqin + * + * Description: + * Set the base frequency source selection for with a clock domain + * + ****************************************************************************/ + +void lpc31_selectfreqin(enum lpc31_domainid_e dmnid, uint32_t finsel) +{ + uint32_t scraddr = LPC31_CGU_SCR(dmnid); + uint32_t fs1addr = LPC31_CGU_FS1(dmnid); + uint32_t fs2addr = LPC31_CGU_FS2(dmnid); + uint32_t scrbits; + + /* Get the frequency selection from the switch configuration register (SCR) + * for this domain. + */ + + scrbits = getreg32(scraddr) & ~(CGU_SCR_ENF1|CGU_SCR_ENF2); + + /* If FS1 is currently enabled set the reference clock to FS2 and enable FS2 */ + + if ((getreg32(LPC31_CGU_SSR(dmnid)) & CGU_SSR_FS1STAT) != 0) + { + /* Check if the selected frequency, FS1, is same as requested */ + + if ((getreg32(fs1addr) & CGU_FS_MASK) != finsel) + { + /* No.. Set up FS2 */ + + putreg32(finsel, fs2addr); + putreg32(scrbits | CGU_SCR_ENF2, scraddr); + } + } + + /* FS1 is not currently enabled, check if the selected frequency, FS2, + * is same as requested + */ + + else if ((getreg32(fs2addr) & CGU_FS_MASK) != finsel) + { + /* No.. Set up FS1 */ + + putreg32(finsel, fs1addr); + putreg32(scrbits | CGU_SCR_ENF1, scraddr); + } +} diff --git a/nuttx/arch/arm/src/lpc31xx/lpc31_softreset.c b/nuttx/arch/arm/src/lpc31xx/lpc31_softreset.c new file mode 100755 index 000000000..8bf9ef12a --- /dev/null +++ b/nuttx/arch/arm/src/lpc31xx/lpc31_softreset.c @@ -0,0 +1,90 @@ +/************************************************************************ + * arch/arm/src/lpc31xx/lpc31_softreset.c + * + * Copyright (C) 2009 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * References: + * - UM10314 LPC3130/31 User manual Rev. 1.01 — 9 September 2009 + * - lpc313x.cdl.drivers.zip example driver code + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name NuttX nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ************************************************************************/ + +/************************************************************************ + * Included Files + ************************************************************************/ + +#include +#include + +#include "up_arch.h" +#include "lpc31_cgudrvr.h" + +/************************************************************************ + * Pre-processor Definitions + ************************************************************************/ + +/************************************************************************ + * Private Data + ************************************************************************/ + +/************************************************************************ + * Private Functions + ************************************************************************/ + +/************************************************************************ + * Public Functions + ************************************************************************/ + +/************************************************************************ + * Name: lpc31_softreset + * + * Description: + * Perform a soft reset on the specified module. + * + ************************************************************************/ + +void lpc31_softreset(enum lpc31_resetid_e resetid) +{ + uint32_t address = LPC31_CGU_SOFTRST(resetid); + volatile int i; + + /* Clear and set the register */ + + putreg32(0, address); + + /* Delay a bit */ + + for (i = 0;i < 1000; i++); + + /* Then set the the soft reset bit */ + + putreg32(CGU_SOFTRESET, address); +} diff --git a/nuttx/arch/arm/src/lpc31xx/lpc31_spi.c b/nuttx/arch/arm/src/lpc31xx/lpc31_spi.c new file mode 100644 index 000000000..5667ba95d --- /dev/null +++ b/nuttx/arch/arm/src/lpc31xx/lpc31_spi.c @@ -0,0 +1,971 @@ +/************************************************************************************ + * arm/arm/src/lpc31xx/lpc31_spi.c + * + * Copyright (C) 2009-2010 Gregory Nutt. All rights reserved. + * Author: David Hewson, deriving in part from other SPI drivers originally by + * Gregory Nutt + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name NuttX nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ************************************************************************************/ + +/************************************************************************************ + * Included Files + ************************************************************************************/ + +#include + +#include +#include +#include +#include +#include +#include + +#include +#include + +#include + +#include "lpc31_spi.h" +#include "lpc31_ioconfig.h" + +/************************************************************************************ + * Definitions + ************************************************************************************/ + +/* Configuration ********************************************************************/ + +/* Debug ****************************************************************************/ +/* Define the following to enable extremely detailed register debug */ + +#undef CONFIG_DEBUG_SPIREGS + +/* CONFIG_DEBUG must also be defined */ + +#ifndef CONFIG_DEBUG +# undef CONFIG_DEBUG_SPIREGS +#endif + +/* FIFOs ****************************************************************************/ + +#define SPI_FIFO_DEPTH 64 /* 64 words deep (8- or 16-bit words) */ + +/* Timing ***************************************************************************/ + +#define SPI_MAX_DIVIDER 65024 /* = 254 * (255 + 1) */ +#define SPI_MIN_DIVIDER 2 + +/************************************************************************************ + * Private Types + ************************************************************************************/ + +struct lpc31_spidev_s +{ + struct spi_dev_s spidev; /* Externally visible part of the SPI interface */ + sem_t exclsem; /* Held while chip is selected for mutual exclusion */ + uint32_t frequency; /* Requested clock frequency */ + uint32_t actual; /* Actual clock frequency */ + uint8_t nbits; /* Width of work in bits (8 or 16) */ + uint8_t mode; /* Mode 0,1,2,3 */ + + uint32_t slv1; + uint32_t slv2; +}; + +/************************************************************************************ + * Private Function Prototypes + ************************************************************************************/ + +#ifdef CONFIG_DEBUG_SPIREGS +static bool spi_checkreg(bool wr, uint32_t value, uint32_t address); +static void spi_putreg(uint32_t value, uint32_t address); +static uint32_t spi_getreg(uint32_t address); +#else +# define spi_putreg(v,a) putreg32(v,a) +# define spi_getreg(a) getreg32(a) +#endif + +static inline void spi_drive_cs(FAR struct lpc31_spidev_s *priv, uint8_t slave, uint8_t val); +static inline void spi_select_slave(FAR struct lpc31_spidev_s *priv, uint8_t slave); +static inline uint16_t spi_readword(FAR struct lpc31_spidev_s *priv); +static inline void spi_writeword(FAR struct lpc31_spidev_s *priv, uint16_t word); + +static int spi_lock(FAR struct spi_dev_s *dev, bool lock); +static void spi_select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected); +static uint32_t spi_setfrequency(FAR struct spi_dev_s *dev, uint32_t frequency); +static void spi_setmode(FAR struct spi_dev_s *dev, enum spi_mode_e mode); +static void spi_setbits(FAR struct spi_dev_s *dev, int nbits); +static uint8_t spi_status(FAR struct spi_dev_s *dev, enum spi_dev_e devid); +static uint16_t spi_send(FAR struct spi_dev_s *dev, uint16_t word); +static void spi_exchange(FAR struct spi_dev_s *dev, FAR const void *txbuffer, + FAR void *rxbuffer, size_t nwords); +#ifndef CONFIG_SPI_EXCHANGE +static void spi_sndblock(FAR struct spi_dev_s *dev, FAR const void *txbuffer, + size_t nwords); +static void spi_recvblock(FAR struct spi_dev_s *dev, FAR void *rxbuffer, + size_t nwords); +#endif + + +/************************************************************************************ + * Private Data + ************************************************************************************/ + +static const struct spi_ops_s g_spiops = +{ + .lock = spi_lock, + .select = spi_select, + .setfrequency = spi_setfrequency, + .setmode = spi_setmode, + .setbits = spi_setbits, + .status = spi_status, +#ifdef CONFIG_SPI_CMDDATA + .cmddata = lpc31_spicmddata, +#endif + .send = spi_send, +#ifdef CONFIG_SPI_EXCHANGE + .exchange = spi_exchange, +#else + .sndblock = spi_sndblock, + .recvblock = spi_recvblock, +#endif + .registercallback = 0, +}; + +static struct lpc31_spidev_s g_spidev = +{ + .spidev = { &g_spiops }, +}; + +#ifdef CONFIG_DEBUG_SPIREGS +static bool g_wrlast; +static uint32_t g_addresslast; +static uint32_t g_valuelast; +static int g_ntimes; +#endif + +/************************************************************************************ + * Public Data + ************************************************************************************/ + +/************************************************************************************ + * Private Functions + ************************************************************************************/ + +/**************************************************************************** + * Name: spi_checkreg + * + * Description: + * Check if the current register access is a duplicate of the preceding. + * + * Input Parameters: + * value - The value to be written + * address - The address of the register to write to + * + * Returned Value: + * true: This is the first register access of this type. + * flase: This is the same as the preceding register access. + * + ****************************************************************************/ + +#ifdef CONFIG_DEBUG_SPIREGS +static bool spi_checkreg(bool wr, uint32_t value, uint32_t address) +{ + if (wr == g_wrlast && value == g_valuelast && address == g_addresslast) + { + g_ntimes++; + return false; + } + else + { + if (g_ntimes > 0) + { + lldbg("...[Repeats %d times]...\n", g_ntimes); + } + + g_wrlast = wr; + g_valuelast = value; + g_addresslast = address; + g_ntimes = 0; + } + return true; +} +#endif + +/**************************************************************************** + * Name: spi_putreg + * + * Description: + * Write a 32-bit value to an SPI register + * + * Input Parameters: + * value - The value to be written + * address - The address of the register to write to + * + * Returned Value: + * None + * + ****************************************************************************/ + +#ifdef CONFIG_DEBUG_SPIREGS +static void spi_putreg(uint32_t value, uint32_t address) +{ + if (spi_checkreg(true, value, address)) + { + lldbg("%08x<-%08x\n", address, value); + } + putreg32(value, address); +} +#endif + +/**************************************************************************** + * Name: spi_getreg + * + * Description: + * Read a 32-bit value from an SPI register + * + * Input Parameters: + * address - The address of the register to read from + * + * Returned Value: + * The value read from the register + * + ****************************************************************************/ + +#ifdef CONFIG_DEBUG_SPIREGS +static uint32_t spi_getreg(uint32_t address) +{ + uint32_t value = getreg32(address); + if (spi_checkreg(false, value, address)) + { + lldbg("%08x->%08x\n", address, value); + } + return value; +} +#endif + +/**************************************************************************** + * Name: spi_drive_cs + * + * Description: + * Drive the chip select signal for this slave + * + * Input Parameters: + * dev - Device-specific state data + * slave - slave id + * value - value (0 for assert) + * + * Returned Value: + * None + * + ****************************************************************************/ + +static inline void spi_drive_cs(FAR struct lpc31_spidev_s *priv, uint8_t slave, uint8_t val) +{ + switch (slave) + { + case 0: + if (val == 0) + { + spi_putreg(IOCONFIG_SPI_CSOUT0, LPC31_IOCONFIG_SPI_MODE0RESET); + } + else + { + spi_putreg(IOCONFIG_SPI_CSOUT0, LPC31_IOCONFIG_SPI_MODE0SET); + } + spi_putreg(IOCONFIG_SPI_CSOUT0, LPC31_IOCONFIG_SPI_MODE1SET); + break; + + case 1: + if (val == 0) + { + spi_putreg(IOCONFIG_EBII2STX0_MUARTCTSN, LPC31_IOCONFIG_EBII2STX0_MODE0RESET); + } + else + { + spi_putreg(IOCONFIG_EBII2STX0_MUARTCTSN, LPC31_IOCONFIG_EBII2STX0_MODE0SET); + } + spi_putreg(IOCONFIG_EBII2STX0_MUARTCTSN, LPC31_IOCONFIG_EBII2STX0_MODE1SET); + break; + + case 2: + if (val == 0) + { + spi_putreg(IOCONFIG_EBII2STX0_MUARTRTSN, LPC31_IOCONFIG_EBII2STX0_MODE0RESET); + } + else + { + spi_putreg(IOCONFIG_EBII2STX0_MUARTRTSN, LPC31_IOCONFIG_EBII2STX0_MODE0SET); + } + spi_putreg(IOCONFIG_EBII2STX0_MUARTRTSN, LPC31_IOCONFIG_EBII2STX0_MODE1SET); + break; + } +} + +/**************************************************************************** + * Name: spi_select_slave + * + * Description: + * Select the slave device for the next transfer + * + * Input Parameters: + * dev - Device-specific state data + * slave - slave id + * + * Returned Value: + * None + * + ****************************************************************************/ + +static inline void spi_select_slave(FAR struct lpc31_spidev_s *priv, uint8_t slave) +{ + switch (slave) + { + case 0: + spi_putreg(priv->slv1, LPC31_SPI_SLV0_1); + spi_putreg(priv->slv2, LPC31_SPI_SLV0_2); + spi_putreg(SPI_SLVENABLE1_ENABLED, LPC31_SPI_SLVENABLE); + break; + + case 1: + spi_putreg(priv->slv1, LPC31_SPI_SLV1_1); + spi_putreg(priv->slv2, LPC31_SPI_SLV1_2); + spi_putreg(SPI_SLVENABLE2_ENABLED, LPC31_SPI_SLVENABLE); + break; + + case 2: + spi_putreg(priv->slv1, LPC31_SPI_SLV2_1); + spi_putreg(priv->slv2, LPC31_SPI_SLV2_2); + spi_putreg(SPI_SLVENABLE3_ENABLED, LPC31_SPI_SLVENABLE); + break; + } +} + +/************************************************************************************ + * Name: spi_readword + * + * Description: + * Read one word from SPI + * + * Input Parameters: + * priv - Device-specific state data + * + * Returned Value: + * Byte as read + * + ************************************************************************************/ + +static inline uint16_t spi_readword(FAR struct lpc31_spidev_s *priv) +{ + /* Wait until the RX FIFO is not empty */ + + while ((spi_getreg(LPC31_SPI_STATUS) & SPI_STATUS_RXFIFOEMPTY) != 0); + + /* Then return the received word */ + + return (uint16_t)spi_getreg(LPC31_SPI_FIFODATA); +} + +/************************************************************************************ + * Name: spi_writeword + * + * Description: + * Write one word to SPI + * + * Input Parameters: + * priv - Device-specific state data + * word - Word to send + * + * Returned Value: + * None + * + ************************************************************************************/ + +static inline void spi_writeword(FAR struct lpc31_spidev_s *priv, uint16_t word) +{ + /* Wait until the TX FIFO is not full */ + + while ((spi_getreg(LPC31_SPI_STATUS) & SPI_STATUS_TXFIFOFULL) != 0); + + /* Then send the word */ + + spi_putreg(word, LPC31_SPI_FIFODATA); +} + +/**************************************************************************** + * Name: spi_lock + * + * Description: + * On SPI busses where there are multiple devices, it will be necessary to + * lock SPI to have exclusive access to the busses for a sequence of + * transfers. The bus should be locked before the chip is selected. After + * locking the SPI bus, the caller should then also call the setfrequency, + * setbits, and setmode methods to make sure that the SPI is properly + * configured for the device. If the SPI buss is being shared, then it + * may have been left in an incompatible state. + * + * Input Parameters: + * dev - Device-specific state data + * lock - true: Lock spi bus, false: unlock SPI bus + * + * Returned Value: + * None + * + ****************************************************************************/ + +static int spi_lock(FAR struct spi_dev_s *dev, bool lock) +{ + FAR struct lpc31_spidev_s *priv = (FAR struct lpc31_spidev_s *)dev; + + if (lock) + { + /* Take the semaphore (perhaps waiting) */ + + while (sem_wait(&priv->exclsem) != 0) + { + /* The only case that an error should occur here is if the wait was awakened + * by a signal. + */ + + ASSERT(errno == EINTR); + } + } + else + { + (void)sem_post(&priv->exclsem); + } + return OK; +} + +/**************************************************************************** + * Name: spi_select + * + * Description: + * Enable/disable the SPI slave select. The implementation of this method + * must include handshaking: If a device is selected, it must hold off + * all other attempts to select the device until the device is deselecte. + * + * Input Parameters: + * dev - Device-specific state data + * devid - Identifies the device to select + * selected - true: slave selected, false: slave de-selected + * + * Returned Value: + * None + * + ****************************************************************************/ + +static void spi_select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected) +{ + struct lpc31_spidev_s *priv = (struct lpc31_spidev_s *) dev; + uint8_t slave = 0; + + /* FIXME: map the devid to the SPI slave - this should really + * be in board specific code..... */ + switch (devid) + { + case SPIDEV_FLASH: + slave = 0; + break; + + case SPIDEV_MMCSD: + slave = 1; + break; + + case SPIDEV_ETHERNET: + slave = 2; + break; + + default: + return; + } + + /* + * Since we don't use sequential multi-slave mode, but rather + * perform the transfer piecemeal by consecutive calls to + * SPI_SEND, then we must manually assert the chip select + * across the whole transfer + */ + + if (selected) + { + spi_drive_cs(priv, slave, 0); + spi_select_slave(priv, slave); + + /* Enable SPI as master and notify of slave enables change */ + + spi_putreg((1 << SPI_CONFIG_INTERSLVDELAY_SHIFT) | SPI_CONFIG_UPDENABLE | SPI_CONFIG_SPIENABLE, LPC31_SPI_CONFIG); + } + else + { + spi_drive_cs(priv, slave, 1); + + /* Disable all slaves */ + + spi_putreg(0, LPC31_SPI_SLVENABLE); + + /* Disable SPI as master */ + + spi_putreg(SPI_CONFIG_UPDENABLE, LPC31_SPI_CONFIG); + } +} + +/************************************************************************************ + * Name: spi_setfrequency + * + * Description: + * Set the SPI frequency. + * + * Input Parameters: + * dev - Device-specific state data + * frequency - The SPI frequency requested + * + * Returned Value: + * Returns the actual frequency selected + * + ************************************************************************************/ + +static uint32_t spi_setfrequency(FAR struct spi_dev_s *dev, uint32_t frequency) +{ + FAR struct lpc31_spidev_s *priv = (FAR struct lpc31_spidev_s *)dev; + uint32_t spi_clk, div, div1, div2; + + if (priv->frequency != frequency) + { + /* The SPI clock is derived from the (main system oscillator / 2), + * so compute the best divider from that clock */ + + spi_clk = lpc31_clkfreq(CLKID_SPICLK, DOMAINID_SPI); + + /* Find closest divider to get at or under the target frequency */ + + div = (spi_clk + frequency / 2) / frequency; + + if (div > SPI_MAX_DIVIDER) + { + div = SPI_MAX_DIVIDER; + } + else if (div < SPI_MIN_DIVIDER) + { + div = SPI_MIN_DIVIDER; + } + + div2 = (((div-1) / 512) + 2) * 2; + div1 = ((((div + div2 / 2) / div2) - 1)); + + priv->slv1 = (priv->slv1 & ~(SPI_SLV_1_CLKDIV2_MASK | SPI_SLV_1_CLKDIV1_MASK)) | (div2 << SPI_SLV_1_CLKDIV2_SHIFT) | (div1 << SPI_SLV_1_CLKDIV1_SHIFT); + + priv->frequency = frequency; + priv->actual = frequency; // FIXME + } + + return priv->actual; +} + +/************************************************************************************ + * Name: spi_setmode + * + * Description: + * Set the SPI mode. see enum spi_mode_e for mode definitions + * + * Input Parameters: + * dev - Device-specific state data + * mode - The SPI mode requested + * + * Returned Value: + * Returns the actual frequency selected + * + ************************************************************************************/ + +static void spi_setmode(FAR struct spi_dev_s *dev, enum spi_mode_e mode) +{ + FAR struct lpc31_spidev_s *priv = (FAR struct lpc31_spidev_s *)dev; + uint16_t setbits; + uint16_t clrbits; + +/* Has the mode changed? */ + + if (mode != priv->mode) + { + /* Yes... Set CR1 appropriately */ + + switch (mode) + { + case SPIDEV_MODE0: /* SPO=0; SPH=0 */ + setbits = 0; + clrbits = SPI_SLV_2_SPO|SPI_SLV_2_SPH; + break; + + case SPIDEV_MODE1: /* SPO=0; SPH=1 */ + setbits = SPI_SLV_2_SPH; + clrbits = SPI_SLV_2_SPO; + break; + + case SPIDEV_MODE2: /* SPO=1; SPH=0 */ + setbits = SPI_SLV_2_SPO; + clrbits = SPI_SLV_2_SPH; + break; + + case SPIDEV_MODE3: /* SPO=1; SPH=1 */ + setbits = SPI_SLV_2_SPO|SPI_SLV_2_SPH; + clrbits = 0; + break; + + default: + return; + } + + priv->slv2 = (priv->slv2 & ~clrbits) | setbits; + priv->mode = mode; + } +} + +/************************************************************************************ + * Name: spi_setbits + * + * Description: + * Set the number of bits per word. + * + * Input Parameters: + * dev - Device-specific state data + * nbits - The number of bits requested + * + * Returned Value: + * None + * + ************************************************************************************/ + +static void spi_setbits(FAR struct spi_dev_s *dev, int nbits) +{ + FAR struct lpc31_spidev_s *priv = (FAR struct lpc31_spidev_s *)dev; + + /* Has the number of bits changed? */ + + if (nbits != priv->nbits) + { + priv->slv2 = (priv->slv2 & ~SPI_SLV_2_WDSIZE_MASK) | ((nbits-1) << SPI_SLV_2_WDSIZE_SHIFT); + priv->nbits = nbits; + } +} + +/**************************************************************************** + * Name: spi_status + * + * Description: + * Get SPI/MMC status + * + * Input Parameters: + * dev - Device-specific state data + * devid - Identifies the device to report status on + * + * Returned Value: + * Returns a bitset of status values (see SPI_STATUS_* defines + * + ****************************************************************************/ + +static uint8_t spi_status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) +{ + /* FIXME: is there anyway to determine this + * it should probably be board dependant anyway */ + + return SPI_STATUS_PRESENT; +} + +/************************************************************************************ + * Name: spi_send + * + * Description: + * Exchange one word on SPI + * + * Input Parameters: + * dev - Device-specific state data + * word - The word to send. the size of the data is determined by the + * number of bits selected for the SPI interface. + * + * Returned Value: + * response + * + ************************************************************************************/ + +static uint16_t spi_send(FAR struct spi_dev_s *dev, uint16_t word) +{ + FAR struct lpc31_spidev_s *priv = (FAR struct lpc31_spidev_s *)dev; + DEBUGASSERT(priv); + + spi_writeword(priv, word); + return spi_readword(priv); +} + +/************************************************************************* + * Name: spi_exchange + * + * Description: + * Exchange a block of data on SPI + * + * Input Parameters: + * dev - Device-specific state data + * txbuffer - A pointer to the buffer of data to be sent + * rxbuffer - A pointer to a buffer in which to receive data + * nwords - the length of data to be exchaned in units of words. + * The wordsize is determined by the number of bits-per-word + * selected for the SPI interface. If nbits <= 8, the data is + * packed into uint8_t's; if nbits >8, the data is packed into uint16_t's + * + * Returned Value: + * None + * + ************************************************************************************/ + +static void spi_exchange(FAR struct spi_dev_s *dev, FAR const void *txbuffer, + FAR void *rxbuffer, size_t nwords) +{ + FAR struct lpc31_spidev_s *priv = (FAR struct lpc31_spidev_s *)dev; + unsigned int maxtx; + unsigned int ntx; + + DEBUGASSERT(priv); + + /* 8- or 16-bit mode? */ + + if (priv->nbits == 16) + { + /* 16-bit mode */ + + const uint16_t *src = (const uint16_t*)txbuffer;; + uint16_t *dest = (uint16_t*)rxbuffer; + uint16_t word; + + while (nwords > 0) + { + /* Fill up the TX FIFO */ + + maxtx = nwords > SPI_FIFO_DEPTH ? SPI_FIFO_DEPTH : nwords; + for (ntx = 0; ntx < maxtx; ntx++) + { + /* Get the next word to write. Is there a source buffer? */ + + word = src ? *src++ : 0xffff; + + /* Then send the word */ + + spi_writeword(priv, word); + } + nwords -= maxtx; + + /* Then empty the RX FIFO */ + + while (ntx-- > 0) + { + word = spi_readword(priv); + + /* Is there a buffer to receive the return value? */ + + if (dest) + { + *dest++ = word; + } + } + } + } + else + { + /* 8-bit mode */ + + const uint8_t *src = (const uint8_t*)txbuffer;; + uint8_t *dest = (uint8_t*)rxbuffer; + uint8_t word; + + while (nwords > 0) + { + /* Fill up the TX FIFO */ + + maxtx = nwords > SPI_FIFO_DEPTH ? SPI_FIFO_DEPTH : nwords; + for (ntx = 0; ntx < maxtx; ntx++) + { + /* Get the next word to write. Is there a source buffer? */ + + word = src ? *src++ : 0xff; + + /* Then send the word */ + + spi_writeword(priv, (uint16_t)word); + } + nwords -= maxtx; + + /* Then empty the RX FIFO */ + + while (ntx-- > 0) + { + word = (uint8_t)spi_readword(priv); + + /* Is there a buffer to receive the return value? */ + + if (dest) + { + *dest++ = word; + } + } + } + } +} + +/************************************************************************* + * Name: spi_sndblock + * + * Description: + * Send a block of data on SPI + * + * Input Parameters: + * dev - Device-specific state data + * txbuffer - A pointer to the buffer of data to be sent + * nwords - the length of data to send from the buffer in number of words. + * The wordsize is determined by the number of bits-per-word + * selected for the SPI interface. If nbits <= 8, the data is + * packed into uint8_t's; if nbits >8, the data is packed into uint16_t's + * + * Returned Value: + * None + * + ************************************************************************************/ + +#ifndef CONFIG_SPI_EXCHANGE +static void spi_sndblock(FAR struct spi_dev_s *dev, FAR const void *txbuffer, size_t nwords) +{ + return spi_exchange(dev, txbuffer, NULL, nwords); +} +#endif + +/************************************************************************************ + * Name: spi_recvblock + * + * Description: + * Revice a block of data from SPI + * + * Input Parameters: + * dev - Device-specific state data + * rxbuffer - A pointer to the buffer in which to recieve data + * nwords - the length of data that can be received in the buffer in number + * of words. The wordsize is determined by the number of bits-per-word + * selected for the SPI interface. If nbits <= 8, the data is + * packed into uint8_t's; if nbits >8, the data is packed into uint16_t's + * + * Returned Value: + * None + * + ************************************************************************************/ + +#ifndef CONFIG_SPI_EXCHANGE +static void spi_recvblock(FAR struct spi_dev_s *dev, FAR void *rxbuffer, size_t nwords) +{ + return spi_exchange(dev, NULL, rxbuffer, nwords); +} +#endif + +/************************************************************************************ + * Public Functions + ************************************************************************************/ + +/************************************************************************************ + * Name: up_spiinitialize + * + * Description: + * Initialize the selected SPI port + * + * Input Parameter: + * Port number (for hardware that has mutiple SPI interfaces) + * + * Returned Value: + * Valid SPI device structure reference on succcess; a NULL on failure + * + ************************************************************************************/ + +FAR struct spi_dev_s *up_spiinitialize(int port) +{ + FAR struct lpc31_spidev_s *priv = &g_spidev; + + /* Only the SPI0 interface is supported */ + + if (port != 0) + { + return NULL; + } + + /* Configure SPI pins. Nothing needs to be done here because the SPI pins + * default to "driven-by-IP" on reset. + */ + +#ifdef CONFIG_DEBUG_SPIREGS + lldbg("PINS: %08x MODE0: %08x MODE1: %08x\n", + spi_getreg(LPC31_IOCONFIG_SPI_PINS), + spi_getreg(LPC31_IOCONFIG_SPI_MODE0), + spi_getreg(LPC31_IOCONFIG_SPI_MODE1)); +#endif + + /* Enable SPI clocks */ + + lpc31_enableclock(CLKID_SPIPCLK); + lpc31_enableclock(CLKID_SPIPCLKGATED); + lpc31_enableclock(CLKID_SPICLK); + lpc31_enableclock(CLKID_SPICLKGATED); + + /* Soft Reset the module */ + + lpc31_softreset(RESETID_SPIRSTAPB); + lpc31_softreset(RESETID_SPIRSTIP); + + /* Initialize the SPI semaphore that enforces mutually exclusive access */ + + sem_init(&priv->exclsem, 0, 1); + + /* Reset the SPI block */ + + spi_putreg(SPI_CONFIG_SOFTRST, LPC31_SPI_CONFIG); + + /* Initialise Slave 0 settings registers */ + + priv->slv1 = 0; + priv->slv2 = 0; + + /* Configure initial default mode */ + + priv->mode = SPIDEV_MODE1; + spi_setmode(&priv->spidev, SPIDEV_MODE0); + + /* Configure word width */ + + priv->nbits = 0; + spi_setbits(&priv->spidev, 8); + + /* Select a default frequency of approx. 400KHz */ + + priv->frequency = 0; + spi_setfrequency(&priv->spidev, 400000); + + return (FAR struct spi_dev_s *)priv; +} diff --git a/nuttx/arch/arm/src/lpc31xx/lpc31_spi.h b/nuttx/arch/arm/src/lpc31xx/lpc31_spi.h new file mode 100755 index 000000000..819dae5ae --- /dev/null +++ b/nuttx/arch/arm/src/lpc31xx/lpc31_spi.h @@ -0,0 +1,252 @@ +/************************************************************************************************ + * arch/arm/src/lpc31xx/lpc31_spi.h + * + * Copyright (C) 2009-2010 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * 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_LPC31XX_LPC31_SPI_H +#define __ARCH_ARM_SRC_LPC31XX_LPC31_SPI_H + +/************************************************************************************************ + * Included Files + ************************************************************************************************/ + +#include +#include "lpc31_memorymap.h" + +/************************************************************************************************ + * Pre-processor Definitions + ************************************************************************************************/ + +/* SPI register base address offset into the APB2 domain ****************************************/ + +#define LPC31_SPI_VBASE (LPC31_APB2_VSECTION+LPC31_APB2_SPI_OFFSET) +#define LPC31_SPI_PBASE (LPC31_APB2_PSECTION+LPC31_APB2_SPI_OFFSET) + +/* SPI register offsets (with respect to the SPI base) ******************************************/ +/* SPI configuration registers */ + +#define LPC31_SPI_CONFIG_OFFSET 0x000 /* Configuration register */ +#define LPC31_SPI_SLVENABLE_OFFSET 0x004 /* Slave enable register */ +#define LPC31_SPI_TXFIFO_OFFSET 0x008 /* Transmit FIFO flush register */ +#define LPC31_SPI_FIFODATA_OFFSET 0x00C /* FIFO data register */ +#define LPC31_SPI_NHPPOP_OFFSET 0x010 /* NHP pop register */ +#define LPC31_SPI_NHPMODE_OFFSET 0x014 /* NHP mode selection register */ +#define LPC31_SPI_DMA_OFFSET 0x018 /* DMA settings register */ +#define LPC31_SPI_STATUS_OFFSET 0x01c /* Status register */ +#define LPC31_SPI_HWINFO_OFFSET 0x020 /* Hardware information register */ + +/* SPI slave registers */ + +#define LPC31_SPI_SLV0_1_OFFSET 0x024 /* Slave settings register 1 (for slave 0) */ +#define LPC31_SPI_SLV0_2_OFFSET 0x028 /* Slave settings register 2 (for slave 0) */ +#define LPC31_SPI_SLV1_1_OFFSET 0x02c /* Slave settings register 1 (for slave 1) */ +#define LPC31_SPI_SLV1_2_OFFSET 0x030 /* Slave settings register 2 (for slave 1) */ +#define LPC31_SPI_SLV2_1_OFFSET 0x034 /* Slave settings register 1 (for slave 2) */ +#define LPC31_SPI_SLV2_2_OFFSET 0x038 /* Slave settings register 2 (for slave 2) */ + /* 0x03c-0xfd0: Reserved */ +/* SPI interrupt registers */ + +#define LPC31_SPI_INTTHR_OFFSET 0xfd4 /* Tx/Rx threshold interrupt levels */ +#define LPC31_SPI_INTCLRENABLE_OFFSET 0xfd8 /* INT_ENABLE bits clear register */ +#define LPC31_SPI_INTSETENABLE_OFFSET 0xfdc /* INT_ENABLE bits set register */ +#define LPC31_SPI_INTSTATUS_OFFSET 0xfe0 /* Interrupt status register */ +#define LPC31_SPI_INTENABLE_OFFSET 0xfe4 /* Interrupt enable register */ +#define LPC31_SPI_INTCLRSTATUS_OFFSET 0xfe8 /* INT_STATUS bits clear register */ +#define LPC31_SPI_INTSETSTATUS_OFFSET 0xfec /* INT_STATUS bits set register */ + /* 0xff0-0xff8: Reserved */ + +/* SPI register (virtual) addresses *************************************************************/ + +/* SPI configuration registers */ + +#define LPC31_SPI_CONFIG (LPC31_SPI_VBASE+LPC31_SPI_CONFIG_OFFSET) +#define LPC31_SPI_SLVENABLE (LPC31_SPI_VBASE+LPC31_SPI_SLVENABLE_OFFSET) +#define LPC31_SPI_TXFIFO (LPC31_SPI_VBASE+LPC31_SPI_TXFIFO_OFFSET) +#define LPC31_SPI_FIFODATA (LPC31_SPI_VBASE+LPC31_SPI_FIFODATA_OFFSET) +#define LPC31_SPI_NHPPOP (LPC31_SPI_VBASE+LPC31_SPI_NHPPOP_OFFSET) +#define LPC31_SPI_NHPMODE (LPC31_SPI_VBASE+LPC31_SPI_NHPMODE_OFFSET) +#define LPC31_SPI_DMA (LPC31_SPI_VBASE+LPC31_SPI_DMA_OFFSET) +#define LPC31_SPI_STATUS (LPC31_SPI_VBASE+LPC31_SPI_STATUS_OFFSET) +#define LPC31_SPI_HWINFO (LPC31_SPI_VBASE+LPC31_SPI_HWINFO_OFFSET) + +/* SPI slave registers */ + +#define LPC31_SPI_SLV0_1 (LPC31_SPI_VBASE+LPC31_SPI_SLV0_1_OFFSET) +#define LPC31_SPI_SLV0_2 (LPC31_SPI_VBASE+LPC31_SPI_SLV0_2_OFFSET) +#define LPC31_SPI_SLV1_1 (LPC31_SPI_VBASE+LPC31_SPI_SLV1_1_OFFSET) +#define LPC31_SPI_SLV1_2 (LPC31_SPI_VBASE+LPC31_SPI_SLV1_2_OFFSET) +#define LPC31_SPI_SLV2_1 (LPC31_SPI_VBASE+LPC31_SPI_SLV2_1_OFFSET) +#define LPC31_SPI_SLV2_2 (LPC31_SPI_VBASE+LPC31_SPI_SLV2_2_OFFSET) + +/* SPI interrupt registers */ + +#define LPC31_SPI_INTTHR (LPC31_SPI_VBASE+LPC31_SPI_INTTHR_OFFSET) +#define LPC31_SPI_INTCLRENABLE (LPC31_SPI_VBASE+LPC31_SPI_INTCLRENABLE_OFFSET) +#define LPC31_SPI_INTSETENABLE (LPC31_SPI_VBASE+LPC31_SPI_INTSETENABLE_OFFSET) +#define LPC31_SPI_INTSTATUS (LPC31_SPI_VBASE+LPC31_SPI_INTSTATUS_OFFSET) +#define LPC31_SPI_INTENABLE (LPC31_SPI_VBASE+LPC31_SPI_INTENABLE_OFFSET) +#define LPC31_SPI_INTCLRSTATUS (LPC31_SPI_VBASE+LPC31_SPI_INTCLRSTATUS_OFFSET) +#define LPC31_SPI_INTSETSTATUS (LPC31_SPI_VBASE+LPC31_SPI_INTSETSTATUS_OFFSET) + +/* SPI register bit definitions *****************************************************************/ +/* SPI Configuration register CONFIG, address 0x15002000 */ + +#define SPI_CONFIG_INTERSLVDELAY_SHIFT (16) /* Bits 16-31: Delay between xfrs to different slaves */ +#define SPI_CONFIG_NTERSLVDELAY_MASK (0xffff << SPI_CONFIG_INTERSLVDELAY_SHIFT) +#define SPI_CONFIG_UPDENABLE (1 << 7) /* Bit 7: 7 Update enable bit */ +#define SPI_CONFIG_SOFTRST (1 << 6) /* Bit 6: 6 Software reset bit */ +#define SPI_CONFIG_SLVDISABLE (1 << 4) /* Bit 4: 4 Slave output disable (slave mode) */ +#define SPI_CONFIG_XMITMODE (1 << 3) /* Bit 3: 3 Transmit mode */ +#define SPI_CONFIG_LOOPBACK (1 << 2) /* Bit 2: 2 Loopback mode bit */ +#define SPI_CONFIG_MS (1 << 1) /* Bit 1: 1 Master/slave mode bit */ +#define SPI_CONFIG_SPIENABLE (1 << 0) /* Bit 0: 0 SPI enable bit */ + +/* Slave Enable register SLVENABLE, address 0x15002004 */ + +#define SPI_SLVENABLE3_SHIFT (4) /* Bits 4-5: Slave 3 enable bits */ +#define SPI_SLVENABLE3_MASK (3 << SPI_SLVENABLE3_SHIFT) +# define SPI_SLVENABLE3_DISABLED (0 << SPI_SLVENABLE3_SHIFT) /* Disabled */ +# define SPI_SLVENABLE3_ENABLED (1 << SPI_SLVENABLE3_SHIFT) /* Enabled */ +# define SPI_SLVENABLE3_SUSPENDED (3 << SPI_SLVENABLE3_SHIFT) /* Suspended */ +#define SPI_SLVENABLE2_SHIFT (2) /* Bits 2-3: Slave 2 enable bits */ +#define SPI_SLVENABLE2_MASK (3 << SPI_SLVENABLE2_SHIFT) +# define SPI_SLVENABLE2_DISABLED (0 << SPI_SLVENABLE2_SHIFT) /* Disabled */ +# define SPI_SLVENABLE2_ENABLED (1 << SPI_SLVENABLE2_SHIFT) /* Enabled */ +# define SPI_SLVENABLE2_SUSPENDED (3 << SPI_SLVENABLE2_SHIFT) /* Suspended */ +#define SPI_SLVENABLE1_SHIFT (0) /* Bits 0-1: Slave 1 enable bits */ +#define SPI_SLVENABLE1_MASK (3 << SPI_SLVENABLE1_SHIFT) +# define SPI_SLVENABLE1_DISABLED (0 << SPI_SLVENABLE1_SHIFT) /* Disabled */ +# define SPI_SLVENABLE1_ENABLED (1 << SPI_SLVENABLE1_SHIFT) /* Enabled */ +# define SPI_SLVENABLE1_SUSPENDED (3 << SPI_SLVENABLE1_SHIFT) /* Suspended */ + +/* Transmit FIFO flush register TXFIFO, address 0x15002008 */ + +#define SPI_TXFIFO_FLUSH (1 << 0) /* Bit 0: Transmit FIFO flush bit */ + +/* FIFO data register FIFODATA, address 0x1500200c */ + +#define SPI_FIFODATA_SHIFT (0) /* Bits 0-15: FIFO data */ +#define SPI_FIFODATA_MASK (0xffff << SPI_FIFODATA_SHIFT) + +/* NHP POP register NHPPOP, address 0x15002010 */ + +#define SPI_NHPPOP (1 << 0) /* Bit 0: NHP pop bit */ + +/* NHP mode register NHPMODE, address 0x15002014 */ + +#define SPI_NHPMODE (1 << 0) /* Bit 0: NHP mode bit */ + +/* DMA setting register DMA, address 0x15002018 */ + +#define SPI_DMA_TXENABLE (1 << 1) /* Bit 1: Tx DMA enable bit */ +#define SPI_DMA_RXEMABLE (1 << 0) /* Bit 0: Rx DMA enable bit */ + +/* Status register STATUS, address 0x1500201c */ + +#define SPI_STATUS_SMSBUSY (1 << 5) /* Bit 5: Sequential multi-slave mode busy */ +#define SPI_STATUS_BUSY (1 << 4) /* Bit 4: SPI busy flag */ +#define SPI_STATUS_RXFIFOFULL (1 << 3) /* Bit 3: Receive FIFO full bit */ +#define SPI_STATUS_RXFIFOEMPTY (1 << 2) /* Bit 2: Receive FIFO empty bit */ +#define SPI_STATUS_TXFIFOFULL (1 << 1) /* Bit 1: Transmit FIFO full bit */ +#define SPI_STATUS_TXFIFOEMPTY (1 << 0) /* Bit 0: Transmit FIFO empty bit */ + +/* Hardware information register HWINFO, address 0x15002020 */ + +#define SPI_HWINFO_FIFOIMPLT (1 << 30) /* Bit 30: FIFO memory implementation */ +#define SPI_HWINFO_NSLAVES_SHIFT (26) /* Bits 26-29: Maximum number of slaves (minus 1) */ +#define SPI_HWINFO_NSLAVES_MASK (0x0f << SPI_HWINFO_NSLAVES_SHIFT) +#define SPI_HWINFO_TXFIFOWIDTH_SHIFT (21) /* Bits 21-25: Width transmit FIFO (minus 1) */ +#define SPI_HWINFO_TXFIFOWIDTH_MASK (0x1f << SPI_HWINFO_TXFIFOWIDTH_SHIFT) +#define SPI_HWINFO_RXFIFOWIDTH_SHIFT (16) /* Bits 16-20: Width receive FIFO (minus 1) */ +#define SPI_HWINFO_RXFIFOWIDTH_MASK (0x1f << SPI_HWINFO_RXFIFOWIDTH_SHIFT) +#define SPI_HWINFO_TXFIFODEPTH_SHIFT (8) /* Bits 8-15: 64 */ +#define SPI_HWINFO_TXFIFODEPTH_MASK (0x0ff << SPI_HWINFO_TXFIFODEPTH_SHIFT) +#define SPI_HWINFO_RXFIFODEPTH_SHIFT (0) /* Bits 0-7: 64 */ +#define SPI_HWINFO_RXFIFODEPTH_MASK (0xff << SPI_HWINFO_RXFIFODEPTH_SHIFT) + +/* Slave settings 1 SLV0-2_1, addresses 0x15002024, 0x1500202c, and 0x15002034 */ + +#define SPI_SLV_1_INTERXFRDLY_SHIFT (24) /* Bits 24-31: Delay between slave xfrs (master mode) */ +#define SPI_SLV_1_INTERXFRDLY_MASK (0xff << SPI_SLV_1_INTERXFRDLY_SHIFT) +#define SPI_SLV_1_NWORDS_SHIFT (16) /* Bits 16-23: Number words to send in SMS mode (master mode) */ +#define SPI_SLV_1_NWORDS_MASK (0xff << SPI_SLV_1_NWORDS_SHIFT) +#define SPI_SLV_1_CLKDIV2_SHIFT (8) /* Bits 8-15: Serial clock divisor 2 */ +#define SPI_SLV_1_CLKDIV2_MASK (0xff << SPI_SLV_1_CLKDIV2_SHIFT) +#define SPI_SLV_1_CLKDIV1_SHIFT (0) /* Bits 0-7: Serial clock rate divisor 1 */ +#define SPI_SLV_1_CLKDIV1_MASK (0xff << SPI_SLV_1_CLKDIV1_SHIFT) + +/* Slave settings 2 SLV0-2_2, addresses 0x15002028, 0x15002030, and0x15002038 */ + +#define SPI_SLV_2_DELAY_SHIFT (9) /* Bits 9-16: Programmable delay */ +#define SPI_SLV_2_DELAY_MASK (0xff << SPI_SLV_2_DELAY_SHIFT) +#define SPI_SLV_2_CSVAL (1 << 8) /* Bit 8: Chip select value between transfers */ +#define SPI_SLV_2_XFRFMT (1 << 7) /* Bit 7: Format of transfer */ +#define SPI_SLV_2_SPO (1 << 6) /* Bit 6: Serial clock polarity */ +#define SPI_SLV_2_SPH (1 << 5) /* Bit 5: Serial clock phase */ +#define SPI_SLV_2_WDSIZE_SHIFT (0) /* Bits 0-4: Word size of transfers slave (minus 1) */ +#define SPI_SLV_2_WDSIZE_MASK (0x1f << SPI_SLV_2_WDSIZE_SHIFT) + +/* Interrupt threshold register INTTHR, address 0x15002fd4 */ + +#define SPI_INTTHR_TX_SHIFT (8) /* Bits 8-15: Interrupt when less than this in TX FIFO */ +#define SPI_INTTHR_TX_MASK (0xff << SPI_INTTHR_TX_SHIFT) +#define SPI_INTTHR_RX_SHIFT (0) /* Bits 0-7: Interrupt when more than this in RX FIFO */ +#define SPI_INTTHR_RX_MASK (0xff << SPI_INTTHR_TX_SHIFT) + +/* Interrupt clear enable register INTCLRENABLE, address 0x15002fd8, + * Interrupt set enable register INTSETENABLE, address 0x15002fdc, + * Interrupt status register INTSTATUS, address 0x15002fe0, + * Interrupt enable register INTENABLE, address 0x15002fe4, + * Interrupt clear status register INTCLRSTATUS, address 0x15002fe8, + * Interrupt set status register INTSETSTATUS, address 0x15002fec + */ + +#define SPI_INT_SMS (1 << 4) /* Bit 4: Sequential multi-slave mode ready interrupt bit */ +#define SPI_INT_TX (1 << 3) /* Bit 3: Transmit threshold level interrupt bit */ +#define SPI_INT_RX (1 << 2) /* Bit 3: Receive threshold level interrupt bit */ +#define SPI_INT_TO (1 << 1) /* Bit 1: Receive timeout interrupt bit */ +#define SPI_INT_OV (1 << 0) /* Bit 0: Receive overrtun interrrupt bit */ + +/************************************************************************************************ + * Public Types + ************************************************************************************************/ + +/************************************************************************************************ + * Public Data + ************************************************************************************************/ + +/************************************************************************************************ + * Public Functions + ************************************************************************************************/ + +#endif /* __ARCH_ARM_SRC_LPC31XX_LPC31_SPI_H */ diff --git a/nuttx/arch/arm/src/lpc31xx/lpc31_syscreg.h b/nuttx/arch/arm/src/lpc31xx/lpc31_syscreg.h new file mode 100755 index 000000000..3a031a13c --- /dev/null +++ b/nuttx/arch/arm/src/lpc31xx/lpc31_syscreg.h @@ -0,0 +1,611 @@ +/******************************************************************************************************** + * arch/arm/src/lpc31xx/lpc31_syscreg.h + * + * Copyright (C) 2009-2010 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * 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_LPC31XX_LPC31_SYSCREG_H +#define __ARCH_ARM_SRC_LPC31XX_LPC31_SYSCREG_H + +/******************************************************************************************************** + * Included Files + ********************************************************************************************************/ + +#include +#include "lpc31_memorymap.h" + +/******************************************************************************************************** + * Pre-processor Definitions + ********************************************************************************************************/ + +/* SYSCREG register base address offset into the APB0 domain ********************************************/ + +#define LPC31_SYSCREG_VBASE (LPC31_APB0_VADDR+LPC31_APB0_SYSCREG_OFFSET) +#define LPC31_SYSCREG_PBASE (LPC31_APB0_PADDR+LPC31_APB0_SYSCREG_OFFSET) + +/* SYSCREG register offsets (with respect to the SYSCREG base) ******************************************/ +/* Miscellaneous system configuration registers, part1 */ + /* 0x000-0x004: Reserved */ +#define LPC31_SYSCREG_EBIMPMCPRIO_OFFSET 0x008 /* Priority of MPMC channel for EBI interface */ +#define LPC31_SYSCREG_EBNANDCPRIO_OFFSET 0x00c /* Priority of NAND controller channel for EBI interface */ +#define LPC31_SYSCREG_EBIUNUSEDPRIO_OFFSET 0x010 /* Priority of unused channel */ +#define LPC31_SYSCREG_RINGOSCCFG_OFFSET 0x014 /* RING oscillator configuration register */ +#define LPC31_SYSCREG_ADCPDADC10BITS_OFFSET 0x018 /* Powerdown register of ADC 10bits */ +#define LPC31_SYSCREG_CGUDYNHP0_OFFSET 0x01c /* reserved */ +#define LPC31_SYSCREG_CGUDYNHP1_OFFSET 0x020 /* reserved */ +#define LPC31_SYSCREG_ABCCFG_OFFSET 0x024 /* AHB burst control register */ +#define LPC31_SYSCREG_SDMMCCFG_OFFSET 0x028 /* SD_MMC (MCI) configuration register */ +#define LPC31_SYSCREG_MCIDELAYMODES_OFFSET 0x02c /* Delay register for the SD_MMC (MCI) clocks */ + +/* USB configuration registers */ + +#define LPC31_SYSCREG_USB_ATXPLLPDREG_OFFSET 0x030 /* Power down register of USB ATX PLL */ +#define LPC31_SYSCREG_USB_OTGCFG_OFFSET 0x034 /* USB OTG configuration register */ +#define LPC31_SYSCREG_USB_OTGPORTINDCTL_OFFSET 0x038 /* USB OTG port indicator LED control outputs */ + /* 0x03c: Reserved */ +#define LPC31_SYSCREG_USB_PLLNDEC_OFFSET 0x040 /* USB OTG PLL configuration register NOEC */ +#define LPC31_SYSCREG_USB_PLLMDEC_OFFSET 0x044 /* USB OTG PLL configuration register MDEC */ +#define LPC31_SYSCREG_USB_PLLPDEC_OFFSET 0x048 /* USB OTG PLL configuration register PDEC */ +#define LPC31_SYSCREG_USB_PLLSELR_OFFSET 0x04c /* USB OTG PLL configuration register SELR */ +#define LPC31_SYSCREG_USB_PLLSELI_OFFSET 0x050 /* USB OTG PLL configuration register SELI */ +#define LPC31_SYSCREG_USB_PLLSELP_OFFSET 0x054 /* USB OTG PLL configuration register SELP */ + +/* ISRAM/ISROM configuration registers */ + +#define LPC31_SYSCREG_ISRAM0_LATENCYCFG_OFFSET 0x058 /* Internal SRAM 0 latency configuration register */ +#define LPC31_SYSCREG_ISRAM1_LATENCYCFG_OFFSET 0x05c /* Internal SRAM 1 latency configuration register */ +#define LPC31_SYSCREG_ISROM_LATENCYCFG_OFFSET 0x060 /* Internal SROM latency configuration register */ + +/* MPMC configuration registers */ + +#define LPC31_SYSCREG_MPMC_AHBMISC_OFFSET 0x064 /* Configuration register of MPMC */ +#define LPC31_SYSCREG_MPMC_DELAYMODES_OFFSET 0x068 /* Configuration of MPMC clock delay */ +#define LPC31_SYSCREG_MPMC_WAITRD0_OFFSET 0x06c /* Configuration of the wait cycles for read transfers */ +#define LPC31_SYSCREG_MPMC_WAITRD1_OFFSET 0x070 /* Configuration of the wait cycles for read transfers */ +#define LPC31_SYSCREG_MPMC_WIREEBIMSZ_OFFSET 0x074 /* Configuration of the memory width for MPMC */ +#define LPC31_SYSCREG_MPMC_TESTMODE0_OFFSET 0x078 /* Configuration for refresh generation of MPMC */ +#define LPC31_SYSCREG_MPMC_TESTMODE1_OFFSET 0x07c /* Configuration for refresh generation of MPMC */ + +/* Miscellaneous system configuration registers, part 2 */ + +#define LPC31_SYSCREG_AHB0EXTPRIO_OFFSET 0x080 /* Priority of the AHB masters */ +#define LPC31_SYSCREG_ARM926SHADOWPTR_OFFSET 0x084 /* Memory mapping */ + /* 0x088-0x08c reserved */ +/* Pin multiplexing control registers */ + +#define LPC31_SYSCREG_MUX_LCDEBISEL_OFFSET 0x090 /* Selects between lcd_interface and EBI pins */ +#define LPC31_SYSCREG_MUX_GPIOMCISEL_OFFSET 0x094 /* Selects between GPIO and MCI pins */ +#define LPC31_SYSCREG_MUX_NANDMCISEL_OFFSET 0x098 /* Selects between NAND flash controller and MCI pins */ +#define LPC31_SYSCREG_MUX_UARTSPISEL_OFFSET 0x09c /* Selects between UART and SPI pins */ +#define LPC31_SYSCREG_MUX_I2STXPCMSEL_OFFSET 0x0a0 /* Selects between I2STX and PCM pins */ + +/* Pad configuration registers */ + +#define LPC31_SYSCREG_PAD_EBID9_OFFSET 0x0a4 /* Control pad EBI_D_9 */ +#define LPC31_SYSCREG_PAD_EBID10_OFFSET 0x0a8 /* Control pad EBI_D_10 */ +#define LPC31_SYSCREG_PAD_EBID11_OFFSET 0x0ac /* Control pad EBI_D_11 */ +#define LPC31_SYSCREG_PAD_EBID12_OFFSET 0x0b0 /* Control pad EBI_D_12 */ +#define LPC31_SYSCREG_PAD_EBID13_OFFSET 0x0b4 /* Control pad EBI_D_13 */ +#define LPC31_SYSCREG_PAD_EBID14_OFFSET 0x0b8 /* Control pad EBI_D_14 */ +#define LPC31_SYSCREG_PAD_I2SRXBCK0_OFFSET 0x0bc /* Control pad I2SRX_BCK0 */ +#define LPC31_SYSCREG_PAD_MGPIO9_OFFSET 0x0c0 /* Control pad MGPIO9 */ +#define LPC31_SYSCREG_PAD_MGPIO6_OFFSET 0x0c4 /* Control pad MGPIO6 */ +#define LPC31_SYSCREG_PAD_MLCDDB7_OFFSET 0x0c8 /* Control pad MLCD_DB_7 */ +#define LPC31_SYSCREG_PAD_MLCDDB4_OFFSET 0x0cc /* Control pad MLCD_DB_4 */ +#define LPC31_SYSCREG_PAD_MLCDDB2_OFFSET 0x0d0 /* Control pad MLCD_DB_2 */ +#define LPC31_SYSCREG_PAD_MNANDRYBN0_OFFSET 0x0d4 /* Control pad MNAND_RYBN0 */ +#define LPC31_SYSCREG_PAD_GPIO1_OFFSET 0x0d8 /* Control pad GPIO1 */ +#define LPC31_SYSCREG_PAD_EBID4_OFFSET 0x0dc /* Control pad EBI_D_4 */ +#define LPC31_SYSCREG_PAD_MI2STXCLK0_OFFSET 0x0e0 /* Control pad MI2STX_CLK0 */ +#define LPC31_SYSCREG_PAD_MI2STXBCK0_OFFSET 0x0e4 /* Control pad MI2STX_BCK0 */ +#define LPC31_SYSCREG_PAD_EBIA1CLE_OFFSET 0x0e8 /* Control pad EBI_A_1_CLE */ +#define LPC31_SYSCREG_PAD_EBINCASBLOUT0_OFFSET 0x0ec /* Control pad EBI_NCAS_BLOUT_0 */ +#define LPC31_SYSCREG_PAD_NANDNCS3_OFFSET 0x0f0 /* Control pad NAND_NCS_3 */ +#define LPC31_SYSCREG_PAD_MLCDDB0_OFFSET 0x0f4 /* Control pad MLCD_DB_0 */ +#define LPC31_SYSCREG_PAD_EBIDQM0NOE_OFFSET 0x0f8 /* Control pad EBI_DQM_0_NOE */ +#define LPC31_SYSCREG_PAD_EBID0_OFFSET 0x0fc /* Control pad EBI_D_0 */ +#define LPC31_SYSCREG_PAD_EBID1_OFFSET 0x100 /* Control pad EBI_D_1 */ +#define LPC31_SYSCREG_PAD_EBID2_OFFSET 0x104 /* Control pad EBI_D_2 */ +#define LPC31_SYSCREG_PAD_EBID3_OFFSET 0x108 /* Control pad EBI_D_3 */ +#define LPC31_SYSCREG_PAD_EBID5_OFFSET 0x10c /* Control pad EBI_D_5 */ +#define LPC31_SYSCREG_PAD_EBID6_OFFSET 0x110 /* Control pad EBI_D_6 */ +#define LPC31_SYSCREG_PAD_EBID7_OFFSET 0x114 /* Control pad EBI_D_7 */ +#define LPC31_SYSCREG_PAD_EBID8_OFFSET 0x118 /* Control pad EBI_D_8 */ +#define LPC31_SYSCREG_PAD_EBID15_OFFSET 0x11c /* Control pad EBI_D_15 */ +#define LPC31_SYSCREG_PAD_I2STXDATA1_OFFSET 0x120 /* Control pad I2STX_DATA1 */ +#define LPC31_SYSCREG_PAD_I2STXBCK1_OFFSET 0x124 /* Control pad I2STX_BCK1 */ +#define LPC31_SYSCREG_PAD_I2STXWS1_OFFSET 0x128 /* Control pad I2STX_WS1 */ +#define LPC31_SYSCREG_PAD_I2SRXDATA0_OFFSET 0x12c /* Control pad I2SRX_DATA0 */ +#define LPC31_SYSCREG_PAD_I2SRXWS0_OFFSET 0x130 /* Control pad I2SRX_WS0 */ +#define LPC31_SYSCREG_PAD_I2SRXDATA1_OFFSET 0x134 /* Control pad I2SRX_DATA1 */ +#define LPC31_SYSCREG_PAD_I2SRXBCK1_OFFSET 0x138 /* Control pad I2SRX_BCK1 */ +#define LPC31_SYSCREG_PAD_I2SRXWS1_OFFSET 0x13c /* Control pad I2SRX_WS1 */ +#define LPC31_SYSCREG_PAD_SYSCLKO_OFFSET 0x140 /* Control pad SYSCLK_O */ +#define LPC31_SYSCREG_PAD_PWMDATA_OFFSET 0x144 /* Control pad PWM_DATA */ +#define LPC31_SYSCREG_PAD_UARTRXD_OFFSET 0x148 /* Control pad UART_RXD */ +#define LPC31_SYSCREG_PAD_UARTTXD_OFFSET 0x14c /* Control pad UART_TXD */ +#define LPC31_SYSCREG_PAD_I2CSDA1_OFFSET 0x150 /* Control pad I2C_SDA1 */ +#define LPC31_SYSCREG_PAD_I2CSCL1_OFFSET 0x154 /* Control pad I2C_SCL1 */ +#define LPC31_SYSCREG_PAD_CLK256FSO_OFFSET 0x158 /* Control pad CLK_256FS_O */ +#define LPC31_SYSCREG_PAD_GPIO0_OFFSET 0x15c /* Control pad GPIO0 */ +#define LPC31_SYSCREG_PAD_GPIO2_OFFSET 0x160 /* Control pad GPIO2 */ +#define LPC31_SYSCREG_PAD_GPIO3_OFFSET 0x164 /* Control pad GPIO3 */ +#define LPC31_SYSCREG_PAD_GPIO4_OFFSET 0x168 /* Control pad GPIO4 */ +#define LPC31_SYSCREG_PAD_GPIO11_OFFSET 0x16c /* Control pad GPIO11 */ +#define LPC31_SYSCREG_PAD_GPIO12_OFFSET 0x170 /* Control pad GPIO12 */ +#define LPC31_SYSCREG_PAD_GPIO13_OFFSET 0x174 /* Control pad GPIO13 */ +#define LPC31_SYSCREG_PAD_GPIO14_OFFSET 0x178 /* Control pad GPIO14 */ +#define LPC31_SYSCREG_PAD_GPIO15_OFFSET 0x17c /* Control pad GPIO15 */ +#define LPC31_SYSCREG_PAD_GPIO16_OFFSET 0x180 /* Control pad GPIO16 */ +#define LPC31_SYSCREG_PAD_GPIO17_OFFSET 0x184 /* Control pad GPIO17 */ +#define LPC31_SYSCREG_PAD_GPIO18_OFFSET 0x188 /* Control pad GPIO18 */ +#define LPC31_SYSCREG_PAD_GPIO19_OFFSET 0x18c /* Control pad GPIO19 */ +#define LPC31_SYSCREG_PAD_GPIO20_OFFSET 0x190 /* Control pad GPIO20 */ +#define LPC31_SYSCREG_PAD_SPIMISO_OFFSET 0x194 /* Control pad SPI_MISO */ +#define LPC31_SYSCREG_PAD_SPIMOSI_OFFSET 0x198 /* Control pad SPI_MOSI */ +#define LPC31_SYSCREG_PAD_SPICSIN_OFFSET 0x19c /* Control pad SPI_CS_IN */ +#define LPC31_SYSCREG_PAD_SPISCK_OFFSET 0x1a0 /* Control pad SPI_SCK */ +#define LPC31_SYSCREG_PAD_SPICSOUT0_OFFSET 0x1a4 /* Control pad SPI_CS_OUT0 */ +#define LPC31_SYSCREG_PAD_NANDNCS0_OFFSET 0x1a8 /* Control pad NAND_NCS_0 */ +#define LPC31_SYSCREG_PAD_NANDNCS1_OFFSET 0x1ac /* Control pad NAND_NCS_1 */ +#define LPC31_SYSCREG_PAD_NANDNCS2_OFFSET 0x1b0 /* Control pad NAND_NCS_2 */ +#define LPC31_SYSCREG_PAD_MLCDCSB_OFFSET 0x1b4 /* Control pad MLCD_CSB */ +#define LPC31_SYSCREG_PAD_MLCDDB1_OFFSET 0x1b8 /* Control pad MLCD_DB_1 */ +#define LPC31_SYSCREG_PAD_MLCDERD_OFFSET 0x1bc /* Control pad MLCD_E_RD */ +#define LPC31_SYSCREG_PAD_MLCDRS_OFFSET 0x1c0 /* Control pad MLCD_RS */ +#define LPC31_SYSCREG_PAD_MLCDRWWR_OFFSET 0x1c4 /* Control pad MLCD_RW_WR */ +#define LPC31_SYSCREG_PAD_MLCDDB3_OFFSET 0x1c8 /* Control pad MLCD_DB_3 */ +#define LPC31_SYSCREG_PAD_MLCDDB5_OFFSET 0x1cc /* Control pad MLCD_DB_5 */ +#define LPC31_SYSCREG_PAD_MLCDDB6_OFFSET 0x1d0 /* Control pad MLCD_DB_6 */ +#define LPC31_SYSCREG_PAD_MLCDDB8_OFFSET 0x1d4 /* Control pad MLCD_DB_8 */ +#define LPC31_SYSCREG_PAD_MLCDDB9_OFFSET 0x1d8 /* Control pad MLCD_DB_9 */ +#define LPC31_SYSCREG_PAD_MLCDDB10_OFFSET 0x1dc /* Control pad MLCD_DB_10 */ +#define LPC31_SYSCREG_PAD_MLCDDB11_OFFSET 0x1e0 /* Control pad MLCD_DB_11 */ +#define LPC31_SYSCREG_PAD_MLCDDB12_OFFSET 0x1e4 /* Control pad MLCD_DB_12 */ +#define LPC31_SYSCREG_PAD_MLCDDB13_OFFSET 0x1e8 /* Control pad MLCD_DB_13 */ +#define LPC31_SYSCREG_PAD_MLCDDB14_OFFSET 0x1ec /* Control pad MLCD_DB_14 */ +#define LPC31_SYSCREG_PAD_MLCDDB15_OFFSET 0x1f0 /* Control pad MLCD_DB_15 */ +#define LPC31_SYSCREG_PAD_MGPIO5_OFFSET 0x1f4 /* Control pad MGPIO5 */ +#define LPC31_SYSCREG_PAD_MGPIO7_OFFSET 0x1f8 /* Control pad MGPIO5 */ +#define LPC31_SYSCREG_PAD_MGPIO8_OFFSET 0x1fc /* Control pad MGPIO8 */ +#define LPC31_SYSCREG_PAD_MGPIO10_OFFSET 0x200 /* Control pad MGPIO10 */ +#define LPC31_SYSCREG_PAD_MNANDRYBN1_OFFSET 0x204 /* Control pad MNAND_RYBN1 */ +#define LPC31_SYSCREG_PAD_MNANDRYBN2_OFFSET 0x208 /* Control pad MNAND_RYBN2 */ +#define LPC31_SYSCREG_PAD_MNANDRYBN3_OFFSET 0x20c /* Control pad MNAND_RYBN3 */ +#define LPC31_SYSCREG_PAD_MUARTCTSN_OFFSET 0x210 /* Control pad MUART_CTS_N */ +#define LPC31_SYSCREG_PAD_MI2STXDATA0_OFFSET 0x218 /* Control pad MI2STX_DATA0 */ +#define LPC31_SYSCREG_PAD_MI2STXWS0_OFFSET 0x21c /* Control pad MI2STX_WS0 */ +#define LPC31_SYSCREG_PAD_EBINRASBLOUT1_OFFSET 0x220 /* Control pad EBI_NRAS_BLOUT_1 */ +#define LPC31_SYSCREG_PAD_EBIA0ALE_OFFSET 0x224 /* Control pad EBI_A_0_ALE */ +#define LPC31_SYSCREG_PAD_EBINWE_OFFSET 0x228 /* Control pad EBI_NWE */ +#define LPC31_SYSCREG_PAD_ESHCTRLSUP4_OFFSET 0x22c /* Control pad at 1.8 and 3.3V (Nandflash/EBI pads) */ +#define LPC31_SYSCREG_PAD_ESHCTRLSUP8_OFFSET 0x230 /* Control pad at 1.8 and 3.3V (LCD interface/SDRAM pads) */ + +/* SYSCREG register (virtual) addresses *****************************************************************/ +/* Miscellaneous system configuration registers, part1 */ + +#define LPC31_SYSCREG_EBIMPMCPRIO (LPC31_SYSCREG_VBASE+LPC31_SYSCREG_EBIMPMCPRIO_OFFSET) +#define LPC31_SYSCREG_EBNANDCPRIO (LPC31_SYSCREG_VBASE+LPC31_SYSCREG_EBNANDCPRIO_OFFSET) +#define LPC31_SYSCREG_EBIUNUSEDPRIO (LPC31_SYSCREG_VBASE+LPC31_SYSCREG_EBIUNUSEDPRIO_OFFSET) +#define LPC31_SYSCREG_RINGOSCCFG (LPC31_SYSCREG_VBASE+LPC31_SYSCREG_RINGOSCCFG_OFFSET) +#define LPC31_SYSCREG_ADCPDADC10BITS (LPC31_SYSCREG_VBASE+LPC31_SYSCREG_ADCPDADC10BITS_OFFSET) +#define LPC31_SYSCREG_ABCCFG (LPC31_SYSCREG_VBASE+LPC31_SYSCREG_ABCCFG_OFFSET) +#define LPC31_SYSCREG_SDMMCCFG (LPC31_SYSCREG_VBASE+LPC31_SYSCREG_SDMMCCFG_OFFSET) +#define LPC31_SYSCREG_MCIDELAYMODES (LPC31_SYSCREG_VBASE+LPC31_SYSCREG_MCIDELAYMODES_OFFSET) + +/* USB configuration registers */ + +#define LPC31_SYSCREG_USB_ATXPLLPDREG (LPC31_SYSCREG_VBASE+LPC31_SYSCREG_USB_ATXPLLPDREG_OFFSET) +#define LPC31_SYSCREG_USB_OTGCFG (LPC31_SYSCREG_VBASE+LPC31_SYSCREG_USB_OTGCFG_OFFSET) +#define LPC31_SYSCREG_USB_OTGPORTINDCTL (LPC31_SYSCREG_VBASE+LPC31_SYSCREG_USB_OTGPORTINDCTL_OFFSET) +#define LPC31_SYSCREG_USB_PLLNDEC (LPC31_SYSCREG_VBASE+LPC31_SYSCREG_USB_PLLNDEC_OFFSET) +#define LPC31_SYSCREG_USB_PLLMDEC (LPC31_SYSCREG_VBASE+LPC31_SYSCREG_USB_PLLMDEC_OFFSET) +#define LPC31_SYSCREG_USB_PLLPDEC (LPC31_SYSCREG_VBASE+LPC31_SYSCREG_USB_PLLPDEC_OFFSET) +#define LPC31_SYSCREG_USB_PLLSELR (LPC31_SYSCREG_VBASE+LPC31_SYSCREG_USB_PLLSELR_OFFSET) +#define LPC31_SYSCREG_USB_PLLSELI (LPC31_SYSCREG_VBASE+LPC31_SYSCREG_USB_PLLSELI_OFFSET) +#define LPC31_SYSCREG_USB_PLLSELP (LPC31_SYSCREG_VBASE+LPC31_SYSCREG_USB_PLLSELP_OFFSET) + +/* ISRAM/ISROM configuration registers */ + +#define LPC31_SYSCREG_ISRAM0_LATENCYCFG (LPC31_SYSCREG_VBASE+LPC31_SYSCREG_ISRAM0_LATENCYCFG_OFFSET) +#define LPC31_SYSCREG_ISRAM1_LATENCYCFG (LPC31_SYSCREG_VBASE+LPC31_SYSCREG_ISRAM1_LATENCYCFG_OFFSET) +#define LPC31_SYSCREG_ISROM_LATENCYCFG (LPC31_SYSCREG_VBASE+LPC31_SYSCREG_ISROM_LATENCYCFG_OFFSET) + +/* MPMC configuration registers */ + +#define LPC31_SYSCREG_MPMC_AHBMISC (LPC31_SYSCREG_VBASE+LPC31_SYSCREG_MPMC_AHBMISC_OFFSET) +#define LPC31_SYSCREG_MPMC_DELAYMODES (LPC31_SYSCREG_VBASE+LPC31_SYSCREG_MPMC_DELAYMODES_OFFSET) +#define LPC31_SYSCREG_MPMC_WAITRD0 (LPC31_SYSCREG_VBASE+LPC31_SYSCREG_MPMC_WAITRD0_OFFSET) +#define LPC31_SYSCREG_MPMC_WAITRD1 (LPC31_SYSCREG_VBASE+LPC31_SYSCREG_MPMC_WAITRD1_OFFSET) +#define LPC31_SYSCREG_MPMC_WIREEBIMSZ (LPC31_SYSCREG_VBASE+LPC31_SYSCREG_MPMC_WIREEBIMSZ_OFFSET) +#define LPC31_SYSCREG_MPMC_TESTMODE0 (LPC31_SYSCREG_VBASE+LPC31_SYSCREG_MPMC_TESTMODE0_OFFSET) +#define LPC31_SYSCREG_MPMC_TESTMODE1 (LPC31_SYSCREG_VBASE+LPC31_SYSCREG_MPMC_TESTMODE1_OFFSET) + +/* Miscellaneous system configuration registers, part 2 */ + +#define LPC31_SYSCREG_AHB0EXTPRIO (LPC31_SYSCREG_VBASE+LPC31_SYSCREG_AHB0EXTPRIO_OFFSET) +#define LPC31_SYSCREG_ARM926SHADOWPTR (LPC31_SYSCREG_VBASE+LPC31_SYSCREG_ARM926SHADOWPTR_OFFSET) + +/* Pin multiplexing control registers */ + +#define LPC31_SYSCREG_MUX_LCDEBISEL (LPC31_SYSCREG_VBASE+LPC31_SYSCREG_MUX_LCDEBISEL_OFFSET) +#define LPC31_SYSCREG_MUX_GPIOMCISEL (LPC31_SYSCREG_VBASE+LPC31_SYSCREG_MUX_GPIOMCISEL_OFFSET) +#define LPC31_SYSCREG_MUX_NANDMCISEL (LPC31_SYSCREG_VBASE+LPC31_SYSCREG_MUX_NANDMCISEL_OFFSET) +#define LPC31_SYSCREG_MUX_UARTSPISEL (LPC31_SYSCREG_VBASE+LPC31_SYSCREG_MUX_UARTSPISEL_OFFSET) +#define LPC31_SYSCREG_MUX_I2STXPCMSEL (LPC31_SYSCREG_VBASE+LPC31_SYSCREG_MUX_I2STXPCMSEL_OFFSET) + +/* Pad configuration registers */ + +#define LPC31_SYSCREG_PAD_EBID9 (LPC31_SYSCREG_VBASE+LPC31_SYSCREG_PAD_EBID9_OFFSET) +#define LPC31_SYSCREG_PAD_EBID10 (LPC31_SYSCREG_VBASE+LPC31_SYSCREG_PAD_EBID10_OFFSET) +#define LPC31_SYSCREG_PAD_EBID11 (LPC31_SYSCREG_VBASE+LPC31_SYSCREG_PAD_EBID11_OFFSET) +#define LPC31_SYSCREG_PAD_EBID12 (LPC31_SYSCREG_VBASE+LPC31_SYSCREG_PAD_EBID12_OFFSET) +#define LPC31_SYSCREG_PAD_EBID13 (LPC31_SYSCREG_VBASE+LPC31_SYSCREG_PAD_EBID13_OFFSET) +#define LPC31_SYSCREG_PAD_EBID14 (LPC31_SYSCREG_VBASE+LPC31_SYSCREG_PAD_EBID14_OFFSET) +#define LPC31_SYSCREG_PAD_I2SRXBCK0 (LPC31_SYSCREG_VBASE+LPC31_SYSCREG_PAD_I2SRXBCK0_OFFSET) +#define LPC31_SYSCREG_PAD_MGPIO9 (LPC31_SYSCREG_VBASE+LPC31_SYSCREG_PAD_MGPIO9_OFFSET) +#define LPC31_SYSCREG_PAD_MGPIO6 (LPC31_SYSCREG_VBASE+LPC31_SYSCREG_PAD_MGPIO6_OFFSET) +#define LPC31_SYSCREG_PAD_MLCDDB7 (LPC31_SYSCREG_VBASE+LPC31_SYSCREG_PAD_MLCDDB7_OFFSET) +#define LPC31_SYSCREG_PAD_MLCDDB4 (LPC31_SYSCREG_VBASE+LPC31_SYSCREG_PAD_MLCDDB4_OFFSET) +#define LPC31_SYSCREG_PAD_MLCDDB2 (LPC31_SYSCREG_VBASE+LPC31_SYSCREG_PAD_MLCDDB2_OFFSET) +#define LPC31_SYSCREG_PAD_MNANDRYBN0 (LPC31_SYSCREG_VBASE+LPC31_SYSCREG_PAD_MNANDRYBN0_OFFSET) +#define LPC31_SYSCREG_PAD_GPIO1 (LPC31_SYSCREG_VBASE+LPC31_SYSCREG_PAD_GPIO1_OFFSET) +#define LPC31_SYSCREG_PAD_EBID4 (LPC31_SYSCREG_VBASE+LPC31_SYSCREG_PAD_EBID4_OFFSET) +#define LPC31_SYSCREG_PAD_MI2STXCLK0 (LPC31_SYSCREG_VBASE+LPC31_SYSCREG_PAD_MI2STXCLK0_OFFSET) +#define LPC31_SYSCREG_PAD_MI2STXBCK0 (LPC31_SYSCREG_VBASE+LPC31_SYSCREG_PAD_MI2STXBCK0_OFFSET) +#define LPC31_SYSCREG_PAD_EBIA1CLE (LPC31_SYSCREG_VBASE+LPC31_SYSCREG_PAD_EBIA1CLE_OFFSET) +#define LPC31_SYSCREG_PAD_EBINCASBLOUT0 (LPC31_SYSCREG_VBASE+LPC31_SYSCREG_PAD_EBINCASBLOUT0_OFFSET) +#define LPC31_SYSCREG_PAD_NANDNCS3 (LPC31_SYSCREG_VBASE+LPC31_SYSCREG_PAD_NANDNCS3_OFFSET) +#define LPC31_SYSCREG_PAD_MLCDDB0 (LPC31_SYSCREG_VBASE+LPC31_SYSCREG_PAD_MLCDDB0_OFFSET) +#define LPC31_SYSCREG_PAD_EBIDQM0NOE (LPC31_SYSCREG_VBASE+LPC31_SYSCREG_PAD_EBIDQM0NOE_OFFSET) +#define LPC31_SYSCREG_PAD_EBID0 (LPC31_SYSCREG_VBASE+LPC31_SYSCREG_PAD_EBID0_OFFSET) +#define LPC31_SYSCREG_PAD_EBID1 (LPC31_SYSCREG_VBASE+LPC31_SYSCREG_PAD_EBID1_OFFSET) +#define LPC31_SYSCREG_PAD_EBID2 (LPC31_SYSCREG_VBASE+LPC31_SYSCREG_PAD_EBID2_OFFSET) +#define LPC31_SYSCREG_PAD_EBID3 (LPC31_SYSCREG_VBASE+LPC31_SYSCREG_PAD_EBID3_OFFSET) +#define LPC31_SYSCREG_PAD_EBID5 (LPC31_SYSCREG_VBASE+LPC31_SYSCREG_PAD_EBID5_OFFSET) +#define LPC31_SYSCREG_PAD_EBID6 (LPC31_SYSCREG_VBASE+LPC31_SYSCREG_PAD_EBID6_OFFSET) +#define LPC31_SYSCREG_PAD_EBID7 (LPC31_SYSCREG_VBASE+LPC31_SYSCREG_PAD_EBID7_OFFSET) +#define LPC31_SYSCREG_PAD_EBID8 (LPC31_SYSCREG_VBASE+LPC31_SYSCREG_PAD_EBID8_OFFSET) +#define LPC31_SYSCREG_PAD_EBID15 (LPC31_SYSCREG_VBASE+LPC31_SYSCREG_PAD_EBID15_OFFSET) +#define LPC31_SYSCREG_PAD_I2STXDATA1 (LPC31_SYSCREG_VBASE+LPC31_SYSCREG_PAD_I2STXDATA1_OFFSET) +#define LPC31_SYSCREG_PAD_I2STXBCK1 (LPC31_SYSCREG_VBASE+LPC31_SYSCREG_PAD_I2STXBCK1_OFFSET) +#define LPC31_SYSCREG_PAD_I2STXWS1 (LPC31_SYSCREG_VBASE+LPC31_SYSCREG_PAD_I2STXWS1_OFFSET) +#define LPC31_SYSCREG_PAD_I2SRXDATA0 (LPC31_SYSCREG_VBASE+LPC31_SYSCREG_PAD_I2SRXDATA0_OFFSET) +#define LPC31_SYSCREG_PAD_I2SRXWS0 (LPC31_SYSCREG_VBASE+LPC31_SYSCREG_PAD_I2SRXWS0_OFFSET) +#define LPC31_SYSCREG_PAD_I2SRXDATA1 (LPC31_SYSCREG_VBASE+LPC31_SYSCREG_PAD_I2SRXDATA1_OFFSET) +#define LPC31_SYSCREG_PAD_I2SRXBCK1 (LPC31_SYSCREG_VBASE+LPC31_SYSCREG_PAD_I2SRXBCK1_OFFSET) +#define LPC31_SYSCREG_PAD_I2SRXWS1 (LPC31_SYSCREG_VBASE+LPC31_SYSCREG_PAD_I2SRXWS1_OFFSET) +#define LPC31_SYSCREG_PAD_SYSCLKO (LPC31_SYSCREG_VBASE+LPC31_SYSCREG_PAD_SYSCLKO_OFFSET) +#define LPC31_SYSCREG_PAD_PWMDATA (LPC31_SYSCREG_VBASE+LPC31_SYSCREG_PAD_PWMDATA_OFFSET) +#define LPC31_SYSCREG_PAD_UARTRXD (LPC31_SYSCREG_VBASE+LPC31_SYSCREG_PAD_UARTRXD_OFFSET) +#define LPC31_SYSCREG_PAD_UARTTXD (LPC31_SYSCREG_VBASE+LPC31_SYSCREG_PAD_UARTTXD_OFFSET) +#define LPC31_SYSCREG_PAD_I2CSDA1 (LPC31_SYSCREG_VBASE+LPC31_SYSCREG_PAD_I2CSDA1_OFFSET) +#define LPC31_SYSCREG_PAD_I2CSCL1 (LPC31_SYSCREG_VBASE+LPC31_SYSCREG_PAD_I2CSCL1_OFFSET) +#define LPC31_SYSCREG_PAD_CLK256FSO (LPC31_SYSCREG_VBASE+LPC31_SYSCREG_PAD_CLK256FSO_OFFSET) +#define LPC31_SYSCREG_PAD_GPIO0 (LPC31_SYSCREG_VBASE+LPC31_SYSCREG_PAD_GPIO0_OFFSET) +#define LPC31_SYSCREG_PAD_GPIO2 (LPC31_SYSCREG_VBASE+LPC31_SYSCREG_PAD_GPIO2_OFFSET) +#define LPC31_SYSCREG_PAD_GPIO3 (LPC31_SYSCREG_VBASE+LPC31_SYSCREG_PAD_GPIO3_OFFSET) +#define LPC31_SYSCREG_PAD_GPIO4 (LPC31_SYSCREG_VBASE+LPC31_SYSCREG_PAD_GPIO4_OFFSET) +#define LPC31_SYSCREG_PAD_GPIO11 (LPC31_SYSCREG_VBASE+LPC31_SYSCREG_PAD_GPIO11_OFFSET) +#define LPC31_SYSCREG_PAD_GPIO12 (LPC31_SYSCREG_VBASE+LPC31_SYSCREG_PAD_GPIO12_OFFSET) +#define LPC31_SYSCREG_PAD_GPIO13 (LPC31_SYSCREG_VBASE+LPC31_SYSCREG_PAD_GPIO13_OFFSET) +#define LPC31_SYSCREG_PAD_GPIO14 (LPC31_SYSCREG_VBASE+LPC31_SYSCREG_PAD_GPIO14_OFFSET) +#define LPC31_SYSCREG_PAD_GPIO15 (LPC31_SYSCREG_VBASE+LPC31_SYSCREG_PAD_GPIO15_OFFSET) +#define LPC31_SYSCREG_PAD_GPIO16 (LPC31_SYSCREG_VBASE+LPC31_SYSCREG_PAD_GPIO16_OFFSET) +#define LPC31_SYSCREG_PAD_GPIO17 (LPC31_SYSCREG_VBASE+LPC31_SYSCREG_PAD_GPIO17_OFFSET) +#define LPC31_SYSCREG_PAD_GPIO18 (LPC31_SYSCREG_VBASE+LPC31_SYSCREG_PAD_GPIO18_OFFSET) +#define LPC31_SYSCREG_PAD_GPIO19 (LPC31_SYSCREG_VBASE+LPC31_SYSCREG_PAD_GPIO19_OFFSET) +#define LPC31_SYSCREG_PAD_GPIO20 (LPC31_SYSCREG_VBASE+LPC31_SYSCREG_PAD_GPIO20_OFFSET) +#define LPC31_SYSCREG_PAD_SPIMISO (LPC31_SYSCREG_VBASE+LPC31_SYSCREG_PAD_SPIMISO_OFFSET) +#define LPC31_SYSCREG_PAD_SPIMOSI (LPC31_SYSCREG_VBASE+LPC31_SYSCREG_PAD_SPIMOSI_OFFSET) +#define LPC31_SYSCREG_PAD_SPICSIN (LPC31_SYSCREG_VBASE+LPC31_SYSCREG_PAD_SPICSIN_OFFSET) +#define LPC31_SYSCREG_PAD_SPISCK (LPC31_SYSCREG_VBASE+LPC31_SYSCREG_PAD_SPISCK_OFFSET) +#define LPC31_SYSCREG_PAD_SPICSOUT0 (LPC31_SYSCREG_VBASE+LPC31_SYSCREG_PAD_SPICSOUT0_OFFSET) +#define LPC31_SYSCREG_PAD_NANDNCS0 (LPC31_SYSCREG_VBASE+LPC31_SYSCREG_PAD_NANDNCS0_OFFSET) +#define LPC31_SYSCREG_PAD_NANDNCS1 (LPC31_SYSCREG_VBASE+LPC31_SYSCREG_PAD_NANDNCS1_OFFSET) +#define LPC31_SYSCREG_PAD_NANDNCS2 (LPC31_SYSCREG_VBASE+LPC31_SYSCREG_PAD_NANDNCS2_OFFSET) +#define LPC31_SYSCREG_PAD_MLCDCSB (LPC31_SYSCREG_VBASE+LPC31_SYSCREG_PAD_MLCDCSB_OFFSET) +#define LPC31_SYSCREG_PAD_MLCDDB1 (LPC31_SYSCREG_VBASE+LPC31_SYSCREG_PAD_MLCDDB1_OFFSET) +#define LPC31_SYSCREG_PAD_MLCDERD (LPC31_SYSCREG_VBASE+LPC31_SYSCREG_PAD_MLCDERD_OFFSET) +#define LPC31_SYSCREG_PAD_MLCDRS (LPC31_SYSCREG_VBASE+LPC31_SYSCREG_PAD_MLCDRS_OFFSET) +#define LPC31_SYSCREG_PAD_MLCDRWWR (LPC31_SYSCREG_VBASE+LPC31_SYSCREG_PAD_MLCDRWWR_OFFSET) +#define LPC31_SYSCREG_PAD_MLCDDB3 (LPC31_SYSCREG_VBASE+LPC31_SYSCREG_PAD_MLCDDB3_OFFSET) +#define LPC31_SYSCREG_PAD_MLCDDB5 (LPC31_SYSCREG_VBASE+LPC31_SYSCREG_PAD_MLCDDB5_OFFSET) +#define LPC31_SYSCREG_PAD_MLCDDB6 (LPC31_SYSCREG_VBASE+LPC31_SYSCREG_PAD_MLCDDB6_OFFSET) +#define LPC31_SYSCREG_PAD_MLCDDB8 (LPC31_SYSCREG_VBASE+LPC31_SYSCREG_PAD_MLCDDB8_OFFSET) +#define LPC31_SYSCREG_PAD_MLCDDB9 (LPC31_SYSCREG_VBASE+LPC31_SYSCREG_PAD_MLCDDB9_OFFSET) +#define LPC31_SYSCREG_PAD_MLCDDB10 (LPC31_SYSCREG_VBASE+LPC31_SYSCREG_PAD_MLCDDB10_OFFSET) +#define LPC31_SYSCREG_PAD_MLCDDB11 (LPC31_SYSCREG_VBASE+LPC31_SYSCREG_PAD_MLCDDB11_OFFSET) +#define LPC31_SYSCREG_PAD_MLCDDB12 (LPC31_SYSCREG_VBASE+LPC31_SYSCREG_PAD_MLCDDB12_OFFSET) +#define LPC31_SYSCREG_PAD_MLCDDB13 (LPC31_SYSCREG_VBASE+LPC31_SYSCREG_PAD_MLCDDB13_OFFSET) +#define LPC31_SYSCREG_PAD_MLCDDB14 (LPC31_SYSCREG_VBASE+LPC31_SYSCREG_PAD_MLCDDB14_OFFSET) +#define LPC31_SYSCREG_PAD_MLCDDB15 (LPC31_SYSCREG_VBASE+LPC31_SYSCREG_PAD_MLCDDB15_OFFSET) +#define LPC31_SYSCREG_PAD_MGPIO5 (LPC31_SYSCREG_VBASE+LPC31_SYSCREG_PAD_MGPIO5_OFFSET) +#define LPC31_SYSCREG_PAD_MGPIO7 (LPC31_SYSCREG_VBASE+LPC31_SYSCREG_PAD_MGPIO7_OFFSET) +#define LPC31_SYSCREG_PAD_MGPIO8 (LPC31_SYSCREG_VBASE+LPC31_SYSCREG_PAD_MGPIO8_OFFSET) +#define LPC31_SYSCREG_PAD_MGPIO10 (LPC31_SYSCREG_VBASE+LPC31_SYSCREG_PAD_MGPIO10_OFFSET) +#define LPC31_SYSCREG_PAD_MNANDRYBN1 (LPC31_SYSCREG_VBASE+LPC31_SYSCREG_PAD_MNANDRYBN1_OFFSET) +#define LPC31_SYSCREG_PAD_MNANDRYBN2 (LPC31_SYSCREG_VBASE+LPC31_SYSCREG_PAD_MNANDRYBN2_OFFSET) +#define LPC31_SYSCREG_PAD_MNANDRYBN3 (LPC31_SYSCREG_VBASE+LPC31_SYSCREG_PAD_MNANDRYBN3_OFFSET) +#define LPC31_SYSCREG_PAD_MUARTCTSN (LPC31_SYSCREG_VBASE+LPC31_SYSCREG_PAD_MUARTCTSN_OFFSET) +#define LPC31_SYSCREG_PAD_MI2STXDATA0 (LPC31_SYSCREG_VBASE+LPC31_SYSCREG_PAD_MI2STXDATA0_OFFSET) +#define LPC31_SYSCREG_PAD_MI2STXWS0 (LPC31_SYSCREG_VBASE+LPC31_SYSCREG_PAD_MI2STXWS0_OFFSET) +#define LPC31_SYSCREG_PAD_EBINRASBLOUT1 (LPC31_SYSCREG_VBASE+LPC31_SYSCREG_PAD_EBINRASBLOUT1_OFFSET) +#define LPC31_SYSCREG_PAD_EBIA0ALE (LPC31_SYSCREG_VBASE+LPC31_SYSCREG_PAD_EBIA0ALE_OFFSET) +#define LPC31_SYSCREG_PAD_EBINWE (LPC31_SYSCREG_VBASE+LPC31_SYSCREG_PAD_EBINWE_OFFSET) +#define LPC31_SYSCREG_PAD_ESHCTRLSUP4 (LPC31_SYSCREG_VBASE+LPC31_SYSCREG_PAD_ESHCTRLSUP4_OFFSET) +#define LPC31_SYSCREG_PAD_ESHCTRLSUP8 (LPC31_SYSCREG_VBASE+LPC31_SYSCREG_PAD_ESHCTRLSUP8_OFFSET) + +/* SYSCREG register bit definitions *********************************************************************/ +/* Miscellaneous system configuration registers, part1 */ + +/* SYSCREG_EBIMPMCPRIO, address 0x13002808 + * SYSCREG_EBINANDCPRIO address 0x1300280c + * SYSCREG_EBIUNUSEDPRIO address 0x13002810 + */ + +#define SYSCREG_EBI_TIMEOUT_SHIFT (0) /* Bits 0-9: Time MPMC, NAND or unused channel */ +#define SYSCREG_EBI_TIMEOUT_MASK (0x3ff << SYSCREG_EBI_TIMEOUT_SHIFT) + +/* RINGOSCCFG address 0x13002814 */ + +#define SYSCREG_RINGOSCCFG_OSC1EN (1 << 1) /* Bit 1: Enable ring oscillator 1 */ +#define SYSCREG_RINGOSCCFG_OSC0EN (1 << 0) /* Bit 0: Enable oscillator 0 */ + +/* SYSCREG_ADCPDADC10BITS address 0x13002818 */ + +#define SYSCREG_ADCPDADC10BITS_PWRDOWN (1 << 0) /* Bit 0: Power down ADC */ + +/* SYSCREG_ABCCFG address 0x13002824 */ + +#define SYSCREG_ABCCFG_USBOTG_SHIFT (9) /* Bits 9-11: USB_OTG AHB bus bandwidth control */ +#define SYSCREG_ABCCFG_USBOTG_MASK (7 << SYSCREG_ABCCFG_USBOTG_SHIFT) +# define SYSCREG_ABCCFG_USBOTG_NORMAL (0 << SYSCREG_ABCCFG_USBOTG_SHIFT) /* Normal mode */ +# define SYSCREG_ABCCFG_USBOTG_NONSEQ (1 << SYSCREG_ABCCFG_USBOTG_SHIFT) /* Make non-sequential */ +# define SYSCREG_ABCCFG_USBOTG_SPLIT4 (2 << SYSCREG_ABCCFG_USBOTG_SHIFT) /* Split to 4-beat */ +# define SYSCREG_ABCCFG_USBOTG_SPLIT8 (3 << SYSCREG_ABCCFG_USBOTG_SHIFT) /* Split to 8-beat */ +# define SYSCREG_ABCCFG_USBOTG_EXT8 (4 << SYSCREG_ABCCFG_USBOTG_SHIFT) /* Extend to 8-beat */ +# define SYSCREG_ABCCFG_USBOTG_EXT16 (5 << SYSCREG_ABCCFG_USBOTG_SHIFT) /* Extend to 16-beat */ +# define SYSCREG_ABCCFG_USBOTG_SPLIT4W (6 << SYSCREG_ABCCFG_USBOTG_SHIFT) /* Split to 4-beat */ +# define SYSCREG_ABCCFG_USBOTG_EXT32 (7 << SYSCREG_ABCCFG_USBOTG_SHIFT) /* extend to 32-beat */ +#define SYSCREG_ABCCFG_ARM926EJSI_SHIFT (6) /* Bits 6-8: ARM926EJS instruction AHB bus bandwidth control */ +#define SYSCREG_ABCCFG_ARM926EJSI_MASK (7 << SYSCREG_ABCCFG_ARM926EJSI_SHIFT) +# define SYSCREG_ABCCFG_ARM926EJSI_NORMAL (0 << SYSCREG_ABCCFG_ARM926EJSI_SHIFT) /* Normal mode */ +# define SYSCREG_ABCCFG_ARM926EJSI_NONSEQ (1 << SYSCREG_ABCCFG_ARM926EJSI_SHIFT) /* Make non-sequential */ +# define SYSCREG_ABCCFG_ARM926EJSI_SPLIT4 (2 << SYSCREG_ABCCFG_ARM926EJSI_SHIFT) /* Split to 4-beat */ +# define SYSCREG_ABCCFG_ARM926EJSI_SPLIT8 (3 << SYSCREG_ABCCFG_ARM926EJSI_SHIFT) /* Split to 8-beat */ +# define SYSCREG_ABCCFG_ARM926EJSI_EXT8 (4 << SYSCREG_ABCCFG_ARM926EJSI_SHIFT) /* Extend to 8-beat */ +# define SYSCREG_ABCCFG_ARM926EJSI_EXT16 (5 << SYSCREG_ABCCFG_ARM926EJSI_SHIFT) /* Extend to 16-beat */ +# define SYSCREG_ABCCFG_ARM926EJSI_SPLIT4W (6 << SYSCREG_ABCCFG_ARM926EJSI_SHIFT) /* Split to 4-beat */ +# define SYSCREG_ABCCFG_ARM926EJSI_EXT32 (7 << SYSCREG_ABCCFG_ARM926EJSI_SHIFT) /* extend to 32-beat */ +#define SYSCREG_ABCCFG_ARM926EJSD_SHIFT (3) /* Bits 3-5: ARM926EJS data AHB bus bandwidth control */ +#define SYSCREG_ABCCFG_ARM926EJSD_MASK (7 << SYSCREG_ABCCFG_ARM926EJSD_SHIFT) +# define SYSCREG_ABCCFG_ARM926EJSD_NORMAL (0 << SYSCREG_ABCCFG_ARM926EJSD_SHIFT) /* Normal mode */ +# define SYSCREG_ABCCFG_ARM926EJSD_NONSEQ (1 << SYSCREG_ABCCFG_ARM926EJSD_SHIFT) /* Make non-sequential */ +# define SYSCREG_ABCCFG_ARM926EJSD_SPLIT4 (2 << SYSCREG_ABCCFG_ARM926EJSD_SHIFT) /* Split to 4-beat */ +# define SYSCREG_ABCCFG_ARM926EJSD_SPLIT8 (3 << SYSCREG_ABCCFG_ARM926EJSD_SHIFT) /* Split to 8-beat */ +# define SYSCREG_ABCCFG_ARM926EJSD_EXT8 (4 << SYSCREG_ABCCFG_ARM926EJSD_SHIFT) /* Extend to 8-beat */ +# define SYSCREG_ABCCFG_ARM926EJSD_EXT16 (5 << SYSCREG_ABCCFG_ARM926EJSD_SHIFT) /* Extend to 16-beat */ +# define SYSCREG_ABCCFG_ARM926EJSD_SPLIT4W (6 << SYSCREG_ABCCFG_ARM926EJSD_SHIFT) /* Split to 4-beat */ +# define SYSCREG_ABCCFG_ARM926EJSD_EXT32 (7 << SYSCREG_ABCCFG_ARM926EJSD_SHIFT) /* extend to 32-beat */ +#define SYSCREG_ABCCFG_DMA_SHIFT (0) /* Bits 0-2: 2:0 DMA AHB bus bandwidth control */ +#define SYSCREG_ABCCFG_DMA_MASK (7 << SYSCREG_ABCCFG_DMA_SHIFT) +# define SYSCREG_ABCCFG_DMA_NORMAL (0 << SYSCREG_ABCCFG_DMA_SHIFT) /* Normal mode */ +# define SYSCREG_ABCCFG_DMA_NONSEQ (1 << SYSCREG_ABCCFG_DMA_SHIFT) /* Make non-sequential */ +# define SYSCREG_ABCCFG_DMA_SPLIT4 (2 << SYSCREG_ABCCFG_DMA_SHIFT) /* Split to 4-beat */ +# define SYSCREG_ABCCFG_DMA_SPLIT8 (3 << SYSCREG_ABCCFG_DMA_SHIFT) /* Split to 8-beat */ +# define SYSCREG_ABCCFG_DMA_EXT8 (4 << SYSCREG_ABCCFG_DMA_SHIFT) /* Extend to 8-beat */ +# define SYSCREG_ABCCFG_DMA_EXT16 (5 << SYSCREG_ABCCFG_DMA_SHIFT) /* Extend to 16-beat */ +# define SYSCREG_ABCCFG_DMA_SPLIT4W (6 << SYSCREG_ABCCFG_DMA_SHIFT) /* Split to 4-beat */ +# define SYSCREG_ABCCFG_DMA_EXT32 (7 << SYSCREG_ABCCFG_DMA_SHIFT) /* extend to 32-beat */ + +/* SYSCREG_SDMMCCFG address 0x13002828 */ + +#define SYSCREG_SDMMCCFG_CARDDETECT (1 << 1) /* Bit 1: Card detect signal */ +#define SYSCREG_SDMMCCFG_CARDWRITEPRT (1 << 0) /* Bit 0: Card write protect signal for SD cards */ + +/* SYSCREG_MCIDELAYMODES address 0x1300282c */ + +#define SYSCREG_MCIDELAYMODES_DELAYENABLE (1 << 4) /* Bit 4: Enable delay cells */ +#define SYSCREG_MCIDELAYMODES_DELAYCELLS_SHIFT (0) /* Bits 0-3: Number of delay cells needed */ +#define SYSCREG_MCIDELAYMODES_DELAYCELLS_MASK (15 << SYSCREG_MCIDELAYMODES_DELAYCELLS_SHIFT) + +/* USB configuration registers */ +/* USB_ATXPLLPDREG address 0x13002830 */ + +#define SYSCREG_USB_ATXPLLPDREG_PWRDOWN (1 << 0) /* Bit 0: Powerdown */ + +/* USB_OTGCFG address 0x13002834 */ + +#define SYSCREG_USB_OTGCFG_VBUSPWRFAULT (1 << 3) /* Bit 3: Charge pump overcurrent */ +#define SYSCREG_USB_OTGCFG_DEVWAKEUP (1 << 2) /* Bit 2: External wakeup (device mode) */ +#define SYSCREG_USB_OTGCFG_HOSTWAKEUP (1 << 1) /* Bit 1: External wake-up (host mode) */ + +/* USB_OTGPORTINDCTL address 0x1300 2838 */ + +#define SYSCREG_USB_OTGPORTINDCTL_SHIFT (0) /* Bits 0-1: Status bits for USB connector LEDs */ +#define SYSCREG_USB_OTGPORTINDCTL_MASK (3 << SYSCREG_USB_OTGPORTINDCTL_SHIFT) +# define SYSCREG_USB_OTGPORTINDCTL_OFF (0 << SYSCREG_USB_OTGPORTINDCTL_SHIFT) /* off */ +# define SYSCREG_USB_OTGPORTINDCTL_AMBER (1 << SYSCREG_USB_OTGPORTINDCTL_SHIFT) /* amber */ +# define SYSCREG_USB_OTGPORTINDCTL_GREEN (2 << SYSCREG_USB_OTGPORTINDCTL_SHIFT) /* green */ + +/* USB_PLLNDEC address 0x13002840 */ + +#define SYSCREG_USB_PLLNDEC_SHIFT (0) /* Bits 0-9: Pre-divider for the USB pll */ +#define SYSCREG_USB_PLLNDEC_MASK (0x3ff << SYSCREG_USB_PLLNDEC_SHIFT) + +/* USB_PLLMDEC address 0x13002844 */ + +#define SYSCREG_USB_PLLMDEC_SHIFT (0) /* Bits 0-16: Feedback-divider for the USB pll */ +#define SYSCREG_USB_PLLMDEC_MASK (0x1ffff << SYSCREG_USB_PLLMDEC_SHIFT) + +/* USB_PLLPDEC address 0x13002848 */ + +#define SYSCREG_USB_PLLPDEC_SHIFT (0) /* Bits 0-3: Feedback-divider for the USB pll */ +#define SYSCREG_USB_PLLPDEC_MASK (15 << SYSCREG_USB_PLLPDEC_SHIFT) + +/* USB_PLLSELR address 0x1300284c */ + +#define SYSCREG_USB_PLLSELR_SHIFT (0) /* Bits 0-3: Bandwidth selection */ +#define SYSCREG_USB_PLLSELR_MASK (15 << SYSCREG_USB_PLLSELR_SHIFT) + +/* USB_PLLSELI address 0x13002850 */ + +#define SYSCREG_USB_PLLSELI_SHIFT (0) /* Bits 0-3: Bandwidth selection */ +#define SYSCREG_USB_PLLSELI_MASK (15 << SYSCREG_USB_PLLSELI_SHIFT) + +/* USB_PLLSELP address 0x13002854 */ + +#define SYSCREG_USB_PLLSELP_SHIFT (0) /* Bits 0-3: Bandwidth selection */ +#define SYSCREG_USB_PLLSELP_MASK (15 << SYSCREG_USB_PLLSELP_SHIFT) + +/* ISRAM/ISROM configuration registers */ +/* SYSCREG_ISRAM0_LATENCYCFG address 0x13002858 */ + +#define SYSCREG_ISRAM0_LATENCYCFG_SHIFT (0) /* Bits 0-1: Number of waitstates */ +#define SYSCREG_ISRAM0_LATENCYCFG_MASK (3 << SYSCREG_ISRAM0_LATENCYCFG_SHIFT) + +/* SYSCREG_ISRAM1_LATENCYCFG address 0x1300285c */ + +#define SYSCREG_ISRAM1_LATENCYCFG_SHIFT (0) /* Bits 0-1: Number of waitstates */ +#define SYSCREG_ISRAM1_LATENCYCFG_MASK (3 << SYSCREG_ISRAM1_LATENCYCFG_SHIFT) + +/* SYSCREG_ISROM_LATENCYCFG address 0x13002860 */ + +#define SYSCREG_ISROM_LATENCYCFG_SHIFT (0) /* Bits 0-1: Number of waitstates */ +#define SYSCREG_ISROM_LATENCYCFG_MASK (3 << SYSCREG_ISROM_LATENCYCFG_SHIFT) + +/* MPMC configuration registers */ +/* SYSCREG_AHB_MPMC_MISC (address 0x13002864 */ + +#define SYSCREG_MPMC_MISC_REL1CONFIG (1 << 8) /* Bit 8: Static memory address mode select */ +#define SYSCREG_MPMC_MISC_STCS1PB (1 << 7) /* Bit 7: Polarity of byte lane select for static memory CS1 */ +#define SYSCREG_MPMC_MISC_STCS1POL (1 << 4) /* Bit 4: Polarity of static memory CS1 */ +#define SYSCREG_MPMC_MISC_STCS0POL (1 << 3) /* Bit 3: Polarity of static memory CS0 */ +#define SYSCREG_MPMC_MISC_SREFREQ (1 << 0) /* Bit 0: Self refresh request */ + +/* SYSCREG_MPMC_DELAYMODES address 0x13002868 */ + +#define SYSCREG_MPMC_DELAYMODES_DEL1_SHIFT (12) /* Bits 12-17: Delay cells for MPMCCLKOUT */ +#define SYSCREG_MPMC_DELAYMODES_DEL1_MASK (63 << SYSCREG_MPMC_DELAYMODES_DEL1_SHIFT) +#define SYSCREG_MPMC_DELAYMODES_DEL2_SHIFT (6) /* Bits 6-11: Delay cells between MPMCCLK and MPMCCLKDELAY */ +#define SYSCREG_MPMC_DELAYMODES_DEL2_MASK (63 << SYSCREG_MPMC_DELAYMODES_DEL2_SHIFT) +#define SYSCREG_MPMC_DELAYMODES_DEL3_SHIFT (0) /* Bits 0-5: Delay cells between MPMCCLK and MPMCFBCLKIN */ +#define SYSCREG_MPMC_DELAYMODES_DEL3_MASK (63 << SYSCREG_MPMC_DELAYMODES_DEL3_SHIFT) + +/* SYSCREG_MPMC_WAITRD0 address 0x1300286c */ + +#define SYSCREG_MPMC_WAITRD0_EXTRAOE (1 << 5) /* Bit 5: Enable the extra inactive OE cycle */ +#define SYSCREG_MPMC_WAITRD0_SHIFT (0) /* Bits 0-4: Value for MPMCStaticWaitRd0 */ +#define SYSCREG_MPMC_WAITRD0_MASK (31 << SYSCREG_MPMC_WAITRD0_SHIFT) + +/* SYSCREG_MPMC_WAITRD1 address 0x13002870 */ + +#define SYSCREG_MPMC_WAITRD1_EXTRAOE (1 << 5) /* Bit 5: Enable the extra inactive OE cycle */ +#define SYSCREG_MPMC_WAITRD1_SHIFT (0) /* Bits 0-4: Value for MPMCStaticWaitRd1 */ +#define SYSCREG_MPMC_WAITRD1_MASK (31 << SYSCREG_MPMC_WAITRD1_SHIFT) + +/* SYSCREG_WIR_EBIMSINIT address 0x13002874 */ + +#define SYSCREG_MPMC_WIREEBIMSZ_SHIFT (0) /* Bits 0-1: Memory width of CS1 */ +#define SYSCREG_MPMC_WIREEBIMSZ_MASK (3 << SYSCREG_MPMC_WIREEBIMSZ_SHIFT) + +/* MPMC_TESTMODE0 address 0x13002878 */ + +#define SYSCREG_MPMC_TESTMODE0_EXTREFENABLE (1 << 12) /* Bit 13: External refresh of MPMC */ +#define SYSCREG_MPMC_TESTMODE0_EXTREFCNT_SHIFT (0) /* Bits 0-11: Period of external refresh */ +#define SYSCREG_MPMC_TESTMODE0_EXTREFCNT_MASK (0xfff << SYSCREG_MPMC_TESTMODE0_EXTREFCNT_SHIFT) + +/* MPMC_TESTMODE1 address 0x1300287c */ + +#define SYSCREG_MPMC_TESTMODE1_HSENABLE_SHIFT (0) /* Bits 0-7: Allows AHB to run faster while refreshing */ +#define SYSCREG_MPMC_TESTMODE1_HSENABLE_MASK (0xff << SYSCREG_MPMC_TESTMODE1_HSENABLE_SHIFT) + +/* Miscellaneous system configuration registers, part 2 */ +/* AHB0EXTPRIO address 0x13002880 */ + +#define SYSCREG_AHB0EXTPRIO_USBOTG (1 << 3) /* Bit 3: USBOTG has higher priority */ +#define SYSCREG_AHB0EXTPRIO_ARM926DATA (1 << 2) /* Bit 2: ARM926 Data has higher priority */ +#define SYSCREG_AHB0EXTPRIO_ARM926NSTR (1 << 1) /* Bit 1: ARM926 Instruction has higher priority */ +#define SYSCREG_AHB0EXTPRIO_DMA (1 << 0) /* Bit 0: DMA has higher priority */ + +/* Pin multiplexing control registers */ +/* SYSCREG_MUX_LCDEBISEL address 0x13002890 */ + +#define SYSCREG_MUX_LCDEBISEL_EBIMPMC (1 << 0) /* Bit 0: Selects between LCD and EBI/MPMC pins */ + +/* SYSCREG_MUX_GPIOMCISEL address 0x13002894 */ + +#define SYSCREG_MUX_GPIOMCISEL_MCI (1 << 0) /* Bit 0: Selects between GPIO and MCI pins */ + +/* SYSCREG_MUX_NANDMCISEL address 0x13002898 */ + +#define SYSCREG_MUX_NANDMCISEL_MCI (1 << 0) /* Bit 0: Selects between NAND and MCI pins */ + +/* SYSCREG_MUX_UARTSPISEL address 0x1300289c */ + +#define SYSCREG_MUX_UARTSPISEL_SPI (1 << 0) /* Bit 0: Selects between SPI and UART pins */ + +/* SYSCREG_MUX_I2STXIPCMSEL address 0x130028a0 */ + +#define SYSCREG_MUX_I2STXPCMSEL_PCM (1 << 0) /* Bit 0: Selects between I2STX_0 and IPINT_1 pins */ + +/* Pad configuration registers */ +/* SYSCREG_PAD_padname addresses 0x130028a4 to 0x13002a28 */ + +#define SYSCREG_PAD_P2 (1 << 1) /* Bit 1: The logic pin p2 of the pad */ +#define SYSCREG_PAD_P1 (1 << 0) /* Bit 0: The logic pin p1 of the pad */ +#define SYSCREG_PAD_PULLUP (0) +#define SYSCREG_PAD_INPUT (SYSCREG_PAD_P2) +#define SYSCREG_PAD_REPEATER (SYSCREG_PAD_P1) +#define SYSCREG_PAD_WEAKPULLUP (SYSCREG_PAD_P1|SYSCREG_PAD_P2) + +/* SYSCREG_ESHCTRLSUP4 address 0x13002a2c */ + +#define SYSCREG_PAD_ESHCTRLSUP4_LESS (1 << 0) /* Bit 0: Domain SUP4 less switching noise */ + +/* SYSCREG_ESHCTRLSUP8 address 0x13002a2c */ + +#define SYSCREG_PAD_ESHCTRLSUP8_LESS (1 << 0) /* Bit 0: Domain SUP8 switching less noise */ +/******************************************************************************************************** + * Public Types + ********************************************************************************************************/ + +/******************************************************************************************************** + * Public Data + ********************************************************************************************************/ + +/******************************************************************************************************** + * Public Functions + ********************************************************************************************************/ + +#endif /* __ARCH_ARM_SRC_LPC31XX_LPC31_SYSCREG_H */ diff --git a/nuttx/arch/arm/src/lpc31xx/lpc31_timer.h b/nuttx/arch/arm/src/lpc31xx/lpc31_timer.h new file mode 100755 index 000000000..88deb1756 --- /dev/null +++ b/nuttx/arch/arm/src/lpc31xx/lpc31_timer.h @@ -0,0 +1,119 @@ +/************************************************************************************************ + * arch/arm/src/lpc31xx/lpc31_timer.h + * + * Copyright (C) 2009-2010 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * 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_LPC31XX_LPC31_TIMER_H +#define __ARCH_ARM_SRC_LPC31XX_LPC31_TIMER_H + +/************************************************************************************************ + * Included Files + ************************************************************************************************/ + +#include +#include "lpc31_memorymap.h" + +/************************************************************************************************ + * Pre-processor Definitions + ************************************************************************************************/ + +/* TIMER register base address offset into the APB1 domain **************************************/ + +#define LPC31_TIMER0_VBASE (LPC31_APB1_VADDR+LPC31_APB1_TIMER0_OFFSET) +#define LPC31_TIMER0_PBASE (LPC31_APB1_PADDR+LPC31_APB1_TIMER0_OFFSET) + +#define LPC31_TIMER1_VBASE (LPC31_APB1_VADDR+LPC31_APB1_TIMER1_OFFSET) +#define LPC31_TIMER1_PBASE (LPC31_APB1_PADDR+LPC31_APB1_TIMER1_OFFSET) + +#define LPC31_TIMER2_VBASE (LPC31_APB1_VADDR+LPC31_APB1_TIMER2_OFFSET) +#define LPC31_TIMER2_PBASE (LPC31_APB1_PADDR+LPC31_APB1_TIMER2_OFFSET) + +#define LPC31_TIMER3_VBASE (LPC31_APB1_VADDR+LPC31_APB1_TIMER3_OFFSET) +#define LPC31_TIMER3_PBASE (LPC31_APB1_PADDR+LPC31_APB1_TIMER3_OFFSET) + +/* TIMER register offsets (with respect to the TIMERn base) *************************************/ + +#define LPC31_TIMER_LOAD_OFFSET 0x00 /* Timer reload value */ +#define LPC31_TIMER_VALUE_OFFSET 0x04 /* Current timer value */ +#define LPC31_TIMER_CTRL_OFFSET 0x08 /* Timer nable/disable and pre-scale */ +#define LPC31_TIMER_CLEAR_OFFSET 0x0c /* Clear timer interrupt */ + +/* TIMER register (virtual) addresses ***********************************************************/ + +#define LPC31_TIMER0_LOAD (LPC31_TIMER0_VBASE+LPC31_TIMER_LOAD_OFFSET) +#define LPC31_TIMER0_VALUE (LPC31_TIMER0_VBASE+LPC31_TIMER_VALUE_OFFSET) +#define LPC31_TIMER0_CTRL (LPC31_TIMER0_VBASE+LPC31_TIMER_CTRL_OFFSET) +#define LPC31_TIMER0_CLEAR (LPC31_TIMER0_VBASE+LPC31_TIMER_CLEAR_OFFSET) + +#define LPC31_TIMER1_LOAD (LPC31_TIMER1_VBASE+LPC31_TIMER_LOAD_OFFSET) +#define LPC31_TIMER1_VALUE (LPC31_TIMER1_VBASE+LPC31_TIMER_VALUE_OFFSET) +#define LPC31_TIMER1_CTRL (LPC31_TIMER1_VBASE+LPC31_TIMER_CTRL_OFFSET) +#define LPC31_TIMER1_CLEAR (LPC31_TIMER1_VBASE+LPC31_TIMER_CLEAR_OFFSET) + +#define LPC31_TIMER2_LOAD (LPC31_TIMER2_VBASE+LPC31_TIMER_LOAD_OFFSET) +#define LPC31_TIMER2_VALUE (LPC31_TIMER2_VBASE+LPC31_TIMER_VALUE_OFFSET) +#define LPC31_TIMER2_CTRL (LPC31_TIMER2_VBASE+LPC31_TIMER_CTRL_OFFSET) +#define LPC31_TIMER2_CLEAR (LPC31_TIMER2_VBASE+LPC31_TIMER_CLEAR_OFFSET) + +#define LPC31_TIMER3_LOAD (LPC31_TIMER3_VBASE+LPC31_TIMER_LOAD_OFFSET) +#define LPC31_TIMER3_VALUE (LPC31_TIMER3_VBASE+LPC31_TIMER_VALUE_OFFSET) +#define LPC31_TIMER3_CTRL (LPC31_TIMER3_VBASE+LPC31_TIMER_CTRL_OFFSET) +#define LPC31_TIMER3_CLEAR (LPC31_TIMER3_VBASE+LPC31_TIMER_CLEAR_OFFSET) + +/* TIMER register bit definitions ***************************************************************/ + +/* Timer Control register TIMER0_CTRL, address 0x13008008 TIMER1_CTRL, address 0x13008408 + * TIMER2_CTRL, address 0x13008808 TIMER3_CTRL, adddress 0x13008c08 + */ + +#define TIMER_CTRL_ENABLE (1 << 7) /* Bit 7: Timer enable */ +#define TIMER_CTRL_PERIODIC (1 << 6) /* Bit 6: Periodic timer mode */ +#define TIMER_CTRL_PRESCALE_SHIFT (2) /* Bits 2-3: Timer pre-scale */ +#define TIMER_CTRL_PRESCALE_MASK (3 << TIMER_CTRL_PRESCALE_SHIFT) +# define TIMER_CTRL_PRESCALE_DIV1 (0 << TIMER_CTRL_PRESCALE_SHIFT) /* Divider=1 Stages=0 */ +# define TIMER_CTRL_PRESCALE_DIV16 (1 << TIMER_CTRL_PRESCALE_SHIFT) /* Divider=16 Stages4 */ +# define TIMER_CTRL_PRESCALE_DIV256 (2 << TIMER_CTRL_PRESCALE_SHIFT) /* Divider=256 Stages=8 */ + +/************************************************************************************************ + * Public Types + ************************************************************************************************/ + +/************************************************************************************************ + * Public Data + ************************************************************************************************/ + +/************************************************************************************************ + * Public Functions + ************************************************************************************************/ + +#endif /* __ARCH_ARM_SRC_LPC31XX_LPC31_TIMER_H */ diff --git a/nuttx/arch/arm/src/lpc31xx/lpc31_timerisr.c b/nuttx/arch/arm/src/lpc31xx/lpc31_timerisr.c new file mode 100755 index 000000000..1a484477e --- /dev/null +++ b/nuttx/arch/arm/src/lpc31xx/lpc31_timerisr.c @@ -0,0 +1,162 @@ +/**************************************************************************** + * arch/arm/src/lpc31xx/lpc31_timerisr.c + * + * Copyright (C) 2009 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name NuttX nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include +#include + +#include +#include + +#include "clock_internal.h" +#include "up_internal.h" +#include "up_arch.h" + +#include "lpc31_timer.h" +#include "lpc31_internal.h" + +/**************************************************************************** + * Definitions + ****************************************************************************/ + +/**************************************************************************** + * 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. + * + ****************************************************************************/ + +int up_timerisr(int irq, uint32_t *regs) +{ + /* Clear the lattched timer interrupt (Writing any value to the CLEAR register + * clears the interrupt generated by the counter timer + */ + + putreg32(1, LPC31_TIMER0_CLEAR); + + /* Process timer interrupt */ + + sched_process_timer(); + return 0; +} + +/**************************************************************************** + * Function: up_timerinit + * + * Description: + * This function is called during start-up to initialize + * the timer interrupt. + * + ****************************************************************************/ + +void up_timerinit(void) +{ + uint32_t regval; + uint64_t load; + uint64_t freq; + + /* Enable the timer0 system clock */ + + lpc31_enableclock(CLKID_TIMER0PCLK); + + /* Soft reset the timer0 module so that we start in a known state */ + + lpc31_softreset(RESETID_TIMER0RST); + + /* Set timer load register to 10mS (100Hz). First, get the frequency + * of the timer0 module clock (in the AHB0APB1_BASE domain (2)). + */ + + freq = (uint64_t)lpc31_clkfreq(CLKID_TIMER0PCLK, DOMAINID_AHB0APB1); + + /* If the clock is >1MHz, use pre-dividers */ + + regval = getreg32(LPC31_TIMER0_CTRL); + if (freq > 1000000) + { + /* Use the divide by 16 pre-divider */ + + regval &= ~TIMER_CTRL_PRESCALE_MASK; + regval |= TIMER_CTRL_PRESCALE_DIV16; + freq >>= 4; + } + + load =((freq * (uint64_t)10000) / 1000000); + putreg32((uint32_t)load, LPC31_TIMER0_LOAD); + + /* Set periodic mode */ + + regval |= TIMER_CTRL_PERIODIC; + putreg32(regval, LPC31_TIMER0_CTRL); + + /* Attach the timer interrupt vector */ + + (void)irq_attach(LPC31_IRQ_TMR0, (xcpt_t)up_timerisr); + + /* Clear any latched timer interrupt (Writing any value to the CLEAR register + * clears the latched interrupt generated by the counter timer) + */ + + putreg32(1, LPC31_TIMER0_CLEAR); + + /* Enable timers (starts counting) */ + + regval |= TIMER_CTRL_ENABLE; + putreg32(regval, LPC31_TIMER0_CTRL); + + /* Enable timer match interrupts in the interrupt controller */ + + up_enable_irq(LPC31_IRQ_TMR0); +} diff --git a/nuttx/arch/arm/src/lpc31xx/lpc31_uart.h b/nuttx/arch/arm/src/lpc31xx/lpc31_uart.h new file mode 100755 index 000000000..f80fe4d92 --- /dev/null +++ b/nuttx/arch/arm/src/lpc31xx/lpc31_uart.h @@ -0,0 +1,263 @@ +/************************************************************************************************ + * arch/arm/src/lpc31xx/lpc31_uart.h + * + * Copyright (C) 2009 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * 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_LPC31XX_LPC31_UART_H +#define __ARCH_ARM_SRC_LPC31XX_LPC31_UART_H + +/************************************************************************************************ + * Included Files + ************************************************************************************************/ + +#include +#include "lpc31_memorymap.h" + +/************************************************************************************************ + * Pre-processor Definitions + ************************************************************************************************/ + +/* UART register base address offset into the APB2 domain ***************************************/ + +#define LPC31_UART_VBASE (LPC31_APB2_VSECTION+LPC31_APB2_UART_OFFSET) +#define LPC31_UART_PBASE (LPC31_APB2_PSECTION+LPC31_APB2_UART_OFFSET) + +/* UART register offsets (with respect to the UART base) ****************************************/ + +#define LPC31_UART_RBR_OFFSET 0x000 /* Receiver Buffer Register */ +#define LPC31_UART_THR_OFFSET 0x000 /* Transmitter Holding Register */ +#define LPC31_UART_DLL_OFFSET 0x000 /* Divisor Latch LSB */ +#define LPC31_UART_DLM_OFFSET 0x004 /* Divisor Latch MSB */ +#define LPC31_UART_IER_OFFSET 0x004 /* Interrupt Enable Register */ +#define LPC31_UART_IIR_OFFSET 0x008 /* Interrupt Identification Register */ +#define LPC31_UART_FCR_OFFSET 0x008 /* FIFO Control Register */ +#define LPC31_UART_LCR_OFFSET 0x00c /* Line Control Register */ +#define LPC31_UART_MCR_OFFSET 0x010 /* Modem Control Register */ +#define LPC31_UART_LSR_OFFSET 0x014 /* Line Status Register */ +#define LPC31_UART_MSR_OFFSET 0x018 /* Modem status Register */ +#define LPC31_UART_SCR_OFFSET 0x01c /* Scratch Register */ + /* 0x020: Reserved */ +#define LPC31_UART_ICR_OFFSET 0x024 /* IrDA Control Register */ +#define LPC31_UART_FDR_OFFSET 0x028 /* Fractional Divider Register */ + /* 0x02c: Reserved */ +#define LPC31_UART_POP_OFFSET 0x030 /* NHP Pop Register */ +#define LPC31_UART_MODE_OFFSET 0x034 /* NHP Mode Selection Register */ + /* 0x038-0xfd4: Reserved */ +#define LPC31_UART_INTCE_OFFSET 0xfd8 /* Interrupt Clear Enable Register */ +#define LPC31_UART_INTSE_OFFSET 0xfdc /* Interrupt Set Enable Register */ +#define LPC31_UART_INTS_OFFSET 0xfe0 /* Interrupt Status Register */ +#define LPC31_UART_INTE_OFFSET 0xfe4 /* Interrupt Enable Register */ +#define LPC31_UART_INTCS_OFFSET 0xfe8 /* Interrupt Clear Status Register */ +#define LPC31_UART_INTSS_OFFSET 0xfec /* Interrupt Set Status Register */ + /* 0xff0-0xff8: Reserved */ + +/* UART register (virtual) addresses ************************************************************/ + +#define LPC31_UART_RBR (LPC31_UART_VBASE+LPC31_UART_RBR_OFFSET) +#define LPC31_UART_THR (LPC31_UART_VBASE+LPC31_UART_THR_OFFSET) +#define LPC31_UART_DLL (LPC31_UART_VBASE+LPC31_UART_DLL_OFFSET) +#define LPC31_UART_DLM (LPC31_UART_VBASE+LPC31_UART_DLM_OFFSET) +#define LPC31_UART_IER (LPC31_UART_VBASE+LPC31_UART_IER_OFFSET) +#define LPC31_UART_IIR (LPC31_UART_VBASE+LPC31_UART_IIR_OFFSET) +#define LPC31_UART_FCR (LPC31_UART_VBASE+LPC31_UART_FCR_OFFSET) +#define LPC31_UART_LCR (LPC31_UART_VBASE+LPC31_UART_LCR_OFFSET) +#define LPC31_UART_MCR (LPC31_UART_VBASE+LPC31_UART_MCR_OFFSET) +#define LPC31_UART_LSR (LPC31_UART_VBASE+LPC31_UART_LSR_OFFSET) +#define LPC31_UART_MSR (LPC31_UART_VBASE+LPC31_UART_MSR_OFFSET) +#define LPC31_UART_SCR (LPC31_UART_VBASE+LPC31_UART_SCR_OFFSET) +#define LPC31_UART_ICR (LPC31_UART_VBASE+LPC31_UART_ICR_OFFSET) +#define LPC31_UART_FDR (LPC31_UART_VBASE+LPC31_UART_FDR_OFFSET) +#define LPC31_UART_POP (LPC31_UART_VBASE+LPC31_UART_POP_OFFSET) +#define LPC31_UART_MODE (LPC31_UART_VBASE+LPC31_UART_MODE_OFFSET) +#define LPC31_UART_INTCE (LPC31_UART_VBASE+LPC31_UART_INTCE_OFFSET) +#define LPC31_UART_INTSE (LPC31_UART_VBASE+LPC31_UART_INTSE_OFFSET) +#define LPC31_UART_INTS (LPC31_UART_VBASE+LPC31_UART_INTS_OFFSET) +#define LPC31_UART_INTE (LPC31_UART_VBASE+LPC31_UART_INTE_OFFSET) +#define LPC31_UART_INTCS (LPC31_UART_VBASE+LPC31_UART_INTCS_OFFSET) +#define LPC31_UART_INTSS (LPC31_UART_VBASE+LPC31_UART_INTSS_OFFSET) + +/* UART register bit definitions ****************************************************************/ +/* Receive Buffer Register RBR, address 0x15001000 */ + +#define UART_RBR_SHIFT (0) /* Bits 0-7 */ +#define UART_RBR_MASK (0xff << UART_RBR_SHIFT) + +/* Transmitter Holding Register THR, address 0x15001000 */ + +#define UART_THR_SHIFT (0) /* Bits 0-7 */ +#define UART_THR_MASK (0xff << UART_THR_SHIFT) + +/* Divisor register Latch LSB DLL, address 0x15001000 */ + +#define UART_DLL_SHIFT (0) /* Bits 0-7 */ +#define UART_DLL_MASK (0xff << UART_DLL_SHIFT) + +/* Divisor latch register MSB DLM, address 0x15001004 */ + +#define UART_DLM_SHIFT (0) /* Bits 0-7 */ +#define UART_DLM_MASK (0xff << UART_DLM_SHIFT) + +/* Interrupt Enable Register IER, address 0x15001004 */ + +#define UART_IER_CTSINTEN (1 << 7) /* Bit 7: Enable modem status interrupt on CTS transition */ +#define UART_IER_MSINTEN (1 << 3) /* Bit 3: Enable Modem Status interrupt */ +#define UART_IER_RLSINTEN (1 << 2) /* Bit 2: Receiver Line Status interrupt enable */ +#define UART_IER_THREINTEN (1 << 1) /* Bit 1: Transmitter Holding Register Empty interrupt enable */ +#define UART_IER_RDAINTEN (1 << 0) /* Bit 0: Receive Data Available interrupt enable */ +#define UART_IER_ALLINTS (0x1f) + +/* Interrupt Identification Register IIR, address 0x15001008 */ + +#define UART_IIR_FIFOEN_SHIFT (6) /* Bits 6-7: Copies of FCR[0] */ +#define UART_IIR_FIFOEN_MASK (3 << UART_IIR_FIFOEN_SHIFT) +#define UART_IIR_INTID_SHIFT (1) /* Bits 1-3: Interrupt identification */ +#define UART_IIR_INTID_MASK (7 << UART_IIR_INTID_SHIFT) +# define UART_IIR_INTID_MS (0 << UART_IIR_INTID_SHIFT) /* Modem status */ +# define UART_IIR_INTID_THRE (1 << UART_IIR_INTID_SHIFT) /* Transmitter Holding Register empty */ +# define UART_IIR_INTID_RDA (2 << UART_IIR_INTID_SHIFT) /* Received Data Available */ +# define UART_IIR_INTID_RLS (3 << UART_IIR_INTID_SHIFT) /* Receiver Line Status */ +# define UART_IIR_INTID_TIMEOUT (6 << UART_IIR_INTID_SHIFT) /* Character time-out */ +#define UART_IIR_NOINT (1 << 0) /* Bit 0: Interrupt status, 1=no interrupt */ + +/* FIFO Control Register FCR, address 0x15001008 */ + +#define UART_FCR_RXTRIGLEVEL_SHIFT (6) /* Bits 6-7: 7:6 Receiver trigger level selection */ +#define UART_FCR_RXTRIGLEVEL_MASK (3 << UART_FCR_RXTRIGLEVEL_SHIFT) +# define UART_FCR_RXTRIGLEVEL_1 (0 << UART_FCR_RXTRIGLEVEL_SHIFT) /* Rx trigger at character 1 */ +# define UART_FCR_RXTRIGLEVEL_16 (1 << UART_FCR_RXTRIGLEVEL_SHIFT) /* Rx trigger at character 16 */ +# define UART_FCR_RXTRIGLEVEL_32 (2 << UART_FCR_RXTRIGLEVEL_SHIFT) /* Rx trigger at character 32 */ +# define UART_FCR_RXTRIGLEVEL_56 (3 << UART_FCR_RXTRIGLEVEL_SHIFT) /* Rx trigger at character 56 */ +#define UART_FCR_DMAMODE (1 << 3) /* Bit 3: DMA mode select */ +#define UART_FCR_TXFIFORST (1 << 2) /* Bit 2: Transmitter FIFO reset */ +#define UART_FCR_RXFIFORST (1 << 1) /* Bit 1: Receiver FIFO reset */ +#define UART_FCR_FIFOENABLE (1 << 0) /* Bit 0: Transmit and receive FIFO enable */ + +/* Line Control Register LCR, address 0x1500100c */ + +#define UART_LCR_DLAB (1 << 7) /* Bit 7: Divisor Latch Access bit */ +#define UART_LCR_BRKCTRL (1 << 6) /* Bit 6: Break control bit */ +#define UART_LCR_PARSTICK (1 << 5) /* Bit 5: Enable sticky parity mode */ +#define UART_LCR_PAREVEN (1 << 4) /* Bit 4: Select even parity */ +#define UART_LCR_PAREN (1 << 3) /* Bit 3: Parity enable */ +#define UART_LCR_NSTOPBITS (1 << 2) /* Bit 2: Number of stop bits selector */ +#define UART_LCR_WDLENSEL_SHIFT (0) /* Bits 0-1: Word length selector */ +#define UART_LCR_WDLENSEL_MASK (3 << UART_LCR_WDLENSEL_SHIFT) +# define UART_LCR_WDLENSEL_5BITS (0 << UART_LCR_WDLENSEL_SHIFT) /* Char length=5 stopbits=1 or 1.5*/ +# define UART_LCR_WDLENSEL_6BITS (1 << UART_LCR_WDLENSEL_SHIFT) /* Char length=6 stopbits=1 or 2 */ +# define UART_LCR_WDLENSEL_7BITS (2 << UART_LCR_WDLENSEL_SHIFT) /* Char length=7 stopbits=1 or 2 */ +# define UART_LCR_WDLENSEL_8BITS (3 << UART_LCR_WDLENSEL_SHIFT) /* Char length=8 stopbits=1 or 2 */ + +/* Modem Control Register MCR, address 0x15001010 */ + +#define UART_MCR_AUTOCTSEN (1 << 7) /* Bit 7: Auto-cts flow control enable */ +#define UART_MCR_AUTORTSEN (1 << 6) /* Bit 6: Auto-rts flow control enable */ +#define UART_MCR_LOOPEN (1 << 4) /* Bit 4: Loop-back mode enable */ +#define UART_MCR_RTS (1 << 1) /* Bit 1: Request To Send */ + +/* Line Status Register LSR, address 0x15001014 */ + +#define UART_LSR_RXER (1 << 7) /* Bit 7: Error in receiver FIFO */ +#define UART_LSR_TEMT (1 << 6) /* Bit 6: Transmitter empty (TSR and THR) */ +#define UART_LSR_THRE (1 << 5) /* Bit 5: Transmitter Holding Register empty */ +#define UART_LSR_BI (1 << 4) /* Bit 4: Break indication */ +#define UART_LSR_FE (1 << 3) /* Bit 3: Framing error */ +#define UART_LSR_PE (1 << 2) /* Bit 2: Parity error */ +#define UART_LSR_OE (1 << 1) /* Bit 1: Overrun error */ +#define UART_LSR_RDR (1 << 0) /* Bit 0: Read Data ready */ + +/* Modem Status Register MSR, address 0x15001018 */ + +#define UART_MSR_CTS (1 << 4) /* Bit 4: CTS is modem flow control signal */ +#define UART_MSR_DCTS (1 << 0) /* Bit 0: Delta Clear To Send */ + +/* Scratch Register SCR, address 0x1500101c */ + +#define UART_SCR_SCRVAL_SHIFT (0) /* Bits 0-7: Scratch Value */ +#define UART_SCR_SCRVAL_MASK (0xff << bb) + +/* IrDA Control Register ICR, address 0x15001024 */ + +#define UART_ICR_PULSEDIV_SHIFT (3) /* Bits 3-5: Configures fixed pulse width mode */ +#define UART_ICR_PULSEDIV_MASK (7 << UART_ICR_PULSEDIV_SHIFT) +#define UART_ICR_FIXPULSEEN (1 << 2) /* Bit 2: Enables IrDA fixed pulse width mode */ +#define UART_ICR_IRDAINV (1 << 1) /* Bit 1: Serial input is inverted */ +#define UART_ICR_IRDAEN (1 << 0) /* Bit 0: Enable IrDA */ + +/* Fractional Divider Register FDR, address 0x15001028 */ + +#define UART_FDR_MULVAL_SHIFT (4) /* Bits 4-7: Baud pre-scaler multiplier value */ +#define UART_FDR_MULVAL_MASK (15 << UART_FDR_MULVAL_SHIFT) +#define UART_FDR_DIVADDVAL_SHIFT (0) /* Bits 0-3: Baud pre-scaler divisor value */ +#define UART_FDR_DIVADDVAL_MASK (15 << UART_FDR_DIVADDVAL_SHIFT) + +/* NHP POP Register POP, address 0x15001030 */ + +#define UART_POP_POPRBR (1 << 0) /* Bit 0: Pop from RBR as if RBR read in non-NHP mode */ + +/* Mode Selection Register MODE, 0x15001034 */ + +#define UART_MODE_NHP (1 << 0) /* Bit 0: Enable UART NHP mode */ + +/* Interrupt Clear Enable Register INTCE, address 0x15001fd8 + * Interrupt Set Enable Register INTSE, address 0x15001fdc + * Interrupt Status Register INTS, address 0x15001fe0 + * Interrupt Enable Register INTE, address 0x15001fe4 + * Interrupt Clear Status Register INTCS, address 0x15001fe8 + * Interrupt Set Status Register INTSS, address 0x15001fec + */ + +#define UART_OEINT (1 << 15) /* Bit 15: Overrun Error Interrupt */ +#define UART_PEINT (1 << 14) /* Bit 14: Parity Error Interrupt (not INTSS) */ +#define UART_FEINT (1 << 13) /* Bit 13: Frame Error Interrupt (not INTSS) */ +#define UART_BIINT (1 << 12) /* Bit 12: Break Indication Interrupt (not INTSS) */ +#define UART_ABTOINT (1 << 9) /* Bit 9: Auto-Baud Time-Out Interrupt */ +#define UART_ABEOINT (1 << 8) /* Bit 8: End of Auto-Baud Interrupt */ +#define UART_RXDAINT (1 << 6) /* Bit 6: Receiver Data Available Interrupt (not INTSS) */ +#define UART_RXTOINT (1 << 5) /* Bit 5: Receiver Time-Out Interrupt (not INTCE) */ +#define UART_THREINT (1 << 4) /* Bit 4: Transmitter Holding Register Empty Interrupt */ +#define UART_DCTSINT (1 << 0) /* Bit 0: Delta Clear To Send Interrupt */ + + +/************************************************************************************************ + * Public Types + ************************************************************************************************/ + +/************************************************************************************************ + * Public Data + ************************************************************************************************/ + +/************************************************************************************************ + * Public Functions + ************************************************************************************************/ + +#endif /* __ARCH_ARM_SRC_LPC31XX_LPC31_UART_H */ diff --git a/nuttx/arch/arm/src/lpc31xx/lpc31_usbdev.c b/nuttx/arch/arm/src/lpc31xx/lpc31_usbdev.c new file mode 100755 index 000000000..b25e5e942 --- /dev/null +++ b/nuttx/arch/arm/src/lpc31xx/lpc31_usbdev.c @@ -0,0 +1,2653 @@ +/******************************************************************************* + * arch/arm/src/lpc31xx/lpc31_usbdev.c + * + * Author: Davide Hewson + * + * Part of the NuttX OS and based, in part, on the LPC2148 USB driver: + * + * Copyright (C) 2010 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name NuttX nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + *******************************************************************************/ + +/******************************************************************************* + * Included Files + *******************************************************************************/ + +#include + +#include +#include +#include +#include +#include +#include +#include + +#include +#include +#include +#include + +#include +#include + +#include "chip.h" +#include "up_arch.h" +#include "up_internal.h" + +#include "lpc31_usbotg.h" +#include "lpc31_evntrtr.h" +#include "lpc31_syscreg.h" + +/******************************************************************************* + * Definitions + *******************************************************************************/ + +/* Configuration ***************************************************************/ + +#ifndef CONFIG_USBDEV_EP0_MAXSIZE +# define CONFIG_USBDEV_EP0_MAXSIZE 64 +#endif + +#ifndef CONFIG_USBDEV_MAXPOWER +# define CONFIG_USBDEV_MAXPOWER 100 /* mA */ +#endif + +/* Extremely detailed register debug that you would normally never want + * enabled. + */ + +#undef CONFIG_LPC31_USBDEV_REGDEBUG + +/* Enable reading SOF from interrupt handler vs. simply reading on demand. Probably + * a bad idea... Unless there is some issue with sampling the SOF from hardware + * asynchronously. + */ + +#ifdef CONFIG_LPC31_USBDEV_FRAME_INTERRUPT +# define USB_FRAME_INT USBDEV_USBINTR_SRE +#else +# define USB_FRAME_INT 0 +#endif + +#ifdef CONFIG_DEBUG +# define USB_ERROR_INT USBDEV_USBINTR_UEE +#else +# define USB_ERROR_INT 0 +#endif + +/* Debug ***********************************************************************/ + +/* Trace error codes */ + +#define LPC31_TRACEERR_ALLOCFAIL 0x0001 +#define LPC31_TRACEERR_BADCLEARFEATURE 0x0002 +#define LPC31_TRACEERR_BADDEVGETSTATUS 0x0003 +#define LPC31_TRACEERR_BADEPNO 0x0004 +#define LPC31_TRACEERR_BADEPGETSTATUS 0x0005 +#define LPC31_TRACEERR_BADEPTYPE 0x0006 +#define LPC31_TRACEERR_BADGETCONFIG 0x0007 +#define LPC31_TRACEERR_BADGETSETDESC 0x0008 +#define LPC31_TRACEERR_BADGETSTATUS 0x0009 +#define LPC31_TRACEERR_BADSETADDRESS 0x000a +#define LPC31_TRACEERR_BADSETCONFIG 0x000b +#define LPC31_TRACEERR_BADSETFEATURE 0x000c +#define LPC31_TRACEERR_BINDFAILED 0x000d +#define LPC31_TRACEERR_DISPATCHSTALL 0x000e +#define LPC31_TRACEERR_DRIVER 0x000f +#define LPC31_TRACEERR_DRIVERREGISTERED 0x0010 +#define LPC31_TRACEERR_EP0SETUPSTALLED 0x0011 +#define LPC31_TRACEERR_EPINNULLPACKET 0x0012 +#define LPC31_TRACEERR_EPOUTNULLPACKET 0x0013 +#define LPC31_TRACEERR_INVALIDCTRLREQ 0x0014 +#define LPC31_TRACEERR_INVALIDPARMS 0x0015 +#define LPC31_TRACEERR_IRQREGISTRATION 0x0016 +#define LPC31_TRACEERR_NOEP 0x0017 +#define LPC31_TRACEERR_NOTCONFIGURED 0x0018 +#define LPC31_TRACEERR_REQABORTED 0x0019 + +/* Trace interrupt codes */ + +#define LPC31_TRACEINTID_USB 0x0001 +#define LPC31_TRACEINTID_CLEARFEATURE 0x0002 +#define LPC31_TRACEINTID_DEVGETSTATUS 0x0003 +#define LPC31_TRACEINTID_DEVRESET 0x0004 +#define LPC31_TRACEINTID_DISPATCH 0x0005 +#define LPC31_TRACEINTID_EP0COMPLETE 0x0006 +#define LPC31_TRACEINTID_EP0NAK 0x0007 +#define LPC31_TRACEINTID_EP0SETUP 0x0008 +#define LPC31_TRACEINTID_EPGETSTATUS 0x0009 +#define LPC31_TRACEINTID_EPIN 0x000a +#define LPC31_TRACEINTID_EPINQEMPTY 0x000b +#define LPC31_TRACEINTID_EP0INSETADDRESS 0x000c +#define LPC31_TRACEINTID_EPOUT 0x000d +#define LPC31_TRACEINTID_EPOUTQEMPTY 0x000e +#define LPC31_TRACEINTID_EP0SETUPSETADDRESS 0x000f +#define LPC31_TRACEINTID_FRAME 0x0010 +#define LPC31_TRACEINTID_GETCONFIG 0x0011 +#define LPC31_TRACEINTID_GETSETDESC 0x0012 +#define LPC31_TRACEINTID_GETSETIF 0x0013 +#define LPC31_TRACEINTID_GETSTATUS 0x0014 +#define LPC31_TRACEINTID_IFGETSTATUS 0x0015 +#define LPC31_TRACEINTID_SETCONFIG 0x0016 +#define LPC31_TRACEINTID_SETFEATURE 0x0017 +#define LPC31_TRACEINTID_SUSPENDCHG 0x0018 +#define LPC31_TRACEINTID_SYNCHFRAME 0x0019 + +/* Hardware interface **********************************************************/ + +/* This represents a Endpoint Transfer Descriptor - note these must be 32 byte aligned */ +struct lpc31_dtd_s +{ + volatile uint32_t nextdesc; /* Address of the next DMA descripto in RAM */ + volatile uint32_t config; /* Misc. bit encoded configuration information */ + uint32_t buffer0; /* Buffer start address */ + uint32_t buffer1; /* Buffer start address */ + uint32_t buffer2; /* Buffer start address */ + uint32_t buffer3; /* Buffer start address */ + uint32_t buffer4; /* Buffer start address */ + uint32_t xfer_len; /* Software only - transfer len that was queued */ +}; + +/* DTD nextdesc field*/ +#define DTD_NEXTDESC_INVALID (1 << 0) /* Bit 0 : Next Descriptor Invalid */ + +/* DTD config field */ +#define DTD_CONFIG_LENGTH(n) ((n) << 16) /* Bits 16-31 : Total bytes to transfer */ +#define DTD_CONFIG_IOC (1 << 15) /* Bit 15 : Interrupt on Completion */ +#define DTD_CONFIG_MULT_VARIABLE (0 << 10) /* Bits 10-11 : Number of packets executed per transacation descriptor (override) */ +#define DTD_CONFIG_MULT_NUM(n) ((n) << 10) +#define DTD_CONFIG_ACTIVE (1 << 7) /* Bit 7 : Status Active */ +#define DTD_CONFIG_HALTED (1 << 6) /* Bit 6 : Status Halted */ +#define DTD_CONFIG_BUFFER_ERROR (1 << 5) /* Bit 6 : Status Buffer Error */ +#define DTD_CONFIG_TRANSACTION_ERROR (1 << 3) /* Bit 3 : Status Transaction Error */ + +/* This represents a queue head - not these must be aligned to a 2048 byte boundary */ +struct lpc31_dqh_s +{ + uint32_t capability; /* Endpoint capability */ + uint32_t currdesc; /* Current dTD pointer */ + struct lpc31_dtd_s overlay; /* DTD overlay */ + volatile uint32_t setup[2]; /* Set-up buffer */ + uint32_t gap[4]; /* align to 64 bytes */ +}; + +/* DQH capability field */ +#define DQH_CAPABILITY_MULT_VARIABLE (0 << 30) /* Bits 30-31 : Number of packets executed per transaction descriptor */ +#define DQH_CAPABILITY_MULT_NUM(n) ((n) << 30) +#define DQH_CAPABILITY_ZLT (1 << 29) /* Bit 29 : Zero Length Termination Select */ +#define DQH_CAPABILITY_MAX_PACKET(n) ((n) << 16) /* Bits 16-29 : Maximum packet size of associated endpoint (<1024) */ +#define DQH_CAPABILITY_IOS (1 << 15) /* Bit 15 : Interrupt on Setup */ + +/* Endpoints ******************************************************************/ + +/* Number of endpoints */ +#define LPC31_NLOGENDPOINTS (4) /* ep0-3 */ +#define LPC31_NPHYSENDPOINTS (8) /* x2 for IN and OUT */ + +/* Odd physical endpoint numbers are IN; even are OUT */ +#define LPC31_EPPHYIN(epphy) (((epphy)&1)!=0) +#define LPC31_EPPHYOUT(epphy) (((epphy)&1)==0) + +#define LPC31_EPPHYIN2LOG(epphy) (((uint8_t)(epphy)>>1)|USB_DIR_IN) +#define LPC31_EPPHYOUT2LOG(epphy) (((uint8_t)(epphy)>>1)|USB_DIR_OUT) + +/* Endpoint 0 is special... */ +#define LPC31_EP0_OUT (0) +#define LPC31_EP0_IN (1) + +/* Each endpoint has somewhat different characteristics */ +#define LPC31_EPALLSET (0xff) /* All endpoints */ +#define LPC31_EPOUTSET (0x55) /* Even phy endpoint numbers are OUT EPs */ +#define LPC31_EPINSET (0xaa) /* Odd endpoint numbers are IN EPs */ +#define LPC31_EPCTRLSET (0x03) /* EP0 IN/OUT are control endpoints */ +#define LPC31_EPINTRSET (0xa8) /* Interrupt endpoints */ +#define LPC31_EPBULKSET (0xfc) /* Bulk endpoints */ +#define LPC31_EPISOCSET (0xfc) /* Isochronous endpoints */ + +/* Maximum packet sizes for endpoints */ +#define LPC31_EP0MAXPACKET (64) /* EP0 max packet size (1-64) */ +#define LPC31_BULKMAXPACKET (512) /* Bulk endpoint max packet (8/16/32/64/512) */ +#define LPC31_INTRMAXPACKET (1024) /* Interrupt endpoint max packet (1 to 1024) */ +#define LPC31_ISOCMAXPACKET (512) /* Acutally 1..1023 */ + +/* The address of the endpoint control register */ +#define LPC31_USBDEV_ENDPTCTRL(epphy) (LPC31_USBDEV_ENDPTCTRL0 + ((epphy)>>1)*4) + +/* Endpoint bit position in SETUPSTAT, PRIME, FLUSH, STAT, COMPLETE registers */ +#define LPC31_ENDPTSHIFT(epphy) (LPC31_EPPHYIN(epphy) ? (16 + ((epphy) >> 1)) : ((epphy) >> 1)) +#define LPC31_ENDPTMASK(epphy) (1 << LPC31_ENDPTSHIFT(epphy)) +#define LPC31_ENDPTMASK_ALL 0x000f000f + +/* Request queue operations ****************************************************/ + +#define lpc31_rqempty(ep) ((ep)->head == NULL) +#define lpc31_rqpeek(ep) ((ep)->head) + +/******************************************************************************* + * Private Types + *******************************************************************************/ + +/* A container for a request so that the request may be retained in a list */ + +struct lpc31_req_s +{ + struct usbdev_req_s req; /* Standard USB request */ + struct lpc31_req_s *flink; /* Supports a singly linked list */ +}; + +/* This is the internal representation of an endpoint */ + +struct lpc31_ep_s +{ + /* Common endpoint fields. This must be the first thing defined in the + * structure so that it is possible to simply cast from struct usbdev_ep_s + * to struct lpc31_ep_s. + */ + + struct usbdev_ep_s ep; /* Standard endpoint structure */ + + /* LPC31XX-specific fields */ + + struct lpc31_usbdev_s *dev; /* Reference to private driver data */ + struct lpc31_req_s *head; /* Request list for this endpoint */ + struct lpc31_req_s *tail; + uint8_t epphy; /* Physical EP address */ + uint8_t stalled:1; /* 1: Endpoint is stalled */ +}; + +/* This structure retains the state of the USB device controller */ + +struct lpc31_usbdev_s +{ + /* Common device fields. This must be the first thing defined in the + * structure so that it is possible to simply cast from struct usbdev_s + * to struct lpc31_usbdev_s. + */ + + struct usbdev_s usbdev; + + /* The bound device class driver */ + + struct usbdevclass_driver_s *driver; + + /* LPC31XX-specific fields */ + + uint8_t ep0state; /* State of certain EP0 operations */ + uint8_t ep0buf[64]; /* buffer for EP0 short transfers */ + uint8_t paddr; /* Address assigned by SETADDRESS */ + uint8_t stalled:1; /* 1: Protocol stalled */ + uint8_t selfpowered:1; /* 1: Device is self powered */ + uint8_t paddrset:1; /* 1: Peripheral addr has been set */ + uint8_t attached:1; /* 1: Host attached */ + uint32_t softprio; /* Bitset of high priority interrupts */ + uint32_t epavail; /* Bitset of available endpoints */ +#ifdef CONFIG_LPC31_USBDEV_FRAME_INTERRUPT + uint32_t sof; /* Last start-of-frame */ +#endif + + /* The endpoint list */ + struct lpc31_ep_s eplist[LPC31_NPHYSENDPOINTS]; +}; + +#define EP0STATE_IDLE 0 /* Idle State, leave on receiving a setup packet or epsubmit */ +#define EP0STATE_SETUP_OUT 1 /* Setup Packet received - SET/CLEAR */ +#define EP0STATE_SETUP_IN 2 /* Setup Packet received - GET */ +#define EP0STATE_SHORTWRITE 3 /* Short write without a usb_request */ +#define EP0STATE_WAIT_NAK_OUT 4 /* Waiting for Host to illicit status phase (GET) */ +#define EP0STATE_WAIT_NAK_IN 5 /* Waiting for Host to illicit status phase (SET/CLEAR) */ +#define EP0STATE_WAIT_STATUS_OUT 6 /* Wait for status phase to complete */ +#define EP0STATE_WAIT_STATUS_IN 7 /* Wait for status phase to complete */ +#define EP0STATE_DATA_IN 8 +#define EP0STATE_DATA_OUT 9 + +/******************************************************************************* + * Private Function Prototypes + *******************************************************************************/ + +/* Register operations ********************************************************/ + +#if defined(CONFIG_LPC31_USBDEV_REGDEBUG) && defined(CONFIG_DEBUG) +static uint32_t lpc31_getreg(uint32_t addr); +static void lpc31_putreg(uint32_t val, uint32_t addr); +#else +# define lpc31_getreg(addr) getreg32(addr) +# define lpc31_putreg(val,addr) putreg32(val,addr) +#endif + +static inline void lpc31_clrbits(uint32_t mask, uint32_t addr); +static inline void lpc31_setbits(uint32_t mask, uint32_t addr); +static inline void lpc31_chgbits(uint32_t mask, uint32_t val, uint32_t addr); + +/* Request queue operations ****************************************************/ + +static FAR struct lpc31_req_s *lpc31_rqdequeue(FAR struct lpc31_ep_s *privep); +static bool lpc31_rqenqueue(FAR struct lpc31_ep_s *privep, + FAR struct lpc31_req_s *req); + +/* Low level data transfers and request operations *****************************/ + +static inline void lpc31_writedtd(struct lpc31_dtd_s *dtd, const uint8_t *data, uint32_t nbytes); +static inline void lpc31_queuedtd(uint8_t epphy, struct lpc31_dtd_s *dtd); +static inline void lpc31_ep0xfer(uint8_t epphy, uint8_t *data, uint32_t nbytes); +static void lpc31_readsetup(uint8_t epphy, struct usb_ctrlreq_s *ctrl); + +static inline void lpc31_set_address(struct lpc31_usbdev_s *priv, uint16_t address); + +static void lpc31_flushep(struct lpc31_ep_s *privep); + +static int lpc31_progressep(struct lpc31_ep_s *privep); +static inline void lpc31_abortrequest(struct lpc31_ep_s *privep, + struct lpc31_req_s *privreq, int16_t result); +static void lpc31_reqcomplete(struct lpc31_ep_s *privep, struct lpc31_req_s *privreq, int16_t result); + +static void lpc31_cancelrequests(struct lpc31_ep_s *privep, int16_t status); + +/* Interrupt handling **********************************************************/ +static struct lpc31_ep_s *lpc31_epfindbyaddr(struct lpc31_usbdev_s *priv, uint16_t eplog); +static void lpc31_dispatchrequest(struct lpc31_usbdev_s *priv, const struct usb_ctrlreq_s *ctrl); +static void lpc31_ep0configure(struct lpc31_usbdev_s *priv); +static void lpc31_usbreset(struct lpc31_usbdev_s *priv); + +static inline void lpc31_ep0state(struct lpc31_usbdev_s *priv, uint16_t state); +static void lpc31_ep0setup(struct lpc31_usbdev_s *priv); + +static void lpc31_ep0complete(struct lpc31_usbdev_s *priv, uint8_t epphy); +static void lpc31_ep0nak(struct lpc31_usbdev_s *priv, uint8_t epphy); +static bool lpc31_epcomplete(struct lpc31_usbdev_s *priv, uint8_t epphy); + +static int lpc31_usbinterrupt(int irq, FAR void *context); + +/* Endpoint operations *********************************************************/ + +/* USB device controller operations ********************************************/ + +static int lpc31_epconfigure(FAR struct usbdev_ep_s *ep, + const struct usb_epdesc_s *desc, bool last); +static int lpc31_epdisable(FAR struct usbdev_ep_s *ep); +static FAR struct usbdev_req_s *lpc31_epallocreq(FAR struct usbdev_ep_s *ep); +static void lpc31_epfreereq(FAR struct usbdev_ep_s *ep, + FAR struct usbdev_req_s *); +static void *lpc31_epallocbuffer(FAR struct usbdev_ep_s *ep, unsigned bytes); +static void lpc313_epfreebuffer(FAR struct usbdev_ep_s *ep, FAR void *buf); +static int lpc31_epsubmit(FAR struct usbdev_ep_s *ep, + struct usbdev_req_s *req); +static int lpc31_epcancel(FAR struct usbdev_ep_s *ep, + struct usbdev_req_s *req); +static int lpc31_epstall(FAR struct usbdev_ep_s *ep, bool resume); + +static FAR struct usbdev_ep_s *lcp313x_allocep(FAR struct usbdev_s *dev, + uint8_t epno, bool in, uint8_t eptype); +static void lpc31_freeep(FAR struct usbdev_s *dev, FAR struct usbdev_ep_s *ep); +static int lpc31_getframe(struct usbdev_s *dev); +static int lpc31_wakeup(struct usbdev_s *dev); +static int lpc31_selfpowered(struct usbdev_s *dev, bool selfpowered); +static int lpc31_pullup(struct usbdev_s *dev, bool enable); + +/******************************************************************************* + * Private Data + *******************************************************************************/ + +/* Since there is only a single USB interface, all status information can be + * be simply retained in a single global instance. + */ + +static struct lpc31_usbdev_s g_usbdev; + +static struct lpc31_dqh_s __attribute__((aligned(2048))) g_qh[LPC31_NPHYSENDPOINTS]; +static struct lpc31_dtd_s __attribute__((aligned(32))) g_td[LPC31_NPHYSENDPOINTS]; + +static const struct usbdev_epops_s g_epops = +{ + .configure = lpc31_epconfigure, + .disable = lpc31_epdisable, + .allocreq = lpc31_epallocreq, + .freereq = lpc31_epfreereq, +#ifdef CONFIG_ARCH_USBDEV_DMA + .allocbuffer = lpc31_epallocbuffer, + .freebuffer = lpc31_epfreebuffer, +#endif + .submit = lpc31_epsubmit, + .cancel = lpc31_epcancel, + .stall = lpc31_epstall, +}; + +static const struct usbdev_ops_s g_devops = +{ + .allocep = lcp313x_allocep, + .freeep = lpc31_freeep, + .getframe = lpc31_getframe, + .wakeup = lpc31_wakeup, + .selfpowered = lpc31_selfpowered, + .pullup = lpc31_pullup, +}; + +/******************************************************************************* + * Public Data + *******************************************************************************/ + +/******************************************************************************* + * Private Functions + *******************************************************************************/ + +/******************************************************************************* + * Name: lpc31_getreg + * + * Description: + * Get the contents of an LPC313x register + * + *******************************************************************************/ + +#if defined(CONFIG_LPC31_USBDEV_REGDEBUG) && defined(CONFIG_DEBUG) +static uint32_t lpc31_getreg(uint32_t addr) +{ + static uint32_t prevaddr = 0; + static uint32_t preval = 0; + static uint32_t count = 0; + + /* Read the value from the register */ + + uint32_t val = getreg32(addr); + + /* Is this the same value that we read from the same registe last time? Are + * we polling the register? If so, suppress some of the output. + */ + + if (addr == prevaddr && val == preval) + { + if (count == 0xffffffff || ++count > 3) + { + if (count == 4) + { + lldbg("...\n"); + } + return val; + } + } + + /* No this is a new address or value */ + + else + { + /* Did we print "..." for the previous value? */ + + if (count > 3) + { + /* Yes.. then show how many times the value repeated */ + + lldbg("[repeats %d more times]\n", count-3); + } + + /* Save the new address, value, and count */ + + prevaddr = addr; + preval = val; + count = 1; + } + + /* Show the register value read */ + + lldbg("%08x->%08x\n", addr, val); + return val; +} +#endif + +/******************************************************************************* + * Name: lpc31_putreg + * + * Description: + * Set the contents of an LPC313x register to a value + * + *******************************************************************************/ + +#if defined(CONFIG_LPC31_USBDEV_REGDEBUG) && defined(CONFIG_DEBUG) +static void lpc31_putreg(uint32_t val, uint32_t addr) +{ + /* Show the register value being written */ + + lldbg("%08x<-%08x\n", addr, val); + + /* Write the value */ + + putreg32(val, addr); +} +#endif + +/******************************************************************************* + * Name: lpc31_clrbits + * + * Description: + * Clear bits in a register + * + *******************************************************************************/ + +static inline void lpc31_clrbits(uint32_t mask, uint32_t addr) +{ + uint32_t reg = lpc31_getreg(addr); + reg &= ~mask; + lpc31_putreg(reg, addr); +} + +/******************************************************************************* + * Name: lpc31_setbits + * + * Description: + * Set bits in a register + * + *******************************************************************************/ + +static inline void lpc31_setbits(uint32_t mask, uint32_t addr) +{ + uint32_t reg = lpc31_getreg(addr); + reg |= mask; + lpc31_putreg(reg, addr); +} + +/******************************************************************************* + * Name: lpc31_chgbits + * + * Description: + * Change bits in a register + * + *******************************************************************************/ + +static inline void lpc31_chgbits(uint32_t mask, uint32_t val, uint32_t addr) +{ + uint32_t reg = lpc31_getreg(addr); + reg &= ~mask; + reg |= val; + lpc31_putreg(reg, addr); +} + +/******************************************************************************* + * Name: lpc31_rqdequeue + * + * Description: + * Remove a request from an endpoint request queue + * + *******************************************************************************/ + +static FAR struct lpc31_req_s *lpc31_rqdequeue(FAR struct lpc31_ep_s *privep) +{ + FAR struct lpc31_req_s *ret = privep->head; + + if (ret) + { + privep->head = ret->flink; + if (!privep->head) + { + privep->tail = NULL; + } + + ret->flink = NULL; + } + + return ret; +} + +/******************************************************************************* + * Name: lpc31_rqenqueue + * + * Description: + * Add a request from an endpoint request queue + * + *******************************************************************************/ + +static bool lpc31_rqenqueue(FAR struct lpc31_ep_s *privep, + FAR struct lpc31_req_s *req) +{ + bool is_empty = !privep->head; + + req->flink = NULL; + if (is_empty) + { + privep->head = req; + privep->tail = req; + } + else + { + privep->tail->flink = req; + privep->tail = req; + } + return is_empty; +} + +/******************************************************************************* + * Name: lpc31_writedtd + * + * Description: + * Initialise a DTD to transfer the data + * + *******************************************************************************/ + +static inline void lpc31_writedtd(struct lpc31_dtd_s *dtd, const uint8_t *data, uint32_t nbytes) +{ + dtd->nextdesc = DTD_NEXTDESC_INVALID; + dtd->config = DTD_CONFIG_LENGTH(nbytes) | DTD_CONFIG_IOC | DTD_CONFIG_ACTIVE; + dtd->buffer0 = ((uint32_t) data); + dtd->buffer1 = (((uint32_t) data) + 0x1000) & 0xfffff000; + dtd->buffer2 = (((uint32_t) data) + 0x2000) & 0xfffff000; + dtd->buffer3 = (((uint32_t) data) + 0x3000) & 0xfffff000; + dtd->buffer4 = (((uint32_t) data) + 0x4000) & 0xfffff000; + dtd->xfer_len = nbytes; +} + +/******************************************************************************* + * Name: lpc31_queuedtd + * + * Description: + * Add the DTD to the device list + * + *******************************************************************************/ + +static void lpc31_queuedtd(uint8_t epphy, struct lpc31_dtd_s *dtd) +{ + /* Queue the DTD onto the Endpoint */ + /* NOTE - this only works when no DTD is currently queued */ + + g_qh[epphy].overlay.nextdesc = (uint32_t) dtd; + g_qh[epphy].overlay.config &= ~(DTD_CONFIG_ACTIVE | DTD_CONFIG_HALTED); + + uint32_t bit = LPC31_ENDPTMASK(epphy); + + lpc31_setbits (bit, LPC31_USBDEV_ENDPTPRIME); + + while (lpc31_getreg (LPC31_USBDEV_ENDPTPRIME) & bit) + ; +} + +/******************************************************************************* + * Name: lpc31_ep0xfer + * + * Description: + * Schedule a short transfer for Endpoint 0 (IN or OUT) + * + *******************************************************************************/ + +static inline void lpc31_ep0xfer(uint8_t epphy, uint8_t *buf, uint32_t nbytes) +{ + struct lpc31_dtd_s *dtd = &g_td[epphy]; + + lpc31_writedtd(dtd, buf, nbytes); + + lpc31_queuedtd(epphy, dtd); +} + +/******************************************************************************* + * Name: lpc31_readsetup + * + * Description: + * Read a Setup packet from the DTD. + * + *******************************************************************************/ +static void lpc31_readsetup(uint8_t epphy, struct usb_ctrlreq_s *ctrl) +{ + struct lpc31_dqh_s *dqh = &g_qh[epphy]; + int i; + + do { + /* Set the trip wire */ + lpc31_setbits(USBDEV_USBCMD_SUTW, LPC31_USBDEV_USBCMD); + + // copy the request... + for (i = 0; i < 8; i++) + ((uint8_t *) ctrl)[i] = ((uint8_t *) dqh->setup)[i]; + + } while (!(lpc31_getreg(LPC31_USBDEV_USBCMD) & USBDEV_USBCMD_SUTW)); + + /* Clear the trip wire */ + lpc31_clrbits(USBDEV_USBCMD_SUTW, LPC31_USBDEV_USBCMD); + + /* Clear the Setup Interrupt */ + lpc31_putreg (LPC31_ENDPTMASK(LPC31_EP0_OUT), LPC31_USBDEV_ENDPTSETUPSTAT); +} + +/******************************************************************************* + * Name: lpc31_set_address + * + * Description: + * Set the devices USB address + * + *******************************************************************************/ + +static inline void lpc31_set_address(struct lpc31_usbdev_s *priv, uint16_t address) +{ + priv->paddr = address; + priv->paddrset = address != 0; + + lpc31_chgbits(USBDEV_DEVICEADDR_MASK, priv->paddr << USBDEV_DEVICEADDR_SHIFT, + LPC31_USBDEV_DEVICEADDR); +} + +/******************************************************************************* + * Name: lpc31_flushep + * + * Description: + * Flush any primed descriptors from this ep + * + *******************************************************************************/ + +static void lpc31_flushep(struct lpc31_ep_s *privep) +{ + uint32_t mask = LPC31_ENDPTMASK(privep->epphy); + do { + lpc31_putreg (mask, LPC31_USBDEV_ENDPTFLUSH); + while ((lpc31_getreg(LPC31_USBDEV_ENDPTFLUSH) & mask) != 0) + ; + } while ((lpc31_getreg(LPC31_USBDEV_ENDPTSTATUS) & mask) != 0); +} + + +/******************************************************************************* + * Name: lpc31_progressep + * + * Description: + * Progress the Endpoint by priming the first request into the queue head + * + *******************************************************************************/ + +static int lpc31_progressep(struct lpc31_ep_s *privep) +{ + struct lpc31_dtd_s *dtd = &g_td[privep->epphy]; + struct lpc31_req_s *privreq; + + /* Check the request from the head of the endpoint request queue */ + + privreq = lpc31_rqpeek(privep); + if (!privreq) + { + usbtrace(TRACE_INTDECODE(LPC31_TRACEINTID_EPINQEMPTY), 0); + return OK; + } + + /* Ignore any attempt to send a zero length packet */ + + if (privreq->req.len == 0) + { + /* If the class driver is responding to a setup packet, then wait for the + * host to illicit thr response */ + + if (privep->epphy == LPC31_EP0_IN && privep->dev->ep0state == EP0STATE_SETUP_OUT) + lpc31_ep0state (privep->dev, EP0STATE_WAIT_NAK_IN); + else + { + if (LPC31_EPPHYIN(privep->epphy)) + usbtrace(TRACE_DEVERROR(LPC31_TRACEERR_EPINNULLPACKET), 0); + else + usbtrace(TRACE_DEVERROR(LPC31_TRACEERR_EPOUTNULLPACKET), 0); + } + + lpc31_reqcomplete(privep, lpc31_rqdequeue(privep), OK); + return OK; + } + + if (privep->epphy == LPC31_EP0_IN) + lpc31_ep0state (privep->dev, EP0STATE_DATA_IN); + else if (privep->epphy == LPC31_EP0_OUT) + lpc31_ep0state (privep->dev, EP0STATE_DATA_OUT); + + int bytesleft = privreq->req.len - privreq->req.xfrd; + + if (LPC31_EPPHYIN(privep->epphy)) + usbtrace(TRACE_WRITE(privep->epphy), privreq->req.xfrd); + else + usbtrace(TRACE_READ(privep->epphy), privreq->req.xfrd); + + /* Initialise the DTD to transfer the next chunk */ + + lpc31_writedtd (dtd, privreq->req.buf + privreq->req.xfrd, bytesleft); + + /* then queue onto the DQH */ + lpc31_queuedtd(privep->epphy, dtd); + + return OK; +} + +/******************************************************************************* + * Name: lpc31_abortrequest + * + * Description: + * Discard a request + * + *******************************************************************************/ + +static inline void lpc31_abortrequest(struct lpc31_ep_s *privep, + struct lpc31_req_s *privreq, + int16_t result) +{ + usbtrace(TRACE_DEVERROR(LPC31_TRACEERR_REQABORTED), (uint16_t)privep->epphy); + + /* Save the result in the request structure */ + + privreq->req.result = result; + + /* Callback to the request completion handler */ + + privreq->req.callback(&privep->ep, &privreq->req); +} + +/******************************************************************************* + * Name: lpc31_reqcomplete + * + * Description: + * Handle termination of the request at the head of the endpoint request queue. + * + *******************************************************************************/ + +static void lpc31_reqcomplete(struct lpc31_ep_s *privep, struct lpc31_req_s *privreq, int16_t result) +{ + /* If endpoint 0, temporarily reflect the state of protocol stalled + * in the callback. + */ + + bool stalled = privep->stalled; + if (privep->epphy == LPC31_EP0_IN) + privep->stalled = privep->dev->stalled; + + /* Save the result in the request structure */ + + privreq->req.result = result; + + /* Callback to the request completion handler */ + + privreq->req.callback(&privep->ep, &privreq->req); + + /* Restore the stalled indication */ + + privep->stalled = stalled; +} + +/******************************************************************************* + * Name: lpc31_cancelrequests + * + * Description: + * Cancel all pending requests for an endpoint + * + *******************************************************************************/ + +static void lpc31_cancelrequests(struct lpc31_ep_s *privep, int16_t status) +{ + if (!lpc31_rqempty(privep)) + lpc31_flushep(privep); + + while (!lpc31_rqempty(privep)) + { + // FIXME: the entry at the head should be sync'd with the DTD + // FIXME: only report the error status if the transfer hasn't completed + usbtrace(TRACE_COMPLETE(privep->epphy), + (lpc31_rqpeek(privep))->req.xfrd); + lpc31_reqcomplete(privep, lpc31_rqdequeue(privep), status); + } +} + +/******************************************************************************* + * Name: lpc31_epfindbyaddr + * + * Description: + * Find the physical endpoint structure corresponding to a logic endpoint + * address + * + *******************************************************************************/ + +static struct lpc31_ep_s *lpc31_epfindbyaddr(struct lpc31_usbdev_s *priv, + uint16_t eplog) +{ + struct lpc31_ep_s *privep; + int i; + + /* Endpoint zero is a special case */ + + if (USB_EPNO(eplog) == 0) + { + return &priv->eplist[0]; + } + + /* Handle the remaining */ + + for (i = 1; i < LPC31_NPHYSENDPOINTS; i++) + { + privep = &priv->eplist[i]; + + /* Same logical endpoint number? (includes direction bit) */ + + if (eplog == privep->ep.eplog) + { + /* Return endpoint found */ + + return privep; + } + } + + /* Return endpoint not found */ + + return NULL; +} + +/******************************************************************************* + * Name: lpc31_dispatchrequest + * + * Description: + * Provide unhandled setup actions to the class driver. This is logically part + * of the USB interrupt handler. + * + *******************************************************************************/ + +static void lpc31_dispatchrequest(struct lpc31_usbdev_s *priv, + const struct usb_ctrlreq_s *ctrl) +{ + int ret = -EIO; + + usbtrace(TRACE_INTDECODE(LPC31_TRACEINTID_DISPATCH), 0); + if (priv->driver) + { + /* Forward to the control request to the class driver implementation */ + + ret = CLASS_SETUP(priv->driver, &priv->usbdev, ctrl); + } + + if (ret < 0) + { + /* Stall on failure */ + + usbtrace(TRACE_DEVERROR(LPC31_TRACEERR_DISPATCHSTALL), 0); + priv->stalled = true; + } +} + +/******************************************************************************* + * Name: lpc31_ep0configure + * + * Description: + * Reset Usb engine + * + *******************************************************************************/ + +static void lpc31_ep0configure(struct lpc31_usbdev_s *priv) +{ + /* Enable ep0 IN and ep0 OUT */ + g_qh[LPC31_EP0_OUT].capability = (DQH_CAPABILITY_MAX_PACKET(CONFIG_USBDEV_EP0_MAXSIZE) | + DQH_CAPABILITY_IOS | + DQH_CAPABILITY_ZLT); + + g_qh[LPC31_EP0_IN ].capability = (DQH_CAPABILITY_MAX_PACKET(CONFIG_USBDEV_EP0_MAXSIZE) | + DQH_CAPABILITY_IOS | + DQH_CAPABILITY_ZLT); + + g_qh[LPC31_EP0_OUT].currdesc = DTD_NEXTDESC_INVALID; + g_qh[LPC31_EP0_IN ].currdesc = DTD_NEXTDESC_INVALID; + + /* Enable EP0 */ + lpc31_setbits (USBDEV_ENDPTCTRL0_RXE | USBDEV_ENDPTCTRL0_TXE, LPC31_USBDEV_ENDPTCTRL0); +} + +/******************************************************************************* + * Name: lpc31_usbreset + * + * Description: + * Reset Usb engine + * + *******************************************************************************/ + +static void lpc31_usbreset(struct lpc31_usbdev_s *priv) +{ + int epphy; + + /* Disable all endpoints */ + + lpc31_clrbits (USBDEV_ENDPTCTRL_RXE | USBDEV_ENDPTCTRL_TXE, LPC31_USBDEV_ENDPTCTRL0); + lpc31_clrbits (USBDEV_ENDPTCTRL_RXE | USBDEV_ENDPTCTRL_TXE, LPC31_USBDEV_ENDPTCTRL1); + lpc31_clrbits (USBDEV_ENDPTCTRL_RXE | USBDEV_ENDPTCTRL_TXE, LPC31_USBDEV_ENDPTCTRL2); + lpc31_clrbits (USBDEV_ENDPTCTRL_RXE | USBDEV_ENDPTCTRL_TXE, LPC31_USBDEV_ENDPTCTRL3); + + /* Clear all pending interrupts */ + + lpc31_putreg (lpc31_getreg(LPC31_USBDEV_ENDPTNAK), LPC31_USBDEV_ENDPTNAK); + lpc31_putreg (lpc31_getreg(LPC31_USBDEV_ENDPTSETUPSTAT), LPC31_USBDEV_ENDPTSETUPSTAT); + lpc31_putreg (lpc31_getreg(LPC31_USBDEV_ENDPTCOMPLETE), LPC31_USBDEV_ENDPTCOMPLETE); + + /* Wait for all prime operations to have completed and then flush all DTDs */ + while (lpc31_getreg (LPC31_USBDEV_ENDPTPRIME) != 0) + ; + lpc31_putreg (LPC31_ENDPTMASK_ALL, LPC31_USBDEV_ENDPTFLUSH); + while (lpc31_getreg (LPC31_USBDEV_ENDPTFLUSH)) + ; + + /* Reset endpoints */ + for (epphy = 0; epphy < LPC31_NPHYSENDPOINTS; epphy++) + { + struct lpc31_ep_s *privep = &priv->eplist[epphy]; + + lpc31_cancelrequests (privep, -ESHUTDOWN); + + /* Reset endpoint status */ + privep->stalled = false; + } + + /* Tell the class driver that we are disconnected. The class + * driver should then accept any new configurations. */ + + if (priv->driver) + CLASS_DISCONNECT(priv->driver, &priv->usbdev); + + /* Set the interrupt Threshold control interval to 0 */ + lpc31_chgbits(USBDEV_USBCMD_ITC_MASK, USBDEV_USBCMD_ITCIMME, LPC31_USBDEV_USBCMD); + + /* Zero out the Endpoint queue heads */ + memset ((void *) g_qh, 0, sizeof (g_qh)); + memset ((void *) g_td, 0, sizeof (g_td)); + + /* Set USB address to 0 */ + lpc31_set_address (priv, 0); + + /* Initialise the Enpoint List Address */ + lpc31_putreg ((uint32_t)g_qh, LPC31_USBDEV_ENDPOINTLIST); + + /* EndPoint 0 initialization */ + lpc31_ep0configure(priv); + + /* Enable Device interrupts */ + lpc31_putreg(USB_FRAME_INT | USB_ERROR_INT | + USBDEV_USBINTR_NAKE | USBDEV_USBINTR_SLE | USBDEV_USBINTR_URE | USBDEV_USBINTR_PCE | USBDEV_USBINTR_UE, + LPC31_USBDEV_USBINTR); +} + +/******************************************************************************* + * Name: lpc31_setstate + * + * Description: + * Sets the EP0 state and manages the NAK interrupts + * + *******************************************************************************/ + +static inline void lpc31_ep0state(struct lpc31_usbdev_s *priv, uint16_t state) +{ + priv->ep0state = state; + + switch (state) + { + case EP0STATE_WAIT_NAK_IN: + lpc31_putreg (LPC31_ENDPTMASK(LPC31_EP0_IN), LPC31_USBDEV_ENDPTNAKEN); + break; + case EP0STATE_WAIT_NAK_OUT: + lpc31_putreg (LPC31_ENDPTMASK(LPC31_EP0_OUT), LPC31_USBDEV_ENDPTNAKEN); + break; + default: + lpc31_putreg(0, LPC31_USBDEV_ENDPTNAKEN); + break; + } +} + +/******************************************************************************* + * Name: lpc31_ep0setup + * + * Description: + * USB Ctrl EP Setup Event. This is logically part of the USB interrupt + * handler. This event occurs when a setup packet is receive on EP0 OUT. + * + *******************************************************************************/ + +static inline void lpc31_ep0setup(struct lpc31_usbdev_s *priv) +{ + struct lpc31_ep_s *privep; + struct usb_ctrlreq_s ctrl; + uint16_t value; + uint16_t index; + uint16_t len; + + /* Terminate any pending requests - since all DTDs will have been retired + * because of the setup packet */ + + lpc31_cancelrequests(&priv->eplist[LPC31_EP0_OUT], -EPROTO); + lpc31_cancelrequests(&priv->eplist[LPC31_EP0_IN], -EPROTO); + + /* Assume NOT stalled */ + + priv->eplist[LPC31_EP0_OUT].stalled = false; + priv->eplist[LPC31_EP0_IN].stalled = false; + priv->stalled = false; + + /* Read EP0 setup data */ + lpc31_readsetup(LPC31_EP0_OUT, &ctrl); + + /* Starting a control request - update state */ + lpc31_ep0state (priv, (ctrl.type & USB_REQ_DIR_IN) ? EP0STATE_SETUP_IN : EP0STATE_SETUP_OUT); + + /* And extract the little-endian 16-bit values to host order */ + value = GETUINT16(ctrl.value); + index = GETUINT16(ctrl.index); + len = GETUINT16(ctrl.len); + + ullvdbg("type=%02x req=%02x value=%04x index=%04x len=%04x\n", + ctrl.type, ctrl.req, value, index, len); + + /* Dispatch any non-standard requests */ + if ((ctrl.type & USB_REQ_TYPE_MASK) != USB_REQ_TYPE_STANDARD) + lpc31_dispatchrequest(priv, &ctrl); + else + { + /* Handle standard request. Pick off the things of interest to the USB + * device controller driver; pass what is left to the class driver */ + switch (ctrl.req) + { + case USB_REQ_GETSTATUS: + { + /* type: device-to-host; recipient = device, interface, endpoint + * value: 0 + * index: zero interface endpoint + * len: 2; data = status + */ + + usbtrace(TRACE_INTDECODE(LPC31_TRACEINTID_GETSTATUS), 0); + if (!priv->paddrset || len != 2 || + (ctrl.type & USB_REQ_DIR_IN) == 0 || value != 0) + { + priv->stalled = true; + } + else + { + switch (ctrl.type & USB_REQ_RECIPIENT_MASK) + { + case USB_REQ_RECIPIENT_ENDPOINT: + { + usbtrace(TRACE_INTDECODE(LPC31_TRACEINTID_EPGETSTATUS), 0); + privep = lpc31_epfindbyaddr(priv, index); + if (!privep) + { + usbtrace(TRACE_DEVERROR(LPC31_TRACEERR_BADEPGETSTATUS), 0); + priv->stalled = true; + } + else + { + if (privep->stalled) + priv->ep0buf[0] = 1; /* Stalled */ + else + priv->ep0buf[0] = 0; /* Not stalled */ + priv->ep0buf[1] = 0; + + lpc31_ep0xfer (LPC31_EP0_IN, priv->ep0buf, 2); + lpc31_ep0state (priv, EP0STATE_SHORTWRITE); + } + } + break; + + case USB_REQ_RECIPIENT_DEVICE: + { + if (index == 0) + { + usbtrace(TRACE_INTDECODE(LPC31_TRACEINTID_DEVGETSTATUS), 0); + + /* Features: Remote Wakeup=YES; selfpowered=? */ + + priv->ep0buf[0] = (priv->selfpowered << USB_FEATURE_SELFPOWERED) | + (1 << USB_FEATURE_REMOTEWAKEUP); + priv->ep0buf[1] = 0; + + lpc31_ep0xfer(LPC31_EP0_IN, priv->ep0buf, 2); + lpc31_ep0state (priv, EP0STATE_SHORTWRITE); + } + else + { + usbtrace(TRACE_DEVERROR(LPC31_TRACEERR_BADDEVGETSTATUS), 0); + priv->stalled = true; + } + } + break; + + case USB_REQ_RECIPIENT_INTERFACE: + { + usbtrace(TRACE_INTDECODE(LPC31_TRACEINTID_IFGETSTATUS), 0); + priv->ep0buf[0] = 0; + priv->ep0buf[1] = 0; + + lpc31_ep0xfer(LPC31_EP0_IN, priv->ep0buf, 2); + lpc31_ep0state (priv, EP0STATE_SHORTWRITE); + } + break; + + default: + { + usbtrace(TRACE_DEVERROR(LPC31_TRACEERR_BADGETSTATUS), 0); + priv->stalled = true; + } + break; + } + } + } + break; + + case USB_REQ_CLEARFEATURE: + { + /* type: host-to-device; recipient = device, interface or endpoint + * value: feature selector + * index: zero interface endpoint; + * len: zero, data = none + */ + + usbtrace(TRACE_INTDECODE(LPC31_TRACEINTID_CLEARFEATURE), 0); + if ((ctrl.type & USB_REQ_RECIPIENT_MASK) != USB_REQ_RECIPIENT_ENDPOINT) + { + lpc31_dispatchrequest(priv, &ctrl); + } + else if (priv->paddrset != 0 && value == USB_FEATURE_ENDPOINTHALT && len == 0 && + (privep = lpc31_epfindbyaddr(priv, index)) != NULL) + { + lpc31_epstall(&privep->ep, true); + + lpc31_ep0state (priv, EP0STATE_WAIT_NAK_IN); + } + else + { + usbtrace(TRACE_DEVERROR(LPC31_TRACEERR_BADCLEARFEATURE), 0); + priv->stalled = true; + } + } + break; + + case USB_REQ_SETFEATURE: + { + /* type: host-to-device; recipient = device, interface, endpoint + * value: feature selector + * index: zero interface endpoint; + * len: 0; data = none + */ + + usbtrace(TRACE_INTDECODE(LPC31_TRACEINTID_SETFEATURE), 0); + if (((ctrl.type & USB_REQ_RECIPIENT_MASK) == USB_REQ_RECIPIENT_DEVICE) && + value == USB_FEATURE_TESTMODE) + { + ullvdbg("test mode: %d\n", index); + } + else if ((ctrl.type & USB_REQ_RECIPIENT_MASK) != USB_REQ_RECIPIENT_ENDPOINT) + { + lpc31_dispatchrequest(priv, &ctrl); + } + else if (priv->paddrset != 0 && value == USB_FEATURE_ENDPOINTHALT && len == 0 && + (privep = lpc31_epfindbyaddr(priv, index)) != NULL) + { + lpc31_epstall(&privep->ep, false); + + lpc31_ep0state (priv, EP0STATE_WAIT_NAK_IN); + } + else + { + usbtrace(TRACE_DEVERROR(LPC31_TRACEERR_BADSETFEATURE), 0); + priv->stalled = true; + } + } + break; + + case USB_REQ_SETADDRESS: + { + /* type: host-to-device; recipient = device + * value: device address + * index: 0 + * len: 0; data = none + */ + usbtrace(TRACE_INTDECODE(LPC31_TRACEINTID_EP0SETUPSETADDRESS), value); + if ((ctrl.type & USB_REQ_RECIPIENT_MASK) == USB_REQ_RECIPIENT_DEVICE && + index == 0 && len == 0 && value < 128) + { + /* Save the address. We cannot actually change to the next address until + * the completion of the status phase. */ + + priv->paddr = ctrl.value[0]; + priv->paddrset = false; + + lpc31_ep0state (priv, EP0STATE_WAIT_NAK_IN); + } + else + { + usbtrace(TRACE_DEVERROR(LPC31_TRACEERR_BADSETADDRESS), 0); + priv->stalled = true; + } + } + break; + + case USB_REQ_GETDESCRIPTOR: + /* type: device-to-host; recipient = device + * value: descriptor type and index + * index: 0 or language ID; + * len: descriptor len; data = descriptor + */ + case USB_REQ_SETDESCRIPTOR: + /* type: host-to-device; recipient = device + * value: descriptor type and index + * index: 0 or language ID; + * len: descriptor len; data = descriptor + */ + { + usbtrace(TRACE_INTDECODE(LPC31_TRACEINTID_GETSETDESC), 0); + if ((ctrl.type & USB_REQ_RECIPIENT_MASK) == USB_REQ_RECIPIENT_DEVICE) + { + lpc31_dispatchrequest(priv, &ctrl); + } + else + { + usbtrace(TRACE_DEVERROR(LPC31_TRACEERR_BADGETSETDESC), 0); + priv->stalled = true; + } + } + break; + + case USB_REQ_GETCONFIGURATION: + /* type: device-to-host; recipient = device + * value: 0; + * index: 0; + * len: 1; data = configuration value + */ + { + usbtrace(TRACE_INTDECODE(LPC31_TRACEINTID_GETCONFIG), 0); + if (priv->paddrset && (ctrl.type & USB_REQ_RECIPIENT_MASK) == USB_REQ_RECIPIENT_DEVICE && + value == 0 && index == 0 && len == 1) + { + lpc31_dispatchrequest(priv, &ctrl); + } + else + { + usbtrace(TRACE_DEVERROR(LPC31_TRACEERR_BADGETCONFIG), 0); + priv->stalled = true; + } + } + break; + + case USB_REQ_SETCONFIGURATION: + /* type: host-to-device; recipient = device + * value: configuration value + * index: 0; + * len: 0; data = none + */ + { + usbtrace(TRACE_INTDECODE(LPC31_TRACEINTID_SETCONFIG), 0); + if ((ctrl.type & USB_REQ_RECIPIENT_MASK) == USB_REQ_RECIPIENT_DEVICE && + index == 0 && len == 0) + { + lpc31_dispatchrequest(priv, &ctrl); + } + else + { + usbtrace(TRACE_DEVERROR(LPC31_TRACEERR_BADSETCONFIG), 0); + priv->stalled = true; + } + } + break; + + case USB_REQ_GETINTERFACE: + /* type: device-to-host; recipient = interface + * value: 0 + * index: interface; + * len: 1; data = alt interface + */ + case USB_REQ_SETINTERFACE: + /* type: host-to-device; recipient = interface + * value: alternate setting + * index: interface; + * len: 0; data = none + */ + { + usbtrace(TRACE_INTDECODE(LPC31_TRACEINTID_GETSETIF), 0); + lpc31_dispatchrequest(priv, &ctrl); + } + break; + + case USB_REQ_SYNCHFRAME: + /* type: device-to-host; recipient = endpoint + * value: 0 + * index: endpoint; + * len: 2; data = frame number + */ + { + usbtrace(TRACE_INTDECODE(LPC31_TRACEINTID_SYNCHFRAME), 0); + } + break; + + default: + { + usbtrace(TRACE_DEVERROR(LPC31_TRACEERR_INVALIDCTRLREQ), 0); + priv->stalled = true; + } + break; + } + } + + if (priv->stalled) + { + usbtrace(TRACE_DEVERROR(LPC31_TRACEERR_EP0SETUPSTALLED), priv->ep0state); + lpc31_epstall(&priv->eplist[LPC31_EP0_IN].ep, false); + lpc31_epstall(&priv->eplist[LPC31_EP0_OUT].ep, false); + } +} + +/******************************************************************************* + * Name: lpc31_ep0complete + * + * Description: + * Transfer complete handler for Endpoint 0 + * + *******************************************************************************/ + +static void lpc31_ep0complete(struct lpc31_usbdev_s *priv, uint8_t epphy) +{ + struct lpc31_ep_s *privep = &priv->eplist[epphy]; + + usbtrace(TRACE_INTDECODE(LPC31_TRACEINTID_EP0COMPLETE), (uint16_t)priv->ep0state); + + switch (priv->ep0state) + { + case EP0STATE_DATA_IN: + if (lpc31_rqempty(privep)) + return; + + if (lpc31_epcomplete (priv, epphy)) + lpc31_ep0state (priv, EP0STATE_WAIT_NAK_OUT); + break; + + case EP0STATE_DATA_OUT: + if (lpc31_rqempty(privep)) + return; + + if (lpc31_epcomplete (priv, epphy)) + lpc31_ep0state (priv, EP0STATE_WAIT_NAK_IN); + break; + + case EP0STATE_SHORTWRITE: + lpc31_ep0state (priv, EP0STATE_WAIT_NAK_OUT); + break; + + case EP0STATE_WAIT_STATUS_IN: + lpc31_ep0state (priv, EP0STATE_IDLE); + + /* If we've received a SETADDRESS packet, then we set the address + * now that the status phase has completed */ + if (! priv->paddrset && priv->paddr != 0) + { + usbtrace(TRACE_INTDECODE(LPC31_TRACEINTID_EP0INSETADDRESS), (uint16_t)priv->paddr); + lpc31_set_address (priv, priv->paddr); + } + break; + + case EP0STATE_WAIT_STATUS_OUT: + lpc31_ep0state (priv, EP0STATE_IDLE); + break; + + default: +#ifdef CONFIG_DEBUG + DEBUGASSERT(priv->ep0state != EP0STATE_DATA_IN && + priv->ep0state != EP0STATE_DATA_OUT && + priv->ep0state != EP0STATE_SHORTWRITE && + priv->ep0state != EP0STATE_WAIT_STATUS_IN && + priv->ep0state != EP0STATE_WAIT_STATUS_OUT); +#endif + priv->stalled = true; + break; + } + + if (priv->stalled) + { + usbtrace(TRACE_DEVERROR(LPC31_TRACEERR_EP0SETUPSTALLED), priv->ep0state); + lpc31_epstall(&priv->eplist[LPC31_EP0_IN].ep, false); + lpc31_epstall(&priv->eplist[LPC31_EP0_OUT].ep, false); + } +} + +/******************************************************************************* + * Name: lpc31_ep0nak + * + * Description: + * Handle a NAK interrupt on EP0 + * + *******************************************************************************/ + +static void lpc31_ep0nak(struct lpc31_usbdev_s *priv, uint8_t epphy) +{ + usbtrace(TRACE_INTDECODE(LPC31_TRACEINTID_EP0NAK), (uint16_t)priv->ep0state); + + switch (priv->ep0state) + { + case EP0STATE_WAIT_NAK_IN: + lpc31_ep0xfer (LPC31_EP0_IN, NULL, 0); + lpc31_ep0state (priv, EP0STATE_WAIT_STATUS_IN); + break; + case EP0STATE_WAIT_NAK_OUT: + lpc31_ep0xfer (LPC31_EP0_OUT, NULL, 0); + lpc31_ep0state (priv, EP0STATE_WAIT_STATUS_OUT); + break; + default: +#ifdef CONFIG_DEBUG + DEBUGASSERT(priv->ep0state != EP0STATE_WAIT_NAK_IN && + priv->ep0state != EP0STATE_WAIT_NAK_OUT); +#endif + priv->stalled = true; + break; + } + if (priv->stalled) + { + usbtrace(TRACE_DEVERROR(LPC31_TRACEERR_EP0SETUPSTALLED), priv->ep0state); + lpc31_epstall(&priv->eplist[LPC31_EP0_IN].ep, false); + lpc31_epstall(&priv->eplist[LPC31_EP0_OUT].ep, false); + } +} + +/******************************************************************************* + * Name: lpc31_epcomplete + * + * Description: + * Transfer complete handler for Endpoints other than 0 + * returns whether the request at the head has completed + * + *******************************************************************************/ + +bool +lpc31_epcomplete(struct lpc31_usbdev_s *priv, uint8_t epphy) +{ + struct lpc31_ep_s *privep = &priv->eplist[epphy]; + struct lpc31_req_s *privreq = privep->head; + struct lpc31_dtd_s *dtd = &g_td[epphy]; + + if (privreq == NULL) /* This shouldn't really happen */ + { + if (LPC31_EPPHYOUT(privep->epphy)) + usbtrace(TRACE_INTDECODE(LPC31_TRACEINTID_EPINQEMPTY), 0); + else + usbtrace(TRACE_INTDECODE(LPC31_TRACEINTID_EPOUTQEMPTY), 0); + return true; + } + + int xfrd = dtd->xfer_len - (dtd->config >> 16); + + privreq->req.xfrd += xfrd; + + bool complete = true; + if (LPC31_EPPHYOUT(privep->epphy)) + { + /* read(OUT) completes when request filled, or a short transfer is received */ + + usbtrace(TRACE_INTDECODE(LPC31_TRACEINTID_EPIN), complete); + } + else + { + /* write(IN) completes when request finished, unless we need to terminate with a ZLP */ + + bool need_zlp = (xfrd == privep->ep.maxpacket) && ((privreq->req.flags & USBDEV_REQFLAGS_NULLPKT) != 0); + + complete = (privreq->req.xfrd >= privreq->req.len && !need_zlp); + + usbtrace(TRACE_INTDECODE(LPC31_TRACEINTID_EPOUT), complete); + } + + /* If the transfer is complete, then dequeue and progress any further queued requests */ + + if (complete) + { + privreq = lpc31_rqdequeue (privep); + } + + if (!lpc31_rqempty(privep)) + { + lpc31_progressep(privep); + } + + /* Now it's safe to call the completion callback as it may well submit a new request */ + + if (complete) + { + usbtrace(TRACE_COMPLETE(privep->epphy), privreq->req.xfrd); + lpc31_reqcomplete(privep, privreq, OK); + } + + return complete; +} + + +/******************************************************************************* + * Name: lpc31_usbinterrupt + * + * Description: + * USB interrupt handler + * + *******************************************************************************/ + +static int lpc31_usbinterrupt(int irq, FAR void *context) +{ + struct lpc31_usbdev_s *priv = &g_usbdev; + uint32_t disr, portsc1, n; + + usbtrace(TRACE_INTENTRY(LPC31_TRACEINTID_USB), 0); + + /* Read the interrupts and then clear them */ + disr = lpc31_getreg(LPC31_USBDEV_USBSTS); + lpc31_putreg(disr, LPC31_USBDEV_USBSTS); + + if (disr & USBDEV_USBSTS_URI) + { + usbtrace(TRACE_INTDECODE(LPC31_TRACEINTID_DEVRESET),0); + + lpc31_usbreset(priv); + + usbtrace(TRACE_INTEXIT(LPC31_TRACEINTID_USB), 0); + return OK; + } + + if (disr & USBDEV_USBSTS_SLI) + { + // FIXME: what do we need to do here... + usbtrace(TRACE_INTDECODE(LPC31_TRACEINTID_SUSPENDCHG),0); + } + + if (disr & USBDEV_USBSTS_PCI) + { + portsc1 = lpc31_getreg(LPC31_USBDEV_PORTSC1); + + if (portsc1 & USBDEV_PRTSC1_HSP) + priv->usbdev.speed = USB_SPEED_HIGH; + else + priv->usbdev.speed = USB_SPEED_FULL; + + if (portsc1 & USBDEV_PRTSC1_FPR) + { + /* FIXME: this occurs because of a J-to-K transition detected + * while the port is in SUSPEND state - presumambly this + * is where the host is resuming the device? + * + * - but do we need to "ack" the interrupt + */ + } + } + +#ifdef CONFIG_LPC31_USBDEV_FRAME_INTERRUPT + if (disr & USBDEV_USBSTT_SRI) + { + usbtrace(TRACE_INTDECODE(LPC31_TRACEINTID_FRAME), 0); + + priv->sof = (int)lpc31_getreg(LPC31_USBDEV_FRINDEX_OFFSET); + } +#endif + + if (disr & USBDEV_USBSTS_UEI) + { + /* FIXME: these occur when a transfer results in an error condition + * it is set alongside USBINT if the DTD also had its IOC + * bit set. */ + } + + if (disr & USBDEV_USBSTS_UI) + { + /* Handle completion interrupts */ + uint32_t mask = lpc31_getreg (LPC31_USBDEV_ENDPTCOMPLETE); + + if (mask) + { + // Clear any NAK interrupt and completion interrupts + lpc31_putreg (mask, LPC31_USBDEV_ENDPTNAK); + lpc31_putreg (mask, LPC31_USBDEV_ENDPTCOMPLETE); + + if (mask & LPC31_ENDPTMASK(0)) + lpc31_ep0complete(priv, 0); + if (mask & LPC31_ENDPTMASK(1)) + lpc31_ep0complete(priv, 1); + + for (n = 1; n < LPC31_NLOGENDPOINTS; n++) + { + if (mask & LPC31_ENDPTMASK((n<<1))) + lpc31_epcomplete (priv, (n<<1)); + if (mask & LPC31_ENDPTMASK((n<<1)+1)) + lpc31_epcomplete(priv, (n<<1)+1); + } + } + + /* Handle setup interrupts */ + uint32_t setupstat = lpc31_getreg(LPC31_USBDEV_ENDPTSETUPSTAT); + if (setupstat) + { + /* Clear the endpoint complete CTRL OUT and IN when a Setup is received */ + lpc31_putreg (LPC31_ENDPTMASK(LPC31_EP0_IN) | LPC31_ENDPTMASK(LPC31_EP0_OUT), + LPC31_USBDEV_ENDPTCOMPLETE); + + if (setupstat & LPC31_ENDPTMASK(LPC31_EP0_OUT)) + { + usbtrace(TRACE_INTDECODE(LPC31_TRACEINTID_EP0SETUP), setupstat); + lpc31_ep0setup(priv); + } + } + } + + if (disr & USBDEV_USBSTS_NAKI) + { + uint32_t pending = lpc31_getreg(LPC31_USBDEV_ENDPTNAK) & lpc31_getreg(LPC31_USBDEV_ENDPTNAKEN); + if (pending) + { + /* We shouldn't see NAK interrupts except on Endpoint 0 */ + if (pending & LPC31_ENDPTMASK(0)) + lpc31_ep0nak(priv, 0); + if (pending & LPC31_ENDPTMASK(1)) + lpc31_ep0nak(priv, 1); + } + + // clear the interrupts + lpc31_putreg(pending, LPC31_USBDEV_ENDPTNAK); + } + usbtrace(TRACE_INTEXIT(LPC31_TRACEINTID_USB), 0); + return OK; +} + +/******************************************************************************* + * Endpoint operations + *******************************************************************************/ + +/******************************************************************************* + * Name: lpc31_epconfigure + * + * Description: + * Configure endpoint, making it usable + * + * Input Parameters: + * ep - the struct usbdev_ep_s instance obtained from allocep() + * desc - A struct usb_epdesc_s instance describing the endpoint + * last - true if this this last endpoint to be configured. Some hardware + * needs to take special action when all of the endpoints have been + * configured. + * + *******************************************************************************/ + +static int lpc31_epconfigure(FAR struct usbdev_ep_s *ep, + FAR const struct usb_epdesc_s *desc, + bool last) +{ + FAR struct lpc31_ep_s *privep = (FAR struct lpc31_ep_s *)ep; + + usbtrace(TRACE_EPCONFIGURE, privep->epphy); + DEBUGASSERT(desc->addr == ep->eplog); + + // Initialise EP capabilities + + uint16_t maxsize = GETUINT16(desc->mxpacketsize); + if ((desc->attr & USB_EP_ATTR_XFERTYPE_MASK) == USB_EP_ATTR_XFER_ISOC) + { + g_qh[privep->epphy].capability = (DQH_CAPABILITY_MAX_PACKET(maxsize) | + DQH_CAPABILITY_IOS | + DQH_CAPABILITY_ZLT); + } + else + { + g_qh[privep->epphy].capability = (DQH_CAPABILITY_MAX_PACKET(maxsize) | + DQH_CAPABILITY_ZLT); + } + + /* Setup Endpoint Control Register */ + + if (LPC31_EPPHYIN(privep->epphy)) + { + /* Reset the data toggles */ + uint32_t cfg = USBDEV_ENDPTCTRL_TXR; + + /* Set the endpoint type */ + switch (desc->attr & USB_EP_ATTR_XFERTYPE_MASK) + { + case USB_EP_ATTR_XFER_CONTROL: cfg |= USBDEV_ENDPTCTRL_TXT_CTRL; break; + case USB_EP_ATTR_XFER_ISOC: cfg |= USBDEV_ENDPTCTRL_TXT_ISOC; break; + case USB_EP_ATTR_XFER_BULK: cfg |= USBDEV_ENDPTCTRL_TXT_BULK; break; + case USB_EP_ATTR_XFER_INT: cfg |= USBDEV_ENDPTCTRL_TXT_INTR; break; + } + lpc31_chgbits (0xFFFF0000, cfg, LPC31_USBDEV_ENDPTCTRL(privep->epphy)); + } + else + { + /* Reset the data toggles */ + uint32_t cfg = USBDEV_ENDPTCTRL_RXR; + + /* Set the endpoint type */ + switch (desc->attr & USB_EP_ATTR_XFERTYPE_MASK) + { + case USB_EP_ATTR_XFER_CONTROL: cfg |= USBDEV_ENDPTCTRL_RXT_CTRL; break; + case USB_EP_ATTR_XFER_ISOC: cfg |= USBDEV_ENDPTCTRL_RXT_ISOC; break; + case USB_EP_ATTR_XFER_BULK: cfg |= USBDEV_ENDPTCTRL_RXT_BULK; break; + } + lpc31_chgbits (0x0000FFFF, cfg, LPC31_USBDEV_ENDPTCTRL(privep->epphy)); + } + + /* Reset endpoint status */ + privep->stalled = false; + + /* Enable the endpoint */ + if (LPC31_EPPHYIN(privep->epphy)) + lpc31_setbits (USBDEV_ENDPTCTRL_TXE, LPC31_USBDEV_ENDPTCTRL(privep->epphy)); + else + lpc31_setbits (USBDEV_ENDPTCTRL_RXE, LPC31_USBDEV_ENDPTCTRL(privep->epphy)); + + return OK; +} + +/******************************************************************************* + * Name: lpc31_epdisable + * + * Description: + * The endpoint will no longer be used + * + *******************************************************************************/ + +static int lpc31_epdisable(FAR struct usbdev_ep_s *ep) +{ + FAR struct lpc31_ep_s *privep = (FAR struct lpc31_ep_s *)ep; + irqstate_t flags; + +#ifdef CONFIG_DEBUG + if (!ep) + { + usbtrace(TRACE_DEVERROR(LPC31_TRACEERR_INVALIDPARMS), 0); + return -EINVAL; + } +#endif + usbtrace(TRACE_EPDISABLE, privep->epphy); + + flags = irqsave(); + + /* Disable Endpoint */ + if (LPC31_EPPHYIN(privep->epphy)) + lpc31_clrbits (USBDEV_ENDPTCTRL_TXE, LPC31_USBDEV_ENDPTCTRL(privep->epphy)); + else + lpc31_clrbits (USBDEV_ENDPTCTRL_RXE, LPC31_USBDEV_ENDPTCTRL(privep->epphy)); + + privep->stalled = true; + + /* Cancel any ongoing activity */ + lpc31_cancelrequests(privep, -ESHUTDOWN); + + irqrestore(flags); + return OK; +} + +/******************************************************************************* + * Name: lpc31_epallocreq + * + * Description: + * Allocate an I/O request + * + *******************************************************************************/ + +static FAR struct usbdev_req_s *lpc31_epallocreq(FAR struct usbdev_ep_s *ep) +{ + FAR struct lpc31_req_s *privreq; + +#ifdef CONFIG_DEBUG + if (!ep) + { + usbtrace(TRACE_DEVERROR(LPC31_TRACEERR_INVALIDPARMS), 0); + return NULL; + } +#endif + usbtrace(TRACE_EPALLOCREQ, ((FAR struct lpc31_ep_s *)ep)->epphy); + + privreq = (FAR struct lpc31_req_s *)malloc(sizeof(struct lpc31_req_s)); + if (!privreq) + { + usbtrace(TRACE_DEVERROR(LPC31_TRACEERR_ALLOCFAIL), 0); + return NULL; + } + + memset(privreq, 0, sizeof(struct lpc31_req_s)); + + return &privreq->req; +} + +/******************************************************************************* + * Name: lpc31_epfreereq + * + * Description: + * Free an I/O request + * + *******************************************************************************/ + +static void lpc31_epfreereq(FAR struct usbdev_ep_s *ep, FAR struct usbdev_req_s *req) +{ + FAR struct lpc31_req_s *privreq = (FAR struct lpc31_req_s *)req; + +#ifdef CONFIG_DEBUG + if (!ep || !req) + { + usbtrace(TRACE_DEVERROR(LPC31_TRACEERR_INVALIDPARMS), 0); + return; + } +#endif + + usbtrace(TRACE_EPFREEREQ, ((FAR struct lpc31_ep_s *)ep)->epphy); + + free(privreq); +} + +/******************************************************************************* + * Name: lpc31_epallocbuffer + * + * Description: + * Allocate an I/O buffer + * + *******************************************************************************/ + +#ifdef CONFIG_ARCH_USBDEV_DMA +static void *lpc31_epallocbuffer(FAR struct usbdev_ep_s *ep, unsigned bytes) +{ + usbtrace(TRACE_EPALLOCBUFFER, privep->epphy); + return malloc(bytes) +} +#endif + +/******************************************************************************* + * Name: lpc31_epfreebuffer + * + * Description: + * Free an I/O buffer + * + *******************************************************************************/ + +#ifdef CONFIG_LPC313x_USBDEV_DMA +static void lpc31_epfreebuffer(FAR struct usbdev_ep_s *ep, FAR void *buf) +{ + usbtrace(TRACE_EPFREEBUFFER, privep->epphy); + free(buf); +} +#endif + +/******************************************************************************* + * Name: lpc31_epsubmit + * + * Description: + * Submit an I/O request to the endpoint + * + *******************************************************************************/ + +static int lpc31_epsubmit(FAR struct usbdev_ep_s *ep, FAR struct usbdev_req_s *req) +{ + FAR struct lpc31_req_s *privreq = (FAR struct lpc31_req_s *)req; + FAR struct lpc31_ep_s *privep = (FAR struct lpc31_ep_s *)ep; + FAR struct lpc31_usbdev_s *priv; + irqstate_t flags; + int ret = OK; + +#ifdef CONFIG_DEBUG + if (!req || !req->callback || !req->buf || !ep) + { + usbtrace(TRACE_DEVERROR(LPC31_TRACEERR_INVALIDPARMS), 0); + ullvdbg("req=%p callback=%p buf=%p ep=%p\n", req, req->callback, req->buf, ep); + return -EINVAL; + } +#endif + + usbtrace(TRACE_EPSUBMIT, privep->epphy); + priv = privep->dev; + + if (!priv->driver || priv->usbdev.speed == USB_SPEED_UNKNOWN) + { + usbtrace(TRACE_DEVERROR(LPC31_TRACEERR_NOTCONFIGURED), priv->usbdev.speed); + return -ESHUTDOWN; + } + + /* Handle the request from the class driver */ + + req->result = -EINPROGRESS; + req->xfrd = 0; + + /* Disable Interrupts */ + + flags = irqsave(); + + /* If we are stalled, then drop all requests on the floor */ + + if (privep->stalled) + { + ret = -EBUSY; + } + else + { + /* Add the new request to the request queue for the endpoint */ + + if (LPC31_EPPHYIN(privep->epphy)) + usbtrace(TRACE_INREQQUEUED(privep->epphy), privreq->req.len); + else + usbtrace(TRACE_OUTREQQUEUED(privep->epphy), privreq->req.len); + + if (lpc31_rqenqueue(privep, privreq)) + { + lpc31_progressep(privep); + } + } + + irqrestore(flags); + return ret; +} + +/******************************************************************************* + * Name: lpc31_epcancel + * + * Description: + * Cancel an I/O request previously sent to an endpoint + * + *******************************************************************************/ + +static int lpc31_epcancel(FAR struct usbdev_ep_s *ep, FAR struct usbdev_req_s *req) +{ + FAR struct lpc31_ep_s *privep = (FAR struct lpc31_ep_s *)ep; + FAR struct lpc31_usbdev_s *priv; + irqstate_t flags; + +#ifdef CONFIG_DEBUG + if (!ep || !req) + { + usbtrace(TRACE_DEVERROR(LPC31_TRACEERR_INVALIDPARMS), 0); + return -EINVAL; + } +#endif + + usbtrace(TRACE_EPCANCEL, privep->epphy); + priv = privep->dev; + + flags = irqsave(); + + /* FIXME: if the request is the first, then we need to flush the EP + * otherwise just remove it from the list + * + * but ... all other implementations cancel all requests ... + */ + + lpc31_cancelrequests(privep, -ESHUTDOWN); + irqrestore(flags); + return OK; +} + +/******************************************************************************* + * Name: lpc31_epstall + * + * Description: + * Stall or resume and endpoint + * + *******************************************************************************/ + +static int lpc31_epstall(FAR struct usbdev_ep_s *ep, bool resume) +{ + FAR struct lpc31_ep_s *privep = (FAR struct lpc31_ep_s *)ep; + irqstate_t flags; + + /* STALL or RESUME the endpoint */ + + flags = irqsave(); + usbtrace(resume ? TRACE_EPRESUME : TRACE_EPSTALL, privep->epphy); + + uint32_t addr = LPC31_USBDEV_ENDPTCTRL(privep->epphy); + uint32_t ctrl_xs = LPC31_EPPHYIN(privep->epphy) ? USBDEV_ENDPTCTRL_TXS : USBDEV_ENDPTCTRL_RXS; + uint32_t ctrl_xr = LPC31_EPPHYIN(privep->epphy) ? USBDEV_ENDPTCTRL_TXR : USBDEV_ENDPTCTRL_RXR; + + if (resume) + { + privep->stalled = false; + + /* Clear stall and reset the data toggle */ + + lpc31_chgbits (ctrl_xs | ctrl_xr, ctrl_xr, addr); + } + else + { + privep->stalled = true; + + lpc31_setbits (ctrl_xs, addr); + } + + irqrestore(flags); + return OK; +} + +/******************************************************************************* + * Device operations + *******************************************************************************/ + +/******************************************************************************* + * Name: lcp313x_allocep + * + * Description: + * Allocate an endpoint matching the parameters. + * + * Input Parameters: + * eplog - 7-bit logical endpoint number (direction bit ignored). Zero means + * that any endpoint matching the other requirements will suffice. The + * assigned endpoint can be found in the eplog field. + * in - true: IN (device-to-host) endpoint requested + * eptype - Endpoint type. One of {USB_EP_ATTR_XFER_ISOC, USB_EP_ATTR_XFER_BULK, + * USB_EP_ATTR_XFER_INT} + * + *******************************************************************************/ + +static FAR struct usbdev_ep_s *lcp313x_allocep(FAR struct usbdev_s *dev, uint8_t eplog, + bool in, uint8_t eptype) +{ + FAR struct lpc31_usbdev_s *priv = (FAR struct lpc31_usbdev_s *)dev; + uint32_t epset = LPC31_EPALLSET & ~LPC31_EPCTRLSET; + irqstate_t flags; + int epndx = 0; + + usbtrace(TRACE_DEVALLOCEP, (uint16_t)eplog); + + /* Ignore any direction bits in the logical address */ + + eplog = USB_EPNO(eplog); + + /* A logical address of 0 means that any endpoint will do */ + + if (eplog > 0) + { + /* Otherwise, we will return the endpoint structure only for the requested + * 'logical' endpoint. All of the other checks will still be performed. + * + * First, verify that the logical endpoint is in the range supported by + * by the hardware. + */ + + if (eplog >= LPC31_NLOGENDPOINTS) + { + usbtrace(TRACE_DEVERROR(LPC31_TRACEERR_BADEPNO), (uint16_t)eplog); + return NULL; + } + + /* Convert the logical address to a physical OUT endpoint address and + * remove all of the candidate endpoints from the bitset except for the + * the IN/OUT pair for this logical address. + */ + + epset &= 3 << (eplog << 1); + } + + /* Get the subset matching the requested direction */ + + if (in) + { + epset &= LPC31_EPINSET; + } + else + { + epset &= LPC31_EPOUTSET; + } + + /* Get the subset matching the requested type */ + + switch (eptype) + { + case USB_EP_ATTR_XFER_INT: /* Interrupt endpoint */ + epset &= LPC31_EPINTRSET; + break; + + case USB_EP_ATTR_XFER_BULK: /* Bulk endpoint */ + epset &= LPC31_EPBULKSET; + break; + + case USB_EP_ATTR_XFER_ISOC: /* Isochronous endpoint */ + epset &= LPC31_EPISOCSET; + break; + + case USB_EP_ATTR_XFER_CONTROL: /* Control endpoint -- not a valid choice */ + default: + usbtrace(TRACE_DEVERROR(LPC31_TRACEERR_BADEPTYPE), (uint16_t)eptype); + return NULL; + } + + /* Is the resulting endpoint supported by the LPC313x? */ + + if (epset) + { + /* Yes.. now see if any of the request endpoints are available */ + + flags = irqsave(); + epset &= priv->epavail; + if (epset) + { + /* Select the lowest bit in the set of matching, available endpoints */ + + for (epndx = 2; epndx < LPC31_NPHYSENDPOINTS; epndx++) + { + uint32_t bit = 1 << epndx; + if ((epset & bit) != 0) + { + /* Mark the IN/OUT endpoint no longer available */ + + priv->epavail &= ~(3 << (bit & ~1)); + irqrestore(flags); + + /* And return the pointer to the standard endpoint structure */ + + return &priv->eplist[epndx].ep; + } + } + /* Shouldn't get here */ + } + irqrestore(flags); + } + + usbtrace(TRACE_DEVERROR(LPC31_TRACEERR_NOEP), (uint16_t)eplog); + return NULL; +} + +/******************************************************************************* + * Name: lpc31_freeep + * + * Description: + * Free the previously allocated endpoint + * + *******************************************************************************/ + +static void lpc31_freeep(FAR struct usbdev_s *dev, FAR struct usbdev_ep_s *ep) +{ + FAR struct lpc31_usbdev_s *priv = (FAR struct lpc31_usbdev_s *)dev; + FAR struct lpc31_ep_s *privep = (FAR struct lpc31_ep_s *)ep; + irqstate_t flags; + + usbtrace(TRACE_DEVFREEEP, (uint16_t)privep->epphy); + + if (priv && privep) + { + /* Mark the endpoint as available */ + + flags = irqsave(); + priv->epavail |= (1 << privep->epphy); + irqrestore(flags); + } +} + +/******************************************************************************* + * Name: lpc31_getframe + * + * Description: + * Returns the current frame number + * + *******************************************************************************/ + +static int lpc31_getframe(struct usbdev_s *dev) +{ +#ifdef CONFIG_LPC31_USBDEV_FRAME_INTERRUPT + FAR struct lpc31_usbdev_s *priv = (FAR struct lpc31_usbdev_s *)dev; + + /* Return last valid value of SOF read by the interrupt handler */ + + usbtrace(TRACE_DEVGETFRAME, (uint16_t)priv->sof); + return priv->sof; +#else + /* Return the last frame number detected by the hardware */ + + usbtrace(TRACE_DEVGETFRAME, 0); + + /* FIXME: this actually returns the micro frame number! */ + return (int)lpc31_getreg(LPC31_USBDEV_FRINDEX_OFFSET); +#endif +} + +/******************************************************************************* + * Name: lpc31_wakeup + * + * Description: + * Tries to wake up the host connected to this device + * + *******************************************************************************/ + +static int lpc31_wakeup(struct usbdev_s *dev) +{ + irqstate_t flags; + + usbtrace(TRACE_DEVWAKEUP, 0); + + flags = irqsave(); + lpc31_setbits(USBDEV_PRTSC1_FPR, LPC31_USBDEV_PORTSC1); + irqrestore(flags); + return OK; +} + +/******************************************************************************* + * Name: lpc31_selfpowered + * + * Description: + * Sets/clears the device selfpowered feature + * + *******************************************************************************/ + +static int lpc31_selfpowered(struct usbdev_s *dev, bool selfpowered) +{ + FAR struct lpc31_usbdev_s *priv = (FAR struct lpc31_usbdev_s *)dev; + + usbtrace(TRACE_DEVSELFPOWERED, (uint16_t)selfpowered); + +#ifdef CONFIG_DEBUG + if (!dev) + { + usbtrace(TRACE_DEVERROR(LPC31_TRACEERR_INVALIDPARMS), 0); + return -ENODEV; + } +#endif + + priv->selfpowered = selfpowered; + return OK; +} + +/******************************************************************************* + * Name: lpc31_pullup + * + * Description: + * Software-controlled connect to/disconnect from USB host + * + *******************************************************************************/ + +static int lpc31_pullup(struct usbdev_s *dev, bool enable) +{ + usbtrace(TRACE_DEVPULLUP, (uint16_t)enable); + + irqstate_t flags = irqsave(); + if (enable) + lpc31_setbits (USBDEV_USBCMD_RS, LPC31_USBDEV_USBCMD); + else + lpc31_clrbits (USBDEV_USBCMD_RS, LPC31_USBDEV_USBCMD); + irqrestore(flags); + return OK; +} + +/******************************************************************************* + * Public Functions + *******************************************************************************/ + +/******************************************************************************* + * Name: up_usbinitialize + * + * Description: + * Initialize USB hardware. + * + * Assumptions: + * - This function is called very early in the initialization sequence + * - PLL and GIO pin initialization is not performed here but should been in + * the low-level boot logic: PLL1 must be configured for operation at 48MHz + * and P0.23 and PO.31 in PINSEL1 must be configured for Vbus and USB connect + * LED. + * + *******************************************************************************/ + +void up_usbinitialize(void) +{ + struct lpc31_usbdev_s *priv = &g_usbdev; + int i; + + usbtrace(TRACE_DEVINIT, 0); + + /* Disable USB interrupts */ + + lpc31_putreg(0, LPC31_USBDEV_USBINTR); + + /* Initialize the device state structure */ + + memset(priv, 0, sizeof(struct lpc31_usbdev_s)); + priv->usbdev.ops = &g_devops; + priv->usbdev.ep0 = &priv->eplist[LPC31_EP0_IN].ep; + priv->epavail = LPC31_EPALLSET; + + /* Initialize the endpoint list */ + + for (i = 0; i < LPC31_NPHYSENDPOINTS; i++) + { + uint32_t bit = 1 << i; + + /* Set endpoint operations, reference to driver structure (not + * really necessary because there is only one controller), and + * the physical endpoint number (which is just the index to the + * endpoint). + */ + priv->eplist[i].ep.ops = &g_epops; + priv->eplist[i].dev = priv; + + /* The index, i, is the physical endpoint address; Map this + * to a logical endpoint address usable by the class driver. + */ + + priv->eplist[i].epphy = i; + if (LPC31_EPPHYIN(i)) + { + priv->eplist[i].ep.eplog = LPC31_EPPHYIN2LOG(i); + } + else + { + priv->eplist[i].ep.eplog = LPC31_EPPHYOUT2LOG(i); + } + + /* The maximum packet size may depend on the type of endpoint */ + + if ((LPC31_EPCTRLSET & bit) != 0) + { + priv->eplist[i].ep.maxpacket = LPC31_EP0MAXPACKET; + } + else if ((LPC31_EPINTRSET & bit) != 0) + { + priv->eplist[i].ep.maxpacket = LPC31_INTRMAXPACKET; + } + else if ((LPC31_EPBULKSET & bit) != 0) + { + priv->eplist[i].ep.maxpacket = LPC31_BULKMAXPACKET; + } + else /* if ((LPC31_EPISOCSET & bit) != 0) */ + { + priv->eplist[i].ep.maxpacket = LPC31_ISOCMAXPACKET; + } + } + + /* Enable USB to AHB clock and to Event router*/ + + lpc31_enableclock (CLKID_USBOTGAHBCLK); + lpc31_enableclock (CLKID_EVENTROUTERPCLK); + + /* Reset USB block */ + + lpc31_softreset (RESETID_USBOTGAHBRST); + + /* Enable USB OTG PLL and wait for lock */ + + lpc31_putreg (0, LPC31_SYSCREG_USB_ATXPLLPDREG); + + uint32_t bank = EVNTRTR_BANK(EVENTRTR_USBATXPLLLOCK); + uint32_t bit = EVNTRTR_BIT(EVENTRTR_USBATXPLLLOCK); + + while (! (lpc31_getreg(LPC31_EVNTRTR_RSR(bank)) & (1 << bit))) + ; + + /* Enable USB AHB clock */ + + lpc31_enableclock (CLKID_USBOTGAHBCLK); + + /* Reset the controller */ + + lpc31_putreg (USBDEV_USBCMD_RST, LPC31_USBDEV_USBCMD); + while (lpc31_getreg (LPC31_USBDEV_USBCMD) & USBDEV_USBCMD_RST) + ; + + /* Attach USB controller interrupt handler */ + + if (irq_attach(LPC31_IRQ_USBOTG, lpc31_usbinterrupt) != 0) + { + usbtrace(TRACE_DEVERROR(LPC31_TRACEERR_IRQREGISTRATION), + (uint16_t)LPC31_IRQ_USBOTG); + goto errout; + } + + + /* Program the controller to be the USB device controller */ + + lpc31_putreg (USBDEV_USBMODE_SDIS | USBDEV_USBMODE_SLOM | USBDEV_USBMODE_CMDEVICE, + LPC31_USBDEV_USBMODE); + + /* Disconnect device */ + + lpc31_pullup(&priv->usbdev, false); + + /* Reset/Re-initialize the USB hardware */ + + lpc31_usbreset(priv); + + return; + +errout: + up_usbuninitialize(); +} + +/******************************************************************************* + * Name: up_usbuninitialize + *******************************************************************************/ + +void up_usbuninitialize(void) +{ + struct lpc31_usbdev_s *priv = &g_usbdev; + irqstate_t flags; + + usbtrace(TRACE_DEVUNINIT, 0); + + if (priv->driver) + { + usbtrace(TRACE_DEVERROR(LPC31_TRACEERR_DRIVERREGISTERED), 0); + usbdev_unregister(priv->driver); + } + + /* Disconnect device */ + + flags = irqsave(); + lpc31_pullup(&priv->usbdev, false); + priv->usbdev.speed = USB_SPEED_UNKNOWN; + + /* Disable and detach IRQs */ + + up_disable_irq(LPC31_IRQ_USBOTG); + irq_detach(LPC31_IRQ_USBOTG); + + /* Reset the controller */ + + lpc31_putreg (USBDEV_USBCMD_RST, LPC31_USBDEV_USBCMD); + while (lpc31_getreg (LPC31_USBDEV_USBCMD) & USBDEV_USBCMD_RST) + ; + + /* Turn off USB power and clocking */ + + lpc31_disableclock (CLKID_USBOTGAHBCLK); + lpc31_disableclock (CLKID_EVENTROUTERPCLK); + + + irqrestore(flags); +} + +/******************************************************************************* + * Name: usbdev_register + * + * Description: + * Register a USB device class driver. The class driver's bind() method will be + * called to bind it to a USB device driver. + * + *******************************************************************************/ + +int usbdev_register(struct usbdevclass_driver_s *driver) +{ + int ret; + + usbtrace(TRACE_DEVREGISTER, 0); + +#ifdef CONFIG_DEBUG + if (!driver || !driver->ops->bind || !driver->ops->unbind || + !driver->ops->disconnect || !driver->ops->setup) + { + usbtrace(TRACE_DEVERROR(LPC31_TRACEERR_INVALIDPARMS), 0); + return -EINVAL; + } + + if (g_usbdev.driver) + { + usbtrace(TRACE_DEVERROR(LPC31_TRACEERR_DRIVER), 0); + return -EBUSY; + } +#endif + + /* First hook up the driver */ + + g_usbdev.driver = driver; + + /* Then bind the class driver */ + + ret = CLASS_BIND(driver, &g_usbdev.usbdev); + if (ret) + { + usbtrace(TRACE_DEVERROR(LPC31_TRACEERR_BINDFAILED), (uint16_t)-ret); + g_usbdev.driver = NULL; + } + else + { + /* Enable USB controller interrupts */ + + up_enable_irq(LPC31_IRQ_USBOTG); + + /* FIXME: nothing seems to call DEV_CONNECT(), but we need to set + * the RS bit to enable the controller. It kind of makes sense + * to do this after the class has bound to us... + * GEN: This bug is really in the class driver. It should make the + * soft connect when it is ready to be enumerated. I have added + * that logic to the class drivers but left this logic here. + */ + + lpc31_pullup(&g_usbdev.usbdev, true); + } + return ret; +} + +/******************************************************************************* + * Name: usbdev_unregister + * + * Description: + * Un-register usbdev class driver.If the USB device is connected to a USB host, + * it will first disconnect(). The driver is also requested to unbind() and clean + * up any device state, before this procedure finally returns. + * + *******************************************************************************/ + +int usbdev_unregister(struct usbdevclass_driver_s *driver) +{ + usbtrace(TRACE_DEVUNREGISTER, 0); + +#ifdef CONFIG_DEBUG + if (driver != g_usbdev.driver) + { + usbtrace(TRACE_DEVERROR(LPC31_TRACEERR_INVALIDPARMS), 0); + return -EINVAL; + } +#endif + + /* Unbind the class driver */ + + CLASS_UNBIND(driver, &g_usbdev.usbdev); + + /* Disable USB controller interrupts */ + + up_disable_irq(LPC31_IRQ_USBOTG); + + /* Unhook the driver */ + + g_usbdev.driver = NULL; + return OK; +} + diff --git a/nuttx/arch/arm/src/lpc31xx/lpc31_usbotg.h b/nuttx/arch/arm/src/lpc31xx/lpc31_usbotg.h new file mode 100755 index 000000000..5057f3d46 --- /dev/null +++ b/nuttx/arch/arm/src/lpc31xx/lpc31_usbotg.h @@ -0,0 +1,654 @@ +/************************************************************************************************ + * arch/arm/src/lpc31xx/lpc31_usbotg.h + * + * Copyright (C) 2009-2010 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * 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_LPC31XX_LPC31_USBOTG_H +#define __ARCH_ARM_SRC_LPC31XX_LPC31_USBOTG_H + +/************************************************************************************************ + * Included Files + ************************************************************************************************/ + +#include +#include "lpc31_memorymap.h" + +/************************************************************************************************ + * Pre-processor Definitions + ************************************************************************************************/ + +/* USBOTG register base address offset into the USBOTG domain ***********************************/ + +#define LPC31_USBOTG_VBASE (LPC31_USBOTG_VSECTION) +#define LPC31_USBOTG_PBASE (LPC31_USBOTG_PSECTION) + +/* USBOTG register offsets (with respect to the base of the USBOTG domain) **********************/ + /* 0x000 - 0x0ff: Reserved */ +/* Device/host capability registers */ + +#define LPC31_USBOTG_CAPLENGTH_OFFSET 0x100 /* Capability register length */ +#define LPC31_USBHOST_HCIVERSION_OFFSET 0x102 /* Host interface version number */ +#define LPC31_USBHOST_HCSPARAMS_OFFSET 0x104 /* Host controller structural parameters */ +#define LPC31_USBHOST_HCCPARAMS_OFFSET 0x108 /* Host controller capability parameters */ +#define LPC31_USBDEV_DCIVERSION_OFFSET 0x120 /* Device interface version number */ +#define LPC31_USBDEV_DCCPARAMS_OFFSET 0x124 /* Device controller capability parameters */ + +/* Device/host/OTG operational registers */ + +#define LPC31_USBOTG_USBCMD_OFFSET 0x140 /* USB command (both) */ +#define LPC31_USBOTG_USBSTS_OFFSET 0x144 /* USB status (both) */ +#define LPC31_USBOTG_USBINTR_OFFSET 0x148 /* USB interrupt enable (both) */ +#define LPC31_USBOTG_FRINDEX_OFFSET 0x14C /* USB frame index (both) */ +#define LPC31_USBOTG_PERIODICLIST_OFFSET 0x154 /* Frame list base address (host) */ +#define LPC31_USBOTG_DEVICEADDR_OFFSET 0x154 /* USB device address (device) */ +#define LPC31_USBOTG_ASYNCLISTADDR_OFFSET 0x158 /* Next asynchronous list address (host) */ +#define LPC31_USBOTG_ENDPOINTLIST_OFFSET 0x158 /* Address of endpoint list in memory (device) */ +#define LPC31_USBOTG_TTCTRL_OFFSET 0x15C /* Asynchronous buffer status for embedded TT (host) */ +#define LPC31_USBOTG_BURSTSIZE_OFFSET 0x160 /* Programmable burst size (both) */ +#define LPC31_USBOTG_TXFILLTUNING_OFFSET 0x164 /* Host transmit pre-buffer packet tuning (host) */ +#define LPC31_USBOTG_BINTERVAL_OFFSET 0x174 /* Length of virtual frame (both) */ +#define LPC31_USBOTG_ENDPTNAK_OFFSET 0x178 /* Endpoint NAK (device) */ +#define LPC31_USBOTG_ENDPTNAKEN_OFFSET 0x17C /* Endpoint NAK Enable (device) */ +#define LPC31_USBOTG_CONFIGFLAG_OFFSET 0x180 /* Configured flag register (not used in lpc313x) */ +#define LPC31_USBOTG_PORTSC1_OFFSET 0x184 /* Port status/control 1 (both) */ +#define LPC31_USBOTG_OTGSC_OFFSET 0x1A4 /* OTG status and control (otg) */ +#define LPC31_USBOTG_USBMODE_OFFSET 0x1A8 /* USB device mode (both) */ + +#define LPC31_USBDEV_USBCMD_OFFSET 0x140 /* USB command (both) */ +#define LPC31_USBDEV_USBSTS_OFFSET 0x144 /* USB status (both) */ +#define LPC31_USBDEV_USBINTR_OFFSET 0x148 /* USB interrupt enable (both) */ +#define LPC31_USBDEV_FRINDEX_OFFSET 0x14C /* USB frame index (both) */ +#define LPC31_USBDEV_DEVICEADDR_OFFSET 0x154 /* USB device address (device) */ +#define LPC31_USBDEV_ENDPOINTLIST_OFFSET 0x158 /* Address of endpoint list in memory (device) */ +#define LPC31_USBDEV_BURSTSIZE_OFFSET 0x160 /* Programmable burst size (both) */ +#define LPC31_USBDEV_BINTERVAL_OFFSET 0x174 /* Length of virtual frame (both) */ +#define LPC31_USBDEV_ENDPTNAK_OFFSET 0x178 /* Endpoint NAK (device) */ +#define LPC31_USBDEV_ENDPTNAKEN_OFFSET 0x17C /* Endpoint NAK Enable (device) */ +#define LPC31_USBDEV_PORTSC1_OFFSET 0x184 /* Port status/control 1 (both) */ +#define LPC31_USBDEV_USBMODE_OFFSET 0x1A8 /* USB device mode (both) */ + +#define LPC31_USBHOST_USBCMD_OFFSET 0x140 /* USB command (both) */ +#define LPC31_USBHOST_USBSTS_OFFSET 0x144 /* USB status (both) */ +#define LPC31_USBHOST_USBINTR_OFFSET 0x148 /* USB interrupt enable (both) */ +#define LPC31_USBHOST_FRINDEX_OFFSET 0x14C /* USB frame index (both) */ +#define LPC31_USBHOST_PERIODICLIST_OFFSET 0x154 /* Frame list base address (host) */ +#define LPC31_USBHOST_ASYNCLISTADDR_OFFSET 0x158 /* Next asynchronous list address (host) */ +#define LPC31_USBHOST_TTCTRL_OFFSET 0x15C /* Asynchronous buffer status for embedded TT (host) */ +#define LPC31_USBHOST_BURSTSIZE_OFFSET 0x160 /* Programmable burst size (both) */ +#define LPC31_USBHOST_TXFILLTUNING_OFFSET 0x164 /* Host transmit pre-buffer packet tuning (host) */ +#define LPC31_USBHOST_BINTERVAL_OFFSET 0x174 /* Length of virtual frame (both) */ +#define LPC31_USBHOST_PORTSC1_OFFSET 0x184 /* Port status/control 1 (both) */ +#define LPC31_USBHOST_USBMODE_OFFSET 0x1A8 /* USB device mode (both) */ + +/* Device endpoint registers */ + +#define LPC31_USBDEV_ENDPTSETUPSTAT_OFFSET 0x1AC /* Endpoint setup status */ +#define LPC31_USBDEV_ENDPTPRIME_OFFSET 0x1B0 /* Endpoint initialization */ +#define LPC31_USBDEV_ENDPTFLUSH_OFFSET 0x1B4 /* Endpoint de-initialization */ +#define LPC31_USBDEV_ENDPTSTATUS_OFFSET 0x1B8 /* Endpoint status */ +#define LPC31_USBDEV_ENDPTCOMPLETE_OFFSET 0x1BC /* Endpoint complete */ +#define LPC31_USBDEV_ENDPTCTRL0_OFFSET 0x1C0 /* Endpoint control 0 */ +#define LPC31_USBDEV_ENDPTCTRL1_OFFSET 0x1C4 /* Endpoint control 1 */ +#define LPC31_USBDEV_ENDPTCTRL2_OFFSET 0x1C8 /* Endpoint control 2 */ +#define LPC31_USBDEV_ENDPTCTRL3_OFFSET 0x1CC /* Endpoint control 3 */ + +/* USBOTG register (virtual) addresses **********************************************************/ + +/* Device/host capability registers */ + +#define LPC31_USBOTG_CAPLENGTH (LPC31_USBOTG_VBASE+LPC31_USBOTG_CAPLENGTH_OFFSET) +#define LPC31_USBHOST_HCIVERSION (LPC31_USBOTG_VBASE+LPC31_USBHOST_HCIVERSION_OFFSET) +#define LPC31_USBHOST_HCSPARAMS (LPC31_USBOTG_VBASE+LPC31_USBHOST_HCSPARAMS_OFFSET) +#define LPC31_USBHOST_HCCPARAMS (LPC31_USBOTG_VBASE+LPC31_USBHOST_HCCPARAMS_OFFSET) +#define LPC31_USBDEV_DCIVERSION (LPC31_USBOTG_VBASE+LPC31_USBDEV_DCIVERSION_OFFSET) +#define LPC31_USBDEV_DCCPARAMS (LPC31_USBOTG_VBASE+LPC31_USBDEV_DCCPARAMS_OFFSET) + +/* Device/host operational registers */ + +#define LPC31_USBOTG_USBCMD (LPC31_USBOTG_VBASE+LPC31_USBOTG_USBCMD_OFFSET) +#define LPC31_USBOTG_USBSTS (LPC31_USBOTG_VBASE+LPC31_USBOTG_USBSTS_OFFSET) +#define LPC31_USBOTG_USBINTR (LPC31_USBOTG_VBASE+LPC31_USBOTG_USBINTR_OFFSET) +#define LPC31_USBOTG_FRINDEX (LPC31_USBOTG_VBASE+LPC31_USBOTG_FRINDEX_OFFSET) +#define LPC31_USBOTG_PERIODICLIST (LPC31_USBOTG_VBASE+LPC31_USBOTG_PERIODICLIST_OFFSET) +#define LPC31_USBOTG_DEVICEADDR (LPC31_USBOTG_VBASE+LPC31_USBOTG_DEVICEADDR_OFFSET) +#define LPC31_USBOTG_ASYNCLISTADDR (LPC31_USBOTG_VBASE+LPC31_USBOTG_ASYNCLISTADDR_OFFSET) +#define LPC31_USBOTG_ENDPOINTLIST (LPC31_USBOTG_VBASE+LPC31_USBOTG_ENDPOINTLIST_OFFSET) +#define LPC31_USBOTG_TTCTRL (LPC31_USBOTG_VBASE+LPC31_USBOTG_TTCTRL_OFFSET) +#define LPC31_USBOTG_BURSTSIZE (LPC31_USBOTG_VBASE+LPC31_USBOTG_BURSTSIZE_OFFSET) +#define LPC31_USBOTG_TXFILLTUNING (LPC31_USBOTG_VBASE+LPC31_USBOTG_TXFILLTUNING_OFFSET) +#define LPC31_USBOTG_BINTERVAL (LPC31_USBOTG_VBASE+LPC31_USBOTG_BINTERVAL_OFFSET) +#define LPC31_USBOTG_ENDPTNAK (LPC31_USBOTG_VBASE+LPC31_USBOTG_ENDPTNAK_OFFSET) +#define LPC31_USBOTG_ENDPTNAKEN (LPC31_USBOTG_VBASE+LPC31_USBOTG_ENDPTNAKEN_OFFSET) +#define LPC31_USBOTG_PORTSC1 (LPC31_USBOTG_VBASE+LPC31_USBOTG_PORTSC1_OFFSET) +#define LPC31_USBOTG_OTGSC (LPC31_USBOTG_VBASE+LPC31_USBOTG_OTGSC_OFFSET) +#define LPC31_USBOTG_USBMODE (LPC31_USBOTG_VBASE+LPC31_USBOTG_USBMODE_OFFSET) + +#define LPC31_USBDEV_USBCMD (LPC31_USBOTG_VBASE+LPC31_USBDEV_USBCMD_OFFSET) +#define LPC31_USBDEV_USBSTS (LPC31_USBOTG_VBASE+LPC31_USBDEV_USBSTS_OFFSET) +#define LPC31_USBDEV_USBINTR (LPC31_USBOTG_VBASE+LPC31_USBDEV_USBINTR_OFFSET) +#define LPC31_USBDEV_FRINDEX (LPC31_USBOTG_VBASE+LPC31_USBDEV_FRINDEX_OFFSET) +#define LPC31_USBDEV_DEVICEADDR (LPC31_USBOTG_VBASE+LPC31_USBDEV_DEVICEADDR_OFFSET) +#define LPC31_USBDEV_ENDPOINTLIST (LPC31_USBOTG_VBASE+LPC31_USBDEV_ENDPOINTLIST_OFFSET) +#define LPC31_USBDEV_BURSTSIZE (LPC31_USBOTG_VBASE+LPC31_USBDEV_BURSTSIZE_OFFSET) +#define LPC31_USBDEV_BINTERVAL (LPC31_USBOTG_VBASE+LPC31_USBDEV_BINTERVAL_OFFSET) +#define LPC31_USBDEV_ENDPTNAK (LPC31_USBOTG_VBASE+LPC31_USBDEV_ENDPTNAK_OFFSET) +#define LPC31_USBDEV_ENDPTNAKEN (LPC31_USBOTG_VBASE+LPC31_USBDEV_ENDPTNAKEN_OFFSET) +#define LPC31_USBDEV_PORTSC1 (LPC31_USBOTG_VBASE+LPC31_USBDEV_PORTSC1_OFFSET) +#define LPC31_USBDEV_USBMODE (LPC31_USBOTG_VBASE+LPC31_USBDEV_USBMODE_OFFSET) + +#define LPC31_USBHOST_USBCMD (LPC31_USBOTG_VBASE+LPC31_USBHOST_USBCMD_OFFSET) +#define LPC31_USBHOST_USBSTS (LPC31_USBOTG_VBASE+LPC31_USBHOST_USBSTS_OFFSET) +#define LPC31_USBHOST_USBINTR (LPC31_USBOTG_VBASE+LPC31_USBHOST_USBINTR_OFFSET) +#define LPC31_USBHOST_FRINDEX (LPC31_USBOTG_VBASE+LPC31_USBHOST_FRINDEX_OFFSET) +#define LPC31_USBHOST_PERIODICLIST (LPC31_USBOTG_VBASE+LPC31_USBHOST_PERIODICLIST_OFFSET) +#define LPC31_USBHOST_ASYNCLISTADDR (LPC31_USBOTG_VBASE+LPC31_USBHOST_ASYNCLISTADDR_OFFSET) +#define LPC31_USBHOST_TTCTRL (LPC31_USBOTG_VBASE+LPC31_USBHOST_TTCTRL_OFFSET) +#define LPC31_USBHOST_BURSTSIZE (LPC31_USBOTG_VBASE+LPC31_USBHOST_BURSTSIZE_OFFSET) +#define LPC31_USBHOST_TXFILLTUNING (LPC31_USBOTG_VBASE+LPC31_USBHOST_TXFILLTUNING_OFFSET) +#define LPC31_USBHOST_BINTERVAL (LPC31_USBOTG_VBASE+LPC31_USBHOST_BINTERVAL_OFFSET) +#define LPC31_USBHOST_PORTSC1 (LPC31_USBOTG_VBASE+LPC31_USBHOST_PORTSC1_OFFSET) +#define LPC31_USBHOST_USBMODE (LPC31_USBOTG_VBASE+LPC31_USBHOST_USBMODE_OFFSET) + +/* Device endpoint registers */ + +#define LPC31_USBDEV_ENDPTSETUPSTAT (LPC31_USBOTG_VBASE+LPC31_USBDEV_ENDPTSETUPSTAT_OFFSET) +#define LPC31_USBDEV_ENDPTPRIME (LPC31_USBOTG_VBASE+LPC31_USBDEV_ENDPTPRIME_OFFSET) +#define LPC31_USBDEV_ENDPTFLUSH (LPC31_USBOTG_VBASE+LPC31_USBDEV_ENDPTFLUSH_OFFSET) +#define LPC31_USBDEV_ENDPTSTATUS (LPC31_USBOTG_VBASE+LPC31_USBDEV_ENDPTSTATUS_OFFSET) +#define LPC31_USBDEV_ENDPTCOMPLETE (LPC31_USBOTG_VBASE+LPC31_USBDEV_ENDPTCOMPLETE_OFFSET) +#define LPC31_USBDEV_ENDPTCTRL0 (LPC31_USBOTG_VBASE+LPC31_USBDEV_ENDPTCTRL0_OFFSET) +#define LPC31_USBDEV_ENDPTCTRL1 (LPC31_USBOTG_VBASE+LPC31_USBDEV_ENDPTCTRL1_OFFSET) +#define LPC31_USBDEV_ENDPTCTRL2 (LPC31_USBOTG_VBASE+LPC31_USBDEV_ENDPTCTRL2_OFFSET) +#define LPC31_USBDEV_ENDPTCTRL3 (LPC31_USBOTG_VBASE+LPC31_USBDEV_ENDPTCTRL3_OFFSET) + +/* USBOTG register bit definitions **************************************************************/ + +/* Device/host capability registers */ +/* CAPLENGTH (address 0x19000100) */ + +#define USBOTG_CAPLENGTH_SHIFT (0) /* Bits 0-7: Offset from register base to operational regs */ +#define USBOTG_CAPLENGTH_MASK (0xff << USBOTG_CAPLENGTH_SHIFT) + +/* HCIVERSION (address 0x19000102) */ + +#define USBHOST_HCIVERSION_SHIFT (0) /* Bits 0-15: BCD encoding of the EHCI revision number */ +#define USBHOST_HCIVERSION_MASK (0xffff << USBHOST_HCIVERSION_SHIFT) + +/* HCSPARAMS (address 0x19000104) */ + +#define USBHOST_HCSPARAMS_NTT_SHIFT (24) /* Bits 24-27: Number of Transaction Translators */ +#define USBHOST_HCSPARAMS_NTT_MASK (15 << USBHOST_HCSPARAMS_NTT_SHIFT) +#define USBHOST_HCSPARAMS_NPTT_SHIFT (20) /* Bits 20-23: Number of Ports per Transaction Translator */ +#define USBHOST_HCSPARAMS_NPTT_MASK (15 << USBHOST_HCSPARAMS_NPTT_SHIFT) +#define USBHOST_HCSPARAMS_PI (1 >> 16) /* Bit 16: Port indicators */ +#define USBHOST_HCSPARAMS_NCC_SHIFT (15) /* Bits 12-15: Number of Companion Controller */ +#define USBHOST_HCSPARAMS_NCC_MASK (15 << USBHOST_HCSPARAMS_NCC_SHIFT) +#define USBHOST_HCSPARAMS_NPCC_SHIFT (8) /* Bits 8-11: Number of Ports per Companion Controller */ +#define USBHOST_HCSPARAMS_NPCC_MASK (15 << USBHOST_HCSPARAMS_NPCC_SHIFT) +#define USBHOST_HCSPARAMS_PPC (1 >> 4) /* Bit 4: Port Power Control */ +#define USBHOST_HCSPARAMS_NPORTS_SHIF (0) /* Bits 0-3: Number of downstream ports */ +#define USBHOST_HCSPARAMS_NPORTS_MASK (15 << USBHOST_HCSPARAMS_NPORTS_SHIFT) + +/* HCCPARAMS (address 0x19000108) */ + +#define USBHOST_HCCPARAMS_EECP_SHIFT (8) /* Bits 8-15: EHCI Extended Capabilities Pointer */ +#define USBHOST_HCCPARAMS_EECP_MASK (255 << USBHOST_HCCPARAMS_EECP_SHIFT) +#define USBHOST_HCCPARAMS_IST_SHIFT (4) /* Bits 4-7: Isochronous Scheduling Threshold */ +#define USBHOST_HCCPARAMS_IST_MASK (15 << USBHOST_HCCPARAMS_IST_SHIFT) +#define USBHOST_HCCPARAMS_ASP (1 >> 2) /* Bit 2: Asynchronous Schedule Park Capability */ +#define USBHOST_HCCPARAMS_PFL (1 >> 1) /* Bit 1: Programmable Frame List Flag */ +#define USBHOST_HCCPARAMS_ADC (1 >> 0) /* Bit 0: 64-bit Addressing Capability */ + +/* DCIVERSION (address 0x19000120) */ + +#define USBDEV_DCIVERSION_SHIFT (0) /* Bits 0-15: BCD encoding of the device interface */ +#define USBDEV_DCIVERSION_MASK (0xffff << USBDEV_DCIVERSION_SHIFT) + +/* DCCPARAMS (address 0x19000124) */ + +#define USBDEV_DCCPARAMS_HC (1 >> 8) /* Bit 8: Host Capable */ +#define USBDEV_DCCPARAMS_DC (1 >> 7) /* Bit 7: Device Capable */ +#define USBDEV_DCCPARAMS_DEN_SHIFT (0) /* Bits 0-4: DEN Device Endpoint Number */ +#define USBDEV_DCCPARAMS_DEN_MASK (31 << USBDEV_DCCPARAMS_DEN_SHIFT) + +/* Device/host operational registers */ +/* USB Command register USBCMD (address 0x19000140) -- Device Mode */ + +#define USBDEV_USBCMD_ITC_SHIFT (16) /* Bits 16-23: Interrupt threshold control */ +#define USBDEV_USBCMD_ITC_MASK (255 << USBDEV_USBCMD_ITC_SHIFT) +# define USBDEV_USBCMD_ITCIMME (0 << USBDEV_USBCMD_ITC_SHIFT) /* Immediate (no threshold) */ +# define USBDEV_USBCMD_ITC1UF (1 << USBDEV_USBCMD_ITC_SHIFT) /* 1 micro frame */ +# define USBDEV_USBCMD_ITC2UF (2 << USBDEV_USBCMD_ITC_SHIFT) /* 2 micro frames */ +# define USBDEV_USBCMD_ITC4UF (4 << USBDEV_USBCMD_ITC_SHIFT) /* 4 micro frames */ +# define USBDEV_USBCMD_ITC8UF (8 << USBDEV_USBCMD_ITC_SHIFT) /* 8 micro frames */ +# define USBDEV_USBCMD_ITC16UF (16 << USBDEV_USBCMD_ITC_SHIFT) /* 16 micro frames */ +# define USBDEV_USBCMD_ITC32UF (32 << USBDEV_USBCMD_ITC_SHIFT) /* 32 micro frames */ +# define USBDEV_USBCMD_ITC64UF (64 << USBDEV_USBCMD_ITC_SHIFT) /* 64 micro frames */ +#define USBDEV_USBCMD_SUTW (1 << 13) /* Bit 13: Setup trip wire */ +#define USBDEV_USBCMD_ATDTW (1 << 12) /* Bit 12: Add dTD trip wire */ +#define USBDEV_USBCMD_RST (1 << 1) /* Bit 1: 1 Controller reset */ +#define USBDEV_USBCMD_RS (1 << 0) /* Bit 0: 0 Run/Stop */ + +/* USB Command register USBCMD (address 0x19000140) -- Host Mode */ + +#define USBHOST_USBCMD_ITC_SHIFT (16) /* Bits 16-13: Interrupt threshold control */ +#define USBHOST_USBCMD_ITC_MASK (255 << USBHOST_USBCMD_ITC_SHIFT) +# define USBHOST_USBCMD_ITCIMMED (0 << USBHOST_USBCMD_ITC_SHIFT) /* Immediate (no threshold) */ +# define USBHOST_USBCMD_ITC1UF (1 << USBHOST_USBCMD_ITC_SHIFT) /* 1 micro frame */ +# define USBHOST_USBCMD_ITC2UF (2 << USBHOST_USBCMD_ITC_SHIFT) /* 2 micro frames */ +# define USBHOST_USBCMD_ITC4UF (4 << USBHOST_USBCMD_ITC_SHIFT) /* 4 micro frames */ +# define USBHOST_USBCMD_ITC8UF (8 << USBHOST_USBCMD_ITC_SHIFT) /* 8 micro frames */ +# define USBHOST_USBCMD_ITC16UF (16 << USBHOST_USBCMD_ITC_SHIFT) /* 16 micro frames */ +# define USBHOST_USBCMD_ITC32UF (32 << USBHOST_USBCMD_ITC_SHIFT) /* 32 micro frames */ +# define USBHOST_USBCMD_ITC64UF (64 << USBHOST_USBCMD_ITC_SHIFT) /* 64 micro frames */ +#define USBHOST_USBCMD_FS2 (1 << 15) /* Bit 15: Bit 2 of the Frame List Size bits */ +#define USBHOST_USBCMD_ASPE (1 << 11) /* Bit 11: Asynchronous Schedule Park Mode Enable */ +#define USBHOST_USBCMD_ASP_SHIFT (8) /* Bits 8-9: Asynchronous schedule park mode */ +#define USBHOST_USBCMD_ASP_MASK (3 << USBHOST_USBCMD_ASP_SHIFT) +#define USBHOST_USBCMD_IAA (1 << 6) /* Bit 6: Interrupt next asynchronous schedule */ +#define USBHOST_USBCMD_ASE (1 << 5) /* Bit 5: Skips processing asynchronous schedule */ +#define USBHOST_USBCMD_PSE (1 << 4) /* Bit 4: Skips processing periodic schedule */ +#define USBHOST_USBCMD_FS1 (1 << 3) /* Bit 3: Bit 1 of the Frame List Size bits */ +#define USBHOST_USBCMD_FS0 (1 << 2) /* Bit 2: Bit 0 of the Frame List Size bits */ +#define USBHOST_USBCMD_RST (1 << 1) /* Bit 1: Controller reset */ +#define USBHOST_USBCMD_RS (1 << 0) /* Bit 0: Run/Stop */ + +/* USB Status register USBSTS (address 0x19000144) -- Device Mode */ + +#define USBDEV_USBSTS_NAKI (1 << 16) /* Bit 16: NAK interrupt bit */ +#define USBDEV_USBSTS_SLI (1 << 8) /* Bit 8: DCSuspend */ +#define USBDEV_USBSTS_SRI (1 << 7) /* Bit 7: SOF received */ +#define USBDEV_USBSTS_URI (1 << 6) /* Bit 6: USB reset received */ +#define USBDEV_USBSTS_PCI (1 << 2) /* Bit 2: Port change detect */ +#define USBDEV_USBSTS_UEI (1 << 1) /* Bit 1: USB error interrupt */ +#define USBDEV_USBSTS_UI (1 << 0) /* Bit 0: USB interrupt */ + +/* USB Status register USBSTS (address 0x19000144) -- Host Mode */ + +#define USBHOST_USBSTS_UPI (1 << 19) /* Bit 19: USB host periodic interrupt */ +#define USBHOST_USBSTS_UAI (1 << 18) /* Bit 18: USB host asynchronous interrupt */ +#define USBHOST_USBSTS_AS (1 << 15) /* Bit 15: Asynchronous schedule status */ +#define USBHOST_USBSTS_PS (1 << 14) /* Bit 14: Periodic schedule status */ +#define USBHOST_USBSTS_RCL (1 << 13) /* Bit 13: Reclamation */ +#define USBHOST_USBSTS_HCH (1 << 12) /* Bit 12: HCHalted */ +#define USBHOST_USBSTS_SRI (1 << 7) /* Bit 7: SOF received */ +#define USBHOST_USBSTS_AAI (1 << 5) /* Bit 5: Interrupt on async advance */ +#define USBHOST_USBSTS_FRI (1 << 3) /* Bit 3: Frame list roll-over */ +#define USBHOST_USBSTS_PCI (1 << 2) /* Bit 2: Port change detect */ +#define USBHOST_USBSTS_UEI (1 << 1) /* Bit 1: USB error interrupt */ +#define USBHOST_USBSTS_UI (1 << 0) /* Bit 0: USB interrupt */ + +/* USB interrupt register USBINTR (address 0x19000148) -- Device Mode */ + +#define USBDEV_USBINTR_NAKE (1 << 16) /* Bit 16: NAK interrupt enable */ +#define USBDEV_USBINTR_SLE (1 << 8) /* Bit 8: Sleep enable */ +#define USBDEV_USBINTR_SRE (1 << 7) /* Bit 7: SOF received enable */ +#define USBDEV_USBINTR_URE (1 << 6) /* Bit 6: USB reset enable */ +#define USBDEV_USBINTR_PCE (1 << 2) /* Bit 2: Port change detect enable */ +#define USBDEV_USBINTR_UEE (1 << 1) /* Bit 1: USB error interrupt enable */ +#define USBDEV_USBINTR_UE (1 << 0) /* Bit 0: USB interrupt enable */ + +/* USB interrupt register USBINTR (address 0x19000148) -- Host Mode */ + +#define USBHOST_USBINTR_UPIA (1 << 19) /* Bit 19: USB host periodic interrupt enable */ +#define USBHOST_USBINTR_UAIE (1 << 18) /* Bit 18: USB host asynchronous interrupt enable */ +#define USBHOST_USBINTR_SRE (1 << 7) /* Bit 7: SOF timer interrupt enable */ +#define USBHOST_USBINTR_AAE (1 << 5) /* Bit 5: Interrupt on asynchronous advance enable */ +#define USBHOST_USBINTR_FRE (1 << 3) /* Bit 3: Frame list rollover enable */ +#define USBHOST_USBINTR_PCE (1 << 2) /* Bit 2: Port change detect enable */ +#define USBHOST_USBINTR_UEE (1 << 1) /* Bit 1: USB error interrupt enable */ +#define USBHOST_USBINTR_UE (1 << 0) /* Bit 0: USB interrupt enable */ + +/* Frame index register FRINDEX (address 0x1900014c) -- Device Mode */ + +#define USBDEV_FRINDEX_LFN_SHIFT (3) /* Bits 3-13: Frame number of last frame transmitted */ +#define USBDEV_FRINDEX_LFN_MASK (0x7ff << USBDEV_FRINDEX_LFN_SHIFT) +#define USBDEV_FRINDEX_CUFN_SHIFT (0) /* Bits 0-2: Current micro frame number */ +#define USBDEV_FRINDEX_CUFN_MASK (7 << USBDEV_FRINDEX_CUFN_SHIFT) + +/* Frame index register FRINDEX (address 0x1900014c) -- Host Mode */ + +#define USBHOST_FRINDEX_FLI_SHIFT (3) /* Bits 3-(n+2): Frame list current index */ +#define USBHOST_FRINDEX_FLI_MASK(n) (0x7ff << ((n)+USBHOST_FRINDEX_FLI_SHIFT-1) +#define USBHOST_FRINDEX_CUFN_SHIFT (0) /* Bits 0-2: Current micro frame number */ +#define USBHOST_FRINDEX_CUFN_MASK (7 << USBHOST_FRINDEX_CUFN_SHIFT) + +/* USB Device Address register DEVICEADDR (address 0x19000154) -- Device Mode */ + +#define USBDEV_DEVICEADDR_SHIFT (25) /* Bits 25-31: USBADR USB device address */ +#define USBDEV_DEVICEADDR_MASK (0x3c << USBDEV_DEVICEADDR_SHIFT) +#define USBDEV_DEVICEADDR_USBADRA (1 << 24) /* Bit 24: Device address advance */ + +/* USB Periodic List Base register PERIODICLIST (address 0x19000154) -- Host Mode */ + +#define USBHOST_PERIODICLIST_PERBASE_SHIFT (12) /* Bits 12-31: Base Address (Low) */ +#define USBHOST_PERIODICLIST_PERBASE_MASK (0x000fffff << USBHOST_PERIODICLIST_PERBASE_SHIFT) + +/* USB Endpoint List Address register ENDPOINTLISTADDR (address 0x19000158) -- Device Mode */ + +#define USBDEV_ENDPOINTLIST_EPBASE_SHIFT (11) /* Bits 11-31: Endpoint list pointer (low) */ +#define USBDEV_ENDPOINTLIST_EPBASE_MASK (0x001fffff << USBDEV_ENDPOINTLIST_EPBASE_SHIFT) + +/* USB Asynchronous List Address register ASYNCLISTADDR- (address 0x19000158) -- Host Mode */ + +#define USBHOST_ASYNCLISTADDR_ASYBASE_SHIFT (5) /* Bits 5-31: Link pointer (Low) LPL */ +#define USBHOST_ASYNCLISTADDR_ASYBASE_MASK (0x07ffffff << USBHOST_ASYNCLISTADDR_ASYBASE_SHIFT) + +/* USB TT Control register TTCTRL (address 0x1900015c) -- Host Mode */ + +#define USBHOST_TTCTRL_TTHA_SHIFT (24) /* Bits 24-30: Hub address */ +#define USBHOST_TTCTRL_TTHA_MASK (0x7f << USBHOST_TTCTRL_TTHA_SHIFT) + +/* USB burst size register BURSTSIZE (address 0x19000160) -- Device/Host Mode */ + +#define USBDEV_BURSTSIZE_TXPBURST_SHIFT (8) /* Bits 8-15: Programmable TX burst length */ +#define USBDEV_BURSTSIZE_TXPBURST_MASK (255 << USBDEV_BURSTSIZE_TXPBURST_SHIFT) +#define USBDEV_BURSTSIZE_RXPBURST_SHIFT (0) /* Bits 0-7: RXPBURST Programmable RX burst length */ +#define USBDEV_BURSTSIZE_RXPBURST_MASK (255 << USBDEV_BURSTSIZE_RXPBURST_SHIFT) + +#define USBHOST_BURSTSIZE_TXPBURST_SHIFT (8) /* Bits 8-15: Programmable TX burst length */ +#define USBHOST_BURSTSIZE_TXPBURST_MASK (255 << USBHOST_BURSTSIZE_TXPBURST_SHIFT) +#define USBHOST_BURSTSIZE_RXPBURST_SHIFT (0) /* Bits 0-7: RXPBURST Programmable RX burst length */ +#define USBHOST_BURSTSIZE_RXPBURST_MASK (255 << USBHOST_BURSTSIZE_RXPBURST_SHIFT) + +/* USB Transfer buffer Fill Tuning register TXFIFOFILLTUNING (address 0x19000164) -- Host Mode */ + +#define USBHOST_TXFILLTUNING_FIFOTHRES_SHIFT (16) /* Bits 16-21: Scheduler overhead */ +#define USBHOST_TXFILLTUNING_FIFOTHRES_MASK (0x3c << USBHOST_TXFILLTUNING_FIFOTHRES_SHIFT) +#define USBHOST_TXFILLTUNING_SCHEATLTH_SHIFT (8) /* Bits 8-12: Scheduler health counter */ +#define USBHOST_TXFILLTUNING_SCHEATLTH_MASK (0x1f << USBHOST_TXFILLTUNING_SCHEATLTH_SHIFT) +#define USBHOST_TXFILLTUNING_SCHOH_SHIFT (0) /* Bits 0-7: FIFO burst threshold */ +#define USBHOST_TXFILLTUNING_SCHOH_MASK (0xff << USBHOST_TXFILLTUNING_SCHOH_SHIFT) + +/* USB BINTERVAL register BINTERVAL (address 0x19000174) -- Device/Host Mode */ + +#define USBDEV_BINTERVAL_SHIFT (0) /* Bits 0-3: bInterval value */ +#define USBDEV_BINTERVAL_MASK (15 << USBDEV_BINTERVAL_SHIFT) + +#define USBHOST_BINTERVAL_SHIFT (0) /* Bits 0-3: bInterval value */ +#define USBHOST_BINTERVAL_MASK (15 << USBHOST_BINTERVAL_SHIFT) + +/* USB endpoint NAK register ENDPTNAK (address 0x19000178) -- Device Mode */ + +#define USBDEV_ENDPTNAK_EPTN_SHIFT (16) /* Bits 16-19: Tx endpoint NAK */ +#define USBDEV_ENDPTNAK_EPTN_MASK (15 << USBDEV_ENDPTNAK_EPTN_SHIFT) +#define USBDEV_ENDPTNAK_EPRN_SHIFT (0) /* Bits 0-3: Rx endpoint NAK */ +#define USBDEV_ENDPTNAK_EPRN_MASK (15 << USBDEV_ENDPTNAK_EPRN_SHIFT) + +/* USB Endpoint NAK Enable register ENDPTNAKEN (address 0x1900017c) -- Device Mode */ + +#define USBDEV_ENDPTNAK_EPTNE_SHIFT (16) /* Bits 16-19: Tx endpoint NAK enable */ +#define USBDEV_ENDPTNAK_EPTNE_MASK (15 << USBDEV_ENDPTNAK_EPTNE_SHIFT) +#define USBDEV_ENDPTNAK_EPRNE_SHIFT (0) /* Bits 0-3: Rx endpoint NAK enable */ +#define USBDEV_ENDPTNAK_EPRNE_MASK (15 << USBDEV_ENDPTNAK_EPRNE_SHIFT) + +/* Port Status and Control register PRTSC1 (address 0x19000184) -- Device Mode */ + +#define USBDEV_PRTSC1_PSPD_SHIFT (26) /* Bits 26-27: Port speed */ +# define USBDEV_PRTSC1_PSPD_MASK (3 << USBDEV_PRTSC1_PSPD_SHIFT) +# define USBDEV_PRTSC1_PSPD_FS (0 << USBDEV_PRTSC1_PSPD_SHIFT) /* Full-speed */ +# define USBDEV_PRTSC1_PSPD_HS (2 << USBDEV_PRTSC1_PSPD_SHIFT) /* High-speed */ +# define USBDEV_PRTSC1_PFSC (1 << 24) /* Bit 24: Port force full speed connect */ +#define USBDEV_PRTSC1_PHCD (1 << 23) /* Bit 23: PHY low power suspend - clock disable (PLPSCD) */ +#define USBDEV_PRTSC1_PTC_SHIFT (16) /* Bits 16-19: 19: Port test control */ +#define USBDEV_PRTSC1_PTC_MASK (15 << USBDEV_PRTSC1_PTC_SHIFT) +# define USBDEV_PRTSC1_PTC_DISABLE (0 << USBDEV_PRTSC1_PTC_SHIFT) /* TEST_MODE_DISABLE */ +# define USBDEV_PRTSC1_PTC_JSTATE (1 << USBDEV_PRTSC1_PTC_SHIFT) /* J_STATE */ +# define USBDEV_PRTSC1_PTC_KSTATE (2 << USBDEV_PRTSC1_PTC_SHIFT) /* K_STATE */ +# define USBDEV_PRTSC1_PTC_SE0 (3 << USBDEV_PRTSC1_PTC_SHIFT) /* SE0 (host)/NAK (device) */ +# define USBDEV_PRTSC1_PTC_PACKET (4 << USBDEV_PRTSC1_PTC_SHIFT) /* Packet */ +# define USBDEV_PRTSC1_PTC_HS (5 << USBDEV_PRTSC1_PTC_SHIFT) /* FORCE_ENABLE_HS */ +# define USBDEV_PRTSC1_PTC_FS (6 << USBDEV_PRTSC1_PTC_SHIFT) /* FORCE_ENABLE_FS */ +#define USBDEV_PRTSC1_PIC_SHIFT (14) /* Bits 14-15: Port indicator control */ +#define USBDEV_PRTSC1_PIC_MASK (3 << USBDEV_PRTSC1_PIC_SHIFT) +# define USBDEV_PRTSC1_PIC_OFF (0 << USBDEV_PRTSC1_PIC_SHIFT) /* 00 Port indicators are off */ +# define USBDEV_PRTSC1_PIC_AMBER (1 << USBDEV_PRTSC1_PIC_SHIFT) /* 01 amber */ +# define USBDEV_PRTSC1_PIC_GREEN (2 << USBDEV_PRTSC1_PIC_SHIFT) /* 10 green */ +#define USBDEV_PRTSC1_HSP (1 << 9) /* Bit 9: High-speed status */ +#define USBDEV_PRTSC1_PR (1 << 8) /* Bit 8: Port reset */ +#define USBDEV_PRTSC1_SUSP (1 << 7) /* Bit 7: Suspend */ +#define USBDEV_PRTSC1_FPR (1 << 6) /* Bit 6: Force port resume */ +#define USBDEV_PRTSC1_PEC (1 << 3) /* Bit 3: Port enable/disable change */ +#define USBDEV_PRTSC1_PE (1 << 2) /* Bit 2: Port enable */ +#define USBDEV_PRTSC1_CCS (1 << 0) /* Bit 0: Current connect status */ + +/* Port Status and Control register PRTSC1 (address 0x19000184) -- Host Mode */ + +#define USBHOST_PRTSC1_PSPD_SHIFT (26) /* Bits 26-27: Port speed */ +#define USBHOST_PRTSC1_PSPD_MASK (3 << USBHOST_PRTSC1_PSPD_SHIFT) +# define USBHOST_PRTSC1_PSPD_FS (0 << USBHOST_PRTSC1_PSPD_SHIFT) /* Full-speed */ +# define USBHOST_PRTSC1_PSPD_LS (1 << USBHOST_PRTSC1_PSPD_SHIFT) /* Low-speed */ +# define USBHOST_PRTSC1_PSPD_HS (2 << USBHOST_PRTSC1_PSPD_SHIFT) /* High-speed */ +#define USBHOST_PRTSC1_PFSC (1 << 24) /* Bit 24: Port force full speed connect */ +#define USBHOST_PRTSC1_PHCD (1 << 23) /* Bit 23: PHY low power suspend - clock disable (PLPSCD) */ +#define USBHOST_PRTSC1_WKOC (1 << 22) /* Bit 22: Wake on over-current enable (WKOC_E) */ +#define USBHOST_PRTSC1_WKDC (1 << 21) /* Bit 21: Wake on disconnect enable (WKDSCNNT_E) */ +#define USBHOST_PRTSC1_WKCN (1 << 20) /* Bit 20: Wake on connect enable (WKCNNT_E) */ +#define USBHOST_PRTSC1_PTC_SHIFT (16) /* Bits 16-19: Port test control */ +#define USBHOST_PRTSC1_PTC_MASK (15 << USBHOST_PRTSC1_PTC_SHIFT) +# define USBHOST_PRTSC1_PTC_DISABLE (0 << USBHOST_PRTSC1_PTC_SHIFT) /* 0000 TEST_MODE_DISABLE */ +# define USBHOST_PRTSC1_PTC_JSTATE (1 << USBHOST_PRTSC1_PTC_SHIFT) /* 0001 J_STATE */ +# define USBHOST_PRTSC1_PTC_KSTATE (2 << USBHOST_PRTSC1_PTC_SHIFT) /* 0010 K_STATE */ +# define USBHOST_PRTSC1_PTC_SE0 (3 << USBHOST_PRTSC1_PTC_SHIFT) /* 0011 SE0 (host)/NAK (device) */ +# define USBHOST_PRTSC1_PTC_PACKET (4 << USBHOST_PRTSC1_PTC_SHIFT) /* 0100 Packet */ +# define USBHOST_PRTSC1_PTC_HS (5 << USBHOST_PRTSC1_PTC_SHIFT) /* 0101 FORCE_ENABLE_HS */ +# define USBHOST_PRTSC1_PTC_FS (6 << USBHOST_PRTSC1_PTC_SHIFT) /* 0110 FORCE_ENABLE_FS */ +# define USBHOST_PRTSC1_PTC_LS (7 << USBHOST_PRTSC1_PTC_SHIFT) /* 0111 FORCE_ENABLE_LS */ +#define USBHOST_PRTSC1_PIC_SHIFT (14) /* Bits 14-15: Port indicator control */ +#define USBHOST_PRTSC1_PIC_MASK (3 << USBHOST_PRTSC1_PIC_SHIFT) +# define USBHOST_PRTSC1_PIC_OFF (0 << USBHOST_PRTSC1_PIC_SHIFT) /* 00 Port indicators are off */ +# define USBHOST_PRTSC1_PIC_AMBER (1 << USBHOST_PRTSC1_PIC_SHIFT) /* 01 Amber */ +# define USBHOST_PRTSC1_PIC_GREEN (2 << USBHOST_PRTSC1_PIC_SHIFT) /* 10 Green */ +#define USBHOST_PRTSC1_PP (1 << 12) /* Bit 12: Port power control */ +#define USBHOST_PRTSC1_LS_SHIFT (10) /* Bits 10-11: Line status */ +#define USBHOST_PRTSC1_LS_MASK (3 << USBHOST_PRTSC1_LS_SHIFT) +# define USBHOST_PRTSC1_LS_SE0 (0 << USBHOST_PRTSC1_LS_SHIFT) /* SE0 (USB_DP and USB_DM LOW) */ +# define USBHOST_PRTSC1_LS_JSTATE (2 << USBHOST_PRTSC1_LS_SHIFT) /* J-state (USB_DP HIGH and USB_DM LOW) */ +# define USBHOST_PRTSC1_LS_KSTATE (1 << USBHOST_PRTSC1_LS_SHIFT) /* K-state (USB_DP LOW and USB_DM HIGH) */ +#define USBHOST_PRTSC1_HSP (1 << 9) /* Bit 9: High-speed status */ +#define USBHOST_PRTSC1_PR (1 << 8) /* Bit 8: Port reset */ +#define USBHOST_PRTSC1_SUSP (1 << 7) /* Bit 7: Suspend */ +#define USBHOST_PRTSC1_FPR (1 << 6) /* Bit 6: Force port resume */ +#define USBHOST_PRTSC1_OCC (1 << 5) /* Bit 5: Over-current change */ +#define USBHOST_PRTSC1_OCA (1 << 4) /* Bit 4: Over-current active */ +#define USBHOST_PRTSC1_PEC (1 << 3) /* Bit 3: Port disable/enable change */ +#define USBHOST_PRTSC1_PE (1 << 2) /* Bit 2: Port enable */ +#define USBHOST_PRTSC1_CSC (1 << 1) /* Bit 1: Connect status change */ +#define USBHOST_PRTSC1_CCS (1 << 0) /* Bit 0: Current connect status */ + +/* OTG Status and Control register (OTGSC - address 0x190001a4) */ + +/* OTG interrupt enable */ + +#define USBOTG_OTGSC_DPIE (1 << 30) /* Bit 30: Data pulse interrupt enable */ +#define USBOTG_OTGSC_1MSE (1 << 29) /* Bit 29: 1 millisecond timer interrupt enable */ +#define USBOTG_OTGSC_BSEIE (1 << 28) /* Bit 28: B-session end interrupt enable */ +#define USBOTG_OTGSC_BSVIE (1 << 27) /* Bit 27: B-session valid interrupt enable */ +#define USBOTG_OTGSC_ASVIE (1 << 26) /* Bit 26: A-session valid interrupt enable */ +#define USBOTG_OTGSC_AVVIE (1 << 25) /* Bit 25: A-VBUS valid interrupt enable */ +#define USBOTG_OTGSC_IDIE (1 << 24) /* Bit 24: USB ID interrupt enable */ + +/* OTG interrupt status */ + +#define USBOTG_OTGSC_DPIS (1 << 22) /* Bit 22: Data pulse interrupt status */ +#define USBOTG_OTGSC_1MSS (1 << 21) /* Bit 21: 1 millisecond timer interrupt status */ +#define USBOTG_OTGSC_BSEIS (1 << 20) /* Bit 20: B-Session end interrupt status */ +#define USBOTG_OTGSC_BSVIS (1 << 19) /* Bit 19: B-Session valid interrupt status */ +#define USBOTG_OTGSC_ASVIS (1 << 18) /* Bit 18: A-Session valid interrupt status */ +#define USBOTG_OTGSC_AVVIS (1 << 17) /* Bit 17: A-VBUS valid interrupt status */ +#define USBOTG_OTGSC_IDIS (1 << 16) /* Bit 16: USB ID interrupt status */ + +/* OTG status inputs */ + +#define USBOTG_OTGSC_DPS (1 << 14) /* Bit 14: Data bus pulsing status */ +#define USBOTG_OTGSC_1MST (1 << 13) /* Bit 13: 1 millisecond timer toggle */ +#define USBOTG_OTGSC_BSE (1 << 12) /* Bit 12: B-session end */ +#define USBOTG_OTGSC_BSV (1 << 11) /* Bit 11: B-session valid */ +#define USBOTG_OTGSC_ASV (1 << 10) /* Bit 10: A-session valid */ +#define USBOTG_OTGSC_AVV (1 << 9) /* Bit 9: A-VBUS valid */ +#define USBOTG_OTGSC_ID (1 << 8) /* Bit 8: USB ID */ + +/* OTG controls */ + +#define USBOTG_OTGSC_HABA (1 << 7) /* Bit 7: Hardware assist B-disconnect to A-connect */ +#define USBOTG_OTGSC_HADP (1 << 6) /* Bit 6: Hardware assist data pulse */ +#define USBOTG_OTGSC_IDPU (1 << 5) /* Bit 5: ID pull-up */ +#define USBOTG_OTGSC_DP (1 << 4) /* Bit 4: Data pulsing */ +#define USBOTG_OTGSC_OT (1 << 3) /* Bit 3: OTG termination */ +#define USBOTG_OTGSC_HAAR (1 << 2) /* Bit 2: Hardware assist auto_reset */ +#define USBOTG_OTGSC_VC (1 << 1) /* Bit 1: VBUS_Charge */ +#define USBOTG_OTGSC_VD (1 << 0) /* Bit 0: VBUS_Discharge */ + +/* USB Mode register USBMODE (address 0x190001a8) -- Device Mode */ + +#define USBDEV_USBMODE_SDIS (1 << 4) /* Bit 4: Stream disable mode */ +#define USBDEV_USBMODE_SLOM (1 << 3) /* Bit 3: Setup Lockout mode */ +#define USBDEV_USBMODE_ES (1 << 2) /* Bit 2: Endian select */ +#define USBDEV_USBMODE_CM_SHIFT (0) /* Bits 0-1: Controller mode */ +#define USBDEV_USBMODE_CM_MASK (3 << USBDEV_USBMODE_CM_SHIFT) +# define USBDEV_USBMODE_CMIDLE (0 << USBDEV_USBMODE_CM_SHIFT) /* Idle */ +# define USBDEV_USBMODE_CMDEVICE (2 << USBDEV_USBMODE_CM_SHIFT) /* Device controller */ +# define USBDEV_USBMODE_CMHOST (3 << USBDEV_USBMODE_CM_SHIFT) /* Host controller */ + +/* USB Mode register USBMODE (address 0x190001a8) -- Device Mode */ + +#define USBHOST_USBMODE_VBPS (1 << 5) /* Bit 5: VBUS power select */ +#define USBHOST_USBMODE_SDIS (1 << 4) /* Bit 4: Stream disable mode */ +#define USBHOST_USBMODE_ES (1 << 2) /* Bit 2: Endian select */ +#define USBHOST_USBMODE_CM_SHIFT (0) /* Bits 0-1: Controller mode */ +#define USBHOST_USBMODE_CM_MASK (3 << USBHOST_USBMODE_CM_SHIFT) +# define USBHOST_USBMODE_CMIDLE (0 << USBHOST_USBMODE_CM_SHIFT) /* Idle */ +# define USBHOST_USBMODE_CMDEVICE (2 << USBHOST_USBMODE_CM_SHIFT) /* Device controller */ +# define USBHOST_USBMODE_CMHOST (3 << USBHOST_USBMODE_CM_SHIFT) /* Host controller */ + +/* Device endpoint registers */ + +/* USB Endpoint Setup Status register ENDPTSETUPSTAT (address 0x190001ac) */ + +#define USBDEV_ENDPTSETSTAT_STAT3 (1 << 3) /* Bit 3: Setup EP status for logical EP 3 */ +#define USBDEV_ENDPTSETSTAT_STAT2 (1 << 2) /* Bit 2: Setup EP status for logical EP 2 */ +#define USBDEV_ENDPTSETSTAT_STAT1 (1 << 1) /* Bit 1: Setup EP status for logical EP 1 */ +#define USBDEV_ENDPTSETSTAT_STAT0 (1 << 0) /* Bit 0: Setup EP status for logical EP 0 */ + +/* USB Endpoint Prime register ENDPTPRIME (address 0x190001b0) */ + +#define USBDEV_ENDPTPRIM_PETB3 (1 << 19) /* Bit 19: Prime EP xmt buffer for physical IN EP 3 */ +#define USBDEV_ENDPTPRIM_PETB2 (1 << 18) /* Bit 18: Prime EP xmt buffer for physical IN EP 2 */ +#define USBDEV_ENDPTPRIM_PETB1 (1 << 17) /* Bit 17: Prime EP xmt buffer for physical IN EP 1 */ +#define USBDEV_ENDPTPRIM_PETB0 (1 << 16) /* Bit 16: Prime EP xmt buffer for physical IN EP 0 */ +#define USBDEV_ENDPTPRIM_PERB3 (1 << 3) /* Bit 3: Prime EP recv buffer for physical OUT EP 3 */ +#define USBDEV_ENDPTPRIM_PERB2 (1 << 2) /* Bit 2: Prime EP recv buffer for physical OUT EP 2 */ +#define USBDEV_ENDPTPRIM_PERB1 (1 << 1) /* Bit 1: Prime EP recv buffer for physical OUT EP 1 */ +#define USBDEV_ENDPTPRIM_PERB0 (1 << 0) /* Bit 0: Prime EP recv buffer for physical OUT EP 0 */ + +/* USB Endpoint Flush register ENDPTFLUSH(address 0x190001b4) */ + +#define USBDEV_ENDPTFLUSH_FETB3 (1 << 19) /* Bit 19: Flush EP xmt buffer for physical IN EP 3 */ +#define USBDEV_ENDPTFLUSH_FETB2 (1 << 18) /* Bit 18: Flush EP xmt buffer for physical IN EP 2 */ +#define USBDEV_ENDPTFLUSH_FETB1 (1 << 17) /* Bit 17: Flush EP xmt buffer for physical IN EP 1 */ +#define USBDEV_ENDPTFLUSH_FETB0 (1 << 16) /* Bit 16: Flush EP xmt buffer for physical IN EP 0 */ +#define USBDEV_ENDPTFLUSH_FERB3 (1 << 3) /* Bit 3: Flush EP recv buffer for physical OUT EP 3 */ +#define USBDEV_ENDPTFLUSH_FERB2 (1 << 2) /* Bit 2: Flush EP recv buffer for physical OUT EP 2 */ +#define USBDEV_ENDPTFLUSH_FERB1 (1 << 1) /* Bit 1: Flush EP recv buffer for physical OUT EP 1 */ +#define USBDEV_ENDPTFLUSH_FERB0 (1 << 0) /* Bit 0: Flush EP recv buffer for physical OUT EP 0 */ + +/* USB Endpoint Status register ENDPTSTATUS (address 0x190001b8) */ + +#define USBDEV_ENDPTSTATUS_ETBR3 (1 << 19) /* Bit 19: EP xmt buffer ready for physical IN EP 3 */ +#define USBDEV_ENDPTSTATUS_ETBR2 (1 << 18) /* Bit 18: EP xmt buffer ready for physical IN EP 2 */ +#define USBDEV_ENDPTSTATUS_ETBR1 (1 << 17) /* Bit 17: EP xmt buffer ready for physical IN EP 1 */ +#define USBDEV_ENDPTSTATUS_ETBR0 (1 << 16) /* Bit 16: EP xmt buffer ready for physical IN EP 0 */ +#define USBDEV_ENDPTSTATUS_ERBR3 (1 << 3) /* Bit 3: EP recv buffer ready for physical OUT EP 3 */ +#define USBDEV_ENDPTSTATUS_ERBR2 (1 << 2) /* Bit 2: EP recv buffer ready for physical OUT EP 2 */ +#define USBDEV_ENDPTSTATUS_ERBR1 (1 << 1) /* Bit 1: EP recv buffer ready for physical OUT EP 1 */ +#define USBDEV_ENDPTSTATUS_ERBR0 (1 << 0) /* Bit 0: EP recv buffer ready for physical OUT EP 0 */ + +/* USB Endpoint Complete register ENDPTCOMPLETE (address 0x190001bc) */ + +#define USBDEV_ENDPTCOMPLETE_ETCE3 (1 << 19) /* Bit 19: EP xmt complete event for physical IN EP 3 */ +#define USBDEV_ENDPTCOMPLETE_ETCE2 (1 << 18) /* Bit 18: EP xmt complete event for physical IN EP 2 */ +#define USBDEV_ENDPTCOMPLETE_ETCE1 (1 << 17) /* Bit 17: EP xmt complete event for physical IN EP 1 */ +#define USBDEV_ENDPTCOMPLETE_ETCE0 (1 << 16) /* Bit 16: EP xmt complete event for physical IN EP 0 */ +#define USBDEV_ENDPTCOMPLETE_ERCE3 (1 << 3) /* Bit 3: EP recv complete event for physical OUT EP 3 */ +#define USBDEV_ENDPTCOMPLETE_ERCE2 (1 << 2) /* Bit 2: EP recv complete event for physical OUT EP 2 */ +#define USBDEV_ENDPTCOMPLETE_ERCE1 (1 << 1) /* Bit 1: EP recv complete event for physical OUT EP 1 */ +#define USBDEV_ENDPTCOMPLETE_ERCE0 (1 << 0) /* Bit 0: EP recv complete event for physical OUT EP 0 */ + +/* USB Endpoint 0 Control register ENDPTCTRL0 (address 0x190001c0) */ + +#define USBDEV_ENDPTCTRL0_TXE (1 << 23) /* Bit 23: Tx endpoint enable */ +#define USBDEV_ENDPTCTRL0_TXT_SHIFT (18) /* Bits 18-19: Tx endpoint type */ +#define USBDEV_ENDPTCTRL0_TXT_MASK (3 << USBDEV_ENDPTCTRL0_TXT_SHIFT) +# define USBDEV_ENDPTCTRL0_TXT_CTRL (0 << USBDEV_ENDPTCTRL0_TXT_SHIFT) /* Control */ +#define USBDEV_ENDPTCTRL0_TXS (1 << 16) /* Bit 16: Tx endpoint stall */ +#define USBDEV_ENDPTCTRL0_RXE (1 << 7) /* Bit 7: Rx endpoint enable */ +#define USBDEV_ENDPTCTRL0_RXT_SHIFT (2) /* Bits 2-3: Endpoint type */ +#define USBDEV_ENDPTCTR0L_RXT_MASK (3 << USBDEV_ENDPTCTRL0_RXT_SHIFT) +# define USBDEV_ENDPTCTRL0_RXT_CTRL (0 << USBDEV_ENDPTCTRL0_RXT_SHIFT) /* Control */ +#define USBDEV_ENDPTCTRL0_RXS (1 << 0) /* Bit 0: Rx endpoint stall */ + +/* USB Endpoint 1-3 control registers ENDPTCTRL1-ENDPPTCTRL3 (address 0x190001c4-0x190001cc) */ + +#define USBDEV_ENDPTCTRL_TXE (1 << 23) /* Bit 23: Tx endpoint enable */ +#define USBDEV_ENDPTCTRL_TXR (1 << 22) /* Bit 22: Tx data toggle reset */ +#define USBDEV_ENDPTCTRL_TXI (1 << 21) /* Bit 21: Tx data toggle inhibit */ +#define USBDEV_ENDPTCTRL_TXT_SHIFT (18) /* Bits 18-19: Tx endpoint type */ +#define USBDEV_ENDPTCTRL_TXT_MASK (3 << USBDEV_ENDPTCTRL_TXT_SHIFT) +# define USBDEV_ENDPTCTRL_TXT_CTRL (0 << USBDEV_ENDPTCTRL_TXT_SHIFT) /* Control */ +# define USBDEV_ENDPTCTRL_TXT_ISOC (1 << USBDEV_ENDPTCTRL_TXT_SHIFT) /* Isochronous */ +# define USBDEV_ENDPTCTRL_TXT_BULK (2 << USBDEV_ENDPTCTRL_TXT_SHIFT) /* Bulk */ +# define USBDEV_ENDPTCTRL_TXT_INTR (3 << USBDEV_ENDPTCTRL_TXT_SHIFT) /* Interrupt */ +#define USBDEV_ENDPTCTRL_TXS (1 << 16) /* Bit 16: Tx endpoint stall */ +#define USBDEV_ENDPTCTRL_RXE (1 << 7) /* Bit 7: Rx endpoint enable */ +#define USBDEV_ENDPTCTRL_RXR (1 << 6) /* Bit 6: Rx data toggle reset */ +#define USBDEV_ENDPTCTRL_RXI (1 << 5) /* Bit 5: Rx data toggle inhibit */ +#define USBDEV_ENDPTCTRL_RXT_SHIFT (2) /* Bits 2-3: Endpoint type */ +#define USBDEV_ENDPTCTRL_RXT_MASK (3 << USBDEV_ENDPTCTRL_RXT_SHIFT) +# define USBDEV_ENDPTCTRL_RXT_CTRL (0 << USBDEV_ENDPTCTRL_RXT_SHIFT) /* Control */ +# define USBDEV_ENDPTCTRL_RXT_ISOC (1 << USBDEV_ENDPTCTRL_RXT_SHIFT) /* Isochronous */ +# define USBDEV_ENDPTCTRL_RXT_BULK (2 << USBDEV_ENDPTCTRL_RXT_SHIFT) /* Bulk */ +#define USBDEV_ENDPTCTRL_RXS (1 << 0) /* Bit 0: Rx endpoint stall */ + +/************************************************************************************************ + * Public Types + ************************************************************************************************/ + +/************************************************************************************************ + * Public Data + ************************************************************************************************/ + +/************************************************************************************************ + * Public Functions + ************************************************************************************************/ + +#endif /* __ARCH_ARM_SRC_LPC31XX_LPC31_USBOTG_H */ diff --git a/nuttx/arch/arm/src/lpc31xx/lpc31_wdt.h b/nuttx/arch/arm/src/lpc31xx/lpc31_wdt.h new file mode 100755 index 000000000..ac063472d --- /dev/null +++ b/nuttx/arch/arm/src/lpc31xx/lpc31_wdt.h @@ -0,0 +1,130 @@ +/************************************************************************************************ + * arch/arm/src/lpc31xx/lpc31_wdt.h + * + * Copyright (C) 2009-2010 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * 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_LPC31XX_LPC31_WDT_H +#define __ARCH_ARM_SRC_LPC31XX_LPC31_WDT_H + +/************************************************************************************************ + * Included Files + ************************************************************************************************/ + +#include +#include "lpc31_memorymap.h" + +/************************************************************************************************ + * Pre-processor Definitions + ************************************************************************************************/ + +/* WDT register base address offset into the APB0 domain ****************************************/ + +#define LPC31_WDT_VBASE (LPC31_APB0_VADDR+LPC31_APB0_WDT_OFFSET) +#define LPC31_WDT_PBASE (LPC31_APB0_PADDR+LPC31_APB0_WDT_OFFSET) + +/* WDT register offsets (with respect to the WDT base) ******************************************/ + +#define LPC31_WDT_IR_OFFSET 0x000 /* Interrupt Register */ +#define LPC31_WDT_TCR_OFFSET 0x004 /* Timer Control Register */ +#define LPC31_WDT_TC_OFFSET 0x008 /* Timer Counter */ +#define LPC31_WDT_PR_OFFSET 0x00c /* Timer Prescale Register */ +#define LPC31_WDT_PC_OFFSET 0x010 /* Prescale Counter */ +#define LPC31_WDT_MCR_OFFSET 0x014 /* Match Control Register */ +#define LPC31_WDT_MR0_OFFSET 0x018 /* Match Register 0 */ +#define LPC31_WDT_MR1_OFFSET 0x01c /* Match Register 1 */ + /* 0x020-0x038: Reserved */ +#define LPC31_WDT_EMR_OFFSET 0x03c /* External Match Register */ + +/* WDT register (virtual) addresses *************************************************************/ + +#define LPC31_WDT_IR (LPC31_WDT_VBASE+LPC31_WDT_IR_OFFSET) +#define LPC31_WDT_TCR (LPC31_WDT_VBASE+LPC31_WDT_TCR_OFFSET) +#define LPC31_WDT_TC (LPC31_WDT_VBASE+LPC31_WDT_TC_OFFSET) +#define LPC31_WDT_PR (LPC31_WDT_VBASE+LPC31_WDT_PR_OFFSET) +#define LPC31_WDT_PC (LPC31_WDT_VBASE+LPC31_WDT_PC_OFFSET) +#define LPC31_WDT_MCR (LPC31_WDT_VBASE+LPC31_WDT_MCR_OFFSET) +#define LPC31_WDT_MR0 (LPC31_WDT_VBASE+LPC31_WDT_MR0_OFFSET) +#define LPC31_WDT_MR1 (LPC31_WDT_VBASE+LPC31_WDT_MR1_OFFSET) +#define LPC31_WDT_EMR (LPC31_WDT_VBASE+LPC31_WDT_EMR_OFFSET) + +/* WDT register bit definitions *****************************************************************/ + +/* Interrupt Register (IR), address 0x13002400 */ + +#define WDT_IR_INTRM1 (1 << 1) /* Bit 1: MR1 and TC match interrupt */ +#define WDT_IR_INTRM0 (1 << 0) /* Bit 0: MR0 and TC match interrupt */ + +/* Timer Control Register (TCR), address 0x13002404 */ + +#define WDT_TCR_RESET (1 << 1) /* Bit 1: Reset on the next WDOG_PCLK */ +#define WDT_TCR_ENABLE (1 << 0) /* Bit 0: Enable */ + +/* Match Control Register (MCR), address 0x1300 2414 */ + +#define WDT_MCR_MR1STOP (1 << 5) /* Bit 5: Stop counting when MR1=TC */ +#define WDT_MCR_MR1RESET (1 << 4) /* Bit 4: Reset TC if MR1=TC */ +#define WDT_MCR_MR1INT (1 << 3) /* Bit 3: System reset when MR1=TC */ +#define WDT_MCR_MR0STOP (1 << 2) /* Bit 2: Stop counting when MR0=TC */ +#define WDT_MCR_MR0RESET (1 << 1) /* Bit 1: Reset TC if MR0=TC */ +#define WDT_MCR_MR0INT (1 << 0) /* Bit 0: System reset when MR0=TC */ + +/* External Match Registers (EMR), address 0x1300 243c */ + +#define WDT_EMR_EXTMATCHCTRL1_SHIFT (6) /* Bits 6-7: Controls EXTMATCH1 when MR1=TC */ +#define WDT_EMR_EXTMATCHCTRL1_MASK (3 << WDT_EMR_EXTMATCHCTRL1_SHIFT) +# define WDT_EMR_EXTMATCHCTRL1_NOTHING (0 << WDT_EMR_EXTMATCHCTRL1_SHIFT) /* Do Nothing */ +# define WDT_EMR_EXTMATCHCTRL1_SETLOW (1 << WDT_EMR_EXTMATCHCTRL1_SHIFT) /* Set LOW */ +# define WDT_EMR_EXTMATCHCTRL1_SETHIGH (2 << WDT_EMR_EXTMATCHCTRL1_SHIFT) /* Set HIGH */ +# define WDT_EMR_EXTMATCHCTRL1_TOGGLE (3 << WDT_EMR_EXTMATCHCTRL1_SHIFT) /* Toggle */ +#define WDT_EMR_EXTMATCHCTRL0_SHIFT (4) /* Bits 4-5: Controls EXTMATCH0 when MR0=TC */ +#define WDT_EMR_EXTMATCHCTRL0_MASK (3 << WDT_EMR_EXTMATCHCTRL0_SHIFT) +# define WDT_EMR_EXTMATCHCTRL0_NOTHING (0 << WDT_EMR_EXTMATCHCTRL0_SHIFT) /* Do Nothing */ +# define WDT_EMR_EXTMATCHCTRL0_SETLOW (1 << WDT_EMR_EXTMATCHCTRL0_SHIFT) /* Set LOW */ +# define WDT_EMR_EXTMATCHCTRL0_SETHIGH (2 << WDT_EMR_EXTMATCHCTRL0_SHIFT) /* Set HIGH */ +# define WDT_EMR_EXTMATCHCTRL0_TOGGLE (3 << WDT_EMR_EXTMATCHCTRL0_SHIFT) /* Toggle */ +#define WDT_EMR_EXTMATCH1 (1 << 1) /* Bit 1: EXTMATCHCTRL1 controls behavior */ +#define WDT_EMR_EXTMATCH0 (1 << 0) /* Bit 0: EXTMATCHCTRL1 controls behavior */ + +/************************************************************************************************ + * Public Types + ************************************************************************************************/ + +/************************************************************************************************ + * Public Data + ************************************************************************************************/ + +/************************************************************************************************ + * Public Functions + ************************************************************************************************/ + +#endif /* __ARCH_ARM_SRC_LPC31XX_LPC31_WDT_H */ diff --git a/nuttx/configs/ea3131/README.txt b/nuttx/configs/ea3131/README.txt index db6fc0b8d..4b8a8705e 100755 --- a/nuttx/configs/ea3131/README.txt +++ b/nuttx/configs/ea3131/README.txt @@ -43,12 +43,12 @@ GNU Toolchain Options add one of the following configuration options to your .config (or defconfig) file: - CONFIG_LPC313X_CODESOURCERYW=y : CodeSourcery under Windows - CONFIG_LPC313X_CODESOURCERYL=y : CodeSourcery under Linux - CONFIG_LPC313X_DEVKITARM=y : devkitARM under Windows - CONFIG_LPC313X_BUILDROOT=y : NuttX buildroot under Linux or Cygwin (default) + CONFIG_LPC31XX_CODESOURCERYW=y : CodeSourcery under Windows + CONFIG_LPC31XX_CODESOURCERYL=y : CodeSourcery under Linux + CONFIG_LPC31XX_DEVKITARM=y : devkitARM under Windows + CONFIG_LPC31XX_BUILDROOT=y : NuttX buildroot under Linux or Cygwin (default) - If you are not using CONFIG_LPC313X_BUILDROOT, then you may also have to modify + If you are not using CONFIG_LPC31XX_BUILDROOT, then you may also have to modify the PATH in the setenv.h file if your make cannot find the tools. NOTE: the CodeSourcery (for Windows), devkitARM, and Raisonance toolchains are @@ -117,13 +117,13 @@ IDEs 2) Start the NuttX build at least one time from the Cygwin command line before trying to create your project. This is necessary to create certain auto-generated files and directories that will be needed. - 3) Set up include pathes: You will need include/, arch/arm/src/lpc313x, + 3) Set up include pathes: You will need include/, arch/arm/src/lpc31xx, arch/arm/src/common, arch/arm/src/cortexm3, and sched/. 4) All assembly files need to have the definition option -D __ASSEMBLY__ on the command line. Startup files will probably cause you some headaches. The NuttX startup file - is arch/arm/src/lpc313x/lpc313x_vectors.S. With RIDE, I have to build NuttX + is arch/arm/src/lpc31xx/lpc31_vectors.S. With RIDE, I have to build NuttX one time from the Cygwin command line in order to obtain the pre-built startup object needed by RIDE. @@ -426,7 +426,7 @@ On-Demand Paging NOTE: See the TODO list in the top-level directory: - "arch/arm/src/lpc313x/lpc313x_spi.c may or may not be functional. It was + "arch/arm/src/lpc31xx/lpc31_spi.c may or may not be functional. It was reported to be working, but I was unable to get it working with the Atmel at45dbxx serial FLASH driver." @@ -549,27 +549,27 @@ ARM/EA3131-specific Configuration Options Individual subsystems can be enabled: - CONFIG_LPC313X_MCI, CONFIG_LPC313X_SPI, CONFIG_LPC313X_UART + CONFIG_LPC31XX_MCI, CONFIG_LPC31XX_SPI, CONFIG_LPC31XX_UART External memory available on the board (see also CONFIG_MM_REGIONS) - CONFIG_LPC313X_EXTSRAM0 - Select if external SRAM0 is present - CONFIG_LPC313X_EXTSRAM0HEAP - Select if external SRAM0 should be + CONFIG_LPC31XX_EXTSRAM0 - Select if external SRAM0 is present + CONFIG_LPC31XX_EXTSRAM0HEAP - Select if external SRAM0 should be configured as part of the NuttX heap. - CONFIG_LPC313X_EXTSRAM0SIZE - Size (in bytes) of the installed + CONFIG_LPC31XX_EXTSRAM0SIZE - Size (in bytes) of the installed external SRAM0 memory - CONFIG_LPC313X_EXTSRAM1 - Select if external SRAM1 is present - CONFIG_LPC313X_EXTSRAM1HEAP - Select if external SRAM1 should be + CONFIG_LPC31XX_EXTSRAM1 - Select if external SRAM1 is present + CONFIG_LPC31XX_EXTSRAM1HEAP - Select if external SRAM1 should be configured as part of the NuttX heap. - CONFIG_LPC313X_EXTSRAM1SIZE - Size (in bytes) of the installed + CONFIG_LPC31XX_EXTSRAM1SIZE - Size (in bytes) of the installed external SRAM1 memory - CONFIG_LPC313X_EXTSDRAM - Select if external SDRAM is present - CONFIG_LPC313X_EXTSDRAMHEAP - Select if external SDRAM should be + CONFIG_LPC31XX_EXTSDRAM - Select if external SDRAM is present + CONFIG_LPC31XX_EXTSDRAMHEAP - Select if external SDRAM should be configured as part of the NuttX heap. - CONFIG_LPC313X_EXTSDRAMSIZE - Size (in bytes) of the installed + CONFIG_LPC31XX_EXTSDRAMSIZE - Size (in bytes) of the installed external SDRAM memory - CONFIG_LPC313X_EXTNAND - Select if external NAND is present - CONFIG_LPC313X_EXTSDRAMSIZE - Size (in bytes) of the installed + CONFIG_LPC31XX_EXTNAND - Select if external NAND is present + CONFIG_LPC31XX_EXTSDRAMSIZE - Size (in bytes) of the installed external NAND memory LPC313X specific device driver settings diff --git a/nuttx/configs/ea3131/include/board.h b/nuttx/configs/ea3131/include/board.h index 464099107..7e0a01b6a 100755 --- a/nuttx/configs/ea3131/include/board.h +++ b/nuttx/configs/ea3131/include/board.h @@ -44,7 +44,7 @@ #include #ifndef __ASSEMBLY__ # include -# include "lpc313x_cgudrvr.h" +# include "lpc31_cgudrvr.h" #endif /************************************************************************************ @@ -131,16 +131,16 @@ extern "C" { * Public Function Prototypes ************************************************************************************/ /************************************************************************************ - * Name: lpc313x_boardinitialize + * Name: lpc31_boardinitialize * * Description: - * All LPC313X architectures must provide the following entry point. This entry + * All LPC31XX architectures must provide the following entry point. This entry * point is called early in the intitialization -- after all memory has been * configured and mapped but before any devices have been initialized. * ************************************************************************************/ -EXTERN void lpc313x_boardinitialize(void); +EXTERN void lpc31_boardinitialize(void); /************************************************************************************ * Button support. diff --git a/nuttx/configs/ea3131/include/board_memorymap.h b/nuttx/configs/ea3131/include/board_memorymap.h index 576228aad..2604865c1 100755 --- a/nuttx/configs/ea3131/include/board_memorymap.h +++ b/nuttx/configs/ea3131/include/board_memorymap.h @@ -2,7 +2,7 @@ * configs/ea3131/include/board_memorymap.h * include/arch/board/board_memorymap.h * - * Copyright (C) 2009-2010 Gregory Nutt. All rights reserved. + * Copyright (C) 2009-2011 Gregory Nutt. All rights reserved. * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without @@ -38,7 +38,7 @@ #define __ARCH_BOARD_BOARD_MEMORYMAP_H /* This file should never be included directly, but only indirectly via - * lpc313x_memorymap.h. + * lpc31_memorymap.h. */ /************************************************************************************ @@ -51,44 +51,44 @@ * Definitions ************************************************************************************/ -/* If the LPC313x ROM page table is selected, then the board-logic is required +/* If the LPC31xx ROM page table is selected, then the board-logic is required * to provide: * * PGTABLE_BASE_PADDR - The physical address of the page table in ROM, * PGTABLE_BASE_VADDR - The mapped address of the page table in ROM, and - * Mappings for each of the PSECTIONS in lpc313x_memorymap.h + * Mappings for each of the PSECTIONS in lpc31_memorymap.h */ #ifdef CONFIG_ARCH_ROMPGTABLE - /* The LPC313x ROM page table uses a 1-1 physical to virtual memory mapping */ + /* The LPC31xx ROM page table uses a 1-1 physical to virtual memory mapping */ -# define LPC313X_SHADOWSPACE_VSECTION 0x00000000 /* 0x00000000-0x00000fff: Shadow Area 4Kb */ -# define LPC313X_INTSRAM_VSECTION 0x11028000 /* Internal SRAM 96Kb-192Kb */ -# define LPC313X_INTSRAM0_VADDR 0x11028000 /* 0x11028000-0x1103ffff: Internal SRAM 0 96Kb */ -# define LPC313X_INTSRAM1_VADDR 0x11040000 /* 0x11040000-0x11057fff: Internal SRAM 1 96Kb */ -# define LPC313X_INTSROM0_VSECTION 0x12000000 /* 0x12000000-0x1201ffff: Internal SROM 0 128Kb */ -# define LPC313X_APB01_VSECTION 0x13000000 /* 0x13000000-0x1300bfff: APB0 32Kb APB1 16Kb*/ -# define LPC313X_APB0_VADDR 0x13000000 /* 0x13000000-0x13007fff: APB0 32Kb */ -# define LPC313X_APB1_VADDR 0x13008000 /* 0x13008000-0x1300bfff: APB1 16Kb */ -# define LPC313X_APB2_VSECTION 0x15000000 /* 0x15000000-0x15003fff: APB2 16Kb */ -# define LPC313X_APB3_VSECTION 0x16000000 /* 0x16000000-0x160003ff: APB3 1Kb */ -# define LPC313X_APB4MPMC_VSECTION 0x17000000 /* 8Kb */ -# define LPC313X_APB4_VADDR 0x17000000 /* 0x17000000-0x17000fff: APB4 4Kb */ -# define LPC313X_MPMC_VADDR 0x17008000 /* 0x17008000-0x17008fff: MPMC cfg 4Kb */ -# define LPC313X_MCI_VSECTION 0x18000000 /* 0x18000000 0x180003ff: MCI/SD/SDIO 1Kb */ -# define LPC313X_USBOTG_VSECTION 0x19000000 /* 0x19000000-0x19000fff: USB OTG 4Kb */ -# define LPC313X_EXTSRAM_VSECTION 0x20020000 /* 64-128Kb */ -# define LPC313X_EXTSRAM0_VADDR 0x20000000 /* 0x20000000-0x2001ffff: External SRAM 0 64-128Kb */ -# define LPC313X_EXTSRAM1_VADDR 0x20020000 /* 0x20020000-0x2003ffff: External SRAM 1 64-128Kb */ -# define LPC313X_EXTSDRAM0_VSECTION 0x30000000 /* 0x30000000-0x37ffffff: External SDRAM 0 128Mb */ -# define LPC313X_INTC_VSECTION 0x60000000 /* 0x60000000-0x60000fff: Interrupt controller 4Kb */ -# define LPC313X_NAND_VSECTION 0x70000000 /* 0x70000000-0x700007ff: NANDFLASH Ctrl 2Kb */ +# define LPC31_SHADOWSPACE_VSECTION 0x00000000 /* 0x00000000-0x00000fff: Shadow Area 4Kb */ +# define LPC31_INTSRAM_VSECTION 0x11028000 /* Internal SRAM 96Kb-192Kb */ +# define LPC31_INTSRAM0_VADDR 0x11028000 /* 0x11028000-0x1103ffff: Internal SRAM 0 96Kb */ +# define LPC31_INTSRAM1_VADDR 0x11040000 /* 0x11040000-0x11057fff: Internal SRAM 1 96Kb */ +# define LPC31_INTSROM0_VSECTION 0x12000000 /* 0x12000000-0x1201ffff: Internal SROM 0 128Kb */ +# define LPC31_APB01_VSECTION 0x13000000 /* 0x13000000-0x1300bfff: APB0 32Kb APB1 16Kb*/ +# define LPC31_APB0_VADDR 0x13000000 /* 0x13000000-0x13007fff: APB0 32Kb */ +# define LPC31_APB1_VADDR 0x13008000 /* 0x13008000-0x1300bfff: APB1 16Kb */ +# define LPC31_APB2_VSECTION 0x15000000 /* 0x15000000-0x15003fff: APB2 16Kb */ +# define LPC31_APB3_VSECTION 0x16000000 /* 0x16000000-0x160003ff: APB3 1Kb */ +# define LPC31_APB4MPMC_VSECTION 0x17000000 /* 8Kb */ +# define LPC31_APB4_VADDR 0x17000000 /* 0x17000000-0x17000fff: APB4 4Kb */ +# define LPC31_MPMC_VADDR 0x17008000 /* 0x17008000-0x17008fff: MPMC cfg 4Kb */ +# define LPC31_MCI_VSECTION 0x18000000 /* 0x18000000 0x180003ff: MCI/SD/SDIO 1Kb */ +# define LPC31_USBOTG_VSECTION 0x19000000 /* 0x19000000-0x19000fff: USB OTG 4Kb */ +# define LPC31_EXTSRAM_VSECTION 0x20020000 /* 64-128Kb */ +# define LPC31_EXTSRAM0_VADDR 0x20000000 /* 0x20000000-0x2001ffff: External SRAM 0 64-128Kb */ +# define LPC31_EXTSRAM1_VADDR 0x20020000 /* 0x20020000-0x2003ffff: External SRAM 1 64-128Kb */ +# define LPC31_EXTSDRAM0_VSECTION 0x30000000 /* 0x30000000-0x37ffffff: External SDRAM 0 128Mb */ +# define LPC31_INTC_VSECTION 0x60000000 /* 0x60000000-0x60000fff: Interrupt controller 4Kb */ +# define LPC31_NAND_VSECTION 0x70000000 /* 0x70000000-0x700007ff: NANDFLASH Ctrl 2Kb */ /* Define the address of the page table within the ROM */ -# define ROMPGTABLE_OFFSET 0x0001c000 /* Offset of the ROM page table in ROM */ -# define PGTABLE_BASE_PADDR (LPC313X_INTSROM0_PSECTION+ROMPGTABLE_OFFSET) -# define PGTABLE_BASE_VADDR (LPC313X_INTSROM0_VSECTION+ROMPGTABLE_OFFSET) +# define ROMPGTABLE_OFFSET 0x0001c000 /* Offset of the ROM page table in ROM */ +# define PGTABLE_BASE_PADDR (LPC31_INTSROM0_PSECTION+ROMPGTABLE_OFFSET) +# define PGTABLE_BASE_VADDR (LPC31_INTSROM0_VSECTION+ROMPGTABLE_OFFSET) #endif /************************************************************************************ diff --git a/nuttx/configs/ea3131/locked/mklocked.sh b/nuttx/configs/ea3131/locked/mklocked.sh index 8457ab818..ac99f4438 100755 --- a/nuttx/configs/ea3131/locked/mklocked.sh +++ b/nuttx/configs/ea3131/locked/mklocked.sh @@ -117,7 +117,7 @@ echo "EXTERN(up_vectoraddrexcptn)" >>ld-locked.inc echo "EXTERN(up_timerinit)" >>ld-locked.inc -answer=$(checkconfig CONFIG_LPC313X_UART) +answer=$(checkconfig CONFIG_LPC31XX_UART) if [ $answer = y ]; then echo "EXTERN(up_earlyserialinit)" >>ld-locked.inc fi diff --git a/nuttx/configs/ea3131/nsh/Make.defs b/nuttx/configs/ea3131/nsh/Make.defs index 162397f8b..247cb6ebd 100755 --- a/nuttx/configs/ea3131/nsh/Make.defs +++ b/nuttx/configs/ea3131/nsh/Make.defs @@ -37,23 +37,23 @@ include ${TOPDIR}/.config # Setup for the selected toolchain -ifeq ($(CONFIG_LPC313X_CODESOURCERYW),y) +ifeq ($(CONFIG_LPC31XX_CODESOURCERYW),y) # CodeSourcery under Windows CROSSDEV = arm-none-eabi- WINTOOL = y MAXOPTIMIZATION = -O2 endif -ifeq ($(CONFIG_LPC313X_CODESOURCERYL),y) +ifeq ($(CONFIG_LPC31XX_CODESOURCERYL),y) # CodeSourcery under Linux CROSSDEV = arm-none-eabi- MAXOPTIMIZATION = -O2 endif -ifeq ($(CONFIG_LPC313X_DEVKITARM),y) +ifeq ($(CONFIG_LPC31XX_DEVKITARM),y) # devkitARM under Windows CROSSDEV = arm-eabi- WINTOOL = y endif -ifeq ($(CONFIG_LPC313X_BUILDROOT),y) +ifeq ($(CONFIG_LPC31XX_BUILDROOT),y) # NuttX buildroot under Linux or Cygwin CROSSDEV = arm-elf- MAXOPTIMIZATION = -Os @@ -121,7 +121,7 @@ OBJEXT = .o LIBEXT = .a EXEEXT = -ifneq ($(CONFIG_LPC313X_BUILDROOT),y) +ifneq ($(CONFIG_LPC31XX_BUILDROOT),y) LDFLAGS += -nostartfiles -nodefaultlibs endif ifeq ($(CONFIG_DEBUG_SYMBOLS),y) diff --git a/nuttx/configs/ea3131/nsh/defconfig b/nuttx/configs/ea3131/nsh/defconfig index 29da6335d..0c7193079 100755 --- a/nuttx/configs/ea3131/nsh/defconfig +++ b/nuttx/configs/ea3131/nsh/defconfig @@ -50,13 +50,13 @@ # CONFIG_ENDIAN_BIG - define if big endian (default is little endian) # CONFIG_BOARD_LOOPSPERMSEC - for delay loops # CONFIG_DRAM_SIZE - For most ARM9 architectures, this describes the -# size of installed DRAM. For the LPC313X, it is used only to +# size of installed DRAM. For the LPC31XX, it is used only to # deterimine how to map the executable regions. It is SDRAM size # only if you are executing out of the external SDRAM; or it could # be NOR FLASH size, external SRAM size, or internal SRAM size. # CONFIG_DRAM_START - The start address of DRAM (physical) # CONFIG_DRAM_VSTART - The startaddress of DRAM (virtual) -# CONFIG_ARCH_IRQPRIO - The LPC313x supports interrupt prioritization +# CONFIG_ARCH_IRQPRIO - The LPC31xx supports interrupt prioritization # CONFIG_ARCH_INTERRUPTSTACK - This architecture supports an interrupt # stack. If defined, this symbol is the size of the interrupt # stack in bytes. If not defined, the user task stacks will be @@ -76,7 +76,7 @@ CONFIG_ARCH=arm CONFIG_ARCH_ARM=y CONFIG_ARCH_ARM926EJS=y -CONFIG_ARCH_CHIP=lpc313x +CONFIG_ARCH_CHIP=lpc31xx CONFIG_ARCH_CHIP_LPC3131=y CONFIG_ARCH_BOARD=ea3131 CONFIG_ARCH_BOARD_EA3131=y @@ -108,54 +108,54 @@ CONFIG_ARCH_ROMPGTABLE=y # Identify toolchain and linker options # -CONFIG_LPC313X_CODESOURCERYW=n -CONFIG_LPC313X_CODESOURCERYL=n -CONFIG_LPC313X_DEVKITARM=n -CONFIG_LPC313X_BUILDROOT=y +CONFIG_LPC31XX_CODESOURCERYW=n +CONFIG_LPC31XX_CODESOURCERYL=n +CONFIG_LPC31XX_DEVKITARM=n +CONFIG_LPC31XX_BUILDROOT=y # # Individual subsystems can be enabled: # -CONFIG_LPC313X_MCI=n -CONFIG_LPC313X_SPI=n -CONFIG_LPC313X_UART=y +CONFIG_LPC31XX_MCI=n +CONFIG_LPC31XX_SPI=n +CONFIG_LPC31XX_UART=y # # Exernal memory available on the board (see also CONFIG_MM_REGIONS) # -# CONFIG_LPC313X_EXTSRAM0 - Select if external SRAM0 is present -# CONFIG_LPC313X_EXTSRAM0HEAP - Select if external SRAM0 should be +# CONFIG_LPC31XX_EXTSRAM0 - Select if external SRAM0 is present +# CONFIG_LPC31XX_EXTSRAM0HEAP - Select if external SRAM0 should be # configured as part of the NuttX heap. -# CONFIG_LPC313X_EXTSRAM0SIZE - Size (in bytes) of the installed +# CONFIG_LPC31XX_EXTSRAM0SIZE - Size (in bytes) of the installed # external SRAM0 memory -# CONFIG_LPC313X_EXTSRAM1 - Select if external SRAM1 is present -# CONFIG_LPC313X_EXTSRAM1HEAP - Select if external SRAM1 should be +# CONFIG_LPC31XX_EXTSRAM1 - Select if external SRAM1 is present +# CONFIG_LPC31XX_EXTSRAM1HEAP - Select if external SRAM1 should be # configured as part of the NuttX heap. -# CONFIG_LPC313X_EXTSRAM1SIZE - Size (in bytes) of the installed +# CONFIG_LPC31XX_EXTSRAM1SIZE - Size (in bytes) of the installed # external SRAM1 memory -# CONFIG_LPC313X_EXTSDRAM - Select if external SDRAM is present -# CONFIG_LPC313X_EXTSDRAMHEAP - Select if external SDRAM should be +# CONFIG_LPC31XX_EXTSDRAM - Select if external SDRAM is present +# CONFIG_LPC31XX_EXTSDRAMHEAP - Select if external SDRAM should be # configured as part of the NuttX heap. -# CONFIG_LPC313X_EXTSDRAMSIZE - Size (in bytes) of the installed +# CONFIG_LPC31XX_EXTSDRAMSIZE - Size (in bytes) of the installed # external SDRAM memory -# CONFIG_LPC313X_EXTNAND - Select if external NAND is present -# CONFIG_LPC313X_EXTSDRAMSIZE - Size (in bytes) of the installed +# CONFIG_LPC31XX_EXTNAND - Select if external NAND is present +# CONFIG_LPC31XX_EXTSDRAMSIZE - Size (in bytes) of the installed # external NAND memory # -CONFIG_LPC313X_EXTSRAM0=n -CONFIG_LPC313X_EXTSRAM0HEAP=n -CONFIG_LPC313X_EXTSRAM0SIZE=(128*1024) -CONFIG_LPC313X_EXTSRAM1=n -CONFIG_LPC313X_EXTSRAM1HEAP=n -CONFIG_LPC313X_EXTSRAM1SIZE=(128*1024) -CONFIG_LPC313X_EXTSDRAM=n -CONFIG_LPC313X_EXTSDRAMHEAP=n -CONFIG_LPC313X_EXTSDRAMSIZE=(64*1024*1024) -CONFIG_LPC313X_EXTNAND=n -CONFIG_LPC313X_EXTNANDSIZE=(64*1024*1024) +CONFIG_LPC31XX_EXTSRAM0=n +CONFIG_LPC31XX_EXTSRAM0HEAP=n +CONFIG_LPC31XX_EXTSRAM0SIZE=(128*1024) +CONFIG_LPC31XX_EXTSRAM1=n +CONFIG_LPC31XX_EXTSRAM1HEAP=n +CONFIG_LPC31XX_EXTSRAM1SIZE=(128*1024) +CONFIG_LPC31XX_EXTSDRAM=n +CONFIG_LPC31XX_EXTSDRAMHEAP=n +CONFIG_LPC31XX_EXTSDRAMSIZE=(64*1024*1024) +CONFIG_LPC31XX_EXTNAND=n +CONFIG_LPC31XX_EXTNANDSIZE=(64*1024*1024) # -# LPC313X specific device driver settings +# LPC31XX specific device driver settings # # CONFIG_UART_SERIAL_CONSOLE - selects the UART for the # console and ttys0 @@ -535,20 +535,20 @@ CONFIG_USBDEV_TRACE=n CONFIG_USBDEV_TRACE_NRECORDS=128 # -# LPC313X USB Configuration +# LPC31XX USB Configuration # -# CONFIG_LPC313X_GIO_USBATTACH +# CONFIG_LPC31XX_GIO_USBATTACH # GIO that detects USB attach/detach events -# CONFIG_LPC313X_GIO_USBDPPULLUP +# CONFIG_LPC31XX_GIO_USBDPPULLUP # GIO # CONFIG_DMA320_USBDEV_DMA -# Enable LPC313X-specific DMA support +# Enable LPC31XX-specific DMA support # -CONFIG_LPC313X_GIO_USBATTACH=6 -CONFIG_LPC313X_GIO_USBDPPULLUP=17 -CONFIG_LPC313X_VENDORID=0xd320 -CONFIG_LPC313X_PRODUCTID=0x3211 -CONFIG_LPC313X_USBDEV_DMA=n +CONFIG_LPC31XX_GIO_USBATTACH=6 +CONFIG_LPC31XX_GIO_USBDPPULLUP=17 +CONFIG_LPC31XX_VENDORID=0xd320 +CONFIG_LPC31XX_PRODUCTID=0x3211 +CONFIG_LPC31XX_USBDEV_DMA=n # # USB Serial Device Configuration diff --git a/nuttx/configs/ea3131/nsh/ld.script b/nuttx/configs/ea3131/nsh/ld.script index 1d57baed0..8c3b2db45 100755 --- a/nuttx/configs/ea3131/nsh/ld.script +++ b/nuttx/configs/ea3131/nsh/ld.script @@ -34,7 +34,7 @@ ****************************************************************************/ /* The LPC3131 has 192Kb of ISRAM beginning at virtual address 0x1102:8000. - * LPC313x boot ROM expects the boot image be compiled with entry point at + * LPC31xx boot ROM expects the boot image be compiled with entry point at * 0x1102:9000. A 128b header will appear at this address (applied by * lpc313xImgCreator) and the executable code must begin at 0x1102:9080. */ diff --git a/nuttx/configs/ea3131/ostest/Make.defs b/nuttx/configs/ea3131/ostest/Make.defs index 25cb28b70..fd72ded9d 100755 --- a/nuttx/configs/ea3131/ostest/Make.defs +++ b/nuttx/configs/ea3131/ostest/Make.defs @@ -37,23 +37,23 @@ include ${TOPDIR}/.config # Setup for the selected toolchain -ifeq ($(CONFIG_LPC313X_CODESOURCERYW),y) +ifeq ($(CONFIG_LPC31XX_CODESOURCERYW),y) # CodeSourcery under Windows CROSSDEV = arm-none-eabi- WINTOOL = y MAXOPTIMIZATION = -O2 endif -ifeq ($(CONFIG_LPC313X_CODESOURCERYL),y) +ifeq ($(CONFIG_LPC31XX_CODESOURCERYL),y) # CodeSourcery under Linux CROSSDEV = arm-none-eabi- MAXOPTIMIZATION = -O2 endif -ifeq ($(CONFIG_LPC313X_DEVKITARM),y) +ifeq ($(CONFIG_LPC31XX_DEVKITARM),y) # devkitARM under Windows CROSSDEV = arm-eabi- WINTOOL = y endif -ifeq ($(CONFIG_LPC313X_BUILDROOT),y) +ifeq ($(CONFIG_LPC31XX_BUILDROOT),y) # NuttX buildroot under Linux or Cygwin CROSSDEV = arm-elf- MAXOPTIMIZATION = -Os @@ -121,7 +121,7 @@ OBJEXT = .o LIBEXT = .a EXEEXT = -ifneq ($(CONFIG_LPC313X_BUILDROOT),y) +ifneq ($(CONFIG_LPC31XX_BUILDROOT),y) LDFLAGS += -nostartfiles -nodefaultlibs endif ifeq ($(CONFIG_DEBUG_SYMBOLS),y) diff --git a/nuttx/configs/ea3131/ostest/defconfig b/nuttx/configs/ea3131/ostest/defconfig index f085980ba..0027aa242 100755 --- a/nuttx/configs/ea3131/ostest/defconfig +++ b/nuttx/configs/ea3131/ostest/defconfig @@ -50,13 +50,13 @@ # CONFIG_ENDIAN_BIG - define if big endian (default is little endian) # CONFIG_BOARD_LOOPSPERMSEC - for delay loops # CONFIG_DRAM_SIZE - For most ARM9 architectures, this describes the -# size of installed DRAM. For the LPC313X, it is used only to +# size of installed DRAM. For the LPC31XX, it is used only to # deterimine how to map the executable regions. It is SDRAM size # only if you are executing out of the external SDRAM; or it could # be NOR FLASH size, external SRAM size, or internal SRAM size. # CONFIG_DRAM_START - The start address of DRAM (physical) # CONFIG_DRAM_VSTART - The startaddress of DRAM (virtual) -# CONFIG_ARCH_IRQPRIO - The LPC313x supports interrupt prioritization +# CONFIG_ARCH_IRQPRIO - The LPC31xx supports interrupt prioritization # CONFIG_ARCH_INTERRUPTSTACK - This architecture supports an interrupt # stack. If defined, this symbol is the size of the interrupt # stack in bytes. If not defined, the user task stacks will be @@ -76,7 +76,7 @@ CONFIG_ARCH=arm CONFIG_ARCH_ARM=y CONFIG_ARCH_ARM926EJS=y -CONFIG_ARCH_CHIP=lpc313x +CONFIG_ARCH_CHIP=lpc31xx CONFIG_ARCH_CHIP_LPC3131=y CONFIG_ARCH_BOARD=ea3131 CONFIG_ARCH_BOARD_EA3131=y @@ -108,54 +108,54 @@ CONFIG_ARCH_ROMPGTABLE=y # Identify toolchain and linker options # -CONFIG_LPC313X_CODESOURCERYW=n -CONFIG_LPC313X_CODESOURCERYL=n -CONFIG_LPC313X_DEVKITARM=n -CONFIG_LPC313X_BUILDROOT=y +CONFIG_LPC31XX_CODESOURCERYW=n +CONFIG_LPC31XX_CODESOURCERYL=n +CONFIG_LPC31XX_DEVKITARM=n +CONFIG_LPC31XX_BUILDROOT=y # # Individual subsystems can be enabled: # -CONFIG_LPC313X_MCI=n -CONFIG_LPC313X_SPI=n -CONFIG_LPC313X_UART=y +CONFIG_LPC31XX_MCI=n +CONFIG_LPC31XX_SPI=n +CONFIG_LPC31XX_UART=y # # Exernal memory available on the board (see also CONFIG_MM_REGIONS) # -# CONFIG_LPC313X_EXTSRAM0 - Select if external SRAM0 is present -# CONFIG_LPC313X_EXTSRAM0HEAP - Select if external SRAM0 should be +# CONFIG_LPC31XX_EXTSRAM0 - Select if external SRAM0 is present +# CONFIG_LPC31XX_EXTSRAM0HEAP - Select if external SRAM0 should be # configured as part of the NuttX heap. -# CONFIG_LPC313X_EXTSRAM0SIZE - Size (in bytes) of the installed +# CONFIG_LPC31XX_EXTSRAM0SIZE - Size (in bytes) of the installed # external SRAM0 memory -# CONFIG_LPC313X_EXTSRAM1 - Select if external SRAM1 is present -# CONFIG_LPC313X_EXTSRAM1HEAP - Select if external SRAM1 should be +# CONFIG_LPC31XX_EXTSRAM1 - Select if external SRAM1 is present +# CONFIG_LPC31XX_EXTSRAM1HEAP - Select if external SRAM1 should be # configured as part of the NuttX heap. -# CONFIG_LPC313X_EXTSRAM1SIZE - Size (in bytes) of the installed +# CONFIG_LPC31XX_EXTSRAM1SIZE - Size (in bytes) of the installed # external SRAM1 memory -# CONFIG_LPC313X_EXTSDRAM - Select if external SDRAM is present -# CONFIG_LPC313X_EXTSDRAMHEAP - Select if external SDRAM should be +# CONFIG_LPC31XX_EXTSDRAM - Select if external SDRAM is present +# CONFIG_LPC31XX_EXTSDRAMHEAP - Select if external SDRAM should be # configured as part of the NuttX heap. -# CONFIG_LPC313X_EXTSDRAMSIZE - Size (in bytes) of the installed +# CONFIG_LPC31XX_EXTSDRAMSIZE - Size (in bytes) of the installed # external SDRAM memory -# CONFIG_LPC313X_EXTNAND - Select if external NAND is present -# CONFIG_LPC313X_EXTSDRAMSIZE - Size (in bytes) of the installed +# CONFIG_LPC31XX_EXTNAND - Select if external NAND is present +# CONFIG_LPC31XX_EXTSDRAMSIZE - Size (in bytes) of the installed # external NAND memory # -CONFIG_LPC313X_EXTSRAM0=n -CONFIG_LPC313X_EXTSRAM0HEAP=n -CONFIG_LPC313X_EXTSRAM0SIZE=(128*1024) -CONFIG_LPC313X_EXTSRAM1=n -CONFIG_LPC313X_EXTSRAM1HEAP=n -CONFIG_LPC313X_EXTSRAM1SIZE=(128*1024) -CONFIG_LPC313X_EXTSDRAM=n -CONFIG_LPC313X_EXTSDRAMHEAP=n -CONFIG_LPC313X_EXTSDRAMSIZE=(64*1024*1024) -CONFIG_LPC313X_EXTNAND=n -CONFIG_LPC313X_EXTNANDSIZE=(64*1024*1024) +CONFIG_LPC31XX_EXTSRAM0=n +CONFIG_LPC31XX_EXTSRAM0HEAP=n +CONFIG_LPC31XX_EXTSRAM0SIZE=(128*1024) +CONFIG_LPC31XX_EXTSRAM1=n +CONFIG_LPC31XX_EXTSRAM1HEAP=n +CONFIG_LPC31XX_EXTSRAM1SIZE=(128*1024) +CONFIG_LPC31XX_EXTSDRAM=n +CONFIG_LPC31XX_EXTSDRAMHEAP=n +CONFIG_LPC31XX_EXTSDRAMSIZE=(64*1024*1024) +CONFIG_LPC31XX_EXTNAND=n +CONFIG_LPC31XX_EXTNANDSIZE=(64*1024*1024) # -# LPC313X specific device driver settings +# LPC31XX specific device driver settings # # CONFIG_UART_SERIAL_CONSOLE - selects the UART for the # console and ttys0 @@ -535,20 +535,20 @@ CONFIG_USBDEV_TRACE=n CONFIG_USBDEV_TRACE_NRECORDS=128 # -# LPC313X USB Configuration +# LPC31XX USB Configuration # -# CONFIG_LPC313X_GIO_USBATTACH +# CONFIG_LPC31XX_GIO_USBATTACH # GIO that detects USB attach/detach events -# CONFIG_LPC313X_GIO_USBDPPULLUP +# CONFIG_LPC31XX_GIO_USBDPPULLUP # GIO # CONFIG_DMA320_USBDEV_DMA -# Enable LPC313X-specific DMA support +# Enable LPC31XX-specific DMA support # -CONFIG_LPC313X_GIO_USBATTACH=6 -CONFIG_LPC313X_GIO_USBDPPULLUP=17 -CONFIG_LPC313X_VENDORID=0xd320 -CONFIG_LPC313X_PRODUCTID=0x3211 -CONFIG_LPC313X_USBDEV_DMA=n +CONFIG_LPC31XX_GIO_USBATTACH=6 +CONFIG_LPC31XX_GIO_USBDPPULLUP=17 +CONFIG_LPC31XX_VENDORID=0xd320 +CONFIG_LPC31XX_PRODUCTID=0x3211 +CONFIG_LPC31XX_USBDEV_DMA=n # # USB Serial Device Configuration diff --git a/nuttx/configs/ea3131/ostest/ld.script b/nuttx/configs/ea3131/ostest/ld.script index 1e1f0ff39..531e64ce9 100755 --- a/nuttx/configs/ea3131/ostest/ld.script +++ b/nuttx/configs/ea3131/ostest/ld.script @@ -34,7 +34,7 @@ ****************************************************************************/ /* The LPC3131 has 192Kb of ISRAM beginning at virtual address 0x1102:8000. - * LPC313x boot ROM expects the boot image be compiled with entry point at + * LPC31xx boot ROM expects the boot image be compiled with entry point at * 0x1102:9000. A 128b header will appear at this address (applied by * lpc313xImgCreator) and the executable code must begin at 0x1102:9080. */ diff --git a/nuttx/configs/ea3131/pgnsh/Make.defs b/nuttx/configs/ea3131/pgnsh/Make.defs index f19d54bbd..81edc73fa 100755 --- a/nuttx/configs/ea3131/pgnsh/Make.defs +++ b/nuttx/configs/ea3131/pgnsh/Make.defs @@ -37,23 +37,23 @@ include ${TOPDIR}/.config # Setup for the selected toolchain -ifeq ($(CONFIG_LPC313X_CODESOURCERYW),y) +ifeq ($(CONFIG_LPC31XX_CODESOURCERYW),y) # CodeSourcery under Windows CROSSDEV = arm-none-eabi- WINTOOL = y MAXOPTIMIZATION = -O2 endif -ifeq ($(CONFIG_LPC313X_CODESOURCERYL),y) +ifeq ($(CONFIG_LPC31XX_CODESOURCERYL),y) # CodeSourcery under Linux CROSSDEV = arm-none-eabi- MAXOPTIMIZATION = -O2 endif -ifeq ($(CONFIG_LPC313X_DEVKITARM),y) +ifeq ($(CONFIG_LPC31XX_DEVKITARM),y) # devkitARM under Windows CROSSDEV = arm-eabi- WINTOOL = y endif -ifeq ($(CONFIG_LPC313X_BUILDROOT),y) +ifeq ($(CONFIG_LPC31XX_BUILDROOT),y) # NuttX buildroot under Linux or Cygwin CROSSDEV = arm-elf- MAXOPTIMIZATION = -Os @@ -121,7 +121,7 @@ OBJEXT = .o LIBEXT = .a EXEEXT = -ifneq ($(CONFIG_LPC313X_BUILDROOT),y) +ifneq ($(CONFIG_LPC31XX_BUILDROOT),y) LDFLAGS += -nostartfiles -nodefaultlibs endif ifeq ($(CONFIG_DEBUG_SYMBOLS),y) diff --git a/nuttx/configs/ea3131/pgnsh/defconfig b/nuttx/configs/ea3131/pgnsh/defconfig index e24897d24..252a64c09 100755 --- a/nuttx/configs/ea3131/pgnsh/defconfig +++ b/nuttx/configs/ea3131/pgnsh/defconfig @@ -50,13 +50,13 @@ # CONFIG_ENDIAN_BIG - define if big endian (default is little endian) # CONFIG_BOARD_LOOPSPERMSEC - for delay loops # CONFIG_DRAM_SIZE - For most ARM9 architectures, this describes the -# size of installed DRAM. For the LPC313X, it is used only to +# size of installed DRAM. For the LPC31XX, it is used only to # deterimine how to map the executable regions. It is SDRAM size # only if you are executing out of the external SDRAM; or it could # be NOR FLASH size, external SRAM size, or internal SRAM size. # CONFIG_DRAM_START - The start address of DRAM (physical) # CONFIG_DRAM_VSTART - The startaddress of DRAM (virtual) -# CONFIG_ARCH_IRQPRIO - The LPC313x supports interrupt prioritization +# CONFIG_ARCH_IRQPRIO - The LPC31xx supports interrupt prioritization # CONFIG_ARCH_INTERRUPTSTACK - This architecture supports an interrupt # stack. If defined, this symbol is the size of the interrupt # stack in bytes. If not defined, the user task stacks will be @@ -76,7 +76,7 @@ CONFIG_ARCH=arm CONFIG_ARCH_ARM=y CONFIG_ARCH_ARM926EJS=y -CONFIG_ARCH_CHIP=lpc313x +CONFIG_ARCH_CHIP=lpc31xx CONFIG_ARCH_CHIP_LPC3131=y CONFIG_ARCH_BOARD=ea3131 CONFIG_ARCH_BOARD_EA3131=y @@ -108,54 +108,54 @@ CONFIG_ARCH_ROMPGTABLE=n # Identify toolchain and linker options # -CONFIG_LPC313X_CODESOURCERYW=n -CONFIG_LPC313X_CODESOURCERYL=n -CONFIG_LPC313X_DEVKITARM=n -CONFIG_LPC313X_BUILDROOT=y +CONFIG_LPC31XX_CODESOURCERYW=n +CONFIG_LPC31XX_CODESOURCERYL=n +CONFIG_LPC31XX_DEVKITARM=n +CONFIG_LPC31XX_BUILDROOT=y # # Individual subsystems can be enabled: # -CONFIG_LPC313X_MCI=n -CONFIG_LPC313X_SPI=y -CONFIG_LPC313X_UART=y +CONFIG_LPC31XX_MCI=n +CONFIG_LPC31XX_SPI=y +CONFIG_LPC31XX_UART=y # # Exernal memory available on the board (see also CONFIG_MM_REGIONS) # -# CONFIG_LPC313X_EXTSRAM0 - Select if external SRAM0 is present -# CONFIG_LPC313X_EXTSRAM0HEAP - Select if external SRAM0 should be +# CONFIG_LPC31XX_EXTSRAM0 - Select if external SRAM0 is present +# CONFIG_LPC31XX_EXTSRAM0HEAP - Select if external SRAM0 should be # configured as part of the NuttX heap. -# CONFIG_LPC313X_EXTSRAM0SIZE - Size (in bytes) of the installed +# CONFIG_LPC31XX_EXTSRAM0SIZE - Size (in bytes) of the installed # external SRAM0 memory -# CONFIG_LPC313X_EXTSRAM1 - Select if external SRAM1 is present -# CONFIG_LPC313X_EXTSRAM1HEAP - Select if external SRAM1 should be +# CONFIG_LPC31XX_EXTSRAM1 - Select if external SRAM1 is present +# CONFIG_LPC31XX_EXTSRAM1HEAP - Select if external SRAM1 should be # configured as part of the NuttX heap. -# CONFIG_LPC313X_EXTSRAM1SIZE - Size (in bytes) of the installed +# CONFIG_LPC31XX_EXTSRAM1SIZE - Size (in bytes) of the installed # external SRAM1 memory -# CONFIG_LPC313X_EXTSDRAM - Select if external SDRAM is present -# CONFIG_LPC313X_EXTSDRAMHEAP - Select if external SDRAM should be +# CONFIG_LPC31XX_EXTSDRAM - Select if external SDRAM is present +# CONFIG_LPC31XX_EXTSDRAMHEAP - Select if external SDRAM should be # configured as part of the NuttX heap. -# CONFIG_LPC313X_EXTSDRAMSIZE - Size (in bytes) of the installed +# CONFIG_LPC31XX_EXTSDRAMSIZE - Size (in bytes) of the installed # external SDRAM memory -# CONFIG_LPC313X_EXTNAND - Select if external NAND is present -# CONFIG_LPC313X_EXTSDRAMSIZE - Size (in bytes) of the installed +# CONFIG_LPC31XX_EXTNAND - Select if external NAND is present +# CONFIG_LPC31XX_EXTSDRAMSIZE - Size (in bytes) of the installed # external NAND memory # -CONFIG_LPC313X_EXTSRAM0=n -CONFIG_LPC313X_EXTSRAM0HEAP=n -CONFIG_LPC313X_EXTSRAM0SIZE=(128*1024) -CONFIG_LPC313X_EXTSRAM1=n -CONFIG_LPC313X_EXTSRAM1HEAP=n -CONFIG_LPC313X_EXTSRAM1SIZE=(128*1024) -CONFIG_LPC313X_EXTSDRAM=n -CONFIG_LPC313X_EXTSDRAMHEAP=n -CONFIG_LPC313X_EXTSDRAMSIZE=(64*1024*1024) -CONFIG_LPC313X_EXTNAND=n -CONFIG_LPC313X_EXTNANDSIZE=(64*1024*1024) +CONFIG_LPC31XX_EXTSRAM0=n +CONFIG_LPC31XX_EXTSRAM0HEAP=n +CONFIG_LPC31XX_EXTSRAM0SIZE=(128*1024) +CONFIG_LPC31XX_EXTSRAM1=n +CONFIG_LPC31XX_EXTSRAM1HEAP=n +CONFIG_LPC31XX_EXTSRAM1SIZE=(128*1024) +CONFIG_LPC31XX_EXTSDRAM=n +CONFIG_LPC31XX_EXTSDRAMHEAP=n +CONFIG_LPC31XX_EXTSDRAMSIZE=(64*1024*1024) +CONFIG_LPC31XX_EXTNAND=n +CONFIG_LPC31XX_EXTNANDSIZE=(64*1024*1024) # -# LPC313X specific device driver settings +# LPC31XX specific device driver settings # # CONFIG_UART_SERIAL_CONSOLE - selects the UART for the # console and ttys0 @@ -681,20 +681,20 @@ CONFIG_USBDEV_TRACE=n CONFIG_USBDEV_TRACE_NRECORDS=128 # -# LPC313X USB Configuration +# LPC31XX USB Configuration # -# CONFIG_LPC313X_GIO_USBATTACH +# CONFIG_LPC31XX_GIO_USBATTACH # GIO that detects USB attach/detach events -# CONFIG_LPC313X_GIO_USBDPPULLUP +# CONFIG_LPC31XX_GIO_USBDPPULLUP # GIO # CONFIG_DMA320_USBDEV_DMA -# Enable LPC313X-specific DMA support +# Enable LPC31XX-specific DMA support # -CONFIG_LPC313X_GIO_USBATTACH=6 -CONFIG_LPC313X_GIO_USBDPPULLUP=17 -CONFIG_LPC313X_VENDORID=0xd320 -CONFIG_LPC313X_PRODUCTID=0x3211 -CONFIG_LPC313X_USBDEV_DMA=n +CONFIG_LPC31XX_GIO_USBATTACH=6 +CONFIG_LPC31XX_GIO_USBDPPULLUP=17 +CONFIG_LPC31XX_VENDORID=0xd320 +CONFIG_LPC31XX_PRODUCTID=0x3211 +CONFIG_LPC31XX_USBDEV_DMA=n # # USB Serial Device Configuration diff --git a/nuttx/configs/ea3131/pgnsh/ld.script b/nuttx/configs/ea3131/pgnsh/ld.script index eb77ecaff..c4c597567 100755 --- a/nuttx/configs/ea3131/pgnsh/ld.script +++ b/nuttx/configs/ea3131/pgnsh/ld.script @@ -34,7 +34,7 @@ ****************************************************************************/ /* The LPC3131 has 192Kb of ISRAM beginning at virtual address 0x1102:8000. - * LPC313x boot ROM expects the boot image be compiled with entry point at + * LPC31xx boot ROM expects the boot image be compiled with entry point at * 0x1102:9000. A 128b header will appear at this address (applied by * lpc313xImgCreator) and the executable code must begin at 0x1102:9080. * diff --git a/nuttx/configs/ea3131/src/Makefile b/nuttx/configs/ea3131/src/Makefile index c97c4fecf..6e62138d6 100755 --- a/nuttx/configs/ea3131/src/Makefile +++ b/nuttx/configs/ea3131/src/Makefile @@ -44,13 +44,13 @@ CSRCS = up_boot.c up_clkinit.c ifeq ($(CONFIG_ARCH_BUTTONS),y) CSRCS += up_buttons.c endif -ifeq ($(CONFIG_LPC313X_EXTSDRAM),y) +ifeq ($(CONFIG_LPC31XX_EXTSDRAM),y) CSRCS += up_mem.c endif ifeq ($(CONFIG_ARCH_LEDS),y) CSRCS += up_leds.c endif -ifeq ($(CONFIG_LPC313X_SPI),y) +ifeq ($(CONFIG_LPC31XX_SPI),y) CSRCS += up_spi.c endif ifeq ($(CONFIG_NSH_ARCHINIT),y) diff --git a/nuttx/configs/ea3131/src/ea3131_internal.h b/nuttx/configs/ea3131/src/ea3131_internal.h index 0f28ea1cc..ca2a5b570 100755 --- a/nuttx/configs/ea3131/src/ea3131_internal.h +++ b/nuttx/configs/ea3131/src/ea3131_internal.h @@ -1,127 +1,127 @@ -/************************************************************************************ - * configs/ea3131/src/ea3131_internal.h - * arch/arm/src/board/ea3131_internal.n - * - * Copyright (C) 2009-2010 Gregory Nutt. All rights reserved. - * Author: Gregory Nutt - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name NuttX nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - ************************************************************************************/ - -#ifndef __CONFIGS_EA3131_SRC_EA3131_INTERNAL_H -#define __CONFIGS_EA3131_SRC_EA3131_INTERNAL_H - -/************************************************************************************ - * Included Files - ************************************************************************************/ - -#include -#include -#include - -#include "lpc313x_ioconfig.h" - -/************************************************************************************ - * Definitions - ************************************************************************************/ - -/* EA3131L GPIOs ********************************************************************/ - -/* LEDs -- interface through an I2C GPIO expander */ - -/* BUTTONS -- NOTE that some have EXTI interrupts configured */ - -/* SPI Chip Selects */ -/* SPI NOR flash is the only device on SPI. SPI_CS_OUT0 is its chip select */ - -#define SPINOR_CS IOCONFIG_SPI_CSOUT0 - -/* USB Soft Connect Pullup -- NONE */ - -/************************************************************************************ - * Public Types - ************************************************************************************/ - -/************************************************************************************ - * Public data - ************************************************************************************/ - -#ifndef __ASSEMBLY__ - -/************************************************************************************ - * Public Functions - ************************************************************************************/ - -/************************************************************************************ - * Name: lpc313x_meminitialize - * - * Description: - * Initialize external memory resources (sram, sdram, nand, nor, etc.) - * - ************************************************************************************/ - -#ifdef CONFIG_LPC313X_EXTSDRAM -extern void lpc313x_meminitialize(void); -#endif - -/************************************************************************************ - * Name: lpc313x_spiinitialize - * - * Description: - * Called to configure SPI chip select GPIO pins for the EA3131 board. - * - ************************************************************************************/ - -extern void weak_function lpc313x_spiinitialize(void); - -/************************************************************************************ - * Name: lpc313x_usbinitialize - * - * Description: - * Called to setup USB-related GPIO pins for the EA3131 board. - * - ************************************************************************************/ - -extern void weak_function lpc313x_usbinitialize(void); - -/************************************************************************************ - * Name: lpc313x_pginitialize - * - * Description: - * Set up mass storage device to support on demand paging. - * - ************************************************************************************/ - -#ifdef CONFIG_PAGING -extern void weak_function lpc313x_pginitialize(void); -#endif - -#endif /* __ASSEMBLY__ */ -#endif /* __CONFIGS_EA3131_SRC_EA3131_INTERNAL_H */ - +/************************************************************************************ + * configs/ea3131/src/ea3131_internal.h + * arch/arm/src/board/ea3131_internal.n + * + * Copyright (C) 2009-2010 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name NuttX nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ************************************************************************************/ + +#ifndef __CONFIGS_EA3131_SRC_EA3131_INTERNAL_H +#define __CONFIGS_EA3131_SRC_EA3131_INTERNAL_H + +/************************************************************************************ + * Included Files + ************************************************************************************/ + +#include +#include +#include + +#include "lpc31_ioconfig.h" + +/************************************************************************************ + * Definitions + ************************************************************************************/ + +/* EA3131L GPIOs ********************************************************************/ + +/* LEDs -- interface through an I2C GPIO expander */ + +/* BUTTONS -- NOTE that some have EXTI interrupts configured */ + +/* SPI Chip Selects */ +/* SPI NOR flash is the only device on SPI. SPI_CS_OUT0 is its chip select */ + +#define SPINOR_CS IOCONFIG_SPI_CSOUT0 + +/* USB Soft Connect Pullup -- NONE */ + +/************************************************************************************ + * Public Types + ************************************************************************************/ + +/************************************************************************************ + * Public data + ************************************************************************************/ + +#ifndef __ASSEMBLY__ + +/************************************************************************************ + * Public Functions + ************************************************************************************/ + +/************************************************************************************ + * Name: lpc31_meminitialize + * + * Description: + * Initialize external memory resources (sram, sdram, nand, nor, etc.) + * + ************************************************************************************/ + +#ifdef CONFIG_LPC31XX_EXTSDRAM +extern void lpc31_meminitialize(void); +#endif + +/************************************************************************************ + * Name: lpc31_spiinitialize + * + * Description: + * Called to configure SPI chip select GPIO pins for the EA3131 board. + * + ************************************************************************************/ + +extern void weak_function lpc31_spiinitialize(void); + +/************************************************************************************ + * Name: lpc31_usbinitialize + * + * Description: + * Called to setup USB-related GPIO pins for the EA3131 board. + * + ************************************************************************************/ + +extern void weak_function lpc31_usbinitialize(void); + +/************************************************************************************ + * Name: lpc31_pginitialize + * + * Description: + * Set up mass storage device to support on demand paging. + * + ************************************************************************************/ + +#ifdef CONFIG_PAGING +extern void weak_function lpc31_pginitialize(void); +#endif + +#endif /* __ASSEMBLY__ */ +#endif /* __CONFIGS_EA3131_SRC_EA3131_INTERNAL_H */ + diff --git a/nuttx/configs/ea3131/src/up_boot.c b/nuttx/configs/ea3131/src/up_boot.c index 59ed9e778..94c4d8a9c 100755 --- a/nuttx/configs/ea3131/src/up_boot.c +++ b/nuttx/configs/ea3131/src/up_boot.c @@ -1,119 +1,119 @@ -/************************************************************************************ - * configs/ea3131/src/up_boot.c - * arch/arm/src/board/up_boot.c - * - * Copyright (C) 2009 Gregory Nutt. All rights reserved. - * Author: Gregory Nutt - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name NuttX nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - ************************************************************************************/ - -/************************************************************************************ - * Included Files - ************************************************************************************/ - -#include - -#include - -#include - -#include "up_arch.h" -#include "up_internal.h" -#include "lpc313x_internal.h" -#include "ea3131_internal.h" - -/************************************************************************************ - * Definitions - ************************************************************************************/ - -/************************************************************************************ - * Private Functions - ************************************************************************************/ - -/************************************************************************************ - * Public Functions - ************************************************************************************/ - -/************************************************************************************ - * Name: lpc313x_boardinitialize - * - * Description: - * All LPC313X architectures must provide the following entry point. This entry - * point is called early in the intitialization -- after all memory has been - * configured and mapped but before any devices have been initialized. - * - ************************************************************************************/ - -void lpc313x_boardinitialize(void) -{ - /* Initialize configured, external memory resources */ - -#ifdef CONFIG_LPC313X_EXTSDRAM - lpc313x_meminitialize(); -#endif - - /* Configure SPI chip selects if 1) SPI is not disabled, and 2) the weak function - * lpc313x_spiinitialize() has been brought into the link. - */ - -#if defined(CONFIG_LPC313X_SPI) - if (lpc313x_spiinitialize) - { - lpc313x_spiinitialize(); - } -#endif - - /* Initialize USB is 1) USBDEV is selected, 2) the USB controller is not - * disabled, and 3) the weak function lpc313x_usbinitialize() has been brought - * into the build. - */ - -#if defined(CONFIG_USBDEV) && defined(CONFIG_LPC313X_USB) - if (lpc313x_usbinitialize) - { - lpc313x_usbinitialize(); - } -#endif - - /* Configure on-board LEDs if LED support has been selected. */ - -#ifdef CONFIG_ARCH_LEDS - up_ledinit(); -#endif - - /* Set up mass storage device to support on demand paging */ - -#if defined(CONFIG_PAGING) - if (lpc313x_pginitialize) - { - lpc313x_pginitialize(); - } -#endif -} +/************************************************************************************ + * configs/ea3131/src/up_boot.c + * arch/arm/src/board/up_boot.c + * + * Copyright (C) 2009 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name NuttX nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ************************************************************************************/ + +/************************************************************************************ + * Included Files + ************************************************************************************/ + +#include + +#include + +#include + +#include "up_arch.h" +#include "up_internal.h" +#include "lpc31_internal.h" +#include "ea3131_internal.h" + +/************************************************************************************ + * Definitions + ************************************************************************************/ + +/************************************************************************************ + * Private Functions + ************************************************************************************/ + +/************************************************************************************ + * Public Functions + ************************************************************************************/ + +/************************************************************************************ + * Name: lpc31_boardinitialize + * + * Description: + * All LPC31XX architectures must provide the following entry point. This entry + * point is called early in the intitialization -- after all memory has been + * configured and mapped but before any devices have been initialized. + * + ************************************************************************************/ + +void lpc31_boardinitialize(void) +{ + /* Initialize configured, external memory resources */ + +#ifdef CONFIG_LPC31XX_EXTSDRAM + lpc31_meminitialize(); +#endif + + /* Configure SPI chip selects if 1) SPI is not disabled, and 2) the weak function + * lpc31_spiinitialize() has been brought into the link. + */ + +#if defined(CONFIG_LPC31XX_SPI) + if (lpc31_spiinitialize) + { + lpc31_spiinitialize(); + } +#endif + + /* Initialize USB is 1) USBDEV is selected, 2) the USB controller is not + * disabled, and 3) the weak function lpc31_usbinitialize() has been brought + * into the build. + */ + +#if defined(CONFIG_USBDEV) && defined(CONFIG_LPC31XX_USB) + if (lpc31_usbinitialize) + { + lpc31_usbinitialize(); + } +#endif + + /* Configure on-board LEDs if LED support has been selected. */ + +#ifdef CONFIG_ARCH_LEDS + up_ledinit(); +#endif + + /* Set up mass storage device to support on demand paging */ + +#if defined(CONFIG_PAGING) + if (lpc31_pginitialize) + { + lpc31_pginitialize(); + } +#endif +} diff --git a/nuttx/configs/ea3131/src/up_clkinit.c b/nuttx/configs/ea3131/src/up_clkinit.c index 8277e633b..a0eba9c75 100755 --- a/nuttx/configs/ea3131/src/up_clkinit.c +++ b/nuttx/configs/ea3131/src/up_clkinit.c @@ -44,8 +44,8 @@ #include -#include "lpc313x_cgu.h" -#include "lpc313x_cgudrvr.h" +#include "lpc31_cgu.h" +#include "lpc31_cgudrvr.h" /**************************************************************************** * Definitions @@ -284,7 +284,7 @@ * 11 - DOMAIN_SYSCLKO FFAST - - */ -const struct lpc313x_clkinit_s g_boardclks = +const struct lpc31_clkinit_s g_boardclks = { /* Domain 0 (DOMAINID_SYS), Clocks 0 - 29, Fraction dividers 0-6 */ diff --git a/nuttx/configs/ea3131/src/up_fillpage.c b/nuttx/configs/ea3131/src/up_fillpage.c index 2d3412bef..531675aa0 100755 --- a/nuttx/configs/ea3131/src/up_fillpage.c +++ b/nuttx/configs/ea3131/src/up_fillpage.c @@ -58,7 +58,7 @@ # include # include # include -# include "lpc313x_internal.h" +# include "lpc31_internal.h" # endif #endif @@ -85,8 +85,8 @@ # undef CONFIG_PAGING_SDSLOT # endif #else - /* Add configuration for new LPC313X boards here */ -# error "Unrecognized LPC313X board" + /* Add configuration for new LPC31XX boards here */ +# error "Unrecognized LPC31XX board" # undef CONFIG_PAGING_SDSLOT # undef HAVE_SD # undef HAVE_SPINOR @@ -122,7 +122,7 @@ * is not enabled. */ -# if defined(CONFIG_DISABLE_MOUNTPOINT) || !defined(CONFIG_LPC313X_MCI) +# if defined(CONFIG_DISABLE_MOUNTPOINT) || !defined(CONFIG_LPC31XX_MCI) # ifdef CONFIG_PAGING_SDSLOT # error "Mountpoints and/or MCI disabled" # endif @@ -152,7 +152,7 @@ /* Verify that SPI support is enabld */ -#ifndef CONFIG_LPC313X_SPI +#ifndef CONFIG_LPC31XX_SPI # error "SPI support is not enabled" #endif @@ -219,7 +219,7 @@ static struct pg_source_s g_pgsrc; ****************************************************************************/ /**************************************************************************** - * Name: lpc313x_initsrc() + * Name: lpc31_initsrc() * * Description: * Initialize the source device that will support paging. @@ -230,7 +230,7 @@ static struct pg_source_s g_pgsrc; ****************************************************************************/ #if defined(CONFIG_PAGING_BINPATH) -static inline void lpc313x_initsrc(void) +static inline void lpc31_initsrc(void) { #ifdef CONFIG_PAGING_SDSLOT FAR struct sdio_dev_s *sdio; @@ -287,7 +287,7 @@ static inline void lpc313x_initsrc(void) } #elif defined(CONFIG_PAGING_M25PX) || defined(CONFIG_PAGING_AT45DB) -static inline void lpc313x_initsrc(void) +static inline void lpc31_initsrc(void) { FAR struct spi_dev_s *spi; #ifdef CONFIG_DEBUG @@ -339,7 +339,7 @@ static inline void lpc313x_initsrc(void) } #else -# define lpc313x_initsrc() +# define lpc31_initsrc() #endif /**************************************************************************** @@ -425,7 +425,7 @@ int up_fillpage(FAR _TCB *tcb, FAR void *vpage) /* Perform initialization of the paging source device (if necessary) */ - lpc313x_initsrc(); + lpc31_initsrc(); /* Create an offset into the binary image that corresponds to the * virtual address. File offset 0 corresponds to PG_LOCKED_VBASE. @@ -448,7 +448,7 @@ int up_fillpage(FAR _TCB *tcb, FAR void *vpage) /* Perform initialization of the paging source device (if necessary) */ - lpc313x_initsrc(); + lpc31_initsrc(); /* Create an offset into the binary image that corresponds to the * virtual address. File offset 0 corresponds to PG_LOCKED_VBASE. @@ -493,21 +493,21 @@ int up_fillpage(FAR _TCB *tcb, FAR void *vpage, up_pgcallback_t pg_callback) #endif /* CONFIG_PAGING_BLOCKINGFILL */ /************************************************************************************ - * Name: lpc313x_pginitialize + * Name: lpc31_pginitialize * * Description: * Set up mass storage device to support on demand paging. * ************************************************************************************/ -void weak_function lpc313x_pginitialize(void) +void weak_function lpc31_pginitialize(void) { /* This initialization does nothing in this example setup. But this function is * where you might, for example: * * - Initialize and configure a mass storage device to support on-demand paging. * This might be, perhaps an SD card or NAND memory. An SPI FLASH would probably - * already have been configured by lpc313x_spiinitialize(void); + * already have been configured by lpc31_spiinitialize(void); * - Set up resources to support up_fillpage() operation. For example, perhaps the * the text image is stored in a named binary file. In this case, the virtual * text addresses might map to offsets into that file. diff --git a/nuttx/configs/ea3131/src/up_leds.c b/nuttx/configs/ea3131/src/up_leds.c index 43a9847db..a0bec01b0 100755 --- a/nuttx/configs/ea3131/src/up_leds.c +++ b/nuttx/configs/ea3131/src/up_leds.c @@ -49,7 +49,7 @@ #include "chip.h" #include "up_arch.h" #include "up_internal.h" -#include "lpc313x_internal.h" +#include "lpc31_internal.h" /**************************************************************************** * Definitions diff --git a/nuttx/configs/ea3131/src/up_mem.c b/nuttx/configs/ea3131/src/up_mem.c index 956e3ee75..1559468ac 100755 --- a/nuttx/configs/ea3131/src/up_mem.c +++ b/nuttx/configs/ea3131/src/up_mem.c @@ -54,12 +54,12 @@ #include "chip.h" #include "up_arch.h" -#include "lpc313x_syscreg.h" -#include "lpc313x_cgudrvr.h" -#include "lpc313x_mpmc.h" +#include "lpc31_syscreg.h" +#include "lpc31_cgudrvr.h" +#include "lpc31_mpmc.h" #include "ea3131_internal.h" -#ifdef CONFIG_LPC313X_EXTSDRAM +#ifdef CONFIG_LPC31XX_EXTSDRAM /**************************************************************************** * Pre-processor Definitions @@ -103,7 +103,7 @@ ****************************************************************************/ /**************************************************************************** - * Name: lpc313x_sdraminitialize + * Name: lpc31_sdraminitialize * * Description: * Configure SDRAM on the EA3131 board @@ -155,7 +155,7 @@ * ****************************************************************************/ -static void lpc313x_sdraminitialize(void) +static void lpc31_sdraminitialize(void) { uint32_t tmp; uint32_t regval; @@ -164,10 +164,10 @@ static void lpc313x_sdraminitialize(void) * replaced with an apriori value. */ -#ifdef CONFIG_LPC313X_SDRAMHCLK -# define HCLK CONFIG_LPC313X_SDRAMHCLK +#ifdef CONFIG_LPC31XX_SDRAMHCLK +# define HCLK CONFIG_LPC31XX_SDRAMHCLK #else - uint32_t hclk = lpc313x_clkfreq(CLKID_MPMCCFGCLK2, DOMAINID_SYS); + uint32_t hclk = lpc31_clkfreq(CLKID_MPMCCFGCLK2, DOMAINID_SYS); # define HCLK hclk #endif @@ -175,7 +175,7 @@ static void lpc313x_sdraminitialize(void) #if 0 uint32_t hclk2 = hclk; - if (((getreg32(LPC313X_MPMC_CONFIG) & MPMC_CONFIG_CLK)) != 0) + if (((getreg32(LPC31_MPMC_CONFIG) & MPMC_CONFIG_CLK)) != 0) { hclk2 >>= 1; } @@ -187,45 +187,45 @@ static void lpc313x_sdraminitialize(void) /* Set command delay startergy */ - putreg32(MPMC_DYNREADCONFIG_CMDDEL, LPC313X_MPMC_DYNREADCONFIG); + putreg32(MPMC_DYNREADCONFIG_CMDDEL, LPC31_MPMC_DYNREADCONFIG); /* Configure device config register nSDCE0 for proper width SDRAM */ putreg32((MPMC_DYNCONFIG0_MDSDRAM|MPMC_DYNCONFIG_HP16_32MX16), - LPC313X_MPMC_DYNCONFIG0); + LPC31_MPMC_DYNCONFIG0); putreg32((MPMC_DYNRASCAS0_RAS2CLK|MPMC_DYNRASCAS0_CAS2CLK), - LPC313X_MPMC_DYNRASCAS0); + LPC31_MPMC_DYNRASCAS0); /* Min 20ns program 1 so that at least 2 HCLKs are used */ putreg32(NS2HCLKS(EA3131_SDRAM_TRP, HCLK2, MPMC_DYNTRP_MASK), - LPC313X_MPMC_DYNTRP); + LPC31_MPMC_DYNTRP); putreg32(NS2HCLKS(EA3131_SDRAM_TRAS, HCLK2, MPMC_DYNTRAS_MASK), - LPC313X_MPMC_DYNTRAS); + LPC31_MPMC_DYNTRAS); putreg32(NS2HCLKS(EA3131_SDRAM_TREX, HCLK2, MPMC_DYNTSREX_MASK), - LPC313X_MPMC_DYNTSREX); + LPC31_MPMC_DYNTSREX); putreg32(EA3131_SDRAM_TARP, - LPC313X_MPMC_DYNTAPR); + LPC31_MPMC_DYNTAPR); putreg32(NS2HCLKS(EA3131_SDRAM_TDAL, HCLK2, MPMC_DYNTDAL_MASK), - LPC313X_MPMC_DYNTDAL); + LPC31_MPMC_DYNTDAL); putreg32(NS2HCLKS(EA3131_SDRAM_TWR, HCLK2, MPMC_DYNTWR_MASK), - LPC313X_MPMC_DYNTWR); + LPC31_MPMC_DYNTWR); putreg32(NS2HCLKS(EA3131_SDRAM_TRC, HCLK2, MPMC_DYNTRC_MASK), - LPC313X_MPMC_DYNTRC); + LPC31_MPMC_DYNTRC); putreg32(NS2HCLKS(EA3131_SDRAM_TRFC, HCLK2, MPMC_DYNTRFC_MASK), - LPC313X_MPMC_DYNTRFC); + LPC31_MPMC_DYNTRFC); putreg32(NS2HCLKS(EA3131_SDRAM_TXSR, HCLK2, MPMC_DYNTXSR_MASK), - LPC313X_MPMC_DYNTXSR); + LPC31_MPMC_DYNTXSR); putreg32(NS2HCLKS(EA3131_SDRAM_TRRD, HCLK2, MPMC_DYNTRRD_MASK), - LPC313X_MPMC_DYNTRRD); + LPC31_MPMC_DYNTRRD); putreg32(NS2HCLKS(EA3131_SDRAM_TMRD, HCLK2, MPMC_DYNTMRD_MASK), - LPC313X_MPMC_DYNTMRD); + LPC31_MPMC_DYNTMRD); up_udelay(100); /* Issue continuous NOP commands */ putreg32((MPMC_DYNCONTROL_CE|MPMC_DYNCONTROL_CS|MPMC_DYNCONTROL_INOP), - LPC313X_MPMC_DYNCONTROL); + LPC31_MPMC_DYNCONTROL); /* Load ~200us delay value to timer1 */ @@ -234,14 +234,14 @@ static void lpc313x_sdraminitialize(void) /* Issue a "pre-charge all" command */ putreg32((MPMC_DYNCONTROL_CE|MPMC_DYNCONTROL_CS|MPMC_DYNCONTROL_IPALL), - LPC313X_MPMC_DYNCONTROL); + LPC31_MPMC_DYNCONTROL); /* Minimum refresh pulse interval (tRFC) for MT48LC32M16A2=80nsec, * 100nsec provides more than adequate interval. */ putreg32(NS2HCLKS(EA3131_SDRAM_REFRESH, HCLK, MPMC_DYNREFRESH_TIMER_MASK), - LPC313X_MPMC_DYNREFRESH); + LPC31_MPMC_DYNREFRESH); /* Load ~250us delay value to timer1 */ @@ -253,12 +253,12 @@ static void lpc313x_sdraminitialize(void) */ putreg32(NS2HCLKS(EA3131_SDRAM_OPERREFRESH, HCLK, MPMC_DYNREFRESH_TIMER_MASK), - LPC313X_MPMC_DYNREFRESH); + LPC31_MPMC_DYNREFRESH); /* Select mode register update mode */ putreg32((MPMC_DYNCONTROL_CE|MPMC_DYNCONTROL_CS|MPMC_DYNCONTROL_IMODE), - LPC313X_MPMC_DYNCONTROL); + LPC31_MPMC_DYNCONTROL); /* Program the SDRAM internal mode registers on bank nSDCE0 and reconfigure * the SDRAM chips. Bus speeds up to 90MHz requires use of a CAS latency = 2. @@ -266,26 +266,26 @@ static void lpc313x_sdraminitialize(void) * 16bit mode */ - tmp = getreg32(LPC313X_EXTSDRAM0_VSECTION | (0x23 << 13)); + tmp = getreg32(LPC31_EXTSDRAM0_VSECTION | (0x23 << 13)); putreg32((MPMC_DYNCONFIG0_MDSDRAM|MPMC_DYNCONFIG_HP16_32MX16), - LPC313X_MPMC_DYNCONFIG0); + LPC31_MPMC_DYNCONFIG0); putreg32((MPMC_DYNRASCAS0_RAS2CLK|MPMC_DYNRASCAS0_CAS2CLK), - LPC313X_MPMC_DYNRASCAS0); + LPC31_MPMC_DYNRASCAS0); /* Select normal operating mode */ putreg32((MPMC_DYNCONTROL_CE|MPMC_DYNCONTROL_CS|MPMC_DYNCONTROL_INORMAL), - LPC313X_MPMC_DYNCONTROL); + LPC31_MPMC_DYNCONTROL); /* Enable buffers */ - regval = getreg32(LPC313X_MPMC_DYNCONFIG0); + regval = getreg32(LPC31_MPMC_DYNCONFIG0); regval |= MPMC_DYNCONFIG0_B; - putreg32(regval, LPC313X_MPMC_DYNCONFIG0); + putreg32(regval, LPC31_MPMC_DYNCONFIG0); putreg32((MPMC_DYNCONTROL_INORMAL|MPMC_DYNCONTROL_CS), - LPC313X_MPMC_DYNCONTROL); + LPC31_MPMC_DYNCONTROL); } /**************************************************************************** @@ -293,14 +293,14 @@ static void lpc313x_sdraminitialize(void) ****************************************************************************/ /**************************************************************************** - * Name: lpc313x_meminitialize + * Name: lpc31_meminitialize * * Description: * Initialize external memory resources (sram, sdram, nand, nor, etc.) * ****************************************************************************/ -void lpc313x_meminitialize(void) +void lpc31_meminitialize(void) { /* Configure the LCD pins in external bus interface (EBI/MPMC) memory mode. * @@ -326,34 +326,34 @@ void lpc313x_meminitialize(void) * LCD_DB_15 -> EBI_A_15 */ - putreg32(SYSCREG_MUX_LCDEBISEL_EBIMPMC, LPC313X_SYSCREG_MUX_LCDEBISEL); + putreg32(SYSCREG_MUX_LCDEBISEL_EBIMPMC, LPC31_SYSCREG_MUX_LCDEBISEL); /* Enable EBI clock */ - lpc313x_enableclock(CLKID_EBICLK); + lpc31_enableclock(CLKID_EBICLK); /* Enable MPMC controller clocks */ - lpc313x_enableclock(CLKID_MPMCCFGCLK); - lpc313x_enableclock(CLKID_MPMCCFGCLK2); - lpc313x_enableclock(CLKID_MPMCCFGCLK3); + lpc31_enableclock(CLKID_MPMCCFGCLK); + lpc31_enableclock(CLKID_MPMCCFGCLK2); + lpc31_enableclock(CLKID_MPMCCFGCLK3); /* Enable the external memory controller */ - putreg32(MPMC_CONTROL_E, LPC313X_MPMC_CONTROL); + putreg32(MPMC_CONTROL_E, LPC31_MPMC_CONTROL); /* Force HCLK to MPMC_CLK to 1:1 ratio, little-endian mode */ - putreg32(0, LPC313X_MPMC_CONFIG); + putreg32(0, LPC31_MPMC_CONFIG); /* Set MPMC delay based on trace lengths between SDRAM and the chip * and on the delay strategy used for SDRAM. */ - putreg32(EA3131_MPMC_DELAY, LPC313X_SYSCREG_MPMC_DELAYMODES); + putreg32(EA3131_MPMC_DELAY, LPC31_SYSCREG_MPMC_DELAYMODES); /* Configure Micron MT48LC32M16A2 SDRAM on the EA3131 board */ - lpc313x_sdraminitialize(); + lpc31_sdraminitialize(); } -#endif /* CONFIG_LPC313X_EXTSDRAM */ +#endif /* CONFIG_LPC31XX_EXTSDRAM */ diff --git a/nuttx/configs/ea3131/src/up_nsh.c b/nuttx/configs/ea3131/src/up_nsh.c index c0848c9f1..c8dbf017b 100755 --- a/nuttx/configs/ea3131/src/up_nsh.c +++ b/nuttx/configs/ea3131/src/up_nsh.c @@ -45,12 +45,12 @@ #include #include -#ifdef CONFIG_LPC313X_MCI +#ifdef CONFIG_LPC31XX_MCI # include # include #endif -#include "lpc313x_internal.h" +#include "lpc31_internal.h" /**************************************************************************** * Pre-Processor Definitions @@ -71,8 +71,9 @@ # define CONFIG_NSH_MMCSDSLOTNO 0 # endif #else - /* Add configuration for new LPC313X boards here */ -# error "Unrecognized LPC313X board" + /* Add configuration for new LPC31XX boards here */ + +# error "Unrecognized LPC31XX board" # undef CONFIG_NSH_HAVEUSBDEV # undef CONFIG_NSH_HAVEMMCSD #endif @@ -87,7 +88,7 @@ * is not enabled. */ -#if defined(CONFIG_DISABLE_MOUNTPOINT) || !defined(CONFIG_LPC313X_MCI) +#if defined(CONFIG_DISABLE_MOUNTPOINT) || !defined(CONFIG_LPC31XX_MCI) # undef CONFIG_NSH_HAVEMMCSD #endif diff --git a/nuttx/configs/ea3131/src/up_spi.c b/nuttx/configs/ea3131/src/up_spi.c index c2df60a48..7755e55b4 100755 --- a/nuttx/configs/ea3131/src/up_spi.c +++ b/nuttx/configs/ea3131/src/up_spi.c @@ -2,7 +2,7 @@ * configs/ea3131/src/up_spi.c * arch/arm/src/board/up_spi.c * - * Copyright (C) 2009-2010 Gregory Nutt. All rights reserved. + * Copyright (C) 2009-2011 Gregory Nutt. All rights reserved. * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without @@ -49,12 +49,12 @@ #include "up_arch.h" #include "chip.h" -#include "lpc313x_internal.h" +#include "lpc31_internal.h" #include "ea3131_internal.h" -#ifdef CONFIG_LPC313X_SPI -#if 0 /* At present, EA3131 specific logic is hard-coded in the file lpc313x_spi.c - * in arch/arm/src/lpc313x */ +#ifdef CONFIG_LPC31XX_SPI +#if 0 /* At present, EA3131 specific logic is hard-coded in the file lpc31_spi.c + * in arch/arm/src/lpc31xx */ /************************************************************************************ * Definitions @@ -87,14 +87,14 @@ ************************************************************************************/ /************************************************************************************ - * Name: lpc313x_spiinitialize + * Name: lpc31_spiinitialize * * Description: * Called to configure SPI chip select GPIO pins for the EA3131 board. * ************************************************************************************/ -void weak_function lpc313x_spiinitialize(void) +void weak_function lpc31_spiinitialize(void) { /* NOTE: Clocking for SPI has already been provided. Pin configuration is performed * on-the-fly, so no additional setup is required. @@ -102,19 +102,19 @@ void weak_function lpc313x_spiinitialize(void) } /************************************************************************************ - * Name: lpc313x_spiselect and lpc313x_spistatus + * Name: lpc31_spiselect and lpc31_spistatus * * Description: - * The external functions, lpc313x_spiselect and lpc313x_spistatus must be + * The external functions, lpc31_spiselect and lpc31_spistatus must be * provided by board-specific logic. They are implementations of the select * and status methods of the SPI interface defined by struct spi_ops_s (see * include/nuttx/spi.h). All other methods (including up_spiinitialize()) - * are provided by common LPC313X logic. To use this common SPI logic on your + * are provided by common LPC31XX logic. To use this common SPI logic on your * board: * - * 1. Provide logic in lpc313x_boardinitialize() to configure SPI chip select + * 1. Provide logic in lpc31_boardinitialize() to configure SPI chip select * pins. - * 2. Provide lpc313x_spiselect() and lpc313x_spistatus() functions in your + * 2. Provide lpc31_spiselect() and lpc31_spistatus() functions in your * board-specific logic. These functions will perform chip selection and * status operations using GPIOs in the way your board is configured. * 3. Add a calls to up_spiinitialize() in your low level application @@ -126,17 +126,17 @@ void weak_function lpc313x_spiinitialize(void) * ************************************************************************************/ -void lpc313x_spiselect(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected) +void lpc31_spiselect(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected) { spidbg("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert"); #warning "Missing logic" } -uint8_t lpc313x_spistatus(FAR struct spi_dev_s *dev, enum spi_dev_e devid) +uint8_t lpc31_spistatus(FAR struct spi_dev_s *dev, enum spi_dev_e devid) { return SPI_STATUS_PRESENT; } #endif /* 0 */ -#endif /* CONFIG_LPC313X_SPI */ +#endif /* CONFIG_LPC31XX_SPI */ diff --git a/nuttx/configs/ea3131/tools/armusbocd.cfg b/nuttx/configs/ea3131/tools/armusbocd.cfg index de17e8b0e..733e3768c 100755 --- a/nuttx/configs/ea3131/tools/armusbocd.cfg +++ b/nuttx/configs/ea3131/tools/armusbocd.cfg @@ -1,34 +1,34 @@ -#daemon configuration -telnet_port 4444 -gdb_port 3333 - -#interface -interface ft2232 -ft2232_device_desc "Olimex OpenOCD JTAG A" -ft2232_layout "olimex-jtag" -ft2232_vid_pid 0x15BA 0x0003 -jtag_speed 2 - -#use combined on interfaces or targets that can't set TRST/SRST separately -reset_config trst_and_srst separate - -#jtag scan chain -#format L IRC IRCM IDCODE (Length, IR Capture, IR Capture Mask, IDCODE) -jtag_device 4 0x1 0xf 0xe - -#target configuration -daemon_startup reset - -#target -#target arm9ejs -target arm926ejs little run_and_halt 0 arm926ejs -run_and_halt_time 0 30 - -#target_script 0 reset oocd_flash2138.script -working_area 0 0x1102800 0x60000 nobackup - -#flash configuration -#flash bank lpc2000 0x0 0x40000 0 0 0 lpc2000_v2 12000 calc_checksum - -# For more information about the configuration files, take a look at: -# http://openfacts.berlios.de/index-en.phtml?title=Open+On-Chip+Debugger +#daemon configuration +telnet_port 4444 +gdb_port 3333 + +#interface +interface ft2232 +ft2232_device_desc "Olimex OpenOCD JTAG A" +ft2232_layout "olimex-jtag" +ft2232_vid_pid 0x15BA 0x0003 +jtag_speed 2 + +#use combined on interfaces or targets that can't set TRST/SRST separately +reset_config trst_and_srst separate + +#jtag scan chain +#format L IRC IRCM IDCODE (Length, IR Capture, IR Capture Mask, IDCODE) +jtag_device 4 0x1 0xf 0xe + +#target configuration +daemon_startup reset + +#target +#target arm9ejs +target arm926ejs little run_and_halt 0 arm926ejs +run_and_halt_time 0 30 + +#target_script 0 reset oocd_flash2138.script +working_area 0 0x1102800 0x60000 nobackup + +#flash configuration +#flash bank lpc2000 0x0 0x40000 0 0 0 lpc2000_v2 12000 calc_checksum + +# For more information about the configuration files, take a look at: +# http://openfacts.berlios.de/index-en.phtml?title=Open+On-Chip+Debugger diff --git a/nuttx/configs/ea3131/tools/lpchdr.c b/nuttx/configs/ea3131/tools/lpchdr.c index 99b820bb0..9325c8813 100755 --- a/nuttx/configs/ea3131/tools/lpchdr.c +++ b/nuttx/configs/ea3131/tools/lpchdr.c @@ -1,297 +1,297 @@ -/************************************************************************************ - * configs/ea3131/tools/lpchdr.c - * - * Copyright (C) 2010 Gregory Nutt. All rights reserved. - * Author: Gregory Nutt - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name NuttX nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - ************************************************************************************/ - -/************************************************************************************ - * Included Files - ************************************************************************************/ - -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include "lpchdr.h" - -/************************************************************************************ - * Pre-processor Definitions - ************************************************************************************/ - -#define IO_BUF_SIZE 1024 -#define HDR_SIZE 0x80 -#define HDR_CRC_SIZE 0x6c - -/************************************************************************************ - * Private Data - ************************************************************************************/ - -static const char *g_infile; -static const char *g_outfile; - -/************************************************************************************ - * Private Functions - ************************************************************************************/ - -static void show_usage(const char *progname, int exitcode) -{ - fprintf(stderr, "%s -o \n", progname); - exit(exitcode); -} - -static void parse_args(int argc, char **argv) -{ - int ch; - - while ((ch = getopt(argc, argv, ":o:")) >= 0) - { - switch (ch) - { - case 'o': - g_outfile = optarg; - break; - - case ':': - fprintf(stderr, "Missing option argumen\n"); - show_usage(argv[0], 1); - - case '?': - default: - fprintf(stderr, "Unrecognized option\n"); - show_usage(argv[0], 1); - } - } - - if (optind >= argc) - { - fprintf(stderr, "Missing binary input file name\n"); - show_usage(argv[0], 1); - } - - g_infile = argv[optind]; - optind++; - - if (optind < argc) - { - fprintf(stderr, "Garbage at the end of the command line\n"); - show_usage(argv[0], 1); - } -} - -static inline uint32_t infilecrc32(int infd, size_t len, size_t padlen) -{ - off_t offset; - uint8_t buffer[IO_BUF_SIZE]; - ssize_t nbytes; - size_t bytesread; - uint32_t crc; - - offset = lseek(infd, 0, SEEK_SET); - if (offset == (off_t)-1) - { - fprintf(stderr, "lseek failed: %s\n", strerror(errno)); - exit(4); - } - - crc = 0; - for (bytesread = 0; bytesread < len; bytesread += nbytes) - { - nbytes = read(infd, buffer, IO_BUF_SIZE); - if (nbytes < 0) - { - fprintf(stderr, "read failed: %s\n", strerror(errno)); - exit(4); - } - else if (nbytes == 0) - { - fprintf(stderr, "Unexpected end-of-file: %s\n", strerror(errno)); - exit(4); - } - else - { - crc = crc32part(buffer, nbytes, crc); - } - } - - /* Add the zero-padding at the end of the binary in the CRC */ - - memset(buffer, 0, IO_BUF_SIZE); - return crc32part(buffer, padlen, crc); -} - -static inline void writefile(int infd, int outfd, size_t len, size_t padlen) -{ - off_t offset; - uint8_t buffer[IO_BUF_SIZE]; - ssize_t nbytesread; - ssize_t nbyteswritten; - size_t totalread; - - offset = lseek(infd, 0, SEEK_SET); - if (offset == (off_t)-1) - { - fprintf(stderr, "lseek failed: %s\n", strerror(errno)); - exit(4); - } - - for (totalread = 0; totalread < len; totalread += nbytesread) - { - nbytesread = read(infd, buffer, IO_BUF_SIZE); - if (nbytesread < 0) - { - fprintf(stderr, "read failed: %s\n", strerror(errno)); - exit(4); - } - else if (nbytesread == 0) - { - fprintf(stderr, "Unexpected end-of-file: %s\n", strerror(errno)); - exit(4); - } - else - { - nbyteswritten = write(outfd, buffer, nbytesread); - if (nbyteswritten < 0) - { - fprintf(stderr, "write failed: %s\n", strerror(errno)); - exit(4); - } - else if (nbyteswritten != nbytesread) - { - fprintf(stderr, "Short writes not handled\n"); - exit(4); - } - } - } - - /* Write the zero-padding at the end of the binary */ - - memset(buffer, 0, IO_BUF_SIZE); - nbyteswritten = write(outfd, buffer, padlen); - if (nbyteswritten < 0) - { - fprintf(stderr, "write failed: %s\n", strerror(errno)); - exit(4); - } - else if (nbyteswritten != padlen) - { - fprintf(stderr, "Short writes not handled\n"); - exit(4); - } -} - -/************************************************************************************ - * Public Functions - ************************************************************************************/ - -int main(int argc, char **argv, char **envp) -{ - struct lpc313x_header_s g_hdr; - struct stat buf; - ssize_t nbytes; - size_t padlen; - int infd; - int outfd; - int ret; - - /* Parse arguments */ - - parse_args(argc, argv); - - /* Open files */ - - infd = open(g_infile, O_RDONLY); - if (infd < 0) - { - fprintf(stderr, "Failed to open %s for reading: %s\n", g_infile, strerror(errno)); - exit(2); - } - - outfd = open(g_outfile, O_WRONLY|O_CREAT|O_TRUNC, 0644); - if (outfd < 0) - { - fprintf(stderr, "Failed to open %s for writing: %s\n", g_outfile, strerror(errno)); - exit(2); - } - - /* Get the size of the binary file */ - - ret = fstat(infd, &buf); - if (ret < 0) - { - fprintf(stderr, "stat of %s failed: %s\n", g_infile, strerror(errno)); - exit(3); - } - - /* Initialize the header */ - - memset(&g_hdr, 0, sizeof(struct lpc313x_header_s)); - g_hdr.vector = 0xea00001e; /* b 0x11029080 */ - g_hdr.magic = 0x41676d69; -#if 1 /* CRC doesn't seem to be functional */ - g_hdr.imageType = 0x0000000a; -#else - g_hdr.imageType = 0x0000000b; -#endif - g_hdr.imageLength = (buf.st_size + sizeof(struct lpc313x_header_s) + 511) & ~0x1ff; - - /* This is how much we must pad at the end of the binary image. */ - - padlen = g_hdr.imageLength - buf.st_size; - - /* Calculate CRCs */ - - g_hdr.execution_crc32 = infilecrc32(infd, buf.st_size, padlen); - g_hdr.header_crc32 = crc32((const uint8_t*)&g_hdr, HDR_CRC_SIZE); - - /* Write the header */ - - nbytes = write(outfd, &g_hdr, HDR_SIZE); - if (nbytes != 0x80) - { - fprintf(stderr, "write of header to of %s failed: %s\n", g_outfile, strerror(errno)); - exit(4); - } - - /* Copy the input file to the output */ - - writefile(infd, outfd, buf.st_size, padlen); - close(infd); - close(outfd); - return 0; -} - - +/************************************************************************************ + * configs/ea3131/tools/lpchdr.c + * + * Copyright (C) 2010-2011 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name NuttX nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ************************************************************************************/ + +/************************************************************************************ + * Included Files + ************************************************************************************/ + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include "lpchdr.h" + +/************************************************************************************ + * Pre-processor Definitions + ************************************************************************************/ + +#define IO_BUF_SIZE 1024 +#define HDR_SIZE 0x80 +#define HDR_CRC_SIZE 0x6c + +/************************************************************************************ + * Private Data + ************************************************************************************/ + +static const char *g_infile; +static const char *g_outfile; + +/************************************************************************************ + * Private Functions + ************************************************************************************/ + +static void show_usage(const char *progname, int exitcode) +{ + fprintf(stderr, "%s -o \n", progname); + exit(exitcode); +} + +static void parse_args(int argc, char **argv) +{ + int ch; + + while ((ch = getopt(argc, argv, ":o:")) >= 0) + { + switch (ch) + { + case 'o': + g_outfile = optarg; + break; + + case ':': + fprintf(stderr, "Missing option argumen\n"); + show_usage(argv[0], 1); + + case '?': + default: + fprintf(stderr, "Unrecognized option\n"); + show_usage(argv[0], 1); + } + } + + if (optind >= argc) + { + fprintf(stderr, "Missing binary input file name\n"); + show_usage(argv[0], 1); + } + + g_infile = argv[optind]; + optind++; + + if (optind < argc) + { + fprintf(stderr, "Garbage at the end of the command line\n"); + show_usage(argv[0], 1); + } +} + +static inline uint32_t infilecrc32(int infd, size_t len, size_t padlen) +{ + off_t offset; + uint8_t buffer[IO_BUF_SIZE]; + ssize_t nbytes; + size_t bytesread; + uint32_t crc; + + offset = lseek(infd, 0, SEEK_SET); + if (offset == (off_t)-1) + { + fprintf(stderr, "lseek failed: %s\n", strerror(errno)); + exit(4); + } + + crc = 0; + for (bytesread = 0; bytesread < len; bytesread += nbytes) + { + nbytes = read(infd, buffer, IO_BUF_SIZE); + if (nbytes < 0) + { + fprintf(stderr, "read failed: %s\n", strerror(errno)); + exit(4); + } + else if (nbytes == 0) + { + fprintf(stderr, "Unexpected end-of-file: %s\n", strerror(errno)); + exit(4); + } + else + { + crc = crc32part(buffer, nbytes, crc); + } + } + + /* Add the zero-padding at the end of the binary in the CRC */ + + memset(buffer, 0, IO_BUF_SIZE); + return crc32part(buffer, padlen, crc); +} + +static inline void writefile(int infd, int outfd, size_t len, size_t padlen) +{ + off_t offset; + uint8_t buffer[IO_BUF_SIZE]; + ssize_t nbytesread; + ssize_t nbyteswritten; + size_t totalread; + + offset = lseek(infd, 0, SEEK_SET); + if (offset == (off_t)-1) + { + fprintf(stderr, "lseek failed: %s\n", strerror(errno)); + exit(4); + } + + for (totalread = 0; totalread < len; totalread += nbytesread) + { + nbytesread = read(infd, buffer, IO_BUF_SIZE); + if (nbytesread < 0) + { + fprintf(stderr, "read failed: %s\n", strerror(errno)); + exit(4); + } + else if (nbytesread == 0) + { + fprintf(stderr, "Unexpected end-of-file: %s\n", strerror(errno)); + exit(4); + } + else + { + nbyteswritten = write(outfd, buffer, nbytesread); + if (nbyteswritten < 0) + { + fprintf(stderr, "write failed: %s\n", strerror(errno)); + exit(4); + } + else if (nbyteswritten != nbytesread) + { + fprintf(stderr, "Short writes not handled\n"); + exit(4); + } + } + } + + /* Write the zero-padding at the end of the binary */ + + memset(buffer, 0, IO_BUF_SIZE); + nbyteswritten = write(outfd, buffer, padlen); + if (nbyteswritten < 0) + { + fprintf(stderr, "write failed: %s\n", strerror(errno)); + exit(4); + } + else if (nbyteswritten != padlen) + { + fprintf(stderr, "Short writes not handled\n"); + exit(4); + } +} + +/************************************************************************************ + * Public Functions + ************************************************************************************/ + +int main(int argc, char **argv, char **envp) +{ + struct lpc31_header_s g_hdr; + struct stat buf; + ssize_t nbytes; + size_t padlen; + int infd; + int outfd; + int ret; + + /* Parse arguments */ + + parse_args(argc, argv); + + /* Open files */ + + infd = open(g_infile, O_RDONLY); + if (infd < 0) + { + fprintf(stderr, "Failed to open %s for reading: %s\n", g_infile, strerror(errno)); + exit(2); + } + + outfd = open(g_outfile, O_WRONLY|O_CREAT|O_TRUNC, 0644); + if (outfd < 0) + { + fprintf(stderr, "Failed to open %s for writing: %s\n", g_outfile, strerror(errno)); + exit(2); + } + + /* Get the size of the binary file */ + + ret = fstat(infd, &buf); + if (ret < 0) + { + fprintf(stderr, "stat of %s failed: %s\n", g_infile, strerror(errno)); + exit(3); + } + + /* Initialize the header */ + + memset(&g_hdr, 0, sizeof(struct lpc31_header_s)); + g_hdr.vector = 0xea00001e; /* b 0x11029080 */ + g_hdr.magic = 0x41676d69; +#if 1 /* CRC doesn't seem to be functional */ + g_hdr.imageType = 0x0000000a; +#else + g_hdr.imageType = 0x0000000b; +#endif + g_hdr.imageLength = (buf.st_size + sizeof(struct lpc31_header_s) + 511) & ~0x1ff; + + /* This is how much we must pad at the end of the binary image. */ + + padlen = g_hdr.imageLength - buf.st_size; + + /* Calculate CRCs */ + + g_hdr.execution_crc32 = infilecrc32(infd, buf.st_size, padlen); + g_hdr.header_crc32 = crc32((const uint8_t*)&g_hdr, HDR_CRC_SIZE); + + /* Write the header */ + + nbytes = write(outfd, &g_hdr, HDR_SIZE); + if (nbytes != 0x80) + { + fprintf(stderr, "write of header to of %s failed: %s\n", g_outfile, strerror(errno)); + exit(4); + } + + /* Copy the input file to the output */ + + writefile(infd, outfd, buf.st_size, padlen); + close(infd); + close(outfd); + return 0; +} + + diff --git a/nuttx/configs/ea3131/tools/lpchdr.h b/nuttx/configs/ea3131/tools/lpchdr.h index 036dc8728..46cc91076 100755 --- a/nuttx/configs/ea3131/tools/lpchdr.h +++ b/nuttx/configs/ea3131/tools/lpchdr.h @@ -1,105 +1,105 @@ -/************************************************************************************ - * configs/ea3131/tools/lpchdr.h - * - * Copyright (C) 2010 Gregory Nutt. All rights reserved. - * Author: Gregory Nutt - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name NuttX nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - ************************************************************************************/ - -#ifndef __CONFIGS_EA3131_TOOLS_BINFMT_H -#define __CONFIGS_EA3131_TOOLS_BINFMT_H - -/************************************************************************************ - * Included Files - ************************************************************************************/ - -#include - -/************************************************************************************ - * Definitions - ************************************************************************************/ - -/************************************************************************************ - * Public Types - ************************************************************************************/ - -struct lpc313x_header_s -{ - /* OFFS DESCRIPTION */ - uint32_t vector; /* 0x00 Valid ARM instruction. Usually this will be - * a branch instruction to entry point of the - * image. */ - uint32_t magic; /* 0x04 This field is used by boot ROM to detect a - * valid image header. This field should always - * be set to 0x41676d69. */ - uint32_t execution_crc32; /* 0x08 CRC32 value of execution part of the image. If - * the ‘image_type’ is set to ‘0xA’, this field - * is ignored by boot ROM. */ - uint32_t Reserved0[4]; /* 0x0c-0x18: Should be zero. */ - uint32_t imageType; /* 0x1c Specifies whether CRC check should be done - * on the image or not: - * 0xA – No CRC check required. - * 0xB – Do CRC32 check on both header and - * execution part of the image. */ - uint32_t imageLength; /* 0x20 Total image length including header rounded - * up to the nearest 512 byte boundary. In C - * language the field can be computed as: - * imageLength = (Actual length + 511) & ~0x1FF; */ - uint32_t releaseID; /* 0x24 Release or version number of the image. Note, - * this field is not used by boot ROM but is - * provided to track the image versions. */ - uint32_t buildTime; /* 0x28 Time (expressed in EPOC time format) at which - * image is built. Note, this field is not used - * by boot ROM but is provided to track the image - * versions. */ - uint32_t sbzBootParameter; /* 0x2c hould be zero. */ - uint32_t cust_reserved[15]; /* 0x30-0x68: Reserved for customer use (60 bytes) */ - uint32_t header_crc32; /* 0x6c CRC32 value of the header (bytes 0x00 to 0x6C - * of the image). If the ‘image_type’ is set - * to ‘0xA’, this field is ignored by boot ROM. */ - uint32_t Reserved1[4]; /* 0x70-0x7c: Should be zero. */ - /* 0x80 Start of program code (128Kb max). The final - * image has to be padded to the nearest 512 - * byte boundary */ -}; - -/************************************************************************************ - * Public data - ************************************************************************************/ - -/************************************************************************************ - * Public Functions - ************************************************************************************/ - -extern uint32_t crc32part(const uint8_t *src, size_t len, uint32_t crc32val); -extern uint32_t crc32(const uint8_t *src, size_t len); - -#endif /* __CONFIGS_EA3131_TOOLS_BINFMT_H */ - +/************************************************************************************ + * configs/ea3131/tools/lpchdr.h + * + * Copyright (C) 2010 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name NuttX nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ************************************************************************************/ + +#ifndef __CONFIGS_EA3131_TOOLS_LPCHDR_H +#define __CONFIGS_EA3131_TOOLS_LPCHDR_H + +/************************************************************************************ + * Included Files + ************************************************************************************/ + +#include + +/************************************************************************************ + * Definitions + ************************************************************************************/ + +/************************************************************************************ + * Public Types + ************************************************************************************/ + +struct lpc31_header_s +{ + /* OFFS DESCRIPTION */ + uint32_t vector; /* 0x00 Valid ARM instruction. Usually this will be + * a branch instruction to entry point of the + * image. */ + uint32_t magic; /* 0x04 This field is used by boot ROM to detect a + * valid image header. This field should always + * be set to 0x41676d69. */ + uint32_t execution_crc32; /* 0x08 CRC32 value of execution part of the image. If + * the ‘image_type’ is set to ‘0xA’, this field + * is ignored by boot ROM. */ + uint32_t Reserved0[4]; /* 0x0c-0x18: Should be zero. */ + uint32_t imageType; /* 0x1c Specifies whether CRC check should be done + * on the image or not: + * 0xA – No CRC check required. + * 0xB – Do CRC32 check on both header and + * execution part of the image. */ + uint32_t imageLength; /* 0x20 Total image length including header rounded + * up to the nearest 512 byte boundary. In C + * language the field can be computed as: + * imageLength = (Actual length + 511) & ~0x1FF; */ + uint32_t releaseID; /* 0x24 Release or version number of the image. Note, + * this field is not used by boot ROM but is + * provided to track the image versions. */ + uint32_t buildTime; /* 0x28 Time (expressed in EPOC time format) at which + * image is built. Note, this field is not used + * by boot ROM but is provided to track the image + * versions. */ + uint32_t sbzBootParameter; /* 0x2c hould be zero. */ + uint32_t cust_reserved[15]; /* 0x30-0x68: Reserved for customer use (60 bytes) */ + uint32_t header_crc32; /* 0x6c CRC32 value of the header (bytes 0x00 to 0x6C + * of the image). If the ‘image_type’ is set + * to ‘0xA’, this field is ignored by boot ROM. */ + uint32_t Reserved1[4]; /* 0x70-0x7c: Should be zero. */ + /* 0x80 Start of program code (128Kb max). The final + * image has to be padded to the nearest 512 + * byte boundary */ +}; + +/************************************************************************************ + * Public data + ************************************************************************************/ + +/************************************************************************************ + * Public Functions + ************************************************************************************/ + +extern uint32_t crc32part(const uint8_t *src, size_t len, uint32_t crc32val); +extern uint32_t crc32(const uint8_t *src, size_t len); + +#endif /* __CONFIGS_EA3131_TOOLS_LPCHDR_H */ + diff --git a/nuttx/configs/ea3131/usbserial/Make.defs b/nuttx/configs/ea3131/usbserial/Make.defs index 377c417c8..b1e236df8 100755 --- a/nuttx/configs/ea3131/usbserial/Make.defs +++ b/nuttx/configs/ea3131/usbserial/Make.defs @@ -37,23 +37,23 @@ include ${TOPDIR}/.config # Setup for the selected toolchain -ifeq ($(CONFIG_LPC313X_CODESOURCERYW),y) +ifeq ($(CONFIG_LPC31XX_CODESOURCERYW),y) # CodeSourcery under Windows CROSSDEV = arm-none-eabi- WINTOOL = y MAXOPTIMIZATION = -O2 endif -ifeq ($(CONFIG_LPC313X_CODESOURCERYL),y) +ifeq ($(CONFIG_LPC31XX_CODESOURCERYL),y) # CodeSourcery under Linux CROSSDEV = arm-none-eabi- MAXOPTIMIZATION = -O2 endif -ifeq ($(CONFIG_LPC313X_DEVKITARM),y) +ifeq ($(CONFIG_LPC31XX_DEVKITARM),y) # devkitARM under Windows CROSSDEV = arm-eabi- WINTOOL = y endif -ifeq ($(CONFIG_LPC313X_BUILDROOT),y) +ifeq ($(CONFIG_LPC31XX_BUILDROOT),y) # NuttX buildroot under Linux or Cygwin CROSSDEV = arm-elf- MAXOPTIMIZATION = -Os @@ -121,7 +121,7 @@ OBJEXT = .o LIBEXT = .a EXEEXT = -ifneq ($(CONFIG_LPC313X_BUILDROOT),y) +ifneq ($(CONFIG_LPC31XX_BUILDROOT),y) LDFLAGS += -nostartfiles -nodefaultlibs endif ifeq ($(CONFIG_DEBUG_SYMBOLS),y) diff --git a/nuttx/configs/ea3131/usbserial/defconfig b/nuttx/configs/ea3131/usbserial/defconfig index 29c169cfd..d06212649 100755 --- a/nuttx/configs/ea3131/usbserial/defconfig +++ b/nuttx/configs/ea3131/usbserial/defconfig @@ -50,13 +50,13 @@ # CONFIG_ENDIAN_BIG - define if big endian (default is little endian) # CONFIG_BOARD_LOOPSPERMSEC - for delay loops # CONFIG_DRAM_SIZE - For most ARM9 architectures, this describes the -# size of installed DRAM. For the LPC313X, it is used only to +# size of installed DRAM. For the LPC31XX, it is used only to # deterimine how to map the executable regions. It is SDRAM size # only if you are executing out of the external SDRAM; or it could # be NOR FLASH size, external SRAM size, or internal SRAM size. # CONFIG_DRAM_START - The start address of DRAM (physical) # CONFIG_DRAM_VSTART - The startaddress of DRAM (virtual) -# CONFIG_ARCH_IRQPRIO - The LPC313x supports interrupt prioritization +# CONFIG_ARCH_IRQPRIO - The LPC31xx supports interrupt prioritization # CONFIG_ARCH_INTERRUPTSTACK - This architecture supports an interrupt # stack. If defined, this symbol is the size of the interrupt # stack in bytes. If not defined, the user task stacks will be @@ -76,7 +76,7 @@ CONFIG_ARCH=arm CONFIG_ARCH_ARM=y CONFIG_ARCH_ARM926EJS=y -CONFIG_ARCH_CHIP=lpc313x +CONFIG_ARCH_CHIP=lpc31xx CONFIG_ARCH_CHIP_LPC3131=y CONFIG_ARCH_BOARD=ea3131 CONFIG_ARCH_BOARD_EA3131=y @@ -108,54 +108,54 @@ CONFIG_ARCH_ROMPGTABLE=y # Identify toolchain and linker options # -CONFIG_LPC313X_CODESOURCERYW=n -CONFIG_LPC313X_CODESOURCERYL=y -CONFIG_LPC313X_DEVKITARM=n -CONFIG_LPC313X_BUILDROOT=n +CONFIG_LPC31XX_CODESOURCERYW=n +CONFIG_LPC31XX_CODESOURCERYL=y +CONFIG_LPC31XX_DEVKITARM=n +CONFIG_LPC31XX_BUILDROOT=n # # Individual subsystems can be enabled: # -CONFIG_LPC313X_MCI=n -CONFIG_LPC313X_SPI=n -CONFIG_LPC313X_UART=y +CONFIG_LPC31XX_MCI=n +CONFIG_LPC31XX_SPI=n +CONFIG_LPC31XX_UART=y # # Exernal memory available on the board (see also CONFIG_MM_REGIONS) # -# CONFIG_LPC313X_EXTSRAM0 - Select if external SRAM0 is present -# CONFIG_LPC313X_EXTSRAM0HEAP - Select if external SRAM0 should be +# CONFIG_LPC31XX_EXTSRAM0 - Select if external SRAM0 is present +# CONFIG_LPC31XX_EXTSRAM0HEAP - Select if external SRAM0 should be # configured as part of the NuttX heap. -# CONFIG_LPC313X_EXTSRAM0SIZE - Size (in bytes) of the installed +# CONFIG_LPC31XX_EXTSRAM0SIZE - Size (in bytes) of the installed # external SRAM0 memory -# CONFIG_LPC313X_EXTSRAM1 - Select if external SRAM1 is present -# CONFIG_LPC313X_EXTSRAM1HEAP - Select if external SRAM1 should be +# CONFIG_LPC31XX_EXTSRAM1 - Select if external SRAM1 is present +# CONFIG_LPC31XX_EXTSRAM1HEAP - Select if external SRAM1 should be # configured as part of the NuttX heap. -# CONFIG_LPC313X_EXTSRAM1SIZE - Size (in bytes) of the installed +# CONFIG_LPC31XX_EXTSRAM1SIZE - Size (in bytes) of the installed # external SRAM1 memory -# CONFIG_LPC313X_EXTSDRAM - Select if external SDRAM is present -# CONFIG_LPC313X_EXTSDRAMHEAP - Select if external SDRAM should be +# CONFIG_LPC31XX_EXTSDRAM - Select if external SDRAM is present +# CONFIG_LPC31XX_EXTSDRAMHEAP - Select if external SDRAM should be # configured as part of the NuttX heap. -# CONFIG_LPC313X_EXTSDRAMSIZE - Size (in bytes) of the installed +# CONFIG_LPC31XX_EXTSDRAMSIZE - Size (in bytes) of the installed # external SDRAM memory -# CONFIG_LPC313X_EXTNAND - Select if external NAND is present -# CONFIG_LPC313X_EXTSDRAMSIZE - Size (in bytes) of the installed +# CONFIG_LPC31XX_EXTNAND - Select if external NAND is present +# CONFIG_LPC31XX_EXTSDRAMSIZE - Size (in bytes) of the installed # external NAND memory # -CONFIG_LPC313X_EXTSRAM0=n -CONFIG_LPC313X_EXTSRAM0HEAP=n -CONFIG_LPC313X_EXTSRAM0SIZE=(128*1024) -CONFIG_LPC313X_EXTSRAM1=n -CONFIG_LPC313X_EXTSRAM1HEAP=n -CONFIG_LPC313X_EXTSRAM1SIZE=(128*1024) -CONFIG_LPC313X_EXTSDRAM=n -CONFIG_LPC313X_EXTSDRAMHEAP=n -CONFIG_LPC313X_EXTSDRAMSIZE=(64*1024*1024) -CONFIG_LPC313X_EXTNAND=n -CONFIG_LPC313X_EXTNANDSIZE=(64*1024*1024) +CONFIG_LPC31XX_EXTSRAM0=n +CONFIG_LPC31XX_EXTSRAM0HEAP=n +CONFIG_LPC31XX_EXTSRAM0SIZE=(128*1024) +CONFIG_LPC31XX_EXTSRAM1=n +CONFIG_LPC31XX_EXTSRAM1HEAP=n +CONFIG_LPC31XX_EXTSRAM1SIZE=(128*1024) +CONFIG_LPC31XX_EXTSDRAM=n +CONFIG_LPC31XX_EXTSDRAMHEAP=n +CONFIG_LPC31XX_EXTSDRAMSIZE=(64*1024*1024) +CONFIG_LPC31XX_EXTNAND=n +CONFIG_LPC31XX_EXTNANDSIZE=(64*1024*1024) # -# LPC313X specific device driver settings +# LPC31XX specific device driver settings # # CONFIG_UART_SERIAL_CONSOLE - selects the UART for the # console and ttys0 @@ -538,20 +538,20 @@ CONFIG_USBDEV_TRACE=y CONFIG_USBDEV_TRACE_NRECORDS=128 # -# LPC313X USB Configuration +# LPC31XX USB Configuration # -# CONFIG_LPC313X_GIO_USBATTACH +# CONFIG_LPC31XX_GIO_USBATTACH # GIO that detects USB attach/detach events -# CONFIG_LPC313X_GIO_USBDPPULLUP +# CONFIG_LPC31XX_GIO_USBDPPULLUP # GIO # CONFIG_DMA320_USBDEV_DMA -# Enable LPC313X-specific DMA support +# Enable LPC31XX-specific DMA support # -CONFIG_LPC313X_GIO_USBATTACH=6 -CONFIG_LPC313X_GIO_USBDPPULLUP=17 -CONFIG_LPC313X_VENDORID=0xd320 -CONFIG_LPC313X_PRODUCTID=0x3211 -CONFIG_LPC313X_USBDEV_DMA=n +CONFIG_LPC31XX_GIO_USBATTACH=6 +CONFIG_LPC31XX_GIO_USBDPPULLUP=17 +CONFIG_LPC31XX_VENDORID=0xd320 +CONFIG_LPC31XX_PRODUCTID=0x3211 +CONFIG_LPC31XX_USBDEV_DMA=n # # USB Serial Device Configuration diff --git a/nuttx/configs/ea3131/usbserial/ld.script b/nuttx/configs/ea3131/usbserial/ld.script index 1bdc7d9fc..380051e28 100755 --- a/nuttx/configs/ea3131/usbserial/ld.script +++ b/nuttx/configs/ea3131/usbserial/ld.script @@ -34,7 +34,7 @@ ****************************************************************************/ /* The LPC3131 has 192Kb of ISRAM beginning at virtual address 0x1102:8000. - * LPC313x boot ROM expects the boot image be compiled with entry point at + * LPC31xx boot ROM expects the boot image be compiled with entry point at * 0x1102:9000. A 128b header will appear at this address (applied by * lpc313xImgCreator) and the executable code must begin at 0x1102:9080. */ diff --git a/nuttx/configs/ea3131/usbstorage/Make.defs b/nuttx/configs/ea3131/usbstorage/Make.defs index 21506cbed..6838c9d69 100755 --- a/nuttx/configs/ea3131/usbstorage/Make.defs +++ b/nuttx/configs/ea3131/usbstorage/Make.defs @@ -37,23 +37,23 @@ include ${TOPDIR}/.config # Setup for the selected toolchain -ifeq ($(CONFIG_LPC313X_CODESOURCERYW),y) +ifeq ($(CONFIG_LPC31XX_CODESOURCERYW),y) # CodeSourcery under Windows CROSSDEV = arm-none-eabi- WINTOOL = y MAXOPTIMIZATION = -O2 endif -ifeq ($(CONFIG_LPC313X_CODESOURCERYL),y) +ifeq ($(CONFIG_LPC31XX_CODESOURCERYL),y) # CodeSourcery under Linux CROSSDEV = arm-none-eabi- MAXOPTIMIZATION = -O2 endif -ifeq ($(CONFIG_LPC313X_DEVKITARM),y) +ifeq ($(CONFIG_LPC31XX_DEVKITARM),y) # devkitARM under Windows CROSSDEV = arm-eabi- WINTOOL = y endif -ifeq ($(CONFIG_LPC313X_BUILDROOT),y) +ifeq ($(CONFIG_LPC31XX_BUILDROOT),y) # NuttX buildroot under Linux or Cygwin CROSSDEV = arm-elf- MAXOPTIMIZATION = -Os @@ -121,7 +121,7 @@ OBJEXT = .o LIBEXT = .a EXEEXT = -ifneq ($(CONFIG_LPC313X_BUILDROOT),y) +ifneq ($(CONFIG_LPC31XX_BUILDROOT),y) LDFLAGS += -nostartfiles -nodefaultlibs endif ifeq ($(CONFIG_DEBUG_SYMBOLS),y) diff --git a/nuttx/configs/ea3131/usbstorage/defconfig b/nuttx/configs/ea3131/usbstorage/defconfig index df2cb7464..5dc459316 100755 --- a/nuttx/configs/ea3131/usbstorage/defconfig +++ b/nuttx/configs/ea3131/usbstorage/defconfig @@ -50,13 +50,13 @@ # CONFIG_ENDIAN_BIG - define if big endian (default is little endian) # CONFIG_BOARD_LOOPSPERMSEC - for delay loops # CONFIG_DRAM_SIZE - For most ARM9 architectures, this describes the -# size of installed DRAM. For the LPC313X, it is used only to +# size of installed DRAM. For the LPC31XX, it is used only to # deterimine how to map the executable regions. It is SDRAM size # only if you are executing out of the external SDRAM; or it could # be NOR FLASH size, external SRAM size, or internal SRAM size. # CONFIG_DRAM_START - The start address of DRAM (physical) # CONFIG_DRAM_VSTART - The startaddress of DRAM (virtual) -# CONFIG_ARCH_IRQPRIO - The LPC313x supports interrupt prioritization +# CONFIG_ARCH_IRQPRIO - The LPC31xx supports interrupt prioritization # CONFIG_ARCH_INTERRUPTSTACK - This architecture supports an interrupt # stack. If defined, this symbol is the size of the interrupt # stack in bytes. If not defined, the user task stacks will be @@ -76,7 +76,7 @@ CONFIG_ARCH=arm CONFIG_ARCH_ARM=y CONFIG_ARCH_ARM926EJS=y -CONFIG_ARCH_CHIP=lpc313x +CONFIG_ARCH_CHIP=lpc31xx CONFIG_ARCH_CHIP_LPC3131=y CONFIG_ARCH_BOARD=ea3131 CONFIG_ARCH_BOARD_EA3131=y @@ -108,54 +108,54 @@ CONFIG_ARCH_ROMPGTABLE=y # Identify toolchain and linker options # -CONFIG_LPC313X_CODESOURCERYW=n -CONFIG_LPC313X_CODESOURCERYL=y -CONFIG_LPC313X_DEVKITARM=n -CONFIG_LPC313X_BUILDROOT=n +CONFIG_LPC31XX_CODESOURCERYW=n +CONFIG_LPC31XX_CODESOURCERYL=y +CONFIG_LPC31XX_DEVKITARM=n +CONFIG_LPC31XX_BUILDROOT=n # # Individual subsystems can be enabled: # -CONFIG_LPC313X_MCI=n -CONFIG_LPC313X_SPI=n -CONFIG_LPC313X_UART=y +CONFIG_LPC31XX_MCI=n +CONFIG_LPC31XX_SPI=n +CONFIG_LPC31XX_UART=y # # Exernal memory available on the board (see also CONFIG_MM_REGIONS) # -# CONFIG_LPC313X_EXTSRAM0 - Select if external SRAM0 is present -# CONFIG_LPC313X_EXTSRAM0HEAP - Select if external SRAM0 should be +# CONFIG_LPC31XX_EXTSRAM0 - Select if external SRAM0 is present +# CONFIG_LPC31XX_EXTSRAM0HEAP - Select if external SRAM0 should be # configured as part of the NuttX heap. -# CONFIG_LPC313X_EXTSRAM0SIZE - Size (in bytes) of the installed +# CONFIG_LPC31XX_EXTSRAM0SIZE - Size (in bytes) of the installed # external SRAM0 memory -# CONFIG_LPC313X_EXTSRAM1 - Select if external SRAM1 is present -# CONFIG_LPC313X_EXTSRAM1HEAP - Select if external SRAM1 should be +# CONFIG_LPC31XX_EXTSRAM1 - Select if external SRAM1 is present +# CONFIG_LPC31XX_EXTSRAM1HEAP - Select if external SRAM1 should be # configured as part of the NuttX heap. -# CONFIG_LPC313X_EXTSRAM1SIZE - Size (in bytes) of the installed +# CONFIG_LPC31XX_EXTSRAM1SIZE - Size (in bytes) of the installed # external SRAM1 memory -# CONFIG_LPC313X_EXTSDRAM - Select if external SDRAM is present -# CONFIG_LPC313X_EXTSDRAMHEAP - Select if external SDRAM should be +# CONFIG_LPC31XX_EXTSDRAM - Select if external SDRAM is present +# CONFIG_LPC31XX_EXTSDRAMHEAP - Select if external SDRAM should be # configured as part of the NuttX heap. -# CONFIG_LPC313X_EXTSDRAMSIZE - Size (in bytes) of the installed +# CONFIG_LPC31XX_EXTSDRAMSIZE - Size (in bytes) of the installed # external SDRAM memory -# CONFIG_LPC313X_EXTNAND - Select if external NAND is present -# CONFIG_LPC313X_EXTSDRAMSIZE - Size (in bytes) of the installed +# CONFIG_LPC31XX_EXTNAND - Select if external NAND is present +# CONFIG_LPC31XX_EXTSDRAMSIZE - Size (in bytes) of the installed # external NAND memory # -CONFIG_LPC313X_EXTSRAM0=n -CONFIG_LPC313X_EXTSRAM0HEAP=n -CONFIG_LPC313X_EXTSRAM0SIZE=(128*1024) -CONFIG_LPC313X_EXTSRAM1=n -CONFIG_LPC313X_EXTSRAM1HEAP=n -CONFIG_LPC313X_EXTSRAM1SIZE=(128*1024) -CONFIG_LPC313X_EXTSDRAM=n -CONFIG_LPC313X_EXTSDRAMHEAP=n -CONFIG_LPC313X_EXTSDRAMSIZE=(64*1024*1024) -CONFIG_LPC313X_EXTNAND=n -CONFIG_LPC313X_EXTNANDSIZE=(64*1024*1024) +CONFIG_LPC31XX_EXTSRAM0=n +CONFIG_LPC31XX_EXTSRAM0HEAP=n +CONFIG_LPC31XX_EXTSRAM0SIZE=(128*1024) +CONFIG_LPC31XX_EXTSRAM1=n +CONFIG_LPC31XX_EXTSRAM1HEAP=n +CONFIG_LPC31XX_EXTSRAM1SIZE=(128*1024) +CONFIG_LPC31XX_EXTSDRAM=n +CONFIG_LPC31XX_EXTSDRAMHEAP=n +CONFIG_LPC31XX_EXTSDRAMSIZE=(64*1024*1024) +CONFIG_LPC31XX_EXTNAND=n +CONFIG_LPC31XX_EXTNANDSIZE=(64*1024*1024) # -# LPC313X specific device driver settings +# LPC31XX specific device driver settings # # CONFIG_UART_SERIAL_CONSOLE - selects the UART for the # console and ttys0 @@ -538,20 +538,20 @@ CONFIG_USBDEV_TRACE=n CONFIG_USBDEV_TRACE_NRECORDS=128 # -# LPC313X USB Configuration +# LPC31XX USB Configuration # -# CONFIG_LPC313X_GIO_USBATTACH +# CONFIG_LPC31XX_GIO_USBATTACH # GIO that detects USB attach/detach events -# CONFIG_LPC313X_GIO_USBDPPULLUP +# CONFIG_LPC31XX_GIO_USBDPPULLUP # GIO # CONFIG_DMA320_USBDEV_DMA -# Enable LPC313X-specific DMA support +# Enable LPC31XX-specific DMA support # -CONFIG_LPC313X_GIO_USBATTACH=6 -CONFIG_LPC313X_GIO_USBDPPULLUP=17 -CONFIG_LPC313X_VENDORID=0xd320 -CONFIG_LPC313X_PRODUCTID=0x3211 -CONFIG_LPC313X_USBDEV_DMA=n +CONFIG_LPC31XX_GIO_USBATTACH=6 +CONFIG_LPC31XX_GIO_USBDPPULLUP=17 +CONFIG_LPC31XX_VENDORID=0xd320 +CONFIG_LPC31XX_PRODUCTID=0x3211 +CONFIG_LPC31XX_USBDEV_DMA=n # # USB Serial Device Configuration diff --git a/nuttx/configs/ea3131/usbstorage/ld.script b/nuttx/configs/ea3131/usbstorage/ld.script index c6ba1c293..9828e5c97 100755 --- a/nuttx/configs/ea3131/usbstorage/ld.script +++ b/nuttx/configs/ea3131/usbstorage/ld.script @@ -34,7 +34,7 @@ ****************************************************************************/ /* The LPC3131 has 192Kb of ISRAM beginning at virtual address 0x1102:8000. - * LPC313x boot ROM expects the boot image be compiled with entry point at + * LPC31xx boot ROM expects the boot image be compiled with entry point at * 0x1102:9000. A 128b header will appear at this address (applied by * lpc313xImgCreator) and the executable code must begin at 0x1102:9080. */ -- cgit v1.2.3