i.MXRT1060-EVK (mostly): Add basic LCD support for the board IMXRT1060-EVK.

This commit is contained in:
Fabio Balzano 2019-10-23 13:17:30 -06:00 committed by Gregory Nutt
parent 005a8a606f
commit 5ca0b57a59
8 changed files with 641 additions and 38 deletions

View File

@ -582,34 +582,37 @@
/* LCD */
#define GPIO_LCD_CLK (GPIO_PERIPH | GPIO_ALT0 | GPIO_PADMUX(IMXRT_PADMUX_GPIO_B0_00_INDEX))
#define GPIO_LCD_DATA00 (GPIO_PERIPH | GPIO_ALT0 | GPIO_PADMUX(IMXRT_PADMUX_GPIO_B0_04_INDEX))
#define GPIO_LCD_DATA01 (GPIO_PERIPH | GPIO_ALT0 | GPIO_PADMUX(IMXRT_PADMUX_GPIO_B0_05_INDEX))
#define GPIO_LCD_DATA02 (GPIO_PERIPH | GPIO_ALT0 | GPIO_PADMUX(IMXRT_PADMUX_GPIO_B0_06_INDEX))
#define GPIO_LCD_DATA03 (GPIO_PERIPH | GPIO_ALT0 | GPIO_PADMUX(IMXRT_PADMUX_GPIO_B0_07_INDEX))
#define GPIO_LCD_DATA04 (GPIO_PERIPH | GPIO_ALT0 | GPIO_PADMUX(IMXRT_PADMUX_GPIO_B0_08_INDEX))
#define GPIO_LCD_DATA05 (GPIO_PERIPH | GPIO_ALT0 | GPIO_PADMUX(IMXRT_PADMUX_GPIO_B0_09_INDEX))
#define GPIO_LCD_DATA06 (GPIO_PERIPH | GPIO_ALT0 | GPIO_PADMUX(IMXRT_PADMUX_GPIO_B0_10_INDEX))
#define GPIO_LCD_DATA07 (GPIO_PERIPH | GPIO_ALT0 | GPIO_PADMUX(IMXRT_PADMUX_GPIO_B0_11_INDEX))
#define GPIO_LCD_DATA08 (GPIO_PERIPH | GPIO_ALT0 | GPIO_PADMUX(IMXRT_PADMUX_GPIO_B0_12_INDEX))
#define GPIO_LCD_DATA09 (GPIO_PERIPH | GPIO_ALT0 | GPIO_PADMUX(IMXRT_PADMUX_GPIO_B0_13_INDEX))
#define GPIO_LCD_DATA10 (GPIO_PERIPH | GPIO_ALT0 | GPIO_PADMUX(IMXRT_PADMUX_GPIO_B0_14_INDEX))
#define GPIO_LCD_DATA11 (GPIO_PERIPH | GPIO_ALT0 | GPIO_PADMUX(IMXRT_PADMUX_GPIO_B0_15_INDEX))
#define GPIO_LCD_DATA12 (GPIO_PERIPH | GPIO_ALT0 | GPIO_PADMUX(IMXRT_PADMUX_GPIO_B1_00_INDEX))
#define GPIO_LCD_DATA13 (GPIO_PERIPH | GPIO_ALT0 | GPIO_PADMUX(IMXRT_PADMUX_GPIO_B1_01_INDEX))
#define GPIO_LCD_DATA14 (GPIO_PERIPH | GPIO_ALT0 | GPIO_PADMUX(IMXRT_PADMUX_GPIO_B1_02_INDEX))
#define GPIO_LCD_DATA15 (GPIO_PERIPH | GPIO_ALT0 | GPIO_PADMUX(IMXRT_PADMUX_GPIO_B1_03_INDEX))
#define GPIO_LCD_DATA16 (GPIO_PERIPH | GPIO_ALT0 | GPIO_PADMUX(IMXRT_PADMUX_GPIO_B1_04_INDEX))
#define GPIO_LCD_DATA17 (GPIO_PERIPH | GPIO_ALT0 | GPIO_PADMUX(IMXRT_PADMUX_GPIO_B1_05_INDEX))
#define GPIO_LCD_DATA18 (GPIO_PERIPH | GPIO_ALT0 | GPIO_PADMUX(IMXRT_PADMUX_GPIO_B1_06_INDEX))
#define GPIO_LCD_DATA19 (GPIO_PERIPH | GPIO_ALT0 | GPIO_PADMUX(IMXRT_PADMUX_GPIO_B1_07_INDEX))
#define GPIO_LCD_DATA20 (GPIO_PERIPH | GPIO_ALT0 | GPIO_PADMUX(IMXRT_PADMUX_GPIO_B1_08_INDEX))
#define GPIO_LCD_DATA21 (GPIO_PERIPH | GPIO_ALT0 | GPIO_PADMUX(IMXRT_PADMUX_GPIO_B1_09_INDEX))
#define GPIO_LCD_DATA22 (GPIO_PERIPH | GPIO_ALT0 | GPIO_PADMUX(IMXRT_PADMUX_GPIO_B1_10_INDEX))
#define GPIO_LCD_DATA23 (GPIO_PERIPH | GPIO_ALT0 | GPIO_PADMUX(IMXRT_PADMUX_GPIO_B1_11_INDEX))
#define GPIO_LCD_ENABLE (GPIO_PERIPH | GPIO_ALT0 | GPIO_PADMUX(IMXRT_PADMUX_GPIO_B0_01_INDEX))
#define GPIO_LCD_HSYNC (GPIO_PERIPH | GPIO_ALT0 | GPIO_PADMUX(IMXRT_PADMUX_GPIO_B0_02_INDEX))
#define GPIO_LCD_VSYNC (GPIO_PERIPH | GPIO_ALT0 | GPIO_PADMUX(IMXRT_PADMUX_GPIO_B0_03_INDEX))
#define IOMUX_LCD (IOMUX_PULL_UP_100K | IOMUX_CMOS_OUTPUT | IOMUX_DRIVE_40OHM | \
IOMUX_SLEW_SLOW | IOMUX_SPEED_MEDIUM | IOMUX_SCHMITT_TRIGGER)
#define GPIO_LCD_CLK (GPIO_PERIPH | GPIO_ALT0 | GPIO_PADMUX(IMXRT_PADMUX_GPIO_B0_00_INDEX) | IOMUX_LCD)
#define GPIO_LCD_DATA00 (GPIO_PERIPH | GPIO_ALT0 | GPIO_PADMUX(IMXRT_PADMUX_GPIO_B0_04_INDEX) | IOMUX_LCD)
#define GPIO_LCD_DATA01 (GPIO_PERIPH | GPIO_ALT0 | GPIO_PADMUX(IMXRT_PADMUX_GPIO_B0_05_INDEX) | IOMUX_LCD)
#define GPIO_LCD_DATA02 (GPIO_PERIPH | GPIO_ALT0 | GPIO_PADMUX(IMXRT_PADMUX_GPIO_B0_06_INDEX) | IOMUX_LCD)
#define GPIO_LCD_DATA03 (GPIO_PERIPH | GPIO_ALT0 | GPIO_PADMUX(IMXRT_PADMUX_GPIO_B0_07_INDEX) | IOMUX_LCD)
#define GPIO_LCD_DATA04 (GPIO_PERIPH | GPIO_ALT0 | GPIO_PADMUX(IMXRT_PADMUX_GPIO_B0_08_INDEX) | IOMUX_LCD)
#define GPIO_LCD_DATA05 (GPIO_PERIPH | GPIO_ALT0 | GPIO_PADMUX(IMXRT_PADMUX_GPIO_B0_09_INDEX) | IOMUX_LCD)
#define GPIO_LCD_DATA06 (GPIO_PERIPH | GPIO_ALT0 | GPIO_PADMUX(IMXRT_PADMUX_GPIO_B0_10_INDEX) | IOMUX_LCD)
#define GPIO_LCD_DATA07 (GPIO_PERIPH | GPIO_ALT0 | GPIO_PADMUX(IMXRT_PADMUX_GPIO_B0_11_INDEX) | IOMUX_LCD)
#define GPIO_LCD_DATA08 (GPIO_PERIPH | GPIO_ALT0 | GPIO_PADMUX(IMXRT_PADMUX_GPIO_B0_12_INDEX) | IOMUX_LCD)
#define GPIO_LCD_DATA09 (GPIO_PERIPH | GPIO_ALT0 | GPIO_PADMUX(IMXRT_PADMUX_GPIO_B0_13_INDEX) | IOMUX_LCD)
#define GPIO_LCD_DATA10 (GPIO_PERIPH | GPIO_ALT0 | GPIO_PADMUX(IMXRT_PADMUX_GPIO_B0_14_INDEX) | IOMUX_LCD)
#define GPIO_LCD_DATA11 (GPIO_PERIPH | GPIO_ALT0 | GPIO_PADMUX(IMXRT_PADMUX_GPIO_B0_15_INDEX) | IOMUX_LCD)
#define GPIO_LCD_DATA12 (GPIO_PERIPH | GPIO_ALT0 | GPIO_PADMUX(IMXRT_PADMUX_GPIO_B1_00_INDEX) | IOMUX_LCD)
#define GPIO_LCD_DATA13 (GPIO_PERIPH | GPIO_ALT0 | GPIO_PADMUX(IMXRT_PADMUX_GPIO_B1_01_INDEX) | IOMUX_LCD)
#define GPIO_LCD_DATA14 (GPIO_PERIPH | GPIO_ALT0 | GPIO_PADMUX(IMXRT_PADMUX_GPIO_B1_02_INDEX) | IOMUX_LCD)
#define GPIO_LCD_DATA15 (GPIO_PERIPH | GPIO_ALT0 | GPIO_PADMUX(IMXRT_PADMUX_GPIO_B1_03_INDEX) | IOMUX_LCD)
#define GPIO_LCD_DATA16 (GPIO_PERIPH | GPIO_ALT0 | GPIO_PADMUX(IMXRT_PADMUX_GPIO_B1_04_INDEX) | IOMUX_LCD)
#define GPIO_LCD_DATA17 (GPIO_PERIPH | GPIO_ALT0 | GPIO_PADMUX(IMXRT_PADMUX_GPIO_B1_05_INDEX) | IOMUX_LCD)
#define GPIO_LCD_DATA18 (GPIO_PERIPH | GPIO_ALT0 | GPIO_PADMUX(IMXRT_PADMUX_GPIO_B1_06_INDEX) | IOMUX_LCD)
#define GPIO_LCD_DATA19 (GPIO_PERIPH | GPIO_ALT0 | GPIO_PADMUX(IMXRT_PADMUX_GPIO_B1_07_INDEX) | IOMUX_LCD)
#define GPIO_LCD_DATA20 (GPIO_PERIPH | GPIO_ALT0 | GPIO_PADMUX(IMXRT_PADMUX_GPIO_B1_08_INDEX) | IOMUX_LCD)
#define GPIO_LCD_DATA21 (GPIO_PERIPH | GPIO_ALT0 | GPIO_PADMUX(IMXRT_PADMUX_GPIO_B1_09_INDEX) | IOMUX_LCD)
#define GPIO_LCD_DATA22 (GPIO_PERIPH | GPIO_ALT0 | GPIO_PADMUX(IMXRT_PADMUX_GPIO_B1_10_INDEX) | IOMUX_LCD)
#define GPIO_LCD_DATA23 (GPIO_PERIPH | GPIO_ALT0 | GPIO_PADMUX(IMXRT_PADMUX_GPIO_B1_11_INDEX) | IOMUX_LCD)
#define GPIO_LCD_ENABLE (GPIO_PERIPH | GPIO_ALT0 | GPIO_PADMUX(IMXRT_PADMUX_GPIO_B0_01_INDEX) | IOMUX_LCD)
#define GPIO_LCD_HSYNC (GPIO_PERIPH | GPIO_ALT0 | GPIO_PADMUX(IMXRT_PADMUX_GPIO_B0_02_INDEX) | IOMUX_LCD)
#define GPIO_LCD_VSYNC (GPIO_PERIPH | GPIO_ALT0 | GPIO_PADMUX(IMXRT_PADMUX_GPIO_B0_03_INDEX) | IOMUX_LCD)
/* Low Power Inter-Integrated Circuit (LPI2C) */

View File

@ -68,7 +68,8 @@
* 600Mhz = 600Mhz / 1
*
* PRE_PERIPH_CLK_SEL = PRE_PERIPH_CLK_SEL_PLL1
* PERIPH_CLK_SEL = 1 (0 select PERIPH_CLK2_PODF, 1 select PRE_PERIPH_CLK_SEL_PLL1)
* PERIPH_CLK_SEL = 1 (0 select PERIPH_CLK2_PODF,
* 1 select PRE_PERIPH_CLK_SEL_PLL1)
* PERIPH_CLK = 600Mhz
*
* IPG_CLOCK_ROOT = AHB_CLOCK_ROOT / IMXRT_IPG_PODF_DIVIDER
@ -79,7 +80,8 @@
* IMXRT_PERCLK_PODF_DIVIDER = 1
* 150Mhz = 150Mhz / 1
*
* SEMC_CLK_ROOT = 600Mhz / IMXRT_SEMC_PODF_DIVIDER (labeled AIX_PODF in 18.2)
* SEMC_CLK_ROOT = 600Mhz / IMXRT_SEMC_PODF_DIVIDER
* (labeled AIX_PODF in 18.2)
* IMXRT_SEMC_PODF_DIVIDER = 8
* 75Mhz = 600Mhz / 8
*
@ -156,6 +158,17 @@
* 2Hz, then a fatal error has been detected and the system has halted.
*/
/* Touchscreen definitions **************************************************/
/* The IMXRT 1050/1060 have connectors for the LCD model RK043FN02H-CT.
* It comes with the FT5336GQQ (FT5X06) touchscreen chip integrated.
* FT5X06 is connected to the LPI2C1 bus.
*/
/* LPI2C address of the FT5336GQQ touchscreen chip */
#define FT5X06_I2C_ADDRESS 0x38
/* Button definitions *******************************************************/
/* The IMXRT board has one external user button

View File

@ -70,6 +70,14 @@ ifeq ($(CONFIG_MMCSD_SPI),y)
CSRCS += imxrt_mmcsd_spi.c
endif
ifeq ($(CONFIG_DEV_GPIO),y)
CSRCS += imxrt_gpio.c
endif
ifeq ($(CONFIG_INPUT_FT5X06),y)
CSRCS += imxrt_ft5x06.c
endif
ifeq ($(CONFIG_IMXRT_LCD),y)
CSRCS += imxrt_lcd.c
endif

View File

@ -58,7 +58,7 @@
/* Configuration ************************************************************/
/* i.MX RT 1050 GPIO Pin Definitions ****************************************/
/* i.MX RT 1060 GPIO Pin Definitions ****************************************/
/* LEDs
*
@ -105,6 +105,27 @@
#define GPIO_SW8 (GPIO_INTERRUPT | GPIO_INT_FALLINGEDGE | \
GPIO_PORT5 | GPIO_PIN0 | IOMUX_SW8)
/* Touchscreen
*
* Interrupt line: GPIO_AD_B0_11
*
* The interrupt line coming from the touchscreen FT5336GQQ IC.
* The touchscreen IC is integrated into the optional RK043FN02H-CT LCD panel
* and it's connected to the LPI2C1 bus.
*
* Reset line: GPIO_AD_B0_02
*
* The reset line is active low.
*/
#define GPIO_FT5X06_INTR IMXRT_IRQ_GPIO1_11
#define IOMUX_FT5X06_RST (IOMUX_SLEW_FAST | IOMUX_DRIVE_50OHM | \
IOMUX_SPEED_MEDIUM | IOMUX_PULL_UP_100K | \
_IOMUX_PULL_ENABLE)
#define GPIO_FT5X06_CTRSTn (GPIO_OUTPUT | GPIO_OUTPUT_ZERO | \
GPIO_PORT1 | GPIO_PIN2 | IOMUX_FT5X06_RST)
/* Ethernet Interrupt: GPIOAD_B0_10
*
* This pin has a week pull-up within the PHY, is open-drain, and requires
@ -218,8 +239,6 @@ int imxrt_mmcsd_spi_initialize(int minor)
void imxrt_autoled_initialize(void);
#endif
#ifdef CONFIG_DEV_GPIO
/****************************************************************************
* Name: imxrt_gpio_initialize
*
@ -228,8 +247,33 @@ void imxrt_autoled_initialize(void);
*
****************************************************************************/
#ifdef CONFIG_DEV_GPIO
int imxrt_gpio_initialize(void);
#endif
/****************************************************************************
* Name: imxrt_ft5x06_register
*
* Description:
* Initialize ft5x06 IC touchscreen driver
*
****************************************************************************/
#ifdef CONFIG_INPUT_FT5X06
int imxrt_ft5x06_register(void);
#endif
/****************************************************************************
* Name: imxrt_backlight
*
* Description:
* Initialize the backlight pins of the LCD and turn it ON
*
****************************************************************************/
#ifdef CONFIG_IMXRT_LCD
void imxrt_lcd_initialize(void);
#endif
#endif /* __ASSEMBLY__ */
#endif /* __BOARDS_ARM_IMXRT1060_EVK_SRC_IMXRT1060_EVK_H */

View File

@ -182,6 +182,8 @@ int imxrt_bringup(void)
#endif
#ifdef CONFIG_DEV_GPIO
/* Initialize the GPIO driver */
ret = imxrt_gpio_initialize();
if (ret < 0)
{
@ -190,6 +192,22 @@ int imxrt_bringup(void)
}
#endif
#ifdef CONFIG_INPUT_FT5X06
/* Initialize the FT5X06 touchscreen driver */
ret = imxrt_ft5x06_register();
if (ret < 0)
{
syslog(LOG_ERR, "ERROR: imxrt_ft5x06_register() failed: %d\n", ret);
}
#endif
#ifdef CONFIG_IMXRT_LCD
/* Initialize the backlight pin and turn it to ON. */
imxrt_lcd_initialize();
#endif
#ifdef CONFIG_VIDEO_FB
/* Initialize and register the framebuffer driver */

View File

@ -0,0 +1,258 @@
/****************************************************************************
* boards/arm/imxrt/imxrt1060-evk/src/imxrt_ft5x06.c
*
* Copyright 2019 ElFaro LAB S.L. All rights reserved.
* Author: Fabio Balzano <fabio@elfarolab.com>
*
* Based on boards/arm/lpc54xx/lpcxpresso-lpc54628/src/lpc54_ft5x06.c
* Copyright (C) 2017 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 <syslog.h>
#include <errno.h>
#include <nuttx/arch.h>
#include <nuttx/i2c/i2c_master.h>
#include <nuttx/input/ft5x06.h>
#include "imxrt_config.h"
#include "imxrt_gpio.h"
#include "imxrt_lpi2c.h"
#include "imxrt1060-evk.h"
#include <arch/board/board.h>
#ifdef CONFIG_INPUT_FT5X06
/****************************************************************************
* Pre-processor Defintions
****************************************************************************/
#define FT5X06_FREQUENCY 400000 /* For now, will boost later */
/****************************************************************************
* Private Function Ptototypes
****************************************************************************/
#ifndef CONFIG_FT5X06_POLLMODE
static int imxrt_ft5x06_attach(FAR const struct ft5x06_config_s *config,
xcpt_t isr, FAR void *arg);
static void imxrt_ft5x06_enable(FAR const struct ft5x06_config_s *config,
bool enable);
static void imxrt_ft5x06_clear(FAR const struct ft5x06_config_s *config);
#endif
static void imxrt_ft5x06_wakeup(FAR const struct ft5x06_config_s *config);
static void imxrt_ft5x06_nreset(FAR const struct ft5x06_config_s *config,
bool state);
/****************************************************************************
* Private Data
****************************************************************************/
static const struct ft5x06_config_s g_ft5x06_config =
{
.address = FT5X06_I2C_ADDRESS,
.frequency = FT5X06_FREQUENCY,
#ifndef CONFIG_FT5X06_POLLMODE
.attach = imxrt_ft5x06_attach,
.enable = imxrt_ft5x06_enable,
.clear = imxrt_ft5x06_clear,
#endif
.wakeup = imxrt_ft5x06_wakeup,
.nreset = imxrt_ft5x06_nreset
};
#ifndef CONFIG_FT5X06_POLLMODE
static uint8_t g_ft5x06_irq;
#endif
/****************************************************************************
* Private Functions
****************************************************************************/
/****************************************************************************
* Name: imxrt_ft5x06_attach
*
* Description:
* Attach an FT5X06 interrupt handler to a GPIO interrupt
*
****************************************************************************/
#ifndef CONFIG_FT5X06_POLLMODE
static int imxrt_ft5x06_attach(FAR const struct ft5x06_config_s *config,
xcpt_t isr, FAR void *arg)
{
return irq_attach(g_ft5x06_irq, isr, arg);
}
#endif
/****************************************************************************
* Name: imxrt_ft5x06_enable
*
* Description:
* Enable or disable a GPIO interrupt
*
****************************************************************************/
#ifndef CONFIG_FT5X06_POLLMODE
static void imxrt_ft5x06_enable(FAR const struct ft5x06_config_s *config,
bool enable)
{
if (enable)
{
up_enable_irq(g_ft5x06_irq);
}
else
{
up_disable_irq(g_ft5x06_irq);
}
}
#endif
/****************************************************************************
* Name: imxrt_ft5x06_clear
*
* Description:
* Acknowledge/clear any pending GPIO interrupt
*
****************************************************************************/
#ifndef CONFIG_FT5X06_POLLMODE
static void imxrt_ft5x06_clear(FAR const struct ft5x06_config_s *config)
{
(void)imxrt_gpio_ackedge(g_ft5x06_irq);
}
#endif
/****************************************************************************
* Name: imxrt_ft5x06_wakeup
*
* Description:
* Issue WAKE interrupt to FT5X06 to change the FT5X06 from Hibernate to
* Active mode.
*
****************************************************************************/
static void imxrt_ft5x06_wakeup(FAR const struct ft5x06_config_s *config)
{
/* We do not have access to the WAKE pin in the implementation */
}
/****************************************************************************
* Name: imxrt_ft5x06_nreset
*
* Description:
* Control the chip reset pin (active low)
*
****************************************************************************/
static void imxrt_ft5x06_nreset(FAR const struct ft5x06_config_s *config,
bool nstate)
{
imxrt_gpio_write(GPIO_FT5X06_CTRSTn, nstate);
}
/****************************************************************************
* Public Functions
****************************************************************************/
/****************************************************************************
* Name: imxrt_ft5x06_register
*
* Description:
* Register the FT5X06 touch panel driver
*
****************************************************************************/
int imxrt_ft5x06_register(void)
{
FAR struct i2c_master_s *i2c;
int ret;
/* Initialize CTRSTn pin */
imxrt_config_gpio(GPIO_FT5X06_CTRSTn);
#ifndef CONFIG_FT5X06_POLLMODE
int irq;
/* Initialize GPIO interrupt pin. */
imxrt_gpio_config(GPIO_FT5X06_INTR);
irq = imxrt_gpio_irqno(GPIO_FT5X06_INTR);
DEBUGASSERT(irq > 0 && irq < UINT8_MAX);
g_ft5x06_irq = (uint8_t)irq;
/* Make sure that the interrupt is disabled at the NVIC */
imxrt_gpio_ackedge(irq);
up_disable_irq(irq);
#endif
/* Take the FT5X06 out of reset */
imxrt_gpio_write(GPIO_FT5X06_CTRSTn, true);
/* The FT5X06 is on LPI2C1. Get the handle and register the F5x06 device */
i2c = imxrt_i2cbus_initialize(1);
if (i2c == NULL)
{
syslog(LOG_ERR, "ERROR: Failed to get LPI2C1 interface\n");
return -ENODEV;
}
else
{
ret = ft5x06_register(i2c, &g_ft5x06_config, 0);
if (ret < 0)
{
syslog(LOG_ERR, "ERROR: Failed to register FT5X06 driver: %d\n",
ret);
imxrt_gpio_write(GPIO_FT5X06_CTRSTn, false);
imxrt_i2cbus_uninitialize(i2c);
return ret;
}
}
return OK;
}
#endif /* CONFIG_INPUT_FT5X06*/

View File

@ -0,0 +1,236 @@
/****************************************************************************
* boards/arm/imxrt/imxrt1060-evk/src/imxrt_gpio.c
*
* Copyright (C) 2017-2018 Gregory Nutt. All rights reserved.
* Copyright (C) 2017 Alan Carvalho de Assis. All rights reserved.
* Author: Alan Carvalho de Assis <acassis@gmail.com>
*
* Based on: boards/imxrt1050-evk/src/imxrt_gpio.c
*
* Author: Pavlina Koleva <pavlinaikoleva19@gmail.com>
* Modified by: Ivan Ucherdzhiev <ivanucherdjiev@gmail.com>
*
* 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 <stdbool.h>
#include <assert.h>
#include <debug.h>
#include <nuttx/clock.h>
#include <nuttx/wdog.h>
#include <nuttx/ioexpander/gpio.h>
#include <arch/board/board.h>
#include "chip.h"
#include <imxrt_gpio.h>
#include "imxrt1060-evk.h"
#if defined(CONFIG_DEV_GPIO) && !defined(CONFIG_GPIO_LOWER_HALF)
/****************************************************************************
* Private Types
****************************************************************************/
struct imxrtgpio_dev_s
{
struct gpio_dev_s gpio;
uint8_t id;
};
/****************************************************************************
* Private Function Prototypes
****************************************************************************/
#if BOARD_NGPIOIN > 0
static int gpin_read(FAR struct gpio_dev_s *dev, FAR bool *value);
#endif
#if BOARD_NGPIOOUT > 0
static int gpout_read(FAR struct gpio_dev_s *dev, FAR bool *value);
static int gpout_write(FAR struct gpio_dev_s *dev, bool value);
#endif
/****************************************************************************
* Private Data
****************************************************************************/
#if BOARD_NGPIOIN > 0
static const struct gpio_operations_s gpin_ops =
{
.go_read = gpin_read,
.go_write = NULL,
.go_attach = NULL,
.go_enable = NULL,
};
/* This array maps the GPIO pins used as INPUT */
static const uint32_t g_gpioinputs[BOARD_NGPIOIN] =
{
GPIO_IN1,
};
static struct imxrtgpio_dev_s g_gpin[BOARD_NGPIOIN];
#endif
#if BOARD_NGPIOOUT > 0
static const struct gpio_operations_s gpout_ops =
{
.go_read = gpout_read,
.go_write = gpout_write,
.go_attach = NULL,
.go_enable = NULL,
};
/* This array maps the GPIO pins used as OUTPUT */
static const uint32_t g_gpiooutputs[BOARD_NGPIOOUT] =
{
GPIO_GOUT1,
GPIO_GOUT2,
GPIO_GOUT3,
GPIO_GOUT4,
};
static struct imxrtgpio_dev_s g_gpout[BOARD_NGPIOOUT];
#endif
/****************************************************************************
* Private Functions
****************************************************************************/
#if BOARD_NGPIOIN > 0
static int gpin_read(FAR struct gpio_dev_s *dev, FAR bool *value)
{
FAR struct imxrtgpio_dev_s *imxrtgpio = (FAR struct imxrtgpio_dev_s *)dev;
DEBUGASSERT(imxrtgpio != NULL && value != NULL);
DEBUGASSERT(imxrtgpio->id < BOARD_NGPIOIN);
gpioinfo("Reading...\n");
*value = imxrt_gpio_read(g_gpioinputs[imxrtgpio->id]);
return OK;
}
#endif
#if BOARD_NGPIOOUT > 0
static int gpout_read(FAR struct gpio_dev_s *dev, FAR bool *value)
{
FAR struct imxrtgpio_dev_s *imxrtgpio = (FAR struct imxrtgpio_dev_s *)dev;
DEBUGASSERT(imxrtgpio != NULL && value != NULL);
DEBUGASSERT(imxrtgpio->id < BOARD_NGPIOOUT);
gpioinfo("Reading...\n");
*value = imxrt_gpio_read(g_gpiooutputs[imxrtgpio->id]);
return OK;
}
static int gpout_write(FAR struct gpio_dev_s *dev, bool value)
{
FAR struct imxrtgpio_dev_s *imxrtgpio = (FAR struct imxrtgpio_dev_s *)dev;
DEBUGASSERT(imxrtgpio != NULL);
DEBUGASSERT(imxrtgpio->id < BOARD_NGPIOOUT);
gpioinfo("Writing %d\n", (int)value);
imxrt_gpio_write(g_gpiooutputs[imxrtgpio->id], value);
return OK;
}
#endif
/****************************************************************************
* Public Functions
****************************************************************************/
/****************************************************************************
* Name: imxrt_gpio_initialize
*
* Description:
* Initialize GPIO drivers for use with /apps/examples/gpio
*
****************************************************************************/
int imxrt_gpio_initialize(void)
{
int pincount = 0;
int i;
#if BOARD_NGPIOIN > 0
for (i = 0; i < BOARD_NGPIOIN; i++)
{
/* Setup and register the GPIO pin */
g_gpin[i].gpio.gp_pintype = GPIO_INPUT_PIN;
g_gpin[i].gpio.gp_ops = &gpin_ops;
g_gpin[i].id = i;
(void)gpio_pin_register(&g_gpin[i].gpio, pincount);
/* Configure the pin that will be used as input */
imxrt_config_gpio(g_gpioinputs[i]);
pincount++;
}
#endif
#if BOARD_NGPIOOUT > 0
for (i = 0; i < BOARD_NGPIOOUT; i++)
{
/* Setup and register the GPIO pin */
g_gpout[i].gpio.gp_pintype = GPIO_OUTPUT_PIN;
g_gpout[i].gpio.gp_ops = &gpout_ops;
g_gpout[i].id = i;
(void)gpio_pin_register(&g_gpout[i].gpio, pincount);
/* Configure the pin that will be used as output */
imxrt_gpio_write(g_gpiooutputs[i], 0);
imxrt_config_gpio(g_gpiooutputs[i]);
pincount++;
}
#endif
return 0;
}
#endif /* CONFIG_DEV_GPIO && !CONFIG_GPIO_LOWER_HALF */

View File

@ -47,22 +47,22 @@
#include "imxrt1060-evk.h"
#ifdef CONFIG_IMXRT_LCD
/****************************************************************************
* Public Functions
****************************************************************************/
/****************************************************************************
* Name: imxrt_lcd_initialize
* Name: imxrt_lcd_bkl_pin_setup
*
* Description:
* Initialize the LCD. Setup backlight (initially off)
* Setup backlight pin (initially off)
*
****************************************************************************/
void imxrt_lcd_initialize(void)
void imxrt_lcd_pkl_pin_setup(void)
{
/* Configure the LCD backlight (and turn the backlight off) */
imxrt_config_gpio(GPIO_LCD_BL);
}
@ -81,3 +81,26 @@ void imxrt_backlight(bool blon)
imxrt_gpio_write(GPIO_LCD_BL, blon); /* High illuminates */
}
#endif
/****************************************************************************
* Name: imxrt_lcd_initialize
*
* Description:
* Initialization of the LCD blackligt and pin for the imxrt_bringup().
*
****************************************************************************/
void imxrt_lcd_initialize(void)
{
/* Setup the backlight pin */
imxrt_lcd_pkl_pin_setup();
#ifdef CONFIG_IMXRT_LCD_BACKLIGHT
/* Turn ON the backlight */
imxrt_backlight(true);
#endif
}
#endif /* CONFIG_IMXRT_LCD */