Squashed commit of the following:

arch/arm/src/tiva:  Add GPIO IRQ stubs for clean compile

    arch/arm/src/tiva/cc13xx:  Add build framework for CC13xx GPIO interrupts.  Change prototypes of some GPIO IRQ interfaces so that the function prototype is common between LM3S, LM4F, TM4C, and CC13xx.
This commit is contained in:
Gregory Nutt 2018-12-09 11:19:24 -06:00
parent b3b53a6dd4
commit eaf62096ee
15 changed files with 380 additions and 196 deletions

View File

@ -49,37 +49,38 @@ CMN_CSRCS += up_svcall.c up_trigger_irq.c up_unblocktask.c up_udelay.c
CMN_CSRCS += up_usestack.c up_vfork.c
ifneq ($(CONFIG_ARCH_IDLE_CUSTOM),y)
CMN_CSRCS += up_idle.c
CMN_CSRCS += up_idle.c
endif
ifeq ($(CONFIG_ARMV7M_LAZYFPU),y)
CMN_ASRCS += up_lazyexception.S
CMN_ASRCS += up_lazyexception.S
else
CMN_ASRCS += up_exception.S
CMN_ASRCS += up_exception.S
endif
CMN_CSRCS += up_vectors.c
ifeq ($(CONFIG_ARCH_FPU),y)
CMN_ASRCS += up_fpu.S
CMN_CSRCS += up_copyarmstate.c
CMN_ASRCS += up_fpu.S
CMN_CSRCS += up_copyarmstate.c
endif
ifeq ($(CONFIG_ARCH_RAMVECTORS),y)
CMN_CSRCS += up_ramvec_initialize.c up_ramvec_attach.c
CMN_CSRCS += up_ramvec_initialize.c up_ramvec_attach.c
endif
ifeq ($(CONFIG_STACK_COLORATION),y)
CMN_CSRCS += up_checkstack.c
CMN_CSRCS += up_checkstack.c
endif
ifeq ($(CONFIG_BUILD_PROTECTED),y)
CMN_CSRCS += up_mpu.c up_task_start.c up_pthread_start.c
CMN_CSRCS += up_mpu.c up_task_start.c up_pthread_start.c
ifneq ($(CONFIG_DISABLE_SIGNALS),y)
CMN_CSRCS += up_signal_dispatch.c
CMN_UASRCS += up_signal_handler.S
CMN_CSRCS += up_signal_dispatch.c
CMN_UASRCS += up_signal_handler.S
endif
else
CMN_CSRCS += up_allocateheap.c
CMN_CSRCS += up_allocateheap.c
endif
CHIP_ASRCS =
@ -87,76 +88,77 @@ CHIP_CSRCS = tiva_allocateheap.c tiva_irq.c tiva_lowputc.c tiva_serial.c
CHIP_CSRCS += tiva_ssi.c
ifeq ($(CONFIG_ARCH_CHIP_LM3S),y)
CHIP_CSRCS += lmxx_tm4c_start.c lm3s_gpio.c tiva_gpioirq.c
CHIP_CSRCS += lmxx_tm4c_start.c lm3s_gpio.c lmxx_tm4c_gpioirq.c
CHIP_CSRCS += lm4xx_tm3c_sysctrl.c
else ifeq ($(CONFIG_ARCH_CHIP_LM4F),y)
CHIP_CSRCS += lmxx_tm4c_start.c lm4f_gpio.c tiva_gpioirq.c
CHIP_CSRCS += lmxx_tm4c_start.c lm4f_gpio.c lmxx_tm4c_gpioirq.c
CHIP_CSRCS += lm4xx_tm3c_sysctrl.c
else ifeq ($(CONFIG_ARCH_CHIP_TM4C),y)
CHIP_CSRCS += lmxx_tm4c_start.c tm4c_gpio.c tiva_gpioirq.c
CHIP_CSRCS += lmxx_tm4c_start.c tm4c_gpio.c lmxx_tm4c_gpioirq.c
ifeq ($(CONFIG_ARCH_CHIP_TM4C129),y)
CHIP_CSRCS += tm4c129_sysctrl.c
else
CHIP_CSRCS += lm4xx_tm3c_sysctrl.c
endif
else ifeq ($(CONFIG_ARCH_CHIP_CC13X0),y)
CHIP_CSRCS += cc13xx_start.c cc13xx_prcm.c cc13xx_gpio.c cc13xx_gpioirq.c
CHIP_CSRCS += cc13xx_enableclks.c cc13xx_enablepwr.c
CHIP_CSRCS += cc13xx_start.c cc13xx_prcm.c cc13xx_gpio.c cc13xx_gpioirq.c
CHIP_CSRCS += cc13xx_enableclks.c cc13xx_enablepwr.c
else ifeq ($(CONFIG_ARCH_CHIP_CC13X2),y)
CHIP_CSRCS += cc13xx_start.c cc13xx_prcm.c cc13xx_gpio.c cc13xx_gpioirq.c
CHIP_CSRCS += cc13xx_enableclks.c cc13xx_enablepwr.c
CHIP_CSRCS += cc13xx_start.c cc13xx_prcm.c cc13xx_gpio.c cc13xx_gpioirq.c
CHIP_CSRCS += cc13xx_enableclks.c cc13xx_enablepwr.c
endif
ifeq ($(CONFIG_DEBUG_GPIO_INFO),y)
CHIP_CSRCS += tiva_dumpgpio.c
endif
ifeq ($(CONFIG_ARCH_CHIP_TM4C129),y)
CHIP_CSRCS += tm4c129_sysctrl.c
else
CHIP_CSRCS += tiva_sysctrl.c
CHIP_CSRCS += tiva_dumpgpio.c
endif
ifneq ($(CONFIG_SCHED_TICKLESS),y)
CHIP_CSRCS += tiva_timerisr.c
CHIP_CSRCS += tiva_timerisr.c
endif
ifeq ($(CONFIG_BUILD_PROTECTED),y)
CHIP_CSRCS += tiva_userspace.c tiva_mpuinit.c
CHIP_CSRCS += tiva_userspace.c tiva_mpuinit.c
endif
ifeq ($(CONFIG_TIVA_I2C),y)
CHIP_CSRCS += tiva_i2c.c
CHIP_CSRCS += tiva_i2c.c
endif
ifeq ($(CONFIG_TIVA_PWM),y)
CHIP_CSRCS += tiva_pwm.c
CHIP_CSRCS += tiva_pwm.c
endif
ifeq ($(CONFIG_TIVA_QEI),y)
CHIP_CSRCS += tiva_qencoder.c
CHIP_CSRCS += tiva_qencoder.c
endif
ifeq ($(CONFIG_TIVA_TIMER),y)
CHIP_CSRCS += tiva_timerlib.c
CHIP_CSRCS += tiva_timerlib.c
ifeq ($(CONFIG_TIVA_TIMER32_PERIODIC),y)
CHIP_CSRCS += tiva_timerlow32.c
CHIP_CSRCS += tiva_timerlow32.c
endif
endif
ifeq ($(CONFIG_TIVA_ADC),y)
CHIP_CSRCS += tiva_adclow.c
CHIP_CSRCS += tiva_adclib.c
CHIP_CSRCS += tiva_adclow.c
CHIP_CSRCS += tiva_adclib.c
endif
ifeq ($(CONFIG_TIVA_ETHERNET),y)
ifeq ($(CONFIG_ARCH_CHIP_LM3S),y)
CHIP_CSRCS += lm3s_ethernet.c
CHIP_CSRCS += lm3s_ethernet.c
endif
ifeq ($(CONFIG_ARCH_CHIP_TM4C),y)
CHIP_CSRCS += tm4c_ethernet.c
CHIP_CSRCS += tm4c_ethernet.c
endif
endif
ifeq ($(CONFIG_TIVA_FLASH),y)
CHIP_CSRCS += tiva_flash.c
CHIP_CSRCS += tiva_flash.c
endif
ifeq ($(CONFIG_TIVA_EEPROM),y)
CHIP_CSRCS += tiva_eeprom.c
CHIP_CSRCS += tiva_eeprom.c
endif
# Paths to source files

View File

@ -45,7 +45,7 @@
#include <nuttx/irq.h>
#include "hardware/tiva_prcm"
#include "hardware/tiva_prcm.h"
#include "tiva_enableclks.h"
/****************************************************************************

View File

@ -45,7 +45,7 @@
#include <nuttx/irq.h>
#include "hardware/tiva_prcm"
#include "hardware/tiva_prcm.h"
#include "tiva_enablepwr.h"
/****************************************************************************
@ -68,14 +68,14 @@ static uint16_t g_domain_usage[2];
void cc13xx_periph_enablepwr(uint32_t peripheral)
{
irgstate_t flags;
irqstate_t flags;
uint32_t domain;
int dndx;
int pndx;
dndx = PRCM_DOMAIN_INDEX(peripheral);
pndx = PRCM_PERIPH_ID(peripheral);
domain = (pndx == 0 ? PRCM_DOMAIN_SERIAL : PRCM_DOMAIN_PERIPH)
domain = (pndx == 0 ? PRCM_DOMAIN_SERIAL : PRCM_DOMAIN_PERIPH);
/* Remember that this peripheral needs power in this domain */
@ -109,7 +109,7 @@ void cc13xx_periph_disablepwr(uint32_t peripheral)
{
int dndx = PRCM_DOMAIN_INDEX(peripheral);
int pndx = PRCM_PERIPH_ID(peripheral);
irgstate_t flags;
irqstate_t flags;
/* This peripheral no longer needs power in this domain */
@ -122,7 +122,7 @@ void cc13xx_periph_disablepwr(uint32_t peripheral)
if (g_domain_usage[dndx] == 0)
{
prcm_powerdomain_off(pndx == ? PRCM_DOMAIN_SERIAL : PRCM_DOMAIN_PERIPH);
prcm_powerdomain_off(pndx == 0 ? PRCM_DOMAIN_SERIAL : PRCM_DOMAIN_PERIPH);
}
spin_unlock_irqrestore(flags);

View File

@ -52,32 +52,12 @@
#include "tiva_enableclks.h"
#include "tiva_gpio.h"
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/
/****************************************************************************
* Private Types
****************************************************************************/
/****************************************************************************
* Private Data
****************************************************************************/
static bool g_gpio_powered;
/****************************************************************************
* Public Data
****************************************************************************/
/****************************************************************************
* Private Functions
****************************************************************************/
/****************************************************************************
* Public Functions
****************************************************************************/
@ -113,6 +93,13 @@ int tiva_configgpio(pinconfig_t pinconfig)
g_gpio_powered = true;
}
#ifdef CONFIG_TIVA_GPIO_IRQS
/* Mask and clear any pending GPIO interrupt */
tiva_gpioirqdisable(pinconfig);
tiva_gpioirqclear(pinconfig);
#endif
/* Configure the GPIO as an input. We don't even know if the pin is a
* a GPIO yet, but may prevent glitches when configure GPIO output pins.
*/

View File

@ -0,0 +1,250 @@
/****************************************************************************
* arch/arm/src/tiva/common/cc13xx_gpioirq.c
*
* Copyright (C) 2018 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 <nuttx/arch.h>
#include <nuttx/irq.h>
#include <stdint.h>
#include <string.h>
#include <assert.h>
#include <debug.h>
#include <arch/board/board.h>
#include "chip.h"
#include "up_internal.h"
#include "up_arch.h"
#include "irq/irq.h"
#include "tiva_gpio.h"
#ifdef CONFIG_TIVA_GPIO_IRQS
/****************************************************************************
* Private types
****************************************************************************/
struct gpio_handler_s
{
xcpt_t isr; /* Interrupt service routine entry point */
void *arg; /* The argument that accompanies the interrupt */
};
/****************************************************************************
* Private Data
****************************************************************************/
/* A table of handlers for each GPIO port interrupt */
static struct gpio_handler_s g_gpio_inthandler[TIVA_NIRQ_PINS];
/****************************************************************************
* Private Functions
****************************************************************************/
/****************************************************************************
* Name: cc13xx_gpio_interrupt
*
* Description:
* Handle interrupts on each enabled GPIO port
*
****************************************************************************/
static int cc13xx_gpio_interrupt)(int irq, FAR void *context, FAR void *arg)
{
unsigned int dio;
#warning Missing logic
/* Clear pending interrupts */
/* Now process each pending interrupt */
/* Call any handler registered for each pending DIO interrupt */
FAR struct gpio_handler_s *handler = &g_gpio_inthandler[dio];
gpioinfo("dio=%d isr=%p arg=%p\n", dio, handler->isr, handler->arg);
handler->isr(irq, context, handler->arg);
return OK;
}
/****************************************************************************
* Public Functions
****************************************************************************/
/****************************************************************************
* Name: tiva_gpioirqinitialize
*
* Description:
* Initialize all vectors to the unexpected interrupt handler
*
****************************************************************************/
int tiva_gpioirqinitialize(void)
{
unsigned int dio;
/* Point all interrupt vectors to the unexpected interrupt */
for (dio = 0; dio < TIVA_NDIO; dio++)
{
g_gpio_inthandler[dio].isr = irq_unexpected_isr;
g_gpio_inthandler[dio].arg = NULL;
}
/* Then attach the GPIO interrupt handler and enable corresponding GPIO
* interrupts at the NVIC.
*/
irq_attach(TIVA_IRQ_AON_GPIO_EDGE, cc13xx_gpio_interrupt, NULL);
up_enable_irq(TIVA_IRQ_AON_GPIO_EDGE);
return OK;
}
/****************************************************************************
* Name: tiva_gpioirqattach
*
* Description:
* Attach in GPIO interrupt to the provided 'isr'. If isr==NULL, then the
* irq_unexpected_isr handler is assigned and the pin's interrupt mask is
* disabled to stop further interrupts. Otherwise, the new isr is linked
* and the pin's interrupt mask is set.
*
* Returned Value:
* Zero (OK) is returned on success. Otherwise a negated errno value is
* return to indicate the nature of the failure.
*
****************************************************************************/
int tiva_gpioirqattach(pinconfig_t pinconfig, xcpt_t isr, void *arg)
{
FAR struct gpio_handler_s *handler;
unsigned int dio;
irqstate_t flags;
/* Assign per-pin interrupt handlers */
dio = (pinconfig->gpio & GPIO_DIO_MASK) >> GPIO_DIO_SHIFT;
DEBUGASSERT(dio < TIVA_NDIO);
if (dio < TIVA_NDIO)
{
flags = enter_critical_section();
/* If the new ISR is NULL, then the ISR is being detached.
* In this case, disable the ISR and direct any interrupts
* to the unexpected interrupt handler.
*/
gpioinfo("Attach dio=%d isr=%p arg=%p\n", dio, isr, arg);
handler = &g_gpio_inthandler[dio];
if (isr == NULL)
{
tiva_gpioirqdisable(pinconfig);
handler->isr = irq_unexpected_isr;
handler->arg = NULL;
}
else
{
handler->isr = isr;
handler->arg = arg;
tiva_gpioirqenable(pinconfig);
}
leave_critical_section(flags);
}
return OK;
}
/****************************************************************************
* Name: tiva_gpioirqenable
*
* Description:
* Enable the GPIO port IRQ
*
****************************************************************************/
void tiva_gpioirqenable(pinconfig_t pinconfig)
{
unsigned int dio;
dio = (pinconfig->gpio & GPIO_DIO_MASK) >> GPIO_DIO_SHIFT;
DEBUGASSERT(dio < TIVA_NDIO);
#warning Missing logic
}
/****************************************************************************
* Name: tiva_gpioirqdisable
*
* Description:
* Disable the GPIO port IRQ
*
****************************************************************************/
void tiva_gpioirqdisable(pinconfig_t pinconfig)
{
unsigned int dio;
dio = (pinconfig->gpio & GPIO_DIO_MASK) >> GPIO_DIO_SHIFT;
DEBUGASSERT(dio < TIVA_NDIO);
#warning Missing logic
}
/****************************************************************************
* Name: tiva_gpioirqclear
*
* Description:
* Clears the interrupt status of the input base
*
****************************************************************************/
void tiva_gpioirqclear(pinconfig_t pinconfig)
{
unsigned int dio;
dio = (pinconfig->gpio & GPIO_DIO_MASK) >> GPIO_DIO_SHIFT;
DEBUGASSERT(dio < TIVA_NDIO);
#warning Missing logic
}
#endif /* CONFIG_TIVA_GPIO_IRQS */

View File

@ -1,5 +1,5 @@
/****************************************************************************
* arch/arm/src/tiva/common/tiva_sysctrl.c
* arch/arm/src/tiva/common/lmxx_tm4c_sysctrl.c
*
* Copyright (C) 2009-2014, 2018 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>

View File

@ -1,7 +1,8 @@
/****************************************************************************
* arch/arm/src/tiva/common/tiva_gpioirq.c
* arch/arm/src/tiva/common/lmxx_tm4c_gpioirq.c
*
* Copyright (C) 2009-2010, 2012, 2014-2016 Gregory Nutt. All rights reserved.
* Copyright (C) 2009-2010, 2012, 2014-2016, 2018 Gregory Nutt. All
* rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@ -241,26 +242,6 @@ static int gpioport2irq(uint8_t port)
return irq;
}
/****************************************************************************
* Name: tiva_gpioirqclear
*
* Description:
* Clears the interrupt status of the input base
*
****************************************************************************/
void tiva_gpioirqclear(uint8_t port, uint32_t pinmask)
{
uintptr_t base = tiva_gpiobaseaddress(port);
/* "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."
*/
modifyreg32(base + TIVA_GPIO_ICR_OFFSET, 0, pinmask);
}
/****************************************************************************
* Name: tiva_gpioporthandler
*
@ -280,10 +261,12 @@ static int tiva_gpioporthandler(uint8_t port, void *context)
irq = gpioport2irq(port);
mis = getreg32(base + TIVA_GPIO_MIS_OFFSET);
tiva_gpioirqclear(port, 0xff);
gpioinfo("irq=%d mis=0b%08b\n", irq, mis & 0xff);
/* Clear all pending interrupts */
putreg32(0xff, base + TIVA_GPIO_ICR_OFFSET);
/* Now process each IRQ pending in the MIS */
if (mis != 0)
@ -551,9 +534,6 @@ int tiva_gpioirqinitialize(void)
g_gpioportirqvector[i].arg = NULL;
}
gpioinfo("tiva_gpioirqinitialize isr=%d/%d irq_unexpected_isr=%p\n",
i, TIVA_NIRQ_PINS, irq_unexpected_isr);
/* Then attach each GPIO interrupt handlers and enable corresponding GPIO
* interrupts
*/
@ -661,12 +641,12 @@ int tiva_gpioirqinitialize(void)
*
****************************************************************************/
int tiva_gpioirqattach(uint32_t pinset, xcpt_t isr, void *arg)
int tiva_gpioirqattach(pinconfig_t pinconfig, xcpt_t isr, void *arg)
{
FAR struct gpio_handler_s *handler;
irqstate_t flags;
uint8_t port = (pinset & GPIO_PORT_MASK) >> GPIO_PORT_SHIFT;
uint8_t pinno = (pinset & GPIO_PIN_MASK);
uint8_t port = (pinconfig & GPIO_PORT_MASK) >> GPIO_PORT_SHIFT;
uint8_t pinno = (pinconfig & GPIO_PIN_MASK);
uint8_t pin = 1 << pinno;
/* Assign per-pin interrupt handlers */
@ -686,7 +666,7 @@ int tiva_gpioirqattach(uint32_t pinset, xcpt_t isr, void *arg)
handler = &g_gpioportirqvector[TIVA_GPIO_IRQ_IDX(port, pinno)];
if (isr == NULL)
{
tiva_gpioirqdisable(port, pin);
tiva_gpioirqdisable(pinconfig);
handler->isr = irq_unexpected_isr;
handler->arg = NULL;
}
@ -694,7 +674,7 @@ int tiva_gpioirqattach(uint32_t pinset, xcpt_t isr, void *arg)
{
handler->isr = isr;
handler->arg = arg;
tiva_gpioirqenable(port, pin);
tiva_gpioirqenable(pinconfig);
}
leave_critical_section(flags);
@ -703,48 +683,6 @@ int tiva_gpioirqattach(uint32_t pinset, xcpt_t isr, void *arg)
return OK;
}
/****************************************************************************
* Name: tiva_gpioportirqattach
*
* Description:
* Attach 'isr' to the GPIO port. Only use this if you want to handle
* the entire ports interrupts explicitly.
*
****************************************************************************/
void tiva_gpioportirqattach(uint8_t port, xcpt_t isr)
{
irqstate_t flags;
int irq = gpioport2irq(port);
/* assign port interrupt handler */
if (port < TIVA_NPORTS)
{
flags = enter_critical_section();
/* If the new ISR is NULL, then the ISR is being detached.
* In this case, disable the ISR and direct any interrupts
* to the unexpected interrupt handler.
*/
gpioinfo("assign function=%p to port=%d\n", isr, port);
if (isr == NULL)
{
tiva_gpioirqdisable(port, 0xff);
irq_attach(irq, irq_unexpected_isr, NULL);
}
else
{
irq_attach(irq, isr, NULL);
tiva_gpioirqenable(port, 0xff);
}
leave_critical_section(flags);
}
}
/****************************************************************************
* Name: tiva_gpioirqenable
*
@ -753,8 +691,10 @@ void tiva_gpioportirqattach(uint8_t port, xcpt_t isr)
*
****************************************************************************/
void tiva_gpioirqenable(uint8_t port, uint8_t pin)
void tiva_gpioirqenable(pinconfig_t pinconfig)
{
uint8_t port = (pinconfig & GPIO_PORT_MASK) >> GPIO_PORT_SHIFT;
uint8_t pin = (pinconfig & GPIO_PIN_MASK);
uintptr_t base = tiva_gpiobaseaddress(port);
/* Enable the GPIO interrupt. "The GPIO IM register is the interrupt
@ -775,8 +715,10 @@ void tiva_gpioirqenable(uint8_t port, uint8_t pin)
*
****************************************************************************/
void tiva_gpioirqdisable(uint8_t port, uint8_t pin)
void tiva_gpioirqdisable(pinconfig_t pinconfig)
{
uint8_t port = (pinconfig & GPIO_PORT_MASK) >> GPIO_PORT_SHIFT;
uint8_t pin = (pinconfig & GPIO_PIN_MASK);
uintptr_t base = tiva_gpiobaseaddress(port);
/* Disable the GPIO interrupt. "The GPIO IM register is the interrupt
@ -789,4 +731,26 @@ void tiva_gpioirqdisable(uint8_t port, uint8_t pin)
modifyreg32(base + TIVA_GPIO_IM_OFFSET, pin, 0);
}
/****************************************************************************
* Name: tiva_gpioirqclear
*
* Description:
* Clears the interrupt status of the input base
*
****************************************************************************/
void tiva_gpioirqclear(pinconfig)
{
uint8_t port = (pinconfig & GPIO_PORT_MASK) >> GPIO_PORT_SHIFT;
uint8_t pin = (pinconfig & GPIO_PIN_MASK);
uintptr_t base = tiva_gpiobaseaddress(port);
/* "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."
*/
putreg32((1 << pin), base + TIVA_GPIO_ICR_OFFSET);
}
#endif /* CONFIG_TIVA_GPIO_IRQS */

View File

@ -50,6 +50,8 @@
* Pre-processor Definitions
************************************************************************************/
#define TIVA_NDIO 32 /* DIO0-31 */
/* IOC register offsets ************************************************************/
#define TIVA_IOC_IOCFG_OFFSET(n) ((n) << 2)
@ -126,9 +128,9 @@
/* Common bitfield for all DIO configuration registers */
#define IOC_IOCFG_PORTID_MASK (0) /* Bits 0-5: Selects DIO usage */
#define IOC_IOCFG_PORTID_SHIFT (0x3f << IOC_IOCFG_PORTID_MASK)
# define IOC_IOCFG_PORTID(n) ((uint32_t)(n) << IOC_IOCFG_PORTID_MASK) /* See PORT ID definitions */
#define IOC_IOCFG_PORTID_SHIFT (0) /* Bits 0-5: Selects DIO usage */
#define IOC_IOCFG_PORTID_MASK (0x3f << IOC_IOCFG_PORTID_SHIFT)
# define IOC_IOCFG_PORTID(n) ((uint32_t)(n) << IOC_IOCFG_PORTID_SHIFT) /* See PORT ID definitions */
#define IOC_IOCFG_IOSTR_SHIFT (8) /* Bits 8-9: I/O drive strength */
#define IOC_IOCFG_IOSTR_MASK (3 << IOC_IOCFG_IOSTR_SHIFT)
# define IOC_IOCFG_IOSTR_AUTO (0 << IOC_IOCFG_IOSTR_SHIFT) /* Automatic drive strength */
@ -154,13 +156,13 @@
# define IOC_IOCFG_EDGEDET_BOTH (3 << IOC_IOCFG_EDGEDET_SHIFT) /* Both edge detection */
#define IOC_IOCFG_EDGE_IRQEN (1 << 18) /* Bit 18: Enable interrupt generation */
#define IOC_IOCFG_IOMODE_SHIFT (24) /* Bits 24-26: I/O Mode */
#define IOC_IOCFG_IOMODE_MASK (7 << IOC_IOCFG1_IOMODE_SHIFT)
# define IOC_IOCFG_IOMODE_NORMAL (0 << IOC_IOCFG1_IOMODE_SHIFT) /* Normal I/O */
# define IOC_IOCFG_IOMODE_INV (1 << IOC_IOCFG1_IOMODE_SHIFT) /* Inverted I/O */
# define IOC_IOCFG_IOMODE_OPENDR (4 << IOC_IOCFG1_IOMODE_SHIFT) /* Open drain */
# define IOC_IOCFG_IOMODE_OPENDRINV (5 << IOC_IOCFG1_IOMODE_SHIFT) /* Open drain, inverted I/O */
# define IOC_IOCFG_IOMODE_OPENSRC (6 << IOC_IOCFG1_IOMODE_SHIFT) /* Open source */
# define IOC_IOCFG_IOMODE_OPENSRCINV (7 << IOC_IOCFG1_IOMODE_SHIFT) /* Open source, inverted I/O */
#define IOC_IOCFG_IOMODE_MASK (7 << IOC_IOCFG_IOMODE_SHIFT)
# define IOC_IOCFG_IOMODE_NORMAL (0 << IOC_IOCFG_IOMODE_SHIFT) /* Normal I/O */
# define IOC_IOCFG_IOMODE_INV (1 << IOC_IOCFG_IOMODE_SHIFT) /* Inverted I/O */
# define IOC_IOCFG_IOMODE_OPENDR (4 << IOC_IOCFG_IOMODE_SHIFT) /* Open drain */
# define IOC_IOCFG_IOMODE_OPENDRINV (5 << IOC_IOCFG_IOMODE_SHIFT) /* Open drain, inverted I/O */
# define IOC_IOCFG_IOMODE_OPENSRC (6 << IOC_IOCFG_IOMODE_SHIFT) /* Open source */
# define IOC_IOCFG_IOMODE_OPENSRCINV (7 << IOC_IOCFG_IOMODE_SHIFT) /* Open source, inverted I/O */
#define IOC_IOCFG_WUCFG_SHIFT (27) /* Bits 27-28: Wakeup Configuration */
#define IOC_IOCFG_WUCFG_MASK (3 << IOC_IOCFG_WUCFG_SHIFT)
# define IOC_IOCFG_WUCFG_NONE (0 << IOC_IOCFG_WUCFG_SHIFT) /* 0, 1: Wakeup disabled */

View File

@ -50,6 +50,8 @@
* Pre-processor Definitions
************************************************************************************/
#define TIVA_NDIO 32 /* DIO0-31 */
/* IOC register offsets ************************************************************/
#define TIVA_IOC_IOCFG_OFFSET(n) ((n) << 2)
@ -126,7 +128,7 @@
#define IOC_IOCFG_PORTID_SHIFT (0) /* Bits 0-5: Selects DIO usage */
#define IOC_IOCFG_PORTID_MASK (0x3f << IOC_IOCFG_PORTID_SHIFT)
# define IOC_IOCFG_PORTID(n) ((uint32_t)(n) << IOC_IOCFG_PORTID_MASK) /* See PORT ID definitions */
# define IOC_IOCFG_PORTID(n) ((uint32_t)(n) << IOC_IOCFG_PORTID_SHIFT) /* See PORT ID definitions */
#define IOC_IOCFG_IOEV_MCU_WUEN (1 << 6) /* Bit 6: Input edge asserts MCU_WU event */
#define IOC_IOCFG_IOEV_RTCEN (1 << 7) /* Bit 7: Input edge asserts RTC event */
#define IOC_IOCFG_IOSTR_SHIFT (8) /* Bits 8-9: I/O drive strength */
@ -157,13 +159,13 @@
#define IOC_IOCFG_IOEV_AON_PROG1 (1 << 22) /* Bit 22: Input edge asserts AON_PROG1 */
#define IOC_IOCFG_IOEV_AON_PROG2 (1 << 23) /* Bit 23: Input edge assert AON_PROG2 */
#define IOC_IOCFG_IOMODE_SHIFT (24) /* Bits 24-26: I/O Mode */
#define IOC_IOCFG_IOMODE_MASK (7 << IOC_IOCFG1_IOMODE_SHIFT)
# define IOC_IOCFG_IOMODE_NORMAL (0 << IOC_IOCFG1_IOMODE_SHIFT) /* Normal I/O */
# define IOC_IOCFG_IOMODE_INV (1 << IOC_IOCFG1_IOMODE_SHIFT) /* Inverted I/O */
# define IOC_IOCFG_IOMODE_OPENDR (4 << IOC_IOCFG1_IOMODE_SHIFT) /* Open drain */
# define IOC_IOCFG_IOMODE_OPENDRINV (5 << IOC_IOCFG1_IOMODE_SHIFT) /* Open drain, inverted I/O */
# define IOC_IOCFG_IOMODE_OPENSRC (6 << IOC_IOCFG1_IOMODE_SHIFT) /* Open source */
# define IOC_IOCFG_IOMODE_OPENSRCINV (7 << IOC_IOCFG1_IOMODE_SHIFT) /* Open source, inverted I/O */
#define IOC_IOCFG_IOMODE_MASK (7 << IOC_IOCFG_IOMODE_SHIFT)
# define IOC_IOCFG_IOMODE_NORMAL (0 << IOC_IOCFG_IOMODE_SHIFT) /* Normal I/O */
# define IOC_IOCFG_IOMODE_INV (1 << IOC_IOCFG_IOMODE_SHIFT) /* Inverted I/O */
# define IOC_IOCFG_IOMODE_OPENDR (4 << IOC_IOCFG_IOMODE_SHIFT) /* Open drain */
# define IOC_IOCFG_IOMODE_OPENDRINV (5 << IOC_IOCFG_IOMODE_SHIFT) /* Open drain, inverted I/O */
# define IOC_IOCFG_IOMODE_OPENSRC (6 << IOC_IOCFG_IOMODE_SHIFT) /* Open source */
# define IOC_IOCFG_IOMODE_OPENSRCINV (7 << IOC_IOCFG_IOMODE_SHIFT) /* Open source, inverted I/O */
#define IOC_IOCFG_WUCFG_SHIFT (27) /* Bits 27-28: Wakeup Configuration */
#define IOC_IOCFG_WUCFG_MASK (3 << IOC_IOCFG_WUCFG_SHIFT)
# define IOC_IOCFG_WUCFG_NONE (0 << IOC_IOCFG_WUCFG_SHIFT) /* 0, 1: Wakeup disabled */

View File

@ -559,8 +559,8 @@ static inline void tiva_interrupt(pinconfig_t pinconfig)
/* Mask and clear the GPIO interrupt */
tiva_gpioirqdisable(port, pin);
tiva_gpioirqclear(port, pin);
tiva_gpioirqdisable(pinconfig);
tiva_gpioirqclear(pinconfig);
/* handle according to the selected interrupt type */

View File

@ -585,8 +585,8 @@ static inline void tiva_interrupt(pinconfig_t pinconfig)
/* Mask and clear the GPIO interrupt */
tiva_gpioirqdisable(port, pin);
tiva_gpioirqclear(port, pin);
tiva_gpioirqdisable(pinconfig);
tiva_gpioirqclear(pinconfig);
/* handle according to the selected interrupt type */

View File

@ -173,18 +173,6 @@ int weak_function tiva_gpioirqinitialize(void);
int tiva_gpioirqattach(pinconfig_t pinconfig, xcpt_t isr, void *arg);
# define tiva_gpioirqdetach(p) tiva_gpioirqattach((p),NULL,NULL)
/****************************************************************************
* Name: tiva_gpioportirqattach
*
* Description:
* Attach 'isr' to the GPIO port. Only use this if you want to handle
* the entire ports interrupts explicitly.
*
****************************************************************************/
void tiva_gpioportirqattach(uint8_t port, xcpt_t isr);
# define tiva_gpioportirqdetach(port) tiva_gpioportirqattach(port, NULL)
/****************************************************************************
* Name: tiva_gpioirqenable
*
@ -193,7 +181,7 @@ void tiva_gpioportirqattach(uint8_t port, xcpt_t isr);
*
****************************************************************************/
void tiva_gpioirqenable(uint8_t port, uint8_t pin);
void tiva_gpioirqenable(pinconfig_t pinconfig);
/****************************************************************************
* Name: tiva_gpioirqdisable
@ -203,7 +191,7 @@ void tiva_gpioirqenable(uint8_t port, uint8_t pin);
*
****************************************************************************/
void tiva_gpioirqdisable(uint8_t port, uint8_t pin);
void tiva_gpioirqdisable(pinconfig_t pinconfig);
/****************************************************************************
* Name: tiva_gpioirqclear
@ -213,7 +201,7 @@ void tiva_gpioirqdisable(uint8_t port, uint8_t pin);
*
****************************************************************************/
void tiva_gpioirqclear(uint8_t port, uint32_t pinmask);
void tiva_gpioirqclear(pinconfig_t pinconfig);
#endif /* CONFIG_TIVA_GPIO_IRQS */

View File

@ -632,8 +632,8 @@ static inline void tiva_interrupt(pinconfig_t pinconfig)
/* Mask and clear the GPIO interrupt */
tiva_gpioirqdisable(port, pin);
tiva_gpioirqclear(port, pin);
tiva_gpioirqdisable(pinconfig);
tiva_gpioirqclear(pinconfig);
/* handle according to the selected interrupt type */

View File

@ -89,6 +89,7 @@ void board_button_initialize(void)
uint32_t board_buttons(void)
{
#warning Missing logic
return 0;
}
/****************************************************************************

View File

@ -56,25 +56,13 @@
const struct cc134xx_pinconfig_s g_gpio_uart0_rx =
{
.gpio =
{
GPIO_DIO(0)
},
.ioc =
{
GPIO_PORTID(IOC_IOCFG_PORTID_UART0_RX) | IOC_STD_INPUT
}
.gpio = GPIO_DIO(0),
.ioc = IOC_IOCFG_PORTID(IOC_IOCFG_PORTID_UART0_RX) | IOC_STD_INPUT
};
const struct cc134xx_pinconfig_s g_gpio_uart0_tx =
{
.gpio =
{
GPIO_DIO(1)
},
.ioc =
{
GPIO_PORTID(IOC_IOCFG_PORTID_UART0_TX) | IOC_STD_OUTPUT
}
.gpio = GPIO_DIO(1),
.ioc = IOC_IOCFG_PORTID(IOC_IOCFG_PORTID_UART0_TX) | IOC_STD_OUTPUT
};
#endif