Add userleds
This commit is contained in:
Philippe Leduc 2023-08-31 17:17:01 +02:00 committed by Xiang Xiao
parent 7ec3cad5af
commit 5b7c948aef
13 changed files with 861 additions and 28 deletions

View file

@ -24,7 +24,7 @@ include armv7-m/Make.defs
CHIP_CSRCS = mx8mp_start.c mx8mp_allocateheap.c mx8mp_iomuxc.c mx8mp_lowputc.c
CHIP_CSRCS += mx8mp_clrpend.c mx8mp_irq.c mx8mp_mpuinit.c mx8mp_ccm.c
CHIP_CSRCS += mx8mp_serial.c mx8mp_clockconfig.c
CHIP_CSRCS += mx8mp_serial.c mx8mp_clockconfig.c mx8mp_gpio.c
# Configuration-dependent files

View file

@ -0,0 +1,91 @@
/****************************************************************************
* arch/arm/src/mx8mp/hardware/mx8mp_gpio.h
*
* Licensed to the Apache Software Foundation (ASF) under one or more
* contributor license agreements. See the NOTICE file distributed with
* this work for additional information regarding copyright ownership. The
* ASF licenses this file to you under the Apache License, Version 2.0 (the
* "License"); you may not use this file except in compliance with the
* License. You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
* WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
* License for the specific language governing permissions and limitations
* under the License.
*
****************************************************************************/
/* Reference:
* "i.MX 8M Plus Applications Processor Reference Manual",
* Document Number: IMX8MPRM Rev. 1, 06/2021. NXP
*/
#ifndef __ARCH_ARM_SRC_MX8MP_HARDWARE_MX8MP_GPIO_H
#define __ARCH_ARM_SRC_MX8MP_HARDWARE_MX8MP_GPIO_H
/****************************************************************************
* Included Files
****************************************************************************/
#include <nuttx/config.h>
#include "hardware/mx8mp_memorymap.h"
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/
#define GPIO1 0 /* Port 1 index */
#define GPIO2 1 /* Port 2 index */
#define GPIO3 2 /* Port 3 index */
#define GPIO4 3 /* Port 4 index */
#define GPIO5 4 /* Port 5 index */
#define GPIO_NPORTS 5 /* Seven total ports */
#define GPIO_NPINS 32 /* Up to 32 pins per port */
/* GPIO Register Offsets ****************************************************/
#define DR_OFFSET 0x0000 /* Data Register */
#define GDIR_OFFSET 0x0004 /* Data Direction Register */
#define PSR_OFFSET 0x0008 /* Pad Status Register */
#define ICR1_OFFSET 0x000c /* Interrupt Configuration Register 1 */
#define ICR2_OFFSET 0x0010 /* Interrupt Configuration Register 2 */
#define IMR_OFFSET 0x0014 /* Interrupt Mask Register */
#define ISR_OFFSET 0x0018 /* Interrupt Status Register */
#define EDGE_OFFSET 0x001c /* Interrupt Status Register */
/* GPIO Register Addresses **************************************************/
#define GPIO_DR(n) (((n - 1) * 0x10000 + MX8M_GPIO) + DR_OFFSET)
#define GPIO_GDIR(n) (((n - 1) * 0x10000 + MX8M_GPIO) + GDIR_OFFSET)
#define GPIO_PSR(n) (((n - 1) * 0x10000 + MX8M_GPIO) + PSR_OFFSET)
#define GPIO_ICR1(n) (((n - 1) * 0x10000 + MX8M_GPIO) + ICR1_OFFSET)
#define GPIO_ICR2(n) (((n - 1) * 0x10000 + MX8M_GPIO) + ICR2_OFFSET)
#define GPIO_IMR(n) (((n - 1) * 0x10000 + MX8M_GPIO) + IMR_OFFSET)
#define GPIO_ISR(n) (((n - 1) * 0x10000 + MX8M_GPIO) + ISR_OFFSET)
#define GPIO_EDGE(n) (((n - 1) * 0x10000 + MX8M_GPIO) + EDGE_OFFSET)
/* GPIO Register Bit Definitions ********************************************/
/* Most registers are laid out simply with one bit per pin */
#define GPIO_PIN(n) (1 << (n)) /* Bit n: Pin n, n=0-31 */
/* GPIO interrupt configuration register 1/2 */
#define ICR_INDEX(n) (((n) >> 4) & 1)
#define ICR_OFFSET(n) (ICR1_OFFSET + (ICR_INDEX(n) << 2))
#define ICR_LOW_LEVEL 0 /* Interrupt is low-level sensitive */
#define ICR_HIGH_LEVEL 1 /* Interrupt is high-level sensitive */
#define ICR_RISING_EDGE 2 /* Interrupt is rising-edge sensitive */
#define ICR_FALLING_EDGE 3 /* Interrupt is falling-edge sensitive */
#define ICR_SHIFT(n) (((n) & 15) << 1)
#define ICR_MASK(n) (3 << ICR_SHIFT(n))
#define ICR(i,n) ((uint32_t)(i) << ICR_SHIFT(n))
#endif /* __ARCH_ARM_SRC_MX8MP_HARDWARE_MX8MP_GPIO_H */

View file

@ -105,11 +105,12 @@
#define MX8M_ECSPI2 0x30830000u
#define MX8M_ECSPI3 0x30840000u
#define MX8M_GPIO1 0x30200000u
#define MX8M_GPIO2 0x30210000u
#define MX8M_GPIO3 0x30220000u
#define MX8M_GPIO4 0x30230000u
#define MX8M_GPIO5 0x30240000u
#define MX8M_GPIO 0x30200000u
#define MX8M_GPIO1 (MX8M_GPIO + 0x10000 * 0)
#define MX8M_GPIO2 (MX8M_GPIO + 0x10000 * 1)
#define MX8M_GPIO3 (MX8M_GPIO + 0x10000 * 2)
#define MX8M_GPIO4 (MX8M_GPIO + 0x10000 * 3)
#define MX8M_GPIO5 (MX8M_GPIO + 0x10000 * 4)
#define MX8M_DDR 0x40000000u
#define MX8M_OCRAM 0x00900000u

View file

@ -879,28 +879,51 @@
#define IOMUXC_HDMI_HPD_CAN2_RX 0x3033024C, 0x4, 0x30330550, 0x3, 0x303304AC
#define IOMUXC_HDMI_HPD_GPIO3_IO29 0x3033024C, 0x5, 0x00000000, 0x0, 0x303304AC
/* FSEL - Slew Rate Field
* 0b0..Slow Slew Rate (SR=1)
* 0b1..Fast Slew Rate (SR=0)
/* DSE - Drive Strength Field
* 00 x1
* 10 x2
* 01 x4
* 11 x6
*/
#define IOMUXC_SW_PAD_CTL_PAD_FSEL_MASK (0x10U)
#define IOMUXC_SW_PAD_CTL_PAD_FSEL_SHIFT (4U)
#define IOMUXC_SW_PAD_CTL_PAD_FSEL(x) (((uint32_t)(((uint32_t)(x)) << IOMUXC_SW_PAD_CTL_PAD_FSEL_SHIFT)) & IOMUXC_SW_PAD_CTL_PAD_FSEL_MASK)
#define PAD_CTL_DSE1 (0 << 1)
#define PAD_CTL_DSE2 (2 << 1)
#define PAD_CTL_DSE4 (1 << 1)
#define PAD_CTL_DSE6 (3 << 1)
/* FSEL - Slew Rate Field
* 0 Slow Slew Rate (SR=1)
* 1 Fast Slew Rate (SR=0)
*/
#define PAD_CTL_FSEL (1 << 4)
/* ODE - Open drain field
* 0 Disable
* 1 Enable
*/
#define PAD_CTL_ODE (1 << 5)
/* PUE - Pull Up / Down Config. Field
* 0b0..Weak pull down
* 0b1..Weak pull up
* 0 Weak pull down
* 1 Weak pull up
*/
#define IOMUXC_SW_PAD_CTL_PAD_PUE_MASK (0x40U)
#define IOMUXC_SW_PAD_CTL_PAD_PUE_SHIFT (6U)
#define IOMUXC_SW_PAD_CTL_PAD_PUE(x) (((uint32_t)(((uint32_t)(x)) << IOMUXC_SW_PAD_CTL_PAD_PUE_SHIFT)) & IOMUXC_SW_PAD_CTL_PAD_PUE_MASK)
#define PAD_CTL_PUE (1 << 6)
/* HYS - Input Select Field
* 0 CMOS
* 1 Schmitt
*/
#define PAD_CTL_HYS (1 << 7)
/* PE - Pull Select Field
* 0b0..Pull Disable
* 0b1..Pull Enable
* 0 Pull Disable
* 1 Pull Enable
*/
#define IOMUXC_SW_PAD_CTL_PAD_PE_MASK (0x100U)
#define IOMUXC_SW_PAD_CTL_PAD_PE_SHIFT (8U)
#define IOMUXC_SW_PAD_CTL_PAD_PE(x) (((uint32_t)(((uint32_t)(x)) << IOMUXC_SW_PAD_CTL_PAD_PE_SHIFT)) & IOMUXC_SW_PAD_CTL_PAD_PE_MASK)
#define PAD_CTL_PE (1 << 8)
/* Helpers for common configurations */
#define GPIO_PAD_CTRL (PAD_CTL_HYS | PAD_CTL_PUE | PAD_CTL_PE | PAD_CTL_DSE2)
#define UART_PAD_CTRL (PAD_CTL_PUE | PAD_CTL_PE)
#endif /* __ARCH_ARM_SRC_MX8MP_HARDWARE_MX8MP_PINMUX_H */

View file

@ -0,0 +1,254 @@
/****************************************************************************
* arch/arm/src/mx8mp/mx8mp_gpio.c
*
* Licensed to the Apache Software Foundation (ASF) under one or more
* contributor license agreements. See the NOTICE file distributed with
* this work for additional information regarding copyright ownership. The
* ASF licenses this file to you under the Apache License, Version 2.0 (the
* "License"); you may not use this file except in compliance with the
* License. You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
* WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
* License for the specific language governing permissions and limitations
* under the License.
*
****************************************************************************/
/****************************************************************************
* Included Files
****************************************************************************/
#include <nuttx/config.h>
#include <stdint.h>
#include <stdbool.h>
#include <errno.h>
#include <nuttx/irq.h>
#include "chip.h"
#include "arm_internal.h"
#include "mx8mp_gpio.h"
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/
/****************************************************************************
* Private Data
****************************************************************************/
/****************************************************************************
* Private Functions
****************************************************************************/
/****************************************************************************
* Public Functions
****************************************************************************/
/****************************************************************************
* Name: mx8mp_gpio_config
*
* Description:
* Configure a GPIO pin based on pin-encoded description of the pin.
*
****************************************************************************/
int mx8mp_gpio_config(gpio_pinset_t pinset)
{
uint32_t port = (pinset & GPIO_PORT_MASK) >> GPIO_PORT_SHIFT;
uint32_t pin = (pinset & GPIO_PIN_MASK) >> GPIO_PIN_SHIFT;
bool value = ((pinset & GPIO_OUTPUT_ONE) != 0);
irqstate_t flags;
int ret = OK;
/* Configure the pin as an input initially to avoid any spurious outputs */
flags = enter_critical_section();
/* Configure based upon the pin mode */
switch (pinset & GPIO_MODE_MASK)
{
case GPIO_INPUT:
{
/* Configure the pin as a GPIO input */
modreg32(0, GPIO_PIN(pin), GPIO_GDIR(port));
}
break;
case GPIO_OUTPUT:
{
/* First configure the pin as a GPIO input to avoid output
* glitches.
*/
modreg32(0, GPIO_PIN(pin), GPIO_GDIR(port));
/* Set the output value */
mx8mp_gpio_write(pinset, value);
/* Convert the configured input GPIO to an output */
modreg32(GPIO_PIN(pin), GPIO_PIN(pin), GPIO_GDIR(port));
printf("output %lx -> %lx (%lu) (%lu)\n", GPIO_GDIR(port), getreg32(GPIO_GDIR(port)), port, pin);
}
break;
case GPIO_INTERRUPT:
{
/* Configure the pin as a GPIO input then the IRQ behavior */
modreg32(0, GPIO_PIN(pin), GPIO_GDIR(port));
mx8mp_gpio_configure_irq(pinset);
}
break;
default:
ret = -EINVAL;
break;
}
leave_critical_section(flags);
return ret;
}
/****************************************************************************
* Name: mx8mp_gpio_write
*
* Description:
* Write one or zero to the selected GPIO pin
*
****************************************************************************/
void mx8mp_gpio_write(gpio_pinset_t pinset, bool value)
{
uint32_t port = (pinset & GPIO_PORT_MASK) >> GPIO_PORT_SHIFT;
uint32_t pin = (pinset & GPIO_PIN_MASK) >> GPIO_PIN_SHIFT;
uint32_t regaddr = GPIO_DR(port);
uint32_t regval;
regval = getreg32(regaddr);
if (value)
{
regval |= GPIO_PIN(pin);
}
else
{
regval &= ~GPIO_PIN(pin);
}
putreg32(regval, regaddr);
}
/****************************************************************************
* Name: mx8mp_gpio_read
*
* Description:
* Read one or zero from the selected GPIO pin
*
****************************************************************************/
bool mx8mp_gpio_read(gpio_pinset_t pinset)
{
uint32_t port = (pinset & GPIO_PORT_MASK) >> GPIO_PORT_SHIFT;
uint32_t pin = (pinset & GPIO_PIN_MASK) >> GPIO_PIN_SHIFT;
uint32_t regval = getreg32(GPIO_DR(port));
return ((regval & GPIO_PIN(pin)) != 0);
}
/****************************************************************************
* Name: mx8mp_gpio_configure_irq
*
* Description:
* Configure an interrupt for the specified GPIO pin.
*
****************************************************************************/
void mx8mp_gpio_configure_irq(gpio_pinset_t pinset)
{
/* Decode information in the pin configuration */
uint32_t port = (pinset & GPIO_PORT_MASK) >> GPIO_PORT_SHIFT;
uint32_t pin = (pinset & GPIO_PIN_MASK) >> GPIO_PIN_SHIFT;
uint32_t icr = (pinset & GPIO_INTCFG_MASK) >> GPIO_INTCFG_SHIFT;
uint32_t both = (pinset & GPIO_INTBOTHCFG_MASK) >> GPIO_INTBOTHCFG_SHIFT;
uintptr_t regaddr;
uint32_t regval;
/* Set the right field in the right ICR register */
regaddr = pin < 16 ? GPIO_ICR1(port) : GPIO_ICR2(port);
regval = getreg32(regaddr);
regval &= ~ICR_MASK(pin);
regval |= ICR(icr, pin);
putreg32(regval, regaddr);
/* Add any both-edge setup (overrides above see User Manual 8.3.5.1.9) */
regaddr = GPIO_EDGE(port);
regval = getreg32(regaddr);
regval &= ~GPIO_PIN(pin);
regval |= (both << pin);
putreg32(regval, regaddr);
}
/****************************************************************************
* Name: mx8mp_gpio_enable_irq
*
* Description:
* Enable the interrupt for specified GPIO IRQ
*
****************************************************************************/
int mx8mp_gpio_enable_irq(int irq)
{
#if 0
uintptr_t regaddr;
unsigned int pin;
int ret;
ret = imxrt_gpio_info(irq, &regaddr, &pin);
if (ret >= 0)
{
modifyreg32(regaddr, 0, 1 << pin);
}
return ret;
#endif
return OK;
}
/****************************************************************************
* Name: mx8mp_gpio_disable_irq
*
* Description:
* Disable the interrupt for specified GPIO IRQ
*
****************************************************************************/
int mx8mp_gpio_disable_irq(int irq)
{
#if 0
uintptr_t regaddr;
unsigned int pin;
int ret;
ret = imxrt_gpio_info(irq, &regaddr, &pin);
if (ret >= 0)
{
modifyreg32(regaddr, 1 << pin, 0);
}
return ret;
#endif
return OK;
}

View file

@ -0,0 +1,247 @@
/****************************************************************************
* arch/arm/src/mx8mp/mx8mp_gpio.h
*
* Licensed to the Apache Software Foundation (ASF) under one or more
* contributor license agreements. See the NOTICE file distributed with
* this work for additional information regarding copyright ownership. The
* ASF licenses this file to you under the Apache License, Version 2.0 (the
* "License"); you may not use this file except in compliance with the
* License. You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
* WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
* License for the specific language governing permissions and limitations
* under the License.
*
****************************************************************************/
#ifndef __ARCH_ARM_SRC_MX8MP_MX8MP_GPIO_H
#define __ARCH_ARM_SRC_MX8MP_MX8MP_GPIO_H
/****************************************************************************
* Included Files
****************************************************************************/
#include <nuttx/config.h>
#include <nuttx/irq.h>
#include <stdint.h>
#include <stdbool.h>
#include "hardware/mx8mp_gpio.h"
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/
/* 32-bit Encoding:
*
* ENCODING IIXX ERRX XXXX XXXX MMMM MMMM MMMM MMMM
* GPIO INPUT 00.. .... GGGP PPPP MMMM MMMM MMMM MMMM
* GPIO OUTPUT 01V. .... GGGP PPPP MMMM MMMM MMMM MMMM
*/
/* Input/Output Selection:
*
* ENCODING II.. .... .... .... .... .... .... ....
*/
#define GPIO_MODE_SHIFT (30) /* Bits 30-31: Pin mode */
#define GPIO_MODE_MASK (3u << GPIO_MODE_SHIFT)
# define GPIO_INPUT (0u << GPIO_MODE_SHIFT) /* GPIO input */
# define GPIO_OUTPUT (1u << GPIO_MODE_SHIFT) /* GPIO output */
# define GPIO_INTERRUPT (3u << GPIO_MODE_SHIFT) /* Interrupt input */
/* Initial Output Value:
*
* GPIO OUTPUT 01V. .... .... .... .... .... .... ....
*/
#define GPIO_OUTPUT_ZERO (0) /* Bit 29: 0=Initial output is low */
#define GPIO_OUTPUT_ONE (1 << 29) /* Bit 29: 1=Initial output is high */
/* Interrupt edge/level configuration
*
* INT INPUT 11.. .EE. .... .... .... .... .... ....
*/
#define GPIO_INTCFG_SHIFT (25) /* Bits 25-26: Interrupt edge/level configuration */
#define GPIO_INTCFG_MASK (3 << GPIO_INTCFG_SHIFT)
# define GPIO_INT_LOW_LEVEL (ICR_LOW_LEVEL << GPIO_INTCFG_SHIFT)
# define GPIO_INT_HIGH_LEVEL (ICR_HIGH_LEVEL << GPIO_INTCFG_SHIFT)
# define GPIO_INT_RISING_EDGE (ICR_RISING_EDGE << GPIO_INTCFG_SHIFT)
# define GPIO_INT_FALLING_EDGE (ICR_FALLING_EDGE << GPIO_INTCFG_SHIFT)
/* Interrupt on both edges configuration
*
* INT INPUT 11.. B... .... .... .... .... .... ....
*/
#define GPIO_INTBOTHCFG_SHIFT (27) /* Bit 27: Interrupt both edges configuration */
#define GPIO_INTBOTHCFG_MASK (1 << GPIO_INTBOTHCFG_SHIFT)
# define GPIO_INTBOTH_EDGES (1 << GPIO_INTBOTHCFG_SHIFT)
/* GPIO Port Number
*
* GPIO INPUT 00.. .... GGG. .... .... .... .... ....
* GPIO OUTPUT 01.. .... GGG. .... .... .... .... ....
*/
#define GPIO_PORT_SHIFT (21) /* Bits 21-23: GPIO port index */
#define GPIO_PORT_MASK (7 << GPIO_PORT_SHIFT)
# define GPIO_PORT1 (1 << GPIO_PORT_SHIFT) /* GPIO1 */
# define GPIO_PORT2 (2 << GPIO_PORT_SHIFT) /* GPIO2 */
# define GPIO_PORT3 (3 << GPIO_PORT_SHIFT) /* GPIO3 */
# define GPIO_PORT4 (4 << GPIO_PORT_SHIFT) /* GPIO4 */
# define GPIO_PORT5 (5 << GPIO_PORT_SHIFT) /* GPIO5 */
/* GPIO Pin Number:
*
* GPIO INPUT 00.. .... ...P PPPP .... .... .... ....
* GPIO OUTPUT 01.. .... ...P PPPP .... .... .... ....
*/
#define GPIO_PIN_SHIFT (16) /* Bits 16-20: GPIO pin number */
#define GPIO_PIN_MASK (15 << GPIO_PIN_SHIFT)
# define GPIO_PIN0 (0 << GPIO_PIN_SHIFT) /* Pin 0 */
# define GPIO_PIN1 (1 << GPIO_PIN_SHIFT) /* Pin 1 */
# define GPIO_PIN2 (2 << GPIO_PIN_SHIFT) /* Pin 2 */
# define GPIO_PIN3 (3 << GPIO_PIN_SHIFT) /* Pin 3 */
# define GPIO_PIN4 (4 << GPIO_PIN_SHIFT) /* Pin 4 */
# define GPIO_PIN5 (5 << GPIO_PIN_SHIFT) /* Pin 5 */
# define GPIO_PIN6 (6 << GPIO_PIN_SHIFT) /* Pin 6 */
# define GPIO_PIN7 (7 << GPIO_PIN_SHIFT) /* Pin 7 */
# define GPIO_PIN8 (8 << GPIO_PIN_SHIFT) /* Pin 8 */
# define GPIO_PIN9 (9 << GPIO_PIN_SHIFT) /* Pin 9 */
# define GPIO_PIN10 (10 << GPIO_PIN_SHIFT) /* Pin 10 */
# define GPIO_PIN11 (11 << GPIO_PIN_SHIFT) /* Pin 11 */
# define GPIO_PIN12 (12 << GPIO_PIN_SHIFT) /* Pin 12 */
# define GPIO_PIN13 (13 << GPIO_PIN_SHIFT) /* Pin 13 */
# define GPIO_PIN14 (14 << GPIO_PIN_SHIFT) /* Pin 14 */
# define GPIO_PIN15 (15 << GPIO_PIN_SHIFT) /* Pin 15 */
# define GPIO_PIN16 (16 << GPIO_PIN_SHIFT) /* Pin 16 */
# define GPIO_PIN17 (17 << GPIO_PIN_SHIFT) /* Pin 17 */
# define GPIO_PIN18 (18 << GPIO_PIN_SHIFT) /* Pin 18 */
# define GPIO_PIN19 (19 << GPIO_PIN_SHIFT) /* Pin 19 */
# define GPIO_PIN20 (20 << GPIO_PIN_SHIFT) /* Pin 20 */
# define GPIO_PIN21 (21 << GPIO_PIN_SHIFT) /* Pin 21 */
# define GPIO_PIN22 (22 << GPIO_PIN_SHIFT) /* Pin 22 */
# define GPIO_PIN23 (23 << GPIO_PIN_SHIFT) /* Pin 23 */
# define GPIO_PIN24 (24 << GPIO_PIN_SHIFT) /* Pin 24 */
# define GPIO_PIN25 (25 << GPIO_PIN_SHIFT) /* Pin 25 */
# define GPIO_PIN26 (26 << GPIO_PIN_SHIFT) /* Pin 26 */
# define GPIO_PIN27 (27 << GPIO_PIN_SHIFT) /* Pin 27 */
# define GPIO_PIN28 (28 << GPIO_PIN_SHIFT) /* Pin 28 */
# define GPIO_PIN29 (29 << GPIO_PIN_SHIFT) /* Pin 29 */
# define GPIO_PIN30 (30 << GPIO_PIN_SHIFT) /* Pin 30 */
# define GPIO_PIN31 (31 << GPIO_PIN_SHIFT) /* Pin 31 */
/****************************************************************************
* Public Types
****************************************************************************/
/* The smallest integer type that can hold the GPIO encoding */
typedef uint32_t gpio_pinset_t;
/****************************************************************************
* Public Data
****************************************************************************/
#undef EXTERN
#if defined(__cplusplus)
#define EXTERN extern "C"
extern "C"
{
#else
#define EXTERN extern
#endif
/****************************************************************************
* Public Function Prototypes
****************************************************************************/
/****************************************************************************
* Name: mx8mp_config_gpio
*
* Description:
* Configure a GPIO pin based on bit-encoded description of the pin.
*
****************************************************************************/
int mx8mp_gpio_config(gpio_pinset_t pinset);
/****************************************************************************
* Name: imx_gpio_write
*
* Description:
* Write one or zero to the selected GPIO pin
*
****************************************************************************/
void mx8mp_gpio_write(gpio_pinset_t pinset, bool value);
/****************************************************************************
* Name: mx8mp_gpio_read
*
* Description:
* Read one or zero from the selected GPIO pin
*
****************************************************************************/
bool mx8mp_gpio_read(gpio_pinset_t pinset);
/****************************************************************************
* Name: mx8mp_gpio_configure_irq
*
* Description:
* Configure an interrupt for the specified GPIO pin.
*
****************************************************************************/
void mx8mp_gpio_configure_irq(gpio_pinset_t pinset);
/****************************************************************************
* Name: imx_gpioirq_enable
*
* Description:
* Enable the interrupt for specified GPIO IRQ
*
****************************************************************************/
int mx8mp_gpio_enable_irq(int irq);
/****************************************************************************
* Name: imx_gpioirq_disable
*
* Description:
* Disable the interrupt for specified GPIO IRQ
*
****************************************************************************/
int mx8mp_gpio_disable_irq(int irq);
/****************************************************************************
* Function: imx_dump_gpio
*
* Description:
* Dump all GPIO registers associated with the base address of the provided
* pinset.
*
****************************************************************************/
#ifdef CONFIG_DEBUG_GPIO_INFO
int mx8mp_dump_gpio(gpio_pinset_t pinset, const char *msg);
#else
# define mx8mp_dump_gpio(p,m)
#endif
#undef EXTERN
#if defined(__cplusplus)
}
#endif
#endif /* __ARCH_ARM_SRC_MX8MP_MX8MP_GPIO_H */

View file

@ -453,7 +453,7 @@ config ARCH_BOARD_ESP32S3_LCD_EV
voice wake-up, and features screen and voice interaction.
The board caters to development needs for touchscreen products with different resolutions
and interfaces. Currently, we have two boards available:
1. ESP32-S3-LCD-EV-Board with 480x480 LCD
2. ESP32-S3-LCD-EV-Board with 800x480 LCD
@ -2753,10 +2753,11 @@ config ARCH_BOARD_XMC4700RELAX
select ARCH_HAVE_IRQBUTTONS
---help---
Infineon XMC4700 Relax
config ARCH_BOARD_VERDIN_MX8MP
bool "Toradex Verdin i.MX8MP"
depends on ARCH_CHIP_MX8MP
select ARCH_HAVE_LEDS
---help---
Toradex Verdin i.MX8MP

View file

@ -18,10 +18,25 @@ CONFIG_ARMV7M_DCACHE=y
CONFIG_ARMV7M_DCACHE_WRITETHROUGH=y
CONFIG_ARMV7M_ICACHE=y
CONFIG_ARM_MPU=y
CONFIG_BOARD_LOOPSPERMSEC=159972
CONFIG_BOARD_LOOPSPERMSEC=8000
CONFIG_BUILTIN=y
CONFIG_CXX_EXCEPTION=y
CONFIG_CXX_RTTI=y
CONFIG_EXAMPLES_CALIB_UDELAY=y
CONFIG_EXAMPLES_CALIB_UDELAY_NUM_MEASUREMENTS=6
CONFIG_EXAMPLES_CALIB_UDELAY_NUM_RESULTS=60
CONFIG_EXAMPLES_INA219=y
CONFIG_HAVE_CXX=y
CONFIG_I2CTOOL_MAXADDR=0x7f
CONFIG_I2CTOOL_MAXBUS=6
CONFIG_I2CTOOL_MINADDR=0x00
CONFIG_I2CTOOL_MINBUS=1
CONFIG_I2C_RESET=y
CONFIG_INIT_ENTRYPOINT="nsh_main"
CONFIG_INTELHEX_BINARY=y
CONFIG_LIBCXX=y
CONFIG_MX8MP_I2C4=y
CONFIG_MX8MP_I2C=y
CONFIG_MX8MP_UART4=y
CONFIG_NSH_ARCHINIT=y
CONFIG_NSH_BUILTIN_APPS=y
@ -36,9 +51,14 @@ CONFIG_READLINE_CMD_HISTORY=y
CONFIG_RR_INTERVAL=200
CONFIG_SCHED_HPWORK=y
CONFIG_SCHED_WAITPID=y
CONFIG_SENSORS=y
CONFIG_SENSORS_INA219=y
CONFIG_START_DAY=10
CONFIG_START_MONTH=3
CONFIG_START_YEAR=2014
CONFIG_SYSTEM_I2CTOOL=y
CONFIG_SYSTEM_NSH=y
CONFIG_SYSTEM_RAMTEST=y
CONFIG_UART4_SERIAL_CONSOLE=y
CONFIG_USERLED=y
CONFIG_USERLED_LOWER=y

View file

@ -36,8 +36,47 @@
* Pre-processor Definitions
****************************************************************************/
#define IOMUX_CONSOLE_UART_RX IOMUXC_UART4_RXD_UART4_RX, 0, IOMUXC_SW_PAD_CTL_PAD_PUE_MASK | IOMUXC_SW_PAD_CTL_PAD_PE_MASK
#define IOMUX_CONSOLE_UART_TX IOMUXC_UART4_TXD_UART4_TX, 0, IOMUXC_SW_PAD_CTL_PAD_PUE_MASK | IOMUXC_SW_PAD_CTL_PAD_PE_MASK
/* Console UART IOMUX configuration */
#define IOMUX_CONSOLE_UART_RX IOMUXC_UART4_RXD_UART4_RX, 0, UART_PAD_CTRL
#define IOMUX_CONSOLE_UART_TX IOMUXC_UART4_TXD_UART4_TX, 0, UART_PAD_CTRL
/* LED definitions **********************************************************/
/* The Freedom K66F has a single RGB LED driven by the K66F as follows:
/* LED index values for use with board_userled() */
#define BOARD_LED_1 0
#define BOARD_LED_2 1
#define BOARD_LED_3 2
#define BOARD_LED_4 3
#define BOARD_NLEDS 4
/* LED bits for use with board_userled_all() */
#define BOARD_LED_1_BIT (1 << BOARD_LED_1)
#define BOARD_LED_2_BIT (1 << BOARD_LED_2)
#define BOARD_LED_3_BIT (1 << BOARD_LED_3)
#define BOARD_LED_4_BIT (1 << BOARD_LED_4)
/* If CONFIG_ARCH_LEDs is defined, then NuttX will control the LED on board.
* The following definitions describe how NuttX controls
* the LEDs:
*
* SYMBOL Meaning LED
* ------------------- ---------------------------- --------------------
*/
#define LED_STARTED 1 /* NuttX has been started None */
#define LED_HEAPALLOCATE 2 /* Heap has been allocated ON(1) */
#define LED_IRQSENABLED 0 /* Interrupts enabled ON(1) */
#define LED_STACKCREATED 3 /* Idle stack created ON(2) */
#define LED_INIRQ 0 /* In an interrupt (no change) */
#define LED_SIGNAL 0 /* In a signal handler (no change) */
#define LED_ASSERTION 0 /* An assertion failed (no change) */
#define LED_PANIC 5 /* The system has crashed FLASH(3) */
#undef LED_IDLE 4 /* idle loop FLASH(4) */
/****************************************************************************
* Public Data

View file

@ -34,5 +34,11 @@ ifeq ($(CONFIG_MX8MP_I2C_DRIVER),y)
CSRCS += mx8mp_i2cdev.c
endif
ifeq ($(CONFIG_ARCH_LEDS),y)
#CSRCS += mx8mp_autoleds.c
else
CSRCS += mx8mp_userleds.c
endif
include $(TOPDIR)/boards/Board.mk

View file

@ -54,7 +54,7 @@ int mx8mp_bringup(void)
{
int ret = OK;
#ifdef CONFIG_USERLED
#if !defined(CONFIG_ARCH_LEDS) && defined(CONFIG_USERLED_LOWER)
/* Register the LED driver */
ret = userled_lower_initialize("/dev/userleds");

View file

@ -0,0 +1,137 @@
/****************************************************************************
* boards/arm/nrf53/nrf5340-dk/src/nrf53_userleds.c
*
* Licensed to the Apache Software Foundation (ASF) under one or more
* contributor license agreements. See the NOTICE file distributed with
* this work for additional information regarding copyright ownership. The
* ASF licenses this file to you under the Apache License, Version 2.0 (the
* "License"); you may not use this file except in compliance with the
* License. You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
* WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
* License for the specific language governing permissions and limitations
* under the License.
*
****************************************************************************/
/****************************************************************************
* Included Files
****************************************************************************/
#include <nuttx/config.h>
#include <stdio.h>
#include <stdint.h>
#include <stdbool.h>
#include <debug.h>
#include <arch/board/board.h>
#include "chip.h"
#include "arm_internal.h"
#include "verdin-mx8mp.h"
#ifndef CONFIG_ARCH_LEDS
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/
/****************************************************************************
* Private Functions
****************************************************************************/
/****************************************************************************
* Name: led_dumppins
****************************************************************************/
#ifdef LED_VERBOSE
static void led_dumppins(const char *msg)
{
nrf53_pin_dump(PINCONFIG_LED, msg);
nrf53_gpio_dump(GPIO_LED, msg);
}
#else
# define led_dumppins(m)
#endif
/****************************************************************************
* Public Functions
****************************************************************************/
/****************************************************************************
* Name: board_userled_initialize
****************************************************************************/
uint32_t board_userled_initialize(void)
{
mx8mp_iomuxc_config(IOMUX_LED_1);
mx8mp_iomuxc_config(IOMUX_LED_1);
mx8mp_iomuxc_config(IOMUX_LED_1);
mx8mp_iomuxc_config(IOMUX_LED_1);
mx8mp_gpio_config(GPIO_LED_1);
mx8mp_gpio_config(GPIO_LED_2);
mx8mp_gpio_config(GPIO_LED_3);
mx8mp_gpio_config(GPIO_LED_4);
return BOARD_NLEDS;
}
/****************************************************************************
* Name: board_userled
****************************************************************************/
void board_userled(int led, bool on)
{
gpio_pinset_t gpio;
switch (led)
{
case BOARD_LED_1:
{
gpio = GPIO_LED_1;
}
break;
case BOARD_LED_2:
{
gpio = GPIO_LED_2;
}
break;
case BOARD_LED_3:
{
gpio = GPIO_LED_3;
}
break;
case BOARD_LED_4:
{
gpio = GPIO_LED_4;
}
break;
default:
return;
}
mx8mp_gpio_write(gpio, on);
}
/****************************************************************************
* Name: board_userled_all
****************************************************************************/
void board_userled_all(uint32_t ledset)
{
mx8mp_gpio_write(GPIO_LED_1, (ledset & BOARD_LED_1_BIT) == 0);
mx8mp_gpio_write(GPIO_LED_2, (ledset & BOARD_LED_2_BIT) == 0);
mx8mp_gpio_write(GPIO_LED_3, (ledset & BOARD_LED_3_BIT) == 0);
mx8mp_gpio_write(GPIO_LED_4, (ledset & BOARD_LED_4_BIT) == 0);
}
#endif /* !CONFIG_ARCH_LEDS */

View file

@ -26,11 +26,25 @@
****************************************************************************/
#include <nuttx/config.h>
#include "mx8mp_gpio.h"
#include "mx8mp_iomuxc.h"
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/
/* Board LEDs*/
#define GPIO_LED_1 (GPIO_OUTPUT | GPIO_OUTPUT_ONE | GPIO_PORT1 | GPIO_PIN0)
#define GPIO_LED_2 (GPIO_OUTPUT | GPIO_OUTPUT_ONE | GPIO_PORT1 | GPIO_PIN1)
#define GPIO_LED_3 (GPIO_OUTPUT | GPIO_OUTPUT_ONE | GPIO_PORT1 | GPIO_PIN5)
#define GPIO_LED_4 (GPIO_OUTPUT | GPIO_OUTPUT_ONE | GPIO_PORT1 | GPIO_PIN6)
#define IOMUX_LED_1 IOMUXC_GPIO1_IO00_GPIO1_IO00, 0, GPIO_PAD_CTRL
#define IOMUX_LED_2 IOMUXC_GPIO1_IO01_GPIO1_IO01, 0, GPIO_PAD_CTRL
#define IOMUX_LED_3 IOMUXC_GPIO1_IO05_GPIO1_IO05, 0, GPIO_PAD_CTRL
#define IOMUX_LED_4 IOMUXC_GPIO1_IO06_GPIO1_IO06, 0, GPIO_PAD_CTRL
/****************************************************************************
* Public Types
****************************************************************************/