From d1b5dcf2deac5613a03a84156176d9f2d4d16cca Mon Sep 17 00:00:00 2001 From: patacongo Date: Tue, 5 Mar 2013 00:31:43 +0000 Subject: Add LM4F120 pin configuration header file git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@5705 42af7a65-404d-4744-a932-0658087f49c3 --- nuttx/arch/arm/src/lm/chip/lm4f_pinmap.h | 215 +++++++++++++++++++++++++++++++ nuttx/arch/arm/src/lm/chip/lm_gpio.h | 24 ++++ nuttx/arch/arm/src/lm/lm_gpio.c | 105 ++++++++++++--- nuttx/arch/arm/src/lm/lm_gpio.h | 127 +++++++++++------- 4 files changed, 404 insertions(+), 67 deletions(-) create mode 100644 nuttx/arch/arm/src/lm/chip/lm4f_pinmap.h (limited to 'nuttx/arch') diff --git a/nuttx/arch/arm/src/lm/chip/lm4f_pinmap.h b/nuttx/arch/arm/src/lm/chip/lm4f_pinmap.h new file mode 100644 index 000000000..567ca4c1c --- /dev/null +++ b/nuttx/arch/arm/src/lm/chip/lm4f_pinmap.h @@ -0,0 +1,215 @@ +/************************************************************************************ + * arch/arm/src/lm/chip/lm4f_pinmap.h + * + * Copyright (C) 2013 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name NuttX nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ************************************************************************************/ + +#ifndef __ARCH_ARM_SRC_LM_CHIP_LM4F_PINMAP_H +#define __ARCH_ARM_SRC_LM_CHIP_LM4F_PINMAP_H + +/************************************************************************************ + * Included Files + ************************************************************************************/ + +#include + +/************************************************************************************ + * Pre-processor Definitions + ************************************************************************************/ +/* Alternate Pin Functions. All members of the LM4F family share the same pin + * multiplexing (although they may differ in the pins physically available). + * + * Alternative pin selections are provided with a numeric suffix like _1, _2, etc. + * Drivers, however, will use the pin selection without the numeric suffix. + * Additional definitions are required in the board.h file. For example, if + * CAN1_RX connects vis PA11 on some board, then the following definitions should + * appear inthe board.h header file for that board: + * + * #define GPIO_CAN1_RX GPIO_CAN1_RX_1 + * + * The driver will then automatically configre PA11 as the CAN1 RX pin. + */ + +/* WARNING!!! WARNING!!! WARNING!!! WARNING!!! WARNING!!! WARNING!!! WARNING!!! + * Additional effort is required to select specific GPIO options such as frequency, + * open-drain/push-pull, and pull-up/down! Just the basics are defined for most + * pins in this file. + */ + +#if defined(CONFIG_ARCH_CHIP_LM4F120) + +# define GPIO_ADC_IN0 (GPIO_FUNC_ANINPUT | GPIO_PORTE | GPIO_PIN_3) +# define GPIO_ADC_IN1 (GPIO_FUNC_ANINPUT | GPIO_PORTE | GPIO_PIN_2) +# define GPIO_ADC_IN2 (GPIO_FUNC_ANINPUT | GPIO_PORTE | GPIO_PIN_1) +# define GPIO_ADC_IN3 (GPIO_FUNC_ANINPUT | GPIO_PORTE | GPIO_PIN_0) +# define GPIO_ADC_IN4 (GPIO_FUNC_ANINPUT | GPIO_PORTD | GPIO_PIN_3) +# define GPIO_ADC_IN5 (GPIO_FUNC_ANINPUT | GPIO_PORTD | GPIO_PIN_2) +# define GPIO_ADC_IN6 (GPIO_FUNC_ANINPUT | GPIO_PORTD | GPIO_PIN_1) +# define GPIO_ADC_IN7 (GPIO_FUNC_ANINPUT | GPIO_PORTD | GPIO_PIN_0) +# define GPIO_ADC_IN8 (GPIO_FUNC_ANINPUT | GPIO_PORTE | GPIO_PIN_5) +# define GPIO_ADC_IN9 (GPIO_FUNC_ANINPUT | GPIO_PORTE | GPIO_PIN_4) +# define GPIO_ADC_IN10 (GPIO_FUNC_ANINPUT | GPIO_PORTB | GPIO_PIN_4) +# define GPIO_ADC_IN11 (GPIO_FUNC_ANINPUT | GPIO_PORTB | GPIO_PIN_5) + +# define GPIO_CAN0_RX_1 (GPIO_FUNC_PFINPUT | GPIO_ALT_3 | GPIO_PORTF | GPIO_PIN_0) +# define GPIO_CAN0_RX_2 (GPIO_FUNC_PFINPUT | GPIO_ALT_8 | GPIO_PORTB | GPIO_PIN_4) +# define GPIO_CAN0_RX_3 (GPIO_FUNC_PFINPUT | GPIO_ALT_8 | GPIO_PORTE | GPIO_PIN_4) +# define GPIO_CAN0_TX_1 (GPIO_FUNC_PFOUTPUT | GPIO_ALT_3 | GPIO_PORTF | GPIO_PIN_3) +# define GPIO_CAN0_TX_2 (GPIO_FUNC_PFOUTPUT | GPIO_ALT_8 | GPIO_PORTB | GPIO_PIN_5) +# define GPIO_CAN0_TX_3 (GPIO_FUNC_PFOUTPUT | GPIO_ALT_8 | GPIO_PORTE | GPIO_PIN_5) + +# define GPIO_CMP0_NIN (GPIO_FUNC_ANINPUT | GPIO_PORTC | GPIO_PIN_7) +# define GPIO_CMP0_OUT (GPIO_FUNC_PFOUTPUT | GPIO_ALT_9 | GPIO_PORTF | GPIO_PIN_0) +# define GPIO_CMP0_PIN (GPIO_FUNC_ANINPUT | GPIO_PORTC | GPIO_PIN_6) +# define GPIO_CMP1_NIN (GPIO_FUNC_ANINPUT | GPIO_PORTC | GPIO_PIN_4) +# define GPIO_CMP1_OUT (GPIO_FUNC_PFOUTPUT | GPIO_ALT_9 | GPIO_PORTF | GPIO_PIN_1) +# define GPIO_CMP1_PIN (GPIO_FUNC_ANINPUT | GPIO_PORTC | GPIO_PIN_5) + +# define GPIO_CORE_TRCLK (GPIO_FUNC_PFOUTPUT | GPIO_ALT_14 | GPIO_PORTF | GPIO_PIN_3) +# define GPIO_CORE_TRD0 (GPIO_FUNC_PFOUTPUT | GPIO_ALT_14 | GPIO_PORTF | GPIO_PIN_2) +# define GPIO_CORE_TRD1 (GPIO_FUNC_PFOUTPUT | GPIO_ALT_14 | GPIO_PORTF | GPIO_PIN_1) + +# define GPIO_I2C0_SCL (GPIO_FUNC_PFODIO | GPIO_ALT_3 | GPIO_PORTB | GPIO_PIN_2) +# define GPIO_I2C0_SDA (GPIO_FUNC_PFODIO | GPIO_ALT_3 | GPIO_PORTB | GPIO_PIN_3) +# define GPIO_I2C1_SCL (GPIO_FUNC_PFODIO | GPIO_ALT_3 | GPIO_PORTA | GPIO_PIN_6) +# define GPIO_I2C1_SDA (GPIO_FUNC_PFODIO | GPIO_ALT_3 | GPIO_PORTA | GPIO_PIN_7) +# define GPIO_I2C2_SCL (GPIO_FUNC_PFODIO | GPIO_ALT_3 | GPIO_PORTE | GPIO_PIN_4) +# define GPIO_I2C2_SDA (GPIO_FUNC_PFODIO | GPIO_ALT_3 | GPIO_PORTE | GPIO_PIN_5) +# define GPIO_I2C3_SCL (GPIO_FUNC_PFODIO | GPIO_ALT_3 | GPIO_PORTD | GPIO_PIN_0) +# define GPIO_I2C3_SDA (GPIO_FUNC_PFODIO | GPIO_ALT_3 | GPIO_PORTD | GPIO_PIN_1) + +# define GPIO_JTAG_SWCLK (GPIO_FUNC_PFINPUT | GPIO_ALT_1 | GPIO_PORTC | GPIO_PIN_0) +# define GPIO_JTAG_SWDIO (GPIO_FUNC_PFIO | GPIO_ALT_1 | GPIO_PORTC | GPIO_PIN_1) +# define GPIO_JTAG_SWO (GPIO_FUNC_PFOUTPUT | GPIO_ALT_1 | GPIO_PORTC | GPIO_PIN_3) +# define GPIO_JTAG_TCK (GPIO_FUNC_PFINPUT | GPIO_ALT_1 | GPIO_PORTC | GPIO_PIN_0) +# define GPIO_JTAG_TDI (GPIO_FUNC_PFINPUT | GPIO_ALT_1 | GPIO_PORTC | GPIO_PIN_2) +# define GPIO_JTAG_TDO (GPIO_FUNC_PFOUTPUT | GPIO_ALT_1 | GPIO_PORTC | GPIO_PIN_3) +# define GPIO_JTAG_TMS (GPIO_FUNC_PFINPUT | GPIO_ALT_1 | GPIO_PORTC | GPIO_PIN_1) + +# define GPIO_SSI0_CLK (GPIO_FUNC_PFIO | GPIO_ALT_2 | GPIO_PORTA | GPIO_PIN_2) +# define GPIO_SSI0_FSS (GPIO_FUNC_PFIO | GPIO_ALT_2 | GPIO_PORTA | GPIO_PIN_3) +# define GPIO_SSI0_RX (GPIO_FUNC_PFINPUT | GPIO_ALT_2 | GPIO_PORTA | GPIO_PIN_4) +# define GPIO_SSI0_TX (GPIO_FUNC_PFOUTPUT | GPIO_ALT_2 | GPIO_PORTA | GPIO_PIN_5) +# define GPIO_SSI1_CLK_1 (GPIO_FUNC_PFIO | GPIO_ALT_2 | GPIO_PORTD | GPIO_PIN_0) +# define GPIO_SSI1_CLK_2 (GPIO_FUNC_PFIO | GPIO_ALT_2 | GPIO_PORTF | GPIO_PIN_2) +# define GPIO_SSI1_FSS_1 (GPIO_FUNC_PFIO | GPIO_ALT_2 | GPIO_PORTD | GPIO_PIN_1) +# define GPIO_SSI1_FSS_2 (GPIO_FUNC_PFIO | GPIO_ALT_2 | GPIO_PORTF | GPIO_PIN_3) +# define GPIO_SSI1_RX_1 (GPIO_FUNC_PFINPUT | GPIO_ALT_2 | GPIO_PORTD | GPIO_PIN_2) +# define GPIO_SSI1_RX_2 (GPIO_FUNC_PFINPUT | GPIO_ALT_2 | GPIO_PORTF | GPIO_PIN_0) +# define GPIO_SSI1_TX_1 (GPIO_FUNC_PFOUTPUT | GPIO_ALT_2 | GPIO_PORTD | GPIO_PIN_3) +# define GPIO_SSI1_TX_2 (GPIO_FUNC_PFOUTPUT | GPIO_ALT_2 | GPIO_PORTF | GPIO_PIN_1) +# define GPIO_SSI2_CLK (GPIO_FUNC_PFIO | GPIO_ALT_2 | GPIO_PORTB | GPIO_PIN_4) +# define GPIO_SSI2_FSS (GPIO_FUNC_PFIO | GPIO_ALT_2 | GPIO_PORTB | GPIO_PIN_5) +# define GPIO_SSI2_RX (GPIO_FUNC_PFINPUT | GPIO_ALT_2 | GPIO_PORTB | GPIO_PIN_6) +# define GPIO_SSI2_TX (GPIO_FUNC_PFOUTPUT | GPIO_ALT_2 | GPIO_PORTB | GPIO_PIN_7) +# define GPIO_SSI3_CLK (GPIO_FUNC_PFIO | GPIO_ALT_1 | GPIO_PORTD | GPIO_PIN_0) +# define GPIO_SSI3_FSS (GPIO_FUNC_PFIO | GPIO_ALT_1 | GPIO_PORTD | GPIO_PIN_1) +# define GPIO_SSI3_RX (GPIO_FUNC_PFINPUT | GPIO_ALT_1 | GPIO_PORTD | GPIO_PIN_2) +# define GPIO_SSI3_TX (GPIO_FUNC_PFOUTPUT | GPIO_ALT_1 | GPIO_PORTD | GPIO_PIN_3) + +# define GPIO_SYSCON_NMI_1 (GPIO_FUNC_PFINPUT | GPIO_ALT_8 | GPIO_PORTD | GPIO_PIN_7) +# define GPIO_SYSCON_NMI_2 (GPIO_FUNC_PFINPUT | GPIO_ALT_8 | GPIO_PORTF | GPIO_PIN_0) + +# define GPIO_TIM0_CCP0_1 (GPIO_FUNC_PFIO | GPIO_ALT_7 | GPIO_PORTB | GPIO_PIN_6) +# define GPIO_TIM0_CCP0_2 (GPIO_FUNC_PFIO | GPIO_ALT_7 | GPIO_PORTF | GPIO_PIN_0) +# define GPIO_TIM0_CCP1_1 (GPIO_FUNC_PFIO | GPIO_ALT_7 | GPIO_PORTB | GPIO_PIN_7) +# define GPIO_TIM0_CCP1_2 (GPIO_FUNC_PFIO | GPIO_ALT_7 | GPIO_PORTF | GPIO_PIN_1) +# define GPIO_TIM1_CCP0_1 (GPIO_FUNC_PFIO | GPIO_ALT_7 | GPIO_PORTB | GPIO_PIN_4) +# define GPIO_TIM1_CCP0_2 (GPIO_FUNC_PFIO | GPIO_ALT_7 | GPIO_PORTF | GPIO_PIN_2) +# define GPIO_TIM1_CCP1_1 (GPIO_FUNC_PFIO | GPIO_ALT_7 | GPIO_PORTB | GPIO_PIN_5) +# define GPIO_TIM1_CCP1_2 (GPIO_FUNC_PFIO | GPIO_ALT_7 | GPIO_PORTF | GPIO_PIN_3) +# define GPIO_TIM2_CCP0_1 (GPIO_FUNC_PFIO | GPIO_ALT_7 | GPIO_PORTB | GPIO_PIN_0) +# define GPIO_TIM2_CCP0_2 (GPIO_FUNC_PFIO | GPIO_ALT_7 | GPIO_PORTF | GPIO_PIN_4) +# define GPIO_TIM2_CCP1 (GPIO_FUNC_PFIO | GPIO_ALT_7 | GPIO_PORTB | GPIO_PIN_1) +# define GPIO_TIM3_CCP0 (GPIO_FUNC_PFIO | GPIO_ALT_7 | GPIO_PORTB | GPIO_PIN_2) +# define GPIO_TIM3_CCP1 (GPIO_FUNC_PFIO | GPIO_ALT_7 | GPIO_PORTB | GPIO_PIN_3) +# define GPIO_TIM4_CCP0 (GPIO_FUNC_PFIO | GPIO_ALT_7 | GPIO_PORTC | GPIO_PIN_0) +# define GPIO_TIM4_CCP1 (GPIO_FUNC_PFIO | GPIO_ALT_7 | GPIO_PORTC | GPIO_PIN_1) +# define GPIO_TIM5_CCP0 (GPIO_FUNC_PFIO | GPIO_ALT_7 | GPIO_PORTC | GPIO_PIN_2) +# define GPIO_TIM5_CCP1 (GPIO_FUNC_PFIO | GPIO_ALT_7 | GPIO_PORTC | GPIO_PIN_3) + +# define GPIO_UART0_RX (GPIO_FUNC_PFINPUT | GPIO_ALT_1 | GPIO_PORTA | GPIO_PIN_0) +# define GPIO_UART0_TX (GPIO_FUNC_PFOUTPUT | GPIO_ALT_1 | GPIO_PORTA | GPIO_PIN_1) +# define GPIO_UART1_CTS_1 (GPIO_FUNC_PFINPUT | GPIO_ALT_1 | GPIO_PORTF | GPIO_PIN_1) +# define GPIO_UART1_CTS_2 (GPIO_FUNC_PFINPUT | GPIO_ALT_8 | GPIO_PORTC | GPIO_PIN_5) +# define GPIO_UART1_RTS_1 (GPIO_FUNC_PFOUTPUT | GPIO_ALT_1 | GPIO_PORTF | GPIO_PIN_0) +# define GPIO_UART1_RTS_1 (GPIO_FUNC_PFOUTPUT | GPIO_ALT_8 | GPIO_PORTC | GPIO_PIN_4) +# define GPIO_UART1_RX_1 (GPIO_FUNC_PFINPUT | GPIO_ALT_1 | GPIO_PORTB | GPIO_PIN_0) +# define GPIO_UART1_RX_2 (GPIO_FUNC_PFINPUT | GPIO_ALT_2 | GPIO_PORTC | GPIO_PIN_4) +# define GPIO_UART1_TX_1 (GPIO_FUNC_PFOUTPUT | GPIO_ALT_1 | GPIO_PORTB | GPIO_PIN_1) +# define GPIO_UART1_TX_2 (GPIO_FUNC_PFOUTPUT | GPIO_ALT_2 | GPIO_PORTC | GPIO_PIN_5) +# define GPIO_UART2_RX_1 (GPIO_FUNC_PFINPUT | GPIO_ALT_1 | GPIO_PORTD | GPIO_PIN_6) +# define GPIO_UART2_TX_2 (GPIO_FUNC_PFOUTPUT | GPIO_ALT_1 | GPIO_PORTD | GPIO_PIN_7) +# define GPIO_UART3_RX (GPIO_FUNC_PFINPUT | GPIO_ALT_1 | GPIO_PORTC | GPIO_PIN_6) +# define GPIO_UART3_TX (GPIO_FUNC_PFOUTPUT | GPIO_ALT_1 | GPIO_PORTC | GPIO_PIN_7) +# define GPIO_UART4_RX (GPIO_FUNC_PFINPUT | GPIO_ALT_1 | GPIO_PORTC | GPIO_PIN_4) +# define GPIO_UART4_TX (GPIO_FUNC_PFOUTPUT | GPIO_ALT_1 | GPIO_PORTC | GPIO_PIN_5) +# define GPIO_UART5_RX (GPIO_FUNC_PFINPUT | GPIO_ALT_1 | GPIO_PORTE | GPIO_PIN_4) +# define GPIO_UART5_TX (GPIO_FUNC_PFOUTPUT | GPIO_ALT_1 | GPIO_PORTE | GPIO_PIN_5) +# define GPIO_UART6_RX (GPIO_FUNC_PFINPUT | GPIO_ALT_1 | GPIO_PORTD | GPIO_PIN_4) +# define GPIO_UART6_TX (GPIO_FUNC_PFOUTPUT | GPIO_ALT_1 | GPIO_PORTD | GPIO_PIN_5) +# define GPIO_UART7_RX (GPIO_FUNC_PFINPUT | GPIO_ALT_1 | GPIO_PORTE | GPIO_PIN_0) +# define GPIO_UART7_TX (GPIO_FUNC_PFOUTPUT | GPIO_ALT_1 | GPIO_PORTE | GPIO_PIN_1) + +# define GPIO_USB0_DM (GPIO_FUNC_ANIO | GPIO_PORTD | GPIO_PIN_4) +# define GPIO_USB0_DP (GPIO_FUNC_ANIO | GPIO_PORTD | GPIO_PIN_5) + +# define GPIO_WTIM0_CCP0 (GPIO_FUNC_PFIO | GPIO_ALT_7 | GPIO_PORTC | GPIO_PIN_4) +# define GPIO_WTIM0_CCP1 (GPIO_FUNC_PFIO | GPIO_ALT_7 | GPIO_PORTC | GPIO_PIN_5) +# define GPIO_WTIM1_CCP0 (GPIO_FUNC_PFIO | GPIO_ALT_7 | GPIO_PORTC | GPIO_PIN_6) +# define GPIO_WTIM1_CCP1 (GPIO_FUNC_PFIO | GPIO_ALT_7 | GPIO_PORTC | GPIO_PIN_7) +# define GPIO_WTIM2_CCP0 (GPIO_FUNC_PFIO | GPIO_ALT_7 | GPIO_PORTD | GPIO_PIN_0) +# define GPIO_WTIM2_CCP1 (GPIO_FUNC_PFIO | GPIO_ALT_7 | GPIO_PORTD | GPIO_PIN_1) +# define GPIO_WTIM3_CCP0 (GPIO_FUNC_PFIO | GPIO_ALT_7 | GPIO_PORTD | GPIO_PIN_2) +# define GPIO_WTIM3_CCP1 (GPIO_FUNC_PFIO | GPIO_ALT_7 | GPIO_PORTD | GPIO_PIN_3) +# define GPIO_WTIM4_CCP0 (GPIO_FUNC_PFIO | GPIO_ALT_7 | GPIO_PORTD | GPIO_PIN_4) +# define GPIO_WTIM4_CCP1 (GPIO_FUNC_PFIO | GPIO_ALT_7 | GPIO_PORTD | GPIO_PIN_5) +# define GPIO_WTIM5_CCP0 (GPIO_FUNC_PFIO | GPIO_ALT_7 | GPIO_PORTD | GPIO_PIN_6) +# define GPIO_WTIM5_CCP1 (GPIO_FUNC_PFIO | GPIO_ALT_7 | GPIO_PORTD | GPIO_PIN_7) + +#else +# error "Unknown Stellaris chip" +#endif + +/************************************************************************************ + * Public Types + ************************************************************************************/ + +/************************************************************************************ + * Public Data + ************************************************************************************/ + +/**************************************************************************** + * Public Function Prototypes + ****************************************************************************/ + +#endif /* __ARCH_ARM_SRC_LM_CHIP_LM4F_PINMAP_H */ diff --git a/nuttx/arch/arm/src/lm/chip/lm_gpio.h b/nuttx/arch/arm/src/lm/chip/lm_gpio.h index ebb5aa94f..3fdf5086f 100644 --- a/nuttx/arch/arm/src/lm/chip/lm_gpio.h +++ b/nuttx/arch/arm/src/lm/chip/lm_gpio.h @@ -481,6 +481,30 @@ #endif /* LM_NPORTS */ +/* GPIO Register Bitfield Definitions ***********************************************/ + +#ifdef LM4F +# define GPIO_PCTL_PMC_SHIFT(n) ((n) << 2) +# define GPIO_PCTL_PMC_MASK(n) (15 << GPIO_PCTL_PMC_SHIFT(n)) + +# define GPIO_PCTL_PMC0_SHIFT (0) /* Bits 0-3: Port Mux Control 0 */ +# define GPIO_PCTL_PMC0_MASK (15 << GPIO_PCTL_PMC0_SHIFT) +# define GPIO_PCTL_PMC1_SHIFT (4) /* Bits 4-7: Port Mux Control 0 */ +# define GPIO_PCTL_PMC1_MASK (15 << GPIO_PCTL_PMC1_SHIFT) +# define GPIO_PCTL_PMC2_SHIFT (8) /* Bits 8-11: Port Mux Control 0 */ +# define GPIO_PCTL_PMC2_MASK (15 << GPIO_PCTL_PMC2_SHIFT) +# define GPIO_PCTL_PMC3_SHIFT (12) /* Bits 12-15: Port Mux Control 0 */ +# define GPIO_PCTL_PMC3_MASK (15 << GPIO_PCTL_PMC3_SHIFT) +# define GPIO_PCTL_PMC4_SHIFT (16) /* Bits 16-19: Port Mux Control 0 */ +# define GPIO_PCTL_PMC4_MASK (15 << GPIO_PCTL_PMC4_SHIFT) +# define GPIO_PCTL_PMC5_SHIFT (20) /* Bits 20-23: Port Mux Control 0 */ +# define GPIO_PCTL_PMC5_MASK (15 << GPIO_PCTL_PMC5_SHIFT) +# define GPIO_PCTL_PMC6_SHIFT (24) /* Bits 24-27: Port Mux Control 0 */ +# define GPIO_PCTL_PMC6_MASK (15 << GPIO_PCTL_PMC6_SHIFT) +# define GPIO_PCTL_PMC7_SHIFT (28) /* Bits 28-31: Port Mux Control 0 */ +# define GPIO_PCTL_PMC7_MASK (15 << GPIO_PCTL_PMC7_SHIFT) +#endif + /************************************************************************************ * Public Types ************************************************************************************/ diff --git a/nuttx/arch/arm/src/lm/lm_gpio.c b/nuttx/arch/arm/src/lm/lm_gpio.c index 43dc42cb4..a33d229c9 100644 --- a/nuttx/arch/arm/src/lm/lm_gpio.c +++ b/nuttx/arch/arm/src/lm/lm_gpio.c @@ -60,6 +60,11 @@ * configuration of Table 9-1 in the LM3S6918 data sheet. */ +#define AMSEL_SHIFT 6 +#define AMSEL_1 (1 << AMSEL_SHIFT) /* Set/clear bit in GPIO AMSEL register */ +#define AMSEL_0 0 +#define AMSEL_X 0 + #define AFSEL_SHIFT 5 #define AFSEL_1 (1 << AFSEL_SHIFT) /* Set/clear bit in GPIO AFSEL register */ #define AFSEL_0 0 @@ -90,29 +95,29 @@ #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_INPUT_SETBITS (AMSEL_0 | AFSEL_0 | DIR_0 | ODR_0 | DEN_1 | PUR_X | PDR_X) +#define GPIO_INPUT_CLRBITS (AMSEL_1 | 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_OUTPUT_SETBITS (AMSEL_0 | AFSEL_0 | DIR_1 | ODR_0 | DEN_1 | PUR_X | PDR_X) +#define GPIO_OUTPUT_CLRBITS (AMSEL_1 | 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_ODINPUT_SETBITS (AMSEL_0 | AFSEL_0 | DIR_0 | ODR_1 | DEN_1 | PUR_X | PDR_X) +#define GPIO_ODINPUT_CLRBITS (AMSEL_1 | 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_ODOUTPUT_SETBITS (AMSEL_0 | AFSEL_0 | DIR_1 | ODR_1 | DEN_1 | PUR_X | PDR_X) +#define GPIO_ODOUTPUT_CLRBITS (AMSEL_1 | 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_PFODIO_SETBITS (AMSEL_0 | AFSEL_1 | DIR_X | ODR_1 | DEN_1 | PUR_X | PDR_X) +#define GPIO_PFODIO_CLRBITS (AMSEL_1 | 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_PFIO_SETBITS (AMSEL_0 | AFSEL_1 | DIR_X | ODR_0 | DEN_1 | PUR_X | PDR_X) +#define GPIO_PFIO_CLRBITS (AMSEL_1 | 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_ANINPUT_SETBITS (AMSEL_1 | AFSEL_0 | DIR_0 | ODR_0 | DEN_0 | PUR_0 | PDR_0) +#define GPIO_ANINPUT_CLRBITS (AMSEL_0 | 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) +#define GPIO_INTERRUPT_SETBITS (AMSEL_0 | AFSEL_0 | DIR_0 | ODR_0 | DEN_1 | PUR_X | PDR_X) +#define GPIO_INTERRUPT_CLRBITS (AMSEL_1 | AFSEL_1 | DIR_1 | ODR_1 | DEN_0 | PUR_X | PDR_X) /**************************************************************************** * Private Types @@ -209,7 +214,8 @@ static uintptr_t lm_gpiobaseaddress(unsigned int port) * ****************************************************************************/ -static void lm_gpiofunc(uint32_t base, uint32_t pinno, const struct gpio_func_s *func) +static void lm_gpiofunc(uint32_t base, uint32_t pinno, + const struct gpio_func_s *func) { uint32_t setbit; uint32_t clrbit; @@ -316,6 +322,24 @@ static void lm_gpiofunc(uint32_t base, uint32_t pinno, const struct gpio_func_s regval &= ~clrbit; regval |= setbit; putreg32(regval, base + LM_GPIO_AFSEL_OFFSET); + + /* Set/clear/ignore the GPIO AMSEL bit. "The GPIOAMSEL register controls + * isolation circuits to the analog side of a unified I/O pad. Because + * the GPIOs may be driven by a 5-V source and affect analog operation, + * analog circuitry requires isolation from the pins when they are not + * used in their analog function. Each bit of this register controls the + * isolation circuitry for the corresponding GPIO signal. + */ + +#ifdef LM4F + setbit = (((uint32_t)func->setbits >> AMSEL_SHIFT) & 1) << pinno; + clrbit = (((uint32_t)func->clrbits >> AMSEL_SHIFT) & 1) << pinno; + + regval = getreg32(base + LM_GPIO_AMSEL_OFFSET); + regval &= ~clrbit; + regval |= setbit; + putreg32(regval, base + LM_GPIO_AMSEL_OFFSET); +#endif } /**************************************************************************** @@ -703,6 +727,46 @@ static inline void lm_interrupt(uint32_t base, uint32_t pin, uint32_t cfgset) putreg32(regval, base + LM_GPIO_IEV_OFFSET); } +/**************************************************************************** + * Name: lm_portcontrol + * + * Description: + * Set the pin alternate function in the port control register. + * + ****************************************************************************/ + +#ifdef LM4F +static inline void lm_portcontrol(uint32_t base, uint32_t pinno, + uint32_t cfgset, + const struct gpio_func_s *func) +{ + uint32_t alt = 0; + uint32_t mask; + uint32_t regval; + + /* Is this pin an alternate function pin? */ + + if ((func->setbits & AFSEL_1) != 0) + { + /* Yes, extract the alternate function number from the pin + * configuration. + */ + + alt = (cfgset & GPIO_ALT_MASK) >> GPIO_ALT_SHIFT; + } + + /* Set the alternate function in the port control register */ + + regval = getreg32(base + LM_GPIO_PCTL_OFFSET); + mask = GPIO_PCTL_PMC_MASK(pinno); + regval &= ~mask; + regval |= (alt << GPIO_PCTL_PMC_SHIFT(pinno)) & mask; + putreg32(regval, base + LM_GPIO_PCTL_OFFSET); +} +#else +# define lm_portcontrol(b,p,f) +#endif + /**************************************************************************** * Public Functions ****************************************************************************/ @@ -730,7 +794,7 @@ int lm_configgpio(uint32_t cfgset) func = (cfgset & GPIO_FUNC_MASK) >> GPIO_FUNC_SHIFT; port = (cfgset & GPIO_PORT_MASK) >> GPIO_PORT_SHIFT; pinno = (cfgset & GPIO_PIN_MASK); - pin = (1 <