From ee00fd9d222a61ca9a36197a0bd618f4ac36e7fd Mon Sep 17 00:00:00 2001 From: patacongo Date: Thu, 14 May 2009 18:55:22 +0000 Subject: Add basic lm3s6918 gpio support git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@1778 42af7a65-404d-4744-a932-0658087f49c3 --- nuttx/arch/arm/src/lm3s/Make.defs | 4 +- nuttx/arch/arm/src/lm3s/lm3s_ethernet.c | 8 +- nuttx/arch/arm/src/lm3s/lm3s_gpio.c | 832 ++++++++++++++++++++++++++++++ nuttx/arch/arm/src/lm3s/lm3s_internal.h | 93 ++-- nuttx/arch/arm/src/lm3s/lm3s_irq.c | 12 +- nuttx/arch/arm/src/lm3s/lm3s_lowputc.c | 16 - nuttx/arch/arm/src/lm3s/lm3s_start.c | 2 +- nuttx/arch/arm/src/lm3s/lm3s_syscontrol.h | 5 + nuttx/arch/arm/src/lm3s/lm3s_vectors.S | 3 +- 9 files changed, 915 insertions(+), 60 deletions(-) create mode 100644 nuttx/arch/arm/src/lm3s/lm3s_gpio.c (limited to 'nuttx/arch/arm') diff --git a/nuttx/arch/arm/src/lm3s/Make.defs b/nuttx/arch/arm/src/lm3s/Make.defs index 0684a35e7..9e9ea238e 100644 --- a/nuttx/arch/arm/src/lm3s/Make.defs +++ b/nuttx/arch/arm/src/lm3s/Make.defs @@ -43,11 +43,11 @@ CMN_CSRCS = up_allocateheap.c up_assert.c up_blocktask.c up_copystate.c \ up_prefetchabort.c up_releasepending.c up_releasestack.c \ up_reprioritizertr.c up_schedulesigaction.c \ up_sigdeliver.c up_syscall.c up_unblocktask.c \ - up_undefinedinsn.c up_usestack.c + up_undefinedinsn.c up_usestack.c up_doirq.c CHIP_ASRCS = lm3s_context.S CHIP_CSRCS = lm3s_start.c lm3s_syscontrol.c lm3s_irq.c lm3s_pendsv.c \ - lm3s_timerisr.c lm3s_lowputc.c lm3s_serial.c + lm3s_gpio.c lm3s_timerisr.c lm3s_lowputc.c lm3s_serial.c ifdef CONFIG_NET CHIP_CSRCS += lm3s_ethernet.c diff --git a/nuttx/arch/arm/src/lm3s/lm3s_ethernet.c b/nuttx/arch/arm/src/lm3s/lm3s_ethernet.c index 6e0081d15..b7aab1544 100644 --- a/nuttx/arch/arm/src/lm3s/lm3s_ethernet.c +++ b/nuttx/arch/arm/src/lm3s/lm3s_ethernet.c @@ -565,14 +565,10 @@ int lm3s_initialize(void) /* Enable Port F for Ethernet LEDs: LED0=Bit 3; LED1=Bit 2 */ #ifdef CONFIG_LM3S_ETHLEDS - /* Make sure that the GPIOF peripheral is enabled */ - - modifyreg32(LM3S_SYSCON_RCGC2_OFFSET, 0, SYSCON_RCGC2_GPIOF); - /* Configure the pins for the peripheral function */ - lm3s_configgpio(GPIO_FUNC_PERIPHERAL | GPIO_STRENGTH_2MA | GPIO_PADTYPE_STD | GPIO_PORTF | 2); - lm3s_configgpio(GPIO_FUNC_PERIPHERAL | GPIO_STRENGTH_2MA | GPIO_PADTYPE_STD | GPIO_PORTF | 3); + lm3s_configgpio(GPIO_ETHPHY_LED0 | GPIO_STRENGTH_2MA | GPIO_PADTYPE_STD); + lm3s_configgpio(GPIO_ETHPHY_LED1 | GPIO_STRENGTH_2MA | GPIO_PADTYPE_STD); #endif #warning "Missing logic" diff --git a/nuttx/arch/arm/src/lm3s/lm3s_gpio.c b/nuttx/arch/arm/src/lm3s/lm3s_gpio.c new file mode 100644 index 000000000..a69b4ec14 --- /dev/null +++ b/nuttx/arch/arm/src/lm3s/lm3s_gpio.c @@ -0,0 +1,832 @@ +/**************************************************************************** + * arch/arm/src/lm3s/lm3s_gpio.c + * arch/arm/src/chip/lm3s_gpio.c + * + * Copyright (C) 2009 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name NuttX nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include +#include + +#include +#include +#include + +#include + +#include "up_arch.h" +#include "os_internal.h" +#include "lm3s_internal.h" + +/**************************************************************************** + * Private Definitions + ****************************************************************************/ + +/* These definitions are part of the implementation of the GPIO pad + * configuration of Table 9-1 in the LM3S6918 data sheet. + */ + +#define AFSEL_SHIFT 5 +#define AFSEL_1 (1 << AFSEL_SHIFT) /* Set/clear bit in GPIO AFSEL register */ +#define AFSEL_0 0 +#define AFSEL_X 0 + +#define DIR_SHIFT 4 +#define DIR_1 (1 << DIR_SHIFT) /* Set/clear bit in GPIO DIR register */ +#define DIR_0 0 +#define DIR_X 0 + +#define ODR_SHIFT 3 +#define ODR_1 (1 << ODR_SHIFT) /* Set/clear bit in GPIO ODR register */ +#define ODR_0 0 +#define ODR_X 0 + +#define DEN_SHIFT 2 +#define DEN_1 (1 << DEN_SHIFT) /* Set/clear bit in GPIO DEN register */ +#define DEN_0 0 +#define DEN_X 0 + +#define PUR_SHIFT 2 +#define PUR_1 (1 << PUR_SHIFT) /* Set/clear bit in GPIO PUR register */ +#define PUR_0 0 +#define PUR_X 0 + +#define PDR_SHIFT 0 +#define PDR_1 (1 << PDR_SHIFT) /* Set/clear bit in GPIO PDR register */ +#define PDR_0 0 +#define PDR_X 0 + +#define GPIO_INPUT_SETBITS (AFSEL_0 | DIR_0 | ODR_0 | DEN_1 | PUR_X | PDR_X) +#define GPIO_INPUT_CLRBITS (AFSEL_1 | DIR_1 | ODR_1 | DEN_0 | PUR_X | PDR_X) + +#define GPIO_OUTPUT_SETBITS (AFSEL_0 | DIR_1 | ODR_0 | DEN_1 | PUR_X | PDR_X) +#define GPIO_OUTPUT_CLRBITS (AFSEL_1 | DIR_0 | ODR_1 | DEN_0 | PUR_X | PDR_X) + +#define GPIO_ODINPUT_SETBITS (AFSEL_0 | DIR_0 | ODR_1 | DEN_1 | PUR_X | PDR_X) +#define GPIO_ODINPUT_CLRBITS (AFSEL_1 | DIR_1 | ODR_0 | DEN_0 | PUR_X | PDR_X) + +#define GPIO_ODOUTPUT_SETBITS (AFSEL_0 | DIR_1 | ODR_1 | DEN_1 | PUR_X | PDR_X) +#define GPIO_ODOUTPUT_CLRBITS (AFSEL_1 | DIR_0 | ODR_0 | DEN_0 | PUR_X | PDR_X) + +#define GPIO_PFODIO_SETBITS (AFSEL_1 | DIR_X | ODR_1 | DEN_1 | PUR_X | PDR_X) +#define GPIO_PFODIO_CLRBITS (AFSEL_0 | DIR_X | ODR_0 | DEN_0 | PUR_X | PDR_X) + +#define GPIO_PFIO_SETBITS (AFSEL_1 | DIR_X | ODR_0 | DEN_1 | PUR_X | PDR_X) +#define GPIO_PFIO_CLRBITS (AFSEL_0 | DIR_X | ODR_1 | DEN_0 | PUR_X | PDR_X) + +#define GPIO_ANINPUT_SETBITS (AFSEL_0 | DIR_0 | ODR_0 | DEN_0 | PUR_0 | PDR_0) +#define GPIO_ANINPUT_CLRBITS (AFSEL_1 | DIR_1 | ODR_1 | DEN_1 | PUR_1 | PDR_1) + +#define GPIO_INTERRUPT_SETBITS (AFSEL_0 | DIR_0 | ODR_0 | DEN_1 | PUR_X | PDR_X) +#define GPIO_INTERRUPT_CLRBITS (AFSEL_1 | DIR_1 | ODR_1 | DEN_0 | PUR_X | PDR_X) + +/**************************************************************************** + * Private Types + ****************************************************************************/ + +struct gpio_func_s +{ + ubyte setbits; /* A set of GPIO register bits to set */ + ubyte clrbits; /* A set of GPIO register bits to clear */ +}; + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +static const struct gpio_func_s g_funcbits[] = +{ + {GPIO_INPUT_SETBITS, GPIO_INPUT_CLRBITS}, /* GPIO_FUNC_INPUT */ + {GPIO_OUTPUT_SETBITS, GPIO_OUTPUT_CLRBITS}, /* GPIO_FUNC_OUTPUT */ + {GPIO_ODINPUT_SETBITS, GPIO_ODINPUT_CLRBITS}, /* GPIO_FUNC_ODINPUT */ + {GPIO_ODOUTPUT_SETBITS, GPIO_ODOUTPUT_CLRBITS}, /* GPIO_FUNC_ODOUTPUT */ + {GPIO_PFODIO_SETBITS, GPIO_PFODIO_CLRBITS}, /* GPIO_FUNC_PFODIO */ + {GPIO_PFIO_SETBITS, GPIO_PFIO_CLRBITS}, /* GPIO_FUNC_PFIO */ + {GPIO_ANINPUT_SETBITS, GPIO_ANINPUT_CLRBITS}, /* GPIO_FUNC_ANINPUT */ + {GPIO_INTERRUPT_SETBITS, GPIO_INTERRUPT_CLRBITS}, /* GPIO_FUNC_INTERRUPT */ +}; + +static const uint32 g_gpiobase[] = +{ + LM3S_GPIOA_BASE, LM3S_GPIOB_BASE, LM3S_GPIOC_BASE, LM3S_GPIOD_BASE, + LM3S_GPIOE_BASE, LM3S_GPIOF_BASE, LM3S_GPIOG_BASE, LM3S_GPIOH_BASE, +}; + +/**************************************************************************** + * Public Data + ****************************************************************************/ + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: lm3s_gpiobaseaddress + * + * Description: + * Given a GPIO enumeration value, return the base address of the + * associated GPIO registers. + * + ****************************************************************************/ + +static inline uint32 lm3s_gpiobaseaddress(unsigned int port) +{ + return g_gpiobase[port & 7]; +} + +/**************************************************************************** + * Name: lm3s_gpiofunc + * + * Description: + * Configure GPIO registers for a specific function + * + ****************************************************************************/ + +static void lm3s_gpiofunc(uint32 base, uint32 pinno, const struct gpio_func_s *func) +{ + uint32 setbit; + uint32 clrbit; + uint32 regval; + + /* Set/clear/ignore the GPIO ODR bit. "The GPIO ODR register is the open drain + * control register. Setting a bit in this register enables the open drain + * configuration of the corresponding GPIO pad. When open drain mode is enabled, + * the corresponding bit should also be set in the GPIO Digital Input Enable + * (GPIO DEN) register ... Corresponding bits in the drive strength registers + * (GPIO DR2R, GPIO DR4R, GPIO DR8R, and GPIO SLR ) can be set to achieve the + * desired rise and fall times. The GPIO acts as an open drain input if the + * corresponding bit in the GPIO DIR register is set to 0; and as an open + * drain output when set to 1." + */ + + setbit = (((uint32)func->setbits >> ODR_SHIFT) & 1) << pinno; + clrbit = (((uint32)func->clrbits >> ODR_SHIFT) & 1) << pinno; + + regval = getreg32(base + LM3S_GPIO_ODR_OFFSET); + regval &= ~clrbit; + regval |= setbit; + putreg32(regval, base + LM3S_GPIO_ODR_OFFSET); + + /* Set/clear the GPIO PUR bit. "The GPIOPUR register is the pull-up control + * register. When a bit is set to 1, it enables a weak pull-up resistor on the + * corresponding GPIO signal. Setting a bit in GPIOPUR automatically clears the + * corresponding bit in the GPIO Pull-Down Select (GPIOPDR) register ..." + */ + + setbit = (((uint32)func->setbits >> PUR_SHIFT) & 1) << pinno; + clrbit = (((uint32)func->clrbits >> PUR_SHIFT) & 1) << pinno; + + if (setbit || clrbit) + { + regval = getreg32(base + LM3S_GPIO_PUR_OFFSET); + regval &= ~clrbit; + regval |= setbit; + putreg32(regval, base + LM3S_GPIO_PUR_OFFSET); + } + + /* Set/clear the GPIO PDR bit. "The GPIOPDR register is the pull-down control + * register. When a bit is set to 1, it enables a weak pull-down resistor on the + * corresponding GPIO signal. Setting a bit in GPIOPDR automatically clears + * the corresponding bit in the GPIO Pull-Up Select (GPIOPUR) register ..." + */ + + setbit = (((uint32)func->setbits >> PDR_SHIFT) & 1) << pinno; + clrbit = (((uint32)func->clrbits >> PDR_SHIFT) & 1) << pinno; + + if (setbit || clrbit) + { + regval = getreg32(base + LM3S_GPIO_PDR_OFFSET); + regval &= ~clrbit; + regval |= setbit; + putreg32(regval, base + LM3S_GPIO_PDR_OFFSET); + } + + /* Set/clear the GPIO DEN bit. "The GPIODEN register is the digital enable + * register. By default, with the exception of the GPIO signals used for JTAG/SWD + * function, all other GPIO signals are configured out of reset to be undriven + * (tristate). Their digital function is disabled; they do not drive a logic + * value on the pin and they do not allow the pin voltage into the GPIO receiver. + * To use the pin in a digital function (either GPIO or alternate function), the + * corresponding GPIODEN bit must be set." + */ + + setbit = (((uint32)func->setbits >> DEN_SHIFT) & 1) << pinno; + clrbit = (((uint32)func->clrbits >> DEN_SHIFT) & 1) << pinno; + + regval = getreg32(base + LM3S_GPIO_DEN_OFFSET); + regval &= ~clrbit; + regval |= setbit; + putreg32(regval, base + LM3S_GPIO_DEN_OFFSET); + + /* Set/clear/ignore the GPIO DIR bit. "The GPIODIR register is the data + * direction register. Bits set to 1 in the GPIODIR register configure + * the corresponding pin to be an output, while bits set to 0 configure the + * pins to be inputs. All bits are cleared by a reset, meaning all GPIO + * pins are inputs by default. + */ + + setbit = (((uint32)func->setbits >> DIR_SHIFT) & 1) << pinno; + clrbit = (((uint32)func->clrbits >> DIR_SHIFT) & 1) << pinno; + + regval = getreg32(base + LM3S_GPIO_DIR_OFFSET); + regval &= ~clrbit; + regval |= setbit; + putreg32(regval, base + LM3S_GPIO_DIR_OFFSET); + + /* Set/clear/ignore the GPIO AFSEL bit. "The GPIOAFSEL register is the mode + * control select register. Writing a 1 to any bit in this register selects + * the hardware control for the corresponding GPIO line. All bits are cleared + * by a reset, therefore no GPIO line is set to hardware control by default." + * + * NOTE: In order so set JTAG/SWD GPIOs, it is also necessary to lock, commit + * and unlock the GPIO. That is not implemented here. + */ + + setbit = (((uint32)func->setbits >> AFSEL_SHIFT) & 1) << pinno; + clrbit = (((uint32)func->clrbits >> AFSEL_SHIFT) & 1) << pinno; + + regval = getreg32(base + LM3S_GPIO_AFSEL_OFFSET); + regval &= ~clrbit; + regval |= setbit; + putreg32(regval, base + LM3S_GPIO_AFSEL_OFFSET); +} + +/**************************************************************************** + * Name: lm3s_gpiopadstrength + * + * Description: + * Set up pad strength and pull-ups + * + ****************************************************************************/ + +static inline void lm3s_gpiopadstrength(uint32 base, uint32 pin, uint32 cfgset) +{ + int strength = (cfgset & GPIO_STRENGTH_MASK) >> GPIO_STRENGTH_SHIFT; + uint32 regoffset; + uint32 regval; + uint32 slrset; + uint32 slrclr; + + /* Prepare bits to disable slew */ + + slrset = 0; + slrclr = pin; + + switch (strength) + { + case 0: /* 2mA pad drive strength */ + { + /* "The GPIODR2R register is the 2-mA drive control register. It + * allows for each GPIO signal in the port to be individually configured + * without affecting the other pads. When writing a DRV2 bit for a GPIO + * signal, the corresponding DRV4 bit in the GPIO DR4R register and the + * DRV8 bit in the GPIODR8R register are automatically cleared by hardware." + */ + + regoffset = LM3S_GPIOA_DR2R; + } + break; + + case 1: /* 4mA pad drive strength */ + { + /* "The GPIODR4R register is the 4-mA drive control register. It allows + * for each GPIO signal in the port to be individually configured without + * affecting the other pads. When writing the DRV4 bit for a GPIO signal, + * the corresponding DRV2 bit in the GPIO DR2R register and the DRV8 bit + * in the GPIO DR8R register are automatically cleared by hardware." + */ + + regoffset = LM3S_GPIOA_DR4R; + } + break; + + case 3: /* 8mA Pad drive with slew rate control */ + { + /* "The GPIOSLR register is the slew rate control register. Slew rate + * control is only available when using the 8-mA drive strength option + * via the GPIO 8-mA Drive Select (GPIODR8R) register..." + */ + + slrset = pin; + slrclr = 0; + } + /* Fall through */ + + case 2: /* 8mA pad drive strength (without slew rate control) */ + { + /* "The GPIODR8R register is the 8-mA drive control register. It + * allows for each GPIO signal in the port to be individually configured + * without affecting the other pads. When writing the DRV8 bit for a GPIO + * signal, the corresponding DRV2 bit in the GPIO DR2R register and the + * DRV4 bit in the GPIO DR4R register are automatically cleared by hardware." + */ + + regoffset = LM3S_GPIOA_DR8R; + } + break; + } + + /* Set the selected pad strength and set/clear optional slew rate control */ + + regval = getreg32(base + regoffset); + regval |= pin; + putreg32(regval, base + regoffset); + + regval = getreg32(base + LM3S_GPIO_SLR_OFFSET); + regval &= slrclr; + regval |= slrset; + putreg32(regval, base + LM3S_GPIO_SLR_OFFSET); +} + +/**************************************************************************** + * Name: lm3s_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 + * are optional for different function selections. + * + ****************************************************************************/ + +static inline void lm3s_gpiopadtype(uint32 base, uint32 pin, uint32 cfgset) +{ + int padtype = (cfgset & GPIO_PADTYPE_MASK) >> GPIO_PADTYPE_SHIFT; +#if 0 /* always overwritten by lm3s_gpiofunc */ + uint32 odrset; + uint32 odrclr; +#endif + uint32 purset; + uint32 purclr; + uint32 pdrset; + uint32 pdrclr; +#if 0 /* always overwritten by lm3s_gpiofunc */ + uint32 denset; + uint32 denclr; +#endif + uint32 regval; + + /* Assume digital GPIO function, push-pull with no pull-up or pull-down */ + +#if 0 /* always overwritten by lm3s_gpiofunc */ + odrset = 0; + odrclr = pin; +#endif + purset = 0; + purclr = pin; + pdrset = 0; + pdrclr = pin; +#if 0 /* always overwritten by lm3s_gpiofunc */ + denset = pin; + denclr = 0; +#endif + + switch (padtype) + { + case 0: /* Push-pull */ + default: + { + } + break; + + case 1: /* Push-pull with weak pull-up */ + { + purset = pin; + purclr = 0; + } + break; + case 2: /* Push-pull with weak pull-down */ + { + pdrset = pin; + pdrclr = 0; + } + break; + case 3: /* Open-drain */ + { +#if 0 /* always overwritten by lm3s_gpiofunc */ + odrset = pin; + odrclr = 0; +#endif + } + break; + case 4: /* Open-drain with weak pull-up */ + { +#if 0 /* always overwritten by lm3s_gpiofunc */ + odrset = pin; + odrclr = 0; +#endif + purset = pin; + purclr = 0; + } + break; + case 5: /* Open-drain with weak pull-down */ + { +#if 0 /* always overwritten by lm3s_gpiofunc */ + odrset = pin; + odrclr = 0; +#endif + pdrset = pin; + pdrclr = 0; + } + break; + case 6: /* Analog comparator */ + { +#if 0 /* always overwritten by lm3s_gpiofunc */ + denset = 0; + denclr = pin; +#endif + } + break; + } + + /* Set/clear the GPIO ODR bit. "The GPIO ODR register is the open drain + * control register. Setting a bit in this register enables the open drain + * configuration of the corresponding GPIO pad. When open drain mode is enabled, + * the corresponding bit should also be set in the GPIO Digital Input Enable + * (GPIO DEN) register ... Corresponding bits in the drive strength registers + * (GPIO DR2R, GPIO DR4R, GPIO DR8R, and GPIO SLR ) can be set to achieve the + * desired rise and fall times. The GPIO acts as an open drain input if the + * corresponding bit in the GPIO DIR register is set to 0; and as an open + * drain output when set to 1." + */ + +#if 0 /* always overwritten by lm3s_gpiofunc */ + regval = getreg32(base + LM3S_GPIO_ODR_OFFSET); + regval &= ~odrclr; + regval |= odrset; + putreg32(regval, base + LM3S_GPIO_ODR_OFFSET); +#endif + + /* Set/clear the GPIO PUR bit. "The GPIOPUR register is the pull-up control + * register. When a bit is set to 1, it enables a weak pull-up resistor on the + * corresponding GPIO signal. Setting a bit in GPIOPUR automatically clears the + * corresponding bit in the GPIO Pull-Down Select (GPIOPDR) register ..." + */ + + regval = getreg32(base + LM3S_GPIO_PUR_OFFSET); + regval &= ~purclr; + regval |= purset; + putreg32(regval, base + LM3S_GPIO_PUR_OFFSET); + + /* Set/clear the GPIO PDR bit. "The GPIOPDR register is the pull-down control + * register. When a bit is set to 1, it enables a weak pull-down resistor on the + * corresponding GPIO signal. Setting a bit in GPIOPDR automatically clears + * the corresponding bit in the GPIO Pull-Up Select (GPIOPUR) register ..." + */ + + regval = getreg32(base + LM3S_GPIO_PDR_OFFSET); + regval &= ~pdrclr; + regval |= pdrset; + putreg32(regval, base + LM3S_GPIO_PDR_OFFSET); + + /* Set/clear the GPIO DEN bit. "The GPIODEN register is the digital enable + * register. By default, with the exception of the GPIO signals used for JTAG/SWD + * function, all other GPIO signals are configured out of reset to be undriven + * (tristate). Their digital function is disabled; they do not drive a logic + * value on the pin and they do not allow the pin voltage into the GPIO receiver. + * To use the pin in a digital function (either GPIO or alternate function), the + * corresponding GPIODEN bit must be set." + */ + +#if 0 /* always overwritten by lm3s_gpiofunc */ + regval = getreg32(base + LM3S_GPIO_DEN_OFFSET); + regval &= ~denclr; + regval |= denset; + putreg32(regval, base + LM3S_GPIO_DEN_OFFSET); +#endif +} + +/**************************************************************************** + * Name: lm3s_initoutput + * + * Description: + * Set the GPIO output value + * + ****************************************************************************/ + +static inline void lm3s_initoutput(uint32 cfgset) +{ + boolean value = ((cfgset & GPIO_VALUE_MASK) != GPIO_VALUE_ZERO); + lm3s_gpiowrite(cfgset, value); +} + +/**************************************************************************** + * Name: lm3s_interrupt + * + * Description: + * Configure the interrupt pin. + * + ****************************************************************************/ + +static inline void lm3s_interrupt(uint32 base, uint32 pin, uint32 cfgset) +{ + int inttype = (cfgset & GPIO_INT_MASK) >> GPIO_INT_SHIFT; + uint32 regval; + uint32 isset; + uint32 isclr; + uint32 ibeset; + uint32 ibeclr; + uint32 iveset; + uint32 iveclr; + + /* Mask and clear the GPIO interrupt + * + * "The GPIOIM register is the interrupt mask register. Bits set to High in + * GPIO IM allow the corresponding pins to trigger their individual interrupts + * and the combined GPIO INTR line. Clearing a bit disables interrupt triggering + * on that pin. All bits are cleared by a reset." + */ + + regval = getreg32(base + LM3S_GPIO_IM_OFFSET); + regval &= ~pin; + putreg32(regval, base + LM3S_GPIO_IM_OFFSET); + + /* "The GPIOICR register is the interrupt clear register. Writing a 1 to a bit + * in this register clears the corresponding interrupt edge detection logic + * register. Writing a 0 has no effect." + */ + + regval = getreg32(base + LM3S_GPIO_ICR_OFFSET); + regval |= pin; + putreg32(regval, base + LM3S_GPIO_ICR_OFFSET); + + /* Assume rising edge */ + + isset = 0; /* Not level sensed */ + isclr = pin; + ibeset = 0; /* Single edge */ + ibeclr = pin; + iveset = pin; /* Rising edge or high levels*/ + iveclr = 0; + + /* Then handle according to the selected interrupt type */ + + switch (inttype) + { + case 0: /* Interrupt on falling edge */ + { + iveset = 0; /* Falling edge or low levels*/ + iveclr = pin; + } + break; + + case 1: /* Interrupt on rising edge */ + default: + break; + + case 2: /* Interrupt on both edges */ + { + ibeset = pin; /* Both edges */ + ibeclr = 0; + } + break; + + case 3: /* Interrupt on low level */ + { + isset = pin; /* Level sensed */ + isclr = 0; + iveset = 0; /* Falling edge or low levels*/ + iveclr = pin; + } + break; + + case 4: /* Interrupt on high level */ + { + isset = pin; /* Level sensed */ + isclr = 0; + } + break; + } + + /* "The GPIO IS register is the interrupt sense register. Bits set to + * 1 in GPIOIS configure the corresponding pins to detect levels, while + * bits set to 0 configure the pins to detect edges. All bits are cleared + * by a reset. + */ + + regval = getreg32(base + LM3S_GPIO_IS_OFFSET); + regval &= isclr; + regval |= isset; + putreg32(regval, base + LM3S_GPIO_IS_OFFSET); + + /* "The GPIO IBE register is the interrupt both-edges register. When the + * corresponding bit in the GPIO Interrupt Sense (GPIO IS) register ... is + * set to detect edges, bits set to High in GPIO IBE configure the + * corresponding pin to detect both rising and falling edges, regardless + * of the corresponding bit in the GPIO Interrupt Event (GPIO IEV) register ... + * Clearing a bit configures the pin to be controlled by GPIOIEV. All bits + * are cleared by a reset. + */ + + regval = getreg32(base + LM3S_GPIO_IBE_OFFSET); + regval &= ibeclr; + regval |= ibeset; + putreg32(regval, base + LM3S_GPIO_IBE_OFFSET); + + /* "The GPIOIEV register is the interrupt event register. Bits set to + * High in GPIO IEV configure the corresponding pin to detect rising edges + * or high levels, depending on the corresponding bit value in the GPIO + * Interrupt Sense (GPIO IS) register... Clearing a bit configures the pin to + * detect falling edges or low levels, depending on the corresponding bit + * value in GPIOIS. All bits are cleared by a reset. + */ + + regval = getreg32(base + LM3S_GPIO_IEV_OFFSET); + regval &= iveclr; + regval |= iveset; + putreg32(regval, base + LM3S_GPIO_IEV_OFFSET); +} + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: lm3s_configgpio + * + * Description: + * Configure a GPIO pin based on bit-encoded description of the pin. + * + ****************************************************************************/ + +int lm3s_configgpio(uint32 cfgset) +{ + irqstate_t flags; + unsigned int func; + unsigned int port; + unsigned int pinno; + uint32 pin; + uint32 base; + uint32 regval; + + /* Decode the basics */ + + func = (cfgset & GPIO_FUNC_MASK) >> GPIO_FUNC_SHIFT; + port = (cfgset & GPIO_PORT_MASK) >> GPIO_PORT_SHIFT; + pinno = (cfgset & GPIO_NUMBER_MASK); + pin = (1 <> GPIO_PORT_SHIFT; + pinno = (pinset & GPIO_NUMBER_MASK); + + /* Get the base address associated with the GPIO port */ + + base = lm3s_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 + * port pins if the respective pins have been configured as outputs through + * the GPIO Direction (GPIO DIR) register ... + * + * "In order to write to GPIO DATA, the corresponding bits in the mask, + * resulting from the address bus bits [9:2], must be High. Otherwise, the + * bit values remain unchanged by the write. + * + * "... All bits are cleared by a reset." + */ + + putreg32((uint32)value << pinno, base + LM3S_GPIO_DATA_OFFSET + (pinno << 2)); +} + +/**************************************************************************** + * Name: lm3s_gpioread + * + * Description: + * Read one or zero from the selected GPIO pin + * + ****************************************************************************/ + +boolean lm3s_gpioread(uint32 pinset, boolean value) +{ + unsigned int port; + unsigned int pinno; + uint32 base; + + /* Decode the basics */ + + port = (pinset & GPIO_PORT_MASK) >> GPIO_PORT_SHIFT; + pinno = (pinset & GPIO_NUMBER_MASK); + + /* Get the base address associated with the GPIO port */ + + base = lm3s_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, + * bits [9:2]. Bits that are 1 in the address mask cause the corresponding + * bits in GPIODATA to be read, and bits that are 0 in the address mask cause + * the corresponding bits in GPIO DATA to be read as 0, regardless of their + * value. + * + * "A read from GPIO DATA returns the last bit value written if the respective + * pins are configured as outputs, or it returns the value on the + * corresponding input pin when these are configured as inputs. All bits + * are cleared by a reset." + */ + + return (getreg32(base + LM3S_GPIO_DATA_OFFSET + (pinno << 2)) != 0); +} \ No newline at end of file diff --git a/nuttx/arch/arm/src/lm3s/lm3s_internal.h b/nuttx/arch/arm/src/lm3s/lm3s_internal.h index 3f8540dd5..0f48c6f23 100644 --- a/nuttx/arch/arm/src/lm3s/lm3s_internal.h +++ b/nuttx/arch/arm/src/lm3s/lm3s_internal.h @@ -57,12 +57,19 @@ * The default priority level is set to the middle value */ -#define NVIC_SYSH_PRIORITY_MIN 0x00 -#define NVIC_SYSH_PRIORITY_DEFAULT 0x80 -#define NVIC_SYSH_PRIORITY_MAX 0xe0 +#define NVIC_SYSH_PRIORITY_MIN 0xe0 /* All bits set in minimum priority */ +#define NVIC_SYSH_PRIORITY_DEFAULT 0x80 /* Midpoint is the default */ +#define NVIC_SYSH_PRIORITY_MAX 0x00 /* Zero is maximum priority */ /* Bit-encoded input to lm3s_configgpio() *******************************************/ +/* Encoding: + * FFFS SPPP IIIn nnnn nnnn nnnn nVPP PBBB + * + * These bits set the primary function of the pin: + * FFFn nnnn nnnn nnnn nnnn nnnn nnnn nnnn + */ + #define GPIO_FUNC_SHIFT 29 /* Bit 31-29: GPIO function */ #define GPIO_FUNC_MASK (7 << GPIO_FUNC_SHIFT) /* (See table 9-1 in data sheet) */ #define GPIO_FUNC_INPUT (0 << GPIO_FUNC_SHIFT) /* Digital GPIO input */ @@ -75,23 +82,21 @@ #define GPIO_FUNC_PFIO (5 << GPIO_FUNC_SHIFT) /* Digital input/output (SSI, UART) */ #define GPIO_FUNC_ANINPUT (6 << GPIO_FUNC_SHIFT) /* Analog input (Comparator) */ #define GPIO_FUNC_INTERRUPT (7 << GPIO_FUNC_SHIFT) /* Interrupt function */ +#define GPIO_FUNC_MAX GPIO_FUNC_INTERRUPT -#define GPIO_INT_SHIFT 26 /* Bits 28-26: Interrupt type */ -#define GPIO_INT_MASK (7 << GPIO_INT_SHIFT) -#define GPIO_INT_FALLINGEDGE (0 << GPIO_INT_SHIFT) /* Interrupt on falling edge */ -#define GPIO_INT_RISINGEDGE (1 << GPIO_INT_SHIFT) /* Interrupt on rising edge */ -#define GPIO_INT_BOTHEDGES (2 << GPIO_INT_SHIFT) /* Interrupt on both edges */ -#define GPIO_INT_LOWLEVEL (3 << GPIO_INT_SHIFT) /* Interrupt on low level */ -#define GPIO_INT_HIGHLEVEL (4 << GPIO_INT_SHIFT) /* Interrupt on high level */ +/* That primary may be modified by the following options + * nnnS SPPP nnnn nnnn nnnn nnnn nnnn nnnn + */ -#define GPIO_STRENGTH_SHIFT 24 /* Bits 25-24: Pad drive strength */ +#define GPIO_STRENGTH_SHIFT 27 /* Bits 28-27: Pad drive strength */ #define GPIO_STRENGTH_MASK (3 << GPIO_STRENGTH_SHIFT) #define GPIO_STRENGTH_2MA (0 << GPIO_STRENGTH_SHIFT) /* 2mA pad drive strength */ #define GPIO_STRENGTH_4MA (1 << GPIO_STRENGTH_SHIFT) /* 4mA pad drive strength */ #define GPIO_STRENGTH_8MA (2 << GPIO_STRENGTH_SHIFT) /* 8mA pad drive strength */ #define GPIO_STRENGTH_8MASC (3 << GPIO_STRENGTH_SHIFT) /* 8mA Pad drive with slew rate control */ +#define GPIO_STRENGTH_MAX GPIO_STRENGTH_8MASC -#define GPIO_PADTYPE_SHIFT 21 /* Bits 21-23: Pad type */ +#define GPIO_PADTYPE_SHIFT 24 /* Bits 26-24: Pad type */ #define GPIO_PADTYPE_MASK (7 << GPIO_PADTYPE_SHIFT) #define GPIO_PADTYPE_STD (0 << GPIO_PADTYPE_SHIFT) /* Push-pull */ #define GPIO_PADTYPE_STDWPU (1 << GPIO_PADTYPE_SHIFT) /* Push-pull with weak pull-up */ @@ -101,11 +106,31 @@ #define GPIO_PADTYPE_ODWPD (5 << GPIO_PADTYPE_SHIFT) /* Open-drain with weak pull-down */ #define GPIO_PADTYPE_ANALOG (6 << GPIO_PADTYPE_SHIFT) /* Analog comparator */ +/* If the pin is an interrupt, then the following options apply + * nnnn nnnn IIIn nnnn nnnn nnnn nnnn nnnn + */ + +#define GPIO_INT_SHIFT 21 /* Bits 23-21: Interrupt type */ +#define GPIO_INT_MASK (7 << GPIO_INT_SHIFT) +#define GPIO_INT_FALLINGEDGE (0 << GPIO_INT_SHIFT) /* Interrupt on falling edge */ +#define GPIO_INT_RISINGEDGE (1 << GPIO_INT_SHIFT) /* Interrupt on rising edge */ +#define GPIO_INT_BOTHEDGES (2 << GPIO_INT_SHIFT) /* Interrupt on both edges */ +#define GPIO_INT_LOWLEVEL (3 << GPIO_INT_SHIFT) /* Interrupt on low level */ +#define GPIO_INT_HIGHLEVEL (4 << GPIO_INT_SHIFT) /* Interrupt on high level */ + +/* If the pin is an GPIO digital output, then this identifies the initial output value: + * nnnn nnnn nnnn nnnn nnnn nnnn nVnn nnnn + */ + #define GPIO_VALUE_SHIFT 6 /* Bit 6: If output, inital value of output */ #define GPIO_VALUE_MASK (1 << GPIO_VALUE_SHIFT) #define GPIO_VALUE_ZERO (0 << GPIO_VALUE_SHIFT) /* Initial value is zero */ #define GPIO_VALUE_ONE (1 << GPIO_VALUE_SHIFT) /* Initial value is one */ +/* This identifies the GPIO port + * nnnn nnnn nnnn nnnn nnnn nnnn nnPP Pnnn + */ + #define GPIO_PORT_SHIFT 3 /* Bit 3-5: Port number */ #define GPIO_PORT_MASK (7 << GPIO_PORT_SHIFT) #define GPIO_PORTA (0 << GPIO_PORT_SHIFT) /* GPIOA */ @@ -117,6 +142,10 @@ #define GPIO_PORTG (6 << GPIO_PORT_SHIFT) /* GPIOG */ #define GPIO_PORTH (7 << GPIO_PORT_SHIFT) /* GPIOH */ +/* This identifies the bit in the port: + * nnnn nnnn nnnn nnnn nnnn nnnn nnnn nBBB + */ + #define GPIO_NUMBER_SHIFT 0 /* Bits 0-2: GPIO number: 0-7 */ #define GPIO_NUMBER_MASK (7 << GPIO_NUMBER_SHIFT) @@ -172,24 +201,6 @@ #ifndef __ASSEMBLY__ -static inline uint32 lm3s_gpiobaseaddress(unsigned int port) -{ -#ifdef CONFIG_ARCH_CHIP_LM3S6918 - unsigned int portno = (port >> GPIO_PORT_SHIFT) & 7; - if (portno < 4) - { - return LM3S_GPIOA_BASE + 0x1000 * portno; - } - else - { - return LM3S_GPIOE_BASE + 0x1000 * portno; - } -#else -# error "GPIO register base addresses not known for this LM3S chip" - return 0; -#endif -} - /************************************************************************************ * Public Data ************************************************************************************/ @@ -249,7 +260,7 @@ EXTERN void up_clockconfig(void); * ****************************************************************************/ -EXTERN int lm3s_configgpio(uint32 bitset); +EXTERN int lm3s_configgpio(uint32 cfgset); /**************************************************************************** * Name: lm3s_pendsv @@ -261,6 +272,26 @@ EXTERN int lm3s_configgpio(uint32 bitset); EXTERN int lm3s_pendsv(int irq, FAR void *context); +/**************************************************************************** + * Name: lm3s_gpiowrite + * + * Description: + * Write one or zero to the selected GPIO pin + * + ****************************************************************************/ + +EXTERN void lm3s_gpiowrite(uint32 pinset, boolean value); + +/**************************************************************************** + * Name: lm3s_gpioread + * + * Description: + * Read one or zero from the selected GPIO pin + * + ****************************************************************************/ + +EXTERN boolean lm3s_gpioread(uint32 pinset, boolean value); + #undef EXTERN #if defined(__cplusplus) } diff --git a/nuttx/arch/arm/src/lm3s/lm3s_irq.c b/nuttx/arch/arm/src/lm3s/lm3s_irq.c index 4b3c404e0..80bb33503 100644 --- a/nuttx/arch/arm/src/lm3s/lm3s_irq.c +++ b/nuttx/arch/arm/src/lm3s/lm3s_irq.c @@ -40,7 +40,9 @@ #include #include + #include +#include #include "up_arch.h" #include "os_internal.h" @@ -173,13 +175,17 @@ void up_irqinitialize(void) current_regs = NULL; - /* Attach the PendSV exception handler. This is used for performing + /* Attach the PendSV exception handler and set it to the minimum + * prioirity. The PendSV exception is used for performing * context switches. */ irq_attach(LMSB_IRQ_PENDSV, lm3s_pendsv); +#ifdef CONFIG_ARCH_IRQPRIO + up_prioritize_irq(LMSB_IRQ_PENDSV, NVIC_SYSH_PRIORITY_MIN); +#endif - /* Attach all processor exceptions (except reset and sys tick) */ + /* Attach all other processor exceptions (except reset and sys tick) */ #ifdef CONFIG_DEBUG irq_attach(LMSB_IRQ_NMI, lm3s_nmi); @@ -285,7 +291,7 @@ int up_prioritize_irq(int irq, int priority) uint32 regval; int shift; - DEBUGASSERT(irq >= LMSB_IRQ_MPU && irq < NR_IRQS && (unsigned)priority <= NVIC_SYSH_PRIORITY_MAX); + DEBUGASSERT(irq >= LMSB_IRQ_MPU && irq < NR_IRQS && (unsigned)priority <= NVIC_SYSH_PRIORITY_MIN); if (irq < LM3S_IRQ_INTERRUPTS) { diff --git a/nuttx/arch/arm/src/lm3s/lm3s_lowputc.c b/nuttx/arch/arm/src/lm3s/lm3s_lowputc.c index bec33ac5e..7e675f110 100644 --- a/nuttx/arch/arm/src/lm3s/lm3s_lowputc.c +++ b/nuttx/arch/arm/src/lm3s/lm3s_lowputc.c @@ -249,22 +249,6 @@ void up_lowsetup(void) putreg32(ctl, LM3S_CONSOLE_BASE+LM3S_UART_CTL_OFFSET); #endif - /* Peripheral clocking to the selected UART modules and to the GPIO - * modules used for the pin configuration. NOTE: this function is - * called very early in the boot sequence so we do not need to be - * concerned about exclusive access to registers. - */ - - rcgc1 = getreg32(LM3S_SYSCON_RCGC1); -#if !defined(CONFIG_UART0_DISABLE) && !defined(CONFIG_UART1_DISABLE) - rcgc1 |= (SYSCON_RCGC1_UART0|SYSCON_RCGC2_GPIOA|SYSCON_RCGC1_UART1|SYSCON_RCGC2_GPIOD); -#elif !defined(CONFIG_UART0_DISABLE) - rcgc1 |= (SYSCON_RCGC1_UART0|SYSCON_RCGC2_GPIOA); -#elif !defined(CONFIG_UART1_DISABLE) - rcgc1 |= (SYSCON_RCGC1_UART1|SYSCON_RCGC2_GPIOD); -#endif - putreg32(rcgc1, LM3S_SYSCON_RCGC1); - /* Then configure GPIO pins to enable the selected UARTs. NOTE: The * serial driver later depends on this pin configuration. */ diff --git a/nuttx/arch/arm/src/lm3s/lm3s_start.c b/nuttx/arch/arm/src/lm3s/lm3s_start.c index 1eeed3af6..f10c2a5a4 100644 --- a/nuttx/arch/arm/src/lm3s/lm3s_start.c +++ b/nuttx/arch/arm/src/lm3s/lm3s_start.c @@ -102,7 +102,7 @@ extern void lm3s_vectors(void); * ****************************************************************************/ -void _start(void) +void __start(void) { const uint32 *src; uint32 *dest; diff --git a/nuttx/arch/arm/src/lm3s/lm3s_syscontrol.h b/nuttx/arch/arm/src/lm3s/lm3s_syscontrol.h index 5fe7ffd37..3a9a83f62 100644 --- a/nuttx/arch/arm/src/lm3s/lm3s_syscontrol.h +++ b/nuttx/arch/arm/src/lm3s/lm3s_syscontrol.h @@ -210,6 +210,7 @@ /* Device Capabilities 4 (DC4), offset 0x01c */ +#define SYSCON_DC4_GPIO(n) (1 << (n)) #define SYSCON_DC4_GPIOA (1 << 0) /* Bit 0: GPIO Port A Present */ #define SYSCON_DC4_GPIOB (1 << 1) /* Bit 1: GPIO Port B Present */ #define SYSCON_DC4_GPIOC (1 << 2) /* Bit 2: GPIO Port C Present */ @@ -264,6 +265,7 @@ /* Software Reset Control 2 (SRCR2), offset 0x048 */ +#define SYSCON_SRCR2_GPIO(n) (1 << (n)) #define SYSCON_SRCR2_GPIOA (1 << 0) /* Bit 0: Port A Reset Control */ #define SYSCON_SRCR2_GPIOB (1 << 1) /* Bit 1: Port B Reset Control */ #define SYSCON_SRCR2_GPIOC (1 << 2) /* Bit 2: Port C Reset Control */ @@ -382,6 +384,7 @@ /* Run Mode Clock Gating Control Register 2 (RCGC2), offset 0x108 */ +#define SYSCON_RCGC2_GPIO(n) (1 << (n)) #define SYSCON_RCGC2_GPIOA (1 << 0) /* Bit 0: Port A Clock Gating Control */ #define SYSCON_RCGC2_GPIOB (1 << 1) /* Bit 1: Port B Clock Gating Control */ #define SYSCON_RCGC2_GPIOC (1 << 2) /* Bit 2: Port C Clock Gating Control */ @@ -418,6 +421,7 @@ /* Sleep Mode Clock Gating Control Register 2 (SCGC2), offset 0x118 */ +#define SYSCON_SCGC2_GPIO(n) (1 << (n)) #define SYSCON_SCGC2_GPIOA (1 << 0) /* Bit 0: Port A Clock Gating Control */ #define SYSCON_SCGC2_GPIOB (1 << 1) /* Bit 1: Port B Clock Gating Control */ #define SYSCON_SCGC2_GPIOC (1 << 2) /* Bit 2: Port C Clock Gating Control */ @@ -454,6 +458,7 @@ /* Deep Sleep Mode Clock Gating Control Register 2 (DCGC2), offset 0x128 */ +#define SYSCON_DCGC2_GPIO(n) (1 << (n)) #define SYSCON_DCGC2_GPIOA (1 << 0) /* Bit 0: Port A Clock Gating Control */ #define SYSCON_DCGC2_GPIOB (1 << 1) /* Bit 1: Port B Clock Gating Control */ #define SYSCON_DCGC2_GPIOC (1 << 2) /* Bit 2: Port C Clock Gating Control */ diff --git a/nuttx/arch/arm/src/lm3s/lm3s_vectors.S b/nuttx/arch/arm/src/lm3s/lm3s_vectors.S index 2873f72e1..f25086c91 100644 --- a/nuttx/arch/arm/src/lm3s/lm3s_vectors.S +++ b/nuttx/arch/arm/src/lm3s/lm3s_vectors.S @@ -64,6 +64,7 @@ * Global Symbols ************************************************************************************/ + .globl __start .globl dispach_irq .syntax unified @@ -99,7 +100,7 @@ lm3s_vectors: /* Processor Exceptions */ .word IDLE_STACK /* Vector 0: Reset stack pointer */ - .word _start /* Vector 1: Reset vector */ + .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) */ -- cgit v1.2.3