Squashed commit of the following:

arch/arm/src/tiva:  Add CC13xx GPIO driver plus various fixes for clean compilation.

    arch/arm/src/tiva/ and configs/launchxl-cc1312r1:  Make type of the GPIO pin configuration an abstract type so that CC13xx MCUs can share the same GPIO function prototypes and usage model.
This commit is contained in:
Gregory Nutt 2018-12-09 09:06:57 -06:00
parent 7113cef6b7
commit 29b9b3b68b
14 changed files with 516 additions and 323 deletions

View File

@ -0,0 +1,214 @@
/****************************************************************************
* arch/arm/src/tiva/cc13xx/cc13xx_gpio.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 <stdint.h>
#include <stdbool.h>
#include <string.h>
#include <assert.h>
#include <debug.h>
#include <nuttx/irq.h>
#include "up_arch.h"
#include "tiva_enablepwr.h"
#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
****************************************************************************/
/****************************************************************************
* Name: tiva_configgpio
*
* Description:
* Configure a GPIO pin based on bit-encoded description of the pin.
*
****************************************************************************/
int tiva_configgpio(pinconfig_t pinconfig)
{
irqstate_t flags;
uintptr_t regaddr;
uint32_t regval;
unsigned int dio;
unsigned int portid;
/* The following requires exclusive access to the GPIO registers */
flags = spin_lock_irqsave();
/* Enable power and clocking for this GPIO peripheral if this is the first
* GPIO pin configured.
*/
if (!g_gpio_powered)
{
tiva_gpio_enablepwr();
tiva_gpio_enableclk();
g_gpio_powered = true;
}
/* 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.
*/
dio = (pinconfig->gpio & GPIO_DIO_MASK) >> GPIO_DIO_SHIFT;
regval = getreg32(TIVA_GPIO_DOE);
regval &= ~(1 << dio);
putreg32(regval, TIVA_GPIO_DOE);
/* Get the address of the IOC configuration register associated with
* this DIO and write the user-privided IOC configuration image.
*
* NOTE that we make no checks so it is possible that a bad IOC value
* could cause problems.
*/
regaddr = TIVA_IOC_IOCFG(dio);
putreg32(pinconfig->ioc, regaddr);
/* If the pin was an output, then set the initial value of the output
* and enable the output.
*/
portid = (pinconfig->ioc & IOC_IOCFG_PORTID_MASK) >>
IOC_IOCFG_PORTID_SHIFT;
if (portid == IOC_IOCFG_PORTID_GPIO &&
(pinconfig->gpio & GPIO_OUTPUT) != 0)
{
/* Set the initial output value */
if ((pinconfig->gpio & GPIO_VALUE_MASK) == GPIO_VALUE_ZERO)
{
regaddr = TIVA_GPIO_DOUTCLR;
}
else /* if ((pinconfig->gpio & GPIO_VALUE_MASK) == GPIO_VALUE_ONE) */
{
regaddr = TIVA_GPIO_DOUTSET;
}
putreg32(1 << dio, regaddr);
/* Configure the GPIO as an output */
regval = getreg32(TIVA_GPIO_DOE);
regval |= ~(1 << dio);
putreg32(regval, TIVA_GPIO_DOE);
}
spin_unlock_irqrestore(flags);
return OK;
}
/****************************************************************************
* Name: tiva_gpiowrite
*
* Description:
* Write one or zero to the selected GPIO pin
*
****************************************************************************/
void tiva_gpiowrite(pinconfig_t pinconfig, bool value)
{
uintptr_t regaddr;
unsigned int dio;
/* Are we setting the output to one or zero? */
if (value)
{
regaddr = TIVA_GPIO_DOUTSET;
}
else /* if ((pinconfig & GPIO_VALUE_MASK) == GPIO_VALUE_ONE) */
{
regaddr = TIVA_GPIO_DOUTCLR;
}
dio = (pinconfig->gpio & GPIO_DIO_MASK) >> GPIO_DIO_SHIFT;
putreg32(1 << dio, regaddr);
}
/****************************************************************************
* Name: tiva_gpioread
*
* Description:
* Read one or zero from the selected GPIO pin
*
****************************************************************************/
bool tiva_gpioread(pinconfig_t pinconfig)
{
unsigned int dio;
/* Return the input value from the specified DIO */
dio = (pinconfig->gpio & GPIO_DIO_MASK) >> GPIO_DIO_SHIFT;
return (getreg32(TIVA_GPIO_DIN) & (1 << dio)) != 0;
}

View File

@ -52,210 +52,100 @@
/* Bit-encoded input to tiva_configgpio() ***********************************/
/* Encoding:
/* 64-Bit Encoding:
*
* PPPP PPIO WCCR SSHS PPAA GIII EEVD DDDD
* Word 1: .... .... .... .... .... ..OV ...D DDDD
* Word 2: .HIC CIII 210. .GEE .PPS AASS RWPP PPPP
*
* PPPPPP - 6 bits. Port ID (see definitions in hardware/c13x0/c13x0_ioc.h
* and hardware.cc13x2_cc26x2/cc13x2_cc26x2_ioc)
* I - 1 bit Input Enable
* O - 1 bit GPIO output
* W - 1 bit Wakeup enable (CC13x2/CC26x only)
* CC - 2 bits Wakeup Configuration
* R - 1 bit RTC event enable (CC13x2/CC26x only)
* SS - 2 bits Drive strength
* H - 1 bit Input hysteresis
* S - 1 bit Reduced output slew enable
* PP - 2 bits Pull-up mode
* AA - 2 bits Current mode
* G - 1 bit Enable interrupt Generation
* III - 3 bits I/O mode
* EE - 2 bits Edge detect mode
* 0 - 1 bit Edge asserts AON_PROG0 (CC13x2/CC26x only) NOTE 1
* 1 - 1 bit Edge asserts AON_PROG1 (CC13x2/CC26x only) NOTE 1
* 2 - 1 bit Edge asserts AON_PROG2 (CC13x2/CC26x only) NOTE 1
* V - 1 bit GPIO output initial value
* DDDDD - 5 bits DIO 0-31
* Word 1: Describes GPIO and provides DIO index
*
* NOTE 1: Not currently implemented because no bits are available in
* the uint32_t. We need more bits!
* O - 1 bit GPIO output
* V - 1 bit GPIO output initial value
* DDDDD - 5 bits DIO 0-31
*
* Word 2: An image of the IOC configuration register (see definitions in
* hardware/c13x0/c13x0_ioc.h and hardware.cc13x2_cc26x2/cc13x2_cc26x2_ioc)
*
* PPPPPP - 6 bits. Port ID. Selects DIO usage
* W - 1 bit Input edge asserts MCU_WU event (CC13x2/CC26x only)
* R - 1 bit Input edge asserts RTC event (CC13x2/CC26x only)
* SS - 2 bits Drive strength
* AA - 2 bits I/O current mode
* S - 1 bit Reduced output slew enable
* PP - 2 bits Pull-up mode control
* EE - 2 bits Edge event generation
* G - 1 bit Enable interrupt Generation
* 0 - 1 bit Edge asserts AON_PROG0 (CC13x2/CC26x only)
* 1 - 1 bit Edge asserts AON_PROG1 (CC13x2/CC26x only)
* 2 - 1 bit Edge asserts AON_PROG2 (CC13x2/CC26x only)
* III - 3 bits I/O mode
* CC - 2 bits Wakeup Configuration
* I - 1 bit Input Enable
* H - 1 bit Input hysteresis
*/
/* Port ID
*
* PPPP PP.. .... .... .... .... .... ....
*
* See PORTID definitions in the IOC register definitions file.
*/
#define GPIO_PORTID_SHIFT (26) /* Bits 26-31: Port ID */
#define GPIO_PORTID_MASK (0x3f << GPIO_PORTID_SHIFT)
# define GPIO_PORTID(n) ((uint32_t)(n) << GPIO_PORTID_SHIFT)
/* Input Enable:
*
* .... ..I. .... .... .... .... .... ....
*/
#define GPIO_IE (1 << 25) /* Bit 25: Input Enable */
/* GPIO output:
*
* .... ...O .... .... .... .... .... ....
* Word 1: .... .... .... .... .... ..O. .... ....
*
* Valid only if Port ID=IOC_IOCFG_PORTID_GPIO
*/
#define GPIO_OUTPUT (1 << 24) /* Bit 24: Input Enable */
/* Wakeup enable (CC13x2/CC26x only):
*
* .... .... W... .... .... .... .... ....
*/
#define GPIO_WUEN (1 << 23) /* Bit 23: Input edge asserts MCU_WU event */
/* Wakeup Configuration:
*
* .... .... .CC. .... .... .... .... ....
*/
#define GPIO_WUCFG_SHIFT (21) /* Bits 21-22: Wakeup Configuration */
#define GPIO_WUCFG_MASK (3 << GPIO_WUCFG_SHIFT)
# define GPIO_WUCFG_NONE (0 << GPIO_WUCFG_SHIFT) /* 0, 1: Wakeup disabled */
# define GPIO_WUCFG_ENABLE (2 << GPIO_WUCFG_SHIFT) /* 2, 3: Wakeup enabled */
# define GPIO_WUCFG_WAKEUPL (2 << GPIO_WUCFG_SHIFT) /* Wakeup on transition low */
# define GPIO_WUCFG_WEKUPH (3 << GPIO_WUCFG_SHIFT) /* Wakeup on transition high */
/* RTC event enable (CC13x2/CC26x only):
*
* .... .... ...R .... .... .... .... ....
*/
#define GPIO_RTCEN (1 << 20) /* Bit 20: Input edge asserts RTC event */
/* Drive strength:
*
* .... .... .... SS.. .... .... .... ....
*/
#define GPIO_IOSTR_SHIFT (18) /* Bits 18-19: I/O drive strength */
#define GPIO_IOSTR_MASK (3 << GPIO_IOSTR_SHIFT)
# define GPIO_IOSTR_AUTO (0 << GPIO_IOSTR_SHIFT) /* Automatic drive strength */
# define GPIO_IOSTR_MIN (1 << GPIO_IOSTR_SHIFT) /* Minimum drive strength */
# define GPIO_IOSTR_MED (2 << GPIO_IOSTR_SHIFT) /* Medium drive strength */
# define GPIO_IOSTR_MAX (3 << GPIO_IOSTR_SHIFT) /* Maximum drive strength */
/* Input hysteresis:
*
* .... .... .... ..H. .... .... .... ....
*/
#define GPIO_HYSTEN (1 << 17) /* Bit 17: Input hysteresis enable */
/* Reduced output slew enable:
*
* .... .... .... ...S .... .... .... ....
*/
#define GPIO_SLEW_RED (1 << 16) /* Bit 16: Reduces output slew rate */
/* Pull-up mode:
*
* .... .... .... .... PP.. .... .... ....
*/
#define GPIO_PULL_SHIFT (14) /* Bits 14-15: Pull Control */
#define GPIO_PULL_MASK (3 << GPIO_PULL_SHIFT)
# define GPIO_PULL_DISABLE (3 << GPIO_PULL_SHIFT) /* No pull */
# define GPIO_PULL_DOWN (1 << GPIO_PULL_SHIFT) /* Pull down */
# define GPIO_PULL_UP (2 << GPIO_PULL_SHIFT) /* Pull up */
/* Current mode:
*
* .... .... .... .... ..AA .... .... ....
*/
#define GPIO_IOCURR_SHIFT (12) /* Bits 12-13: I/O current mode */
#define GPIO_IOCURR_MASK (3 << GPIO_IOCURR_SHIFT)
# define GPIO_IOCURR_2MA (0 << GPIO_IOCURR_SHIFT) /* Extended-Current (EC) mode */
# define GPIO_IOCURR_4MA (1 << GPIO_IOCURR_SHIFT) /* High-Current (HC) mode */
# define GPIO_IOCURR_8MA (2 << GPIO_IOCURR_SHIFT) /* Low-Current (LC) mode */
/* Enable edge interrupt generation:
*
* .... .... .... .... .... G... .... ....
*/
#define GPIO_EDGE_IRQEN (1 << 11) /* Bit 11: Enable edge interrupt generation */
/* I/O mode:
*
* .... .... .... .... .... .III .... ....
*/
#define GPIO_IOMODE_SHIFT (8) /* Bits 8-10: I/O Mode */
#define GPIO_IOMODE_MASK (7 << GPIO_IOMODE_SHIFT)
# define GPIO_IOMODE_NORMAL (0 << GPIO_IOMODE_SHIFT) /* Normal I/O */
# define GPIO_IOMODE_INV (1 << GPIO_IOMODE_SHIFT) /* Inverted I/O */
# define GPIO_IOMODE_OPENDR (4 << GPIO_IOMODE_SHIFT) /* Open drain */
# define GPIO_IOMODE_OPENDRINV (5 << GPIO_IOMODE_SHIFT) /* Open drain, inverted I/O */
# define GPIO_IOMODE_OPENSRC (6 << GPIO_IOMODE_SHIFT) /* Open source */
# define GPIO_IOMODE_OPENSRCINV (7 << GPIO_IOMODE_SHIFT) /* Open source, inverted I/O */
/* Edge detect mode
*
* .... .... .... .... .... .... EE.. ....
*/
#define GPIO_EDGE_SHIFT (6) /* Bits 6-7: Enable edge events generation */
#define GPIO_EDGE_MASK (3 << GPIO_EDGE_SHIFT)
# define GPIO_EDGE_NONE (0 << GPIO_EDGE_SHIFT) /* No edge detection */
# define GPIO_EDGE_NEG (1 << GPIO_EDGE_SHIFT) /* Negative edge detection */
# define GPIO_EDGE_POS (2 << GPIO_EDGE_SHIFT) /* Positive edge detection */
# define GPIO_EDGE_BOTH (3 << GPIO_EDGE_SHIFT) /* Both edge detection */
#if 0 /* Need more bits! */
/* Edge asserts AON_PROG0/1/2 (CC13x2/CC26x only):
*
* .... .... .... .... .... .... .... ....
*/
#define GPIO_AON_PROG0 (1 << xx) /* Bit xx: Input edge asserts AON_PROG0 */
#define GPIO_AON_PROG1 (1 << xx) /* Bit xx: Input edge asserts AON_PROG1 */
#define GPIO_AON_PROG2 (1 << xx) /* Bit xx: Input edge assert AON_PROG2 */
#endif
#define GPIO_OUTPUT (1 << 9) /* Bit 9: GPIO output (if GPIO) */
/* GPIO output initial value:
*
* .... .... .... .... .... .... ..V. ....
* Word 1: .... .... .... .... .... ...V .... ....
*
* Valid only if Port ID=IOC_IOCFG_PORTID_GPIO and GPIO_OUTPUT selected.
*/
#define GPIO_VALUE_SHIFT 8 /* Bit 5: If output, inital value of output */
#define GPIO_VALUE_SHIFT 8 /* Bit 8: If GPIO output,
* initial 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 */
# define GPIO_VALUE_ZERO (0 << GPIO_VALUE_SHIFT) /* Initial value is zero */
# define GPIO_VALUE_ONE (1 << GPIO_VALUE_SHIFT) /* Initial value is one */
/* DIO:
*
* .... .... .... .... .... .... ...D DDDD
* Word 1: .... .... .... .... .... .... ...D DDDD
*/
#define GPIO_DIO_SHIFT (0) /* Bits 0-4: DIO */
#define GPIO_DIO_MASK (0x1f << GPIO_PORTID_SHIFT)
# define GPIO_DIO(n) ((uint32_t)(n) << GPIO_PORTID_SHIFT)
#define GPIO_DIO_MASK (0x1f << GPIO_DIO_SHIFT)
# define GPIO_DIO(n) ((uint32_t)(n) << GPIO_DIO_SHIFT)
/* Helper Definitions *******************************************************/
#define GPIO_STD_INPUT (GPIO_IOCURR_2MA | GPIO_IOSTR_AUTO | \
GPIO_PULL_DISABLE | GPIO_EDGE_NONE | \
GPIO_IOMODE_NORMAL | GPIO_IE)
#define GPIO_STD_OUTPUT (GPIO_IOCURR_2MA | GPIO_IOSTR_AUTO | \
GPIO_PULL_DISABLE | GPIO_EDGE_NONE | \
GPIO_IOMODE_NORMAL)
#define IOC_STD_INPUT (IOC_IOCFG_IOCURR_2MA | \
IOC_IOCFG_IOSTR_AUTO | \
IOC_IOCFG_PULLCTL_DIS | \
IOC_IOCFG_EDGEDET_NONE | \
IOC_IOCFG_IOMODE_NORMAL | \
IOC_IOCFG_IE)
#define IOC_STD_OUTPUT (IOC_IOCFG_IOCURR_2MA | \
IOC_IOCFG_IOSTR_AUTO | \
IOC_IOCFG_PULLCTL_DIS | \
IOC_IOCFG_EDGEDET_NONE | \
IOC_IOCFG_IOMODE_NORMAL)
/****************************************************************************
* Public Types
****************************************************************************/
/* This structure represents the pin configuration */
struct cc134xx_pinconfig_s
{
uint32_t gpio; /* GPIO and DIO definitions */
uint32_t ioc; /* IOC configuration register image */
};
/* This opaque type permits common function prototype for GPIO functions
* across all MCUs.
*/
typedef const struct cc134xx_pinconfig_s *pinconfig_t;
/****************************************************************************
* Public Function Prototypes

View File

@ -241,28 +241,6 @@ static int gpioport2irq(uint8_t port)
return irq;
}
/****************************************************************************
* Name: tiva_gpioirqstatus
*
* Description:
* Returns raw or masked interrupt status.
*
****************************************************************************/
uint32_t tiva_gpioirqstatus(uint8_t port, bool masked)
{
uintptr_t base = tiva_gpiobaseaddress(port);
if (masked)
{
return getreg32(base + TIVA_GPIO_MIS_OFFSET);
}
else
{
return getreg32(base + TIVA_GPIO_RIS_OFFSET);
}
}
/****************************************************************************
* Name: tiva_gpioirqclear
*
@ -293,13 +271,18 @@ void tiva_gpioirqclear(uint8_t port, uint32_t pinmask)
static int tiva_gpioporthandler(uint8_t port, void *context)
{
uintptr_t base; /* GPIO base address */
int irq; /* GPIO port interrupt vector */
uint32_t mis; /* Masked Interrupt Status */
uint8_t pin; /* Pin number */
int irq = gpioport2irq(port); /* GPIO port interrupt vector */
uint32_t mis = tiva_gpioirqstatus(port, true); /* Masked Interrupt Status */
uint8_t pin; /* Pin number */
base = tiva_gpiobaseaddress(port);
irq = gpioport2irq(port);
mis = getreg32(base + TIVA_GPIO_MIS_OFFSET);
tiva_gpioirqclear(port, 0xff);
gpioinfo("mis=0b%08b\n", mis & 0xff);
gpioinfo("irq=%d mis=0b%08b\n", irq, mis & 0xff);
/* Now process each IRQ pending in the MIS */

View File

@ -88,7 +88,7 @@
/* IOC register addresses **********************************************************/
#define TIVA_IOC_IOCFG_(n) (TIVA_IOC_BASE + TIVA_IOC_IOCFG_OFFSET(n))
#define TIVA_IOC_IOCFG(n) (TIVA_IOC_BASE + TIVA_IOC_IOCFG_OFFSET(n))
# define TIVA_IOC_IOCFG0 (TIVA_IOC_BASE + TIVA_IOC_IOCFG0_OFFSET)
# define TIVA_IOC_IOCFG1 (TIVA_IOC_BASE + TIVA_IOC_IOCFG1_OFFSET)
# define TIVA_IOC_IOCFG2 (TIVA_IOC_BASE + TIVA_IOC_IOCFG2_OFFSET)

View File

@ -88,7 +88,7 @@
/* IOC register addresses **********************************************************/
#define TIVA_IOC_IOCFG_(n) (TIVA_IOC_BASE + TIVA_IOC_IOCFG_OFFSET(n))
#define TIVA_IOC_IOCFG(n) (TIVA_IOC_BASE + TIVA_IOC_IOCFG_OFFSET(n))
# define TIVA_IOC_IOCFG0 (TIVA_IOC_BASE + TIVA_IOC_IOCFG0_OFFSET)
# define TIVA_IOC_IOCFG1 (TIVA_IOC_BASE + TIVA_IOC_IOCFG1_OFFSET)
# define TIVA_IOC_IOCFG2 (TIVA_IOC_BASE + TIVA_IOC_IOCFG2_OFFSET)
@ -124,8 +124,8 @@
/* IOC register bit settings *******************************************************/
#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_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_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 */

View File

@ -358,9 +358,9 @@ static void tiva_gpiofunc(uint32_t base, uint32_t pinno,
****************************************************************************/
static inline void tiva_gpiopadstrength(uint32_t base, uint32_t pin,
uint32_t pinset)
pinconfig_t pinconfig)
{
int strength = (pinset & GPIO_STRENGTH_MASK);
int strength = (pinconfig & GPIO_STRENGTH_MASK);
uint32_t slrset = 0;
uint32_t slrclr = 0;
uint32_t dr2rset = 0;
@ -431,9 +431,9 @@ static inline void tiva_gpiopadstrength(uint32_t base, uint32_t pin,
****************************************************************************/
static inline void tiva_gpiopadtype(uint32_t base, uint32_t pin,
uint32_t pinset)
pinconfig_t pinconfig)
{
int padtype = (pinset & GPIO_PADTYPE_MASK);
int padtype = (pinconfig & GPIO_PADTYPE_MASK);
uint32_t odrset = 0;
uint32_t odrclr = 0;
uint32_t purset = 0;
@ -528,10 +528,10 @@ static inline void tiva_gpiopadtype(uint32_t base, uint32_t pin,
*
****************************************************************************/
static inline void tiva_initoutput(uint32_t pinset)
static inline void tiva_initoutput(pinconfig_t pinconfig)
{
bool value = ((pinset & GPIO_VALUE_MASK) != GPIO_VALUE_ZERO);
tiva_gpiowrite(pinset, value);
bool value = ((pinconfig & GPIO_VALUE_MASK) != GPIO_VALUE_ZERO);
tiva_gpiowrite(pinconfig, value);
}
/****************************************************************************
@ -543,12 +543,12 @@ static inline void tiva_initoutput(uint32_t pinset)
****************************************************************************/
#ifdef CONFIG_TIVA_GPIO_IRQS
static inline void tiva_interrupt(uint32_t pinset)
static inline void tiva_interrupt(pinconfig_t pinconfig)
{
uint8_t port = (pinset & GPIO_PORT_MASK) >> GPIO_PORT_SHIFT;
uint8_t pin = 1 << (pinset & GPIO_PIN_MASK);
uint8_t port = (pinconfig & GPIO_PORT_MASK) >> GPIO_PORT_SHIFT;
uint8_t pin = 1 << (pinconfig & GPIO_PIN_MASK);
uintptr_t base = tiva_gpiobaseaddress(port);
uint32_t inttype = pinset & GPIO_INT_MASK;
uint32_t inttype = pinconfig & GPIO_INT_MASK;
uint32_t isset = 0;
uint32_t ibeset = 0;
@ -668,7 +668,7 @@ static inline void tiva_interrupt(uint32_t pinset)
*
****************************************************************************/
int tiva_configgpio(uint32_t pinset)
int tiva_configgpio(pinconfig_t pinconfig)
{
irqstate_t flags;
unsigned int func;
@ -679,9 +679,9 @@ int tiva_configgpio(uint32_t pinset)
/* Decode the basics */
func = (pinset & GPIO_FUNC_MASK) >> GPIO_FUNC_SHIFT;
port = (pinset & GPIO_PORT_MASK) >> GPIO_PORT_SHIFT;
pinno = (pinset & GPIO_PIN_MASK);
func = (pinconfig & GPIO_FUNC_MASK) >> GPIO_FUNC_SHIFT;
port = (pinconfig & GPIO_PORT_MASK) >> GPIO_PORT_SHIFT;
pinno = (pinconfig & GPIO_PIN_MASK);
pin = (1 << pinno);
DEBUGASSERT(func <= GPIO_FUNC_MAX);
@ -714,8 +714,8 @@ int tiva_configgpio(uint32_t pinset)
* user options.
*/
tiva_gpiopadstrength(base, pin, pinset);
tiva_gpiopadtype(base, pin, pinset);
tiva_gpiopadstrength(base, pin, pinconfig);
tiva_gpiopadtype(base, pin, pinconfig);
/* Then set up the real pin function */
@ -725,7 +725,7 @@ int tiva_configgpio(uint32_t pinset)
if (func == 1 || func == 3 || func == 5)
{
tiva_initoutput(pinset);
tiva_initoutput(pinconfig);
}
#ifdef CONFIG_TIVA_GPIO_IRQS
@ -733,7 +733,7 @@ int tiva_configgpio(uint32_t pinset)
else if (func == 7)
{
tiva_interrupt(pinset);
tiva_interrupt(pinconfig);
}
#endif
@ -749,7 +749,7 @@ int tiva_configgpio(uint32_t pinset)
*
****************************************************************************/
void tiva_gpiowrite(uint32_t pinset, bool value)
void tiva_gpiowrite(pinconfig_t pinconfig, bool value)
{
unsigned int port;
unsigned int pinno;
@ -757,8 +757,8 @@ void tiva_gpiowrite(uint32_t pinset, bool value)
/* Decode the basics */
port = (pinset & GPIO_PORT_MASK) >> GPIO_PORT_SHIFT;
pinno = (pinset & GPIO_PIN_MASK);
port = (pinconfig & GPIO_PORT_MASK) >> GPIO_PORT_SHIFT;
pinno = (pinconfig & GPIO_PIN_MASK);
/* Get the base address associated with the GPIO port */
@ -787,7 +787,7 @@ void tiva_gpiowrite(uint32_t pinset, bool value)
*
****************************************************************************/
bool tiva_gpioread(uint32_t pinset)
bool tiva_gpioread(pinconfig_t pinconfig)
{
unsigned int port;
unsigned int pinno;
@ -795,8 +795,8 @@ bool tiva_gpioread(uint32_t pinset)
/* Decode the basics */
port = (pinset & GPIO_PORT_MASK) >> GPIO_PORT_SHIFT;
pinno = (pinset & GPIO_PIN_MASK);
port = (pinconfig & GPIO_PORT_MASK) >> GPIO_PORT_SHIFT;
pinno = (pinconfig & GPIO_PIN_MASK);
/* Get the base address associated with the GPIO port */
@ -826,7 +826,7 @@ bool tiva_gpioread(uint32_t pinset)
*
****************************************************************************/
void tiva_gpio_lockport(uint32_t pinset, bool lock)
void tiva_gpio_lockport(pinconfig_t pinconfig, bool lock)
{
unsigned int port;
unsigned int pinno;
@ -835,8 +835,8 @@ void tiva_gpio_lockport(uint32_t pinset, bool lock)
/* Decode the basics */
port = (pinset & GPIO_PORT_MASK) >> GPIO_PORT_SHIFT;
pinno = (pinset & GPIO_PIN_MASK);
port = (pinconfig & GPIO_PORT_MASK) >> GPIO_PORT_SHIFT;
pinno = (pinconfig & GPIO_PIN_MASK);
pinmask = 1 << pinno;
/* Get the base address associated with the GPIO port */

View File

@ -374,9 +374,9 @@ static void tiva_gpiofunc(uint32_t base, uint32_t pinno,
****************************************************************************/
static inline void tiva_gpiopadstrength(uint32_t base, uint32_t pin,
uint32_t pinset)
pinconfig_t pinconfig)
{
int strength = (pinset & GPIO_STRENGTH_MASK);
int strength = (pinconfig & GPIO_STRENGTH_MASK);
uint32_t slrset = 0;
uint32_t slrclr = 0;
uint32_t dr2rset = 0;
@ -447,9 +447,9 @@ static inline void tiva_gpiopadstrength(uint32_t base, uint32_t pin,
****************************************************************************/
static inline void tiva_gpiopadtype(uint32_t base, uint32_t pin,
uint32_t pinset)
pinconfig_t pinconfig)
{
int padtype = (pinset & GPIO_PADTYPE_MASK);
int padtype = (pinconfig & GPIO_PADTYPE_MASK);
uint32_t odrset = 0;
uint32_t odrclr = 0;
uint32_t purset = 0;
@ -554,10 +554,10 @@ static inline void tiva_gpiopadtype(uint32_t base, uint32_t pin,
*
****************************************************************************/
static inline void tiva_initoutput(uint32_t pinset)
static inline void tiva_initoutput(pinconfig_t pinconfig)
{
bool value = ((pinset & GPIO_VALUE_MASK) != GPIO_VALUE_ZERO);
tiva_gpiowrite(pinset, value);
bool value = ((pinconfig & GPIO_VALUE_MASK) != GPIO_VALUE_ZERO);
tiva_gpiowrite(pinconfig, value);
}
/****************************************************************************
@ -569,12 +569,12 @@ static inline void tiva_initoutput(uint32_t pinset)
****************************************************************************/
#ifdef CONFIG_TIVA_GPIO_IRQS
static inline void tiva_interrupt(uint32_t pinset)
static inline void tiva_interrupt(pinconfig_t pinconfig)
{
uint8_t port = (pinset & GPIO_PORT_MASK) >> GPIO_PORT_SHIFT;
uint8_t pin = 1 << (pinset & GPIO_PIN_MASK);
uint8_t port = (pinconfig & GPIO_PORT_MASK) >> GPIO_PORT_SHIFT;
uint8_t pin = 1 << (pinconfig & GPIO_PIN_MASK);
uintptr_t base = tiva_gpiobaseaddress(port);
uint32_t inttype = pinset & GPIO_INT_MASK;
uint32_t inttype = pinconfig & GPIO_INT_MASK;
uint32_t isset = 0;
uint32_t ibeset = 0;
@ -691,7 +691,7 @@ static inline void tiva_interrupt(uint32_t pinset)
****************************************************************************/
static inline void tiva_portcontrol(uint32_t base, uint32_t pinno,
uint32_t pinset,
pinconfig_t pinconfig,
const struct gpio_func_s *func)
{
uint32_t alt = 0;
@ -706,7 +706,7 @@ static inline void tiva_portcontrol(uint32_t base, uint32_t pinno,
* configuration.
*/
alt = (pinset & GPIO_ALT_MASK) >> GPIO_ALT_SHIFT;
alt = (pinconfig & GPIO_ALT_MASK) >> GPIO_ALT_SHIFT;
}
/* Set the alternate function in the port control register */
@ -730,7 +730,7 @@ static inline void tiva_portcontrol(uint32_t base, uint32_t pinno,
*
****************************************************************************/
int tiva_configgpio(uint32_t pinset)
int tiva_configgpio(uint32_t pinconfig)
{
irqstate_t flags;
unsigned int func;
@ -741,9 +741,9 @@ int tiva_configgpio(uint32_t pinset)
/* Decode the basics */
func = (pinset & GPIO_FUNC_MASK) >> GPIO_FUNC_SHIFT;
port = (pinset & GPIO_PORT_MASK) >> GPIO_PORT_SHIFT;
pinno = (pinset & GPIO_PIN_MASK);
func = (pinconfig & GPIO_FUNC_MASK) >> GPIO_FUNC_SHIFT;
port = (pinconfig & GPIO_PORT_MASK) >> GPIO_PORT_SHIFT;
pinno = (pinconfig & GPIO_PIN_MASK);
pin = (1 << pinno);
DEBUGASSERT(func <= GPIO_FUNC_MAX);
@ -770,26 +770,26 @@ int tiva_configgpio(uint32_t pinset)
*/
tiva_gpiofunc(base, pinno, &g_funcbits[0]);
tiva_portcontrol(base, pinno, pinset, &g_funcbits[0]);
tiva_portcontrol(base, pinno, pinconfig, &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.
*/
tiva_gpiopadstrength(base, pin, pinset);
tiva_gpiopadtype(base, pin, pinset);
tiva_gpiopadstrength(base, pin, pinconfig);
tiva_gpiopadtype(base, pin, pinconfig);
/* Then set up the real pin function */
tiva_gpiofunc(base, pinno, &g_funcbits[func]);
tiva_portcontrol(base, pinno, pinset, &g_funcbits[func]);
tiva_portcontrol(base, pinno, pinconfig, &g_funcbits[func]);
/* Special case GPIO digital output pins */
if (func == 1 || func == 3 || func == 5)
{
tiva_initoutput(pinset);
tiva_initoutput(pinconfig);
}
#ifdef CONFIG_TIVA_GPIO_IRQS
@ -797,7 +797,7 @@ int tiva_configgpio(uint32_t pinset)
else if (func == 7)
{
tiva_interrupt(pinset);
tiva_interrupt(pinconfig);
}
#endif
@ -813,7 +813,7 @@ int tiva_configgpio(uint32_t pinset)
*
****************************************************************************/
void tiva_gpiowrite(uint32_t pinset, bool value)
void tiva_gpiowrite(pinconfig_t pinconfig, bool value)
{
unsigned int port;
unsigned int pinno;
@ -821,8 +821,8 @@ void tiva_gpiowrite(uint32_t pinset, bool value)
/* Decode the basics */
port = (pinset & GPIO_PORT_MASK) >> GPIO_PORT_SHIFT;
pinno = (pinset & GPIO_PIN_MASK);
port = (pinconfig & GPIO_PORT_MASK) >> GPIO_PORT_SHIFT;
pinno = (pinconfig & GPIO_PIN_MASK);
/* Get the base address associated with the GPIO port */
@ -851,7 +851,7 @@ void tiva_gpiowrite(uint32_t pinset, bool value)
*
****************************************************************************/
bool tiva_gpioread(uint32_t pinset)
bool tiva_gpioread(pinconfig_t pinconfig)
{
unsigned int port;
unsigned int pinno;
@ -859,8 +859,8 @@ bool tiva_gpioread(uint32_t pinset)
/* Decode the basics */
port = (pinset & GPIO_PORT_MASK) >> GPIO_PORT_SHIFT;
pinno = (pinset & GPIO_PIN_MASK);
port = (pinconfig & GPIO_PORT_MASK) >> GPIO_PORT_SHIFT;
pinno = (pinconfig & GPIO_PIN_MASK);
/* Get the base address associated with the GPIO port */
@ -890,7 +890,7 @@ bool tiva_gpioread(uint32_t pinset)
*
****************************************************************************/
void tiva_gpio_lockport(uint32_t pinset, bool lock)
void tiva_gpio_lockport(pinconfig_t pinconfig, bool lock)
{
unsigned int port;
unsigned int pinno;
@ -899,8 +899,8 @@ void tiva_gpio_lockport(uint32_t pinset, bool lock)
/* Decode the basics */
port = (pinset & GPIO_PORT_MASK) >> GPIO_PORT_SHIFT;
pinno = (pinset & GPIO_PIN_MASK);
port = (pinconfig & GPIO_PORT_MASK) >> GPIO_PORT_SHIFT;
pinno = (pinconfig & GPIO_PIN_MASK);
pinmask = 1 << pinno;
/* Get the base address associated with the GPIO port */

View File

@ -262,6 +262,16 @@
# define GPIO_PIN_6 (6 << GPIO_PIN_SHIFT)
# define GPIO_PIN_7 (7 << GPIO_PIN_SHIFT)
/****************************************************************************
* Public Types
****************************************************************************/
/* This opaque type permits common function prototype for GPIO functions
* across all MCUs.
*/
typedef uint32_t pinconfig_t;
/****************************************************************************
* Public Function Prototypes
****************************************************************************/

View File

@ -85,7 +85,7 @@ extern "C"
*
****************************************************************************/
int tiva_configgpio(uint32_t pinset);
int tiva_configgpio(pinconfig_t pinconfig);
/****************************************************************************
* Name: tiva_gpiowrite
@ -95,7 +95,7 @@ int tiva_configgpio(uint32_t pinset);
*
****************************************************************************/
void tiva_gpiowrite(uint32_t pinset, bool value);
void tiva_gpiowrite(pinconfig_t pinconfig, bool value);
/****************************************************************************
* Name: tiva_gpioread
@ -105,7 +105,7 @@ void tiva_gpiowrite(uint32_t pinset, bool value);
*
****************************************************************************/
bool tiva_gpioread(uint32_t pinset);
bool tiva_gpioread(pinconfig_t pinconfig);
/****************************************************************************
* Function: tiva_dumpgpio
@ -115,7 +115,7 @@ bool tiva_gpioread(uint32_t pinset);
*
****************************************************************************/
int tiva_dumpgpio(uint32_t pinset, const char *msg);
int tiva_dumpgpio(pinconfig_t pinconfig, const char *msg);
/****************************************************************************
* Name: tiva_gpio_lockport
@ -126,10 +126,12 @@ int tiva_dumpgpio(uint32_t pinset, const char *msg);
*
****************************************************************************/
void tiva_gpio_lockport(uint32_t pinset, bool lock);
#if defined(CONFIG_ARCH_CHIP_LM) || defined(CONFIG_ARCH_CHIP_TM4C)
void tiva_gpio_lockport(pinconfig_t pinconfig, bool lock);
#endif
/****************************************************************************
* Function: tiva_dumpgpio
* Function: tiva_gpio_dumpconfig
*
* Description:
* Dump all GPIO registers associated with the provided base address
@ -137,7 +139,7 @@ void tiva_gpio_lockport(uint32_t pinset, bool lock);
****************************************************************************/
#ifdef CONFIG_DEBUG_GPIO_INFO
void tiva_gpio_dumpconfig(uint32_t pinset);
void tiva_gpio_dumpconfig(pinconfig_t pinconfig);
#else
# define tiva_gpio_dumpconfig(p)
#endif
@ -168,7 +170,7 @@ int weak_function 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);
# define tiva_gpioirqdetach(p) tiva_gpioirqattach((p),NULL,NULL)
/****************************************************************************
@ -203,16 +205,6 @@ void tiva_gpioirqenable(uint8_t port, uint8_t pin);
void tiva_gpioirqdisable(uint8_t port, uint8_t pin);
/****************************************************************************
* Name: tiva_gpioirqstatus
*
* Description:
* Returns raw or masked interrupt status.
*
****************************************************************************/
uint32_t tiva_gpioirqstatus(uint8_t port, bool masked);
/****************************************************************************
* Name: tiva_gpioirqclear
*

View File

@ -243,7 +243,7 @@ inline uintptr_t tiva_gpiobaseaddress(unsigned int port)
*
****************************************************************************/
static void tiva_gpiofunc(uint32_t base, uint32_t pinno,
static void tiva_gpiofunc(uintptr_t base, uint32_t pinno,
const struct gpio_func_s *func)
{
uint32_t setbit;
@ -374,9 +374,9 @@ static void tiva_gpiofunc(uint32_t base, uint32_t pinno,
****************************************************************************/
static inline void tiva_gpiopadstrength(uint32_t base, uint32_t pin,
uint32_t pinset)
pinconfig_t pinconfig)
{
int strength = (pinset & GPIO_STRENGTH_MASK);
int strength = (pinconfig & GPIO_STRENGTH_MASK);
uint32_t slrset = 0;
uint32_t slrclr = 0;
uint32_t dr2rset = 0;
@ -487,9 +487,9 @@ static inline void tiva_gpiopadstrength(uint32_t base, uint32_t pin,
****************************************************************************/
static inline void tiva_gpiopadtype(uint32_t base, uint32_t pin,
uint32_t pinset)
pinconfig_t pinconfig)
{
int padtype = (pinset & GPIO_PADTYPE_MASK);
int padtype = (pinconfig & GPIO_PADTYPE_MASK);
uint32_t odrset = 0;
uint32_t odrclr = 0;
uint32_t purset = 0;
@ -601,10 +601,10 @@ static inline void tiva_gpiopadtype(uint32_t base, uint32_t pin,
*
****************************************************************************/
static inline void tiva_initoutput(uint32_t pinset)
static inline void tiva_initoutput(pinconfig_t pinconfig)
{
bool value = ((pinset & GPIO_VALUE_MASK) != GPIO_VALUE_ZERO);
tiva_gpiowrite(pinset, value);
bool value = ((pinconfig & GPIO_VALUE_MASK) != GPIO_VALUE_ZERO);
tiva_gpiowrite(pinconfig, value);
}
/****************************************************************************
@ -616,12 +616,12 @@ static inline void tiva_initoutput(uint32_t pinset)
****************************************************************************/
#ifdef CONFIG_TIVA_GPIO_IRQS
static inline void tiva_interrupt(uint32_t pinset)
static inline void tiva_interrupt(pinconfig_t pinconfig)
{
uint8_t port = (pinset & GPIO_PORT_MASK) >> GPIO_PORT_SHIFT;
uint8_t pin = 1 << (pinset & GPIO_PIN_MASK);
uint8_t port = (pinconfig & GPIO_PORT_MASK) >> GPIO_PORT_SHIFT;
uint8_t pin = 1 << (pinconfig & GPIO_PIN_MASK);
uintptr_t base = tiva_gpiobaseaddress(port);
uint32_t inttype = pinset & GPIO_INT_MASK;
uint32_t inttype = pinconfig & GPIO_INT_MASK;
uint32_t isset = 0;
uint32_t ibeset = 0;
@ -738,7 +738,7 @@ static inline void tiva_interrupt(uint32_t pinset)
****************************************************************************/
static inline void tiva_portcontrol(uint32_t base, uint32_t pinno,
uint32_t pinset,
pinconfig_t pinconfig,
const struct gpio_func_s *func)
{
uint32_t alt = 0;
@ -753,7 +753,7 @@ static inline void tiva_portcontrol(uint32_t base, uint32_t pinno,
* configuration.
*/
alt = (pinset & GPIO_ALT_MASK) >> GPIO_ALT_SHIFT;
alt = (pinconfig & GPIO_ALT_MASK) >> GPIO_ALT_SHIFT;
}
/* Set the alternate function in the port control register */
@ -777,7 +777,7 @@ static inline void tiva_portcontrol(uint32_t base, uint32_t pinno,
*
****************************************************************************/
int tiva_configgpio(uint32_t pinset)
int tiva_configgpio(pinconfig_t pinconfig)
{
irqstate_t flags;
unsigned int func;
@ -788,9 +788,9 @@ int tiva_configgpio(uint32_t pinset)
/* Decode the basics */
func = (pinset & GPIO_FUNC_MASK) >> GPIO_FUNC_SHIFT;
port = (pinset & GPIO_PORT_MASK) >> GPIO_PORT_SHIFT;
pinno = (pinset & GPIO_PIN_MASK);
func = (pinconfig & GPIO_FUNC_MASK) >> GPIO_FUNC_SHIFT;
port = (pinconfig & GPIO_PORT_MASK) >> GPIO_PORT_SHIFT;
pinno = (pinconfig & GPIO_PIN_MASK);
pin = (1 << pinno);
DEBUGASSERT(func <= GPIO_FUNC_MAX);
@ -822,26 +822,26 @@ int tiva_configgpio(uint32_t pinset)
*/
tiva_gpiofunc(base, pinno, &g_funcbits[0]);
tiva_portcontrol(base, pinno, pinset, &g_funcbits[0]);
tiva_portcontrol(base, pinno, pinconfig, &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.
*/
tiva_gpiopadstrength(base, pin, pinset);
tiva_gpiopadtype(base, pin, pinset);
tiva_gpiopadstrength(base, pin, pinconfig);
tiva_gpiopadtype(base, pin, pinconfig);
/* Then set up the real pin function */
tiva_gpiofunc(base, pinno, &g_funcbits[func]);
tiva_portcontrol(base, pinno, pinset, &g_funcbits[func]);
tiva_portcontrol(base, pinno, pinconfig, &g_funcbits[func]);
/* Special case GPIO digital output pins */
if (func == 1 || func == 3 || func == 5)
{
tiva_initoutput(pinset);
tiva_initoutput(pinconfig);
}
#ifdef CONFIG_TIVA_GPIO_IRQS
@ -849,7 +849,7 @@ int tiva_configgpio(uint32_t pinset)
else if (func == 7)
{
tiva_interrupt(pinset);
tiva_interrupt(pinconfig);
}
#endif
@ -865,7 +865,7 @@ int tiva_configgpio(uint32_t pinset)
*
****************************************************************************/
void tiva_gpiowrite(uint32_t pinset, bool value)
void tiva_gpiowrite(pinconfig_t pinconfig, bool value)
{
unsigned int port;
unsigned int pinno;
@ -873,8 +873,8 @@ void tiva_gpiowrite(uint32_t pinset, bool value)
/* Decode the basics */
port = (pinset & GPIO_PORT_MASK) >> GPIO_PORT_SHIFT;
pinno = (pinset & GPIO_PIN_MASK);
port = (pinconfig & GPIO_PORT_MASK) >> GPIO_PORT_SHIFT;
pinno = (pinconfig & GPIO_PIN_MASK);
/* Get the base address associated with the GPIO port */
@ -903,7 +903,7 @@ void tiva_gpiowrite(uint32_t pinset, bool value)
*
****************************************************************************/
bool tiva_gpioread(uint32_t pinset)
bool tiva_gpioread(pinconfig_t pinconfig)
{
unsigned int port;
unsigned int pinno;
@ -911,8 +911,8 @@ bool tiva_gpioread(uint32_t pinset)
/* Decode the basics */
port = (pinset & GPIO_PORT_MASK) >> GPIO_PORT_SHIFT;
pinno = (pinset & GPIO_PIN_MASK);
port = (pinconfig & GPIO_PORT_MASK) >> GPIO_PORT_SHIFT;
pinno = (pinconfig & GPIO_PIN_MASK);
/* Get the base address associated with the GPIO port */
@ -942,7 +942,7 @@ bool tiva_gpioread(uint32_t pinset)
*
****************************************************************************/
void tiva_gpio_lockport(uint32_t pinset, bool lock)
void tiva_gpio_lockport(pinconfig_t pinconfig, bool lock)
{
unsigned int port;
unsigned int pinno;
@ -951,8 +951,8 @@ void tiva_gpio_lockport(uint32_t pinset, bool lock)
/* Decode the basics */
port = (pinset & GPIO_PORT_MASK) >> GPIO_PORT_SHIFT;
pinno = (pinset & GPIO_PIN_MASK);
port = (pinconfig & GPIO_PORT_MASK) >> GPIO_PORT_SHIFT;
pinno = (pinconfig & GPIO_PIN_MASK);
pinmask = 1 << pinno;
/* Get the base address associated with the GPIO port */

View File

@ -292,6 +292,17 @@
# define GPIO_PIN_6 (6 << GPIO_PIN_SHIFT)
# define GPIO_PIN_7 (7 << GPIO_PIN_SHIFT)
/****************************************************************************
* Public Types
****************************************************************************/
/* This opaque type permits common function prototype for GPIO functions
* across all MCUs.
*/
typedef uint32_t pinconfig_t;
/****************************************************************************
/****************************************************************************
* Public Function Prototypes
****************************************************************************/

View File

@ -100,19 +100,32 @@
/* Button definitions *******************************************************/
/* Pin Disambiguation *******************************************************/
/* Pin configuration ********************************************************/
#ifdef CONFIG_TIVA_UART0
/* UART0:
*
* The on-board XDS110 Debugger provide a USB virtual serial console using
* UART0 (PA0/U0RX and PA1/U0TX).
*/
#define GPIO_UART0_RX (GPIO_PORTID(IOC_IOCFG_PORTID_UART0_RX) | \
GPIO_STD_INPUT | GPIO_DIO(0))
#define GPIO_UART0_TX (GPIO_PORTID(IOC_IOCFG_PORTID_UART0_TX) | \
GPIO_STD_OUTPUT | GPIO_DIO(1))
# define GPIO_UART0_RX &g_gpio_uart0_rx
# define GPIO_UART0_TX &g_gpio_uart0_tx
#endif
/* DMA **********************************************************************/
/****************************************************************************
* Public Data
****************************************************************************/
/* Pin configuration ********************************************************/
struct cc134xx_pinconfig_s; /* Forward reference */
#ifdef CONFIG_TIVA_UART0
extern const struct cc134xx_pinconfig_s g_gpio_uart0_rx;
extern const struct cc134xx_pinconfig_s g_gpio_uart0_tx;
#endif
#endif /* __CONFIG_NUCLEO_F303ZE_INCLUDE_BOARD_H */

View File

@ -36,7 +36,7 @@
-include $(TOPDIR)/Make.defs
ASRCS =
CSRCS = cc1312_boot.c
CSRCS = cc1312_boot.c cc1312_pinconfig.c
ifeq ($(CONFIG_LIB_BOARDCTL),y)
CSRCS += cc1312_appinit.c cc1312_bringup.c

View File

@ -0,0 +1,80 @@
/****************************************************************************
* configs/launchxl-cc1312r1/src/cc1312_userleds.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 "hardware/tiva_ioc.h"
#include "tiva_gpio.h"
#include "launchxl-cc1312r1.h"
/****************************************************************************
* Public Data
****************************************************************************/
#ifdef CONFIG_TIVA_UART0
/* UART0:
*
* The on-board XDS110 Debugger provide a USB virtual serial console using
* UART0 (PA0/U0RX and PA1/U0TX).
*/
const struct cc134xx_pinconfig_s g_gpio_uart0_rx =
{
.gpio =
{
GPIO_DIO(0)
},
.ioc =
{
GPIO_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
}
};
#endif