Rename LM3S files, variables, and types from lm3s_ to lm_; Rename configuration variables from CONFIG_LM3S_ to CONFIG_LM_

git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5497 42af7a65-404d-4744-a932-0658087f49c3
This commit is contained in:
patacongo 2013-01-09 14:48:55 +00:00
parent 8156a2bed1
commit 51fc8af31f
87 changed files with 2079 additions and 2080 deletions

View File

@ -2901,7 +2901,7 @@ extern void up_ledoff(int led);
<li>
<p>
<b>Examples</b>:
<code>arch/arm/src/chip/lm3s_serial.c</code>, <code>arch/arm/src/lpc214x/lpc214x_serial.c</code>, <code>arch/z16/src/z16f/z16f_serial.c</code>, etc.
<code>arch/arm/src/chip/lm_serial.c</code>, <code>arch/arm/src/lpc214x/lpc214x_serial.c</code>, <code>arch/z16/src/z16f/z16f_serial.c</code>, etc.
</p>
</li>
</ul>

View File

@ -308,7 +308,7 @@
* be disabled in order to reduce the size of the implemenation.
*/
#ifndef CONFIG_LM3S_DISABLE_GPIOA_IRQS
#ifndef CONFIG_LM_DISABLE_GPIOA_IRQS
# define LM3S_IRQ_GPIOA_0 (NR_IRQS + 0)
# define LM3S_IRQ_GPIOA_1 (NR_IRQS + 1)
# define LM3S_IRQ_GPIOA_2 (NR_IRQS + 2)
@ -322,7 +322,7 @@
# define _NGPIOAIRQS NR_IRQS
#endif
#ifndef CONFIG_LM3S_DISABLE_GPIOB_IRQS
#ifndef CONFIG_LM_DISABLE_GPIOB_IRQS
# define LM3S_IRQ_GPIOB_0 (_NGPIOAIRQS + 0)
# define LM3S_IRQ_GPIOB_1 (_NGPIOAIRQS + 1)
# define LM3S_IRQ_GPIOB_2 (_NGPIOAIRQS + 2)
@ -336,7 +336,7 @@
# define _NGPIOBIRQS _NGPIOAIRQS
#endif
#ifndef CONFIG_LM3S_DISABLE_GPIOC_IRQS
#ifndef CONFIG_LM_DISABLE_GPIOC_IRQS
# define LM3S_IRQ_GPIOC_0 (_NGPIOBIRQS + 0)
# define LM3S_IRQ_GPIOC_1 (_NGPIOBIRQS + 1)
# define LM3S_IRQ_GPIOC_2 (_NGPIOBIRQS + 2)
@ -350,7 +350,7 @@
# define _NGPIOCIRQS _NGPIOBIRQS
#endif
#ifndef CONFIG_LM3S_DISABLE_GPIOD_IRQS
#ifndef CONFIG_LM_DISABLE_GPIOD_IRQS
# define LM3S_IRQ_GPIOD_0 (_NGPIOCIRQS + 0)
# define LM3S_IRQ_GPIOD_1 (_NGPIOCIRQS + 1)
# define LM3S_IRQ_GPIOD_2 (_NGPIOCIRQS + 2)
@ -364,7 +364,7 @@
# define _NGPIODIRQS _NGPIOCIRQS
#endif
#ifndef CONFIG_LM3S_DISABLE_GPIOE_IRQS
#ifndef CONFIG_LM_DISABLE_GPIOE_IRQS
# define LM3S_IRQ_GPIOE_0 (_NGPIODIRQS + 0)
# define LM3S_IRQ_GPIOE_1 (_NGPIODIRQS + 1)
# define LM3S_IRQ_GPIOE_2 (_NGPIODIRQS + 2)
@ -378,7 +378,7 @@
# define _NGPIOEIRQS _NGPIODIRQS
#endif
#ifndef CONFIG_LM3S_DISABLE_GPIOF_IRQS
#ifndef CONFIG_LM_DISABLE_GPIOF_IRQS
# define LM3S_IRQ_GPIOF_0 (_NGPIOEIRQS + 0)
# define LM3S_IRQ_GPIOF_1 (_NGPIOEIRQS + 1)
# define LM3S_IRQ_GPIOF_2 (_NGPIOEIRQS + 2)
@ -392,7 +392,7 @@
# define _NGPIOFIRQS _NGPIOEIRQS
#endif
#ifndef CONFIG_LM3S_DISABLE_GPIOG_IRQS
#ifndef CONFIG_LM_DISABLE_GPIOG_IRQS
# define LM3S_IRQ_GPIOG_0 (_NGPIOFIRQS + 0)
# define LM3S_IRQ_GPIOG_1 (_NGPIOFIRQS + 1)
# define LM3S_IRQ_GPIOG_2 (_NGPIOFIRQS + 2)
@ -406,7 +406,7 @@
# define _NGPIOGIRQS _NGPIOFIRQS
#endif
#ifndef CONFIG_LM3S_DISABLE_GPIOH_IRQS
#ifndef CONFIG_LM_DISABLE_GPIOH_IRQS
# define LM3S_IRQ_GPIOH_0 (_NGPIOGIRQS + 0)
# define LM3S_IRQ_GPIOH_1 (_NGPIOGIRQS + 1)
# define LM3S_IRQ_GPIOH_2 (_NGPIOGIRQS + 2)
@ -420,7 +420,7 @@
# define _NGPIOHIRQS _NGPIOGIRQS
#endif
#ifndef CONFIG_LM3S_DISABLE_GPIOJ_IRQS
#ifndef CONFIG_LM_DISABLE_GPIOJ_IRQS
# define LM3S_IRQ_GPIOJ_0 (_NGPIOHIRQS + 0)
# define LM3S_IRQ_GPIOJ_1 (_NGPIOHIRQS + 1)
# define LM3S_IRQ_GPIOJ_2 (_NGPIOHIRQS + 2)

View File

@ -53,7 +53,7 @@ ifeq ($(filter y, \
endif
ifeq ($(filter y, \
$(CONFIG_KINETIS_BUILDROOT) \
$(CONFIG_LM3S_BUILDROOT) \
$(CONFIG_LM_BUILDROOT) \
$(CONFIG_LPC17_BUILDROOT) \
$(CONFIG_LPC43_BUILDROOT) \
$(CONFIG_SAM3U_BUILDROOT) \
@ -77,7 +77,7 @@ ifeq ($(filter y, \
endif
ifeq ($(filter y, \
$(CONFIG_KINETIS_CODESOURCERYL) \
$(CONFIG_LM3S_CODESOURCERYL) \
$(CONFIG_LM_CODESOURCERYL) \
$(CONFIG_LPC17_CODESOURCERYL) \
$(CONFIG_LPC43_CODESOURCERYL) \
$(CONFIG_SAM3U_CODESOURCERYL) \
@ -88,7 +88,7 @@ ifeq ($(filter y, \
endif
ifeq ($(filter y, \
$(CONFIG_KINETIS_CODESOURCERYW) \
$(CONFIG_LM3S_CODESOURCERYW) \
$(CONFIG_LM_CODESOURCERYW) \
$(CONFIG_LPC17_CODESOURCERYW) \
$(CONFIG_LPC43_CODESOURCERYW) \
$(CONFIG_SAM3U_CODESOURCERYW) \
@ -99,7 +99,7 @@ ifeq ($(filter y, \
endif
ifeq ($(filter y, \
$(CONFIG_KINETIS_DEVKITARM) \
$(CONFIG_LM3S_DEVKITARM) \
$(CONFIG_LM_DEVKITARM) \
$(CONFIG_LPC17_DEVKITARM) \
$(CONFIG_LPC43_DEVKITARM) \
$(CONFIG_SAM3U_DEVKITARM) \

View File

@ -14,7 +14,7 @@ config ARCH_CHIP_LM3S6918
bool "LM3S6918"
select ARCH_CORTEXM3
select ARCH_CHIP_LM3S
select LM3S_HAVE_SSI1
select LM_HAVE_SSI1
config ARCH_CHIP_LM3S9B96
bool "LM3S9B96"
@ -46,28 +46,28 @@ config ARCH_CHIP_LM3S
config ARCH_CHIP_LM4F
bool
config LM3S_HAVE_SSI1
config LM_HAVE_SSI1
bool
config LM3S_REVA2
config LM_REVA2
bool "Rev A2"
default n
---help---
Some early silicon returned an increase LDO voltage or 2.75V to work
around a PLL bug
config LM3S_DFU
config LM_DFU
bool "DFU"
default y
menu "Stellaris Peripheral Support"
config LM3S_UART0
config LM_UART0
bool "UART0"
select ARCH_HAVE_UART0
default n
config LM3S_UART1
config LM_UART1
bool "UART1"
select ARCH_HAVE_UART1
default n
@ -80,12 +80,12 @@ config SSI1_DISABLE
bool "Disable SSI1"
default y
config LM3S_UART2
config LM_UART2
bool "UART2"
select ARCH_HAVE_UART2
default n
config LM3S_ETHERNET
config LM_ETHERNET
bool "Stellaris Ethernet"
default n
---help---
@ -95,95 +95,95 @@ endmenu
menu "Disable GPIO Interrupts"
config LM3S_DISABLE_GPIOA_IRQS
config LM_DISABLE_GPIOA_IRQS
bool "Disable GPIOA IRQs"
default n
config LM3S_DISABLE_GPIOB_IRQS
config LM_DISABLE_GPIOB_IRQS
bool "Disable GPIOB IRQs"
default n
config LM3S_DISABLE_GPIOC_IRQS
config LM_DISABLE_GPIOC_IRQS
bool "Disable GPIOC IRQs"
default n
config LM3S_DISABLE_GPIOD_IRQS
config LM_DISABLE_GPIOD_IRQS
bool "Disable GPIOD IRQs"
default n
config LM3S_DISABLE_GPIOE_IRQS
config LM_DISABLE_GPIOE_IRQS
bool "Disable GPIOE IRQs"
default n
config LM3S_DISABLE_GPIOF_IRQS
config LM_DISABLE_GPIOF_IRQS
bool "Disable GPIOF IRQs"
default n
config LM3S_DISABLE_GPIOG_IRQS
config LM_DISABLE_GPIOG_IRQS
bool "Disable GPIOG IRQs"
default n
config LM3S_DISABLE_GPIOH_IRQS
config LM_DISABLE_GPIOH_IRQS
bool "Disable GPIOH IRQs"
default n
config LM3S_DISABLE_GPIOJ_IRQS
config LM_DISABLE_GPIOJ_IRQS
bool "Disable GPIOJ IRQs"
default n
endmenu
if LM3S_ETHERNET
if LM_ETHERNET
menu "Stellaris Ethernet Configuration"
config LM3S_ETHLEDS
config LM_ETHLEDS
bool "Ethernet LEDs"
default n
---help---
Enable to use Ethernet LEDs on the board.
config LM3S_BOARDMAC
config LM_BOARDMAC
bool "Board MAC"
default n
---help---
If the board-specific logic can provide a MAC address (via
lm3s_ethernetmac()), then this should be selected.
lm_ethernetmac()), then this should be selected.
config LM3S_ETHHDUPLEX
config LM_ETHHDUPLEX
bool "Force Half Duplex"
default n
---help---
Set to force half duplex operation
config LM3S_ETHNOAUTOCRC
config LM_ETHNOAUTOCRC
bool "Disable auto-CRC"
default n
---help---
Set to suppress auto-CRC generation
config LM3S_ETHNOPAD
config LM_ETHNOPAD
bool "Disable Tx Padding"
default n
---help---
Set to suppress Tx padding
config LM3S_MULTICAST
config LM_MULTICAST
bool "Enable Multicast"
default n
---help---
Set to enable multicast frames
config LM3S_PROMISCUOUS
config LM_PROMISCUOUS
bool "Enable Promiscuous Mode"
default n
---help---
Set to enable promiscuous mode
config LM3S_TIMESTAMP
config LM_TIMESTAMP
bool "Enable Timestamping"
default n
config LM3S_BADCRC
config LM_BADCRC
bool "Enable Bad CRC Rejection"
default n
---help---

View File

@ -33,7 +33,7 @@
#
############################################################################
HEAD_ASRC = lm3s_vectors.S
HEAD_ASRC = lm_vectors.S
CMN_ASRCS = up_saveusercontext.S up_fullcontextrestore.S up_switchcontext.S \
vfork.S
@ -55,10 +55,9 @@ CMN_CSRCS += up_elf.c
endif
CHIP_ASRCS =
CHIP_CSRCS = lm3s_start.c lm3s_syscontrol.c lm3s_irq.c \
lm3s_gpio.c lm3s_gpioirq.c lm3s_timerisr.c lm3s_lowputc.c \
lm3s_serial.c lm3s_ssi.c lm3s_dumpgpio.c
CHIP_CSRCS = lm_start.c lm_syscontrol.c lm_irq.c lm_gpio.c lm_gpioirq.c \
lm_timerisr.c lm_lowputc.c lm_serial.c lm_ssi.c lm_dumpgpio.c
ifdef CONFIG_NET
CHIP_CSRCS += lm3s_ethernet.c
CHIP_CSRCS += lm_ethernet.c
endif

View File

@ -50,13 +50,13 @@
/* Then get all of the register definitions */
#include "chip/lm_memorymap.h" /* Memory map */
#include "chip/lm3s_syscontrol.h" /* System control module */
#include "chip/lm3s_gpio.h" /* GPIO modules */
#include "chip/lm3s_uart.h" /* UART modules */
#include "chip/lm3s_i2c.h" /* I2C modules */
#include "chip/lm3s_ssi.h" /* SSI modules */
#include "chip/lm3s_ethernet.h" /* Ethernet MAC and PHY */
#include "chip/lm3s_flash.h" /* FLASH */
#include "chip/lm_syscontrol.h" /* System control module */
#include "chip/lm_gpio.h" /* GPIO modules */
#include "chip/lm_uart.h" /* UART modules */
#include "chip/lm_i2c.h" /* I2C modules */
#include "chip/lm_ssi.h" /* SSI modules */
#include "chip/lm_ethernet.h" /* Ethernet MAC and PHY */
#include "chip/lm_flash.h" /* FLASH */
/* The LM3S69xx only supports 8 priority levels. The hardware priority mechanism
* will only look at the upper N bits of the 8-bit priority level (where N is 3 for

View File

@ -46,7 +46,7 @@
* Pre-processor Definitions
************************************************************************************/
/* The following lists the input value to lm3s_configgpio to setup the alternate,
/* The following lists the input value to lm_configgpio to setup the alternate,
* hardware function for each pin.
*/

View File

@ -1,5 +1,5 @@
/************************************************************************************
* arch/arm/src/lm/chip/lm3s_epi.h
* arch/arm/src/lm/chip/lm_epi.h
*
* Copyright (C) 2009-2013 Max Neklyudov. All rights reserved.
* Author: Max Neklyudov <macscomp@gmail.com>

View File

@ -1,5 +1,5 @@
/************************************************************************************
* arch/arm/src/lm/chip/lm3s_ethernet.h
* arch/arm/src/lm/chip/lm_ethernet.h
*
* Copyright (C) 2009-2010, 2012-2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>

View File

@ -1,5 +1,5 @@
/************************************************************************************
* arch/arm/src/lm/chip/lm3s_flash.h
* arch/arm/src/lm/chip/lm_flash.h
*
* Copyright (C) 2009, 2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>

View File

@ -1,5 +1,5 @@
/************************************************************************************
* arch/arm/src/lm/chip/lm3s_gpio.h
* arch/arm/src/lm/chip/lm_gpio.h
*
* Copyright (C) 2009-2010, 2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>

View File

@ -1,5 +1,5 @@
/************************************************************************************
* arch/arm/src/lm/chip/lm3s_i2c.h
* arch/arm/src/lm/chip/lm_i2c.h
*
* Copyright (C) 2009, 2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>

View File

@ -1,5 +1,5 @@
/************************************************************************************
* arch/arm/src/lm/chip/lm3s_ssi.h
* arch/arm/src/lm/chip/lm_ssi.h
*
* Copyright (C) 2009, 2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>

View File

@ -1,5 +1,5 @@
/************************************************************************************
* arch/arm/src/lm/chip/lm3s_syscontrol.h
* arch/arm/src/lm/chip/lm_syscontrol.h
*
* Copyright (C) 2009-2010, 2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>

View File

@ -1,5 +1,5 @@
/************************************************************************************
* arch/arm/src/lm/chip/lm3s_timer.h
* arch/arm/src/lm/chip/lm_timer.h
*
* Copyright (C) 2012 Max Nekludov. All rights reserved.
* Author: Max Nekludov <macscomp@gmail.com>

View File

@ -1,5 +1,5 @@
/************************************************************************************
* arch/arm/src/lm/chip/lm3s_uart.h
* arch/arm/src/lm/chip/lm_uart.h
*
* Copyright (C) 2009, 2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>

View File

@ -1,805 +0,0 @@
/************************************************************************************
* arch/arm/src/lm/lm3s_vectors.S
* arch/arm/src/chip/lm3s_vectors.S
*
* Copyright (C) 2009-2010 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name NuttX nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
************************************************************************************/
/************************************************************************************
* Included Files
************************************************************************************/
#include <nuttx/config.h>
#include <arch/irq.h>
/************************************************************************************
* Preprocessor Definitions
************************************************************************************/
/* Memory Map:
*
* 0x0000:0000 - Beginning of FLASH. Address of vectors (if not using bootloader)
* 0x0002:0000 - Address of vectors if using bootloader
* 0x0003:ffff - End of flash
* 0x2000:0000 - Start of SRAM and start of .data (_sdata)
* - End of .data (_edata) abd start of .bss (_sbss)
* - End of .bss (_ebss) and bottom of idle stack
* - _ebss + CONFIG_IDLETHREAD_STACKSIZE = end of idle stack, start of heap
* 0x2000:ffff - End of SRAM and end of heap
*/
#define IDLE_STACK (_ebss+CONFIG_IDLETHREAD_STACKSIZE-4)
#define HEAP_BASE (_ebss+CONFIG_IDLETHREAD_STACKSIZE-4)
/* The Cortex-M3 return from interrupt is unusual. We provide the following special
* address to the BX instruction. The particular value also forces a return to
* thread mode and covers state from the main stack point, the MSP (vs. the MSP).
*/
#define EXC_RETURN 0xfffffff9
/************************************************************************************
* Global Symbols
************************************************************************************/
.globl __start
.syntax unified
.thumb
.file "lm3s_vectors.S"
/************************************************************************************
* Macros
************************************************************************************/
/* On entry into an IRQ, the hardware automatically saves the xPSR, PC, LR, R12, R0-R3
* registers on the stack, then branches to an instantantiation of the following
* macro. This macro simply loads the IRQ number into R0, then jumps to the common
* IRQ handling logic.
*/
.macro HANDLER, label, irqno
.thumb_func
\label:
mov r0, #\irqno
b lm3s_irqcommon
.endm
/************************************************************************************
* Vectors
************************************************************************************/
.section .vectors, "ax"
.code 16
.align 2
.globl lm3s_vectors
.type lm3s_vectors, function
lm3s_vectors:
/* Processor Exceptions */
.word IDLE_STACK /* Vector 0: Reset stack pointer */
.word __start /* Vector 1: Reset vector */
.word lm3s_nmi /* Vector 2: Non-Maskable Interrupt (NMI) */
.word lm3s_hardfault /* Vector 3: Hard fault */
.word lm3s_mpu /* Vector 4: Memory management (MPU) */
.word lm3s_busfault /* Vector 5: Bus fault */
.word lm3s_usagefault /* Vector 6: Usage fault */
.word lm3s_reserved /* Vector 7: Reserved */
.word lm3s_reserved /* Vector 8: Reserved */
.word lm3s_reserved /* Vector 9: Reserved */
.word lm3s_reserved /* Vector 10: Reserved */
.word lm3s_svcall /* Vector 11: SVC call */
.word lm3s_dbgmonitor /* Vector 12: Debug monitor */
.word lm3s_reserved /* Vector 13: Reserved */
.word lm3s_pendsv /* Vector 14: Pendable system service request */
.word lm3s_systick /* Vector 15: System tick */
/* External Interrupts */
#if defined(CONFIG_ARCH_CHIP_LM3S6918)
.word lm3s_gpioa /* Vector 16: GPIO Port A */
.word lm3s_gpiob /* Vector 17: GPIO Port B */
.word lm3s_gpioc /* Vector 18: GPIO Port C */
.word lm3s_gpiod /* Vector 19: GPIO Port D */
.word lm3s_gpioe /* Vector 20: GPIO Port E */
.word lm3s_uart0 /* Vector 21: UART 0 */
.word lm3s_uart1 /* Vector 22: UART 1 */
.word lm3s_ssi0 /* Vector 23: SSI 0 */
.word lm3s_i2c0 /* Vector 24: I2C 0 */
.word lm3s_reserved /* Vector 25: Reserved */
.word lm3s_reserved /* Vector 26: Reserved */
.word lm3s_reserved /* Vector 27: Reserved */
.word lm3s_reserved /* Vector 28: Reserved */
.word lm3s_reserved /* Vector 29: Reserved */
.word lm3s_adc0 /* Vector 30: ADC Sequence 0 */
.word lm3s_adc1 /* Vector 31: ADC Sequence 1 */
.word lm3s_adc2 /* Vector 32: ADC Sequence 2 */
.word lm3s_adc3 /* Vector 33: ADC Sequence 3 */
.word lm3s_wdog /* Vector 34: Watchdog Timer */
.word lm3s_tmr0a /* Vector 35: Timer 0 A */
.word lm3s_tmr0b /* Vector 36: Timer 0 B */
.word lm3s_tmr1a /* Vector 37: Timer 1 A */
.word lm3s_tmr1b /* Vector 38: Timer 1 B */
.word lm3s_tmr2a /* Vector 39: Timer 2 A */
.word lm3s_tmr2b /* Vector 40: Timer 3 B */
.word lm3s_cmp0 /* Vector 41: Analog Comparator 0 */
.word lm3s_cmp1 /* Vector 42: Analog Comparator 1 */
.word lm3s_reserved /* Vector 43: Reserved */
.word lm3s_syscon /* Vector 44: System Control */
.word lm3s_flashcon /* Vector 45: FLASH Control */
.word lm3s_gpiof /* Vector 46: GPIO Port F */
.word lm3s_gpiog /* Vector 47: GPIO Port G */
.word lm3s_gpioh /* Vector 48: GPIO Port H */
.word lm3s_reserved /* Vector 49: Reserved */
.word lm3s_ssi1 /* Vector 50: SSI 1 */
.word lm3s_tmr3a /* Vector 51: Timer 3 A */
.word lm3s_tmr3b /* Vector 52: Timer 3 B */
.word lm3s_i2c1 /* Vector 53: I2C 1 */
.word lm3s_reserved /* Vector 54: Reserved */
.word lm3s_reserved /* Vector 55: Reserved */
.word lm3s_reserved /* Vector 56: Reserved */
.word lm3s_reserved /* Vector 57: Reserved */
.word lm3s_eth /* Vector 58: Ethernet Controller */
.word lm3s_hib /* Vector 59: Hibernation Module */
.word lm3s_reserved /* Vector 60: Reserved */
.word lm3s_reserved /* Vector 61: Reserved */
.word lm3s_reserved /* Vector 62: Reserved */
.word lm3s_reserved /* Vector 63: Reserved */
.word lm3s_reserved /* Vector 64: Reserved */
.word lm3s_reserved /* Vector 65: Reserved */
.word lm3s_reserved /* Vector 66: Reserved */
.word lm3s_reserved /* Vector 67: Reserved */
.word lm3s_reserved /* Vector 68: Reserved */
.word lm3s_reserved /* Vector 69: Reserved */
.word lm3s_reserved /* Vector 70: Reserved */
#elif defined(CONFIG_ARCH_CHIP_LM3S6432)
.word lm3s_gpioa /* Vector 16: GPIO Port A */
.word lm3s_gpiob /* Vector 17: GPIO Port B */
.word lm3s_gpioc /* Vector 18: GPIO Port C */
.word lm3s_gpiod /* Vector 19: GPIO Port D */
.word lm3s_gpioe /* Vector 20: GPIO Port E */
.word lm3s_uart0 /* Vector 21: UART 0 */
.word lm3s_uart1 /* Vector 22: UART 1 */
.word lm3s_ssi0 /* Vector 23: SSI 0 */
.word lm3s_i2c0 /* Vector 24: I2C 0 */
.word lm3s_reserved /* Vector 25: Reserved */
.word lm3s_pwm0 /* Vector 26: PWM Generator 0 */
.word lm3s_reserved /* Vector 27: Reserved */
.word lm3s_reserved /* Vector 28: Reserved */
.word lm3s_reserved /* Vector 29: Reserved */
.word lm3s_adc0 /* Vector 30: ADC Sequence 0 */
.word lm3s_adc1 /* Vector 31: ADC Sequence 1 */
.word lm3s_adc2 /* Vector 32: ADC Sequence 2 */
.word lm3s_adc3 /* Vector 33: ADC Sequence 3 */
.word lm3s_wdog /* Vector 34: Watchdog Timer */
.word lm3s_tmr0a /* Vector 35: Timer 0 A */
.word lm3s_tmr0b /* Vector 36: Timer 0 B */
.word lm3s_tmr1a /* Vector 37: Timer 1 A */
.word lm3s_tmr1b /* Vector 38: Timer 1 B */
.word lm3s_tmr2a /* Vector 39: Timer 2 A */
.word lm3s_tmr2b /* Vector 40: Timer 3 B */
.word lm3s_cmp0 /* Vector 41: Analog Comparator 0 */
.word lm3s_cmp1 /* Vector 42: Analog Comparator 1 */
.word lm3s_reserved /* Vector 43: Reserved */
.word lm3s_syscon /* Vector 44: System Control */
.word lm3s_flashcon /* Vector 45: FLASH Control */
.word lm3s_gpiof /* Vector 46: GPIO Port F */
.word lm3s_gpiog /* Vector 47: GPIO Port G */
.word lm3s_reserved /* Vector 48: Reserved */
.word lm3s_reserved /* Vector 49: Reserved */
.word lm3s_reserved /* Vector 50: Reserved */
.word lm3s_reserved /* Vector 51: Reserved */
.word lm3s_reserved /* Vector 52: Reserved */
.word lm3s_reserved /* Vector 53: Reserved */
.word lm3s_reserved /* Vector 54: Reserved */
.word lm3s_reserved /* Vector 55: Reserved */
.word lm3s_reserved /* Vector 56: Reserved */
.word lm3s_reserved /* Vector 57: Reserved */
.word lm3s_eth /* Vector 58: Ethernet Controller */
.word lm3s_reserved /* Vector 59: Reserved */
.word lm3s_reserved /* Vector 60: Reserved */
.word lm3s_reserved /* Vector 61: Reserved */
.word lm3s_reserved /* Vector 62: Reserved */
.word lm3s_reserved /* Vector 63: Reserved */
.word lm3s_reserved /* Vector 64: Reserved */
.word lm3s_reserved /* Vector 65: Reserved */
.word lm3s_reserved /* Vector 66: Reserved */
.word lm3s_reserved /* Vector 67: Reserved */
.word lm3s_reserved /* Vector 68: Reserved */
.word lm3s_reserved /* Vector 69: Reserved */
.word lm3s_reserved /* Vector 70: Reserved */
#elif defined(CONFIG_ARCH_CHIP_LM3S6965)
.word lm3s_gpioa /* Vector 16: GPIO Port A */
.word lm3s_gpiob /* Vector 17: GPIO Port B */
.word lm3s_gpioc /* Vector 18: GPIO Port C */
.word lm3s_gpiod /* Vector 19: GPIO Port D */
.word lm3s_gpioe /* Vector 20: GPIO Port E */
.word lm3s_uart0 /* Vector 21: UART 0 */
.word lm3s_uart1 /* Vector 22: UART 1 */
.word lm3s_ssi0 /* Vector 23: SSI 0 */
.word lm3s_i2c0 /* Vector 24: I2C 0 */
.word lm3s_pwmfault /* Vector 25: PWM Fault */
.word lm3s_pwm0 /* Vector 26: PWM Generator 0 */
.word lm3s_pwm1 /* Vector 27: PWM Generator 1 */
.word lm3s_pwm2 /* Vector 28: PWM Generator 2 */
.word lm3s_qei0 /* Vector 29: QEI0 */
.word lm3s_adc0 /* Vector 30: ADC Sequence 0 */
.word lm3s_adc1 /* Vector 31: ADC Sequence 1 */
.word lm3s_adc2 /* Vector 32: ADC Sequence 2 */
.word lm3s_adc3 /* Vector 33: ADC Sequence 3 */
.word lm3s_wdog /* Vector 34: Watchdog Timer */
.word lm3s_tmr0a /* Vector 35: Timer 0 A */
.word lm3s_tmr0b /* Vector 36: Timer 0 B */
.word lm3s_tmr1a /* Vector 37: Timer 1 A */
.word lm3s_tmr1b /* Vector 38: Timer 1 B */
.word lm3s_tmr2a /* Vector 39: Timer 2 A */
.word lm3s_tmr2b /* Vector 40: Timer 3 B */
.word lm3s_cmp0 /* Vector 41: Analog Comparator 0 */
.word lm3s_cmp1 /* Vector 42: Analog Comparator 1 */
.word lm3s_reserved /* Vector 43: Reserved */
.word lm3s_syscon /* Vector 44: System Control */
.word lm3s_flashcon /* Vector 45: FLASH Control */
.word lm3s_gpiof /* Vector 46: GPIO Port F */
.word lm3s_gpiog /* Vector 47: GPIO Port G */
.word lm3s_reserved /* Vector 48: Reserved */
.word lm3s_uart2 /* Vector 49: UART 2 */
.word lm3s_reserved /* Vector 50: Reserved */
.word lm3s_tmr3a /* Vector 51: Timer 3 A */
.word lm3s_tmr3b /* Vector 52: Timer 3 B */
.word lm3s_i2c1 /* Vector 53: I2C 1 */
.word lm3s_qei1 /* Vector 54: QEI1 */
.word lm3s_reserved /* Vector 55: Reserved */
.word lm3s_reserved /* Vector 56: Reserved */
.word lm3s_reserved /* Vector 57: Reserved */
.word lm3s_eth /* Vector 58: Ethernet Controller */
.word lm3s_hib /* Vector 59: Hibernation Module */
.word lm3s_reserved /* Vector 60: Reserved */
.word lm3s_reserved /* Vector 61: Reserved */
.word lm3s_reserved /* Vector 62: Reserved */
.word lm3s_reserved /* Vector 63: Reserved */
.word lm3s_reserved /* Vector 64: Reserved */
.word lm3s_reserved /* Vector 65: Reserved */
.word lm3s_reserved /* Vector 66: Reserved */
.word lm3s_reserved /* Vector 67: Reserved */
.word lm3s_reserved /* Vector 68: Reserved */
.word lm3s_reserved /* Vector 69: Reserved */
.word lm3s_reserved /* Vector 70: Reserved */
#elif defined(CONFIG_ARCH_CHIP_LM3S9B96)
.word lm3s_gpioa /* Vector 16: GPIO Port A */
.word lm3s_gpiob /* Vector 17: GPIO Port B */
.word lm3s_gpioc /* Vector 18: GPIO Port C */
.word lm3s_gpiod /* Vector 19: GPIO Port D */
.word lm3s_gpioe /* Vector 20: GPIO Port E */
.word lm3s_uart0 /* Vector 21: UART 0 */
.word lm3s_uart1 /* Vector 22: UART 1 */
.word lm3s_ssi0 /* Vector 23: SSI 0 */
.word lm3s_i2c0 /* Vector 24: I2C 0 */
.word lm3s_pwmfault /* Vector 25: PWM Fault */
.word lm3s_pwm0 /* Vector 26: PWM Generator 0 */
.word lm3s_pwm1 /* Vector 27: PWM Generator 1 */
.word lm3s_pwm2 /* Vector 28: PWM Generator 2 */
.word lm3s_qei0 /* Vector 29: QEI0 */
.word lm3s_adc0 /* Vector 30: ADC Sequence 0 */
.word lm3s_adc1 /* Vector 31: ADC Sequence 1 */
.word lm3s_adc2 /* Vector 32: ADC Sequence 2 */
.word lm3s_adc3 /* Vector 33: ADC Sequence 3 */
.word lm3s_wdog /* Vector 34: Watchdog Timer */
.word lm3s_tmr0a /* Vector 35: Timer 0 A */
.word lm3s_tmr0b /* Vector 36: Timer 0 B */
.word lm3s_tmr1a /* Vector 37: Timer 1 A */
.word lm3s_tmr1b /* Vector 38: Timer 1 B */
.word lm3s_tmr2a /* Vector 39: Timer 2 A */
.word lm3s_tmr2b /* Vector 40: Timer 3 B */
.word lm3s_cmp0 /* Vector 41: Analog Comparator 0 */
.word lm3s_cmp1 /* Vector 42: Analog Comparator 1 */
.word lm3s_cmp2 /* Vector 43: Reserved */
.word lm3s_syscon /* Vector 44: System Control */
.word lm3s_flashcon /* Vector 45: FLASH Control */
.word lm3s_gpiof /* Vector 46: GPIO Port F */
.word lm3s_gpiog /* Vector 47: GPIO Port G */
.word lm3s_gpioh /* Vector 48: GPIO Port H */
.word lm3s_uart2 /* Vector 49: UART 2 */
.word lm3s_ssi1 /* Vector 50: SSI 1 */
.word lm3s_tmr3a /* Vector 51: Timer 3 A */
.word lm3s_tmr3b /* Vector 52: Timer 3 B */
.word lm3s_i2c1 /* Vector 53: I2C 1 */
.word lm3s_qei1 /* Vector 54: QEI1 */
.word lm3s_can0 /* Vector 55: CAN 0 */
.word lm3s_can1 /* Vector 56: CAN 1 */
.word lm3s_reserved /* Vector 57: Reserved */
.word lm3s_eth /* Vector 58: Ethernet Controller */
.word lm3s_reserved /* Vector 59: Reserved */
.word lm3s_usb /* Vector 60: USB */
.word lm3s_pwm3 /* Vector 61: PWM 3 */
.word lm3s_udmasoft /* Vector 62: uDMA Software */
.word lm3s_udmaerror /* Vector 63: uDMA Error */
.word lm3s_adc1_0 /* Vector 64: ADC1 Sequence 0 */
.word lm3s_adc1_1 /* Vector 65: ADC1 Sequence 1 */
.word lm3s_adc1_2 /* Vector 66: ADC1 Sequence 2 */
.word lm3s_adc1_3 /* Vector 67: ADC1 Sequence 3 */
.word lm3s_i2s0 /* Vector 68: I2S 0 */
.word lm3s_epi /* Vector 69: Reserved */
.word lm3s_gpioj /* Vector 70: GPIO J */
.word lm3s_reserved /* Vector 71: Reserved */
#elif defined(CONFIG_ARCH_CHIP_LM3S8962)
.word lm3s_gpioa /* Vector 16: GPIO Port A */
.word lm3s_gpiob /* Vector 17: GPIO Port B */
.word lm3s_gpioc /* Vector 18: GPIO Port C */
.word lm3s_gpiod /* Vector 19: GPIO Port D */
.word lm3s_gpioe /* Vector 20: GPIO Port E */
.word lm3s_uart0 /* Vector 21: UART 0 */
.word lm3s_uart1 /* Vector 22: UART 1 */
.word lm3s_ssi0 /* Vector 23: SSI 0 */
.word lm3s_i2c0 /* Vector 24: I2C 0 */
.word lm3s_pwmfault /* Vector 25: PWM Fault */
.word lm3s_pwm0 /* Vector 26: PWM Generator 0 */
.word lm3s_pwm1 /* Vector 27: PWM Generator 1 */
.word lm3s_pwm2 /* Vector 28: PWM Generator 2 */
.word lm3s_qei0 /* Vector 29: QEI0 */
.word lm3s_adc0 /* Vector 30: ADC Sequence 0 */
.word lm3s_adc1 /* Vector 31: ADC Sequence 1 */
.word lm3s_adc2 /* Vector 32: ADC Sequence 2 */
.word lm3s_adc3 /* Vector 33: ADC Sequence 3 */
.word lm3s_wdog /* Vector 34: Watchdog Timer */
.word lm3s_tmr0a /* Vector 35: Timer 0 A */
.word lm3s_tmr0b /* Vector 36: Timer 0 B */
.word lm3s_tmr1a /* Vector 37: Timer 1 A */
.word lm3s_tmr1b /* Vector 38: Timer 1 B */
.word lm3s_tmr2a /* Vector 39: Timer 2 A */
.word lm3s_tmr2b /* Vector 40: Timer 3 B */
.word lm3s_cmp0 /* Vector 41: Analog Comparator 0 */
.word lm3s_reserved /* Vector 42: Reserved */
.word lm3s_reserved /* Vector 43: Reserved */
.word lm3s_syscon /* Vector 44: System Control */
.word lm3s_flashcon /* Vector 45: FLASH Control */
.word lm3s_gpiof /* Vector 46: GPIO Port F */
.word lm3s_gpiog /* Vector 47: GPIO Port G */
.word lm3s_reserved /* Vector 48: Reserved */
.word lm3s_reserved /* Vector 49: Reserved */
.word lm3s_reserved /* Vector 50: Reserved */
.word lm3s_tmr3a /* Vector 51: Timer 3 A */
.word lm3s_tmr3b /* Vector 52: Timer 3 B */
.word lm3s_reserved /* Vector 53: Reserved*/
.word lm3s_qei1 /* Vector 54: QEI1 */
.word lm3s_can0 /* Vector 55: Can Controller */
.word lm3s_reserved /* Vector 56: Reserved */
.word lm3s_reserved /* Vector 57: Reserved */
.word lm3s_eth /* Vector 58: Ethernet Controller */
.word lm3s_hib /* Vector 59: Hibernation Module */
.word lm3s_reserved /* Vector 60: Reserved */
.word lm3s_reserved /* Vector 61: Reserved */
.word lm3s_reserved /* Vector 62: Reserved */
.word lm3s_reserved /* Vector 63: Reserved */
.word lm3s_reserved /* Vector 64: Reserved */
.word lm3s_reserved /* Vector 65: Reserved */
.word lm3s_reserved /* Vector 66: Reserved */
.word lm3s_reserved /* Vector 67: Reserved */
.word lm3s_reserved /* Vector 68: Reserved */
.word lm3s_reserved /* Vector 69: Reserved */
.word lm3s_reserved /* Vector 70: Reserved */
#else
# error "Vectors not specified for this LM3S chip"
#endif
.size lm3s_vectors, .-lm3s_vectors
/************************************************************************************
* .text
************************************************************************************/
.text
.type handlers, function
.thumb_func
handlers:
HANDLER lm3s_reserved, LM3S_IRQ_RESERVED /* Unexpected/reserved vector */
HANDLER lm3s_nmi, LM3S_IRQ_NMI /* Vector 2: Non-Maskable Interrupt (NMI) */
HANDLER lm3s_hardfault, LM3S_IRQ_HARDFAULT /* Vector 3: Hard fault */
HANDLER lm3s_mpu, LM3S_IRQ_MEMFAULT /* Vector 4: Memory management (MPU) */
HANDLER lm3s_busfault, LM3S_IRQ_BUSFAULT /* Vector 5: Bus fault */
HANDLER lm3s_usagefault, LM3S_IRQ_USAGEFAULT /* Vector 6: Usage fault */
HANDLER lm3s_svcall, LM3S_IRQ_SVCALL /* Vector 11: SVC call */
HANDLER lm3s_dbgmonitor, LM3S_IRQ_DBGMONITOR /* Vector 12: Debug Monitor */
HANDLER lm3s_pendsv, LM3S_IRQ_PENDSV /* Vector 14: Penable system service request */
HANDLER lm3s_systick, LM3S_IRQ_SYSTICK /* Vector 15: System tick */
#if defined(CONFIG_ARCH_CHIP_LM3S6918)
HANDLER lm3s_gpioa, LM3S_IRQ_GPIOA /* Vector 16: GPIO Port A */
HANDLER lm3s_gpiob, LM3S_IRQ_GPIOB /* Vector 17: GPIO Port B */
HANDLER lm3s_gpioc, LM3S_IRQ_GPIOC /* Vector 18: GPIO Port C */
HANDLER lm3s_gpiod, LM3S_IRQ_GPIOD /* Vector 19: GPIO Port D */
HANDLER lm3s_gpioe, LM3S_IRQ_GPIOE /* Vector 20: GPIO Port E */
HANDLER lm3s_uart0, LM3S_IRQ_UART0 /* Vector 21: UART 0 */
HANDLER lm3s_uart1, LM3S_IRQ_UART1 /* Vector 22: UART 1 */
HANDLER lm3s_ssi0, LM3S_IRQ_SSI0 /* Vector 23: SSI 0 */
HANDLER lm3s_i2c0, LM3S_IRQ_I2C0 /* Vector 24: I2C 0 */
HANDLER lm3s_adc0, LM3S_IRQ_ADC0 /* Vector 30: ADC Sequence 0 */
HANDLER lm3s_adc1, LM3S_IRQ_ADC1 /* Vector 31: ADC Sequence 1 */
HANDLER lm3s_adc2, LM3S_IRQ_ADC2 /* Vector 32: ADC Sequence 2 */
HANDLER lm3s_adc3, LM3S_IRQ_ADC3 /* Vector 33: ADC Sequence 3 */
HANDLER lm3s_wdog, LM3S_IRQ_WDOG /* Vector 34: Watchdog Timer */
HANDLER lm3s_tmr0a, LM3S_IRQ_TIMER0A /* Vector 35: Timer 0 A */
HANDLER lm3s_tmr0b, LM3S_IRQ_TIMER0B /* Vector 36: Timer 0 B */
HANDLER lm3s_tmr1a, LM3S_IRQ_TIMER1A /* Vector 37: Timer 1 A */
HANDLER lm3s_tmr1b, LM3S_IRQ_TIMER1B /* Vector 38: Timer 1 B */
HANDLER lm3s_tmr2a, LM3S_IRQ_TIMER2A /* Vector 39: Timer 2 A */
HANDLER lm3s_tmr2b, LM3S_IRQ_TIMER2B /* Vector 40: Timer 3 B */
HANDLER lm3s_cmp0, LM3S_IRQ_COMPARE0 /* Vector 41: Analog Comparator 0 */
HANDLER lm3s_cmp1, LM3S_IRQ_COMPARE1 /* Vector 42: Analog Comparator 1 */
HANDLER lm3s_syscon, LM3S_IRQ_SYSCON /* Vector 44: System Control */
HANDLER lm3s_flashcon, LM3S_IRQ_FLASHCON /* Vector 45: FLASH Control */
HANDLER lm3s_gpiof, LM3S_IRQ_GPIOF /* Vector 46: GPIO Port F */
HANDLER lm3s_gpiog, LM3S_IRQ_GPIOG /* Vector 47: GPIO Port G */
HANDLER lm3s_gpioh, LM3S_IRQ_GPIOH /* Vector 48: GPIO Port H */
HANDLER lm3s_ssi1, LM3S_IRQ_SSI1 /* Vector 50: SSI 1 */
HANDLER lm3s_tmr3a, LM3S_IRQ_TIMER3A /* Vector 51: Timer 3 A */
HANDLER lm3s_tmr3b, LM3S_IRQ_TIMER3B /* Vector 52: Timer 3 B */
HANDLER lm3s_i2c1, LM3S_IRQ_I2C1 /* Vector 53: I2C 1 */
HANDLER lm3s_eth, LM3S_IRQ_ETHCON /* Vector 58: Ethernet Controller */
HANDLER lm3s_hib, LM3S_IRQ_HIBERNATE /* Vector 59: Hibernation Module */
#elif defined(CONFIG_ARCH_CHIP_LM3S6432)
HANDLER lm3s_gpioa, LM3S_IRQ_GPIOA /* Vector 16: GPIO Port A */
HANDLER lm3s_gpiob, LM3S_IRQ_GPIOB /* Vector 17: GPIO Port B */
HANDLER lm3s_gpioc, LM3S_IRQ_GPIOC /* Vector 18: GPIO Port C */
HANDLER lm3s_gpiod, LM3S_IRQ_GPIOD /* Vector 19: GPIO Port D */
HANDLER lm3s_gpioe, LM3S_IRQ_GPIOE /* Vector 20: GPIO Port E */
HANDLER lm3s_uart0, LM3S_IRQ_UART0 /* Vector 21: UART 0 */
HANDLER lm3s_uart1, LM3S_IRQ_UART1 /* Vector 22: UART 1 */
HANDLER lm3s_ssi0, LM3S_IRQ_SSI0 /* Vector 23: SSI 0 */
HANDLER lm3s_i2c0, LM3S_IRQ_I2C0 /* Vector 24: I2C 0 */
HANDLER lm3s_pwm0, LM3S_IRQ_PWM0 /* Vector 26: PWM Generator 0 */
HANDLER lm3s_adc0, LM3S_IRQ_ADC0 /* Vector 30: ADC Sequence 0 */
HANDLER lm3s_adc1, LM3S_IRQ_ADC1 /* Vector 31: ADC Sequence 1 */
HANDLER lm3s_adc2, LM3S_IRQ_ADC2 /* Vector 32: ADC Sequence 2 */
HANDLER lm3s_adc3, LM3S_IRQ_ADC3 /* Vector 33: ADC Sequence 3 */
HANDLER lm3s_wdog, LM3S_IRQ_WDOG /* Vector 34: Watchdog Timer */
HANDLER lm3s_tmr0a, LM3S_IRQ_TIMER0A /* Vector 35: Timer 0 A */
HANDLER lm3s_tmr0b, LM3S_IRQ_TIMER0B /* Vector 36: Timer 0 B */
HANDLER lm3s_tmr1a, LM3S_IRQ_TIMER1A /* Vector 37: Timer 1 A */
HANDLER lm3s_tmr1b, LM3S_IRQ_TIMER1B /* Vector 38: Timer 1 B */
HANDLER lm3s_tmr2a, LM3S_IRQ_TIMER2A /* Vector 39: Timer 2 A */
HANDLER lm3s_tmr2b, LM3S_IRQ_TIMER2B /* Vector 40: Timer 3 B */
HANDLER lm3s_cmp0, LM3S_IRQ_COMPARE0 /* Vector 41: Analog Comparator 0 */
HANDLER lm3s_cmp1, LM3S_IRQ_COMPARE1 /* Vector 42: Analog Comparator 1 */
HANDLER lm3s_syscon, LM3S_IRQ_SYSCON /* Vector 44: System Control */
HANDLER lm3s_flashcon, LM3S_IRQ_FLASHCON /* Vector 45: FLASH Control */
HANDLER lm3s_gpiof, LM3S_IRQ_GPIOF /* Vector 46: GPIO Port F */
HANDLER lm3s_gpiog, LM3S_IRQ_GPIOG /* Vector 47: GPIO Port G */
HANDLER lm3s_eth, LM3S_IRQ_ETHCON /* Vector 58: Ethernet Controller */
#elif defined(CONFIG_ARCH_CHIP_LM3S6965)
HANDLER lm3s_gpioa, LM3S_IRQ_GPIOA /* Vector 16: GPIO Port A */
HANDLER lm3s_gpiob, LM3S_IRQ_GPIOB /* Vector 17: GPIO Port B */
HANDLER lm3s_gpioc, LM3S_IRQ_GPIOC /* Vector 18: GPIO Port C */
HANDLER lm3s_gpiod, LM3S_IRQ_GPIOD /* Vector 19: GPIO Port D */
HANDLER lm3s_gpioe, LM3S_IRQ_GPIOE /* Vector 20: GPIO Port E */
HANDLER lm3s_uart0, LM3S_IRQ_UART0 /* Vector 21: UART 0 */
HANDLER lm3s_uart1, LM3S_IRQ_UART1 /* Vector 22: UART 1 */
HANDLER lm3s_ssi0, LM3S_IRQ_SSI0 /* Vector 23: SSI 0 */
HANDLER lm3s_i2c0, LM3S_IRQ_I2C0 /* Vector 24: I2C 0 */
HANDLER lm3s_pwmfault, LM3S_IRQ_PWMFAULT /* Vector 25: PWM Fault */
HANDLER lm3s_pwm0, LM3S_IRQ_PWM0 /* Vector 26: PWM Generator 0 */
HANDLER lm3s_pwm1, LM3S_IRQ_PWM1 /* Vector 27: PWM Generator 1 */
HANDLER lm3s_pwm2, LM3S_IRQ_PWM2 /* Vector 28: PWM Generator 2 */
HANDLER lm3s_qei0, LM3S_IRQ_QEI0 /* Vector 29: QEI 0 */
HANDLER lm3s_adc0, LM3S_IRQ_ADC0 /* Vector 30: ADC Sequence 0 */
HANDLER lm3s_adc1, LM3S_IRQ_ADC1 /* Vector 31: ADC Sequence 1 */
HANDLER lm3s_adc2, LM3S_IRQ_ADC2 /* Vector 32: ADC Sequence 2 */
HANDLER lm3s_adc3, LM3S_IRQ_ADC3 /* Vector 33: ADC Sequence 3 */
HANDLER lm3s_wdog, LM3S_IRQ_WDOG /* Vector 34: Watchdog Timer */
HANDLER lm3s_tmr0a, LM3S_IRQ_TIMER0A /* Vector 35: Timer 0 A */
HANDLER lm3s_tmr0b, LM3S_IRQ_TIMER0B /* Vector 36: Timer 0 B */
HANDLER lm3s_tmr1a, LM3S_IRQ_TIMER1A /* Vector 37: Timer 1 A */
HANDLER lm3s_tmr1b, LM3S_IRQ_TIMER1B /* Vector 38: Timer 1 B */
HANDLER lm3s_tmr2a, LM3S_IRQ_TIMER2A /* Vector 39: Timer 2 A */
HANDLER lm3s_tmr2b, LM3S_IRQ_TIMER2B /* Vector 40: Timer 3 B */
HANDLER lm3s_cmp0, LM3S_IRQ_COMPARE0 /* Vector 41: Analog Comparator 0 */
HANDLER lm3s_cmp1, LM3S_IRQ_COMPARE1 /* Vector 42: Analog Comparator 1 */
HANDLER lm3s_syscon, LM3S_IRQ_SYSCON /* Vector 44: System Control */
HANDLER lm3s_flashcon, LM3S_IRQ_FLASHCON /* Vector 45: FLASH Control */
HANDLER lm3s_gpiof, LM3S_IRQ_GPIOF /* Vector 46: GPIO Port F */
HANDLER lm3s_gpiog, LM3S_IRQ_GPIOG /* Vector 47: GPIO Port G */
HANDLER lm3s_uart2, LM3S_IRQ_UART1 /* Vector 49: UART 1 */
HANDLER lm3s_tmr3a, LM3S_IRQ_TIMER3A /* Vector 51: Timer 3 A */
HANDLER lm3s_tmr3b, LM3S_IRQ_TIMER3B /* Vector 52: Timer 3 B */
HANDLER lm3s_i2c1, LM3S_IRQ_I2C1 /* Vector 53: I2C 1 */
HANDLER lm3s_qei1, LM3S_IRQ_QEI1 /* Vector 54: QEI 1 */
HANDLER lm3s_eth, LM3S_IRQ_ETHCON /* Vector 58: Ethernet Controller */
HANDLER lm3s_hib, LM3S_IRQ_HIBERNATE /* Vector 59: Hibernation Module */
#elif defined(CONFIG_ARCH_CHIP_LM3S8962)
HANDLER lm3s_gpioa, LM3S_IRQ_GPIOA /* Vector 16: GPIO Port A */
HANDLER lm3s_gpiob, LM3S_IRQ_GPIOB /* Vector 17: GPIO Port B */
HANDLER lm3s_gpioc, LM3S_IRQ_GPIOC /* Vector 18: GPIO Port C */
HANDLER lm3s_gpiod, LM3S_IRQ_GPIOD /* Vector 19: GPIO Port D */
HANDLER lm3s_gpioe, LM3S_IRQ_GPIOE /* Vector 20: GPIO Port E */
HANDLER lm3s_uart0, LM3S_IRQ_UART0 /* Vector 21: UART 0 */
HANDLER lm3s_uart1, LM3S_IRQ_UART1 /* Vector 22: UART 1 */
HANDLER lm3s_ssi0, LM3S_IRQ_SSI0 /* Vector 23: SSI 0 */
HANDLER lm3s_i2c0, LM3S_IRQ_I2C0 /* Vector 24: I2C 0 */
HANDLER lm3s_pwmfault, LM3S_IRQ_PWMFAULT /* Vector 25: PWM Fault */
HANDLER lm3s_pwm0, LM3S_IRQ_PWM0 /* Vector 26: PWM Generator 0 */
HANDLER lm3s_pwm1, LM3S_IRQ_PWM1 /* Vector 27: PWM Generator 1 */
HANDLER lm3s_pwm2, LM3S_IRQ_PWM2 /* Vector 28: PWM Generator 2 */
HANDLER lm3s_qei0, LM3S_IRQ_QEI0 /* Vector 29: QEI 0 */
HANDLER lm3s_adc0, LM3S_IRQ_ADC0 /* Vector 30: ADC Sequence 0 */
HANDLER lm3s_adc1, LM3S_IRQ_ADC1 /* Vector 31: ADC Sequence 1 */
HANDLER lm3s_adc2, LM3S_IRQ_ADC2 /* Vector 32: ADC Sequence 2 */
HANDLER lm3s_adc3, LM3S_IRQ_ADC3 /* Vector 33: ADC Sequence 3 */
HANDLER lm3s_wdog, LM3S_IRQ_WDOG /* Vector 34: Watchdog Timer */
HANDLER lm3s_tmr0a, LM3S_IRQ_TIMER0A /* Vector 35: Timer 0 A */
HANDLER lm3s_tmr0b, LM3S_IRQ_TIMER0B /* Vector 36: Timer 0 B */
HANDLER lm3s_tmr1a, LM3S_IRQ_TIMER1A /* Vector 37: Timer 1 A */
HANDLER lm3s_tmr1b, LM3S_IRQ_TIMER1B /* Vector 38: Timer 1 B */
HANDLER lm3s_tmr2a, LM3S_IRQ_TIMER2A /* Vector 39: Timer 2 A */
HANDLER lm3s_tmr2b, LM3S_IRQ_TIMER2B /* Vector 40: Timer 3 B */
HANDLER lm3s_cmp0, LM3S_IRQ_COMPARE0 /* Vector 41: Analog Comparator 0 */
HANDLER lm3s_syscon, LM3S_IRQ_SYSCON /* Vector 44: System Control */
HANDLER lm3s_flashcon, LM3S_IRQ_FLASHCON /* Vector 45: FLASH Control */
HANDLER lm3s_gpiof, LM3S_IRQ_GPIOF /* Vector 46: GPIO Port F */
HANDLER lm3s_gpiog, LM3S_IRQ_GPIOG /* Vector 47: GPIO Port G */
HANDLER lm3s_uart2, LM3S_IRQ_UART1 /* Vector 49: UART 1 */
HANDLER lm3s_tmr3a, LM3S_IRQ_TIMER3A /* Vector 51: Timer 3 A */
HANDLER lm3s_tmr3b, LM3S_IRQ_TIMER3B /* Vector 52: Timer 3 B */
HANDLER lm3s_i2c1, LM3S_IRQ_I2C1 /* Vector 53: I2C 1 */
HANDLER lm3s_qei1, LM3S_IRQ_QEI1 /* Vector 54: QEI 1 */
HANDLER lm3s_can0, LM3S_IRQ_CAN0 /* Vector 55: CAN 0 */
HANDLER lm3s_eth, LM3S_IRQ_ETHCON /* Vector 58: Ethernet Controller */
HANDLER lm3s_hib, LM3S_IRQ_HIBERNATE /* Vector 59: Hibernation Module */
#elif defined(CONFIG_ARCH_CHIP_LM3S9B96)
HANDLER lm3s_gpioa, LM3S_IRQ_GPIOA /* Vector 16: GPIO Port A */
HANDLER lm3s_gpiob, LM3S_IRQ_GPIOB /* Vector 17: GPIO Port B */
HANDLER lm3s_gpioc, LM3S_IRQ_GPIOC /* Vector 18: GPIO Port C */
HANDLER lm3s_gpiod, LM3S_IRQ_GPIOD /* Vector 19: GPIO Port D */
HANDLER lm3s_gpioe, LM3S_IRQ_GPIOE /* Vector 20: GPIO Port E */
HANDLER lm3s_uart0, LM3S_IRQ_UART0 /* Vector 21: UART 0 */
HANDLER lm3s_uart1, LM3S_IRQ_UART1 /* Vector 22: UART 1 */
HANDLER lm3s_ssi0, LM3S_IRQ_SSI0 /* Vector 23: SSI 0 */
HANDLER lm3s_i2c0, LM3S_IRQ_I2C0 /* Vector 24: I2C 0 */
HANDLER lm3s_pwmfault, LM3S_IRQ_PWMFAULT /* Vector 25: PWM Fault */
HANDLER lm3s_pwm0, LM3S_IRQ_PWM0 /* Vector 26: PWM Generator 0 */
HANDLER lm3s_pwm1, LM3S_IRQ_PWM1 /* Vector 27: PWM Generator 1 */
HANDLER lm3s_pwm2, LM3S_IRQ_PWM2 /* Vector 28: PWM Generator 2 */
HANDLER lm3s_qei0, LM3S_IRQ_QEI0 /* Vector 29: QEI 0 */
HANDLER lm3s_adc0, LM3S_IRQ_ADC0 /* Vector 30: ADC Sequence 0 */
HANDLER lm3s_adc1, LM3S_IRQ_ADC1 /* Vector 31: ADC Sequence 1 */
HANDLER lm3s_adc2, LM3S_IRQ_ADC2 /* Vector 32: ADC Sequence 2 */
HANDLER lm3s_adc3, LM3S_IRQ_ADC3 /* Vector 33: ADC Sequence 3 */
HANDLER lm3s_wdog, LM3S_IRQ_WDOG /* Vector 34: Watchdog Timer */
HANDLER lm3s_tmr0a, LM3S_IRQ_TIMER0A /* Vector 35: Timer 0 A */
HANDLER lm3s_tmr0b, LM3S_IRQ_TIMER0B /* Vector 36: Timer 0 B */
HANDLER lm3s_tmr1a, LM3S_IRQ_TIMER1A /* Vector 37: Timer 1 A */
HANDLER lm3s_tmr1b, LM3S_IRQ_TIMER1B /* Vector 38: Timer 1 B */
HANDLER lm3s_tmr2a, LM3S_IRQ_TIMER2A /* Vector 39: Timer 2 A */
HANDLER lm3s_tmr2b, LM3S_IRQ_TIMER2B /* Vector 40: Timer 3 B */
HANDLER lm3s_cmp0, LM3S_IRQ_COMPARE0 /* Vector 41: Analog Comparator 0 */
HANDLER lm3s_cmp1, LM3S_IRQ_COMPARE1 /* Vector 42: Analog Comparator 1 */
HANDLER lm3s_cmp2, LM3S_IRQ_COMPARE2 /* Vector 43: Analog Comparator 2 */
HANDLER lm3s_syscon, LM3S_IRQ_SYSCON /* Vector 44: System Control */
HANDLER lm3s_flashcon, LM3S_IRQ_FLASHCON /* Vector 45: FLASH Control */
HANDLER lm3s_gpiof, LM3S_IRQ_GPIOF /* Vector 46: GPIO Port F */
HANDLER lm3s_gpiog, LM3S_IRQ_GPIOG /* Vector 47: GPIO Port G */
HANDLER lm3s_gpioh, LM3S_IRQ_GPIOH /* Vector 48: GPIO Port H */
HANDLER lm3s_uart2, LM3S_IRQ_UART2 /* Vector 49: UART 2 */
HANDLER lm3s_ssi1, LM3S_IRQ_SSI1 /* Vector 50: GPIO Port H */
HANDLER lm3s_tmr3a, LM3S_IRQ_TIMER3A /* Vector 51: Timer 3 A */
HANDLER lm3s_tmr3b, LM3S_IRQ_TIMER3B /* Vector 52: Timer 3 B */
HANDLER lm3s_i2c1, LM3S_IRQ_I2C1 /* Vector 53: I2C 1 */
HANDLER lm3s_qei1, LM3S_IRQ_QEI1 /* Vector 54: QEI 1 */
HANDLER lm3s_can0, LM3S_IRQ_CAN0 /* Vector 55: CAN 0 */
HANDLER lm3s_can1, LM3S_IRQ_CAN1 /* Vector 56: CAN 1 */
HANDLER lm3s_eth, LM3S_IRQ_ETHCON /* Vector 58: Ethernet Controller */
HANDLER lm3s_usb, LM3S_IRQ_USB /* Vector 60: USB */
HANDLER lm3s_pwm3, LM3S_IRQ_PWM3 /* Vector 61: PWM 3 */
HANDLER lm3s_udmasoft, LM3S_IRQ_UDMASOFT /* Vector 62: uDMA Software */
HANDLER lm3s_udmaerror, LM3S_IRQ_UDMAERROR /* Vector 63: uDMA Error */
HANDLER lm3s_adc1_0, LM3S_IRQ_ADC1_0 /* Vector 64: ADC1 Sequence 0 */
HANDLER lm3s_adc1_1, LM3S_IRQ_ADC1_1 /* Vector 65: ADC1 Sequence 1 */
HANDLER lm3s_adc1_2, LM3S_IRQ_ADC1_2 /* Vector 66: ADC1 Sequence 2 */
HANDLER lm3s_adc1_3, LM3S_IRQ_ADC1_3 /* Vector 67: ADC1 Sequence 3 */
HANDLER lm3s_i2s0, LM3S_IRQ_I2S0 /* Vector 68: I2S 0 */
HANDLER lm3s_epi, LM3S_IRQ_EPI /* Vector 69: EPI */
HANDLER lm3s_gpioj, LM3S_IRQ_GPIOJ /* Vector 70: GPIO Port J */
#else
# error "Vectors not specified for this LM3S chip"
#endif
/* Common IRQ handling logic. On entry here, the return stack is on either
* the PSP or the MSP and looks like the following:
*
* REG_XPSR
* REG_R15
* REG_R14
* REG_R12
* REG_R3
* REG_R2
* REG_R1
* MSP->REG_R0
*
* And
* R0 contains the IRQ number
* R14 Contains the EXC_RETURN value
* We are in handler mode and the current SP is the MSP
*/
lm3s_irqcommon:
/* Complete the context save */
#ifdef CONFIG_NUTTX_KERNEL
/* The EXC_RETURN value will be 0xfffffff9 (privileged thread) or 0xfffffff1
* (handler mode) if the state is on the MSP. It can only be on the PSP if
* EXC_RETURN is 0xfffffffd (unprivileged thread)
*/
adds r2, r14, #3 /* If R14=0xfffffffd, then r2 == 0 */
ite ne /* Next two instructions are condition */
mrsne r1, msp /* R1=The main stack pointer */
mrseq r1, psp /* R1=The process stack pointer */
#else
mrs r1, msp /* R1=The main stack pointer */
#endif
mov r2, r1 /* R2=Copy of the main/process stack pointer */
add r2, #HW_XCPT_SIZE /* R2=MSP/PSP before the interrupt was taken */
mrs r3, primask /* R3=Current PRIMASK setting */
#ifdef CONFIG_NUTTX_KERNEL
stmdb r1!, {r2-r11,r14} /* Save the remaining registers plus the SP value */
#else
stmdb r1!, {r2-r11} /* Save the remaining registers plus the SP value */
#endif
/* Disable interrupts, select the stack to use for interrupt handling
* and call up_doirq to handle the interrupt
*/
cpsid i /* Disable further interrupts */
/* If CONFIG_ARCH_INTERRUPTSTACK is defined, we will use a special interrupt
* stack pointer. The way that this is done here prohibits nested interrupts!
* Otherwise, we will re-use the main stack for interrupt level processing.
*/
#if CONFIG_ARCH_INTERRUPTSTACK > 3
ldr sp, =g_intstackbase
str r1, [sp, #-4]! /* Save the MSP on the interrupt stack */
bl up_doirq /* R0=IRQ, R1=register save (msp) */
ldr r1, [sp, #+4]! /* Recover R1=main stack pointer */
#else
mov sp, r1 /* We are using the main stack pointer */
bl up_doirq /* R0=IRQ, R1=register save (msp) */
mov r1, sp /* Recover R1=main stack pointer */
#endif
/* On return from up_doirq, R0 will hold a pointer to register context
* array to use for the interrupt return. If that return value is the same
* as current stack pointer, then things are relatively easy.
*/
cmp r0, r1 /* Context switch? */
beq 1f /* Branch if no context switch */
/* We are returning with a pending context switch. This case is different
* because in this case, the register save structure does not lie on the
* stack but, rather, are within a TCB structure. We'll have to copy some
* values to the stack.
*/
add r1, r0, #SW_XCPT_SIZE /* R1=Address of HW save area in reg array */
ldmia r1, {r4-r11} /* Fetch eight registers in HW save area */
ldr r1, [r0, #(4*REG_SP)] /* R1=Value of SP before interrupt */
stmdb r1!, {r4-r11} /* Store eight registers in HW save area */
#ifdef CONFIG_NUTTX_KERNEL
ldmia r0, {r2-r11,r14} /* Recover R4-R11, r14 + 2 temp values */
#else
ldmia r0, {r2-r11} /* Recover R4-R11 + 2 temp values */
#endif
b 2f /* Re-join common logic */
/* We are returning with no context switch. We simply need to "unwind"
* the same stack frame that we created
*/
1:
#ifdef CONFIG_NUTTX_KERNEL
ldmia r1!, {r2-r11,r14} /* Recover R4-R11, r14 + 2 temp values */
#else
ldmia r1!, {r2-r11} /* Recover R4-R11 + 2 temp values */
#endif
2:
#ifdef CONFIG_NUTTX_KERNEL
/* The EXC_RETURN value will be 0xfffffff9 (privileged thread) or 0xfffffff1
* (handler mode) if the state is on the MSP. It can only be on the PSP if
* EXC_RETURN is 0xfffffffd (unprivileged thread)
*/
adds r0, r14, #3 /* If R14=0xfffffffd, then r0 == 0 */
ite ne /* Next two instructions are condition */
msrne msp, r1 /* R1=The main stack pointer */
msreq psp, r1 /* R1=The process stack pointer */
#else
msr msp, r1 /* Recover the return MSP value */
/* Preload r14 with the special return value first (so that the return
* actually occurs with interrupts still disabled).
*/
ldr r14, =EXC_RETURN /* Load the special value */
#endif
/* Restore the interrupt state */
msr primask, r3 /* Restore interrupts */
/* Always return with R14 containing the special value that will: (1)
* return to thread mode, and (2) continue to use the MSP
*/
bx r14 /* And return */
.size handlers, .-handlers
/************************************************************************************
* Name: up_interruptstack/g_intstackbase
*
* Description:
* Shouldn't happen
*
************************************************************************************/
#if CONFIG_ARCH_INTERRUPTSTACK > 3
.bss
.global g_intstackbase
.align 4
up_interruptstack:
.skip (CONFIG_ARCH_INTERRUPTSTACK & ~3)
g_intstackbase:
.size up_interruptstack, .-up_interruptstack
#endif
/************************************************************************************
* .rodata
************************************************************************************/
.section .rodata, "a"
/* Variables: _sbss is the start of the BSS region (see ld.script) _ebss is the end
* of the BSS regsion (see ld.script). The idle task stack starts at the end of BSS
* and is of size CONFIG_IDLETHREAD_STACKSIZE. The IDLE thread is the thread that
* the system boots on and, eventually, becomes the idle, do nothing task that runs
* only when there is nothing else to run. The heap continues from there until the
* end of memory. See g_heapbase below.
*/
.globl g_heapbase
.type g_heapbase, object
g_heapbase:
.long _ebss+CONFIG_IDLETHREAD_STACKSIZE
.size g_heapbase, .-g_heapbase
.end

View File

@ -1,5 +1,5 @@
/****************************************************************************
* arch/arm/src/lm/lm3s_dumpgpio.c
* arch/arm/src/lm/lm_dumpgpio.c
*
* Copyright (C) 2009-2010 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
@ -58,7 +58,7 @@
* Private Types
****************************************************************************/
/* NOTE: this is duplicated in lm3s_gpio.c */
/* NOTE: this is duplicated in lm_gpio.c */
#ifdef LM3S_GPIOH_BASE
static const uint32_t g_gpiobase[8] =
@ -83,7 +83,7 @@ static const char g_portchar[8] = { 'A', 'B', 'C', 'D', 'E', 'F', 'G', '?' };
****************************************************************************/
/****************************************************************************
* Name: lm3s_gpiobaseaddress
* Name: lm_gpiobaseaddress
*
* Description:
* Given a GPIO enumeration value, return the base address of the
@ -91,13 +91,13 @@ static const char g_portchar[8] = { 'A', 'B', 'C', 'D', 'E', 'F', 'G', '?' };
*
****************************************************************************/
static inline uint32_t lm3s_gpiobaseaddress(int port)
static inline uint32_t lm_gpiobaseaddress(int port)
{
return g_gpiobase[port & 7];
}
/****************************************************************************
* Name: lm3s_gpioport
* Name: lm_gpioport
*
* Description:
* Given a GPIO enumeration value, return the base address of the
@ -105,7 +105,7 @@ static inline uint32_t lm3s_gpiobaseaddress(int port)
*
****************************************************************************/
static inline uint8_t lm3s_gpioport(int port)
static inline uint8_t lm_gpioport(int port)
{
return g_portchar[port & 7];
}
@ -115,14 +115,14 @@ static inline uint8_t lm3s_gpioport(int port)
****************************************************************************/
/****************************************************************************
* Function: lm3s_dumpgpio
* Function: lm_dumpgpio
*
* Description:
* Dump all GPIO registers associated with the provided base address
*
****************************************************************************/
int lm3s_dumpgpio(uint32_t pinset, const char *msg)
int lm_dumpgpio(uint32_t pinset, const char *msg)
{
irqstate_t flags;
unsigned int port = (pinset & GPIO_PORT_MASK) >> GPIO_PORT_SHIFT;
@ -132,7 +132,7 @@ int lm3s_dumpgpio(uint32_t pinset, const char *msg)
/* Get the base address associated with the GPIO port */
base = lm3s_gpiobaseaddress(port);
base = lm_gpiobaseaddress(port);
DEBUGASSERT(base != 0);
/* The following requires exclusive access to the GPIO registers */
@ -142,7 +142,7 @@ int lm3s_dumpgpio(uint32_t pinset, const char *msg)
enabled = ((rcgc2 & SYSCON_RCGC2_GPIO(port)) != 0);
lldbg("GPIO%c pinset: %08x base: %08x -- %s\n",
lm3s_gpioport(port), pinset, base, msg);
lm_gpioport(port), pinset, base, msg);
lldbg(" RCGC2: %08x (%s)\n",
rcgc2, enabled ? "enabled" : "disabled" );

View File

@ -74,7 +74,7 @@ extern "C"
****************************************************************************/
/****************************************************************************
* Function: lm3s_ethinitialize
* Function: lm_ethinitialize
*
* Description:
* Initialize the Ethernet driver for one interface. If the LM3S chip
@ -92,7 +92,7 @@ extern "C"
*
****************************************************************************/
int lm3s_ethinitialize(int intf);
int lm_ethinitialize(int intf);
#if defined(__cplusplus)
}

View File

@ -1,6 +1,6 @@
/****************************************************************************
* arch/arm/src/lm/lm3s_gpio.c
* arch/arm/src/chip/lm3s_gpio.c
* arch/arm/src/lm/lm_gpio.c
* arch/arm/src/chip/lm_gpio.c
*
* Copyright (C) 2009-2010 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
@ -169,7 +169,7 @@ static const uint32_t g_gpiobase[LM3S_NPORTS] =
****************************************************************************/
/****************************************************************************
* Name: lm3s_gpiobaseaddress
* Name: lm_gpiobaseaddress
*
* Description:
* Given a GPIO enumeration value, return the base address of the
@ -177,7 +177,7 @@ static const uint32_t g_gpiobase[LM3S_NPORTS] =
*
****************************************************************************/
static uint32_t lm3s_gpiobaseaddress(unsigned int port)
static uint32_t lm_gpiobaseaddress(unsigned int port)
{
uint32_t gpiobase = 0;
if (port < LM3S_NPORTS)
@ -188,14 +188,14 @@ static uint32_t lm3s_gpiobaseaddress(unsigned int port)
}
/****************************************************************************
* Name: lm3s_gpiofunc
* Name: lm_gpiofunc
*
* Description:
* Configure GPIO registers for a specific function
*
****************************************************************************/
static void lm3s_gpiofunc(uint32_t base, uint32_t pinno, const struct gpio_func_s *func)
static void lm_gpiofunc(uint32_t base, uint32_t pinno, const struct gpio_func_s *func)
{
uint32_t setbit;
uint32_t clrbit;
@ -305,14 +305,14 @@ static void lm3s_gpiofunc(uint32_t base, uint32_t pinno, const struct gpio_func_
}
/****************************************************************************
* Name: lm3s_gpiopadstrength
* Name: lm_gpiopadstrength
*
* Description:
* Set up pad strength and pull-ups
*
****************************************************************************/
static inline void lm3s_gpiopadstrength(uint32_t base, uint32_t pin, uint32_t cfgset)
static inline void lm_gpiopadstrength(uint32_t base, uint32_t pin, uint32_t cfgset)
{
int strength = (cfgset & GPIO_STRENGTH_MASK) >> GPIO_STRENGTH_SHIFT;
uint32_t regoffset;
@ -392,19 +392,19 @@ static inline void lm3s_gpiopadstrength(uint32_t base, uint32_t pin, uint32_t cf
}
/****************************************************************************
* Name: lm3s_gpiopadtype
* Name: lm_gpiopadtype
*
* Description:
* Set up pad strength and pull-ups. Some of these values may be over-
* written by lm3s_gpiofunc, depending on the function selection. Others
* written by lm_gpiofunc, depending on the function selection. Others
* are optional for different function selections.
*
****************************************************************************/
static inline void lm3s_gpiopadtype(uint32_t base, uint32_t pin, uint32_t cfgset)
static inline void lm_gpiopadtype(uint32_t base, uint32_t pin, uint32_t cfgset)
{
int padtype = (cfgset & GPIO_PADTYPE_MASK) >> GPIO_PADTYPE_SHIFT;
#if 0 /* always overwritten by lm3s_gpiofunc */
#if 0 /* always overwritten by lm_gpiofunc */
uint32_t odrset;
uint32_t odrclr;
#endif
@ -412,7 +412,7 @@ static inline void lm3s_gpiopadtype(uint32_t base, uint32_t pin, uint32_t cfgset
uint32_t purclr;
uint32_t pdrset;
uint32_t pdrclr;
#if 0 /* always overwritten by lm3s_gpiofunc */
#if 0 /* always overwritten by lm_gpiofunc */
uint32_t denset;
uint32_t denclr;
#endif
@ -420,7 +420,7 @@ static inline void lm3s_gpiopadtype(uint32_t base, uint32_t pin, uint32_t cfgset
/* Assume digital GPIO function, push-pull with no pull-up or pull-down */
#if 0 /* always overwritten by lm3s_gpiofunc */
#if 0 /* always overwritten by lm_gpiofunc */
odrset = 0;
odrclr = pin;
#endif
@ -428,7 +428,7 @@ static inline void lm3s_gpiopadtype(uint32_t base, uint32_t pin, uint32_t cfgset
purclr = pin;
pdrset = 0;
pdrclr = pin;
#if 0 /* always overwritten by lm3s_gpiofunc */
#if 0 /* always overwritten by lm_gpiofunc */
denset = pin;
denclr = 0;
#endif
@ -455,7 +455,7 @@ static inline void lm3s_gpiopadtype(uint32_t base, uint32_t pin, uint32_t cfgset
break;
case 3: /* Open-drain */
{
#if 0 /* always overwritten by lm3s_gpiofunc */
#if 0 /* always overwritten by lm_gpiofunc */
odrset = pin;
odrclr = 0;
#endif
@ -463,7 +463,7 @@ static inline void lm3s_gpiopadtype(uint32_t base, uint32_t pin, uint32_t cfgset
break;
case 4: /* Open-drain with weak pull-up */
{
#if 0 /* always overwritten by lm3s_gpiofunc */
#if 0 /* always overwritten by lm_gpiofunc */
odrset = pin;
odrclr = 0;
#endif
@ -473,7 +473,7 @@ static inline void lm3s_gpiopadtype(uint32_t base, uint32_t pin, uint32_t cfgset
break;
case 5: /* Open-drain with weak pull-down */
{
#if 0 /* always overwritten by lm3s_gpiofunc */
#if 0 /* always overwritten by lm_gpiofunc */
odrset = pin;
odrclr = 0;
#endif
@ -483,7 +483,7 @@ static inline void lm3s_gpiopadtype(uint32_t base, uint32_t pin, uint32_t cfgset
break;
case 6: /* Analog comparator */
{
#if 0 /* always overwritten by lm3s_gpiofunc */
#if 0 /* always overwritten by lm_gpiofunc */
denset = 0;
denclr = pin;
#endif
@ -502,7 +502,7 @@ static inline void lm3s_gpiopadtype(uint32_t base, uint32_t pin, uint32_t cfgset
* drain output when set to 1."
*/
#if 0 /* always overwritten by lm3s_gpiofunc */
#if 0 /* always overwritten by lm_gpiofunc */
regval = getreg32(base + LM3S_GPIO_ODR_OFFSET);
regval &= ~odrclr;
regval |= odrset;
@ -540,7 +540,7 @@ static inline void lm3s_gpiopadtype(uint32_t base, uint32_t pin, uint32_t cfgset
* corresponding GPIODEN bit must be set."
*/
#if 0 /* always overwritten by lm3s_gpiofunc */
#if 0 /* always overwritten by lm_gpiofunc */
regval = getreg32(base + LM3S_GPIO_DEN_OFFSET);
regval &= ~denclr;
regval |= denset;
@ -549,28 +549,28 @@ static inline void lm3s_gpiopadtype(uint32_t base, uint32_t pin, uint32_t cfgset
}
/****************************************************************************
* Name: lm3s_initoutput
* Name: lm_initoutput
*
* Description:
* Set the GPIO output value
*
****************************************************************************/
static inline void lm3s_initoutput(uint32_t cfgset)
static inline void lm_initoutput(uint32_t cfgset)
{
bool value = ((cfgset & GPIO_VALUE_MASK) != GPIO_VALUE_ZERO);
lm3s_gpiowrite(cfgset, value);
lm_gpiowrite(cfgset, value);
}
/****************************************************************************
* Name: lm3s_interrupt
* Name: lm_interrupt
*
* Description:
* Configure the interrupt pin.
*
****************************************************************************/
static inline void lm3s_interrupt(uint32_t base, uint32_t pin, uint32_t cfgset)
static inline void lm_interrupt(uint32_t base, uint32_t pin, uint32_t cfgset)
{
int inttype = (cfgset & GPIO_INT_MASK) >> GPIO_INT_SHIFT;
uint32_t regval;
@ -694,14 +694,14 @@ static inline void lm3s_interrupt(uint32_t base, uint32_t pin, uint32_t cfgset)
****************************************************************************/
/****************************************************************************
* Name: lm3s_configgpio
* Name: lm_configgpio
*
* Description:
* Configure a GPIO pin based on bit-encoded description of the pin.
*
****************************************************************************/
int lm3s_configgpio(uint32_t cfgset)
int lm_configgpio(uint32_t cfgset)
{
irqstate_t flags;
unsigned int func;
@ -722,7 +722,7 @@ int lm3s_configgpio(uint32_t cfgset)
/* Get the base address associated with the GPIO port */
base = lm3s_gpiobaseaddress(port);
base = lm_gpiobaseaddress(port);
DEBUGASSERT(base != 0);
/* The following requires exclusive access to the GPIO registers */
@ -742,25 +742,25 @@ int lm3s_configgpio(uint32_t cfgset)
* to perform reconfiguration.
*/
lm3s_gpiofunc(base, pinno, &g_funcbits[0]);
lm_gpiofunc(base, pinno, &g_funcbits[0]);
/* Then set up pad strengths and pull-ups. These setups should be done before
* setting up the function because some function settings will over-ride these
* user options.
*/
lm3s_gpiopadstrength(base, pin, cfgset);
lm3s_gpiopadtype(base, pin, cfgset);
lm_gpiopadstrength(base, pin, cfgset);
lm_gpiopadtype(base, pin, cfgset);
/* Then set up the real pin function */
lm3s_gpiofunc(base, pinno, &g_funcbits[func]);
lm_gpiofunc(base, pinno, &g_funcbits[func]);
/* Special GPIO digital output pins */
if (func == 1 || func == 3)
{
lm3s_initoutput(cfgset);
lm_initoutput(cfgset);
}
@ -768,7 +768,7 @@ int lm3s_configgpio(uint32_t cfgset)
else if (func == 7)
{
lm3s_interrupt(base, pin, cfgset);
lm_interrupt(base, pin, cfgset);
}
irqrestore(flags);
@ -776,14 +776,14 @@ int lm3s_configgpio(uint32_t cfgset)
}
/****************************************************************************
* Name: lm3s_gpiowrite
* Name: lm_gpiowrite
*
* Description:
* Write one or zero to the selected GPIO pin
*
****************************************************************************/
void lm3s_gpiowrite(uint32_t pinset, bool value)
void lm_gpiowrite(uint32_t pinset, bool value)
{
unsigned int port;
unsigned int pinno;
@ -796,7 +796,7 @@ void lm3s_gpiowrite(uint32_t pinset, bool value)
/* Get the base address associated with the GPIO port */
base = lm3s_gpiobaseaddress(port);
base = lm_gpiobaseaddress(port);
/* "The GPIO DATA register is the data register. In software control mode,
* values written in the GPIO DATA register are transferred onto the GPIO
@ -814,14 +814,14 @@ void lm3s_gpiowrite(uint32_t pinset, bool value)
}
/****************************************************************************
* Name: lm3s_gpioread
* Name: lm_gpioread
*
* Description:
* Read one or zero from the selected GPIO pin
*
****************************************************************************/
bool lm3s_gpioread(uint32_t pinset, bool value)
bool lm_gpioread(uint32_t pinset, bool value)
{
unsigned int port;
unsigned int pinno;
@ -834,7 +834,7 @@ bool lm3s_gpioread(uint32_t pinset, bool value)
/* Get the base address associated with the GPIO port */
base = lm3s_gpiobaseaddress(port);
base = lm_gpiobaseaddress(port);
/* "... the values read from this register are determined for each bit
* by the mask bit derived from the address used to access the data register,

View File

@ -53,7 +53,7 @@
* Pre-processor Definitions
************************************************************************************/
/* Bit-encoded input to lm3s_configgpio() *******************************************/
/* Bit-encoded input to lm_configgpio() *********************************************/
/* Encoding:
* FFFS SPPP IIIn nnnn nnnn nnnn VPPP PBBB
@ -161,57 +161,57 @@ extern "C"
{
#endif
/****************************************************************************
/************************************************************************************
* Public Function Prototypes
****************************************************************************/
************************************************************************************/
/****************************************************************************
* Name: lm3s_configgpio
/************************************************************************************
* Name: lm_configgpio
*
* Description:
* Configure a GPIO pin based on bit-encoded description of the pin.
*
****************************************************************************/
************************************************************************************/
int lm3s_configgpio(uint32_t cfgset);
int lm_configgpio(uint32_t cfgset);
/****************************************************************************
* Name: lm3s_gpiowrite
/************************************************************************************
* Name: lm_gpiowrite
*
* Description:
* Write one or zero to the selected GPIO pin
*
****************************************************************************/
************************************************************************************/
void lm3s_gpiowrite(uint32_t pinset, bool value);
void lm_gpiowrite(uint32_t pinset, bool value);
/****************************************************************************
* Name: lm3s_gpioread
/************************************************************************************
* Name: lm_gpioread
*
* Description:
* Read one or zero from the selected GPIO pin
*
****************************************************************************/
************************************************************************************/
bool lm3s_gpioread(uint32_t pinset, bool value);
bool lm_gpioread(uint32_t pinset, bool value);
/****************************************************************************
* Function: lm3s_dumpgpio
/************************************************************************************
* Function: lm_dumpgpio
*
* Description:
* Dump all GPIO registers associated with the provided base address
*
****************************************************************************/
************************************************************************************/
int lm3s_dumpgpio(uint32_t pinset, const char *msg);
int lm_dumpgpio(uint32_t pinset, const char *msg);
/****************************************************************************
/************************************************************************************
* Name: gpio_irqinitialize
*
* Description:
* Initialize all vectors to the unexpected interrupt handler
*
****************************************************************************/
************************************************************************************/
int weak_function gpio_irqinitialize(void);

View File

@ -1,6 +1,6 @@
/****************************************************************************
* arch/arm/src/lm/lm3s_gpioirq.c
* arch/arm/src/chip/lm3s_gpioirq.c
* arch/arm/src/lm/lm_gpioirq.c
* arch/arm/src/chip/lm_gpioirq.c
*
* Copyright (C) 2009-2010, 2012 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
@ -72,25 +72,25 @@ static FAR xcpt_t g_gpioirqvector[NR_GPIO_IRQS];
static const uint32_t g_gpiobase[] =
{
#ifndef CONFIG_LM3S_DISABLE_GPIOA_IRQS
#ifndef CONFIG_LM_DISABLE_GPIOA_IRQS
LM3S_GPIOA_BASE,
#endif
#ifndef CONFIG_LM3S_DISABLE_GPIOB_IRQS
#ifndef CONFIG_LM_DISABLE_GPIOB_IRQS
LM3S_GPIOB_BASE,
#endif
#ifndef CONFIG_LM3S_DISABLE_GPIOC_IRQS
#ifndef CONFIG_LM_DISABLE_GPIOC_IRQS
LM3S_GPIOC_BASE,
#endif
#ifndef CONFIG_LM3S_DISABLE_GPIOD_IRQS
#ifndef CONFIG_LM_DISABLE_GPIOD_IRQS
LM3S_GPIOD_BASE,
#endif
#ifndef CONFIG_LM3S_DISABLE_GPIOE_IRQS
#ifndef CONFIG_LM_DISABLE_GPIOE_IRQS
LM3S_GPIOE_BASE,
#endif
#ifndef CONFIG_LM3S_DISABLE_GPIOF_IRQS
#ifndef CONFIG_LM_DISABLE_GPIOF_IRQS
LM3S_GPIOF_BASE,
#endif
#ifndef CONFIG_LM3S_DISABLE_GPIOG_IRQS
#ifndef CONFIG_LM_DISABLE_GPIOG_IRQS
LM3S_GPIOG_BASE,
#endif
@ -100,10 +100,10 @@ static const uint32_t g_gpiobase[] =
* errors!
*/
#ifndef CONFIG_LM3S_DISABLE_GPIOH_IRQS
#ifndef CONFIG_LM_DISABLE_GPIOH_IRQS
LM3S_GPIOH_BASE,
#endif
#ifndef CONFIG_LM3S_DISABLE_GPIOJ_IRQS
#ifndef CONFIG_LM_DISABLE_GPIOJ_IRQS
LM3S_GPIOJ_BASE,
#endif
};
@ -119,7 +119,7 @@ static const uint32_t g_gpiobase[] =
****************************************************************************/
/****************************************************************************
* Name: lm3s_gpiobaseaddress
* Name: lm_gpiobaseaddress
*
* Input:
* gpioirq - A pin number in the range of 0 to NR_GPIO_IRQS.
@ -131,7 +131,7 @@ static const uint32_t g_gpiobase[] =
*
****************************************************************************/
static uint32_t lm3s_gpiobaseaddress(unsigned int gpioirq)
static uint32_t lm_gpiobaseaddress(unsigned int gpioirq)
{
unsigned int ndx = gpioirq >> 3;
if (ndx < GPIO_NADDRS)
@ -142,14 +142,14 @@ static uint32_t lm3s_gpiobaseaddress(unsigned int gpioirq)
}
/****************************************************************************
* Name: lm3s_gpio*handler
* Name: lm_gpio*handler
*
* Description:
* Handle interrupts on each enabled GPIO port
*
****************************************************************************/
static int lm3s_gpiohandler(uint32_t regbase, int irqbase, void *context)
static int lm_gpiohandler(uint32_t regbase, int irqbase, void *context)
{
uint32_t mis;
int irq;
@ -184,66 +184,66 @@ static int lm3s_gpiohandler(uint32_t regbase, int irqbase, void *context)
return OK;
}
#ifndef CONFIG_LM3S_DISABLE_GPIOA_IRQS
static int lm3s_gpioahandler(int irq, FAR void *context)
#ifndef CONFIG_LM_DISABLE_GPIOA_IRQS
static int lm_gpioahandler(int irq, FAR void *context)
{
return lm3s_gpiohandler(LM3S_GPIOA_BASE, LM3S_IRQ_GPIOA_0, context);
return lm_gpiohandler(LM3S_GPIOA_BASE, LM3S_IRQ_GPIOA_0, context);
}
#endif
#ifndef CONFIG_LM3S_DISABLE_GPIOB_IRQS
static int lm3s_gpiobhandler(int irq, FAR void *context)
#ifndef CONFIG_LM_DISABLE_GPIOB_IRQS
static int lm_gpiobhandler(int irq, FAR void *context)
{
return lm3s_gpiohandler(LM3S_GPIOB_BASE, LM3S_IRQ_GPIOB_0, context);
return lm_gpiohandler(LM3S_GPIOB_BASE, LM3S_IRQ_GPIOB_0, context);
}
#endif
#ifndef CONFIG_LM3S_DISABLE_GPIOC_IRQS
static int lm3s_gpiochandler(int irq, FAR void *context)
#ifndef CONFIG_LM_DISABLE_GPIOC_IRQS
static int lm_gpiochandler(int irq, FAR void *context)
{
return lm3s_gpiohandler(LM3S_GPIOC_BASE, LM3S_IRQ_GPIOC_0, context);
return lm_gpiohandler(LM3S_GPIOC_BASE, LM3S_IRQ_GPIOC_0, context);
}
#endif
#ifndef CONFIG_LM3S_DISABLE_GPIOD_IRQS
static int lm3s_gpiodhandler(int irq, FAR void *context)
#ifndef CONFIG_LM_DISABLE_GPIOD_IRQS
static int lm_gpiodhandler(int irq, FAR void *context)
{
return lm3s_gpiohandler(LM3S_GPIOD_BASE, LM3S_IRQ_GPIOD_0, context);
return lm_gpiohandler(LM3S_GPIOD_BASE, LM3S_IRQ_GPIOD_0, context);
}
#endif
#ifndef CONFIG_LM3S_DISABLE_GPIOE_IRQS
static int lm3s_gpioehandler(int irq, FAR void *context)
#ifndef CONFIG_LM_DISABLE_GPIOE_IRQS
static int lm_gpioehandler(int irq, FAR void *context)
{
return lm3s_gpiohandler(LM3S_GPIOE_BASE, LM3S_IRQ_GPIOE_0, context);
return lm_gpiohandler(LM3S_GPIOE_BASE, LM3S_IRQ_GPIOE_0, context);
}
#endif
#ifndef CONFIG_LM3S_DISABLE_GPIOF_IRQS
static int lm3s_gpiofhandler(int irq, FAR void *context)
#ifndef CONFIG_LM_DISABLE_GPIOF_IRQS
static int lm_gpiofhandler(int irq, FAR void *context)
{
return lm3s_gpiohandler(LM3S_GPIOF_BASE, LM3S_IRQ_GPIOF_0, context);
return lm_gpiohandler(LM3S_GPIOF_BASE, LM3S_IRQ_GPIOF_0, context);
}
#endif
#ifndef CONFIG_LM3S_DISABLE_GPIOG_IRQS
static int lm3s_gpioghandler(int irq, FAR void *context)
#ifndef CONFIG_LM_DISABLE_GPIOG_IRQS
static int lm_gpioghandler(int irq, FAR void *context)
{
return lm3s_gpiohandler(LM3S_GPIOG_BASE, LM3S_IRQ_GPIOG_0, context);
return lm_gpiohandler(LM3S_GPIOG_BASE, LM3S_IRQ_GPIOG_0, context);
}
#endif
#ifndef CONFIG_LM3S_DISABLE_GPIOH_IRQS
static int lm3s_gpiohhandler(int irq, FAR void *context)
#ifndef CONFIG_LM_DISABLE_GPIOH_IRQS
static int lm_gpiohhandler(int irq, FAR void *context)
{
return lm3s_gpiohandler(LM3S_GPIOH_BASE, LM3S_IRQ_GPIOH_0, context);
return lm_gpiohandler(LM3S_GPIOH_BASE, LM3S_IRQ_GPIOH_0, context);
}
#endif
#ifndef CONFIG_LM3S_DISABLE_GPIOJ_IRQS
static int lm3s_gpiojhandler(int irq, FAR void *context)
#ifndef CONFIG_LM_DISABLE_GPIOJ_IRQS
static int lm_gpiojhandler(int irq, FAR void *context)
{
return lm3s_gpiohandler(LM3S_GPIOJ_BASE, LM3S_IRQ_GPIOJ_0, context);
return lm_gpiohandler(LM3S_GPIOJ_BASE, LM3S_IRQ_GPIOJ_0, context);
}
#endif
@ -274,40 +274,40 @@ int gpio_irqinitialize(void)
* interrupts
*/
#ifndef CONFIG_LM3S_DISABLE_GPIOA_IRQS
irq_attach(LM3S_IRQ_GPIOA, lm3s_gpioahandler);
#ifndef CONFIG_LM_DISABLE_GPIOA_IRQS
irq_attach(LM3S_IRQ_GPIOA, lm_gpioahandler);
up_enable_irq(LM3S_IRQ_GPIOA);
#endif
#ifndef CONFIG_LM3S_DISABLE_GPIOB_IRQS
irq_attach(LM3S_IRQ_GPIOB, lm3s_gpiobhandler);
#ifndef CONFIG_LM_DISABLE_GPIOB_IRQS
irq_attach(LM3S_IRQ_GPIOB, lm_gpiobhandler);
up_enable_irq(LM3S_IRQ_GPIOB);
#endif
#ifndef CONFIG_LM3S_DISABLE_GPIOC_IRQS
irq_attach(LM3S_IRQ_GPIOC, lm3s_gpiochandler);
#ifndef CONFIG_LM_DISABLE_GPIOC_IRQS
irq_attach(LM3S_IRQ_GPIOC, lm_gpiochandler);
up_enable_irq(LM3S_IRQ_GPIOC);
#endif
#ifndef CONFIG_LM3S_DISABLE_GPIOD_IRQS
irq_attach(LM3S_IRQ_GPIOD, lm3s_gpiodhandler);
#ifndef CONFIG_LM_DISABLE_GPIOD_IRQS
irq_attach(LM3S_IRQ_GPIOD, lm_gpiodhandler);
up_enable_irq(LM3S_IRQ_GPIOD);
#endif
#ifndef CONFIG_LM3S_DISABLE_GPIOE_IRQS
irq_attach(LM3S_IRQ_GPIOE, lm3s_gpioehandler);
#ifndef CONFIG_LM_DISABLE_GPIOE_IRQS
irq_attach(LM3S_IRQ_GPIOE, lm_gpioehandler);
up_enable_irq(LM3S_IRQ_GPIOE);
#endif
#ifndef CONFIG_LM3S_DISABLE_GPIOF_IRQS
irq_attach(LM3S_IRQ_GPIOF, lm3s_gpiofhandler);
#ifndef CONFIG_LM_DISABLE_GPIOF_IRQS
irq_attach(LM3S_IRQ_GPIOF, lm_gpiofhandler);
up_enable_irq(LM3S_IRQ_GPIOF);
#endif
#ifndef CONFIG_LM3S_DISABLE_GPIOG_IRQS
irq_attach(LM3S_IRQ_GPIOG, lm3s_gpioghandler);
#ifndef CONFIG_LM_DISABLE_GPIOG_IRQS
irq_attach(LM3S_IRQ_GPIOG, lm_gpioghandler);
up_enable_irq(LM3S_IRQ_GPIOG);
#endif
#ifndef CONFIG_LM3S_DISABLE_GPIOH_IRQS
irq_attach(LM3S_IRQ_GPIOH, lm3s_gpiohhandler);
#ifndef CONFIG_LM_DISABLE_GPIOH_IRQS
irq_attach(LM3S_IRQ_GPIOH, lm_gpiohhandler);
up_enable_irq(LM3S_IRQ_GPIOH);
#endif
#ifndef CONFIG_LM3S_DISABLE_GPIOJ_IRQS
irq_attach(LM3S_IRQ_GPIOJ, lm3s_gpiojhandler);
#ifndef CONFIG_LM_DISABLE_GPIOJ_IRQS
irq_attach(LM3S_IRQ_GPIOJ, lm_gpiojhandler);
up_enable_irq(LM3S_IRQ_GPIOJ);
#endif
@ -374,7 +374,7 @@ void gpio_irqenable(int irq)
{
/* Get the base address of the GPIO module associated with this IRQ */
base = lm3s_gpiobaseaddress(gpioirq);
base = lm_gpiobaseaddress(gpioirq);
DEBUGASSERT(base != 0);
pin = (1 << (gpioirq & 7));
@ -413,7 +413,7 @@ void gpio_irqdisable(int irq)
{
/* Get the base address of the GPIO module associated with this IRQ */
base = lm3s_gpiobaseaddress(gpioirq);
base = lm_gpiobaseaddress(gpioirq);
DEBUGASSERT(base != 0);
pin = (1 << (gpioirq & 7));

View File

@ -1,6 +1,6 @@
/****************************************************************************
* arch/arm/src/lm/lm3s_irq.c
* arch/arm/src/chip/lm3s_irq.c
* arch/arm/src/lm/lm_irq.c
* arch/arm/src/chip/lm_irq.c
*
* Copyright (C) 2009, 2011 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
@ -88,7 +88,7 @@ volatile uint32_t *current_regs;
****************************************************************************/
/****************************************************************************
* Name: lm3s_dumpnvic
* Name: lm_dumpnvic
*
* Description:
* Dump some interesting NVIC registers
@ -96,7 +96,7 @@ volatile uint32_t *current_regs;
****************************************************************************/
#if defined(LM3S_IRQ_DEBUG) && defined (CONFIG_DEBUG)
static void lm3s_dumpnvic(const char *msg, int irq)
static void lm_dumpnvic(const char *msg, int irq)
{
irqstate_t flags;
@ -126,12 +126,12 @@ static void lm3s_dumpnvic(const char *msg, int irq)
irqrestore(flags);
}
#else
# define lm3s_dumpnvic(msg, irq)
# define lm_dumpnvic(msg, irq)
#endif
/****************************************************************************
* Name: lm3s_nmi, lm3s_busfault, lm3s_usagefault, lm3s_pendsv,
* lm3s_dbgmonitor, lm3s_pendsv, lm3s_reserved
* Name: lm_nmi, lm_busfault, lm_usagefault, lm_pendsv,
* lm_dbgmonitor, lm_pendsv, lm_reserved
*
* Description:
* Handlers for various execptions. None are handled and all are fatal
@ -141,7 +141,7 @@ static void lm3s_dumpnvic(const char *msg, int irq)
****************************************************************************/
#ifdef CONFIG_DEBUG
static int lm3s_nmi(int irq, FAR void *context)
static int lm_nmi(int irq, FAR void *context)
{
(void)irqsave();
dbg("PANIC!!! NMI received\n");
@ -149,7 +149,7 @@ static int lm3s_nmi(int irq, FAR void *context)
return 0;
}
static int lm3s_busfault(int irq, FAR void *context)
static int lm_busfault(int irq, FAR void *context)
{
(void)irqsave();
dbg("PANIC!!! Bus fault recived\n");
@ -157,7 +157,7 @@ static int lm3s_busfault(int irq, FAR void *context)
return 0;
}
static int lm3s_usagefault(int irq, FAR void *context)
static int lm_usagefault(int irq, FAR void *context)
{
(void)irqsave();
dbg("PANIC!!! Usage fault received\n");
@ -165,7 +165,7 @@ static int lm3s_usagefault(int irq, FAR void *context)
return 0;
}
static int lm3s_pendsv(int irq, FAR void *context)
static int lm_pendsv(int irq, FAR void *context)
{
(void)irqsave();
dbg("PANIC!!! PendSV received\n");
@ -173,7 +173,7 @@ static int lm3s_pendsv(int irq, FAR void *context)
return 0;
}
static int lm3s_dbgmonitor(int irq, FAR void *context)
static int lm_dbgmonitor(int irq, FAR void *context)
{
(void)irqsave();
dbg("PANIC!!! Debug Monitor receieved\n");
@ -181,7 +181,7 @@ static int lm3s_dbgmonitor(int irq, FAR void *context)
return 0;
}
static int lm3s_reserved(int irq, FAR void *context)
static int lm_reserved(int irq, FAR void *context)
{
(void)irqsave();
dbg("PANIC!!! Reserved interrupt\n");
@ -191,7 +191,7 @@ static int lm3s_reserved(int irq, FAR void *context)
#endif
/****************************************************************************
* Name: lm3s_irqinfo
* Name: lm_irqinfo
*
* Description:
* Given an IRQ number, provide the register and bit setting to enable or
@ -199,7 +199,7 @@ static int lm3s_reserved(int irq, FAR void *context)
*
****************************************************************************/
static int lm3s_irqinfo(int irq, uint32_t *regaddr, uint32_t *bit)
static int lm_irqinfo(int irq, uint32_t *regaddr, uint32_t *bit)
{
DEBUGASSERT(irq >= LM3S_IRQ_NMI && irq < NR_IRQS);
@ -294,7 +294,7 @@ void up_irqinitialize(void)
/* Initialize support for GPIO interrupts if included in this build */
#ifndef CONFIG_LM3S_DISABLE_GPIO_IRQS
#ifndef CONFIG_LM_DISABLE_GPIO_IRQS
#ifdef CONFIG_HAVE_WEAKFUNCTIONS
if (gpio_irqinitialize != NULL)
#endif
@ -330,18 +330,18 @@ void up_irqinitialize(void)
/* Attach all other processor exceptions (except reset and sys tick) */
#ifdef CONFIG_DEBUG
irq_attach(LM3S_IRQ_NMI, lm3s_nmi);
irq_attach(LM3S_IRQ_NMI, lm_nmi);
#ifndef CONFIG_ARMV7M_MPU
irq_attach(LM3S_IRQ_MEMFAULT, up_memfault);
#endif
irq_attach(LM3S_IRQ_BUSFAULT, lm3s_busfault);
irq_attach(LM3S_IRQ_USAGEFAULT, lm3s_usagefault);
irq_attach(LM3S_IRQ_PENDSV, lm3s_pendsv);
irq_attach(LM3S_IRQ_DBGMONITOR, lm3s_dbgmonitor);
irq_attach(LM3S_IRQ_RESERVED, lm3s_reserved);
irq_attach(LM3S_IRQ_BUSFAULT, lm_busfault);
irq_attach(LM3S_IRQ_USAGEFAULT, lm_usagefault);
irq_attach(LM3S_IRQ_PENDSV, lm_pendsv);
irq_attach(LM3S_IRQ_DBGMONITOR, lm_dbgmonitor);
irq_attach(LM3S_IRQ_RESERVED, lm_reserved);
#endif
lm3s_dumpnvic("initial", NR_IRQS);
lm_dumpnvic("initial", NR_IRQS);
#ifndef CONFIG_SUPPRESS_INTERRUPTS
@ -366,7 +366,7 @@ void up_disable_irq(int irq)
uint32_t regval;
uint32_t bit;
if (lm3s_irqinfo(irq, &regaddr, &bit) == 0)
if (lm_irqinfo(irq, &regaddr, &bit) == 0)
{
/* Clear the appropriate bit in the register to enable the interrupt */
@ -374,7 +374,7 @@ void up_disable_irq(int irq)
regval &= ~bit;
putreg32(regval, regaddr);
}
lm3s_dumpnvic("disable", irq);
lm_dumpnvic("disable", irq);
}
/****************************************************************************
@ -391,7 +391,7 @@ void up_enable_irq(int irq)
uint32_t regval;
uint32_t bit;
if (lm3s_irqinfo(irq, &regaddr, &bit) == 0)
if (lm_irqinfo(irq, &regaddr, &bit) == 0)
{
/* Set the appropriate bit in the register to enable the interrupt */
@ -399,7 +399,7 @@ void up_enable_irq(int irq)
regval |= bit;
putreg32(regval, regaddr);
}
lm3s_dumpnvic("enable", irq);
lm_dumpnvic("enable", irq);
}
/****************************************************************************
@ -452,7 +452,7 @@ int up_prioritize_irq(int irq, int priority)
regval |= (priority << shift);
putreg32(regval, regaddr);
lm3s_dumpnvic("prioritize", irq);
lm_dumpnvic("prioritize", irq);
return OK;
}
#endif

View File

@ -1,5 +1,5 @@
/**************************************************************************
* arch/arm/src/lm/lm3s_lowputc.c
* arch/arm/src/lm/lm_lowputc.c
*
* Copyright (C) 2009-2010 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
@ -58,26 +58,26 @@
/* Configuration **********************************************************/
#if LM3S_NUARTS < 2
# undef CONFIG_LM3S_UART1
# undef CONFIG_LM_UART1
# undef CONFIG_UART1_SERIAL_CONSOLE
#endif
#if LM3S_NUARTS < 3
# undef CONFIG_LM3S_UART2
# undef CONFIG_LM_UART2
# undef CONFIG_UART2_SERIAL_CONSOLE
#endif
/* Is there a serial console? */
#if defined(CONFIG_UART0_SERIAL_CONSOLE) && defined(CONFIG_LM3S_UART0)
#if defined(CONFIG_UART0_SERIAL_CONSOLE) && defined(CONFIG_LM_UART0)
# undef CONFIG_UART1_SERIAL_CONSOLE
# undef CONFIG_UART2_SERIAL_CONSOLE
# define HAVE_CONSOLE 1
#elif defined(CONFIG_UART1_SERIAL_CONSOLE) && defined(CONFIG_LM3S_UART1)
#elif defined(CONFIG_UART1_SERIAL_CONSOLE) && defined(CONFIG_LM_UART1)
# undef CONFIG_UART0_SERIAL_CONSOLE
# undef CONFIG_UART2_SERIAL_CONSOLE
# define HAVE_CONSOLE 1
#elif defined(CONFIG_UART2_SERIAL_CONSOLE) && defined(CONFIG_LM3S_UART2)
#elif defined(CONFIG_UART2_SERIAL_CONSOLE) && defined(CONFIG_LM_UART2)
# undef CONFIG_UART0_SERIAL_CONSOLE
# undef CONFIG_UART1_SERIAL_CONSOLE
# define HAVE_CONSOLE 1
@ -259,22 +259,22 @@ void up_lowsetup(void)
* this pin configuration -- whether or not a serial console is selected.
*/
#ifdef CONFIG_LM3S_UART0
#ifdef CONFIG_LM_UART0
regval = getreg32(LM3S_SYSCON_RCGC1);
regval |= SYSCON_RCGC1_UART0;
putreg32(regval, LM3S_SYSCON_RCGC1);
lm3s_configgpio(GPIO_UART0_RX);
lm3s_configgpio(GPIO_UART0_TX);
lm_configgpio(GPIO_UART0_RX);
lm_configgpio(GPIO_UART0_TX);
#endif
#ifdef CONFIG_LM3S_UART1
#ifdef CONFIG_LM_UART1
regval = getreg32(LM3S_SYSCON_RCGC1);
regval |= SYSCON_RCGC1_UART1;
putreg32(regval, LM3S_SYSCON_RCGC1);
lm3s_configgpio(GPIO_UART1_RX);
lm3s_configgpio(GPIO_UART1_TX);
lm_configgpio(GPIO_UART1_RX);
lm_configgpio(GPIO_UART1_TX);
#endif
/* Enable the selected console device */

View File

@ -1,5 +1,5 @@
/************************************************************************************
* arch/arm/src/lm/lm3s_lowputc.h
* arch/arm/src/lm/lm_lowputc.h
*
* Copyright (C) 2009-2010, 2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>

View File

@ -1,5 +1,5 @@
/****************************************************************************
* arch/arm/src/lm/lm3s_serial.c
* arch/arm/src/lm/lm_serial.c
*
* Copyright (C) 2009-2010, 2012 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
@ -67,32 +67,32 @@
/* Some sanity checks *******************************************************/
#if LM3S_NUARTS < 2
# undef CONFIG_LM3S_UART1
# undef CONFIG_LM_UART1
# undef CONFIG_UART1_SERIAL_CONSOLE
#endif
#if LM3S_NUARTS < 3
# undef CONFIG_LM3S_UART2
# undef CONFIG_LM_UART2
# undef CONFIG_UART2_SERIAL_CONSOLE
#endif
/* Is there a UART enabled? */
#if !defined(CONFIG_LM3S_UART0) && !defined(CONFIG_LM3S_UART1) && !defined(CONFIG_LM3S_UART2)
#if !defined(CONFIG_LM_UART0) && !defined(CONFIG_LM_UART1) && !defined(CONFIG_LM_UART2)
# error "No UARTs enabled"
#endif
/* Is there a serial console? */
#if defined(CONFIG_UART0_SERIAL_CONSOLE) && defined(CONFIG_LM3S_UART0)
#if defined(CONFIG_UART0_SERIAL_CONSOLE) && defined(CONFIG_LM_UART0)
# undef CONFIG_UART1_SERIAL_CONSOLE
# undef CONFIG_UART2_SERIAL_CONSOLE
# define HAVE_CONSOLE 1
#elif defined(CONFIG_UART1_SERIAL_CONSOLE) && defined(CONFIG_LM3S_UART1)
#elif defined(CONFIG_UART1_SERIAL_CONSOLE) && defined(CONFIG_LM_UART1)
# undef CONFIG_UART0_SERIAL_CONSOLE
# undef CONFIG_UART2_SERIAL_CONSOLE
# define HAVE_CONSOLE 1
#elif defined(CONFIG_UART2_SERIAL_CONSOLE) && defined(CONFIG_LM3S_UART2)
#elif defined(CONFIG_UART2_SERIAL_CONSOLE) && defined(CONFIG_LM_UART2)
# undef CONFIG_UART0_SERIAL_CONSOLE
# undef CONFIG_UART1_SERIAL_CONSOLE
# define HAVE_CONSOLE 1
@ -115,16 +115,16 @@
#if defined(CONFIG_UART0_SERIAL_CONSOLE)
# define CONSOLE_DEV g_uart0port /* UART0 is console */
# define TTYS0_DEV g_uart0port /* UART0 is ttyS0 */
# ifdef CONFIG_LM3S_UART1
# ifdef CONFIG_LM_UART1
# define TTYS1_DEV g_uart1port /* UART1 is ttyS1 */
# ifdef CONFIG_LM3S_UART2
# ifdef CONFIG_LM_UART2
# define TTYS2_DEV g_uart2port /* UART2 is ttyS2 */
# else
# undef TTYS2_DEV /* No ttyS2 */
# endif
# else
# undef TTYS2_DEV /* No ttyS2 */
# ifdef CONFIG_LM3S_UART2
# ifdef CONFIG_LM_UART2
# define TTYS1_DEV g_uart2port /* UART2 is ttyS1 */
# else
# undef TTYS1_DEV /* No ttyS1 */
@ -133,16 +133,16 @@
#elif defined(CONFIG_UART1_SERIAL_CONSOLE)
# define CONSOLE_DEV g_uart1port /* UART1 is console */
# define TTYS0_DEV g_uart1port /* UART1 is ttyS0 */
# ifdef CONFIG_LM3S_UART0
# ifdef CONFIG_LM_UART0
# define TTYS1_DEV g_uart0port /* UART0 is ttyS1 */
# ifdef CONFIG_LM3S_UART2
# ifdef CONFIG_LM_UART2
# define TTYS2_DEV g_uart2port /* UART2 is ttyS2 */
# else
# undef TTYS2_DEV /* No ttyS2 */
# endif
# else
# undef TTYS2_DEV /* No ttyS2 */
# ifdef CONFIG_LM3S_UART2
# ifdef CONFIG_LM_UART2
# define TTYS1_DEV g_uart2port /* UART2 is ttyS1 */
# else
# undef TTYS1_DEV /* No ttyS1 */
@ -151,49 +151,49 @@
#elif defined(CONFIG_UART2_SERIAL_CONSOLE)
# define CONSOLE_DEV g_uart2port /* UART2 is console */
# define TTYS0_DEV g_uart2port /* UART2 is ttyS0 */
# ifdef CONFIG_LM3S_UART0
# ifdef CONFIG_LM_UART0
# define TTYS1_DEV g_uart0port /* UART0 is ttyS1 */
# ifdef CONFIG_LM3S_UART2
# ifdef CONFIG_LM_UART2
# define TTYS2_DEV g_uart2port /* UART2 is ttyS2 */
# else
# undef TTYS2_DEV /* No ttyS2 */
# endif
# else
# undef TTYS2_DEV /* No ttyS2 */
# ifdef CONFIG_LM3S_UART2
# ifdef CONFIG_LM_UART2
# define TTYS1_DEV g_uart2port /* UART2 is ttyS1 */
# else
# undef TTYS1_DEV /* No ttyS1 */
# endif
# endif
#elifdefined(CONFIG_LM3S_UART0)
#elifdefined(CONFIG_LM_UART0)
# undef CONSOLE_DEV /* No console device */
# define TTYS0_DEV g_uart1port /* UART1 is ttyS0 */
# ifdef CONFIG_LM3S_UART1
# ifdef CONFIG_LM_UART1
# define TTYS1_DEV g_uart1port /* UART1 is ttyS1 */
# ifdef CONFIG_LM3S_UART2
# ifdef CONFIG_LM_UART2
# define TTYS2_DEV g_uart2port /* UART2 is ttyS2 */
# else
# undef TTYS2_DEV /* No ttyS2 */
# endif
# else
# undef TTYS2_DEV /* No ttyS2 */
# ifdef CONFIG_LM3S_UART2
# ifdef CONFIG_LM_UART2
# define TTYS1_DEV g_uart2port /* UART2 is ttyS1 */
# else
# undef TTYS1_DEV /* No ttyS1 */
# endif
# endif
#elifdefined(CONFIG_LM3S_UART1)
#elifdefined(CONFIG_LM_UART1)
# undef CONSOLE_DEV /* No console device */
# define TTYS0_DEV g_uart1port /* UART1 is ttyS0 */
# undef TTYS2_DEV /* No ttyS2 */
# ifdef CONFIG_LM3S_UART2
# ifdef CONFIG_LM_UART2
# define TTYS1_DEV g_uart2port /* UART2 is ttyS1 */
# else
# undef TTYS1_DEV /* No ttyS1 */
# endif
#elifdefined(CONFIG_LM3S_UART2)
#elifdefined(CONFIG_LM_UART2)
# undef CONSOLE_DEV /* No console device */
# define TTYS0_DEV g_uart2port /* UART2 is ttyS0 */
# undef TTYS1_DEV /* No ttyS1 */
@ -261,22 +261,22 @@ struct uart_ops_s g_uart_ops =
/* I/O buffers */
#ifdef CONFIG_LM3S_UART0
#ifdef CONFIG_LM_UART0
static char g_uart0rxbuffer[CONFIG_UART0_RXBUFSIZE];
static char g_uart0txbuffer[CONFIG_UART0_TXBUFSIZE];
#endif
#ifdef CONFIG_LM3S_UART1
#ifdef CONFIG_LM_UART1
static char g_uart1rxbuffer[CONFIG_UART1_RXBUFSIZE];
static char g_uart1txbuffer[CONFIG_UART1_TXBUFSIZE];
#endif
#ifdef CONFIG_LM3S_UART2
#ifdef CONFIG_LM_UART2
static char g_uart2rxbuffer[CONFIG_UART2_RXBUFSIZE];
static char g_uart2txbuffer[CONFIG_UART2_TXBUFSIZE];
#endif
/* This describes the state of the LM3S uart0 port. */
#ifdef CONFIG_LM3S_UART0
#ifdef CONFIG_LM_UART0
static struct up_dev_s g_uart0priv =
{
.uartbase = LM3S_UART0_BASE,
@ -306,7 +306,7 @@ static uart_dev_t g_uart0port =
/* This describes the state of the LM3S uart1 port. */
#ifdef CONFIG_LM3S_UART1
#ifdef CONFIG_LM_UART1
static struct up_dev_s g_uart1priv =
{
.uartbase = LM3S_UART1_BASE,
@ -336,7 +336,7 @@ static uart_dev_t g_uart1port =
/* This describes the state of the LM3S uart1 port. */
#ifdef CONFIG_LM3S_UART2
#ifdef CONFIG_LM_UART2
static struct up_dev_s g_uart2priv =
{
.uartbase = LM3S_UART2_BASE,
@ -686,14 +686,14 @@ static int up_interrupt(int irq, void *context)
int passes;
bool handled;
#ifdef CONFIG_LM3S_UART0
#ifdef CONFIG_LM_UART0
if (g_uart0priv.irq == irq)
{
dev = &g_uart0port;
}
else
#endif
#ifdef CONFIG_LM3S_UART1
#ifdef CONFIG_LM_UART1
if (g_uart1priv.irq == irq)
{
dev = &g_uart1port;

View File

@ -1,5 +1,5 @@
/****************************************************************************
* arch/arm/src/lm32/lm3s_ssi.c
* arch/arm/src/lm/lm_ssi.c
*
* Copyright (C) 2009-2010 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
@ -144,7 +144,7 @@
* Private Type Definitions
****************************************************************************/
struct lm3s_ssidev_s
struct lm_ssidev_s
{
const struct spi_ops_s *ops; /* Common SPI operations */
#ifndef CONFIG_SSI_POLLWAIT
@ -167,8 +167,8 @@ struct lm3s_ssidev_s
* per word.
*/
void (*txword)(struct lm3s_ssidev_s *priv);
void (*rxword)(struct lm3s_ssidev_s *priv);
void (*txword)(struct lm_ssidev_s *priv);
void (*rxword)(struct lm_ssidev_s *priv);
#if NSSI_ENABLED > 1
uint32_t base; /* SSI register base address */
@ -202,15 +202,15 @@ struct lm3s_ssidev_s
/* SSI register access */
static inline uint32_t ssi_getreg(struct lm3s_ssidev_s *priv,
static inline uint32_t ssi_getreg(struct lm_ssidev_s *priv,
unsigned int offset);
static inline void ssi_putreg(struct lm3s_ssidev_s *priv, unsigned int offset,
static inline void ssi_putreg(struct lm_ssidev_s *priv, unsigned int offset,
uint32_t value);
/* Misc helpers */
static uint32_t ssi_disable(struct lm3s_ssidev_s *priv);
static void ssi_enable(struct lm3s_ssidev_s *priv, uint32_t enable);
static uint32_t ssi_disable(struct lm_ssidev_s *priv);
static void ssi_enable(struct lm_ssidev_s *priv, uint32_t enable);
#ifndef CONFIG_SSI_POLLWAIT
static void ssi_semtake(sem_t *sem);
@ -219,27 +219,27 @@ static void ssi_semtake(sem_t *sem);
/* SSI data transfer */
static void ssi_txnull(struct lm3s_ssidev_s *priv);
static void ssi_txuint16(struct lm3s_ssidev_s *priv);
static void ssi_txuint8(struct lm3s_ssidev_s *priv);
static void ssi_rxnull(struct lm3s_ssidev_s *priv);
static void ssi_rxuint16(struct lm3s_ssidev_s *priv);
static void ssi_rxuint8(struct lm3s_ssidev_s *priv);
static inline bool ssi_txfifofull(struct lm3s_ssidev_s *priv);
static inline bool ssi_rxfifoempty(struct lm3s_ssidev_s *priv);
static void ssi_txnull(struct lm_ssidev_s *priv);
static void ssi_txuint16(struct lm_ssidev_s *priv);
static void ssi_txuint8(struct lm_ssidev_s *priv);
static void ssi_rxnull(struct lm_ssidev_s *priv);
static void ssi_rxuint16(struct lm_ssidev_s *priv);
static void ssi_rxuint8(struct lm_ssidev_s *priv);
static inline bool ssi_txfifofull(struct lm_ssidev_s *priv);
static inline bool ssi_rxfifoempty(struct lm_ssidev_s *priv);
#if CONFIG_SSI_TXLIMIT == 1 && defined(CONFIG_SSI_POLLWAIT)
static inline int ssi_performtx(struct lm3s_ssidev_s *priv);
static inline int ssi_performtx(struct lm_ssidev_s *priv);
#else
static int ssi_performtx(struct lm3s_ssidev_s *priv);
static int ssi_performtx(struct lm_ssidev_s *priv);
#endif
static inline void ssi_performrx(struct lm3s_ssidev_s *priv);
static int ssi_transfer(struct lm3s_ssidev_s *priv, const void *txbuffer,
static inline void ssi_performrx(struct lm_ssidev_s *priv);
static int ssi_transfer(struct lm_ssidev_s *priv, const void *txbuffer,
void *rxbuffer, unsigned int nwords);
/* Interrupt handling */
#ifndef CONFIG_SSI_POLLWAIT
static inline struct lm3s_ssidev_s *ssi_mapirq(int irq);
static inline struct lm_ssidev_s *ssi_mapirq(int irq);
static int ssi_interrupt(int irq, void *context);
#endif
@ -248,14 +248,14 @@ static int ssi_interrupt(int irq, void *context);
#ifndef CONFIG_SPI_OWNBUS
static int ssi_lock(FAR struct spi_dev_s *dev, bool lock);
#endif
static uint32_t ssi_setfrequencyinternal(struct lm3s_ssidev_s *priv,
static uint32_t ssi_setfrequencyinternal(struct lm_ssidev_s *priv,
uint32_t frequency);
static uint32_t ssi_setfrequency(FAR struct spi_dev_s *dev,
uint32_t frequency);
static void ssi_setmodeinternal(struct lm3s_ssidev_s *priv,
static void ssi_setmodeinternal(struct lm_ssidev_s *priv,
enum spi_mode_e mode);
static void ssi_setmode(FAR struct spi_dev_s *dev, enum spi_mode_e mode);
static void ssi_setbitsinternal(struct lm3s_ssidev_s *priv, int nbits);
static void ssi_setbitsinternal(struct lm_ssidev_s *priv, int nbits);
static void ssi_setbits(FAR struct spi_dev_s *dev, int nbits);
static uint16_t ssi_send(FAR struct spi_dev_s *dev, uint16_t wd);
#ifdef CONFIG_SPI_EXCHANGE
@ -279,13 +279,13 @@ static const struct spi_ops_s g_spiops =
#ifndef CONFIG_SPI_OWNBUS
.lock = ssi_lock,
#endif
.select = lm3s_spiselect, /* Provided externally by board logic */
.select = lm_spiselect, /* Provided externally by board logic */
.setfrequency = ssi_setfrequency,
.setmode = ssi_setmode,
.setbits = ssi_setbits,
.status = lm3s_spistatus, /* Provided externally by board logic */
.status = lm_spistatus, /* Provided externally by board logic */
#ifdef CONFIG_SPI_CMDDATA
.cmddata = lm3s_spicmddata,
.cmddata = lm_spicmddata,
#endif
.send = ssi_send,
#ifdef CONFIG_SPI_EXCHANGE
@ -298,7 +298,7 @@ static const struct spi_ops_s g_spiops =
/* This supports is up to two SSI busses/ports */
static struct lm3s_ssidev_s g_ssidev[] =
static struct lm_ssidev_s g_ssidev[] =
{
#ifndef CONFIG_SSI0_DISABLE
{
@ -347,7 +347,7 @@ static struct lm3s_ssidev_s g_ssidev[] =
*
****************************************************************************/
static inline uint32_t ssi_getreg(struct lm3s_ssidev_s *priv, unsigned int offset)
static inline uint32_t ssi_getreg(struct lm_ssidev_s *priv, unsigned int offset)
{
#if NSSI_ENABLED > 1
return getreg32(priv->base + offset);
@ -372,7 +372,7 @@ static inline uint32_t ssi_getreg(struct lm3s_ssidev_s *priv, unsigned int offse
*
****************************************************************************/
static inline void ssi_putreg(struct lm3s_ssidev_s *priv, unsigned int offset, uint32_t value)
static inline void ssi_putreg(struct lm_ssidev_s *priv, unsigned int offset, uint32_t value)
{
#if NSSI_ENABLED > 1
putreg32(value, priv->base + offset);
@ -399,7 +399,7 @@ static inline void ssi_putreg(struct lm3s_ssidev_s *priv, unsigned int offset, u
*
****************************************************************************/
static uint32_t ssi_disable(struct lm3s_ssidev_s *priv)
static uint32_t ssi_disable(struct lm_ssidev_s *priv)
{
uint32_t retval;
uint32_t regval;
@ -428,7 +428,7 @@ static uint32_t ssi_disable(struct lm3s_ssidev_s *priv)
*
****************************************************************************/
static void ssi_enable(struct lm3s_ssidev_s *priv, uint32_t enable)
static void ssi_enable(struct lm_ssidev_s *priv, uint32_t enable)
{
uint32_t regval = ssi_getreg(priv, LM3S_SSI_CR1_OFFSET);
regval &= ~SSI_CR1_SSE;
@ -481,13 +481,13 @@ static void ssi_semtake(sem_t *sem)
*
****************************************************************************/
static void ssi_txnull(struct lm3s_ssidev_s *priv)
static void ssi_txnull(struct lm_ssidev_s *priv)
{
ssivdbg("TX: ->0xffff\n");
ssi_putreg(priv, LM3S_SSI_DR_OFFSET, 0xffff);
}
static void ssi_txuint16(struct lm3s_ssidev_s *priv)
static void ssi_txuint16(struct lm_ssidev_s *priv)
{
uint16_t *ptr = (uint16_t*)priv->txbuffer;
ssivdbg("TX: %p->%04x\n", ptr, *ptr);
@ -495,7 +495,7 @@ static void ssi_txuint16(struct lm3s_ssidev_s *priv)
priv->txbuffer = (void*)ptr;
}
static void ssi_txuint8(struct lm3s_ssidev_s *priv)
static void ssi_txuint8(struct lm_ssidev_s *priv)
{
uint8_t *ptr = (uint8_t*)priv->txbuffer;
ssivdbg("TX: %p->%02x\n", ptr, *ptr);
@ -520,7 +520,7 @@ static void ssi_txuint8(struct lm3s_ssidev_s *priv)
*
****************************************************************************/
static void ssi_rxnull(struct lm3s_ssidev_s *priv)
static void ssi_rxnull(struct lm_ssidev_s *priv)
{
#if defined(SSI_DEBUG) && defined(CONFIG_DEBUG_VERBOSE)
uint32_t regval = ssi_getreg(priv, LM3S_SSI_DR_OFFSET);
@ -530,7 +530,7 @@ static void ssi_rxnull(struct lm3s_ssidev_s *priv)
#endif
}
static void ssi_rxuint16(struct lm3s_ssidev_s *priv)
static void ssi_rxuint16(struct lm_ssidev_s *priv)
{
uint16_t *ptr = (uint16_t*)priv->rxbuffer;
*ptr = (uint16_t)ssi_getreg(priv, LM3S_SSI_DR_OFFSET);
@ -538,7 +538,7 @@ static void ssi_rxuint16(struct lm3s_ssidev_s *priv)
priv->rxbuffer = (void*)(++ptr);
}
static void ssi_rxuint8(struct lm3s_ssidev_s *priv)
static void ssi_rxuint8(struct lm_ssidev_s *priv)
{
uint8_t *ptr = (uint8_t*)priv->rxbuffer;
*ptr = (uint8_t)ssi_getreg(priv, LM3S_SSI_DR_OFFSET);
@ -560,7 +560,7 @@ static void ssi_rxuint8(struct lm3s_ssidev_s *priv)
*
****************************************************************************/
static inline bool ssi_txfifofull(struct lm3s_ssidev_s *priv)
static inline bool ssi_txfifofull(struct lm_ssidev_s *priv)
{
return (ssi_getreg(priv, LM3S_SSI_SR_OFFSET) & SSI_SR_TNF) == 0;
}
@ -579,7 +579,7 @@ static inline bool ssi_txfifofull(struct lm3s_ssidev_s *priv)
*
****************************************************************************/
static inline bool ssi_rxfifoempty(struct lm3s_ssidev_s *priv)
static inline bool ssi_rxfifoempty(struct lm_ssidev_s *priv)
{
return (ssi_getreg(priv, LM3S_SSI_SR_OFFSET) & SSI_SR_RNE) == 0;
}
@ -601,7 +601,7 @@ static inline bool ssi_rxfifoempty(struct lm3s_ssidev_s *priv)
****************************************************************************/
#if CONFIG_SSI_TXLIMIT == 1 && defined(CONFIG_SSI_POLLWAIT)
static inline int ssi_performtx(struct lm3s_ssidev_s *priv)
static inline int ssi_performtx(struct lm_ssidev_s *priv)
{
/* Check if the Tx FIFO is full and more data to transfer */
@ -618,7 +618,7 @@ static inline int ssi_performtx(struct lm3s_ssidev_s *priv)
#else /* CONFIG_SSI_TXLIMIT == 1 CONFIG_SSI_POLLWAIT */
static int ssi_performtx(struct lm3s_ssidev_s *priv)
static int ssi_performtx(struct lm_ssidev_s *priv)
{
#ifndef CONFIG_SSI_POLLWAIT
uint32_t regval;
@ -701,7 +701,7 @@ static int ssi_performtx(struct lm3s_ssidev_s *priv)
*
****************************************************************************/
static inline void ssi_performrx(struct lm3s_ssidev_s *priv)
static inline void ssi_performrx(struct lm_ssidev_s *priv)
{
#ifndef CONFIG_SSI_POLLWAIT
uint32_t regval;
@ -778,7 +778,7 @@ static inline void ssi_performrx(struct lm3s_ssidev_s *priv)
*
****************************************************************************/
static int ssi_transfer(struct lm3s_ssidev_s *priv, const void *txbuffer,
static int ssi_transfer(struct lm_ssidev_s *priv, const void *txbuffer,
void *rxbuffer, unsigned int nwords)
{
#ifndef CONFIG_SSI_POLLWAIT
@ -903,7 +903,7 @@ static int ssi_transfer(struct lm3s_ssidev_s *priv, const void *txbuffer,
****************************************************************************/
#ifndef CONFIG_SSI_POLLWAIT
static inline struct lm3s_ssidev_s *ssi_mapirq(int irq)
static inline struct lm_ssidev_s *ssi_mapirq(int irq)
{
switch (irq)
{
@ -944,7 +944,7 @@ static inline struct lm3s_ssidev_s *ssi_mapirq(int irq)
#ifndef CONFIG_SSI_POLLWAIT
static int ssi_interrupt(int irq, void *context)
{
struct lm3s_ssidev_s *priv = ssi_mapirq(irq);
struct lm_ssidev_s *priv = ssi_mapirq(irq);
uint32_t regval;
int ntxd;
@ -1022,7 +1022,7 @@ static int ssi_interrupt(int irq, void *context)
#ifndef CONFIG_SPI_OWNBUS
static int ssi_lock(FAR struct spi_dev_s *dev, bool lock)
{
FAR struct lm3s_ssidev_s *priv = (FAR struct lm3s_ssidev_s *)dev;
FAR struct lm_ssidev_s *priv = (FAR struct lm_ssidev_s *)dev;
if (lock)
{
@ -1063,7 +1063,7 @@ static int ssi_lock(FAR struct spi_dev_s *dev, bool lock)
*
****************************************************************************/
static uint32_t ssi_setfrequencyinternal(struct lm3s_ssidev_s *priv, uint32_t frequency)
static uint32_t ssi_setfrequencyinternal(struct lm_ssidev_s *priv, uint32_t frequency)
{
uint32_t maxdvsr;
uint32_t cpsdvsr;
@ -1165,7 +1165,7 @@ static uint32_t ssi_setfrequencyinternal(struct lm3s_ssidev_s *priv, uint32_t fr
static uint32_t ssi_setfrequency(FAR struct spi_dev_s *dev, uint32_t frequency)
{
struct lm3s_ssidev_s *priv = (struct lm3s_ssidev_s *)dev;
struct lm_ssidev_s *priv = (struct lm_ssidev_s *)dev;
uint32_t enable;
uint32_t actual;
@ -1195,7 +1195,7 @@ static uint32_t ssi_setfrequency(FAR struct spi_dev_s *dev, uint32_t frequency)
*
****************************************************************************/
static void ssi_setmodeinternal(struct lm3s_ssidev_s *priv, enum spi_mode_e mode)
static void ssi_setmodeinternal(struct lm_ssidev_s *priv, enum spi_mode_e mode)
{
uint32_t modebits;
uint32_t regval;
@ -1251,7 +1251,7 @@ static void ssi_setmodeinternal(struct lm3s_ssidev_s *priv, enum spi_mode_e mode
static void ssi_setmode(FAR struct spi_dev_s *dev, enum spi_mode_e mode)
{
struct lm3s_ssidev_s *priv = (struct lm3s_ssidev_s *)dev;
struct lm_ssidev_s *priv = (struct lm_ssidev_s *)dev;
uint32_t enable;
/* NOTE that the SSI must be disabled when setting any configuration registers. */
@ -1279,7 +1279,7 @@ static void ssi_setmode(FAR struct spi_dev_s *dev, enum spi_mode_e mode)
*
****************************************************************************/
static void ssi_setbitsinternal(struct lm3s_ssidev_s *priv, int nbits)
static void ssi_setbitsinternal(struct lm_ssidev_s *priv, int nbits)
{
uint32_t regval;
@ -1299,7 +1299,7 @@ static void ssi_setbitsinternal(struct lm3s_ssidev_s *priv, int nbits)
static void ssi_setbits(FAR struct spi_dev_s *dev, int nbits)
{
struct lm3s_ssidev_s *priv = (struct lm3s_ssidev_s *)dev;
struct lm_ssidev_s *priv = (struct lm_ssidev_s *)dev;
uint32_t enable;
/* NOTE that the SSI must be disabled when setting any configuration registers. */
@ -1327,7 +1327,7 @@ static void ssi_setbits(FAR struct spi_dev_s *dev, int nbits)
static uint16_t ssi_send(FAR struct spi_dev_s *dev, uint16_t wd)
{
struct lm3s_ssidev_s *priv = (struct lm3s_ssidev_s*)dev;
struct lm_ssidev_s *priv = (struct lm_ssidev_s*)dev;
uint16_t response = 0;
(void)ssi_transfer(priv, &wd, &response, 1);
@ -1358,7 +1358,7 @@ static uint16_t ssi_send(FAR struct spi_dev_s *dev, uint16_t wd)
static void ssi_exchange(FAR struct spi_dev_s *dev, FAR const void *txbuffer,
FAR void *rxbuffer, size_t nwords)
{
struct lm3s_ssidev_s *priv = (struct lm3s_ssidev_s *)dev;
struct lm_ssidev_s *priv = (struct lm_ssidev_s *)dev;
(void)ssi_transfer(priv, txbuffer, rxbuffer, nwords);
}
#endif
@ -1385,7 +1385,7 @@ static void ssi_exchange(FAR struct spi_dev_s *dev, FAR const void *txbuffer,
#ifndef CONFIG_SPI_EXCHANGE
static void ssi_sndblock(FAR struct spi_dev_s *dev, FAR const void *buffer, size_t nwords)
{
struct lm3s_ssidev_s *priv = (struct lm3s_ssidev_s *)dev;
struct lm_ssidev_s *priv = (struct lm_ssidev_s *)dev;
(void)ssi_transfer(priv, buffer, NULL, nwords);
}
#endif
@ -1412,7 +1412,7 @@ static void ssi_sndblock(FAR struct spi_dev_s *dev, FAR const void *buffer, size
#ifndef CONFIG_SPI_EXCHANGE
static void ssi_recvblock(FAR struct spi_dev_s *dev, FAR void *buffer, size_t nwords)
{
struct lm3s_ssidev_s *priv = (struct lm3s_ssidev_s *)dev;
struct lm_ssidev_s *priv = (struct lm_ssidev_s *)dev;
(void)ssi_transfer(priv, NULL, buffer, nwords);
}
#endif
@ -1445,7 +1445,7 @@ static void ssi_recvblock(FAR struct spi_dev_s *dev, FAR void *buffer, size_t nw
FAR struct spi_dev_s *up_spiinitialize(int port)
{
struct lm3s_ssidev_s *priv;
struct lm_ssidev_s *priv;
irqstate_t flags;
uint8_t regval;
@ -1473,10 +1473,10 @@ FAR struct spi_dev_s *up_spiinitialize(int port)
* logic in this file makes no assumptions about chip select)
*/
lm3s_configgpio(GPIO_SSI0_CLK); /* PA2: SSI0 clock (SSI0Clk) */
/* lm3s_configgpio(GPIO_SSI0_FSS); PA3: SSI0 frame (SSI0Fss) */
lm3s_configgpio(GPIO_SSI0_RX); /* PA4: SSI0 receive (SSI0Rx) */
lm3s_configgpio(GPIO_SSI0_TX); /* PA5: SSI0 transmit (SSI0Tx) */
lm_configgpio(GPIO_SSI0_CLK); /* PA2: SSI0 clock (SSI0Clk) */
/* lm_configgpio(GPIO_SSI0_FSS); PA3: SSI0 frame (SSI0Fss) */
lm_configgpio(GPIO_SSI0_RX); /* PA4: SSI0 receive (SSI0Rx) */
lm_configgpio(GPIO_SSI0_TX); /* PA5: SSI0 transmit (SSI0Tx) */
break;
#endif /* CONFIG_SSI0_DISABLE */
@ -1495,10 +1495,10 @@ FAR struct spi_dev_s *up_spiinitialize(int port)
/* Configure SSI1 GPIOs */
lm3s_configgpio(GPIO_SSI1_CLK); /* PE0: SSI1 clock (SSI1Clk) */
/* lm3s_configgpio(GPIO_SSI1_FSS); PE1: SSI1 frame (SSI1Fss) */
lm3s_configgpio(GPIO_SSI1_RX); /* PE2: SSI1 receive (SSI1Rx) */
lm3s_configgpio(GPIO_SSI1_TX); /* PE3: SSI1 transmit (SSI1Tx) */
lm_configgpio(GPIO_SSI1_CLK); /* PE0: SSI1 clock (SSI1Clk) */
/* lm_configgpio(GPIO_SSI1_FSS); PE1: SSI1 frame (SSI1Fss) */
lm_configgpio(GPIO_SSI1_RX); /* PE2: SSI1 receive (SSI1Rx) */
lm_configgpio(GPIO_SSI1_TX); /* PE3: SSI1 transmit (SSI1Tx) */
break;
#endif /* CONFIG_SSI1_DISABLE */

View File

@ -73,20 +73,20 @@ extern "C"
****************************************************************************/
/****************************************************************************
* The external functions, lm3s_spiselect, lm3s_spistatus, and
* lm3s_spicmddata must be provided by board-specific logic. These are
* The external functions, lm_spiselect, lm_spistatus, and
* lm_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
* logic. To use this common SPI logic on your board:
*
* 1. Provide logic in lm3s_boardinitialize() to configure SPI chip select
* 1. Provide logic in lm_boardinitialize() to configure SPI chip select
* pins.
* 2. Provide lm3s_spiselect() and lm3s_spistatus() functions in your
* 2. Provide lm_spiselect() and lm_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 defined in your NuttX configuration, provide
* the lm3s_spicmddata() function in your board-specific logic. This
* the lm_spicmddata() function in your board-specific logic. This
* functions will perform cmd/data selection operations using GPIOs in
* the way your board is configured.
* 4. Add a call to up_spiinitialize() in your low level application
@ -100,10 +100,10 @@ extern "C"
struct spi_dev_s;
enum spi_dev_e;
void lm3s_spiselect(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected);
uint8_t lm3s_spistatus(FAR struct spi_dev_s *dev, enum spi_dev_e devid);
void lm_spiselect(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected);
uint8_t lm_spistatus(FAR struct spi_dev_s *dev, enum spi_dev_e devid);
#ifdef CONFIG_SPI_CMDDATA
int lm3s_spicmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd);
int lm_spicmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd);
#endif
#if defined(__cplusplus)

View File

@ -1,6 +1,6 @@
/****************************************************************************
* arch/arm/src/lm/lm3s_start.c
* arch/arm/src/chip/lm3s_start.c
* arch/arm/src/lm/lm_start.c
* arch/arm/src/chip/lm_start.c
*
* Copyright (C) 2009, 2012 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
@ -65,7 +65,7 @@
* Public Data
****************************************************************************/
extern void lm3s_vectors(void);
extern void lm_vectors(void);
/****************************************************************************
* Private Functions
@ -139,7 +139,7 @@ void __start(void)
/* Initialize onboard resources */
lm3s_boardinitialize();
lm_boardinitialize();
showprogress('E');
/* Then start NuttX */

View File

@ -1,6 +1,6 @@
/****************************************************************************
* arch/arm/src/lm/lm3s_syscontrol.c
* arch/arm/src/chip/lm3s_syscontrol.c
* arch/arm/src/lm/lm_syscontrol.c
* arch/arm/src/chip/lm_syscontrol.c
*
* Copyright (C) 2009 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
@ -78,7 +78,7 @@
****************************************************************************/
/****************************************************************************
* Name: lm3s_delay
* Name: lm_delay
*
* Description:
* Wait for the newly selected oscillator(s) to settle. This is tricky because
@ -87,7 +87,7 @@
*
****************************************************************************/
static inline void lm3s_delay(uint32_t delay)
static inline void lm_delay(uint32_t delay)
{
__asm__ __volatile__("1:\n"
"\tsubs %0, #1\n"
@ -96,7 +96,7 @@ static inline void lm3s_delay(uint32_t delay)
}
/****************************************************************************
* Name: lm3s_oscdelay
* Name: lm_oscdelay
*
* Description:
* Wait for the newly selected oscillator(s) to settle. This is tricky because
@ -105,7 +105,7 @@ static inline void lm3s_delay(uint32_t delay)
*
****************************************************************************/
static inline void lm3s_oscdelay(uint32_t rcc, uint32_t rcc2)
static inline void lm_oscdelay(uint32_t rcc, uint32_t rcc2)
{
/* Wait for the oscillator to stabilize. A smaller delay is used if the
* current clock rate is very slow.
@ -138,18 +138,18 @@ static inline void lm3s_oscdelay(uint32_t rcc, uint32_t rcc2)
/* Then delay that number of loops */
lm3s_delay(delay);
lm_delay(delay);
}
/****************************************************************************
* Name: lm3s_plllock
* Name: lm_plllock
*
* Description:
* The new RCC values have been selected... wait for the PLL to lock on
*
****************************************************************************/
static inline void lm3s_plllock(void)
static inline void lm_plllock(void)
{
volatile uint32_t delay;
@ -175,7 +175,7 @@ static inline void lm3s_plllock(void)
****************************************************************************/
/****************************************************************************
* Name: lm3s_clockconfig
* Name: lm_clockconfig
*
* Description:
* Called to change to new clock based on desired rcc and rcc2 settings.
@ -184,7 +184,7 @@ static inline void lm3s_plllock(void)
*
****************************************************************************/
void lm3s_clockconfig(uint32_t newrcc, uint32_t newrcc2)
void lm_clockconfig(uint32_t newrcc, uint32_t newrcc2)
{
uint32_t rcc;
uint32_t rcc2;
@ -221,7 +221,7 @@ void lm3s_clockconfig(uint32_t newrcc, uint32_t newrcc2)
* clock setting, not the one that we are configuring.
*/
lm3s_oscdelay(rcc, rcc2);
lm_oscdelay(rcc, rcc2);
}
/* Set the new crystal value, oscillator source and PLL configuration */
@ -253,7 +253,7 @@ void lm3s_clockconfig(uint32_t newrcc, uint32_t newrcc2)
/* Wait for the new crystal value and oscillator source to take effect */
lm3s_delay(16);
lm_delay(16);
/* Set the requested system divider and disable the non-selected osciallators */
@ -269,7 +269,7 @@ void lm3s_clockconfig(uint32_t newrcc, uint32_t newrcc2)
{
/* Yes, wail untill the PLL is locked */
lm3s_plllock();
lm_plllock();
/* Then enable the PLL */
@ -284,7 +284,7 @@ void lm3s_clockconfig(uint32_t newrcc, uint32_t newrcc2)
/* Wait for the system divider to be effective */
lm3s_delay(6);
lm_delay(6);
}
/****************************************************************************
@ -298,7 +298,7 @@ void lm3s_clockconfig(uint32_t newrcc, uint32_t newrcc2)
void up_clockconfig(void)
{
#ifdef CONFIG_LM3S_REVA2
#ifdef CONFIG_LM_REVA2
/* Some early silicon returned an increase LDO voltage or 2.75V to work
* around a PLL bug
*/
@ -310,6 +310,6 @@ void up_clockconfig(void)
* header file
*/
lm3s_clockconfig(LM3S_RCC_VALUE, LM3S_RCC2_VALUE);
lm_clockconfig(LM3S_RCC_VALUE, LM3S_RCC2_VALUE);
}

View File

@ -1,5 +1,5 @@
/************************************************************************************
* arch/arm/src/lm/lm3s_syscontrol.h
* arch/arm/src/lm/lm_syscontrol.h
*
* Copyright (C) 2009-2010, 2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
@ -70,7 +70,7 @@ extern "C"
****************************************************************************/
/****************************************************************************
* Name: lm3s_clockconfig
* Name: lm_clockconfig
*
* Description:
* Called to change to new clock based on desired rcc and rcc2 settings.
@ -79,7 +79,7 @@ extern "C"
*
****************************************************************************/
void lm3s_clockconfig(uint32_t newrcc, uint32_t newrcc2);
void lm_clockconfig(uint32_t newrcc, uint32_t newrcc2);
/****************************************************************************
* Name: up_clockconfig

View File

@ -1,5 +1,5 @@
/****************************************************************************
* arch/arm/src/lm/lm3s_timerisr.c
* arch/arm/src/lm/lm_timerisr.c
*
* Copyright (C) 2009 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>

View File

@ -0,0 +1,805 @@
/************************************************************************************
* arch/arm/src/lm/lm_vectors.S
* arch/arm/src/chip/lm_vectors.S
*
* Copyright (C) 2009-2010 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name NuttX nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
************************************************************************************/
/************************************************************************************
* Included Files
************************************************************************************/
#include <nuttx/config.h>
#include <arch/irq.h>
/************************************************************************************
* Preprocessor Definitions
************************************************************************************/
/* Memory Map:
*
* 0x0000:0000 - Beginning of FLASH. Address of vectors (if not using bootloader)
* 0x0002:0000 - Address of vectors if using bootloader
* 0x0003:ffff - End of flash
* 0x2000:0000 - Start of SRAM and start of .data (_sdata)
* - End of .data (_edata) abd start of .bss (_sbss)
* - End of .bss (_ebss) and bottom of idle stack
* - _ebss + CONFIG_IDLETHREAD_STACKSIZE = end of idle stack, start of heap
* 0x2000:ffff - End of SRAM and end of heap
*/
#define IDLE_STACK (_ebss+CONFIG_IDLETHREAD_STACKSIZE-4)
#define HEAP_BASE (_ebss+CONFIG_IDLETHREAD_STACKSIZE-4)
/* The Cortex-M3 return from interrupt is unusual. We provide the following special
* address to the BX instruction. The particular value also forces a return to
* thread mode and covers state from the main stack point, the MSP (vs. the MSP).
*/
#define EXC_RETURN 0xfffffff9
/************************************************************************************
* Global Symbols
************************************************************************************/
.globl __start
.syntax unified
.thumb
.file "lm_vectors.S"
/************************************************************************************
* Macros
************************************************************************************/
/* On entry into an IRQ, the hardware automatically saves the xPSR, PC, LR, R12, R0-R3
* registers on the stack, then branches to an instantantiation of the following
* macro. This macro simply loads the IRQ number into R0, then jumps to the common
* IRQ handling logic.
*/
.macro HANDLER, label, irqno
.thumb_func
\label:
mov r0, #\irqno
b lm_irqcommon
.endm
/************************************************************************************
* Vectors
************************************************************************************/
.section .vectors, "ax"
.code 16
.align 2
.globl lm_vectors
.type lm_vectors, function
lm_vectors:
/* Processor Exceptions */
.word IDLE_STACK /* Vector 0: Reset stack pointer */
.word __start /* Vector 1: Reset vector */
.word lm_nmi /* Vector 2: Non-Maskable Interrupt (NMI) */
.word lm_hardfault /* Vector 3: Hard fault */
.word lm_mpu /* Vector 4: Memory management (MPU) */
.word lm_busfault /* Vector 5: Bus fault */
.word lm_usagefault /* Vector 6: Usage fault */
.word lm_reserved /* Vector 7: Reserved */
.word lm_reserved /* Vector 8: Reserved */
.word lm_reserved /* Vector 9: Reserved */
.word lm_reserved /* Vector 10: Reserved */
.word lm_svcall /* Vector 11: SVC call */
.word lm_dbgmonitor /* Vector 12: Debug monitor */
.word lm_reserved /* Vector 13: Reserved */
.word lm_pendsv /* Vector 14: Pendable system service request */
.word lm_systick /* Vector 15: System tick */
/* External Interrupts */
#if defined(CONFIG_ARCH_CHIP_LM3S6918)
.word lm_gpioa /* Vector 16: GPIO Port A */
.word lm_gpiob /* Vector 17: GPIO Port B */
.word lm_gpioc /* Vector 18: GPIO Port C */
.word lm_gpiod /* Vector 19: GPIO Port D */
.word lm_gpioe /* Vector 20: GPIO Port E */
.word lm_uart0 /* Vector 21: UART 0 */
.word lm_uart1 /* Vector 22: UART 1 */
.word lm_ssi0 /* Vector 23: SSI 0 */
.word lm_i2c0 /* Vector 24: I2C 0 */
.word lm_reserved /* Vector 25: Reserved */
.word lm_reserved /* Vector 26: Reserved */
.word lm_reserved /* Vector 27: Reserved */
.word lm_reserved /* Vector 28: Reserved */
.word lm_reserved /* Vector 29: Reserved */
.word lm_adc0 /* Vector 30: ADC Sequence 0 */
.word lm_adc1 /* Vector 31: ADC Sequence 1 */
.word lm_adc2 /* Vector 32: ADC Sequence 2 */
.word lm_adc3 /* Vector 33: ADC Sequence 3 */
.word lm_wdog /* Vector 34: Watchdog Timer */
.word lm_tmr0a /* Vector 35: Timer 0 A */
.word lm_tmr0b /* Vector 36: Timer 0 B */
.word lm_tmr1a /* Vector 37: Timer 1 A */
.word lm_tmr1b /* Vector 38: Timer 1 B */
.word lm_tmr2a /* Vector 39: Timer 2 A */
.word lm_tmr2b /* Vector 40: Timer 3 B */
.word lm_cmp0 /* Vector 41: Analog Comparator 0 */
.word lm_cmp1 /* Vector 42: Analog Comparator 1 */
.word lm_reserved /* Vector 43: Reserved */
.word lm_syscon /* Vector 44: System Control */
.word lm_flashcon /* Vector 45: FLASH Control */
.word lm_gpiof /* Vector 46: GPIO Port F */
.word lm_gpiog /* Vector 47: GPIO Port G */
.word lm_gpioh /* Vector 48: GPIO Port H */
.word lm_reserved /* Vector 49: Reserved */
.word lm_ssi1 /* Vector 50: SSI 1 */
.word lm_tmr3a /* Vector 51: Timer 3 A */
.word lm_tmr3b /* Vector 52: Timer 3 B */
.word lm_i2c1 /* Vector 53: I2C 1 */
.word lm_reserved /* Vector 54: Reserved */
.word lm_reserved /* Vector 55: Reserved */
.word lm_reserved /* Vector 56: Reserved */
.word lm_reserved /* Vector 57: Reserved */
.word lm_eth /* Vector 58: Ethernet Controller */
.word lm_hib /* Vector 59: Hibernation Module */
.word lm_reserved /* Vector 60: Reserved */
.word lm_reserved /* Vector 61: Reserved */
.word lm_reserved /* Vector 62: Reserved */
.word lm_reserved /* Vector 63: Reserved */
.word lm_reserved /* Vector 64: Reserved */
.word lm_reserved /* Vector 65: Reserved */
.word lm_reserved /* Vector 66: Reserved */
.word lm_reserved /* Vector 67: Reserved */
.word lm_reserved /* Vector 68: Reserved */
.word lm_reserved /* Vector 69: Reserved */
.word lm_reserved /* Vector 70: Reserved */
#elif defined(CONFIG_ARCH_CHIP_LM3S6432)
.word lm_gpioa /* Vector 16: GPIO Port A */
.word lm_gpiob /* Vector 17: GPIO Port B */
.word lm_gpioc /* Vector 18: GPIO Port C */
.word lm_gpiod /* Vector 19: GPIO Port D */
.word lm_gpioe /* Vector 20: GPIO Port E */
.word lm_uart0 /* Vector 21: UART 0 */
.word lm_uart1 /* Vector 22: UART 1 */
.word lm_ssi0 /* Vector 23: SSI 0 */
.word lm_i2c0 /* Vector 24: I2C 0 */
.word lm_reserved /* Vector 25: Reserved */
.word lm_pwm0 /* Vector 26: PWM Generator 0 */
.word lm_reserved /* Vector 27: Reserved */
.word lm_reserved /* Vector 28: Reserved */
.word lm_reserved /* Vector 29: Reserved */
.word lm_adc0 /* Vector 30: ADC Sequence 0 */
.word lm_adc1 /* Vector 31: ADC Sequence 1 */
.word lm_adc2 /* Vector 32: ADC Sequence 2 */
.word lm_adc3 /* Vector 33: ADC Sequence 3 */
.word lm_wdog /* Vector 34: Watchdog Timer */
.word lm_tmr0a /* Vector 35: Timer 0 A */
.word lm_tmr0b /* Vector 36: Timer 0 B */
.word lm_tmr1a /* Vector 37: Timer 1 A */
.word lm_tmr1b /* Vector 38: Timer 1 B */
.word lm_tmr2a /* Vector 39: Timer 2 A */
.word lm_tmr2b /* Vector 40: Timer 3 B */
.word lm_cmp0 /* Vector 41: Analog Comparator 0 */
.word lm_cmp1 /* Vector 42: Analog Comparator 1 */
.word lm_reserved /* Vector 43: Reserved */
.word lm_syscon /* Vector 44: System Control */
.word lm_flashcon /* Vector 45: FLASH Control */
.word lm_gpiof /* Vector 46: GPIO Port F */
.word lm_gpiog /* Vector 47: GPIO Port G */
.word lm_reserved /* Vector 48: Reserved */
.word lm_reserved /* Vector 49: Reserved */
.word lm_reserved /* Vector 50: Reserved */
.word lm_reserved /* Vector 51: Reserved */
.word lm_reserved /* Vector 52: Reserved */
.word lm_reserved /* Vector 53: Reserved */
.word lm_reserved /* Vector 54: Reserved */
.word lm_reserved /* Vector 55: Reserved */
.word lm_reserved /* Vector 56: Reserved */
.word lm_reserved /* Vector 57: Reserved */
.word lm_eth /* Vector 58: Ethernet Controller */
.word lm_reserved /* Vector 59: Reserved */
.word lm_reserved /* Vector 60: Reserved */
.word lm_reserved /* Vector 61: Reserved */
.word lm_reserved /* Vector 62: Reserved */
.word lm_reserved /* Vector 63: Reserved */
.word lm_reserved /* Vector 64: Reserved */
.word lm_reserved /* Vector 65: Reserved */
.word lm_reserved /* Vector 66: Reserved */
.word lm_reserved /* Vector 67: Reserved */
.word lm_reserved /* Vector 68: Reserved */
.word lm_reserved /* Vector 69: Reserved */
.word lm_reserved /* Vector 70: Reserved */
#elif defined(CONFIG_ARCH_CHIP_LM3S6965)
.word lm_gpioa /* Vector 16: GPIO Port A */
.word lm_gpiob /* Vector 17: GPIO Port B */
.word lm_gpioc /* Vector 18: GPIO Port C */
.word lm_gpiod /* Vector 19: GPIO Port D */
.word lm_gpioe /* Vector 20: GPIO Port E */
.word lm_uart0 /* Vector 21: UART 0 */
.word lm_uart1 /* Vector 22: UART 1 */
.word lm_ssi0 /* Vector 23: SSI 0 */
.word lm_i2c0 /* Vector 24: I2C 0 */
.word lm_pwmfault /* Vector 25: PWM Fault */
.word lm_pwm0 /* Vector 26: PWM Generator 0 */
.word lm_pwm1 /* Vector 27: PWM Generator 1 */
.word lm_pwm2 /* Vector 28: PWM Generator 2 */
.word lm_qei0 /* Vector 29: QEI0 */
.word lm_adc0 /* Vector 30: ADC Sequence 0 */
.word lm_adc1 /* Vector 31: ADC Sequence 1 */
.word lm_adc2 /* Vector 32: ADC Sequence 2 */
.word lm_adc3 /* Vector 33: ADC Sequence 3 */
.word lm_wdog /* Vector 34: Watchdog Timer */
.word lm_tmr0a /* Vector 35: Timer 0 A */
.word lm_tmr0b /* Vector 36: Timer 0 B */
.word lm_tmr1a /* Vector 37: Timer 1 A */
.word lm_tmr1b /* Vector 38: Timer 1 B */
.word lm_tmr2a /* Vector 39: Timer 2 A */
.word lm_tmr2b /* Vector 40: Timer 3 B */
.word lm_cmp0 /* Vector 41: Analog Comparator 0 */
.word lm_cmp1 /* Vector 42: Analog Comparator 1 */
.word lm_reserved /* Vector 43: Reserved */
.word lm_syscon /* Vector 44: System Control */
.word lm_flashcon /* Vector 45: FLASH Control */
.word lm_gpiof /* Vector 46: GPIO Port F */
.word lm_gpiog /* Vector 47: GPIO Port G */
.word lm_reserved /* Vector 48: Reserved */
.word lm_uart2 /* Vector 49: UART 2 */
.word lm_reserved /* Vector 50: Reserved */
.word lm_tmr3a /* Vector 51: Timer 3 A */
.word lm_tmr3b /* Vector 52: Timer 3 B */
.word lm_i2c1 /* Vector 53: I2C 1 */
.word lm_qei1 /* Vector 54: QEI1 */
.word lm_reserved /* Vector 55: Reserved */
.word lm_reserved /* Vector 56: Reserved */
.word lm_reserved /* Vector 57: Reserved */
.word lm_eth /* Vector 58: Ethernet Controller */
.word lm_hib /* Vector 59: Hibernation Module */
.word lm_reserved /* Vector 60: Reserved */
.word lm_reserved /* Vector 61: Reserved */
.word lm_reserved /* Vector 62: Reserved */
.word lm_reserved /* Vector 63: Reserved */
.word lm_reserved /* Vector 64: Reserved */
.word lm_reserved /* Vector 65: Reserved */
.word lm_reserved /* Vector 66: Reserved */
.word lm_reserved /* Vector 67: Reserved */
.word lm_reserved /* Vector 68: Reserved */
.word lm_reserved /* Vector 69: Reserved */
.word lm_reserved /* Vector 70: Reserved */
#elif defined(CONFIG_ARCH_CHIP_LM3S9B96)
.word lm_gpioa /* Vector 16: GPIO Port A */
.word lm_gpiob /* Vector 17: GPIO Port B */
.word lm_gpioc /* Vector 18: GPIO Port C */
.word lm_gpiod /* Vector 19: GPIO Port D */
.word lm_gpioe /* Vector 20: GPIO Port E */
.word lm_uart0 /* Vector 21: UART 0 */
.word lm_uart1 /* Vector 22: UART 1 */
.word lm_ssi0 /* Vector 23: SSI 0 */
.word lm_i2c0 /* Vector 24: I2C 0 */
.word lm_pwmfault /* Vector 25: PWM Fault */
.word lm_pwm0 /* Vector 26: PWM Generator 0 */
.word lm_pwm1 /* Vector 27: PWM Generator 1 */
.word lm_pwm2 /* Vector 28: PWM Generator 2 */
.word lm_qei0 /* Vector 29: QEI0 */
.word lm_adc0 /* Vector 30: ADC Sequence 0 */
.word lm_adc1 /* Vector 31: ADC Sequence 1 */
.word lm_adc2 /* Vector 32: ADC Sequence 2 */
.word lm_adc3 /* Vector 33: ADC Sequence 3 */
.word lm_wdog /* Vector 34: Watchdog Timer */
.word lm_tmr0a /* Vector 35: Timer 0 A */
.word lm_tmr0b /* Vector 36: Timer 0 B */
.word lm_tmr1a /* Vector 37: Timer 1 A */
.word lm_tmr1b /* Vector 38: Timer 1 B */
.word lm_tmr2a /* Vector 39: Timer 2 A */
.word lm_tmr2b /* Vector 40: Timer 3 B */
.word lm_cmp0 /* Vector 41: Analog Comparator 0 */
.word lm_cmp1 /* Vector 42: Analog Comparator 1 */
.word lm_cmp2 /* Vector 43: Reserved */
.word lm_syscon /* Vector 44: System Control */
.word lm_flashcon /* Vector 45: FLASH Control */
.word lm_gpiof /* Vector 46: GPIO Port F */
.word lm_gpiog /* Vector 47: GPIO Port G */
.word lm_gpioh /* Vector 48: GPIO Port H */
.word lm_uart2 /* Vector 49: UART 2 */
.word lm_ssi1 /* Vector 50: SSI 1 */
.word lm_tmr3a /* Vector 51: Timer 3 A */
.word lm_tmr3b /* Vector 52: Timer 3 B */
.word lm_i2c1 /* Vector 53: I2C 1 */
.word lm_qei1 /* Vector 54: QEI1 */
.word lm_can0 /* Vector 55: CAN 0 */
.word lm_can1 /* Vector 56: CAN 1 */
.word lm_reserved /* Vector 57: Reserved */
.word lm_eth /* Vector 58: Ethernet Controller */
.word lm_reserved /* Vector 59: Reserved */
.word lm_usb /* Vector 60: USB */
.word lm_pwm3 /* Vector 61: PWM 3 */
.word lm_udmasoft /* Vector 62: uDMA Software */
.word lm_udmaerror /* Vector 63: uDMA Error */
.word lm_adc1_0 /* Vector 64: ADC1 Sequence 0 */
.word lm_adc1_1 /* Vector 65: ADC1 Sequence 1 */
.word lm_adc1_2 /* Vector 66: ADC1 Sequence 2 */
.word lm_adc1_3 /* Vector 67: ADC1 Sequence 3 */
.word lm_i2s0 /* Vector 68: I2S 0 */
.word lm_epi /* Vector 69: Reserved */
.word lm_gpioj /* Vector 70: GPIO J */
.word lm_reserved /* Vector 71: Reserved */
#elif defined(CONFIG_ARCH_CHIP_LM3S8962)
.word lm_gpioa /* Vector 16: GPIO Port A */
.word lm_gpiob /* Vector 17: GPIO Port B */
.word lm_gpioc /* Vector 18: GPIO Port C */
.word lm_gpiod /* Vector 19: GPIO Port D */
.word lm_gpioe /* Vector 20: GPIO Port E */
.word lm_uart0 /* Vector 21: UART 0 */
.word lm_uart1 /* Vector 22: UART 1 */
.word lm_ssi0 /* Vector 23: SSI 0 */
.word lm_i2c0 /* Vector 24: I2C 0 */
.word lm_pwmfault /* Vector 25: PWM Fault */
.word lm_pwm0 /* Vector 26: PWM Generator 0 */
.word lm_pwm1 /* Vector 27: PWM Generator 1 */
.word lm_pwm2 /* Vector 28: PWM Generator 2 */
.word lm_qei0 /* Vector 29: QEI0 */
.word lm_adc0 /* Vector 30: ADC Sequence 0 */
.word lm_adc1 /* Vector 31: ADC Sequence 1 */
.word lm_adc2 /* Vector 32: ADC Sequence 2 */
.word lm_adc3 /* Vector 33: ADC Sequence 3 */
.word lm_wdog /* Vector 34: Watchdog Timer */
.word lm_tmr0a /* Vector 35: Timer 0 A */
.word lm_tmr0b /* Vector 36: Timer 0 B */
.word lm_tmr1a /* Vector 37: Timer 1 A */
.word lm_tmr1b /* Vector 38: Timer 1 B */
.word lm_tmr2a /* Vector 39: Timer 2 A */
.word lm_tmr2b /* Vector 40: Timer 3 B */
.word lm_cmp0 /* Vector 41: Analog Comparator 0 */
.word lm_reserved /* Vector 42: Reserved */
.word lm_reserved /* Vector 43: Reserved */
.word lm_syscon /* Vector 44: System Control */
.word lm_flashcon /* Vector 45: FLASH Control */
.word lm_gpiof /* Vector 46: GPIO Port F */
.word lm_gpiog /* Vector 47: GPIO Port G */
.word lm_reserved /* Vector 48: Reserved */
.word lm_reserved /* Vector 49: Reserved */
.word lm_reserved /* Vector 50: Reserved */
.word lm_tmr3a /* Vector 51: Timer 3 A */
.word lm_tmr3b /* Vector 52: Timer 3 B */
.word lm_reserved /* Vector 53: Reserved*/
.word lm_qei1 /* Vector 54: QEI1 */
.word lm_can0 /* Vector 55: Can Controller */
.word lm_reserved /* Vector 56: Reserved */
.word lm_reserved /* Vector 57: Reserved */
.word lm_eth /* Vector 58: Ethernet Controller */
.word lm_hib /* Vector 59: Hibernation Module */
.word lm_reserved /* Vector 60: Reserved */
.word lm_reserved /* Vector 61: Reserved */
.word lm_reserved /* Vector 62: Reserved */
.word lm_reserved /* Vector 63: Reserved */
.word lm_reserved /* Vector 64: Reserved */
.word lm_reserved /* Vector 65: Reserved */
.word lm_reserved /* Vector 66: Reserved */
.word lm_reserved /* Vector 67: Reserved */
.word lm_reserved /* Vector 68: Reserved */
.word lm_reserved /* Vector 69: Reserved */
.word lm_reserved /* Vector 70: Reserved */
#else
# error "Vectors not specified for this LM3S chip"
#endif
.size lm_vectors, .-lm_vectors
/************************************************************************************
* .text
************************************************************************************/
.text
.type handlers, function
.thumb_func
handlers:
HANDLER lm_reserved, LM3S_IRQ_RESERVED /* Unexpected/reserved vector */
HANDLER lm_nmi, LM3S_IRQ_NMI /* Vector 2: Non-Maskable Interrupt (NMI) */
HANDLER lm_hardfault, LM3S_IRQ_HARDFAULT /* Vector 3: Hard fault */
HANDLER lm_mpu, LM3S_IRQ_MEMFAULT /* Vector 4: Memory management (MPU) */
HANDLER lm_busfault, LM3S_IRQ_BUSFAULT /* Vector 5: Bus fault */
HANDLER lm_usagefault, LM3S_IRQ_USAGEFAULT /* Vector 6: Usage fault */
HANDLER lm_svcall, LM3S_IRQ_SVCALL /* Vector 11: SVC call */
HANDLER lm_dbgmonitor, LM3S_IRQ_DBGMONITOR /* Vector 12: Debug Monitor */
HANDLER lm_pendsv, LM3S_IRQ_PENDSV /* Vector 14: Penable system service request */
HANDLER lm_systick, LM3S_IRQ_SYSTICK /* Vector 15: System tick */
#if defined(CONFIG_ARCH_CHIP_LM3S6918)
HANDLER lm_gpioa, LM3S_IRQ_GPIOA /* Vector 16: GPIO Port A */
HANDLER lm_gpiob, LM3S_IRQ_GPIOB /* Vector 17: GPIO Port B */
HANDLER lm_gpioc, LM3S_IRQ_GPIOC /* Vector 18: GPIO Port C */
HANDLER lm_gpiod, LM3S_IRQ_GPIOD /* Vector 19: GPIO Port D */
HANDLER lm_gpioe, LM3S_IRQ_GPIOE /* Vector 20: GPIO Port E */
HANDLER lm_uart0, LM3S_IRQ_UART0 /* Vector 21: UART 0 */
HANDLER lm_uart1, LM3S_IRQ_UART1 /* Vector 22: UART 1 */
HANDLER lm_ssi0, LM3S_IRQ_SSI0 /* Vector 23: SSI 0 */
HANDLER lm_i2c0, LM3S_IRQ_I2C0 /* Vector 24: I2C 0 */
HANDLER lm_adc0, LM3S_IRQ_ADC0 /* Vector 30: ADC Sequence 0 */
HANDLER lm_adc1, LM3S_IRQ_ADC1 /* Vector 31: ADC Sequence 1 */
HANDLER lm_adc2, LM3S_IRQ_ADC2 /* Vector 32: ADC Sequence 2 */
HANDLER lm_adc3, LM3S_IRQ_ADC3 /* Vector 33: ADC Sequence 3 */
HANDLER lm_wdog, LM3S_IRQ_WDOG /* Vector 34: Watchdog Timer */
HANDLER lm_tmr0a, LM3S_IRQ_TIMER0A /* Vector 35: Timer 0 A */
HANDLER lm_tmr0b, LM3S_IRQ_TIMER0B /* Vector 36: Timer 0 B */
HANDLER lm_tmr1a, LM3S_IRQ_TIMER1A /* Vector 37: Timer 1 A */
HANDLER lm_tmr1b, LM3S_IRQ_TIMER1B /* Vector 38: Timer 1 B */
HANDLER lm_tmr2a, LM3S_IRQ_TIMER2A /* Vector 39: Timer 2 A */
HANDLER lm_tmr2b, LM3S_IRQ_TIMER2B /* Vector 40: Timer 3 B */
HANDLER lm_cmp0, LM3S_IRQ_COMPARE0 /* Vector 41: Analog Comparator 0 */
HANDLER lm_cmp1, LM3S_IRQ_COMPARE1 /* Vector 42: Analog Comparator 1 */
HANDLER lm_syscon, LM3S_IRQ_SYSCON /* Vector 44: System Control */
HANDLER lm_flashcon, LM3S_IRQ_FLASHCON /* Vector 45: FLASH Control */
HANDLER lm_gpiof, LM3S_IRQ_GPIOF /* Vector 46: GPIO Port F */
HANDLER lm_gpiog, LM3S_IRQ_GPIOG /* Vector 47: GPIO Port G */
HANDLER lm_gpioh, LM3S_IRQ_GPIOH /* Vector 48: GPIO Port H */
HANDLER lm_ssi1, LM3S_IRQ_SSI1 /* Vector 50: SSI 1 */
HANDLER lm_tmr3a, LM3S_IRQ_TIMER3A /* Vector 51: Timer 3 A */
HANDLER lm_tmr3b, LM3S_IRQ_TIMER3B /* Vector 52: Timer 3 B */
HANDLER lm_i2c1, LM3S_IRQ_I2C1 /* Vector 53: I2C 1 */
HANDLER lm_eth, LM3S_IRQ_ETHCON /* Vector 58: Ethernet Controller */
HANDLER lm_hib, LM3S_IRQ_HIBERNATE /* Vector 59: Hibernation Module */
#elif defined(CONFIG_ARCH_CHIP_LM3S6432)
HANDLER lm_gpioa, LM3S_IRQ_GPIOA /* Vector 16: GPIO Port A */
HANDLER lm_gpiob, LM3S_IRQ_GPIOB /* Vector 17: GPIO Port B */
HANDLER lm_gpioc, LM3S_IRQ_GPIOC /* Vector 18: GPIO Port C */
HANDLER lm_gpiod, LM3S_IRQ_GPIOD /* Vector 19: GPIO Port D */
HANDLER lm_gpioe, LM3S_IRQ_GPIOE /* Vector 20: GPIO Port E */
HANDLER lm_uart0, LM3S_IRQ_UART0 /* Vector 21: UART 0 */
HANDLER lm_uart1, LM3S_IRQ_UART1 /* Vector 22: UART 1 */
HANDLER lm_ssi0, LM3S_IRQ_SSI0 /* Vector 23: SSI 0 */
HANDLER lm_i2c0, LM3S_IRQ_I2C0 /* Vector 24: I2C 0 */
HANDLER lm_pwm0, LM3S_IRQ_PWM0 /* Vector 26: PWM Generator 0 */
HANDLER lm_adc0, LM3S_IRQ_ADC0 /* Vector 30: ADC Sequence 0 */
HANDLER lm_adc1, LM3S_IRQ_ADC1 /* Vector 31: ADC Sequence 1 */
HANDLER lm_adc2, LM3S_IRQ_ADC2 /* Vector 32: ADC Sequence 2 */
HANDLER lm_adc3, LM3S_IRQ_ADC3 /* Vector 33: ADC Sequence 3 */
HANDLER lm_wdog, LM3S_IRQ_WDOG /* Vector 34: Watchdog Timer */
HANDLER lm_tmr0a, LM3S_IRQ_TIMER0A /* Vector 35: Timer 0 A */
HANDLER lm_tmr0b, LM3S_IRQ_TIMER0B /* Vector 36: Timer 0 B */
HANDLER lm_tmr1a, LM3S_IRQ_TIMER1A /* Vector 37: Timer 1 A */
HANDLER lm_tmr1b, LM3S_IRQ_TIMER1B /* Vector 38: Timer 1 B */
HANDLER lm_tmr2a, LM3S_IRQ_TIMER2A /* Vector 39: Timer 2 A */
HANDLER lm_tmr2b, LM3S_IRQ_TIMER2B /* Vector 40: Timer 3 B */
HANDLER lm_cmp0, LM3S_IRQ_COMPARE0 /* Vector 41: Analog Comparator 0 */
HANDLER lm_cmp1, LM3S_IRQ_COMPARE1 /* Vector 42: Analog Comparator 1 */
HANDLER lm_syscon, LM3S_IRQ_SYSCON /* Vector 44: System Control */
HANDLER lm_flashcon, LM3S_IRQ_FLASHCON /* Vector 45: FLASH Control */
HANDLER lm_gpiof, LM3S_IRQ_GPIOF /* Vector 46: GPIO Port F */
HANDLER lm_gpiog, LM3S_IRQ_GPIOG /* Vector 47: GPIO Port G */
HANDLER lm_eth, LM3S_IRQ_ETHCON /* Vector 58: Ethernet Controller */
#elif defined(CONFIG_ARCH_CHIP_LM3S6965)
HANDLER lm_gpioa, LM3S_IRQ_GPIOA /* Vector 16: GPIO Port A */
HANDLER lm_gpiob, LM3S_IRQ_GPIOB /* Vector 17: GPIO Port B */
HANDLER lm_gpioc, LM3S_IRQ_GPIOC /* Vector 18: GPIO Port C */
HANDLER lm_gpiod, LM3S_IRQ_GPIOD /* Vector 19: GPIO Port D */
HANDLER lm_gpioe, LM3S_IRQ_GPIOE /* Vector 20: GPIO Port E */
HANDLER lm_uart0, LM3S_IRQ_UART0 /* Vector 21: UART 0 */
HANDLER lm_uart1, LM3S_IRQ_UART1 /* Vector 22: UART 1 */
HANDLER lm_ssi0, LM3S_IRQ_SSI0 /* Vector 23: SSI 0 */
HANDLER lm_i2c0, LM3S_IRQ_I2C0 /* Vector 24: I2C 0 */
HANDLER lm_pwmfault, LM3S_IRQ_PWMFAULT /* Vector 25: PWM Fault */
HANDLER lm_pwm0, LM3S_IRQ_PWM0 /* Vector 26: PWM Generator 0 */
HANDLER lm_pwm1, LM3S_IRQ_PWM1 /* Vector 27: PWM Generator 1 */
HANDLER lm_pwm2, LM3S_IRQ_PWM2 /* Vector 28: PWM Generator 2 */
HANDLER lm_qei0, LM3S_IRQ_QEI0 /* Vector 29: QEI 0 */
HANDLER lm_adc0, LM3S_IRQ_ADC0 /* Vector 30: ADC Sequence 0 */
HANDLER lm_adc1, LM3S_IRQ_ADC1 /* Vector 31: ADC Sequence 1 */
HANDLER lm_adc2, LM3S_IRQ_ADC2 /* Vector 32: ADC Sequence 2 */
HANDLER lm_adc3, LM3S_IRQ_ADC3 /* Vector 33: ADC Sequence 3 */
HANDLER lm_wdog, LM3S_IRQ_WDOG /* Vector 34: Watchdog Timer */
HANDLER lm_tmr0a, LM3S_IRQ_TIMER0A /* Vector 35: Timer 0 A */
HANDLER lm_tmr0b, LM3S_IRQ_TIMER0B /* Vector 36: Timer 0 B */
HANDLER lm_tmr1a, LM3S_IRQ_TIMER1A /* Vector 37: Timer 1 A */
HANDLER lm_tmr1b, LM3S_IRQ_TIMER1B /* Vector 38: Timer 1 B */
HANDLER lm_tmr2a, LM3S_IRQ_TIMER2A /* Vector 39: Timer 2 A */
HANDLER lm_tmr2b, LM3S_IRQ_TIMER2B /* Vector 40: Timer 3 B */
HANDLER lm_cmp0, LM3S_IRQ_COMPARE0 /* Vector 41: Analog Comparator 0 */
HANDLER lm_cmp1, LM3S_IRQ_COMPARE1 /* Vector 42: Analog Comparator 1 */
HANDLER lm_syscon, LM3S_IRQ_SYSCON /* Vector 44: System Control */
HANDLER lm_flashcon, LM3S_IRQ_FLASHCON /* Vector 45: FLASH Control */
HANDLER lm_gpiof, LM3S_IRQ_GPIOF /* Vector 46: GPIO Port F */
HANDLER lm_gpiog, LM3S_IRQ_GPIOG /* Vector 47: GPIO Port G */
HANDLER lm_uart2, LM3S_IRQ_UART1 /* Vector 49: UART 1 */
HANDLER lm_tmr3a, LM3S_IRQ_TIMER3A /* Vector 51: Timer 3 A */
HANDLER lm_tmr3b, LM3S_IRQ_TIMER3B /* Vector 52: Timer 3 B */
HANDLER lm_i2c1, LM3S_IRQ_I2C1 /* Vector 53: I2C 1 */
HANDLER lm_qei1, LM3S_IRQ_QEI1 /* Vector 54: QEI 1 */
HANDLER lm_eth, LM3S_IRQ_ETHCON /* Vector 58: Ethernet Controller */
HANDLER lm_hib, LM3S_IRQ_HIBERNATE /* Vector 59: Hibernation Module */
#elif defined(CONFIG_ARCH_CHIP_LM3S8962)
HANDLER lm_gpioa, LM3S_IRQ_GPIOA /* Vector 16: GPIO Port A */
HANDLER lm_gpiob, LM3S_IRQ_GPIOB /* Vector 17: GPIO Port B */
HANDLER lm_gpioc, LM3S_IRQ_GPIOC /* Vector 18: GPIO Port C */
HANDLER lm_gpiod, LM3S_IRQ_GPIOD /* Vector 19: GPIO Port D */
HANDLER lm_gpioe, LM3S_IRQ_GPIOE /* Vector 20: GPIO Port E */
HANDLER lm_uart0, LM3S_IRQ_UART0 /* Vector 21: UART 0 */
HANDLER lm_uart1, LM3S_IRQ_UART1 /* Vector 22: UART 1 */
HANDLER lm_ssi0, LM3S_IRQ_SSI0 /* Vector 23: SSI 0 */
HANDLER lm_i2c0, LM3S_IRQ_I2C0 /* Vector 24: I2C 0 */
HANDLER lm_pwmfault, LM3S_IRQ_PWMFAULT /* Vector 25: PWM Fault */
HANDLER lm_pwm0, LM3S_IRQ_PWM0 /* Vector 26: PWM Generator 0 */
HANDLER lm_pwm1, LM3S_IRQ_PWM1 /* Vector 27: PWM Generator 1 */
HANDLER lm_pwm2, LM3S_IRQ_PWM2 /* Vector 28: PWM Generator 2 */
HANDLER lm_qei0, LM3S_IRQ_QEI0 /* Vector 29: QEI 0 */
HANDLER lm_adc0, LM3S_IRQ_ADC0 /* Vector 30: ADC Sequence 0 */
HANDLER lm_adc1, LM3S_IRQ_ADC1 /* Vector 31: ADC Sequence 1 */
HANDLER lm_adc2, LM3S_IRQ_ADC2 /* Vector 32: ADC Sequence 2 */
HANDLER lm_adc3, LM3S_IRQ_ADC3 /* Vector 33: ADC Sequence 3 */
HANDLER lm_wdog, LM3S_IRQ_WDOG /* Vector 34: Watchdog Timer */
HANDLER lm_tmr0a, LM3S_IRQ_TIMER0A /* Vector 35: Timer 0 A */
HANDLER lm_tmr0b, LM3S_IRQ_TIMER0B /* Vector 36: Timer 0 B */
HANDLER lm_tmr1a, LM3S_IRQ_TIMER1A /* Vector 37: Timer 1 A */
HANDLER lm_tmr1b, LM3S_IRQ_TIMER1B /* Vector 38: Timer 1 B */
HANDLER lm_tmr2a, LM3S_IRQ_TIMER2A /* Vector 39: Timer 2 A */
HANDLER lm_tmr2b, LM3S_IRQ_TIMER2B /* Vector 40: Timer 3 B */
HANDLER lm_cmp0, LM3S_IRQ_COMPARE0 /* Vector 41: Analog Comparator 0 */
HANDLER lm_syscon, LM3S_IRQ_SYSCON /* Vector 44: System Control */
HANDLER lm_flashcon, LM3S_IRQ_FLASHCON /* Vector 45: FLASH Control */
HANDLER lm_gpiof, LM3S_IRQ_GPIOF /* Vector 46: GPIO Port F */
HANDLER lm_gpiog, LM3S_IRQ_GPIOG /* Vector 47: GPIO Port G */
HANDLER lm_uart2, LM3S_IRQ_UART1 /* Vector 49: UART 1 */
HANDLER lm_tmr3a, LM3S_IRQ_TIMER3A /* Vector 51: Timer 3 A */
HANDLER lm_tmr3b, LM3S_IRQ_TIMER3B /* Vector 52: Timer 3 B */
HANDLER lm_i2c1, LM3S_IRQ_I2C1 /* Vector 53: I2C 1 */
HANDLER lm_qei1, LM3S_IRQ_QEI1 /* Vector 54: QEI 1 */
HANDLER lm_can0, LM3S_IRQ_CAN0 /* Vector 55: CAN 0 */
HANDLER lm_eth, LM3S_IRQ_ETHCON /* Vector 58: Ethernet Controller */
HANDLER lm_hib, LM3S_IRQ_HIBERNATE /* Vector 59: Hibernation Module */
#elif defined(CONFIG_ARCH_CHIP_LM3S9B96)
HANDLER lm_gpioa, LM3S_IRQ_GPIOA /* Vector 16: GPIO Port A */
HANDLER lm_gpiob, LM3S_IRQ_GPIOB /* Vector 17: GPIO Port B */
HANDLER lm_gpioc, LM3S_IRQ_GPIOC /* Vector 18: GPIO Port C */
HANDLER lm_gpiod, LM3S_IRQ_GPIOD /* Vector 19: GPIO Port D */
HANDLER lm_gpioe, LM3S_IRQ_GPIOE /* Vector 20: GPIO Port E */
HANDLER lm_uart0, LM3S_IRQ_UART0 /* Vector 21: UART 0 */
HANDLER lm_uart1, LM3S_IRQ_UART1 /* Vector 22: UART 1 */
HANDLER lm_ssi0, LM3S_IRQ_SSI0 /* Vector 23: SSI 0 */
HANDLER lm_i2c0, LM3S_IRQ_I2C0 /* Vector 24: I2C 0 */
HANDLER lm_pwmfault, LM3S_IRQ_PWMFAULT /* Vector 25: PWM Fault */
HANDLER lm_pwm0, LM3S_IRQ_PWM0 /* Vector 26: PWM Generator 0 */
HANDLER lm_pwm1, LM3S_IRQ_PWM1 /* Vector 27: PWM Generator 1 */
HANDLER lm_pwm2, LM3S_IRQ_PWM2 /* Vector 28: PWM Generator 2 */
HANDLER lm_qei0, LM3S_IRQ_QEI0 /* Vector 29: QEI 0 */
HANDLER lm_adc0, LM3S_IRQ_ADC0 /* Vector 30: ADC Sequence 0 */
HANDLER lm_adc1, LM3S_IRQ_ADC1 /* Vector 31: ADC Sequence 1 */
HANDLER lm_adc2, LM3S_IRQ_ADC2 /* Vector 32: ADC Sequence 2 */
HANDLER lm_adc3, LM3S_IRQ_ADC3 /* Vector 33: ADC Sequence 3 */
HANDLER lm_wdog, LM3S_IRQ_WDOG /* Vector 34: Watchdog Timer */
HANDLER lm_tmr0a, LM3S_IRQ_TIMER0A /* Vector 35: Timer 0 A */
HANDLER lm_tmr0b, LM3S_IRQ_TIMER0B /* Vector 36: Timer 0 B */
HANDLER lm_tmr1a, LM3S_IRQ_TIMER1A /* Vector 37: Timer 1 A */
HANDLER lm_tmr1b, LM3S_IRQ_TIMER1B /* Vector 38: Timer 1 B */
HANDLER lm_tmr2a, LM3S_IRQ_TIMER2A /* Vector 39: Timer 2 A */
HANDLER lm_tmr2b, LM3S_IRQ_TIMER2B /* Vector 40: Timer 3 B */
HANDLER lm_cmp0, LM3S_IRQ_COMPARE0 /* Vector 41: Analog Comparator 0 */
HANDLER lm_cmp1, LM3S_IRQ_COMPARE1 /* Vector 42: Analog Comparator 1 */
HANDLER lm_cmp2, LM3S_IRQ_COMPARE2 /* Vector 43: Analog Comparator 2 */
HANDLER lm_syscon, LM3S_IRQ_SYSCON /* Vector 44: System Control */
HANDLER lm_flashcon, LM3S_IRQ_FLASHCON /* Vector 45: FLASH Control */
HANDLER lm_gpiof, LM3S_IRQ_GPIOF /* Vector 46: GPIO Port F */
HANDLER lm_gpiog, LM3S_IRQ_GPIOG /* Vector 47: GPIO Port G */
HANDLER lm_gpioh, LM3S_IRQ_GPIOH /* Vector 48: GPIO Port H */
HANDLER lm_uart2, LM3S_IRQ_UART2 /* Vector 49: UART 2 */
HANDLER lm_ssi1, LM3S_IRQ_SSI1 /* Vector 50: GPIO Port H */
HANDLER lm_tmr3a, LM3S_IRQ_TIMER3A /* Vector 51: Timer 3 A */
HANDLER lm_tmr3b, LM3S_IRQ_TIMER3B /* Vector 52: Timer 3 B */
HANDLER lm_i2c1, LM3S_IRQ_I2C1 /* Vector 53: I2C 1 */
HANDLER lm_qei1, LM3S_IRQ_QEI1 /* Vector 54: QEI 1 */
HANDLER lm_can0, LM3S_IRQ_CAN0 /* Vector 55: CAN 0 */
HANDLER lm_can1, LM3S_IRQ_CAN1 /* Vector 56: CAN 1 */
HANDLER lm_eth, LM3S_IRQ_ETHCON /* Vector 58: Ethernet Controller */
HANDLER lm_usb, LM3S_IRQ_USB /* Vector 60: USB */
HANDLER lm_pwm3, LM3S_IRQ_PWM3 /* Vector 61: PWM 3 */
HANDLER lm_udmasoft, LM3S_IRQ_UDMASOFT /* Vector 62: uDMA Software */
HANDLER lm_udmaerror, LM3S_IRQ_UDMAERROR /* Vector 63: uDMA Error */
HANDLER lm_adc1_0, LM3S_IRQ_ADC1_0 /* Vector 64: ADC1 Sequence 0 */
HANDLER lm_adc1_1, LM3S_IRQ_ADC1_1 /* Vector 65: ADC1 Sequence 1 */
HANDLER lm_adc1_2, LM3S_IRQ_ADC1_2 /* Vector 66: ADC1 Sequence 2 */
HANDLER lm_adc1_3, LM3S_IRQ_ADC1_3 /* Vector 67: ADC1 Sequence 3 */
HANDLER lm_i2s0, LM3S_IRQ_I2S0 /* Vector 68: I2S 0 */
HANDLER lm_epi, LM3S_IRQ_EPI /* Vector 69: EPI */
HANDLER lm_gpioj, LM3S_IRQ_GPIOJ /* Vector 70: GPIO Port J */
#else
# error "Vectors not specified for this LM3S chip"
#endif
/* Common IRQ handling logic. On entry here, the return stack is on either
* the PSP or the MSP and looks like the following:
*
* REG_XPSR
* REG_R15
* REG_R14
* REG_R12
* REG_R3
* REG_R2
* REG_R1
* MSP->REG_R0
*
* And
* R0 contains the IRQ number
* R14 Contains the EXC_RETURN value
* We are in handler mode and the current SP is the MSP
*/
lm_irqcommon:
/* Complete the context save */
#ifdef CONFIG_NUTTX_KERNEL
/* The EXC_RETURN value will be 0xfffffff9 (privileged thread) or 0xfffffff1
* (handler mode) if the state is on the MSP. It can only be on the PSP if
* EXC_RETURN is 0xfffffffd (unprivileged thread)
*/
adds r2, r14, #3 /* If R14=0xfffffffd, then r2 == 0 */
ite ne /* Next two instructions are condition */
mrsne r1, msp /* R1=The main stack pointer */
mrseq r1, psp /* R1=The process stack pointer */
#else
mrs r1, msp /* R1=The main stack pointer */
#endif
mov r2, r1 /* R2=Copy of the main/process stack pointer */
add r2, #HW_XCPT_SIZE /* R2=MSP/PSP before the interrupt was taken */
mrs r3, primask /* R3=Current PRIMASK setting */
#ifdef CONFIG_NUTTX_KERNEL
stmdb r1!, {r2-r11,r14} /* Save the remaining registers plus the SP value */
#else
stmdb r1!, {r2-r11} /* Save the remaining registers plus the SP value */
#endif
/* Disable interrupts, select the stack to use for interrupt handling
* and call up_doirq to handle the interrupt
*/
cpsid i /* Disable further interrupts */
/* If CONFIG_ARCH_INTERRUPTSTACK is defined, we will use a special interrupt
* stack pointer. The way that this is done here prohibits nested interrupts!
* Otherwise, we will re-use the main stack for interrupt level processing.
*/
#if CONFIG_ARCH_INTERRUPTSTACK > 3
ldr sp, =g_intstackbase
str r1, [sp, #-4]! /* Save the MSP on the interrupt stack */
bl up_doirq /* R0=IRQ, R1=register save (msp) */
ldr r1, [sp, #+4]! /* Recover R1=main stack pointer */
#else
mov sp, r1 /* We are using the main stack pointer */
bl up_doirq /* R0=IRQ, R1=register save (msp) */
mov r1, sp /* Recover R1=main stack pointer */
#endif
/* On return from up_doirq, R0 will hold a pointer to register context
* array to use for the interrupt return. If that return value is the same
* as current stack pointer, then things are relatively easy.
*/
cmp r0, r1 /* Context switch? */
beq 1f /* Branch if no context switch */
/* We are returning with a pending context switch. This case is different
* because in this case, the register save structure does not lie on the
* stack but, rather, are within a TCB structure. We'll have to copy some
* values to the stack.
*/
add r1, r0, #SW_XCPT_SIZE /* R1=Address of HW save area in reg array */
ldmia r1, {r4-r11} /* Fetch eight registers in HW save area */
ldr r1, [r0, #(4*REG_SP)] /* R1=Value of SP before interrupt */
stmdb r1!, {r4-r11} /* Store eight registers in HW save area */
#ifdef CONFIG_NUTTX_KERNEL
ldmia r0, {r2-r11,r14} /* Recover R4-R11, r14 + 2 temp values */
#else
ldmia r0, {r2-r11} /* Recover R4-R11 + 2 temp values */
#endif
b 2f /* Re-join common logic */
/* We are returning with no context switch. We simply need to "unwind"
* the same stack frame that we created
*/
1:
#ifdef CONFIG_NUTTX_KERNEL
ldmia r1!, {r2-r11,r14} /* Recover R4-R11, r14 + 2 temp values */
#else
ldmia r1!, {r2-r11} /* Recover R4-R11 + 2 temp values */
#endif
2:
#ifdef CONFIG_NUTTX_KERNEL
/* The EXC_RETURN value will be 0xfffffff9 (privileged thread) or 0xfffffff1
* (handler mode) if the state is on the MSP. It can only be on the PSP if
* EXC_RETURN is 0xfffffffd (unprivileged thread)
*/
adds r0, r14, #3 /* If R14=0xfffffffd, then r0 == 0 */
ite ne /* Next two instructions are condition */
msrne msp, r1 /* R1=The main stack pointer */
msreq psp, r1 /* R1=The process stack pointer */
#else
msr msp, r1 /* Recover the return MSP value */
/* Preload r14 with the special return value first (so that the return
* actually occurs with interrupts still disabled).
*/
ldr r14, =EXC_RETURN /* Load the special value */
#endif
/* Restore the interrupt state */
msr primask, r3 /* Restore interrupts */
/* Always return with R14 containing the special value that will: (1)
* return to thread mode, and (2) continue to use the MSP
*/
bx r14 /* And return */
.size handlers, .-handlers
/************************************************************************************
* Name: up_interruptstack/g_intstackbase
*
* Description:
* Shouldn't happen
*
************************************************************************************/
#if CONFIG_ARCH_INTERRUPTSTACK > 3
.bss
.global g_intstackbase
.align 4
up_interruptstack:
.skip (CONFIG_ARCH_INTERRUPTSTACK & ~3)
g_intstackbase:
.size up_interruptstack, .-up_interruptstack
#endif
/************************************************************************************
* .rodata
************************************************************************************/
.section .rodata, "a"
/* Variables: _sbss is the start of the BSS region (see ld.script) _ebss is the end
* of the BSS regsion (see ld.script). The idle task stack starts at the end of BSS
* and is of size CONFIG_IDLETHREAD_STACKSIZE. The IDLE thread is the thread that
* the system boots on and, eventually, becomes the idle, do nothing task that runs
* only when there is nothing else to run. The heap continues from there until the
* end of memory. See g_heapbase below.
*/
.globl g_heapbase
.type g_heapbase, object
g_heapbase:
.long _ebss+CONFIG_IDLETHREAD_STACKSIZE
.size g_heapbase, .-g_heapbase
.end

View File

@ -334,15 +334,15 @@ Eagle100-specific Configuration Options
Additional interrupt support can be disabled if desired to reduce memory
footprint.
CONFIG_LM3S_DISABLE_GPIOA_IRQS=n
CONFIG_LM3S_DISABLE_GPIOB_IRQS=n
CONFIG_LM3S_DISABLE_GPIOC_IRQS=n
CONFIG_LM3S_DISABLE_GPIOD_IRQS=n
CONFIG_LM3S_DISABLE_GPIOE_IRQS=n
CONFIG_LM3S_DISABLE_GPIOF_IRQS=n
CONFIG_LM3S_DISABLE_GPIOG_IRQS=n
CONFIG_LM3S_DISABLE_GPIOH_IRQS=y
CONFIG_LM3S_DISABLE_GPIOJ_IRQS=y
CONFIG_LM_DISABLE_GPIOA_IRQS=n
CONFIG_LM_DISABLE_GPIOB_IRQS=n
CONFIG_LM_DISABLE_GPIOC_IRQS=n
CONFIG_LM_DISABLE_GPIOD_IRQS=n
CONFIG_LM_DISABLE_GPIOE_IRQS=n
CONFIG_LM_DISABLE_GPIOF_IRQS=n
CONFIG_LM_DISABLE_GPIOG_IRQS=n
CONFIG_LM_DISABLE_GPIOH_IRQS=y
CONFIG_LM_DISABLE_GPIOJ_IRQS=y
LM3S6818 specific device driver settings
@ -367,18 +367,18 @@ Eagle100-specific Configuration Options
value is large, then larger values of this setting may cause
Rx FIFO overrun errors. Default: half of the Tx FIFO size (4).
CONFIG_LM3S_ETHERNET - This must be set (along with CONFIG_NET)
CONFIG_LM_ETHERNET - This must be set (along with CONFIG_NET)
to build the LM3S Ethernet driver
CONFIG_LM3S_ETHLEDS - Enable to use Ethernet LEDs on the board.
CONFIG_LM3S_BOARDMAC - If the board-specific logic can provide
CONFIG_LM_ETHLEDS - Enable to use Ethernet LEDs on the board.
CONFIG_LM_BOARDMAC - If the board-specific logic can provide
a MAC address (via lm_ethernetmac()), then this should be selected.
CONFIG_LM3S_ETHHDUPLEX - Set to force half duplex operation
CONFIG_LM3S_ETHNOAUTOCRC - Set to suppress auto-CRC generation
CONFIG_LM3S_ETHNOPAD - Set to suppress Tx padding
CONFIG_LM3S_MULTICAST - Set to enable multicast frames
CONFIG_LM3S_PROMISCUOUS - Set to enable promiscuous mode
CONFIG_LM3S_BADCRC - Set to enable bad CRC rejection.
CONFIG_LM3S_DUMPPACKET - Dump each packet received/sent to the console.
CONFIG_LM_ETHHDUPLEX - Set to force half duplex operation
CONFIG_LM_ETHNOAUTOCRC - Set to suppress auto-CRC generation
CONFIG_LM_ETHNOPAD - Set to suppress Tx padding
CONFIG_LM_MULTICAST - Set to enable multicast frames
CONFIG_LM_PROMISCUOUS - Set to enable promiscuous mode
CONFIG_LM_BADCRC - Set to enable bad CRC rejection.
CONFIG_LM_DUMPPACKET - Dump each packet received/sent to the console.
Configurations
^^^^^^^^^^^^^^

View File

@ -58,21 +58,21 @@ CONFIG_ARCH_CALIBRATION=n
# Disable support for interrupts on GPIOJ which does not
# exist on the LM3S6918. Additional interrupt support can be
# disabled if desired to reduce memory footprint.
CONFIG_LM3S_DISABLE_GPIOA_IRQS=n
CONFIG_LM3S_DISABLE_GPIOB_IRQS=n
CONFIG_LM3S_DISABLE_GPIOC_IRQS=n
CONFIG_LM3S_DISABLE_GPIOD_IRQS=n
CONFIG_LM3S_DISABLE_GPIOE_IRQS=n
CONFIG_LM3S_DISABLE_GPIOF_IRQS=n
CONFIG_LM3S_DISABLE_GPIOG_IRQS=n
CONFIG_LM3S_DISABLE_GPIOH_IRQS=n
CONFIG_LM3S_DISABLE_GPIOJ_IRQS=y
CONFIG_LM_DISABLE_GPIOA_IRQS=n
CONFIG_LM_DISABLE_GPIOB_IRQS=n
CONFIG_LM_DISABLE_GPIOC_IRQS=n
CONFIG_LM_DISABLE_GPIOD_IRQS=n
CONFIG_LM_DISABLE_GPIOE_IRQS=n
CONFIG_LM_DISABLE_GPIOF_IRQS=n
CONFIG_LM_DISABLE_GPIOG_IRQS=n
CONFIG_LM_DISABLE_GPIOH_IRQS=n
CONFIG_LM_DISABLE_GPIOJ_IRQS=y
#
# LM3S6918 specific serial device driver settings
#
CONFIG_LM3S_UART0=y
CONFIG_LM3S_UART1=n
CONFIG_LM_UART0=y
CONFIG_LM_UART1=n
CONFIG_UART0_SERIAL_CONSOLE=y
CONFIG_UART1_SERIAL_CONSOLE=n
CONFIG_UART0_TXBUFSIZE=256
@ -99,16 +99,16 @@ CONFIG_SSI_POLLWAIT=y
#
# LM3S6918 specific serial device driver settings
#
CONFIG_LM3S_ETHERNET=y
CONFIG_LM3S_ETHLEDS=n
CONFIG_LM3S_BOARDMAC=y
CONFIG_LM3S_ETHHDUPLEX=n
CONFIG_LM3S_ETHNOAUTOCRC=n
CONFIG_LM3S_ETHNOPAD=n
CONFIG_LM3S_MULTICAST=n
CONFIG_LM3S_PROMISCUOUS=n
CONFIG_LM3S_BADCRC=n
CONFIG_LM3S_DUMPPACKET=n
CONFIG_LM_ETHERNET=y
CONFIG_LM_ETHLEDS=n
CONFIG_LM_BOARDMAC=y
CONFIG_LM_ETHHDUPLEX=n
CONFIG_LM_ETHNOAUTOCRC=n
CONFIG_LM_ETHNOPAD=n
CONFIG_LM_MULTICAST=n
CONFIG_LM_PROMISCUOUS=n
CONFIG_LM_BADCRC=n
CONFIG_LM_DUMPPACKET=n
#
# General build options

View File

@ -112,7 +112,7 @@
#ifndef __ASSEMBLY__
/************************************************************************************
* Name: lm3s_boardinitialize
* Name: lm_boardinitialize
*
* Description:
* All LM3S architectures must provide the following entry point. This entry point
@ -121,21 +121,21 @@
*
************************************************************************************/
extern void lm3s_boardinitialize(void);
extern void lm_boardinitialize(void);
/************************************************************************************
* Name: lm3s_ethernetmac
* Name: lm_ethernetmac
*
* Description:
* For the Ethernet Eval Kits, the MAC address will be stored in the non-volatile
* USER0 and USER1 registers. If CONFIG_LM3S_BOARDMAC is defined, this function
* USER0 and USER1 registers. If CONFIG_LM_BOARDMAC is defined, this function
* will obtain the MAC address from these registers.
*
************************************************************************************/
#ifdef CONFIG_LM3S_BOARDMAC
#ifdef CONFIG_LM_BOARDMAC
struct ether_addr;
extern void lm3s_ethernetmac(struct ether_addr *ethaddr);
extern void lm_ethernetmac(struct ether_addr *ethaddr);
#endif
#endif /* __ASSEMBLY__ */

View File

@ -58,21 +58,21 @@ CONFIG_ARCH_CALIBRATION=n
# Disable support for interrupts on GPIOJ which does not
# exist on the LM3S6918. Additional interrupt support can be
# disabled if desired to reduce memory footprint.
CONFIG_LM3S_DISABLE_GPIOA_IRQS=n
CONFIG_LM3S_DISABLE_GPIOB_IRQS=n
CONFIG_LM3S_DISABLE_GPIOC_IRQS=n
CONFIG_LM3S_DISABLE_GPIOD_IRQS=n
CONFIG_LM3S_DISABLE_GPIOE_IRQS=n
CONFIG_LM3S_DISABLE_GPIOF_IRQS=n
CONFIG_LM3S_DISABLE_GPIOG_IRQS=n
CONFIG_LM3S_DISABLE_GPIOH_IRQS=n
CONFIG_LM3S_DISABLE_GPIOJ_IRQS=y
CONFIG_LM_DISABLE_GPIOA_IRQS=n
CONFIG_LM_DISABLE_GPIOB_IRQS=n
CONFIG_LM_DISABLE_GPIOC_IRQS=n
CONFIG_LM_DISABLE_GPIOD_IRQS=n
CONFIG_LM_DISABLE_GPIOE_IRQS=n
CONFIG_LM_DISABLE_GPIOF_IRQS=n
CONFIG_LM_DISABLE_GPIOG_IRQS=n
CONFIG_LM_DISABLE_GPIOH_IRQS=n
CONFIG_LM_DISABLE_GPIOJ_IRQS=y
#
# LM3S6918 specific serial device driver settings
#
CONFIG_LM3S_UART0=y
CONFIG_LM3S_UART1=n
CONFIG_LM_UART0=y
CONFIG_LM_UART1=n
CONFIG_UART0_SERIAL_CONSOLE=y
CONFIG_UART1_SERIAL_CONSOLE=n
CONFIG_UART0_TXBUFSIZE=256
@ -99,16 +99,16 @@ CONFIG_SSI_POLLWAIT=y
#
# LM3S6918 specific serial device driver settings
#
CONFIG_LM3S_ETHERNET=y
CONFIG_LM3S_ETHLEDS=n
CONFIG_LM3S_BOARDMAC=y
CONFIG_LM3S_ETHHDUPLEX=n
CONFIG_LM3S_ETHNOAUTOCRC=n
CONFIG_LM3S_ETHNOPAD=n
CONFIG_LM3S_MULTICAST=n
CONFIG_LM3S_PROMISCUOUS=n
CONFIG_LM3S_BADCRC=n
CONFIG_LM3S_DUMPPACKET=n
CONFIG_LM_ETHERNET=y
CONFIG_LM_ETHLEDS=n
CONFIG_LM_BOARDMAC=y
CONFIG_LM_ETHHDUPLEX=n
CONFIG_LM_ETHNOAUTOCRC=n
CONFIG_LM_ETHNOPAD=n
CONFIG_LM_MULTICAST=n
CONFIG_LM_PROMISCUOUS=n
CONFIG_LM_BADCRC=n
CONFIG_LM_DUMPPACKET=n
#
# General build options

View File

@ -58,21 +58,21 @@ CONFIG_ARCH_CALIBRATION=n
# Disable support for interrupts on GPIOJ which does not
# exist on the LM3S6918. Additional interrupt support can be
# disabled if desired to reduce memory footprint.
CONFIG_LM3S_DISABLE_GPIOA_IRQS=n
CONFIG_LM3S_DISABLE_GPIOB_IRQS=n
CONFIG_LM3S_DISABLE_GPIOC_IRQS=n
CONFIG_LM3S_DISABLE_GPIOD_IRQS=n
CONFIG_LM3S_DISABLE_GPIOE_IRQS=n
CONFIG_LM3S_DISABLE_GPIOF_IRQS=n
CONFIG_LM3S_DISABLE_GPIOG_IRQS=n
CONFIG_LM3S_DISABLE_GPIOH_IRQS=n
CONFIG_LM3S_DISABLE_GPIOJ_IRQS=y
CONFIG_LM_DISABLE_GPIOA_IRQS=n
CONFIG_LM_DISABLE_GPIOB_IRQS=n
CONFIG_LM_DISABLE_GPIOC_IRQS=n
CONFIG_LM_DISABLE_GPIOD_IRQS=n
CONFIG_LM_DISABLE_GPIOE_IRQS=n
CONFIG_LM_DISABLE_GPIOF_IRQS=n
CONFIG_LM_DISABLE_GPIOG_IRQS=n
CONFIG_LM_DISABLE_GPIOH_IRQS=n
CONFIG_LM_DISABLE_GPIOJ_IRQS=y
#
# LM3S6918 specific serial device driver settings
#
CONFIG_LM3S_UART0=y
CONFIG_LM3S_UART1=n
CONFIG_LM_UART0=y
CONFIG_LM_UART1=n
CONFIG_UART0_SERIAL_CONSOLE=y
CONFIG_UART1_SERIAL_CONSOLE=n
CONFIG_UART0_TXBUFSIZE=256
@ -99,16 +99,16 @@ CONFIG_SSI_POLLWAIT=y
#
# LM3S6918 specific serial device driver settings
#
CONFIG_LM3S_ETHERNET=y
CONFIG_LM3S_ETHLEDS=n
CONFIG_LM3S_BOARDMAC=y
CONFIG_LM3S_ETHHDUPLEX=n
CONFIG_LM3S_ETHNOAUTOCRC=n
CONFIG_LM3S_ETHNOPAD=n
CONFIG_LM3S_MULTICAST=n
CONFIG_LM3S_PROMISCUOUS=n
CONFIG_LM3S_BADCRC=n
CONFIG_LM3S_DUMPPACKET=n
CONFIG_LM_ETHERNET=y
CONFIG_LM_ETHLEDS=n
CONFIG_LM_BOARDMAC=y
CONFIG_LM_ETHHDUPLEX=n
CONFIG_LM_ETHNOAUTOCRC=n
CONFIG_LM_ETHNOPAD=n
CONFIG_LM_MULTICAST=n
CONFIG_LM_PROMISCUOUS=n
CONFIG_LM_BADCRC=n
CONFIG_LM_DUMPPACKET=n
#
# General build options

View File

@ -58,21 +58,21 @@ CONFIG_ARCH_CALIBRATION=n
# Disable support for interrupts on GPIOJ which does not
# exist on the LM3S6918. Additional interrupt support can be
# disabled if desired to reduce memory footprint.
CONFIG_LM3S_DISABLE_GPIOA_IRQS=n
CONFIG_LM3S_DISABLE_GPIOB_IRQS=n
CONFIG_LM3S_DISABLE_GPIOC_IRQS=n
CONFIG_LM3S_DISABLE_GPIOD_IRQS=n
CONFIG_LM3S_DISABLE_GPIOE_IRQS=n
CONFIG_LM3S_DISABLE_GPIOF_IRQS=n
CONFIG_LM3S_DISABLE_GPIOG_IRQS=n
CONFIG_LM3S_DISABLE_GPIOH_IRQS=n
CONFIG_LM3S_DISABLE_GPIOJ_IRQS=y
CONFIG_LM_DISABLE_GPIOA_IRQS=n
CONFIG_LM_DISABLE_GPIOB_IRQS=n
CONFIG_LM_DISABLE_GPIOC_IRQS=n
CONFIG_LM_DISABLE_GPIOD_IRQS=n
CONFIG_LM_DISABLE_GPIOE_IRQS=n
CONFIG_LM_DISABLE_GPIOF_IRQS=n
CONFIG_LM_DISABLE_GPIOG_IRQS=n
CONFIG_LM_DISABLE_GPIOH_IRQS=n
CONFIG_LM_DISABLE_GPIOJ_IRQS=y
#
# LM3S6918 specific serial device driver settings
#
CONFIG_LM3S_UART0=y
CONFIG_LM3S_UART1=n
CONFIG_LM_UART0=y
CONFIG_LM_UART1=n
CONFIG_UART0_SERIAL_CONSOLE=y
CONFIG_UART1_SERIAL_CONSOLE=n
CONFIG_UART0_TXBUFSIZE=256
@ -99,16 +99,16 @@ CONFIG_SSI_POLLWAIT=y
#
# LM3S6918 specific serial device driver settings
#
CONFIG_LM3S_ETHERNET=n
CONFIG_LM3S_ETHLEDS=n
CONFIG_LM3S_BOARDMAC=y
CONFIG_LM3S_ETHHDUPLEX=n
CONFIG_LM3S_ETHNOAUTOCRC=n
CONFIG_LM3S_ETHNOPAD=n
CONFIG_LM3S_MULTICAST=n
CONFIG_LM3S_PROMISCUOUS=n
CONFIG_LM3S_BADCRC=n
CONFIG_LM3S_DUMPPACKET=n
CONFIG_LM_ETHERNET=n
CONFIG_LM_ETHLEDS=n
CONFIG_LM_BOARDMAC=y
CONFIG_LM_ETHHDUPLEX=n
CONFIG_LM_ETHNOAUTOCRC=n
CONFIG_LM_ETHNOPAD=n
CONFIG_LM_MULTICAST=n
CONFIG_LM_PROMISCUOUS=n
CONFIG_LM_BADCRC=n
CONFIG_LM_DUMPPACKET=n
#
# General build options

View File

@ -58,21 +58,21 @@ CONFIG_ARCH_CALIBRATION=n
# Disable support for interrupts on GPIOJ which does not
# exist on the LM3S6918. Additional interrupt support can be
# disabled if desired to reduce memory footprint.
CONFIG_LM3S_DISABLE_GPIOA_IRQS=n
CONFIG_LM3S_DISABLE_GPIOB_IRQS=n
CONFIG_LM3S_DISABLE_GPIOC_IRQS=n
CONFIG_LM3S_DISABLE_GPIOD_IRQS=n
CONFIG_LM3S_DISABLE_GPIOE_IRQS=n
CONFIG_LM3S_DISABLE_GPIOF_IRQS=n
CONFIG_LM3S_DISABLE_GPIOG_IRQS=n
CONFIG_LM3S_DISABLE_GPIOH_IRQS=n
CONFIG_LM3S_DISABLE_GPIOJ_IRQS=y
CONFIG_LM_DISABLE_GPIOA_IRQS=n
CONFIG_LM_DISABLE_GPIOB_IRQS=n
CONFIG_LM_DISABLE_GPIOC_IRQS=n
CONFIG_LM_DISABLE_GPIOD_IRQS=n
CONFIG_LM_DISABLE_GPIOE_IRQS=n
CONFIG_LM_DISABLE_GPIOF_IRQS=n
CONFIG_LM_DISABLE_GPIOG_IRQS=n
CONFIG_LM_DISABLE_GPIOH_IRQS=n
CONFIG_LM_DISABLE_GPIOJ_IRQS=y
#
# LM3S6918 specific serial device driver settings
#
CONFIG_LM3S_UART0=y
CONFIG_LM3S_UART1=n
CONFIG_LM_UART0=y
CONFIG_LM_UART1=n
CONFIG_UART0_SERIAL_CONSOLE=y
CONFIG_UART1_SERIAL_CONSOLE=n
CONFIG_UART0_TXBUFSIZE=256
@ -99,16 +99,16 @@ CONFIG_SSI_POLLWAIT=y
#
# LM3S6918 specific serial device driver settings
#
CONFIG_LM3S_ETHERNET=n
CONFIG_LM3S_ETHLEDS=n
CONFIG_LM3S_BOARDMAC=y
CONFIG_LM3S_ETHHDUPLEX=n
CONFIG_LM3S_ETHNOAUTOCRC=n
CONFIG_LM3S_ETHNOPAD=n
CONFIG_LM3S_MULTICAST=n
CONFIG_LM3S_PROMISCUOUS=n
CONFIG_LM3S_BADCRC=n
CONFIG_LM3S_DUMPPACKET=n
CONFIG_LM_ETHERNET=n
CONFIG_LM_ETHLEDS=n
CONFIG_LM_BOARDMAC=y
CONFIG_LM_ETHHDUPLEX=n
CONFIG_LM_ETHNOAUTOCRC=n
CONFIG_LM_ETHNOPAD=n
CONFIG_LM_MULTICAST=n
CONFIG_LM_PROMISCUOUS=n
CONFIG_LM_BADCRC=n
CONFIG_LM_DUMPPACKET=n
#
# General build options

View File

@ -81,14 +81,14 @@
#ifndef __ASSEMBLY__
/************************************************************************************
* Name: lm3s_ssiinitialize
* Name: lm_ssiinitialize
*
* Description:
* Called to configure SPI chip select GPIO pins for the Eagle100 board.
*
************************************************************************************/
extern void weak_function lm3s_ssiinitialize(void);
extern void weak_function lm_ssiinitialize(void);
/****************************************************************************
* Name: up_ledinit

View File

@ -60,7 +60,7 @@
************************************************************************************/
/************************************************************************************
* Name: lm3s_boardinitialize
* Name: lm_boardinitialize
*
* Description:
* All LM3S architectures must provide the following entry point. This entry point
@ -68,18 +68,18 @@
* and mapped but before any devices have been initialized.
************************************************************************************/
void lm3s_boardinitialize(void)
void lm_boardinitialize(void)
{
/* Configure SPI chip selects if 1) SSI is not disabled, and 2) the weak function
* lm3s_ssiinitialize() has been brought into the link.
* lm_ssiinitialize() has been brought into the link.
*/
/* The Eagle100 microSD CS is on SSI0 */
#if !defined(CONFIG_SSI0_DISABLE) /* || !defined(CONFIG_SSI1_DISABLE) */
if (lm3s_ssiinitialize)
if (lm_ssiinitialize)
{
lm3s_ssiinitialize();
lm_ssiinitialize();
}
#endif

View File

@ -63,17 +63,17 @@
************************************************************************************/
/************************************************************************************
* Name: lm3s_ethernetmac
* Name: lm_ethernetmac
*
* Description:
* For the Ethernet Eval Kits, the MAC address will be stored in the non-volatile
* USER0 and USER1 registers. If CONFIG_LM3S_BOARDMAC is defined, this function
* USER0 and USER1 registers. If CONFIG_LM_BOARDMAC is defined, this function
* will obtain the MAC address from these registers.
*
************************************************************************************/
#ifdef CONFIG_LM3S_BOARDMAC
void lm3s_ethernetmac(struct ether_addr *ethaddr)
#ifdef CONFIG_LM_BOARDMAC
void lm_ethernetmac(struct ether_addr *ethaddr)
{
uint32_t user0;
uint32_t user1;

View File

@ -72,7 +72,7 @@
/* Dump GPIO registers */
#ifdef LED_DEBUG
# define led_dumpgpio(m) lm3s_dumpgpio(LED_GPIO, m)
# define led_dumpgpio(m) lm_dumpgpio(LED_GPIO, m)
#else
# define led_dumpgpio(m)
#endif
@ -106,9 +106,9 @@ void up_ledinit(void)
/* Configure Port E, Bit 1 as an output, initial value=OFF */
led_dumpgpio("up_ledinit before lm3s_configgpio()");
lm3s_configgpio(LED_GPIO);
led_dumpgpio("up_ledinit after lm3s_configgpio()");
led_dumpgpio("up_ledinit before lm_configgpio()");
lm_configgpio(LED_GPIO);
led_dumpgpio("up_ledinit after lm_configgpio()");
g_nest = 0;
}
@ -132,9 +132,9 @@ void up_ledon(int led)
g_nest++;
case LED_IRQSENABLED:
case LED_STACKCREATED:
led_dumpgpio("up_ledon: before lm3s_gpiowrite()");
lm3s_gpiowrite(LED_GPIO, false);
led_dumpgpio("up_ledon: after lm3s_gpiowrite()");
led_dumpgpio("up_ledon: before lm_gpiowrite()");
lm_gpiowrite(LED_GPIO, false);
led_dumpgpio("up_ledon: after lm_gpiowrite()");
break;
}
}
@ -160,9 +160,9 @@ void up_ledoff(int led)
case LED_PANIC:
if (--g_nest <= 0)
{
led_dumpgpio("up_ledoff: before lm3s_gpiowrite()");
lm3s_gpiowrite(LED_GPIO, true);
led_dumpgpio("up_ledoff: after lm3s_gpiowrite()");
led_dumpgpio("up_ledoff: before lm_gpiowrite()");
lm_gpiowrite(LED_GPIO, true);
led_dumpgpio("up_ledoff: after lm_gpiowrite()");
}
break;
}

View File

@ -81,7 +81,7 @@
/* Dump GPIO registers */
#ifdef SSI_VERBOSE
# define ssi_dumpgpio(m) lm3s_dumpgpio(SDCCS_GPIO, m)
# define ssi_dumpgpio(m) lm_dumpgpio(SDCCS_GPIO, m)
#else
# define ssi_dumpgpio(m)
#endif
@ -95,30 +95,30 @@
************************************************************************************/
/************************************************************************************
* Name: lm3s_ssiinitialize
* Name: lm_ssiinitialize
*
* Description:
* Called to configure SPI chip select GPIO pins for the Eagle100 board.
*
************************************************************************************/
void weak_function lm3s_ssiinitialize(void)
void weak_function lm_ssiinitialize(void)
{
/* Configure the SPI-based microSD CS GPIO */
ssi_dumpgpio("lm3s_ssiinitialize() before lm3s_configgpio()");
lm3s_configgpio(SDCCS_GPIO);
ssi_dumpgpio("lm3s_ssiinitialize() after lm3s_configgpio()");
ssi_dumpgpio("lm_ssiinitialize() before lm_configgpio()");
lm_configgpio(SDCCS_GPIO);
ssi_dumpgpio("lm_ssiinitialize() after lm_configgpio()");
}
/****************************************************************************
* The external functions, lm3s_spiselect and lm3s_spistatus must be provided
* The external functions, lm_spiselect and lm_spistatus must be provided
* by board-specific logic. The are implementations of the select and status
* methods SPI interface defined by struct spi_ops_s (see include/nuttx/spi.h).
* All othermethods (including up_spiinitialize()) are provided by common
* logic. To use this common SPI logic on your board:
*
* 1. Provide lm3s_spiselect() and lm3s_spistatus() functions in your
* 1. Provide lm_spiselect() and lm_spistatus() functions in your
* board-specific logic. This function will perform chip selection and
* status operations using GPIOs in the way your board is configured.
* 2. Add a call to up_spiinitialize() in your low level initialization
@ -130,20 +130,20 @@ void weak_function lm3s_ssiinitialize(void)
*
****************************************************************************/
void lm3s_spiselect(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected)
void lm_spiselect(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected)
{
ssidbg("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert");
if (devid == SPIDEV_MMCSD)
{
/* Assert the CS pin to the card */
ssi_dumpgpio("lm3s_spiselect() before lm3s_gpiowrite()");
lm3s_gpiowrite(SDCCS_GPIO, !selected);
ssi_dumpgpio("lm3s_spiselect() after lm3s_gpiowrite()");
ssi_dumpgpio("lm_spiselect() before lm_gpiowrite()");
lm_gpiowrite(SDCCS_GPIO, !selected);
ssi_dumpgpio("lm_spiselect() after lm_gpiowrite()");
}
}
uint8_t lm3s_spistatus(FAR struct spi_dev_s *dev, enum spi_dev_e devid)
uint8_t lm_spistatus(FAR struct spi_dev_s *dev, enum spi_dev_e devid)
{
ssidbg("Returning SPI_STATUS_PRESENT\n");
return SPI_STATUS_PRESENT;

View File

@ -58,21 +58,21 @@ CONFIG_ARCH_CALIBRATION=n
# Disable support for interrupts on GPIOJ which does not
# exist on the LM3S6918. Additional interrupt support can be
# disabled if desired to reduce memory footprint.
CONFIG_LM3S_DISABLE_GPIOA_IRQS=n
CONFIG_LM3S_DISABLE_GPIOB_IRQS=n
CONFIG_LM3S_DISABLE_GPIOC_IRQS=n
CONFIG_LM3S_DISABLE_GPIOD_IRQS=n
CONFIG_LM3S_DISABLE_GPIOE_IRQS=n
CONFIG_LM3S_DISABLE_GPIOF_IRQS=n
CONFIG_LM3S_DISABLE_GPIOG_IRQS=n
CONFIG_LM3S_DISABLE_GPIOH_IRQS=n
CONFIG_LM3S_DISABLE_GPIOJ_IRQS=y
CONFIG_LM_DISABLE_GPIOA_IRQS=n
CONFIG_LM_DISABLE_GPIOB_IRQS=n
CONFIG_LM_DISABLE_GPIOC_IRQS=n
CONFIG_LM_DISABLE_GPIOD_IRQS=n
CONFIG_LM_DISABLE_GPIOE_IRQS=n
CONFIG_LM_DISABLE_GPIOF_IRQS=n
CONFIG_LM_DISABLE_GPIOG_IRQS=n
CONFIG_LM_DISABLE_GPIOH_IRQS=n
CONFIG_LM_DISABLE_GPIOJ_IRQS=y
#
# LM3S6918 specific serial device driver settings
#
CONFIG_LM3S_UART0=y
CONFIG_LM3S_UART1=n
CONFIG_LM_UART0=y
CONFIG_LM_UART1=n
CONFIG_UART0_SERIAL_CONSOLE=y
CONFIG_UART1_SERIAL_CONSOLE=n
CONFIG_UART0_TXBUFSIZE=256
@ -99,16 +99,16 @@ CONFIG_SSI_POLLWAIT=y
#
# LM3S6918 specific serial device driver settings
#
CONFIG_LM3S_ETHERNET=y
CONFIG_LM3S_ETHLEDS=n
CONFIG_LM3S_BOARDMAC=y
CONFIG_LM3S_ETHHDUPLEX=n
CONFIG_LM3S_ETHNOAUTOCRC=n
CONFIG_LM3S_ETHNOPAD=n
CONFIG_LM3S_MULTICAST=n
CONFIG_LM3S_PROMISCUOUS=n
CONFIG_LM3S_BADCRC=n
CONFIG_LM3S_DUMPPACKET=n
CONFIG_LM_ETHERNET=y
CONFIG_LM_ETHLEDS=n
CONFIG_LM_BOARDMAC=y
CONFIG_LM_ETHHDUPLEX=n
CONFIG_LM_ETHNOAUTOCRC=n
CONFIG_LM_ETHNOPAD=n
CONFIG_LM_MULTICAST=n
CONFIG_LM_PROMISCUOUS=n
CONFIG_LM_BADCRC=n
CONFIG_LM_DUMPPACKET=n
#
# General build options

View File

@ -102,12 +102,12 @@ GNU Toolchain Options
the CodeSourcery or devkitARM, you simply need to add one of the following
configuration options to your .config (or defconfig) file:
CONFIG_LM3S_CODESOURCERYW=y : CodeSourcery under Windows
CONFIG_LM3S_CODESOURCERYL=y : CodeSourcery under Linux
CONFIG_LM3S_DEVKITARM=y : devkitARM under Windows
CONFIG_LM3S_BUILDROOT=y : NuttX buildroot under Linux or Cygwin (default)
CONFIG_LM_CODESOURCERYW=y : CodeSourcery under Windows
CONFIG_LM_CODESOURCERYL=y : CodeSourcery under Linux
CONFIG_LM_DEVKITARM=y : devkitARM under Windows
CONFIG_LM_BUILDROOT=y : NuttX buildroot under Linux or Cygwin (default)
If you are not using CONFIG_LM3S_BUILDROOT, then you may also have to modify
If you are not using CONFIG_LM_BUILDROOT, then you may also have to modify
the PATH in the setenv.h file if your make cannot find the tools.
NOTE: the CodeSourcery (for Windows) and devkitARM are Windows native toolchains.
@ -352,15 +352,15 @@ Stellaris EKK-LM3S9B96 Evaluation Kit Configuration Options
Additional interrupt support can be disabled if desired to reduce memory
footprint.
CONFIG_LM3S_DISABLE_GPIOA_IRQS=n
CONFIG_LM3S_DISABLE_GPIOB_IRQS=n
CONFIG_LM3S_DISABLE_GPIOC_IRQS=n
CONFIG_LM3S_DISABLE_GPIOD_IRQS=n
CONFIG_LM3S_DISABLE_GPIOE_IRQS=n
CONFIG_LM3S_DISABLE_GPIOF_IRQS=n
CONFIG_LM3S_DISABLE_GPIOG_IRQS=n
CONFIG_LM3S_DISABLE_GPIOH_IRQS=n
CONFIG_LM3S_DISABLE_GPIOJ_IRQS=y
CONFIG_LM_DISABLE_GPIOA_IRQS=n
CONFIG_LM_DISABLE_GPIOB_IRQS=n
CONFIG_LM_DISABLE_GPIOC_IRQS=n
CONFIG_LM_DISABLE_GPIOD_IRQS=n
CONFIG_LM_DISABLE_GPIOE_IRQS=n
CONFIG_LM_DISABLE_GPIOF_IRQS=n
CONFIG_LM_DISABLE_GPIOG_IRQS=n
CONFIG_LM_DISABLE_GPIOH_IRQS=n
CONFIG_LM_DISABLE_GPIOJ_IRQS=y
LM3S6818 specific device driver settings
@ -385,18 +385,18 @@ Stellaris EKK-LM3S9B96 Evaluation Kit Configuration Options
value is large, then larger values of this setting may cause
Rx FIFO overrun errors. Default: half of the Tx FIFO size (4).
CONFIG_LM3S_ETHERNET - This must be set (along with CONFIG_NET)
CONFIG_LM_ETHERNET - This must be set (along with CONFIG_NET)
to build the LM3S Ethernet driver
CONFIG_LM3S_ETHLEDS - Enable to use Ethernet LEDs on the board.
CONFIG_LM3S_BOARDMAC - If the board-specific logic can provide
CONFIG_LM_ETHLEDS - Enable to use Ethernet LEDs on the board.
CONFIG_LM_BOARDMAC - If the board-specific logic can provide
a MAC address (via lm_ethernetmac()), then this should be selected.
CONFIG_LM3S_ETHHDUPLEX - Set to force half duplex operation
CONFIG_LM3S_ETHNOAUTOCRC - Set to suppress auto-CRC generation
CONFIG_LM3S_ETHNOPAD - Set to suppress Tx padding
CONFIG_LM3S_MULTICAST - Set to enable multicast frames
CONFIG_LM3S_PROMISCUOUS - Set to enable promiscuous mode
CONFIG_LM3S_BADCRC - Set to enable bad CRC rejection.
CONFIG_LM3S_DUMPPACKET - Dump each packet received/sent to the console.
CONFIG_LM_ETHHDUPLEX - Set to force half duplex operation
CONFIG_LM_ETHNOAUTOCRC - Set to suppress auto-CRC generation
CONFIG_LM_ETHNOPAD - Set to suppress Tx padding
CONFIG_LM_MULTICAST - Set to enable multicast frames
CONFIG_LM_PROMISCUOUS - Set to enable promiscuous mode
CONFIG_LM_BADCRC - Set to enable bad CRC rejection.
CONFIG_LM_DUMPPACKET - Dump each packet received/sent to the console.
Configurations
^^^^^^^^^^^^^^

View File

@ -113,7 +113,7 @@
#ifndef __ASSEMBLY__
/************************************************************************************
* Name: lm3s_boardinitialize
* Name: lm_boardinitialize
*
* Description:
* All LM3S architectures must provide the following entry point. This entry point
@ -122,21 +122,21 @@
*
************************************************************************************/
extern void lm3s_boardinitialize(void);
extern void lm_boardinitialize(void);
/************************************************************************************
* Name: lm3s_ethernetmac
* Name: lm_ethernetmac
*
* Description:
* For the Ethernet Eval Kits, the MAC address will be stored in the non-volatile
* USER0 and USER1 registers. If CONFIG_LM3S_BOARDMAC is defined, this function
* USER0 and USER1 registers. If CONFIG_LM_BOARDMAC is defined, this function
* will obtain the MAC address from these registers.
*
************************************************************************************/
#ifdef CONFIG_LM3S_BOARDMAC
#ifdef CONFIG_LM_BOARDMAC
struct ether_addr;
extern void lm3s_ethernetmac(struct ether_addr *ethaddr);
extern void lm_ethernetmac(struct ether_addr *ethaddr);
#endif
#endif /* __ASSEMBLY__ */

View File

@ -57,32 +57,32 @@ CONFIG_ARCH_CALIBRATION=n
#
# Identify toolchain and linker options
#
CONFIG_LM3S_CODESOURCERYW=n
CONFIG_LM3S_CODESOURCERYL=n
CONFIG_LM3S_DEVKITARM=n
CONFIG_LM3S_BUILDROOT=y
CONFIG_LM3S_DFU=y
CONFIG_LM_CODESOURCERYW=n
CONFIG_LM_CODESOURCERYL=n
CONFIG_LM_DEVKITARM=n
CONFIG_LM_BUILDROOT=y
CONFIG_LM_DFU=y
#
# Disable support for interrupts on GPIOH and GPIOJ which do not
# exist on the LM3S6B96. Additional interrupt support can be
# disabled if desired to reduce memory footprint.
CONFIG_LM3S_DISABLE_GPIOA_IRQS=n
CONFIG_LM3S_DISABLE_GPIOB_IRQS=n
CONFIG_LM3S_DISABLE_GPIOC_IRQS=n
CONFIG_LM3S_DISABLE_GPIOD_IRQS=n
CONFIG_LM3S_DISABLE_GPIOE_IRQS=n
CONFIG_LM3S_DISABLE_GPIOF_IRQS=n
CONFIG_LM3S_DISABLE_GPIOG_IRQS=n
CONFIG_LM3S_DISABLE_GPIOH_IRQS=y
CONFIG_LM3S_DISABLE_GPIOJ_IRQS=y
CONFIG_LM_DISABLE_GPIOA_IRQS=n
CONFIG_LM_DISABLE_GPIOB_IRQS=n
CONFIG_LM_DISABLE_GPIOC_IRQS=n
CONFIG_LM_DISABLE_GPIOD_IRQS=n
CONFIG_LM_DISABLE_GPIOE_IRQS=n
CONFIG_LM_DISABLE_GPIOF_IRQS=n
CONFIG_LM_DISABLE_GPIOG_IRQS=n
CONFIG_LM_DISABLE_GPIOH_IRQS=y
CONFIG_LM_DISABLE_GPIOJ_IRQS=y
#
# LM3S6B96 specific serial device driver settings
#
CONFIG_LM3S_UART0=y
CONFIG_LM3S_UART1=n
CONFIG_LM3S_UART2=n
CONFIG_LM_UART0=y
CONFIG_LM_UART1=n
CONFIG_LM_UART2=n
CONFIG_UART0_SERIAL_CONSOLE=y
CONFIG_UART1_SERIAL_CONSOLE=n
CONFIG_UART2_SERIAL_CONSOLE=n
@ -116,16 +116,16 @@ CONFIG_SSI_POLLWAIT=y
#
# LM3S6B96 specific serial device driver settings
#
CONFIG_LM3S_ETHERNET=y
CONFIG_LM3S_ETHLEDS=n
CONFIG_LM3S_BOARDMAC=n
CONFIG_LM3S_ETHHDUPLEX=n
CONFIG_LM3S_ETHNOAUTOCRC=n
CONFIG_LM3S_ETHNOPAD=n
CONFIG_LM3S_MULTICAST=n
CONFIG_LM3S_PROMISCUOUS=n
CONFIG_LM3S_BADCRC=n
CONFIG_LM3S_DUMPPACKET=n
CONFIG_LM_ETHERNET=y
CONFIG_LM_ETHLEDS=n
CONFIG_LM_BOARDMAC=n
CONFIG_LM_ETHHDUPLEX=n
CONFIG_LM_ETHNOAUTOCRC=n
CONFIG_LM_ETHNOPAD=n
CONFIG_LM_MULTICAST=n
CONFIG_LM_PROMISCUOUS=n
CONFIG_LM_BADCRC=n
CONFIG_LM_DUMPPACKET=n
#
# General build options

View File

@ -57,32 +57,32 @@ CONFIG_ARCH_CALIBRATION=n
#
# Identify toolchain and linker options
#
CONFIG_LM3S_CODESOURCERYW=n
CONFIG_LM3S_CODESOURCERYL=n
CONFIG_LM3S_DEVKITARM=n
CONFIG_LM3S_BUILDROOT=y
CONFIG_LM3S_DFU=y
CONFIG_LM_CODESOURCERYW=n
CONFIG_LM_CODESOURCERYL=n
CONFIG_LM_DEVKITARM=n
CONFIG_LM_BUILDROOT=y
CONFIG_LM_DFU=y
#
# Disable support for interrupts on GPIOH and GPIOJ which do not
# exist on the LM3S6B96. Additional interrupt support can be
# disabled if desired to reduce memory footprint.
CONFIG_LM3S_DISABLE_GPIOA_IRQS=n
CONFIG_LM3S_DISABLE_GPIOB_IRQS=n
CONFIG_LM3S_DISABLE_GPIOC_IRQS=n
CONFIG_LM3S_DISABLE_GPIOD_IRQS=n
CONFIG_LM3S_DISABLE_GPIOE_IRQS=n
CONFIG_LM3S_DISABLE_GPIOF_IRQS=n
CONFIG_LM3S_DISABLE_GPIOG_IRQS=n
CONFIG_LM3S_DISABLE_GPIOH_IRQS=y
CONFIG_LM3S_DISABLE_GPIOJ_IRQS=y
CONFIG_LM_DISABLE_GPIOA_IRQS=n
CONFIG_LM_DISABLE_GPIOB_IRQS=n
CONFIG_LM_DISABLE_GPIOC_IRQS=n
CONFIG_LM_DISABLE_GPIOD_IRQS=n
CONFIG_LM_DISABLE_GPIOE_IRQS=n
CONFIG_LM_DISABLE_GPIOF_IRQS=n
CONFIG_LM_DISABLE_GPIOG_IRQS=n
CONFIG_LM_DISABLE_GPIOH_IRQS=y
CONFIG_LM_DISABLE_GPIOJ_IRQS=y
#
# LM3S6B96 specific serial device driver settings
#
CONFIG_LM3S_UART0=y
CONFIG_LM3S_UART1=n
CONFIG_LM3S_UART2=n
CONFIG_LM_UART0=y
CONFIG_LM_UART1=n
CONFIG_LM_UART2=n
CONFIG_UART0_SERIAL_CONSOLE=y
CONFIG_UART1_SERIAL_CONSOLE=n
CONFIG_UART2_SERIAL_CONSOLE=n
@ -116,16 +116,16 @@ CONFIG_SSI_POLLWAIT=y
#
# LM3S6B96 specific serial device driver settings
#
CONFIG_LM3S_ETHERNET=n
CONFIG_LM3S_ETHLEDS=n
CONFIG_LM3S_BOARDMAC=y
CONFIG_LM3S_ETHHDUPLEX=n
CONFIG_LM3S_ETHNOAUTOCRC=n
CONFIG_LM3S_ETHNOPAD=n
CONFIG_LM3S_MULTICAST=n
CONFIG_LM3S_PROMISCUOUS=n
CONFIG_LM3S_BADCRC=n
CONFIG_LM3S_DUMPPACKET=n
CONFIG_LM_ETHERNET=n
CONFIG_LM_ETHLEDS=n
CONFIG_LM_BOARDMAC=y
CONFIG_LM_ETHHDUPLEX=n
CONFIG_LM_ETHNOAUTOCRC=n
CONFIG_LM_ETHNOPAD=n
CONFIG_LM_MULTICAST=n
CONFIG_LM_PROMISCUOUS=n
CONFIG_LM_BADCRC=n
CONFIG_LM_DUMPPACKET=n
#
# General build options

View File

@ -102,14 +102,14 @@
#ifndef __ASSEMBLY__
/************************************************************************************
* Name: lm3s_ssiinitialize
* Name: lm_ssiinitialize
*
* Description:
* Called to configure SPI chip select GPIO pins for the LM3S6965 Eval Kit.
*
************************************************************************************/
extern void weak_function lm3s_ssiinitialize(void);
extern void weak_function lm_ssiinitialize(void);
#endif /* __ASSEMBLY__ */
#endif /* __CONFIGS_EKK_LM3S9B96_SRC_EKKLM3S9B96_INTERNAL_H */

View File

@ -62,7 +62,7 @@
************************************************************************************/
/************************************************************************************
* Name: lm3s_boardinitialize
* Name: lm_boardinitialize
*
* Description:
* All LM3S architectures must provide the following entry point. This entry point
@ -70,16 +70,16 @@
* and mapped but before any devices have been initialized.
************************************************************************************/
void lm3s_boardinitialize(void)
void lm_boardinitialize(void)
{
/* Configure chip selects if 1) SSI is not disabled, and 2) the weak function
* lm3s_ssiinitialize() has been brought into the link.
* lm_ssiinitialize() has been brought into the link.
*/
#if !defined(CONFIG_SSI0_DISABLE) || !defined(CONFIG_SSI1_DISABLE)
if (lm3s_ssiinitialize)
if (lm_ssiinitialize)
{
lm3s_ssiinitialize();
lm_ssiinitialize();
}
#endif

View File

@ -64,17 +64,17 @@
************************************************************************************/
/************************************************************************************
* Name: lm3s_ethernetmac
* Name: lm_ethernetmac
*
* Description:
* For the Ethernet Eval Kits, the MAC address will be stored in the non-volatile
* USER0 and USER1 registers. If CONFIG_LM3S_BOARDMAC is defined, this function
* USER0 and USER1 registers. If CONFIG_LM_BOARDMAC is defined, this function
* will obtain the MAC address from these registers.
*
************************************************************************************/
#ifdef CONFIG_LM3S_BOARDMAC
void lm3s_ethernetmac(struct ether_addr *ethaddr)
#ifdef CONFIG_LM_BOARDMAC
void lm_ethernetmac(struct ether_addr *ethaddr)
{
uint32_t user0;
uint32_t user1;

View File

@ -73,7 +73,7 @@
/* Dump GPIO registers */
#ifdef LED_DEBUG
# define led_dumpgpio(m) lm3s_dumpgpio(LED_GPIO, m)
# define led_dumpgpio(m) lm_dumpgpio(LED_GPIO, m)
#else
# define led_dumpgpio(m)
#endif
@ -103,9 +103,9 @@ void up_ledinit(void)
/* Configure Port D, Bit 0 as an output, initial value=OFF */
led_dumpgpio("up_ledinit before lm3s_configgpio()");
lm3s_configgpio(LED_GPIO);
led_dumpgpio("up_ledinit after lm3s_configgpio()");
led_dumpgpio("up_ledinit before lm_configgpio()");
lm_configgpio(LED_GPIO);
led_dumpgpio("up_ledinit after lm_configgpio()");
g_nest = 0;
}
@ -129,9 +129,9 @@ void up_ledon(int led)
g_nest++;
case LED_IRQSENABLED:
case LED_STACKCREATED:
led_dumpgpio("up_ledon: before lm3s_gpiowrite()");
lm3s_gpiowrite(LED_GPIO, false);
led_dumpgpio("up_ledon: after lm3s_gpiowrite()");
led_dumpgpio("up_ledon: before lm_gpiowrite()");
lm_gpiowrite(LED_GPIO, false);
led_dumpgpio("up_ledon: after lm_gpiowrite()");
break;
}
}
@ -157,9 +157,9 @@ void up_ledoff(int led)
case LED_PANIC:
if (--g_nest <= 0)
{
led_dumpgpio("up_ledoff: before lm3s_gpiowrite()");
lm3s_gpiowrite(LED_GPIO, true);
led_dumpgpio("up_ledoff: after lm3s_gpiowrite()");
led_dumpgpio("up_ledoff: before lm_gpiowrite()");
lm_gpiowrite(LED_GPIO, true);
led_dumpgpio("up_ledoff: after lm_gpiowrite()");
}
break;
}

View File

@ -81,7 +81,7 @@
#ifdef SSI_VERBOSE
#if 0
# define ssi_dumpgpio(m) lm3s_dumpgpio(SDCCS_GPIO, m)
# define ssi_dumpgpio(m) lm_dumpgpio(SDCCS_GPIO, m)
#endif
#else
# define ssi_dumpgpio(m)
@ -96,31 +96,31 @@
************************************************************************************/
/************************************************************************************
* Name: lm3s_ssiinitialize
* Name: lm_ssiinitialize
*
* Description:
* Called to configure chip select GPIO pins for the LM3S9B96 Eval board.
*
************************************************************************************/
void weak_function lm3s_ssiinitialize(void)
void weak_function lm_ssiinitialize(void)
{
/* Configure the CS GPIO */
#if 0
ssi_dumpgpio("lm3s_ssiinitialize() Entry");
ssi_dumpgpio("lm3s_ssiinitialize() Exit");
ssi_dumpgpio("lm_ssiinitialize() Entry");
ssi_dumpgpio("lm_ssiinitialize() Exit");
#endif
}
#if 0
/****************************************************************************
* The external functions, lm3s_spiselect and lm3s_spistatus must be provided
* The external functions, lm_spiselect and lm_spistatus must be provided
* by board-specific logic. The are implementations of the select and status
* methods SPI interface defined by struct spi_ops_s (see include/nuttx/spi.h).
* All othermethods (including up_spiinitialize()) are provided by common
* logic. To use this common SPI logic on your board:
*
* 1. Provide lm3s_spiselect() and lm3s_spistatus() functions in your
* 1. Provide lm_spiselect() and lm_spistatus() functions in your
* board-specific logic. This function will perform chip selection and
* status operations using GPIOs in the way your board is configured.
* 2. Add a call to up_spiinitialize() in your low level initialization
@ -132,28 +132,28 @@ void weak_function lm3s_ssiinitialize(void)
*
****************************************************************************/
void lm3s_spiselect(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected)
void lm_spiselect(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected)
{
ssidbg("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert");
ssi_dumpgpio("lm3s_spiselect() Entry");
ssi_dumpgpio("lm_spiselect() Entry");
if (devid == SPIDEV_MMCSD)
{
/* Assert the CS pin to the card */
lm3s_gpiowrite(SDCCS_GPIO, !selected);
lm_gpiowrite(SDCCS_GPIO, !selected);
}
#ifdef CONFIG_NX_LCDDRIVER
else if (devid == SPIDEV_DISPLAY)
{
/* Assert the CS pin to the display */
lm3s_gpiowrite(OLEDCS_GPIO, !selected);
lm_gpiowrite(OLEDCS_GPIO, !selected);
}
#endif
ssi_dumpgpio("lm3s_spiselect() Exit");
ssi_dumpgpio("lm_spiselect() Exit");
}
uint8_t lm3s_spistatus(FAR struct spi_dev_s *dev, enum spi_dev_e devid)
uint8_t lm_spistatus(FAR struct spi_dev_s *dev, enum spi_dev_e devid)
{
ssidbg("Returning SPI_STATUS_PRESENT\n");
return SPI_STATUS_PRESENT;

View File

@ -97,12 +97,12 @@ GNU Toolchain Options
To use a specific toolchain, you simply need to add one of the following
configuration options to your .config (or defconfig) file:
CONFIG_LM3S_CODESOURCERYW=y : CodeSourcery under Windows
CONFIG_LM3S_CODESOURCERYL=y : CodeSourcery under Linux or on Mac OS X.
CONFIG_LM3S_DEVKITARM=y : devkitARM under Windows
CONFIG_LM3S_BUILDROOT=y : NuttX buildroot under Linux or Cygwin (default)
CONFIG_LM_CODESOURCERYW=y : CodeSourcery under Windows
CONFIG_LM_CODESOURCERYL=y : CodeSourcery under Linux or on Mac OS X.
CONFIG_LM_DEVKITARM=y : devkitARM under Windows
CONFIG_LM_BUILDROOT=y : NuttX buildroot under Linux or Cygwin (default)
If you are not using CONFIG_LM3S_BUILDROOT, then you may also have to modify
If you are not using CONFIG_LM_BUILDROOT, then you may also have to modify
the PATH in the setenv.h file if your make cannot find the tools.
NOTE: the CodeSourcery (for Windows) and devkitARM are Windows native toolchains.
@ -346,15 +346,15 @@ Stellaris MDL-S2E Reference Design Configuration Options
Additional interrupt support can be disabled if desired to reduce memory
footprint - GPIOs C-G are not pinned out on the MDL-S2E board.
CONFIG_LM3S_DISABLE_GPIOA_IRQS=n
CONFIG_LM3S_DISABLE_GPIOB_IRQS=n
CONFIG_LM3S_DISABLE_GPIOC_IRQS=y
CONFIG_LM3S_DISABLE_GPIOD_IRQS=y
CONFIG_LM3S_DISABLE_GPIOE_IRQS=y
CONFIG_LM3S_DISABLE_GPIOF_IRQS=y
CONFIG_LM3S_DISABLE_GPIOG_IRQS=y
CONFIG_LM3S_DISABLE_GPIOH_IRQS=y
CONFIG_LM3S_DISABLE_GPIOJ_IRQS=y
CONFIG_LM_DISABLE_GPIOA_IRQS=n
CONFIG_LM_DISABLE_GPIOB_IRQS=n
CONFIG_LM_DISABLE_GPIOC_IRQS=y
CONFIG_LM_DISABLE_GPIOD_IRQS=y
CONFIG_LM_DISABLE_GPIOE_IRQS=y
CONFIG_LM_DISABLE_GPIOF_IRQS=y
CONFIG_LM_DISABLE_GPIOG_IRQS=y
CONFIG_LM_DISABLE_GPIOH_IRQS=y
CONFIG_LM_DISABLE_GPIOJ_IRQS=y
LM3S6432 specific device driver settings
@ -388,18 +388,18 @@ Stellaris MDL-S2E Reference Design Configuration Options
value is large, then larger values of this setting may cause
Rx FIFO overrun errors. Default: half of the Tx FIFO size (4).
CONFIG_LM3S_ETHERNET - This must be set (along with CONFIG_NET)
CONFIG_LM_ETHERNET - This must be set (along with CONFIG_NET)
to build the LM3S Ethernet driver
CONFIG_LM3S_ETHLEDS - Enable to use Ethernet LEDs on the board.
CONFIG_LM3S_BOARDMAC - This should be set in order to use the
CONFIG_LM_ETHLEDS - Enable to use Ethernet LEDs on the board.
CONFIG_LM_BOARDMAC - This should be set in order to use the
MAC address configured in the flash USER registers.
CONFIG_LM3S_ETHHDUPLEX - Set to force half duplex operation
CONFIG_LM3S_ETHNOAUTOCRC - Set to suppress auto-CRC generation
CONFIG_LM3S_ETHNOPAD - Set to suppress Tx padding
CONFIG_LM3S_MULTICAST - Set to enable multicast frames
CONFIG_LM3S_PROMISCUOUS - Set to enable promiscuous mode
CONFIG_LM3S_BADCRC - Set to enable bad CRC rejection.
CONFIG_LM3S_DUMPPACKET - Dump each packet received/sent to the console.
CONFIG_LM_ETHHDUPLEX - Set to force half duplex operation
CONFIG_LM_ETHNOAUTOCRC - Set to suppress auto-CRC generation
CONFIG_LM_ETHNOPAD - Set to suppress Tx padding
CONFIG_LM_MULTICAST - Set to enable multicast frames
CONFIG_LM_PROMISCUOUS - Set to enable promiscuous mode
CONFIG_LM_BADCRC - Set to enable bad CRC rejection.
CONFIG_LM_DUMPPACKET - Dump each packet received/sent to the console.
Configurations
^^^^^^^^^^^^^^

View File

@ -114,7 +114,7 @@
#ifndef __ASSEMBLY__
/************************************************************************************
* Name: lm3s_boardinitialize
* Name: lm_boardinitialize
*
* Description:
* All LM3S architectures must provide the following entry point. This entry point
@ -123,21 +123,21 @@
*
************************************************************************************/
extern void lm3s_boardinitialize(void);
extern void lm_boardinitialize(void);
/************************************************************************************
* Name: lm3s_ethernetmac
* Name: lm_ethernetmac
*
* Description:
* For the MDL-S2E Reference Design, the MAC address will be stored in the
* non-volatile USER0 and USER1 registers. If CONFIG_LM3S_BOARDMAC is defined,
* non-volatile USER0 and USER1 registers. If CONFIG_LM_BOARDMAC is defined,
* this function will obtain the MAC address from these registers.
*
************************************************************************************/
#ifdef CONFIG_LM3S_BOARDMAC
#ifdef CONFIG_LM_BOARDMAC
struct ether_addr;
extern void lm3s_ethernetmac(struct ether_addr *ethaddr);
extern void lm_ethernetmac(struct ether_addr *ethaddr);
#endif
#endif /* __ASSEMBLY__ */

View File

@ -56,32 +56,32 @@ CONFIG_ARCH_CALIBRATION=n
#
# Identify toolchain and linker options
#
CONFIG_LM3S_CODESOURCERYW=n
CONFIG_LM3S_CODESOURCERYL=y
CONFIG_LM3S_DEVKITARM=n
CONFIG_LM3S_BUILDROOT=n
CONFIG_LM_CODESOURCERYW=n
CONFIG_LM_CODESOURCERYL=y
CONFIG_LM_DEVKITARM=n
CONFIG_LM_BUILDROOT=n
#
# Disable support for interrupts on GPIOs which do not
# exist on the LM3S6432 or are not pinned anywhere useful
# on the S2E.
#
CONFIG_LM3S_DISABLE_GPIOA_IRQS=n
CONFIG_LM3S_DISABLE_GPIOB_IRQS=n
CONFIG_LM3S_DISABLE_GPIOC_IRQS=y
CONFIG_LM3S_DISABLE_GPIOD_IRQS=y
CONFIG_LM3S_DISABLE_GPIOE_IRQS=y
CONFIG_LM3S_DISABLE_GPIOF_IRQS=y
CONFIG_LM3S_DISABLE_GPIOG_IRQS=y
CONFIG_LM3S_DISABLE_GPIOH_IRQS=y
CONFIG_LM3S_DISABLE_GPIOJ_IRQS=y
CONFIG_LM_DISABLE_GPIOA_IRQS=n
CONFIG_LM_DISABLE_GPIOB_IRQS=n
CONFIG_LM_DISABLE_GPIOC_IRQS=y
CONFIG_LM_DISABLE_GPIOD_IRQS=y
CONFIG_LM_DISABLE_GPIOE_IRQS=y
CONFIG_LM_DISABLE_GPIOF_IRQS=y
CONFIG_LM_DISABLE_GPIOG_IRQS=y
CONFIG_LM_DISABLE_GPIOH_IRQS=y
CONFIG_LM_DISABLE_GPIOJ_IRQS=y
#
# LM3S6432 specific serial device driver settings
#
CONFIG_LM3S_UART0=y
CONFIG_LM3S_UART1=y
CONFIG_LM3S_UART2=n
CONFIG_LM_UART0=y
CONFIG_LM_UART1=y
CONFIG_LM_UART2=n
CONFIG_UART0_SERIAL_CONSOLE=n
CONFIG_UART1_SERIAL_CONSOLE=y
CONFIG_UART2_SERIAL_CONSOLE=n
@ -115,16 +115,16 @@ CONFIG_SSI_POLLWAIT=y
#
# LM3S6432 specific ethernet device driver settings
#
CONFIG_LM3S_ETHERNET=y
CONFIG_LM3S_ETHLEDS=n
CONFIG_LM3S_BOARDMAC=y
CONFIG_LM3S_ETHHDUPLEX=n
CONFIG_LM3S_ETHNOAUTOCRC=n
CONFIG_LM3S_ETHNOPAD=n
CONFIG_LM3S_MULTICAST=n
CONFIG_LM3S_PROMISCUOUS=n
CONFIG_LM3S_BADCRC=n
CONFIG_LM3S_DUMPPACKET=n
CONFIG_LM_ETHERNET=y
CONFIG_LM_ETHLEDS=n
CONFIG_LM_BOARDMAC=y
CONFIG_LM_ETHHDUPLEX=n
CONFIG_LM_ETHNOAUTOCRC=n
CONFIG_LM_ETHNOPAD=n
CONFIG_LM_MULTICAST=n
CONFIG_LM_PROMISCUOUS=n
CONFIG_LM_BADCRC=n
CONFIG_LM_DUMPPACKET=n
#
# General build options

View File

@ -56,32 +56,32 @@ CONFIG_ARCH_CALIBRATION=n
#
# Identify toolchain and linker options
#
CONFIG_LM3S_CODESOURCERYW=n
CONFIG_LM3S_CODESOURCERYL=y
CONFIG_LM3S_DEVKITARM=n
CONFIG_LM3S_BUILDROOT=n
CONFIG_LM_CODESOURCERYW=n
CONFIG_LM_CODESOURCERYL=y
CONFIG_LM_DEVKITARM=n
CONFIG_LM_BUILDROOT=n
#
# Disable support for interrupts on GPIOs which do not
# exist on the LM3S6432 or are not pinned anywhere useful
# on the S2E.
#
CONFIG_LM3S_DISABLE_GPIOA_IRQS=n
CONFIG_LM3S_DISABLE_GPIOB_IRQS=n
CONFIG_LM3S_DISABLE_GPIOC_IRQS=y
CONFIG_LM3S_DISABLE_GPIOD_IRQS=y
CONFIG_LM3S_DISABLE_GPIOE_IRQS=y
CONFIG_LM3S_DISABLE_GPIOF_IRQS=y
CONFIG_LM3S_DISABLE_GPIOG_IRQS=y
CONFIG_LM3S_DISABLE_GPIOH_IRQS=y
CONFIG_LM3S_DISABLE_GPIOJ_IRQS=y
CONFIG_LM_DISABLE_GPIOA_IRQS=n
CONFIG_LM_DISABLE_GPIOB_IRQS=n
CONFIG_LM_DISABLE_GPIOC_IRQS=y
CONFIG_LM_DISABLE_GPIOD_IRQS=y
CONFIG_LM_DISABLE_GPIOE_IRQS=y
CONFIG_LM_DISABLE_GPIOF_IRQS=y
CONFIG_LM_DISABLE_GPIOG_IRQS=y
CONFIG_LM_DISABLE_GPIOH_IRQS=y
CONFIG_LM_DISABLE_GPIOJ_IRQS=y
#
# LM3S6432 specific serial device driver settings
#
CONFIG_LM3S_UART0=y
CONFIG_LM3S_UART1=y
CONFIG_LM3S_UART2=n
CONFIG_LM_UART0=y
CONFIG_LM_UART1=y
CONFIG_LM_UART2=n
CONFIG_UART0_SERIAL_CONSOLE=n
CONFIG_UART1_SERIAL_CONSOLE=y
CONFIG_UART2_SERIAL_CONSOLE=n
@ -115,16 +115,16 @@ CONFIG_SSI_POLLWAIT=y
#
# LM3S6432 specific ethernet device driver settings
#
CONFIG_LM3S_ETHERNET=n
CONFIG_LM3S_ETHLEDS=n
CONFIG_LM3S_BOARDMAC=y
CONFIG_LM3S_ETHHDUPLEX=n
CONFIG_LM3S_ETHNOAUTOCRC=n
CONFIG_LM3S_ETHNOPAD=n
CONFIG_LM3S_MULTICAST=n
CONFIG_LM3S_PROMISCUOUS=n
CONFIG_LM3S_BADCRC=n
CONFIG_LM3S_DUMPPACKET=n
CONFIG_LM_ETHERNET=n
CONFIG_LM_ETHLEDS=n
CONFIG_LM_BOARDMAC=y
CONFIG_LM_ETHHDUPLEX=n
CONFIG_LM_ETHNOAUTOCRC=n
CONFIG_LM_ETHNOPAD=n
CONFIG_LM_MULTICAST=n
CONFIG_LM_PROMISCUOUS=n
CONFIG_LM_BADCRC=n
CONFIG_LM_DUMPPACKET=n
#
# General build options

View File

@ -112,14 +112,14 @@
#ifndef __ASSEMBLY__
/************************************************************************************
* Name: lm3s_ssiinitialize
* Name: lm_ssiinitialize
*
* Description:
* Called to configure SPI chip select GPIO pins for the MDL-S2E.
*
************************************************************************************/
extern void weak_function lm3s_ssiinitialize(void);
extern void weak_function lm_ssiinitialize(void);
#endif /* __ASSEMBLY__ */
#endif /* __CONFIGS_LM3S6432_S2E_SRC_LM3S6432S2E_INTERNAL_H */

View File

@ -54,7 +54,7 @@
* Definitions
************************************************************************************/
#if defined(CONFIG_LM3S_UART1) && !defined(CONFIG_SSI0_DISABLE)
#if defined(CONFIG_LM_UART1) && !defined(CONFIG_SSI0_DISABLE)
# error Only one of UART1 and SSI0 can be enabled on this board.
#endif
@ -67,7 +67,7 @@
************************************************************************************/
/************************************************************************************
* Name: lm3s_boardinitialize
* Name: lm_boardinitialize
*
* Description:
* All LM3S architectures must provide the following entry point. This entry point
@ -75,16 +75,16 @@
* and mapped but before any devices have been initialized.
************************************************************************************/
void lm3s_boardinitialize(void)
void lm_boardinitialize(void)
{
/* Configure SPI chip selects if 1) SSI is not disabled, and 2) the weak function
* lm3s_ssiinitialize() has been brought into the link.
* lm_ssiinitialize() has been brought into the link.
*/
#if !defined(CONFIG_SSI0_DISABLE)
if (lm3s_ssiinitialize)
if (lm_ssiinitialize)
{
lm3s_ssiinitialize();
lm_ssiinitialize();
}
#endif
@ -96,8 +96,8 @@ void lm3s_boardinitialize(void)
/* Configure serial transciever */
lm3s_configgpio(XCVR_INV_GPIO);
lm3s_configgpio(XCVR_ENA_GPIO);
lm3s_configgpio(XCVR_ON_GPIO);
lm3s_configgpio(XCVR_OFF_GPIO);
lm_configgpio(XCVR_INV_GPIO);
lm_configgpio(XCVR_ENA_GPIO);
lm_configgpio(XCVR_ON_GPIO);
lm_configgpio(XCVR_OFF_GPIO);
}

View File

@ -63,17 +63,17 @@
************************************************************************************/
/************************************************************************************
* Name: lm3s_ethernetmac
* Name: lm_ethernetmac
*
* Description:
* For the Ethernet Eval Kits, the MAC address will be stored in the non-volatile
* USER0 and USER1 registers. If CONFIG_LM3S_BOARDMAC is defined, this function
* USER0 and USER1 registers. If CONFIG_LM_BOARDMAC is defined, this function
* will obtain the MAC address from these registers.
*
************************************************************************************/
#ifdef CONFIG_LM3S_BOARDMAC
void lm3s_ethernetmac(struct ether_addr *ethaddr)
#ifdef CONFIG_LM_BOARDMAC
void lm_ethernetmac(struct ether_addr *ethaddr)
{
uint32_t user0;
uint32_t user1;

View File

@ -72,7 +72,7 @@
/* Dump GPIO registers */
#ifdef LED_DEBUG
# define led_dumpgpio(m) lm3s_dumpgpio(LED_GPIO, m)
# define led_dumpgpio(m) lm_dumpgpio(LED_GPIO, m)
#else
# define led_dumpgpio(m)
#endif
@ -102,10 +102,10 @@ void up_ledinit(void)
/* Configure Port F, Bit 2 as an output, initial value=OFF */
led_dumpgpio("up_ledinit before lm3s_configgpio()");
lm3s_configgpio(LED0_GPIO);
lm3s_configgpio(LED1_GPIO);
led_dumpgpio("up_ledinit after lm3s_configgpio()");
led_dumpgpio("up_ledinit before lm_configgpio()");
lm_configgpio(LED0_GPIO);
lm_configgpio(LED1_GPIO);
led_dumpgpio("up_ledinit after lm_configgpio()");
g_nest = 0;
}
@ -129,9 +129,9 @@ void up_ledon(int led)
g_nest++;
case LED_IRQSENABLED:
case LED_STACKCREATED:
led_dumpgpio("up_ledon: before lm3s_gpiowrite()");
lm3s_gpiowrite(LED1_GPIO, false);
led_dumpgpio("up_ledon: after lm3s_gpiowrite()");
led_dumpgpio("up_ledon: before lm_gpiowrite()");
lm_gpiowrite(LED1_GPIO, false);
led_dumpgpio("up_ledon: after lm_gpiowrite()");
break;
}
}
@ -157,9 +157,9 @@ void up_ledoff(int led)
case LED_PANIC:
if (--g_nest <= 0)
{
led_dumpgpio("up_ledoff: before lm3s_gpiowrite()");
lm3s_gpiowrite(LED1_GPIO, true);
led_dumpgpio("up_ledoff: after lm3s_gpiowrite()");
led_dumpgpio("up_ledoff: before lm_gpiowrite()");
lm_gpiowrite(LED1_GPIO, true);
led_dumpgpio("up_ledoff: after lm_gpiowrite()");
}
break;
}

View File

@ -79,7 +79,7 @@
/* Dump GPIO registers */
#ifdef SSI_VERBOSE
# define ssi_dumpgpio(m) lm3s_dumpgpio(SDCCS_GPIO, m)
# define ssi_dumpgpio(m) lm_dumpgpio(SDCCS_GPIO, m)
#else
# define ssi_dumpgpio(m)
#endif
@ -93,30 +93,30 @@
************************************************************************************/
/************************************************************************************
* Name: lm3s_ssiinitialize
* Name: lm_ssiinitialize
*
* Description:
* Called to configure SPI chip select GPIO pins for the MDL-S2E.
*
************************************************************************************/
void weak_function lm3s_ssiinitialize(void)
void weak_function lm_ssiinitialize(void)
{
/* Configure the SPI CS GPIO */
ssi_dumpgpio("lm3s_ssiinitialize() Entry)");
lm3s_configgpio(SSICS_GPIO);
ssi_dumpgpio("lm3s_ssiinitialize() Exit");
ssi_dumpgpio("lm_ssiinitialize() Entry)");
lm_configgpio(SSICS_GPIO);
ssi_dumpgpio("lm_ssiinitialize() Exit");
}
/****************************************************************************
* The external functions, lm3s_spiselect and lm3s_spistatus must be provided
* The external functions, lm_spiselect and lm_spistatus must be provided
* by board-specific logic. The are implementations of the select and status
* methods SPI interface defined by struct spi_ops_s (see include/nuttx/spi.h).
* All othermethods (including up_spiinitialize()) are provided by common
* logic. To use this common SPI logic on your board:
*
* 1. Provide lm3s_spiselect() and lm3s_spistatus() functions in your
* 1. Provide lm_spiselect() and lm_spistatus() functions in your
* board-specific logic. This function will perform chip selection and
* status operations using GPIOs in the way your board is configured.
* 2. Add a call to up_spiinitialize() in your low level initialization
@ -128,21 +128,21 @@ void weak_function lm3s_ssiinitialize(void)
*
****************************************************************************/
void lm3s_spiselect(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected)
void lm_spiselect(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected)
{
ssidbg("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert");
ssi_dumpgpio("lm3s_spiselect() Entry");
ssi_dumpgpio("lm_spiselect() Entry");
if (devid == SPIDEV_MMCSD)
{
/* Assert the CS pin to the card */
lm3s_gpiowrite(SDCCS_GPIO, !selected);
lm_gpiowrite(SDCCS_GPIO, !selected);
}
ssi_dumpgpio("lm3s_spiselect() Exit");
ssi_dumpgpio("lm_spiselect() Exit");
}
uint8_t lm3s_spistatus(FAR struct spi_dev_s *dev, enum spi_dev_e devid)
uint8_t lm_spistatus(FAR struct spi_dev_s *dev, enum spi_dev_e devid)
{
ssidbg("Returning SPI_STATUS_PRESENT\n");
return SPI_STATUS_PRESENT;

View File

@ -126,12 +126,12 @@ GNU Toolchain Options
the CodeSourcery or devkitARM, you simply need to add one of the following
configuration options to your .config (or defconfig) file:
CONFIG_LM3S_CODESOURCERYW=y : CodeSourcery under Windows
CONFIG_LM3S_CODESOURCERYL=y : CodeSourcery under Linux
CONFIG_LM3S_DEVKITARM=y : devkitARM under Windows
CONFIG_LM3S_BUILDROOT=y : NuttX buildroot under Linux or Cygwin (default)
CONFIG_LM_CODESOURCERYW=y : CodeSourcery under Windows
CONFIG_LM_CODESOURCERYL=y : CodeSourcery under Linux
CONFIG_LM_DEVKITARM=y : devkitARM under Windows
CONFIG_LM_BUILDROOT=y : NuttX buildroot under Linux or Cygwin (default)
If you are not using CONFIG_LM3S_BUILDROOT, then you may also have to modify
If you are not using CONFIG_LM_BUILDROOT, then you may also have to modify
the PATH in the setenv.h file if your make cannot find the tools.
NOTE: the CodeSourcery (for Windows) and devkitARM are Windows native toolchains.
@ -415,15 +415,15 @@ Stellaris LM3S6965 Evaluation Kit Configuration Options
Additional interrupt support can be disabled if desired to reduce memory
footprint.
CONFIG_LM3S_DISABLE_GPIOA_IRQS=n
CONFIG_LM3S_DISABLE_GPIOB_IRQS=n
CONFIG_LM3S_DISABLE_GPIOC_IRQS=n
CONFIG_LM3S_DISABLE_GPIOD_IRQS=n
CONFIG_LM3S_DISABLE_GPIOE_IRQS=n
CONFIG_LM3S_DISABLE_GPIOF_IRQS=n
CONFIG_LM3S_DISABLE_GPIOG_IRQS=n
CONFIG_LM3S_DISABLE_GPIOH_IRQS=n
CONFIG_LM3S_DISABLE_GPIOJ_IRQS=y
CONFIG_LM_DISABLE_GPIOA_IRQS=n
CONFIG_LM_DISABLE_GPIOB_IRQS=n
CONFIG_LM_DISABLE_GPIOC_IRQS=n
CONFIG_LM_DISABLE_GPIOD_IRQS=n
CONFIG_LM_DISABLE_GPIOE_IRQS=n
CONFIG_LM_DISABLE_GPIOF_IRQS=n
CONFIG_LM_DISABLE_GPIOG_IRQS=n
CONFIG_LM_DISABLE_GPIOH_IRQS=n
CONFIG_LM_DISABLE_GPIOJ_IRQS=y
LM3S6818 specific device driver settings
@ -448,18 +448,18 @@ Stellaris LM3S6965 Evaluation Kit Configuration Options
value is large, then larger values of this setting may cause
Rx FIFO overrun errors. Default: half of the Tx FIFO size (4).
CONFIG_LM3S_ETHERNET - This must be set (along with CONFIG_NET)
CONFIG_LM_ETHERNET - This must be set (along with CONFIG_NET)
to build the LM3S Ethernet driver
CONFIG_LM3S_ETHLEDS - Enable to use Ethernet LEDs on the board.
CONFIG_LM3S_BOARDMAC - If the board-specific logic can provide
CONFIG_LM_ETHLEDS - Enable to use Ethernet LEDs on the board.
CONFIG_LM_BOARDMAC - If the board-specific logic can provide
a MAC address (via lm_ethernetmac()), then this should be selected.
CONFIG_LM3S_ETHHDUPLEX - Set to force half duplex operation
CONFIG_LM3S_ETHNOAUTOCRC - Set to suppress auto-CRC generation
CONFIG_LM3S_ETHNOPAD - Set to suppress Tx padding
CONFIG_LM3S_MULTICAST - Set to enable multicast frames
CONFIG_LM3S_PROMISCUOUS - Set to enable promiscuous mode
CONFIG_LM3S_BADCRC - Set to enable bad CRC rejection.
CONFIG_LM3S_DUMPPACKET - Dump each packet received/sent to the console.
CONFIG_LM_ETHHDUPLEX - Set to force half duplex operation
CONFIG_LM_ETHNOAUTOCRC - Set to suppress auto-CRC generation
CONFIG_LM_ETHNOPAD - Set to suppress Tx padding
CONFIG_LM_MULTICAST - Set to enable multicast frames
CONFIG_LM_PROMISCUOUS - Set to enable promiscuous mode
CONFIG_LM_BADCRC - Set to enable bad CRC rejection.
CONFIG_LM_DUMPPACKET - Dump each packet received/sent to the console.
Configurations
^^^^^^^^^^^^^^

View File

@ -112,7 +112,7 @@
#ifndef __ASSEMBLY__
/************************************************************************************
* Name: lm3s_boardinitialize
* Name: lm_boardinitialize
*
* Description:
* All LM3S architectures must provide the following entry point. This entry point
@ -121,21 +121,21 @@
*
************************************************************************************/
extern void lm3s_boardinitialize(void);
extern void lm_boardinitialize(void);
/************************************************************************************
* Name: lm3s_ethernetmac
* Name: lm_ethernetmac
*
* Description:
* For the Ethernet Eval Kits, the MAC address will be stored in the non-volatile
* USER0 and USER1 registers. If CONFIG_LM3S_BOARDMAC is defined, this function
* USER0 and USER1 registers. If CONFIG_LM_BOARDMAC is defined, this function
* will obtain the MAC address from these registers.
*
************************************************************************************/
#ifdef CONFIG_LM3S_BOARDMAC
#ifdef CONFIG_LM_BOARDMAC
struct ether_addr;
extern void lm3s_ethernetmac(struct ether_addr *ethaddr);
extern void lm_ethernetmac(struct ether_addr *ethaddr);
#endif
#endif /* __ASSEMBLY__ */

View File

@ -100,44 +100,44 @@ CONFIG_ARMV7M_OABI_TOOLCHAIN=y
# CONFIG_ARCH_CHIP_LM3S6432 is not set
CONFIG_ARCH_CHIP_LM3S6965=y
# CONFIG_ARCH_CHIP_LM3S8962 is not set
# CONFIG_LM3S_REVA2 is not set
CONFIG_LM3S_DFU=y
# CONFIG_LM_REVA2 is not set
CONFIG_LM_DFU=y
#
# Select LM3S Peripheral Support
#
CONFIG_LM3S_UART0=y
# CONFIG_LM3S_UART1 is not set
CONFIG_LM_UART0=y
# CONFIG_LM_UART1 is not set
# CONFIG_SSI0_DISABLE is not set
CONFIG_SSI1_DISABLE=y
# CONFIG_LM3S_UART2 is not set
CONFIG_LM3S_ETHERNET=y
# CONFIG_LM_UART2 is not set
CONFIG_LM_ETHERNET=y
#
# Disable GPIO Interrupts
#
# CONFIG_LM3S_DISABLE_GPIOA_IRQS is not set
# CONFIG_LM3S_DISABLE_GPIOB_IRQS is not set
# CONFIG_LM3S_DISABLE_GPIOC_IRQS is not set
# CONFIG_LM3S_DISABLE_GPIOD_IRQS is not set
# CONFIG_LM3S_DISABLE_GPIOE_IRQS is not set
# CONFIG_LM3S_DISABLE_GPIOF_IRQS is not set
# CONFIG_LM3S_DISABLE_GPIOG_IRQS is not set
CONFIG_LM3S_DISABLE_GPIOH_IRQS=y
CONFIG_LM3S_DISABLE_GPIOJ_IRQS=y
# CONFIG_LM_DISABLE_GPIOA_IRQS is not set
# CONFIG_LM_DISABLE_GPIOB_IRQS is not set
# CONFIG_LM_DISABLE_GPIOC_IRQS is not set
# CONFIG_LM_DISABLE_GPIOD_IRQS is not set
# CONFIG_LM_DISABLE_GPIOE_IRQS is not set
# CONFIG_LM_DISABLE_GPIOF_IRQS is not set
# CONFIG_LM_DISABLE_GPIOG_IRQS is not set
CONFIG_LM_DISABLE_GPIOH_IRQS=y
CONFIG_LM_DISABLE_GPIOJ_IRQS=y
#
# LM3S Ethernet Configuration
#
# CONFIG_LM3S_ETHLEDS is not set
# CONFIG_LM3S_BOARDMAC is not set
# CONFIG_LM3S_ETHHDUPLEX is not set
# CONFIG_LM3S_ETHNOAUTOCRC is not set
# CONFIG_LM3S_ETHNOPAD is not set
# CONFIG_LM3S_MULTICAST is not set
# CONFIG_LM3S_PROMISCUOUS is not set
# CONFIG_LM3S_TIMESTAMP is not set
# CONFIG_LM3S_BADCRC is not set
# CONFIG_LM_ETHLEDS is not set
# CONFIG_LM_BOARDMAC is not set
# CONFIG_LM_ETHHDUPLEX is not set
# CONFIG_LM_ETHNOAUTOCRC is not set
# CONFIG_LM_ETHNOPAD is not set
# CONFIG_LM_MULTICAST is not set
# CONFIG_LM_PROMISCUOUS is not set
# CONFIG_LM_TIMESTAMP is not set
# CONFIG_LM_BADCRC is not set
# CONFIG_M3S_DUMPPACKET is not set
#

View File

@ -100,31 +100,31 @@ CONFIG_ARMV7M_OABI_TOOLCHAIN=y
# CONFIG_ARCH_CHIP_LM3S6432 is not set
CONFIG_ARCH_CHIP_LM3S6965=y
# CONFIG_ARCH_CHIP_LM3S8962 is not set
# CONFIG_LM3S_REVA2 is not set
CONFIG_LM3S_DFU=y
# CONFIG_LM_REVA2 is not set
CONFIG_LM_DFU=y
#
# Select LM3S Peripheral Support
#
CONFIG_LM3S_UART0=y
# CONFIG_LM3S_UART1 is not set
CONFIG_LM_UART0=y
# CONFIG_LM_UART1 is not set
# CONFIG_SSI0_DISABLE is not set
CONFIG_SSI1_DISABLE=y
# CONFIG_LM3S_UART2 is not set
# CONFIG_LM3S_ETHERNET is not set
# CONFIG_LM_UART2 is not set
# CONFIG_LM_ETHERNET is not set
#
# Disable GPIO Interrupts
#
# CONFIG_LM3S_DISABLE_GPIOA_IRQS is not set
# CONFIG_LM3S_DISABLE_GPIOB_IRQS is not set
# CONFIG_LM3S_DISABLE_GPIOC_IRQS is not set
# CONFIG_LM3S_DISABLE_GPIOD_IRQS is not set
# CONFIG_LM3S_DISABLE_GPIOE_IRQS is not set
# CONFIG_LM3S_DISABLE_GPIOF_IRQS is not set
# CONFIG_LM3S_DISABLE_GPIOG_IRQS is not set
CONFIG_LM3S_DISABLE_GPIOH_IRQS=y
CONFIG_LM3S_DISABLE_GPIOJ_IRQS=y
# CONFIG_LM_DISABLE_GPIOA_IRQS is not set
# CONFIG_LM_DISABLE_GPIOB_IRQS is not set
# CONFIG_LM_DISABLE_GPIOC_IRQS is not set
# CONFIG_LM_DISABLE_GPIOD_IRQS is not set
# CONFIG_LM_DISABLE_GPIOE_IRQS is not set
# CONFIG_LM_DISABLE_GPIOF_IRQS is not set
# CONFIG_LM_DISABLE_GPIOG_IRQS is not set
CONFIG_LM_DISABLE_GPIOH_IRQS=y
CONFIG_LM_DISABLE_GPIOJ_IRQS=y
#
# LM3S SSI Configuration

View File

@ -100,31 +100,31 @@ CONFIG_ARMV7M_OABI_TOOLCHAIN=y
# CONFIG_ARCH_CHIP_LM3S6432 is not set
CONFIG_ARCH_CHIP_LM3S6965=y
# CONFIG_ARCH_CHIP_LM3S8962 is not set
# CONFIG_LM3S_REVA2 is not set
CONFIG_LM3S_DFU=y
# CONFIG_LM_REVA2 is not set
CONFIG_LM_DFU=y
#
# Select LM3S Peripheral Support
#
CONFIG_LM3S_UART0=y
# CONFIG_LM3S_UART1 is not set
CONFIG_LM_UART0=y
# CONFIG_LM_UART1 is not set
# CONFIG_SSI0_DISABLE is not set
CONFIG_SSI1_DISABLE=y
# CONFIG_LM3S_UART2 is not set
# CONFIG_LM3S_ETHERNET is not set
# CONFIG_LM_UART2 is not set
# CONFIG_LM_ETHERNET is not set
#
# Disable GPIO Interrupts
#
# CONFIG_LM3S_DISABLE_GPIOA_IRQS is not set
# CONFIG_LM3S_DISABLE_GPIOB_IRQS is not set
# CONFIG_LM3S_DISABLE_GPIOC_IRQS is not set
# CONFIG_LM3S_DISABLE_GPIOD_IRQS is not set
# CONFIG_LM3S_DISABLE_GPIOE_IRQS is not set
# CONFIG_LM3S_DISABLE_GPIOF_IRQS is not set
# CONFIG_LM3S_DISABLE_GPIOG_IRQS is not set
CONFIG_LM3S_DISABLE_GPIOH_IRQS=y
CONFIG_LM3S_DISABLE_GPIOJ_IRQS=y
# CONFIG_LM_DISABLE_GPIOA_IRQS is not set
# CONFIG_LM_DISABLE_GPIOB_IRQS is not set
# CONFIG_LM_DISABLE_GPIOC_IRQS is not set
# CONFIG_LM_DISABLE_GPIOD_IRQS is not set
# CONFIG_LM_DISABLE_GPIOE_IRQS is not set
# CONFIG_LM_DISABLE_GPIOF_IRQS is not set
# CONFIG_LM_DISABLE_GPIOG_IRQS is not set
CONFIG_LM_DISABLE_GPIOH_IRQS=y
CONFIG_LM_DISABLE_GPIOJ_IRQS=y
#
# LM3S SSI Configuration

View File

@ -123,14 +123,14 @@
#ifndef __ASSEMBLY__
/************************************************************************************
* Name: lm3s_ssiinitialize
* Name: lm_ssiinitialize
*
* Description:
* Called to configure SPI chip select GPIO pins for the LM3S6965 Eval Kit.
*
************************************************************************************/
extern void weak_function lm3s_ssiinitialize(void);
extern void weak_function lm_ssiinitialize(void);
#endif /* __ASSEMBLY__ */
#endif /* __CONFIGS_LM3S6965_EK_SRC_LM3S6965EK_INTERNAL_H */

View File

@ -61,7 +61,7 @@
************************************************************************************/
/************************************************************************************
* Name: lm3s_boardinitialize
* Name: lm_boardinitialize
*
* Description:
* All LM3S architectures must provide the following entry point. This entry point
@ -69,18 +69,18 @@
* and mapped but before any devices have been initialized.
************************************************************************************/
void lm3s_boardinitialize(void)
void lm_boardinitialize(void)
{
/* Configure SPI chip selects if 1) SSI is not disabled, and 2) the weak function
* lm3s_ssiinitialize() has been brought into the link.
* lm_ssiinitialize() has been brought into the link.
*/
/* The LM3S6965 Eval Kit microSD CS and OLED are on SSI0 (Duh! There is no SSI1) */
#if !defined(CONFIG_SSI0_DISABLE) /* || !defined(CONFIG_SSI1_DISABLE) */
if (lm3s_ssiinitialize)
if (lm_ssiinitialize)
{
lm3s_ssiinitialize();
lm_ssiinitialize();
}
#endif

View File

@ -63,17 +63,17 @@
************************************************************************************/
/************************************************************************************
* Name: lm3s_ethernetmac
* Name: lm_ethernetmac
*
* Description:
* For the Ethernet Eval Kits, the MAC address will be stored in the non-volatile
* USER0 and USER1 registers. If CONFIG_LM3S_BOARDMAC is defined, this function
* USER0 and USER1 registers. If CONFIG_LM_BOARDMAC is defined, this function
* will obtain the MAC address from these registers.
*
************************************************************************************/
#ifdef CONFIG_LM3S_BOARDMAC
void lm3s_ethernetmac(struct ether_addr *ethaddr)
#ifdef CONFIG_LM_BOARDMAC
void lm_ethernetmac(struct ether_addr *ethaddr)
{
uint32_t user0;
uint32_t user1;

View File

@ -72,7 +72,7 @@
/* Dump GPIO registers */
#ifdef LED_DEBUG
# define led_dumpgpio(m) lm3s_dumpgpio(LED_GPIO, m)
# define led_dumpgpio(m) lm_dumpgpio(LED_GPIO, m)
#else
# define led_dumpgpio(m)
#endif
@ -102,9 +102,9 @@ void up_ledinit(void)
/* Configure Port E, Bit 1 as an output, initial value=OFF */
led_dumpgpio("up_ledinit before lm3s_configgpio()");
lm3s_configgpio(LED_GPIO);
led_dumpgpio("up_ledinit after lm3s_configgpio()");
led_dumpgpio("up_ledinit before lm_configgpio()");
lm_configgpio(LED_GPIO);
led_dumpgpio("up_ledinit after lm_configgpio()");
g_nest = 0;
}
@ -128,9 +128,9 @@ void up_ledon(int led)
g_nest++;
case LED_IRQSENABLED:
case LED_STACKCREATED:
led_dumpgpio("up_ledon: before lm3s_gpiowrite()");
lm3s_gpiowrite(LED_GPIO, false);
led_dumpgpio("up_ledon: after lm3s_gpiowrite()");
led_dumpgpio("up_ledon: before lm_gpiowrite()");
lm_gpiowrite(LED_GPIO, false);
led_dumpgpio("up_ledon: after lm_gpiowrite()");
break;
}
}
@ -156,9 +156,9 @@ void up_ledoff(int led)
case LED_PANIC:
if (--g_nest <= 0)
{
led_dumpgpio("up_ledoff: before lm3s_gpiowrite()");
lm3s_gpiowrite(LED_GPIO, true);
led_dumpgpio("up_ledoff: after lm3s_gpiowrite()");
led_dumpgpio("up_ledoff: before lm_gpiowrite()");
lm_gpiowrite(LED_GPIO, true);
led_dumpgpio("up_ledoff: after lm_gpiowrite()");
}
break;
}

View File

@ -72,8 +72,8 @@
#ifdef CONFIG_LCD_RITDEBUG
# define ritdbg(format, arg...) vdbg(format, ##arg)
# define oleddc_dumpgpio(m) lm3s_dumpgpio(OLEDDC_GPIO, m)
# define oledcs_dumpgpio(m) lm3s_dumpgpio(OLEDCS_GPIO, m)
# define oleddc_dumpgpio(m) lm_dumpgpio(OLEDDC_GPIO, m)
# define oledcs_dumpgpio(m) lm_dumpgpio(OLEDCS_GPIO, m)
#else
# define ritdbg(x...)
# define oleddc_dumpgpio(m)
@ -102,8 +102,8 @@ FAR struct lcd_dev_s *up_nxdrvinit(unsigned int devno)
oledcs_dumpgpio("up_nxdrvinit: After OLEDCS setup");
oleddc_dumpgpio("up_nxdrvinit: On entry");
lm3s_configgpio(OLEDDC_GPIO); /* PC7: OLED display data/control select (D/Cn) */
lm3s_configgpio(OLEDEN_GPIO); /* PC6: Enable +15V needed by OLED (EN+15V) */
lm_configgpio(OLEDDC_GPIO); /* PC7: OLED display data/control select (D/Cn) */
lm_configgpio(OLEDEN_GPIO); /* PC6: Enable +15V needed by OLED (EN+15V) */
oleddc_dumpgpio("up_nxdrvinit: After OLEDDC/EN setup");
@ -137,7 +137,7 @@ FAR struct lcd_dev_s *up_nxdrvinit(unsigned int devno)
}
/******************************************************************************
* Name: lm3s_spicmddata
* Name: lm_spicmddata
*
* Description:
* Set or clear the SD1329 D/Cn bit to select data (true) or command
@ -159,13 +159,13 @@ FAR struct lcd_dev_s *up_nxdrvinit(unsigned int devno)
*
******************************************************************************/
int lm3s_spicmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd)
int lm_spicmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd)
{
if (devid == SPIDEV_DISPLAY)
{
/* Set GPIO to 1 for data, 0 for command */
lm3s_gpiowrite(OLEDDC_GPIO, !cmd);
lm_gpiowrite(OLEDDC_GPIO, !cmd);
return OK;
}
return -ENODEV;

View File

@ -81,7 +81,7 @@
/* Dump GPIO registers */
#ifdef SSI_VERBOSE
# define ssi_dumpgpio(m) lm3s_dumpgpio(SDCCS_GPIO, m)
# define ssi_dumpgpio(m) lm_dumpgpio(SDCCS_GPIO, m)
#else
# define ssi_dumpgpio(m)
#endif
@ -95,33 +95,33 @@
************************************************************************************/
/************************************************************************************
* Name: lm3s_ssiinitialize
* Name: lm_ssiinitialize
*
* Description:
* Called to configure SPI chip select GPIO pins for the LM3S6965 Eval Kit.
*
************************************************************************************/
void weak_function lm3s_ssiinitialize(void)
void weak_function lm_ssiinitialize(void)
{
/* Configure the SPI-based microSD CS GPIO */
ssi_dumpgpio("lm3s_ssiinitialize() Entry)");
lm3s_configgpio(SDCCS_GPIO);
ssi_dumpgpio("lm_ssiinitialize() Entry)");
lm_configgpio(SDCCS_GPIO);
#ifdef CONFIG_NX_LCDDRIVER
lm3s_configgpio(OLEDCS_GPIO);
lm_configgpio(OLEDCS_GPIO);
#endif
ssi_dumpgpio("lm3s_ssiinitialize() Exit");
ssi_dumpgpio("lm_ssiinitialize() Exit");
}
/****************************************************************************
* The external functions, lm3s_spiselect and lm3s_spistatus must be provided
* The external functions, lm_spiselect and lm_spistatus must be provided
* by board-specific logic. The are implementations of the select and status
* methods SPI interface defined by struct spi_ops_s (see include/nuttx/spi.h).
* All othermethods (including up_spiinitialize()) are provided by common
* logic. To use this common SPI logic on your board:
*
* 1. Provide lm3s_spiselect() and lm3s_spistatus() functions in your
* 1. Provide lm_spiselect() and lm_spistatus() functions in your
* board-specific logic. This function will perform chip selection and
* status operations using GPIOs in the way your board is configured.
* 2. Add a call to up_spiinitialize() in your low level initialization
@ -133,29 +133,29 @@ void weak_function lm3s_ssiinitialize(void)
*
****************************************************************************/
void lm3s_spiselect(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected)
void lm_spiselect(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected)
{
ssidbg("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert");
ssi_dumpgpio("lm3s_spiselect() Entry");
ssi_dumpgpio("lm_spiselect() Entry");
if (devid == SPIDEV_MMCSD)
{
/* Assert the CS pin to the card */
lm3s_gpiowrite(SDCCS_GPIO, !selected);
lm_gpiowrite(SDCCS_GPIO, !selected);
}
#ifdef CONFIG_NX_LCDDRIVER
else if (devid == SPIDEV_DISPLAY)
{
/* Assert the CS pin to the display */
lm3s_gpiowrite(OLEDCS_GPIO, !selected);
lm_gpiowrite(OLEDCS_GPIO, !selected);
}
#endif
ssi_dumpgpio("lm3s_spiselect() Exit");
ssi_dumpgpio("lm_spiselect() Exit");
}
uint8_t lm3s_spistatus(FAR struct spi_dev_s *dev, enum spi_dev_e devid)
uint8_t lm_spistatus(FAR struct spi_dev_s *dev, enum spi_dev_e devid)
{
ssidbg("Returning SPI_STATUS_PRESENT\n");
return SPI_STATUS_PRESENT;

View File

@ -126,12 +126,12 @@ GNU Toolchain Options
the CodeSourcery or devkitARM, you simply need to add one of the following
configuration options to your .config (or defconfig) file:
CONFIG_LM3S_CODESOURCERYW=y : CodeSourcery under Windows
CONFIG_LM3S_CODESOURCERYL=y : CodeSourcery under Linux
CONFIG_LM3S_DEVKITARM=y : devkitARM under Windows
CONFIG_LM3S_BUILDROOT=y : NuttX buildroot under Linux or Cygwin (default)
CONFIG_LM_CODESOURCERYW=y : CodeSourcery under Windows
CONFIG_LM_CODESOURCERYL=y : CodeSourcery under Linux
CONFIG_LM_DEVKITARM=y : devkitARM under Windows
CONFIG_LM_BUILDROOT=y : NuttX buildroot under Linux or Cygwin (default)
If you are not using CONFIG_LM3S_BUILDROOT, then you may also have to modify
If you are not using CONFIG_LM_BUILDROOT, then you may also have to modify
the PATH in the setenv.h file if your make cannot find the tools.
NOTE: the CodeSourcery (for Windows) and devkitARM are Windows native toolchains.
@ -399,15 +399,15 @@ Stellaris LM3S8962 Evaluation Kit Configuration Options
Additional interrupt support can be disabled if desired to reduce memory
footprint.
CONFIG_LM3S_DISABLE_GPIOA_IRQS=n
CONFIG_LM3S_DISABLE_GPIOB_IRQS=n
CONFIG_LM3S_DISABLE_GPIOC_IRQS=n
CONFIG_LM3S_DISABLE_GPIOD_IRQS=n
CONFIG_LM3S_DISABLE_GPIOE_IRQS=n
CONFIG_LM3S_DISABLE_GPIOF_IRQS=n
CONFIG_LM3S_DISABLE_GPIOG_IRQS=n
CONFIG_LM3S_DISABLE_GPIOH_IRQS=n
CONFIG_LM3S_DISABLE_GPIOJ_IRQS=y
CONFIG_LM_DISABLE_GPIOA_IRQS=n
CONFIG_LM_DISABLE_GPIOB_IRQS=n
CONFIG_LM_DISABLE_GPIOC_IRQS=n
CONFIG_LM_DISABLE_GPIOD_IRQS=n
CONFIG_LM_DISABLE_GPIOE_IRQS=n
CONFIG_LM_DISABLE_GPIOF_IRQS=n
CONFIG_LM_DISABLE_GPIOG_IRQS=n
CONFIG_LM_DISABLE_GPIOH_IRQS=n
CONFIG_LM_DISABLE_GPIOJ_IRQS=y
LM3S6818 specific device driver settings
@ -432,18 +432,18 @@ Stellaris LM3S8962 Evaluation Kit Configuration Options
value is large, then larger values of this setting may cause
Rx FIFO overrun errors. Default: half of the Tx FIFO size (4).
CONFIG_LM3S_ETHERNET - This must be set (along with CONFIG_NET)
CONFIG_LM_ETHERNET - This must be set (along with CONFIG_NET)
to build the LM3S Ethernet driver
CONFIG_LM3S_ETHLEDS - Enable to use Ethernet LEDs on the board.
CONFIG_LM3S_BOARDMAC - If the board-specific logic can provide
CONFIG_LM_ETHLEDS - Enable to use Ethernet LEDs on the board.
CONFIG_LM_BOARDMAC - If the board-specific logic can provide
a MAC address (via lm_ethernetmac()), then this should be selected.
CONFIG_LM3S_ETHHDUPLEX - Set to force half duplex operation
CONFIG_LM3S_ETHNOAUTOCRC - Set to suppress auto-CRC generation
CONFIG_LM3S_ETHNOPAD - Set to suppress Tx padding
CONFIG_LM3S_MULTICAST - Set to enable multicast frames
CONFIG_LM3S_PROMISCUOUS - Set to enable promiscuous mode
CONFIG_LM3S_BADCRC - Set to enable bad CRC rejection.
CONFIG_LM3S_DUMPPACKET - Dump each packet received/sent to the console.
CONFIG_LM_ETHHDUPLEX - Set to force half duplex operation
CONFIG_LM_ETHNOAUTOCRC - Set to suppress auto-CRC generation
CONFIG_LM_ETHNOPAD - Set to suppress Tx padding
CONFIG_LM_MULTICAST - Set to enable multicast frames
CONFIG_LM_PROMISCUOUS - Set to enable promiscuous mode
CONFIG_LM_BADCRC - Set to enable bad CRC rejection.
CONFIG_LM_DUMPPACKET - Dump each packet received/sent to the console.
Configurations
^^^^^^^^^^^^^^

View File

@ -112,7 +112,7 @@
#ifndef __ASSEMBLY__
/************************************************************************************
* Name: lm3s_boardinitialize
* Name: lm_boardinitialize
*
* Description:
* All LM3S architectures must provide the following entry point. This entry point
@ -121,21 +121,21 @@
*
************************************************************************************/
extern void lm3s_boardinitialize(void);
extern void lm_boardinitialize(void);
/************************************************************************************
* Name: lm3s_ethernetmac
* Name: lm_ethernetmac
*
* Description:
* For the Ethernet Eval Kits, the MAC address will be stored in the non-volatile
* USER0 and USER1 registers. If CONFIG_LM3S_BOARDMAC is defined, this function
* USER0 and USER1 registers. If CONFIG_LM_BOARDMAC is defined, this function
* will obtain the MAC address from these registers.
*
************************************************************************************/
#ifdef CONFIG_LM3S_BOARDMAC
#ifdef CONFIG_LM_BOARDMAC
struct ether_addr;
extern void lm3s_ethernetmac(struct ether_addr *ethaddr);
extern void lm_ethernetmac(struct ether_addr *ethaddr);
#endif
#endif /* __ASSEMBLY__ */

View File

@ -56,32 +56,32 @@ CONFIG_ARCH_CALIBRATION=n
#
# Identify toolchain and linker options
#
CONFIG_LM3S_CODESOURCERYW=n
CONFIG_LM3S_CODESOURCERYL=n
CONFIG_LM3S_DEVKITARM=n
CONFIG_LM3S_BUILDROOT=y
CONFIG_LM3S_DFU=y
CONFIG_LM_CODESOURCERYW=n
CONFIG_LM_CODESOURCERYL=n
CONFIG_LM_DEVKITARM=n
CONFIG_LM_BUILDROOT=y
CONFIG_LM_DFU=y
#
# Disable support for interrupts on GPIOH and GPIOJ which do not
# exist on the LM3S6B96. Additional interrupt support can be
# disabled if desired to reduce memory footprint.
CONFIG_LM3S_DISABLE_GPIOA_IRQS=n
CONFIG_LM3S_DISABLE_GPIOB_IRQS=n
CONFIG_LM3S_DISABLE_GPIOC_IRQS=n
CONFIG_LM3S_DISABLE_GPIOD_IRQS=n
CONFIG_LM3S_DISABLE_GPIOE_IRQS=n
CONFIG_LM3S_DISABLE_GPIOF_IRQS=n
CONFIG_LM3S_DISABLE_GPIOG_IRQS=n
CONFIG_LM3S_DISABLE_GPIOH_IRQS=y
CONFIG_LM3S_DISABLE_GPIOJ_IRQS=y
CONFIG_LM_DISABLE_GPIOA_IRQS=n
CONFIG_LM_DISABLE_GPIOB_IRQS=n
CONFIG_LM_DISABLE_GPIOC_IRQS=n
CONFIG_LM_DISABLE_GPIOD_IRQS=n
CONFIG_LM_DISABLE_GPIOE_IRQS=n
CONFIG_LM_DISABLE_GPIOF_IRQS=n
CONFIG_LM_DISABLE_GPIOG_IRQS=n
CONFIG_LM_DISABLE_GPIOH_IRQS=y
CONFIG_LM_DISABLE_GPIOJ_IRQS=y
#
# LM3S8962 specific serial device driver settings
#
CONFIG_LM3S_UART0=y
CONFIG_LM3S_UART1=n
CONFIG_LM3S_UART2=n
CONFIG_LM_UART0=y
CONFIG_LM_UART1=n
CONFIG_LM_UART2=n
CONFIG_UART0_SERIAL_CONSOLE=y
CONFIG_UART1_SERIAL_CONSOLE=n
CONFIG_UART2_SERIAL_CONSOLE=n
@ -115,16 +115,16 @@ CONFIG_SSI_POLLWAIT=y
#
# LM3S8962 specific serial device driver settings
#
CONFIG_LM3S_ETHERNET=y
CONFIG_LM3S_ETHLEDS=n
CONFIG_LM3S_BOARDMAC=n
CONFIG_LM3S_ETHHDUPLEX=n
CONFIG_LM3S_ETHNOAUTOCRC=n
CONFIG_LM3S_ETHNOPAD=n
CONFIG_LM3S_MULTICAST=n
CONFIG_LM3S_PROMISCUOUS=n
CONFIG_LM3S_BADCRC=n
CONFIG_LM3S_DUMPPACKET=n
CONFIG_LM_ETHERNET=y
CONFIG_LM_ETHLEDS=n
CONFIG_LM_BOARDMAC=n
CONFIG_LM_ETHHDUPLEX=n
CONFIG_LM_ETHNOAUTOCRC=n
CONFIG_LM_ETHNOPAD=n
CONFIG_LM_MULTICAST=n
CONFIG_LM_PROMISCUOUS=n
CONFIG_LM_BADCRC=n
CONFIG_LM_DUMPPACKET=n
#
# General build options

View File

@ -56,32 +56,32 @@ CONFIG_ARCH_CALIBRATION=n
#
# Identify toolchain and linker options
#
CONFIG_LM3S_CODESOURCERYW=n
CONFIG_LM3S_CODESOURCERYL=n
CONFIG_LM3S_DEVKITARM=n
CONFIG_LM3S_BUILDROOT=y
CONFIG_LM3S_DFU=y
CONFIG_LM_CODESOURCERYW=n
CONFIG_LM_CODESOURCERYL=n
CONFIG_LM_DEVKITARM=n
CONFIG_LM_BUILDROOT=y
CONFIG_LM_DFU=y
#
# Disable support for interrupts on GPIOH and GPIOJ which do not
# exist on the LM3S6B96. Additional interrupt support can be
# disabled if desired to reduce memory footprint.
CONFIG_LM3S_DISABLE_GPIOA_IRQS=n
CONFIG_LM3S_DISABLE_GPIOB_IRQS=n
CONFIG_LM3S_DISABLE_GPIOC_IRQS=n
CONFIG_LM3S_DISABLE_GPIOD_IRQS=n
CONFIG_LM3S_DISABLE_GPIOE_IRQS=n
CONFIG_LM3S_DISABLE_GPIOF_IRQS=n
CONFIG_LM3S_DISABLE_GPIOG_IRQS=n
CONFIG_LM3S_DISABLE_GPIOH_IRQS=y
CONFIG_LM3S_DISABLE_GPIOJ_IRQS=y
CONFIG_LM_DISABLE_GPIOA_IRQS=n
CONFIG_LM_DISABLE_GPIOB_IRQS=n
CONFIG_LM_DISABLE_GPIOC_IRQS=n
CONFIG_LM_DISABLE_GPIOD_IRQS=n
CONFIG_LM_DISABLE_GPIOE_IRQS=n
CONFIG_LM_DISABLE_GPIOF_IRQS=n
CONFIG_LM_DISABLE_GPIOG_IRQS=n
CONFIG_LM_DISABLE_GPIOH_IRQS=y
CONFIG_LM_DISABLE_GPIOJ_IRQS=y
#
# LM3S8962 specific serial device driver settings
#
CONFIG_LM3S_UART0=y
CONFIG_LM3S_UART1=n
CONFIG_LM3S_UART2=n
CONFIG_LM_UART0=y
CONFIG_LM_UART1=n
CONFIG_LM_UART2=n
CONFIG_UART0_SERIAL_CONSOLE=y
CONFIG_UART1_SERIAL_CONSOLE=n
CONFIG_UART2_SERIAL_CONSOLE=n
@ -115,16 +115,16 @@ CONFIG_SSI_POLLWAIT=y
#
# LM3S8962 specific serial device driver settings
#
CONFIG_LM3S_ETHERNET=n
CONFIG_LM3S_ETHLEDS=n
CONFIG_LM3S_BOARDMAC=y
CONFIG_LM3S_ETHHDUPLEX=n
CONFIG_LM3S_ETHNOAUTOCRC=n
CONFIG_LM3S_ETHNOPAD=n
CONFIG_LM3S_MULTICAST=n
CONFIG_LM3S_PROMISCUOUS=n
CONFIG_LM3S_BADCRC=n
CONFIG_LM3S_DUMPPACKET=n
CONFIG_LM_ETHERNET=n
CONFIG_LM_ETHLEDS=n
CONFIG_LM_BOARDMAC=y
CONFIG_LM_ETHHDUPLEX=n
CONFIG_LM_ETHNOAUTOCRC=n
CONFIG_LM_ETHNOPAD=n
CONFIG_LM_MULTICAST=n
CONFIG_LM_PROMISCUOUS=n
CONFIG_LM_BADCRC=n
CONFIG_LM_DUMPPACKET=n
#
# General build options

View File

@ -56,32 +56,32 @@ CONFIG_ARCH_CALIBRATION=n
#
# Identify toolchain and linker options
#
CONFIG_LM3S_CODESOURCERYW=n
CONFIG_LM3S_CODESOURCERYL=n
CONFIG_LM3S_DEVKITARM=n
CONFIG_LM3S_BUILDROOT=y
CONFIG_LM3S_DFU=y
CONFIG_LM_CODESOURCERYW=n
CONFIG_LM_CODESOURCERYL=n
CONFIG_LM_DEVKITARM=n
CONFIG_LM_BUILDROOT=y
CONFIG_LM_DFU=y
#
# Disable support for interrupts on GPIOH and GPIOJ which do not
# exist on the LM3S6B96. Additional interrupt support can be
# disabled if desired to reduce memory footprint.
CONFIG_LM3S_DISABLE_GPIOA_IRQS=n
CONFIG_LM3S_DISABLE_GPIOB_IRQS=n
CONFIG_LM3S_DISABLE_GPIOC_IRQS=n
CONFIG_LM3S_DISABLE_GPIOD_IRQS=n
CONFIG_LM3S_DISABLE_GPIOE_IRQS=n
CONFIG_LM3S_DISABLE_GPIOF_IRQS=n
CONFIG_LM3S_DISABLE_GPIOG_IRQS=n
CONFIG_LM3S_DISABLE_GPIOH_IRQS=y
CONFIG_LM3S_DISABLE_GPIOJ_IRQS=y
CONFIG_LM_DISABLE_GPIOA_IRQS=n
CONFIG_LM_DISABLE_GPIOB_IRQS=n
CONFIG_LM_DISABLE_GPIOC_IRQS=n
CONFIG_LM_DISABLE_GPIOD_IRQS=n
CONFIG_LM_DISABLE_GPIOE_IRQS=n
CONFIG_LM_DISABLE_GPIOF_IRQS=n
CONFIG_LM_DISABLE_GPIOG_IRQS=n
CONFIG_LM_DISABLE_GPIOH_IRQS=y
CONFIG_LM_DISABLE_GPIOJ_IRQS=y
#
# LM3S8962 specific serial device driver settings
#
CONFIG_LM3S_UART0=y
CONFIG_LM3S_UART1=n
CONFIG_LM3S_UART2=n
CONFIG_LM_UART0=y
CONFIG_LM_UART1=n
CONFIG_LM_UART2=n
CONFIG_UART0_SERIAL_CONSOLE=y
CONFIG_UART1_SERIAL_CONSOLE=n
CONFIG_UART2_SERIAL_CONSOLE=n
@ -115,16 +115,16 @@ CONFIG_SSI_POLLWAIT=y
#
# LM3S8962 specific serial device driver settings
#
CONFIG_LM3S_ETHERNET=n
CONFIG_LM3S_ETHLEDS=n
CONFIG_LM3S_BOARDMAC=y
CONFIG_LM3S_ETHHDUPLEX=n
CONFIG_LM3S_ETHNOAUTOCRC=n
CONFIG_LM3S_ETHNOPAD=n
CONFIG_LM3S_MULTICAST=n
CONFIG_LM3S_PROMISCUOUS=n
CONFIG_LM3S_BADCRC=n
CONFIG_LM3S_DUMPPACKET=n
CONFIG_LM_ETHERNET=n
CONFIG_LM_ETHLEDS=n
CONFIG_LM_BOARDMAC=y
CONFIG_LM_ETHHDUPLEX=n
CONFIG_LM_ETHNOAUTOCRC=n
CONFIG_LM_ETHNOPAD=n
CONFIG_LM_MULTICAST=n
CONFIG_LM_PROMISCUOUS=n
CONFIG_LM_BADCRC=n
CONFIG_LM_DUMPPACKET=n
#
# General build options

View File

@ -123,14 +123,14 @@
#ifndef __ASSEMBLY__
/************************************************************************************
* Name: lm3s_ssiinitialize
* Name: lm_ssiinitialize
*
* Description:
* Called to configure SPI chip select GPIO pins for the LM3S8962 Eval Kit.
*
************************************************************************************/
extern void weak_function lm3s_ssiinitialize(void);
extern void weak_function lm_ssiinitialize(void);
#endif /* __ASSEMBLY__ */
#endif /* __CONFIGS_LM3S8962_EK_SRC_LM3S8962EK_INTERNAL_H */

View File

@ -61,7 +61,7 @@
************************************************************************************/
/************************************************************************************
* Name: lm3s_boardinitialize
* Name: lm_boardinitialize
*
* Description:
* All LM3S architectures must provide the following entry point. This entry point
@ -69,18 +69,18 @@
* and mapped but before any devices have been initialized.
************************************************************************************/
void lm3s_boardinitialize(void)
void lm_boardinitialize(void)
{
/* Configure SPI chip selects if 1) SSI is not disabled, and 2) the weak function
* lm3s_ssiinitialize() has been brought into the link.
* lm_ssiinitialize() has been brought into the link.
*/
/* The LM3S8962 Eval Kit microSD CS and OLED are on SSI0 (Duh! There is no SSI1) */
#if !defined(CONFIG_SSI0_DISABLE) /* || !defined(CONFIG_SSI1_DISABLE) */
if (lm3s_ssiinitialize)
if (lm_ssiinitialize)
{
lm3s_ssiinitialize();
lm_ssiinitialize();
}
#endif

View File

@ -63,17 +63,17 @@
************************************************************************************/
/************************************************************************************
* Name: lm3s_ethernetmac
* Name: lm_ethernetmac
*
* Description:
* For the Ethernet Eval Kits, the MAC address will be stored in the non-volatile
* USER0 and USER1 registers. If CONFIG_LM3S_BOARDMAC is defined, this function
* USER0 and USER1 registers. If CONFIG_LM_BOARDMAC is defined, this function
* will obtain the MAC address from these registers.
*
************************************************************************************/
#ifdef CONFIG_LM3S_BOARDMAC
void lm3s_ethernetmac(struct ether_addr *ethaddr)
#ifdef CONFIG_LM_BOARDMAC
void lm_ethernetmac(struct ether_addr *ethaddr)
{
uint32_t user0;
uint32_t user1;

View File

@ -72,7 +72,7 @@
/* Dump GPIO registers */
#ifdef LED_DEBUG
# define led_dumpgpio(m) lm3s_dumpgpio(LED_GPIO, m)
# define led_dumpgpio(m) lm_dumpgpio(LED_GPIO, m)
#else
# define led_dumpgpio(m)
#endif
@ -102,9 +102,9 @@ void up_ledinit(void)
/* Configure Port E, Bit 1 as an output, initial value=OFF */
led_dumpgpio("up_ledinit before lm3s_configgpio()");
lm3s_configgpio(LED_GPIO);
led_dumpgpio("up_ledinit after lm3s_configgpio()");
led_dumpgpio("up_ledinit before lm_configgpio()");
lm_configgpio(LED_GPIO);
led_dumpgpio("up_ledinit after lm_configgpio()");
g_nest = 0;
}
@ -128,9 +128,9 @@ void up_ledon(int led)
g_nest++;
case LED_IRQSENABLED:
case LED_STACKCREATED:
led_dumpgpio("up_ledon: before lm3s_gpiowrite()");
lm3s_gpiowrite(LED_GPIO, false);
led_dumpgpio("up_ledon: after lm3s_gpiowrite()");
led_dumpgpio("up_ledon: before lm_gpiowrite()");
lm_gpiowrite(LED_GPIO, false);
led_dumpgpio("up_ledon: after lm_gpiowrite()");
break;
}
}
@ -156,9 +156,9 @@ void up_ledoff(int led)
case LED_PANIC:
if (--g_nest <= 0)
{
led_dumpgpio("up_ledoff: before lm3s_gpiowrite()");
lm3s_gpiowrite(LED_GPIO, true);
led_dumpgpio("up_ledoff: after lm3s_gpiowrite()");
led_dumpgpio("up_ledoff: before lm_gpiowrite()");
lm_gpiowrite(LED_GPIO, true);
led_dumpgpio("up_ledoff: after lm_gpiowrite()");
}
break;
}

View File

@ -72,8 +72,8 @@
#ifdef CONFIG_LCD_RITDEBUG
# define ritdbg(format, arg...) vdbg(format, ##arg)
# define oleddc_dumpgpio(m) lm3s_dumpgpio(OLEDDC_GPIO, m)
# define oledcs_dumpgpio(m) lm3s_dumpgpio(OLEDCS_GPIO, m)
# define oleddc_dumpgpio(m) lm_dumpgpio(OLEDDC_GPIO, m)
# define oledcs_dumpgpio(m) lm_dumpgpio(OLEDCS_GPIO, m)
#else
# define ritdbg(x...)
# define oleddc_dumpgpio(m)
@ -102,8 +102,8 @@ FAR struct lcd_dev_s *up_nxdrvinit(unsigned int devno)
oledcs_dumpgpio("up_nxdrvinit: After OLEDCS setup");
oleddc_dumpgpio("up_nxdrvinit: On entry");
lm3s_configgpio(OLEDDC_GPIO); /* PC7: OLED display data/control select (D/Cn) */
lm3s_configgpio(OLEDEN_GPIO); /* PC6: Enable +15V needed by OLED (EN+15V) */
lm_configgpio(OLEDDC_GPIO); /* PC7: OLED display data/control select (D/Cn) */
lm_configgpio(OLEDEN_GPIO); /* PC6: Enable +15V needed by OLED (EN+15V) */
oleddc_dumpgpio("up_nxdrvinit: After OLEDDC/EN setup");
@ -137,7 +137,7 @@ FAR struct lcd_dev_s *up_nxdrvinit(unsigned int devno)
}
/******************************************************************************
* Name: lm3s_spicmddata
* Name: lm_spicmddata
*
* Description:
* Set or clear the SD1329 D/Cn bit to select data (true) or command
@ -159,13 +159,13 @@ FAR struct lcd_dev_s *up_nxdrvinit(unsigned int devno)
*
******************************************************************************/
int lm3s_spicmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd)
int lm_spicmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd)
{
if (devid == SPIDEV_DISPLAY)
{
/* Set GPIO to 1 for data, 0 for command */
lm3s_gpiowrite(OLEDDC_GPIO, !cmd);
lm_gpiowrite(OLEDDC_GPIO, !cmd);
return OK;
}
return -ENODEV;

View File

@ -81,7 +81,7 @@
/* Dump GPIO registers */
#ifdef SSI_VERBOSE
# define ssi_dumpgpio(m) lm3s_dumpgpio(SDCCS_GPIO, m)
# define ssi_dumpgpio(m) lm_dumpgpio(SDCCS_GPIO, m)
#else
# define ssi_dumpgpio(m)
#endif
@ -95,33 +95,33 @@
************************************************************************************/
/************************************************************************************
* Name: lm3s_ssiinitialize
* Name: lm_ssiinitialize
*
* Description:
* Called to configure SPI chip select GPIO pins for the LM3S8962 Eval Kit.
*
************************************************************************************/
void weak_function lm3s_ssiinitialize(void)
void weak_function lm_ssiinitialize(void)
{
/* Configure the SPI-based microSD CS GPIO */
ssi_dumpgpio("lm3s_ssiinitialize() Entry)");
lm3s_configgpio(SDCCS_GPIO);
ssi_dumpgpio("lm_ssiinitialize() Entry)");
lm_configgpio(SDCCS_GPIO);
#ifdef CONFIG_NX_LCDDRIVER
lm3s_configgpio(OLEDCS_GPIO);
lm_configgpio(OLEDCS_GPIO);
#endif
ssi_dumpgpio("lm3s_ssiinitialize() Exit");
ssi_dumpgpio("lm_ssiinitialize() Exit");
}
/****************************************************************************
* The external functions, lm3s_spiselect and lm3s_spistatus must be provided
* The external functions, lm_spiselect and lm_spistatus must be provided
* by board-specific logic. The are implementations of the select and status
* methods SPI interface defined by struct spi_ops_s (see include/nuttx/spi.h).
* All othermethods (including up_spiinitialize()) are provided by common
* logic. To use this common SPI logic on your board:
*
* 1. Provide lm3s_spiselect() and lm3s_spistatus() functions in your
* 1. Provide lm_spiselect() and lm_spistatus() functions in your
* board-specific logic. This function will perform chip selection and
* status operations using GPIOs in the way your board is configured.
* 2. Add a call to up_spiinitialize() in your low level initialization
@ -133,29 +133,29 @@ void weak_function lm3s_ssiinitialize(void)
*
****************************************************************************/
void lm3s_spiselect(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected)
void lm_spiselect(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected)
{
ssidbg("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert");
ssi_dumpgpio("lm3s_spiselect() Entry");
ssi_dumpgpio("lm_spiselect() Entry");
if (devid == SPIDEV_MMCSD)
{
/* Assert the CS pin to the card */
lm3s_gpiowrite(SDCCS_GPIO, !selected);
lm_gpiowrite(SDCCS_GPIO, !selected);
}
#ifdef CONFIG_NX_LCDDRIVER
else if (devid == SPIDEV_DISPLAY)
{
/* Assert the CS pin to the display */
lm3s_gpiowrite(OLEDCS_GPIO, !selected);
lm_gpiowrite(OLEDCS_GPIO, !selected);
}
#endif
ssi_dumpgpio("lm3s_spiselect() Exit");
ssi_dumpgpio("lm_spiselect() Exit");
}
uint8_t lm3s_spistatus(FAR struct spi_dev_s *dev, enum spi_dev_e devid)
uint8_t lm_spistatus(FAR struct spi_dev_s *dev, enum spi_dev_e devid)
{
ssidbg("Returning SPI_STATUS_PRESENT\n");
return SPI_STATUS_PRESENT;