Merged in alinjerpelea/nuttx (pull request #928)

configs: spresense: add basic LCD configuration

* arch: arm: cxd56xx: add Graphics Engine

    Add driver for hardware image processor device

    to enable the hardware image processor set CXD56_GE2D=true

    Signed-off-by: Alin Jerpelea <alin.jerpelea@sony.com>

* drivers: lcd: add ILI9340 LCD Single Chip Driver

    LCD Single Chip Driver, ILI9340, ILI Technology Corp.

    Required LCD driver settings:
    LCD_MAXCONTRAST should be 255, but any value >0 and <=255 will be accepted.
    LCD_MAXPOWER should be 1:  0=off, 1=on

    Signed-off-by: Alin Jerpelea <alin.jerpelea@sony.com>

* drivers: lcd: JDI LPM013M091A LCD Driver

    JDI LPM013M091A LCD Driver.

    This driver doesn't support reading data.
    Recommended to use DMA to transfer data or displayed image would be
    broken.

    Signed-off-by: Alin Jerpelea <alin.jerpelea@sony.com>

* configs: spresense: add basic LCD configuration

    add basic LCD configuration for spresense board

    Signed-off-by: Alin Jerpelea <alin.jerpelea@sony.com>

* configs: spresense: add lpm013m091a LCD

    add device configuration for lpm013m091a LCD on spresense board

    Signed-off-by: Alin Jerpelea <alin.jerpelea@sony.com>

* configs: spresense: add ili9340 LCD

    add device configuration for ili9340 LCD on spresense board

    Signed-off-by: Alin Jerpelea <alin.jerpelea@sony.com>

* configs: spresense: add defconfig with LCD

    add defconfig with LCD for spresense board

    Signed-off-by: Alin Jerpelea <alin.jerpelea@sony.com>

Approved-by: Gregory Nutt <gnutt@nuttx.org>
This commit is contained in:
Alin Jerpelea 2019-07-03 12:24:13 +00:00 committed by Gregory Nutt
parent 7815c3a720
commit 55a4029885
16 changed files with 3750 additions and 0 deletions

View File

@ -1172,4 +1172,10 @@ config CXD56_EMMC
Emmc driver for cxd56xx chip
endmenu
config CXD56_GE2D
bool "Graphics Engine"
default n
---help---
A hardware image processor device.
endmenu

View File

@ -156,6 +156,10 @@ ifeq ($(CONFIG_CXD56_CHARGER),y)
CHIP_CSRCS += cxd56_charger.c
endif
ifeq ($(CONFIG_CXD56_GE2D),y)
CHIP_CSRCS += cxd56_ge2d.c
endif
ifeq ($(CONFIG_CXD56_SCU),y)
CHIP_CSRCS += cxd56_scu.c cxd56_scufifo.c
ifeq ($(CONFIG_CXD56_ADC),y)

View File

@ -0,0 +1,283 @@
/****************************************************************************
* arch/arm/src/cxd56xx/cxd56_ge2d.c
*
* Copyright 2018 Sony Semiconductor Solutions Corporation
*
* 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 of Sony Semiconductor Solutions Corporation nor
* the names of its contributors may be used to endorse or promote
* products derived from this software without specific prior written
* permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
/****************************************************************************
* Included Files
****************************************************************************/
#include <nuttx/config.h>
#include <nuttx/kmalloc.h>
#include <nuttx/fs/fs.h>
#include <nuttx/irq.h>
#include <queue.h>
#include <semaphore.h>
#include <stdio.h>
#include <stdint.h>
#include <string.h>
#include <debug.h>
#include <errno.h>
#include "up_arch.h"
#include "chip.h"
#include "cxd56_clock.h"
#include "hardware/cxd56_ge2d.h"
/****************************************************************************
* Private Function Prototypes
****************************************************************************/
static int ge2d_open(FAR struct file *filep);
static int ge2d_close(FAR struct file *filep);
static ssize_t ge2d_read(FAR struct file *filep, FAR char *buffer,
size_t len);
static ssize_t ge2d_write(FAR struct file *filep, FAR const char *buffer,
size_t len);
static int ge2d_ioctl(FAR struct file *filep, int cmd, unsigned long arg);
static int ge2d_semtake(sem_t *id);
static void ge2d_semgive(sem_t *id);
static int ge2d_irqhandler(int irq, FAR void *context, FAR void *arg);
/****************************************************************************
* Private Data
****************************************************************************/
static const struct file_operations g_ge2dfops =
{
.open = ge2d_open,
.close = ge2d_close,
.read = ge2d_read,
.write = ge2d_write,
.seek = 0,
.ioctl = ge2d_ioctl,
};
static sem_t g_wait;
static sem_t g_lock;
/****************************************************************************
* Private Functions
****************************************************************************/
/****************************************************************************
* Name: ge2d_semtake
****************************************************************************/
static int ge2d_semtake(sem_t *id)
{
while (sem_wait(id) != 0)
{
ASSERT(errno == EINTR);
}
return OK;
}
/****************************************************************************
* Name: ge2d_semgive
****************************************************************************/
static void ge2d_semgive(sem_t *id)
{
sem_post(id);
}
/****************************************************************************
* Name: ge2d_open
****************************************************************************/
static int ge2d_open(FAR struct file *filep)
{
return 0;
}
/****************************************************************************
* Name: ge2d_close
****************************************************************************/
static int ge2d_close(FAR struct file *filep)
{
return 0;
}
/****************************************************************************
* Name: ge2d_read
****************************************************************************/
static ssize_t ge2d_read(FAR struct file *filep, FAR char *buffer, size_t len)
{
return 0;
}
/****************************************************************************
* Name: ge2d_write
****************************************************************************/
static ssize_t ge2d_write(FAR struct file *filep,
FAR const char *buffer,
size_t len)
{
uint32_t bits;
/* GE2D wants 16 byte aligned address for operation buffer. */
if (((uintptr_t)buffer & 0xf) != 0)
{
set_errno(EINVAL);
return 0;
}
/* Get exclusive access */
ge2d_semtake(&g_lock);
/* Set operation buffer and start processing.
* Descriptor start address bit 0 is select to bus, always 1 (memory),
* can't set except 1 in this chip.
*/
putreg32((uint32_t)(uintptr_t)buffer | 1, GE2D_ADDRESS_DESCRIPTOR_START);
putreg32(GE2D_EXEC, GE2D_CMD_DESCRIPTOR);
/* Enable error and completion interrupts. */
bits = GE2D_INTR_WR_ERR | GE2D_INTR_RD_ERR | GE2D_INTR_NDE | GE2D_INTR_DSD |
GE2D_INTR_NDF;
putreg32(bits, GE2D_INTR_ENABLE);
/* Wait for interrupts for processing done. */
ge2d_semtake(&g_wait);
/* Disable interrupts */
putreg32(0, GE2D_INTR_ENABLE);
ge2d_semgive(&g_lock);
return len;
}
/****************************************************************************
* Name: ge2d_ioctl
****************************************************************************/
static int ge2d_ioctl(FAR struct file *filep, int cmd, unsigned long arg)
{
int ret = -ENOTTY;
/* TODO: Should be implement features:
*
* - stop execution
* - debug for raster operation
*/
switch (cmd)
{
default:
break;
}
return ret;
}
/****************************************************************************
* Name: ge2d_irqhandler
****************************************************************************/
static int ge2d_irqhandler(int irq, FAR void *context, FAR void *arg)
{
uint32_t stat;
/* Clear interrupts */
stat = getreg32(GE2D_INTR_STAT);
putreg32(stat, GE2D_INTR_STAT);
/* TODO: output status to syslog */
/* Release semaphore anyway */
ge2d_semgive(&g_wait);
return OK;
}
/****************************************************************************
* Name: cxd56_ge2dinitialize
****************************************************************************/
int cxd56_ge2dinitialize(FAR const char *devname)
{
int ret;
sem_init(&g_lock, 0, 1);
sem_init(&g_wait, 0, 0);
sem_setprotocol(&g_wait, SEM_PRIO_NONE);
ret = register_driver(devname, &g_ge2dfops, 0666, NULL);
if (ret != 0)
{
return ERROR;
}
cxd56_img_ge2d_clock_enable();
/* Disable interrupts */
putreg32(0, GE2D_INTR_ENABLE);
irq_attach(CXD56_IRQ_GE2D, ge2d_irqhandler, NULL);
up_enable_irq(CXD56_IRQ_GE2D);
return OK;
}
/****************************************************************************
* Name: cxd56_ge2duninitialize
****************************************************************************/
void cxd56_ge2duninitialize(FAR const char *devname)
{
up_disable_irq(CXD56_IRQ_GE2D);
irq_detach(CXD56_IRQ_GE2D);
cxd56_img_ge2d_clock_disable();
sem_destroy(&g_lock);
sem_destroy(&g_wait);
unregister_driver(devname);
}

View File

@ -0,0 +1,82 @@
/****************************************************************************
* arch/arm/src/cxd56xx/hardware/cxd56_ge2d.h
*
* Copyright 2018 Sony Semiconductor Solutions Corporation
*
* 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 of Sony Semiconductor Solutions Corporation 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 __SRC_CHIP_CXD56_GE2D_H
#define __SRC_CHIP_CXD56_GE2D_H
#include "hardware/cxd5602_memorymap.h"
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/
#define GE2D_INTR_ENABLE (CXD56_GE2D_BASE+0x00)
#define GE2D_INTR_STAT (CXD56_GE2D_BASE+0x04)
#define GE2D_ADDRESS_DESCRIPTOR_START (CXD56_GE2D_BASE+0x08)
#define GE2D_STATUS (CXD56_GE2D_BASE+0x0c) /* Read */
#define GE2D_CMD_DESCRIPTOR (CXD56_GE2D_BASE+0x0c) /* Write */
#define GE2D_STAT_NORMAL_DESCRIPTOR_ADDRESS (CXD56_GE2D_BASE+0x10)
#define GE2D_STAT_CURRENT_DESCRIPTOR_ADDRESS (CXD56_GE2D_BASE+0x14)
#define GE2D_AHB_BURST_MODE (CXD56_GE2D_BASE+0x40)
/* Interrupt bits */
#define GE2D_INTR_WR_ERR (1 << 17)
#define GE2D_INTR_RD_ERR (1 << 16)
#define GE2D_INTR_DSD (1 << 8)
#define GE2D_INTR_NDE (1 << 3)
#define GE2D_INTR_NDB (1 << 2)
#define GE2D_INTR_NDF (1 << 1)
#define GE2D_INTR_HPU (1 << 0)
#define GE2D_INTR_ALL (GE2D_INTR_WR_ERR | GE2D_INTR_RD_ERR | \
GE2D_INTR_DSD | GE2D_INTR_NDE | GE2D_INTR_NDB | \
GE2D_INTR_NDF | GE2D_INTR_HPU)
/* Status bits */
#define GE2D_STAT_ISER (1 << 24)
#define GE2D_STAT_NDCR (1 << 8)
#define GE2D_STAT_SREQ (1 << 2)
#define GE2D_STAT_PREQ (1 << 1)
#define GE2D_STAT_NREQ (1 << 0)
/* Running control */
#define GE2D_NOP 0
#define GE2D_EXEC 1
#define GE2D_STOP 3
#endif /* __SRC_CHIP_CXD56_GE2D_H */

View File

@ -36,4 +36,24 @@ endchoice # "TXS02612 port"
endif # SDCARD_TXS02612
if LCD
choice
prompt "LCD SPI connection"
default LCD_ON_EXTENSION_BOARD
config LCD_ON_EXTENSION_BOARD
bool "Extension board: SPI4"
select CXD56_SPI4
---help---
Display connected to extension board.
config LCD_ON_MAIN_BOARD
bool "Main board: SPI5"
select CXD56_SPI5
---help---
Display connected to main board.
endchoice
endif
endif

View File

@ -217,6 +217,28 @@ enum board_power_device
POWER_IMAGE_SENSOR = PMIC_GPO(4) | PMIC_GPO(5) | PMIC_GPO(7),
};
/* LCD Display clocking ****************************************************/
#define ILI9340_SPI_MAXFREQUENCY 40000000
/* Display device pin definitions ******************************************/
#if defined(CONFIG_LCD_ON_MAIN_BOARD) /* Display connected to main board. */
#define DISPLAY_RST PIN_I2S0_BCK
#define DISPLAY_DC PIN_I2S0_LRCK
#define DISPLAY_SPI 5
#else /* Display is connected through extension board. */
#define DISPLAY_RST PIN_SPI2_MISO
#define DISPLAY_DC PIN_PWM2
#define DISPLAY_SPI 4
#endif
/*
* Set signal id for notify USB device connection status and
* supply current value.

View File

@ -0,0 +1,90 @@
#
# This file is autogenerated: PLEASE DO NOT EDIT IT.
#
# You can use "make menuconfig" to make any modifications to the installed .config file.
# You can then do "make savedefconfig" to generate a new defconfig file that includes your
# modifications.
#
# CONFIG_CXD56_I2C0_SCUSEQ is not set
# CONFIG_MMCSD_HAVE_WRITEPROTECT is not set
# CONFIG_MMCSD_SPI is not set
# CONFIG_STANDARD_SERIAL is not set
CONFIG_ARCH="arm"
CONFIG_ARCH_BOARD="spresense"
CONFIG_ARCH_BOARD_SPRESENSE=y
CONFIG_ARCH_CHIP_CXD56XX=y
CONFIG_ARCH_STACKDUMP=y
CONFIG_ARMV7M_USEBASEPRI=y
CONFIG_BOARD_LOOPSPERMSEC=5434
CONFIG_BOOT_RUNFROMISRAM=y
CONFIG_BUILTIN=y
CONFIG_CDCACM=y
CONFIG_CDCACM_COMPOSITE=y
CONFIG_CLOCK_MONOTONIC=y
CONFIG_COMPOSITE_IAD=y
CONFIG_COMPOSITE_MSFT_OS_DESCRIPTORS=y
CONFIG_COMPOSITE_PRODUCTID=0x0bc2
CONFIG_COMPOSITE_VENDORID=0x054c
CONFIG_COMPOSITE_VENDORSTR="Sony"
CONFIG_CXD56_DMAC_SPI4_RX=y
CONFIG_CXD56_DMAC_SPI4_TX=y
CONFIG_CXD56_I2C0=y
CONFIG_CXD56_I2C=y
CONFIG_CXD56_SDIO=y
CONFIG_CXD56_SPI4=y
CONFIG_CXD56_SPI5=y
CONFIG_CXD56_SPI=y
CONFIG_CXD56_USBDEV=y
CONFIG_DEBUG_FULLOPT=y
CONFIG_DEBUG_SYMBOLS=y
CONFIG_FAT_LCNAMES=y
CONFIG_FAT_LFN=y
CONFIG_FAT_MAXFNAME=64
CONFIG_FS_FAT=y
CONFIG_FS_PROCFS=y
CONFIG_FS_PROCFS_REGISTER=y
CONFIG_HAVE_CXX=y
CONFIG_HAVE_CXXINITIALIZE=y
CONFIG_I2C=y
CONFIG_LCD=y
CONFIG_LCD_ILI9340=y
CONFIG_LCD_ILI9340_IFACE0=y
CONFIG_MAX_TASKS=16
CONFIG_MAX_WDOGPARMS=2
CONFIG_MMCSD=y
CONFIG_MMCSD_SDIO=y
CONFIG_NFILE_DESCRIPTORS=8
CONFIG_NFILE_STREAMS=8
CONFIG_NSH_ARCHINIT=y
CONFIG_NSH_BUILTIN_APPS=y
CONFIG_NSH_READLINE=y
CONFIG_PREALLOC_MQ_MSGS=4
CONFIG_PREALLOC_TIMERS=4
CONFIG_PREALLOC_WDOGS=16
CONFIG_RAM_SIZE=1572864
CONFIG_RAM_START=0x0d000000
CONFIG_READLINE_CMD_HISTORY=y
CONFIG_RR_INTERVAL=200
CONFIG_RTC=y
CONFIG_RTC_DRIVER=y
CONFIG_SCHED_WAITPID=y
CONFIG_SDCLONE_DISABLE=y
CONFIG_SPI=y
CONFIG_START_DAY=6
CONFIG_START_MONTH=12
CONFIG_START_YEAR=2011
CONFIG_SYSTEM_CDCACM=y
CONFIG_SYSTEM_CLE=y
CONFIG_SYSTEM_COMPOSITE=y
CONFIG_SYSTEM_NSH=y
CONFIG_SYSTEM_NSH_CXXINITIALIZE=y
CONFIG_SYSTEM_USBMSC=y
CONFIG_UART1_SERIAL_CONSOLE=y
CONFIG_USBDEV=y
CONFIG_USBDEV_COMPOSITE=y
CONFIG_USBDEV_DMA=y
CONFIG_USBDEV_DUALSPEED=y
CONFIG_USBMSC=y
CONFIG_USBMSC_COMPOSITE=y
CONFIG_USBMSC_REMOVABLE=y
CONFIG_USER_ENTRYPOINT="nsh_main"

View File

@ -124,4 +124,12 @@ ifeq ($(CONFIG_CXD56_I2C_DRIVER),y)
CSRCS += cxd56_i2cdev.c
endif
ifeq ($(CONFIG_LCD_LPM013M091A),y)
CSRCS += cxd56_lpm013m091a.c
endif
ifeq ($(CONFIG_LCD_ILI9340),y)
CSRCS += cxd56_ili9340.c
endif
include $(TOPDIR)/configs/Board.mk

View File

@ -0,0 +1,398 @@
/****************************************************************************
* configs/spresense/src/cxd56_ili9340.c
*
* Copyright 2018 Sony Semiconductor Solutions Corporation
*
* 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 of Sony Semiconductor Solutions Corporation 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 <sys/types.h>
#include <stdint.h>
#include <stdbool.h>
#include <string.h>
#include <errno.h>
#include <debug.h>
#include <nuttx/arch.h>
#include <nuttx/board.h>
#include <nuttx/spi/spi.h>
#include <nuttx/lcd/lcd.h>
#include <nuttx/lcd/ili9340.h>
#include <arch/board/board.h>
#include "cxd56_gpio.h"
#include "cxd56_spi.h"
#include "cxd56_pinconfig.h"
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/
/* Check if the following are defined in the board.h */
#ifndef DISPLAY_RST
# error "DISPLAY_RST must be defined in board.h !!"
#endif
#ifndef DISPLAY_DC
# error "DISPLAY_DC must be defined in board.h !!"
#endif
#ifndef DISPLAY_SPI
# error "DISPLAY_SPI must be defined in board.h !!"
#endif
/****************************************************************************
* Private Type Definition
****************************************************************************/
#ifndef ILI9340_SPI_MAXFREQUENCY
# define ILI9340_SPI_MAXFREQUENCY 20000000
#endif
/****************************************************************************
* Private Function Protototypes
****************************************************************************/
/****************************************************************************
* Private Data
****************************************************************************/
struct ili93404ws_lcd_s
{
struct ili9340_lcd_s dev;
struct spi_dev_s *spi;
};
static struct ili93404ws_lcd_s g_lcddev;
static struct lcd_dev_s *g_lcd = NULL;
/****************************************************************************
* Private Functions
****************************************************************************/
/****************************************************************************
* Name: cxd56_ili93404ws_select
*
* Description:
* Select the SPI, locking and re-configuring if necessary
*
* Input Parameters:
* spi - Reference to the public driver structure
*
* Returned Value:
*
****************************************************************************/
static void cxd56_ili93404ws_select(FAR struct ili9340_lcd_s *lcd)
{
FAR struct ili93404ws_lcd_s *priv = (FAR struct ili93404ws_lcd_s *)lcd;
SPI_LOCK(priv->spi, true);
SPI_SELECT(priv->spi, SPIDEV_DISPLAY(0), true);
}
/****************************************************************************
* Name: cxd56_ili93404ws_deselect
*
* Description:
* De-select the SPI
*
* Input Parameters:
* spi - Reference to the public driver structure
*
* Returned Value:
*
****************************************************************************/
static void cxd56_ili93404ws_deselect(FAR struct ili9340_lcd_s *lcd)
{
FAR struct ili93404ws_lcd_s *priv = (FAR struct ili93404ws_lcd_s *)lcd;
SPI_SELECT(priv->spi, SPIDEV_DISPLAY(0), false);
SPI_LOCK(priv->spi, false);
}
/****************************************************************************
* Name: cxd56_ili93404ws_backlight
*
* Description:
* Set the backlight level of the connected display.
*
* Input Parameters:
* spi - Reference to the public driver structure
* level - backligth level
*
* Returned Value:
* OK - On Success
*
****************************************************************************/
static int cxd56_ili93404ws_backlight(FAR struct ili9340_lcd_s *lcd,
int level)
{
if (level > 0)
{
lcd->sendcmd(lcd, ILI9340_WRITE_CTRL_DISPLAY);
lcd->sendparam(lcd, 0x24);
}
else
{
lcd->sendcmd(lcd, ILI9340_WRITE_CTRL_DISPLAY);
lcd->sendparam(lcd, 0x0);
}
return OK;
}
/****************************************************************************
* Name: cxd56_ili93404ws_sendcmd
*
* Description:
* Send a command to the lcd driver.
*
* Input Parameters:
* lcd - Reference to the ili9340_lcd_s driver structure
* cmd - command to send
*
* Returned Value:
* On success - OK
*
****************************************************************************/
static int cxd56_ili93404ws_sendcmd(FAR struct ili9340_lcd_s *lcd,
const uint8_t cmd)
{
FAR struct ili93404ws_lcd_s *priv = (FAR struct ili93404ws_lcd_s *)lcd;
lcdinfo("%02x\n", cmd);
SPI_SETBITS(priv->spi, 8);
/* FIXME: This function can be replaced with SPI_CMDDATA().
* This feature is needed to enable CONFIG_SPI_CMDDATA and board specific
* cmddata() function.
*/
cxd56_gpio_write(DISPLAY_DC, false); /* Indicate CMD */
(void) SPI_SEND(priv->spi, cmd);
cxd56_gpio_write(DISPLAY_DC, true); /* Indicate DATA */
return OK;
}
/****************************************************************************
* Name: cxd56_ili93404ws_sendparam
*
* Description:
* Send a parameter to the lcd driver.
*
* Input Parameters:
* lcd - Reference to the ili9340_lcd_s driver structure
* param - parameter to send
*
* Returned Value:
* OK - On Success
*
****************************************************************************/
static int cxd56_ili93404ws_sendparam(FAR struct ili9340_lcd_s *lcd,
const uint8_t param)
{
FAR struct ili93404ws_lcd_s *priv = (FAR struct ili93404ws_lcd_s *)lcd;
cxd56_gpio_write(DISPLAY_DC, true); /* Indicate DATA */
(void) SPI_SEND(priv->spi, param);
return OK;
}
/****************************************************************************
* Name: cxd56_ili93404ws_sendgram
*
* Description:
* Send a number of pixel words to the lcd driver gram.
*
* Input Parameters:
* lcd - Reference to the ili9340_lcd_s driver structure
* wd - Reference to the words to send
* nwords - number of words to send
*
* Returned Value:
* OK - On Success
*
****************************************************************************/
static int cxd56_ili93404ws_sendgram(FAR struct ili9340_lcd_s *lcd,
const uint16_t *wd, uint32_t nwords)
{
FAR struct ili93404ws_lcd_s *priv = (FAR struct ili93404ws_lcd_s *)lcd;
lcdinfo("lcd:%p, wd=%p, nwords=%d\n", lcd, wd, nwords);
SPI_SETBITS(priv->spi, 16);
(void) SPI_SNDBLOCK(priv->spi, wd, nwords);
return OK;
}
/****************************************************************************
* Name: cxd56_ili93404ws_recvparam
*
* Description:
* Receive a parameter from the lcd driver.
*
* Input Parameters:
* lcd - Reference to the ili9340_lcd_s driver structure
* param - Reference to where parameter receive
*
* Returned Value:
* OK - On Success
*
****************************************************************************/
static int cxd56_ili93404ws_recvparam(FAR struct ili9340_lcd_s *lcd,
uint8_t *param)
{
FAR struct ili93404ws_lcd_s *priv = (FAR struct ili93404ws_lcd_s *)lcd;
cxd56_gpio_write(DISPLAY_DC, true); /* Indicate DATA */
*param = (uint8_t)(SPI_SEND(priv->spi, param) & 0xff);
return OK;
}
/****************************************************************************
* Name: cxd56_ili93404ws_recvgram
*
* Description:
* Receive pixel words from the lcd driver gram.
*
* Input Parameters:
* lcd - Reference to the public driver structure
* wd - Reference to where the pixel words receive
* nwords - number of pixel words to receive
*
* Returned Value:
* OK - On Success
*
****************************************************************************/
static int cxd56_ili93404ws_recvgram(FAR struct ili9340_lcd_s *lcd,
uint16_t *wd, uint32_t nwords)
{
lcdinfo("wd=%p, nwords=%d\n", wd, nwords);
return OK;
};
/****************************************************************************
* Public Functions
****************************************************************************/
/****************************************************************************
* Name: board_lcd_initialize
*
* Description:
* Initialize the LCD video hardware. The initial state of the LCD is
* fully initialized, display memory cleared, and the LCD ready to use,
* but with the power setting at 0 (full off).
*
****************************************************************************/
int board_lcd_initialize(void)
{
FAR struct ili93404ws_lcd_s *priv = &g_lcddev;
FAR struct spi_dev_s *spi;
lcdinfo("Initializing lcd\n");
if (g_lcd == NULL)
{
spi = cxd56_spibus_initialize(DISPLAY_SPI);
if (!spi)
{
lcderr("ERROR: Failed to initialize spi bus.\n");
return -ENODEV;
}
priv->spi = spi;
/* Reset ILI9340 */
up_mdelay(10);
cxd56_gpio_write(DISPLAY_RST, false);
up_mdelay(10);
cxd56_gpio_write(DISPLAY_RST, true);
up_mdelay(50);
/* Configure SPI */
SPI_SETMODE(priv->spi, SPIDEV_MODE3);
SPI_SETBITS(priv->spi, 8);
(void)SPI_HWFEATURES(priv->spi, 0);
(void)SPI_SETFREQUENCY(priv->spi, ILI9340_SPI_MAXFREQUENCY);
/* Initialize ILI9340 driver with necessary methods */
priv->dev.select = cxd56_ili93404ws_select;
priv->dev.deselect = cxd56_ili93404ws_deselect;
priv->dev.sendcmd = cxd56_ili93404ws_sendcmd;
priv->dev.sendparam = cxd56_ili93404ws_sendparam;
priv->dev.recvparam = cxd56_ili93404ws_recvparam;
priv->dev.sendgram = cxd56_ili93404ws_sendgram;
priv->dev.recvgram = cxd56_ili93404ws_recvgram;
priv->dev.backlight = cxd56_ili93404ws_backlight;
g_lcd = ili9340_initialize(&priv->dev, 0);
}
return OK;
}
/****************************************************************************
* Name: board_lcd_getdev
*
* Description:
* Return a a reference to the LCD object for the specified LCD. This
* allows support for multiple LCD devices.
*
****************************************************************************/
FAR struct lcd_dev_s *board_lcd_getdev(int lcddev)
{
if (lcddev == 0)
{
return g_lcd;
}
return NULL;
}

View File

@ -0,0 +1,398 @@
/****************************************************************************
* configs/spresense/src/cxd56_lpm013m091a.c
*
* Copyright 2018 Sony Semiconductor Solutions Corporation
*
* 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 of Sony Semiconductor Solutions Corporation 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 <sys/types.h>
#include <stdint.h>
#include <stdbool.h>
#include <string.h>
#include <errno.h>
#include <debug.h>
#include <nuttx/arch.h>
#include <nuttx/board.h>
#include <nuttx/spi/spi.h>
#include <nuttx/lcd/lcd.h>
#include <nuttx/lcd/lpm013m091a.h>
#include <arch/board/board.h>
#include "cxd56_gpio.h"
#include "cxd56_spi.h"
#include "cxd56_pinconfig.h"
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/
/* Check if the following are defined in the board.h */
#ifndef DISPLAY_RST
# error "DISPLAY_RST must be defined in board.h !!"
#endif
#ifndef DISPLAY_DC
# error "DISPLAY_DC must be defined in board.h !!"
#endif
#ifndef DISPLAY_SPI
# error "DISPLAY_SPI must be defined in board.h !!"
#endif
/****************************************************************************
* Private Type Definition
****************************************************************************/
#ifndef LPM013M091A_SPI_MAXFREQUENCY
# define LPM013M091A_SPI_MAXFREQUENCY 20000000
#endif
/****************************************************************************
* Private Function Protototypes
****************************************************************************/
/****************************************************************************
* Private Data
****************************************************************************/
struct lpm013m091a_lcd_s
{
struct lpm013m091a_lcd_s dev;
struct spi_dev_s *spi;
};
static struct lpm013m091a_lcd_s g_lcddev;
static struct lcd_dev_s *g_lcd = NULL;
/****************************************************************************
* Private Functions
****************************************************************************/
/****************************************************************************
* Name: cxd56_lpm013m091a4ws_select
*
* Description:
* Select the SPI, locking and re-configuring if necessary
*
* Input Parameters:
* spi - Reference to the public driver structure
*
* Returned Value:
*
****************************************************************************/
static void cxd56_lpm013m091a4ws_select(FAR struct lpm013m091a_lcd_s *lcd)
{
FAR struct lpm013m091a_lcd_s *priv = (FAR struct lpm013m091a_lcd_s *)lcd;
SPI_LOCK(priv->spi, true);
SPI_SELECT(priv->spi, SPIDEV_DISPLAY(0), true);
}
/****************************************************************************
* Name: cxd56_lpm013m091a4ws_deselect
*
* Description:
* De-select the SPI
*
* Input Parameters:
* spi - Reference to the public driver structure
*
* Returned Value:
*
****************************************************************************/
static void cxd56_lpm013m091a4ws_deselect(FAR struct lpm013m091a_lcd_s *lcd)
{
FAR struct lpm013m091a_lcd_s *priv = (FAR struct lpm013m091a_lcd_s *)lcd;
SPI_SELECT(priv->spi, SPIDEV_DISPLAY(0), false);
SPI_LOCK(priv->spi, false);
}
/****************************************************************************
* Name: cxd56_lpm013m091a4ws_backlight
*
* Description:
* Set the backlight level of the connected display.
*
* Input Parameters:
* spi - Reference to the public driver structure
* level - backligth level
*
* Returned Value:
* OK - On Success
*
****************************************************************************/
static int cxd56_lpm013m091a4ws_backlight(FAR struct lpm013m091a_lcd_s *lcd,
int level)
{
if (level > 0)
{
lcd->sendcmd(lcd, 0x53);
lcd->sendparam(lcd, 0x24);
}
else
{
lcd->sendcmd(lcd, 0x53);
lcd->sendparam(lcd, 0x0);
}
return OK;
}
/****************************************************************************
* Name: cxd56_lpm013m091a4ws_sendcmd
*
* Description:
* Send a command to the lcd driver.
*
* Input Parameters:
* lcd - Reference to the lpm013m091a_lcd_s driver structure
* cmd - command to send
*
* Returned Value:
* On success - OK
*
****************************************************************************/
static int cxd56_lpm013m091a4ws_sendcmd(FAR struct lpm013m091a_lcd_s *lcd,
const uint8_t cmd)
{
FAR struct lpm013m091a_lcd_s *priv = (FAR struct lpm013m091a_lcd_s *)lcd;
lcdinfo("%02x\n", cmd);
SPI_SETBITS(priv->spi, 8);
/* FIXME: This function can be replaced with SPI_CMDDATA().
* This feature is needed to enable CONFIG_SPI_CMDDATA and board specific
* cmddata() function.
*/
cxd56_gpio_write(DISPLAY_DC, false); /* Indicate CMD */
(void) SPI_SEND(priv->spi, cmd);
cxd56_gpio_write(DISPLAY_DC, true); /* Indicate DATA */
return OK;
}
/****************************************************************************
* Name: cxd56_lpm013m091a4ws_sendparam
*
* Description:
* Send a parameter to the lcd driver.
*
* Input Parameters:
* lcd - Reference to the lpm013m091a_lcd_s driver structure
* param - parameter to send
*
* Returned Value:
* OK - On Success
*
****************************************************************************/
static int cxd56_lpm013m091a4ws_sendparam(FAR struct lpm013m091a_lcd_s *lcd,
const uint8_t param)
{
FAR struct lpm013m091a_lcd_s *priv = (FAR struct lpm013m091a_lcd_s *)lcd;
cxd56_gpio_write(DISPLAY_DC, true); /* Indicate DATA */
(void) SPI_SEND(priv->spi, param);
return OK;
}
/****************************************************************************
* Name: cxd56_lpm013m091a4ws_sendgram
*
* Description:
* Send a number of pixel words to the lcd driver gram.
*
* Input Parameters:
* lcd - Reference to the lpm013m091a_lcd_s driver structure
* wd - Reference to the words to send
* nwords - number of words to send
*
* Returned Value:
* OK - On Success
*
****************************************************************************/
static int cxd56_lpm013m091a4ws_sendgram(FAR struct lpm013m091a_lcd_s *lcd,
const uint16_t *wd, uint32_t nwords)
{
FAR struct lpm013m091a_lcd_s *priv = (FAR struct lpm013m091a_lcd_s *)lcd;
lcdinfo("lcd:%p, wd=%p, nwords=%d\n", lcd, wd, nwords);
SPI_SETBITS(priv->spi, 16);
(void) SPI_SNDBLOCK(priv->spi, wd, nwords);
return OK;
}
/****************************************************************************
* Name: cxd56_lpm013m091a4ws_recvparam
*
* Description:
* Receive a parameter from the lcd driver.
*
* Input Parameters:
* lcd - Reference to the lpm013m091a_lcd_s driver structure
* param - Reference to where parameter receive
*
* Returned Value:
* OK - On Success
*
****************************************************************************/
static int cxd56_lpm013m091a4ws_recvparam(FAR struct lpm013m091a_lcd_s *lcd,
uint8_t *param)
{
FAR struct lpm013m091a_lcd_s *priv = (FAR struct lpm013m091a_lcd_s *)lcd;
cxd56_gpio_write(DISPLAY_DC, true); /* Indicate DATA */
*param = (uint8_t)(SPI_SEND(priv->spi, param) & 0xff);
return OK;
}
/****************************************************************************
* Name: cxd56_lpm013m091a4ws_recvgram
*
* Description:
* Receive pixel words from the lcd driver gram.
*
* Input Parameters:
* lcd - Reference to the public driver structure
* wd - Reference to where the pixel words receive
* nwords - number of pixel words to receive
*
* Returned Value:
* OK - On Success
*
****************************************************************************/
static int cxd56_lpm013m091a4ws_recvgram(FAR struct lpm013m091a_lcd_s *lcd,
uint16_t *wd, uint32_t nwords)
{
lcdinfo("wd=%p, nwords=%d\n", wd, nwords);
return OK;
};
/****************************************************************************
* Public Functions
****************************************************************************/
/****************************************************************************
* Name: board_lcd_initialize
*
* Description:
* Initialize the LCD video hardware. The initial state of the LCD is
* fully initialized, display memory cleared, and the LCD ready to use,
* but with the power setting at 0 (full off).
*
****************************************************************************/
int board_lcd_initialize(void)
{
FAR struct lpm013m091a_lcd_s *priv = &g_lcddev;
FAR struct spi_dev_s *spi;
lcdinfo("Initializing lcd\n");
if (g_lcd == NULL)
{
spi = cxd56_spibus_initialize(DISPLAY_SPI);
if (!spi)
{
lcderr("ERROR: Failed to initialize spi bus.\n");
return -ENODEV;
}
priv->spi = spi;
/* Reset LPM013M091A */
up_mdelay(10);
cxd56_gpio_write(DISPLAY_RST, false);
up_mdelay(10);
cxd56_gpio_write(DISPLAY_RST, true);
up_mdelay(50);
/* Configure SPI */
SPI_SETMODE(priv->spi, SPIDEV_MODE3);
SPI_SETBITS(priv->spi, 8);
(void)SPI_HWFEATURES(priv->spi, 0);
(void)SPI_SETFREQUENCY(priv->spi, LPM013M091A_SPI_MAXFREQUENCY);
/* Initialize LPM013M091A driver with necessary methods */
priv->dev.select = cxd56_lpm013m091a4ws_select;
priv->dev.deselect = cxd56_lpm013m091a4ws_deselect;
priv->dev.sendcmd = cxd56_lpm013m091a4ws_sendcmd;
priv->dev.sendparam = cxd56_lpm013m091a4ws_sendparam;
priv->dev.recvparam = cxd56_lpm013m091a4ws_recvparam;
priv->dev.sendgram = cxd56_lpm013m091a4ws_sendgram;
priv->dev.recvgram = cxd56_lpm013m091a4ws_recvgram;
priv->dev.backlight = cxd56_lpm013m091a4ws_backlight;
g_lcd = lpm013m091a_initialize(&priv->dev, 0);
}
return OK;
}
/****************************************************************************
* Name: board_lcd_getdev
*
* Description:
* Return a a reference to the LCD object for the specified LCD. This
* allows support for multiple LCD devices.
*
****************************************************************************/
FAR struct lcd_dev_s *board_lcd_getdev(int lcddev)
{
if (lcddev == 0)
{
return g_lcd;
}
return NULL;
}

View File

@ -890,6 +890,132 @@ config LCD_RLANDSCAPE
endchoice
config LCD_LPM013M091A
bool "JDI LPM013M091A LCD Driver"
default n
---help---
JDI LPM013M091A LCD Driver.
This driver doesn't support reading data.
Recommended to use DMA to transfer data or displayed image would be
broken.
config LCD_ILI9340
bool "ILI9340 LCD Single Chip Driver"
default n
---help---
LCD Single Chip Driver, ILI9340, ILI Technology Corp.
Required LCD driver settings:
LCD_MAXCONTRAST should be 255, but any value >0 and <=255 will be accepted.
LCD_MAXPOWER should be 1: 0=off, 1=on
config LCD_ILI9340_NINTERFACES
int "Number of supported display driver"
range 1 2
default 1
depends on LCD_ILI9340
---help---
Define the number of supported displays driven by a ili9340 LCD Single
Chip Driver.
config LCD_ILI9340_IFACE0
bool "(1) LCD Display"
depends on LCD_ILI9340_NINTERFACES = 1 || LCD_ILI9340_NINTERFACES = 2
---help---
Configure first LCD Display.
if LCD_ILI9340_IFACE0
choice
prompt "LCD Orientation"
default LCD_ILI9340_IFACE0_LANDSCAPE
---help---
Configure display orientation.
config LCD_ILI9340_IFACE0_LANDSCAPE
bool "Landscape orientation"
---help---
Define for "landscape" orientation support.
config LCD_ILI9340_IFACE0_PORTRAIT
bool "Portrait orientation"
---help---
Define for "portrait" orientation support.
config LCD_ILI9340_IFACE0_RLANDSCAPE
bool "Reverse landscape orientation"
---help---
Define for "reverse landscape" orientation support.
config LCD_ILI9340_IFACE0_RPORTRAIT
bool "Reverse portrait display"
---help---
Define for "reverse portrait" orientation support.
endchoice
choice
prompt "Color format"
default LCD_ILI9340_IFACE0_RGB565
---help---
LCD color format.
config LCD_ILI9340_IFACE0_RGB565
bool "16 bpp RGB565 color format"
---help---
16 bpp RGB565 color format
endchoice
endif
config LCD_ILI9340_IFACE1
bool "(2) LCD Display"
depends on LCD_ILI9340_NINTERFACES = 2
---help---
Configure second LCD Display.
if LCD_ILI9340_IFACE1
choice
prompt "LCD Orientation"
default LCD_ILI9340_IFACE1_LANDSCAPE
---help---
Configure display orientation.
config LCD_ILI9340_IFACE1_LANDSCAPE
bool "Landscape orientation"
---help---
Define for "landscape" orientation support.
config LCD_ILI9340_IFACE1_PORTRAIT
bool "Portrait orientation"
---help---
Define for "portrait" orientation support.
config LCD_ILI9340_IFACE1_RLANDSCAPE
bool "Reverse landscape orientation"
---help---
Define for "reverse landscape" orientation support.
config LCD_ILI9340_IFACE1_RPORTRAIT
bool "Reverse portrait display"
---help---
Define for "reverse portrait" orientation support.
endchoice
choice
prompt "Color format"
default LCD_ILI9340_IFACE1_RGB565
---help---
LCD color format.
config LCD_ILI9340_IFACE1_RGB565
bool "16 bpp RGB565 color format"
---help---
16 bpp RGB565 color format
endchoice
endif
config LCD_ILI9341
bool "ILI9341 LCD Single Chip Driver"
default n

View File

@ -52,6 +52,10 @@ else ifeq ($(CONFIG_LCD_FT80X_I2C),y)
endif
endif
ifeq ($(CONFIG_LCD_LPM013M091A),y)
CSRCS += lpm013m091a.c
endif
ifeq ($(CONFIG_LCD_P14201),y)
CSRCS += p14201.c
endif
@ -112,6 +116,10 @@ ifeq ($(CONFIG_LCD_SHARP_MEMLCD),y)
CSRCS += memlcd.c
endif
ifeq ($(CONFIG_LCD_ILI9340),y)
CSRCS += ili9340.c
endif
ifeq ($(CONFIG_LCD_ILI9341),y)
CSRCS += ili9341.c
endif

1240
drivers/lcd/ili9340.c Normal file

File diff suppressed because it is too large Load Diff

611
drivers/lcd/lpm013m091a.c Normal file
View File

@ -0,0 +1,611 @@
/****************************************************************************
* drivers/lcd/lpm013m091a.c
*
* Driver for LPM013M091A LCD based on ili9341.c.
*
* Copyright (C) 2014 Marco Krahl. All rights reserved.
* Author: Marco Krahl <ocram.lhark@gmail.com>
*
* Copyright 2018 Sony Semiconductor Solutions Corporation
*
* 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 <sys/types.h>
#include <stdint.h>
#include <stdbool.h>
#include <string.h>
#include <errno.h>
#include <debug.h>
#include <nuttx/arch.h>
#include <nuttx/lcd/lcd.h>
#include <nuttx/lcd/lpm013m091a.h>
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/
/* Display resolution */
#define LPM013M091A_XRES 320
#define LPM013M091A_YRES 300
/* TODO: Stride should be configurable by LCD orientation */
#define LPM013M091A_STRIDE LPM013M091A_XRES
/* Dolor depth and format */
#define LPM013M091A_BPP 16
#define LPM013M091A_COLORFMT FB_FMT_RGB16_565
/****************************************************************************
* Private types
****************************************************************************/
struct lpm013m091a_dev_s
{
/* Publically visible device structure */
struct lcd_dev_s dev;
/* Private lcd-specific information follows */
struct lpm013m091a_lcd_s* lcd;
uint8_t power; /* Current power setting */
};
/****************************************************************************
* Private Function Protototypes
****************************************************************************/
static void lpm013m091a_selectarea(FAR struct lpm013m091a_lcd_s *lcd,
uint16_t x0, int16_t y0,
uint16_t x1, int16_t y1);
static int lpm013m091a_hwinitialize(FAR struct lpm013m091a_dev_s *dev);
/* lcd data transfer methods */
static int lpm013m091a_putrun(fb_coord_t row, fb_coord_t col,
FAR const uint8_t *buffer, size_t npixels);
#ifndef CONFIG_LCD_NOGETRUN
static int lpm013m091a_getrun(fb_coord_t row, fb_coord_t col,
FAR uint8_t *buffer,
size_t npixels);
#endif
/* lcd configuration */
static int lpm013m091a_getvideoinfo(FAR struct lcd_dev_s *dev,
FAR struct fb_videoinfo_s *vinfo);
static int lpm013m091a_getplaneinfo(FAR struct lcd_dev_s *dev,
unsigned int planeno,
FAR struct lcd_planeinfo_s *pinfo);
/* lcd specific controls */
static int lpm013m091a_getpower(FAR struct lcd_dev_s *dev);
static int lpm013m091a_setpower(FAR struct lcd_dev_s *dev, int power);
static int lpm013m091a_getcontrast(FAR struct lcd_dev_s *dev);
static int lpm013m091a_setcontrast(FAR struct lcd_dev_s *dev,
unsigned int contrast);
/****************************************************************************
* Private Data
****************************************************************************/
static uint16_t g_runbuffer[LPM013M091A_STRIDE];
/* This structure describes the overall lcd video controller */
static const struct fb_videoinfo_s g_videoinfo =
{
.fmt = LPM013M091A_COLORFMT, /* Color format: rgb16-565: rrrr rggg gggb bbbb */
.xres = LPM013M091A_XRES, /* Horizontal resolution in pixel columns */
.yres = LPM013M091A_YRES, /* Vertical resolution in pixel rows */
.nplanes = 1, /* Number of color planes supported */
};
/* This is the standard, nuttx plane information object */
static const struct lcd_planeinfo_s g_planeinfo =
{
.putrun = lpm013m091a_putrun, /* Put a run into lcd memory */
#ifndef CONFIG_LCD_NOGETRUN
.getrun = lpm013m091a_getrun, /* Get a run from lcd memory */
#endif
.buffer = (uint8_t *) g_runbuffer, /* Run scratch buffer */
.bpp = LPM013M091A_BPP, /* Bits-per-pixel */
};
static struct lpm013m091a_dev_s g_lpm013m091a_dev =
{
.dev =
{
/* lcd configuration */
.getvideoinfo = lpm013m091a_getvideoinfo,
.getplaneinfo = lpm013m091a_getplaneinfo,
/* lcd specific controls */
.getpower = lpm013m091a_getpower,
.setpower = lpm013m091a_setpower,
.getcontrast = lpm013m091a_getcontrast,
.setcontrast = lpm013m091a_setcontrast,
},
.lcd = 0,
};
/****************************************************************************
* Name: lpm013m091a_selectarea
*
* Description:
* Select the active area for displaying pixel
*
* Parameter:
* lcd - Reference to private driver structure
* x0 - Start x position
* y0 - Start y position
* x1 - End x position
* y1 - End y position
*
****************************************************************************/
static void lpm013m091a_selectarea(FAR struct lpm013m091a_lcd_s *lcd,
uint16_t x0, int16_t y0,
uint16_t x1, int16_t y1)
{
lcd->sendcmd(lcd, LPM013M091A_CASET);
lcd->sendparam(lcd, x0 >> 8);
lcd->sendparam(lcd, x0 & 0xff);
lcd->sendparam(lcd, x1 >> 8);
lcd->sendparam(lcd, x1 & 0xff);
lcd->sendcmd(lcd, LPM013M091A_PASET);
lcd->sendparam(lcd, y0 >> 8);
lcd->sendparam(lcd, y0 & 0xff);
lcd->sendparam(lcd, y1 >> 8);
lcd->sendparam(lcd, y1 & 0xff);
}
/****************************************************************************
* Name: lpm013m091a_hwinitialize
*
* Description:
* Initialize and configure the LPM013M091A LCD driver hardware.
*
* Parameter:
* dev - A reference to the driver specific structure
*
* Returned Value:
*
* On success - OK
* On error - EINVAL
*
****************************************************************************/
static int lpm013m091a_hwinitialize(FAR struct lpm013m091a_dev_s *dev)
{
FAR struct lpm013m091a_lcd_s *lcd = dev->lcd;
/* soft reset */
lcd->sendcmd(lcd, LPM013M091A_SWRESET);
up_mdelay(10);
/* Analog mode */
lcd->sendcmd(lcd, 0xb3);
lcd->sendparam(lcd, 0x02);
/* Set Display Mode */
lcd->sendcmd(lcd, 0xbb);
lcd->sendparam(lcd, 0x10);
/* SPI GRAM access enable */
lcd->sendcmd(lcd, 0xf3);
lcd->sendparam(lcd, 0x02);
/* Bright Level Max */
lcd->sendcmd(lcd, 0x51);
lcd->sendparam(lcd, 0xff);
/* Backlight ON */
lcd->sendcmd(lcd, 0x53);
lcd->sendparam(lcd, 0x24);
/* Frame rate 60Hz */
lcd->sendcmd(lcd, 0xff);
lcd->sendparam(lcd, 0x24);
lcd->sendcmd(lcd, 0xd8);
lcd->sendparam(lcd, 0x41);
lcd->sendcmd(lcd, 0xd9);
lcd->sendparam(lcd, 0x1e);
lcd->sendcmd(lcd, 0xff);
lcd->sendparam(lcd, 0x10);
/* Set the color format (18bit:0x06, 16bit:0x05) */
lcd->sendcmd(lcd, LPM013M091A_PIXFMT);
lcd->sendparam(lcd, 0x05);
/* Sleep out */
lcd->sendcmd(lcd, LPM013M091A_SLPOUT);
up_mdelay(10);
/* Display on */
lcd->sendcmd(lcd, LPM013M091A_DISPON);
up_mdelay(120);
return OK;
}
/****************************************************************************
* Name: lpm013m091a_putrun
*
* Description:
* Write a partial raster line to the LCD.
*
* Parameters:
* devno - Number of lcd device
* row - Starting row to write to (range: 0 <= row < yres)
* col - Starting column to write to (range: 0 <= col <= xres-npixels)
* buffer - The buffer containing the run to be writen to the LCD
* npixels - The number of pixels to write to the
* (range: 0 < npixels <= xres-col)
*
* Returned Value:
*
* On success - OK
* On error - -EINVAL
*
****************************************************************************/
static int lpm013m091a_putrun(fb_coord_t row, fb_coord_t col,
FAR const uint8_t *buffer, size_t npixels)
{
FAR struct lpm013m091a_dev_s *dev = (FAR struct lpm013m091a_dev_s *)
&g_lpm013m091a_dev;
FAR struct lpm013m091a_lcd_s *lcd = dev->lcd;
FAR const uint16_t *src = (FAR const uint16_t *)buffer;
DEBUGASSERT(buffer && ((uintptr_t)buffer & 1) == 0);
/* Check if position outside of area */
if (col + npixels > LPM013M091A_XRES || row > LPM013M091A_YRES)
{
return -EINVAL;
}
/* Select lcd driver */
lcd->select(lcd);
/* Select column and area similar to the partial raster line */
lpm013m091a_selectarea(lcd, col, row, col + npixels - 1, row);
/* Send memory write cmd */
lcd->sendcmd(lcd, LPM013M091A_RAMWR);
/* Send pixel to gram */
lcd->sendgram(lcd, src, npixels);
/* Deselect the lcd driver */
lcd->deselect(lcd);
return OK;
}
/****************************************************************************
* Name: lpm013m091a_getrun
*
* Description:
* Read a partial raster line from the LCD.
*
* Parameter:
* devno - Number of the lcd device
* row - Starting row to read from (range: 0 <= row < yres)
* col - Starting column to read read (range: 0 <= col <= xres-npixels)
* buffer - The buffer in which to return the run read from the LCD
* npixels - The number of pixels to read from the LCD
* (range: 0 < npixels <= xres-col)
*
* Returned Value:
*
* On success - OK
* On error - -EINVAL
*
****************************************************************************/
#ifndef CONFIG_LCD_NOGETRUN
int lpm013m091a_getrun(fb_coord_t row, fb_coord_t col, FAR uint8_t * buffer,
size_t npixels)
{
lcderr("getrun is not supported for now.\n");
return -ENOSYS;
}
#endif
/****************************************************************************
* Name: lpm013m091a_getvideoinfo
*
* Description:
* Get information about the LCD video controller configuration.
*
* Parameter:
* dev - A reference to the driver specific structure
* vinfo - A reference to the videoinfo structure
*
* Returned Value:
*
* On success - OK
* On error - -EINVAL
*
****************************************************************************/
static int lpm013m091a_getvideoinfo(FAR struct lcd_dev_s *dev,
FAR struct fb_videoinfo_s *vinfo)
{
if (dev && vinfo)
{
memcpy(vinfo, &g_videoinfo, sizeof(struct fb_videoinfo_s));
lcdinfo("fmt: %d xres: %d yres: %d nplanes: %d\n",
vinfo->fmt, vinfo->xres, vinfo->yres, vinfo->nplanes);
return OK;
}
return -EINVAL;
}
/****************************************************************************
* Name: lpm013m091a_getplaneinfo
*
* Description:
* Get information about the configuration of each LCD color plane.
*
* Parameter:
* dev - A reference to the driver specific structure
* planeno - The plane number
* pinfo - A reference to the planeinfo structure
*
* Returned Value:
*
* On success - OK
* On error - -EINVAL
*
****************************************************************************/
static int lpm013m091a_getplaneinfo(FAR struct lcd_dev_s *dev,
unsigned int planeno,
FAR struct lcd_planeinfo_s *pinfo)
{
if (dev && pinfo && planeno == 0)
{
memcpy(pinfo, &g_planeinfo, sizeof(struct lcd_planeinfo_s));
lcdinfo("planeno: %d bpp: %d\n", planeno, pinfo->bpp);
return OK;
}
return -EINVAL;
}
/****************************************************************************
* Name: lpm013m091a_getpower
*
* Description:
* Get the LCD panel power status
* 0: full off - CONFIG_LCD_MAXPOWER: full on.
* On backlit LCDs, this setting may correspond to the backlight setting.
*
* Parameter:
* dev - A reference to the driver specific structure
*
* Returned Value:
*
* On success - OK
* On error - -EINVAL
*
****************************************************************************/
static int lpm013m091a_getpower(FAR struct lcd_dev_s *dev)
{
FAR struct lpm013m091a_dev_s *priv = (FAR struct lpm013m091a_dev_s *)dev;
lcdinfo("%d\n", priv->power);
return priv->power;
}
/****************************************************************************
* Name: lpm013m091a_setpower
*
* Description:
* Enable/disable LCD panel power
* (0: full off - CONFIG_LCD_MAXPOWER: full on).
* On backlight LCDs, this setting may correspond to the backlight setting.
*
* Parameter:
* dev - A reference to the driver specific structure
* power - Value of the power
*
* Returned Value:
*
* On success - OK
* On error - -EINVAL
*
****************************************************************************/
static int lpm013m091a_setpower(FAR struct lcd_dev_s *dev, int power)
{
FAR struct lpm013m091a_dev_s *priv = (FAR struct lpm013m091a_dev_s *)dev;
FAR struct lpm013m091a_lcd_s *lcd = priv->lcd;
if (!dev)
{
return -EINVAL;
}
lcdinfo("%d\n", power);
lcd->select(lcd);
if (power > 0)
{
lcd->backlight(lcd, power);
lcd->sendcmd(lcd, LPM013M091A_DISPON);
up_mdelay(120);
}
else
{
lcd->sendcmd(lcd, LPM013M091A_DISPOFF);
}
lcd->deselect(lcd);
priv->power = power;
return OK;
}
/****************************************************************************
* Name: ili9340_getcontrast
*
* Description:
* Get the current contrast setting (0-CONFIG_LCD_MAXCONTRAST).
*
* Parameter:
* dev - A reference to the lcd driver structure
*
* Returned Value:
*
* On success - current contrast value
* On error - -ENOSYS, not supported by the ili9340.
*
****************************************************************************/
static int lpm013m091a_getcontrast(FAR struct lcd_dev_s *dev)
{
lcdinfo("Not implemented\n");
return -ENOSYS;
}
/****************************************************************************
* Name: ili9340_setcontrast
*
* Description:
* Set LCD panel contrast (0-CONFIG_LCD_MAXCONTRAST).
*
* Parameter:
* dev - A reference to the lcd driver structure
*
* Returned Value:
*
* On success - OK
* On error - -ENOSYS, not supported by the ili9340.
*
****************************************************************************/
static int lpm013m091a_setcontrast(FAR struct lcd_dev_s *dev,
unsigned int contrast)
{
lcdinfo("Not implemented\n");
return -ENOSYS;
}
/****************************************************************************
* Public Functions
****************************************************************************/
/****************************************************************************
* Initialize LCD
****************************************************************************/
FAR struct lcd_dev_s* lpm013m091a_initialize(FAR struct lpm013m091a_lcd_s *lcd,
int devno)
{
FAR struct lpm013m091a_dev_s *priv = &g_lpm013m091a_dev;
if (lcd && devno == 0)
{
if (!priv->lcd)
{
FAR struct lcd_dev_s *dev = &priv->dev;
int ret;
/* Initialize internal structure */
dev->getvideoinfo = lpm013m091a_getvideoinfo;
dev->getplaneinfo = lpm013m091a_getplaneinfo;
dev->getpower = lpm013m091a_getpower;
dev->setpower = lpm013m091a_setpower;
dev->getcontrast = lpm013m091a_getcontrast;
dev->setcontrast = lpm013m091a_setcontrast;
priv->lcd = lcd;
/* Initialze the LCD driver */
ret = lpm013m091a_hwinitialize(priv);
if (ret == OK)
{
return &priv->dev;
}
errno = EINVAL;
}
}
return NULL;
}

316
include/nuttx/lcd/ili9340.h Normal file
View File

@ -0,0 +1,316 @@
/****************************************************************************
* include/nuttx/lcd/ili9340.h
*
* Copyright (C) 2014 Gregory Nutt. All rights reserved.
* Authors: Gregory Nutt <gnutt@nuttx.org>
* Marco Krahl <ocram.lhark@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.
*
****************************************************************************/
#ifndef __INCLUDE_NUTTX_LCD_ILI9340_H
#define __INCLUDE_NUTTX_LCD_ILI9340_H
/****************************************************************************
* Included Files
****************************************************************************/
#include <nuttx/config.h>
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/
/* ILI9340 ID code */
#define ILI9340_DEVICE_CODE 0x9340
/* ILI9340 LCD Register Addresses *******************************************/
/* Level 1 commands */
#define ILI9340_NOP 0x00 /* Nop operation */
#define ILI9340_SOFTWARE_RESET 0x01 /* Software reset */
#define ILI9340_READ_DISP_ID 0x04 /* Read Display Identification information */
#define ILI9340_READ_DISP_STATUS 0x09 /* Read display status*/
#define ILI9340_READ_DISP_POWER_MODE 0x0a /* Read display power mode */
#define ILI9340_READ_DISP_MADCTRL 0x0b /* Read display MADCTL */
#define ILI9340_READ_DISP_PIXEL_FORMAT 0x0c /* Read display pixel forma */
#define ILI9340_READ_DISP_IMAGE_FORMAT 0x0d /* Read display image format */
#define ILI9340_READ_DISP_SIGNAL_MODE 0x0e /* Read display signal mode */
#define ILI9340_READ_DISP_SELF_DIAGNOSTIC 0x0f /* Read display self-diagnostic result */
#define ILI9340_ENTER_SLEEP_MODE 0x10 /* Enter sleep mode */
#define ILI9340_SLEEP_OUT 0x11 /* Sleep out */
#define ILI9340_PARTIAL_MODE_ON 0x12 /* Partial mode on */
#define ILI9340_NORMAL_DISP_MODE_ON 0x13 /* Normal display mode on */
#define ILI9340_DISP_INVERSION_OFF 0x20 /* Display inversion off */
#define ILI9340_DISP_INVERSION_ON 0x21 /* Display inversion on */
#define ILI9340_GAMMA_SET 0x26 /* Gamma set */
#define ILI9340_DISPLAY_OFF 0x28 /* Display off */
#define ILI9340_DISPLAY_ON 0x29 /* Display on */
#define ILI9340_COLUMN_ADDRESS_SET 0x2a /* Column address set */
#define ILI9340_PAGE_ADDRESS_SET 0x2b /* Page address set */
#define ILI9340_MEMORY_WRITE 0x2c /* Memory write */
#define ILI9340_COLOR_SET 0x2d /* Color set */
#define ILI9340_MEMORY_READ 0x2e /* Memory read */
#define ILI9340_PARTIAL_AREA 0x30 /* Partial area */
#define ILI9340_VERT_SCROLL_DEFINITION 0x33 /* Vertical scrolling definition */
#define ILI9340_TEARING_EFFECT_LINE_OFF 0x34 /* Tearing effect line off */
#define ILI9340_TEARING_EFFECT_LINE_ON 0x35 /* Tearing effect line on */
#define ILI9340_MEMORY_ACCESS_CONTROL 0x36 /* Memory Access control */
#define ILI9340_VERT_SCROLL_START_ADDRESS 0x37 /* Vertical scrolling start address */
#define ILI9340_IDLE_MODE_OFF 0x38 /* Idle mode off */
#define ILI9340_IDLE_MODE_ON 0x39 /* Idle mode on */
#define ILI9340_PIXEL_FORMAT_SET 0x3a /* Pixel Format set */
#define ILI9340_WRITE_MEMORY_CONTINUE 0x3c /* Write memory continue */
#define ILI9340_READ_MEMORY_CONTINUE 0x3e /* Read memory continue */
#define ILI9340_SET_TEAR_SCANLINE 0x44 /* Set tear scanline */
#define ILI9340_GET_SCANLINE 0x45 /* Get scanline */
#define ILI9340_WRITE_DISPLAY_BRIGHTNESS 0x51 /* Write display brightness */
#define ILI9340_READ_DISPLAY_BRIGHTNESS 0x52 /* Read display brightness */
#define ILI9340_WRITE_CTRL_DISPLAY 0x53 /* Write control display */
#define ILI9340_READ_CTRL_DISPLAY 0x54 /* Read control display */
#define ILI9340_WRITE_CONTENT_ADAPT_BRIGHTNESS 0x55 /* write content adaptive brightness control */
#define ILI9340_READ_CONTENT_ADAPT_BRIGHTNESS 0x56 /* Read content adaptive brightness control */
#define ILI9340_WRITE_MIN_CAB_LEVEL 0x5e /* Write CABC minimum brightness */
#define ILI9340_READ_MIN_CAB_LEVEL 0x5f /* Read CABC minimum brightness */
#define ILI9340_READ_ID1 0xda /* Read ID1 */
#define ILI9340_READ_ID2 0xdb /* Read ID2 */
#define ILI9340_READ_ID3 0xdc /* Read ID3 */
/* Level 2 Commands */
#define ILI9340_RGB_SIGNAL_CONTROL 0xb0 /* RGB interface signal control */
#define ILI9340_FRAME_RATE_CONTROL_NORMAL 0xb1 /* Frame control */
#define ILI9340_FRAME_RATE_CONTROL_IDLE_8COLOR 0xb2 /* Frame control in idle mode */
#define ILI9340_FRAME_RATE_CONTROL_PARTIAL 0xb3 /* Frame control in partial mode */
#define ILI9340_DISPLAY_INVERSION_CONTROL 0xb4 /* Display inversion control */
#define ILI9340_BLANKING_PORCH_CONTROL 0xb5 /* Blanking porch control */
#define ILI9340_DISPLAY_FUNCTION_CTL 0xb6 /* Display function control */
#define ILI9340_ENTRY_MODE_SET 0xb7 /* Entry mode set */
#define ILI9340_BACKLIGHT_CONTROL_1 0xb8 /* Backlight control1 */
#define ILI9340_BACKLIGHT_CONTROL_2 0xb9 /* Backlight control2 */
#define ILI9340_BACKLIGHT_CONTROL_3 0xba /* Backlight control3 */
#define ILI9340_BACKLIGHT_CONTROL_4 0xbb /* Backlight control 4 */
#define ILI9340_BACKLIGHT_CONTROL_5 0xbc /* Backlight control 5 */
#define ILI9340_BACKLIGHT_CONTROL_7 0xbe /* Backlight control 7 */
#define ILI9340_BACKLIGHT_CONTROL_8 0xbf /* Backlight control 8 */
#define ILI9340_POWER_CONTROL_1 0xc0 /* Power control 1 */
#define ILI9340_POWER_CONTROL_2 0xc1 /* Power control 2 */
#define ILI9340_VCOM_CONTROL_1 0xc5 /* VCOM control 1 */
#define ILI9340_VCOM_CONTROL_2 0xc7 /* VCOM control 2 */
#define ILI9340_POWER_CONTROL_A 0xcb /* Power control A */
#define ILI9340_POWER_CONTROL_B 0xcf /* Power control B */
#define ILI9340_NVMEM_WRITE 0xd0 /* NV memory write */
#define ILI9340_NVMEM_PROTECTION_KEY 0xd1 /* NV memory protection key */
#define ILI9340_NVMEM_STATUS_READ 0xd2 /* NV memory status read */
#define ILI9340_READ_ID4 0xd3 /* Read ID4 */
#define ILI9340_POSITIVE_GAMMA_CORRECTION 0xe0 /* Positive gamma correction */
#define ILI9340_NEGATIVE_GAMMA_CORRECTION 0xe1 /* Negative gamma correction */
#define ILI9340_DIGITAL_GAMMA_CONTROL_1 0xe2 /* Digital gamma control 1 */
#define ILI9340_DIGITAL_GAMMA_CONTROL_2 0xe3 /* Digital gamma control 2 */
#define ILI9340_DRIVER_TIMING_CTL_A 0xe8 /* Driver timing control A */
#define ILI9340_DRIVER_TIMING_CTL_B 0xea /* Driver timing control B */
#define ILI9340_POWER_ON_SEQUENCE_CONTROL 0xed /* Power-on sequence control */
#define ILI9340_ENABLE_3_GAMMA_CONTROL 0xf2 /* Enable 3g gamma control */
#define ILI9340_INTERFACE_CONTROL 0xf6 /* Interface control */
#define ILI9340_PUMP_RATIO_CONTROL 0xf7 /* Pump ration control */
/* ILI9340 LCD Register Bit Definitions *************************************/
/* Pixel format set */
#define ILI9340_PIXEL_FORMAT_SET_DPI_SHIFT (4)
#define ILI9340_PIXEL_FORMAT_SET_DPI_MASK (7 << ILI9340_PIXEL_FORMAT_SET_DPI_SHIFT)
#define ILI9340_PIXEL_FORMAT_SET_DPI(n) ((n) << ILI9340_PIXEL_FORMAT_SET_DPI_SHIFT)
#define ILI9340_PIXEL_FORMAT_SET_DBI_SHIFT (0)
#define ILI9340_PIXEL_FORMAT_SET_DBI_MASK (7 << ILI9340_PIXEL_FORMAT_SET_DBI_SHIFT)
#define ILI9340_PIXEL_FORMAT_SET_DBI(n) ((n) << ILI9340_PIXEL_FORMAT_SET_DBI_SHIFT)
/* Memory Access control */
#define ILI9340_MEMORY_ACCESS_CONTROL_MH (1 << 2) /* Horizontal refresh order */
#define ILI9340_MEMORY_ACCESS_CONTROL_BGR (1 << 3) /* RGB/BGR order */
#define ILI9340_MEMORY_ACCESS_CONTROL_ML (1 << 4) /* Vertical refresh order */
#define ILI9340_MEMORY_ACCESS_CONTROL_MV (1 << 5) /* Row/column exchange */
#define ILI9340_MEMORY_ACCESS_CONTROL_MX (1 << 6) /* Column address order */
#define ILI9340_MEMORY_ACCESS_CONTROL_MY (1 << 7) /* Row address order */
/* Display function control */
#define ILI9340_DISP_FUNC_CTL_ISC_SHIFT (0)
#define ILI9340_DISP_FUNC_CTL_ISC_MASK (15 << ILI9340_DISP_FUNC_CTL_ISC_SHIFT)
# define ILI9340_DISP_FUNC_CTL_ISC(n) ((n) << ILI9340_DISP_FUNC_CTL_ISC_SHIFT)
#define ILI9340_DISP_FUNC_CTL_SM (1 << 4)
#define ILI9340_DISP_FUNC_CTL_SS (1 << 5)
#define ILI9340_DISP_FUNC_CTL_GS (1 << 6)
#define ILI9340_DISP_FUNC_CTL_REV (1 << 7)
/* Interface function control */
#define ILI9340_INTERFACE_CONTROL_WEMODE (1)
#define ILI9340_INTERFACE_CONTROL_BGREOR (1 << 3)
#define ILI9340_INTERFACE_CONTROL_MVEOR (1 << 5)
#define ILI9340_INTERFACE_CONTROL_MXEOR (1 << 6)
#define ILI9340_INTERFACE_CONTROL_MYEOR (1 << 7)
#define ILI9340_INTERFACE_CONTROL_MDT_SHIFT (0)
#define ILI9340_INTERFACE_CONTROL_MDT_MASK (3 << ILI9340_INTERFACE_CONTROL_MDT_SHIFT)
#define ILI9340_INTERFACE_CONTROL_MDT(n) ((n) << ILI9340_INTERFACE_CONTROL_MDT_SHIFT)
#define ILI9340_INTERFACE_CONTROL_EPF_SHIFT (4)
#define ILI9340_INTERFACE_CONTROL_EPF_MASK (3 << ILI9340_INTERFACE_CONTROL_EPF_SHIFT)
#define ILI9340_INTERFACE_CONTROL_EPF(n) ((n) << ILI9340_INTERFACE_CONTROL_EPF_SHIFT)
#define ILI9340_INTERFACE_CONTROL_RIM (1)
#define ILI9340_INTERFACE_CONTROL_RM (1 << 1)
#define ILI9340_INTERFACE_CONTROL_DM_SHIFT (4)
#define ILI9340_INTERFACE_CONTROL_DM_MASK (2 << ILI9340_INTERFACE_CONTROL_DM_SHIFT)
#define ILI9340_INTERFACE_CONTROL_DM(n) ((n) << ILI9340_INTERFACE_CONTROL_DM_SHIFT)
#define ILI9340_INTERFACE_CONTROL_ENDIAN (1 << 5)
/* Interface Mode control */
#define ILI9340_INTERFACE_CONTROL_EPL (1)
#define ILI9340_INTERFACE_CONTROL_DPL (1 << 1)
#define ILI9340_INTERFACE_CONTROL_HSPL (1 << 2)
#define ILI9340_INTERFACE_CONTROL_VSPL (1 << 3)
#define ILI9340_INTERFACE_CONTROL_RCM_SHIFT (5)
#define ILI9340_INTERFACE_CONTROL_RCM_MASK (2 << ILI9340_INTERFACE_CONTROL_RCM_SHIFT)
#define ILI9340_INTERFACE_CONTROL_RCM(n) ((n) << ILI9340_INTERFACE_CONTROL_RCM_SHIFT)
#define ILI9340_INTERFACE_CONTROL_BPASS (1 << 7)
/****************************************************************************
* Public Types
****************************************************************************/
struct ili9340_lcd_s
{
/* Interface to control the ILI9340 lcd driver
*
* - select Select the device (as neccessary) before performing any
* operations.
* - deselect Deselect the device (as necessary).
* - sendcmd Send specific command to the LCD driver.
* - sendparam Send specific parameter to the LCD driver.
* - recvparam Receive specific parameter from the LCD driver.
* - sendgram Send pixel data to the LCD drivers gram.
* - recvgram Receive pixel data from the LCD drivers gram.
* - backlight Change the backlight level of the connected display.
* In the context of the ili9340 that means change the
* backlight level of the connected LED driver.
* The implementation in detail is part of the platform
* specific sub driver.
*
*/
void (*select)(FAR struct ili9340_lcd_s *lcd);
void (*deselect)(FAR struct ili9340_lcd_s *lcd);
int (*sendcmd)(FAR struct ili9340_lcd_s *lcd, const uint8_t cmd);
int (*sendparam)(FAR struct ili9340_lcd_s *lcd, const uint8_t param);
int (*recvparam)(FAR struct ili9340_lcd_s *lcd, uint8_t *param);
int (*recvgram)(FAR struct ili9340_lcd_s *lcd,
uint16_t *wd, uint32_t nwords);
int (*sendgram)(FAR struct ili9340_lcd_s *lcd,
const uint16_t *wd, uint32_t nwords);
int (*backlight)(FAR struct ili9340_lcd_s *lcd, int level);
/* mcu interface specific data following */
};
/****************************************************************************
* Public Data
****************************************************************************/
#ifdef __cplusplus
#define EXTERN extern "C"
extern "C"
{
#else
#define EXTERN extern
#endif
/****************************************************************************
* Public Function Prototypes
****************************************************************************/
/****************************************************************************
* Name: ili9340_initialize
*
* Description:
* Initialize the LCD video driver internal sturcture. Also initialize the
* lcd hardware if not done. The control of the LCD driver is depend on the
* selected MCU interface and part of the platform specific subdriver (see
* config/stm32f429i-disco/src/stm32_ili93404ws.c)
*
* Input Parameters:
*
* lcd - A reference to the platform specific driver instance to control
* the ili9340 display driver.
* devno - A value in the range of 0 through CONFIG_ILI9340_NINTERFACES-1.
* This allows support for multiple LCD devices.
*
* Returned Value:
*
* On success, this function returns a reference to the LCD driver object
* for the specified LCD driver. NULL is returned on any failure.
*
****************************************************************************/
FAR struct lcd_dev_s *ili9340_initialize(FAR struct ili9340_lcd_s *lcd,
int devno);
/****************************************************************************
* Name: ili9340_clear
*
* Description:
* This is a non-standard LCD interface. Because of the various rotations,
* clearing the display in the normal way by writing a sequences of runs
* that covers the entire display can be very slow.
* Here the display is cleared by simply setting all GRAM memory to the
* specified color.
*
* Parameter:
* dev - A reference to the lcd driver structure
* color - The background color
*
* Returned Value:
*
* On success - OK
* On error - -EINVAL
*
****************************************************************************/
int ili9340_clear(FAR struct lcd_dev_s *dev, uint16_t color);
#undef EXTERN
#ifdef __cplusplus
}
#endif
#endif /* __INCLUDE_NUTTX_LCD_ILI9340_H */

View File

@ -0,0 +1,138 @@
/****************************************************************************
* include/nuttx/lcd/lpm013m091a.h
*
* Copyright 2018 Sony Semiconductor Solutions Corporation
*
* 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 of Sony Semiconductor Solutions Corporation 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 __INCLUDE_NUTTX_LCD_LPM013M091A_H
#define __INCLUDE_NUTTX_LCD_LPM013M091A_H
/* Command set. */
#define LPM013M091A_SWRESET 0x01
#define LPM013M091A_SLPIN 0x10
#define LPM013M091A_SLPOUT 0x11
#define LPM013M091A_DISPOFF 0x28
#define LPM013M091A_DISPON 0x29
#define LPM013M091A_CASET 0x2A
#define LPM013M091A_PASET 0x2B
#define LPM013M091A_RAMWR 0x2C
#define LPM013M091A_PIXFMT 0x3A
/****************************************************************************
* Public Function Prototypes
****************************************************************************/
#ifdef __cplusplus
#define EXTERN extern "C"
extern "C"
{
#else
#define EXTERN extern
#endif
/****************************************************************************
* Response CODE
****************************************************************************/
struct lpm013m091a_lcd_s
{
/* Interface to control the LPM013M091A lcd driver
*
* - select Select the device (as neccessary) before performing
* any operations.
* - deselect Deselect the device (as necessary).
* - sendcmd Send specific command to the LCD driver.
* - sendparam Send specific parameter to the LCD driver.
* - recvparam Receive specific parameter from the LCD driver.
* - sendgram Send pixel data to the LCD drivers gram.
* - recvgram Receive pixel data from the LCD drivers gram.
* - backlight Change the backlight level of the connected display.
* In the context of the lpm013m091a that means change the
* backlight level of the connected LED driver.
* The implementation in detail is part of the platform
* specific sub driver.
*
*/
void (*select)(FAR struct lpm013m091a_lcd_s *lcd);
void (*deselect)(FAR struct lpm013m091a_lcd_s *lcd);
int (*sendcmd)(FAR struct lpm013m091a_lcd_s *lcd, const uint8_t cmd);
int (*sendparam)(FAR struct lpm013m091a_lcd_s *lcd, const uint8_t param);
int (*recvparam)(FAR struct lpm013m091a_lcd_s *lcd, uint8_t *param);
int (*recvgram)(FAR struct lpm013m091a_lcd_s *lcd,
uint16_t *wd, uint32_t nwords);
int (*sendgram)(FAR struct lpm013m091a_lcd_s *lcd,
const uint16_t *wd, uint32_t nwords);
int (*backlight)(FAR struct lpm013m091a_lcd_s *lcd, int level);
/* mcu interface specific data following */
};
/****************************************************************************
* Public Function Prototypes
****************************************************************************/
/****************************************************************************
* Name: lpm013m091a_initialize
*
* Description:
* Initialize the LCD video driver internal sturcture. Also initialize the
* lcd hardware if not done. The control of the LCD driver is depend on the
* selected MCU interface and part of the platform specific subdriver
*
*
* Input Parameters:
*
* lcd - A reference to the platform specific driver instance to control the
* lpm013m091a display driver.
* devno - This is for compat. must be zero.
*
* Returned Value:
*
* On success, this function returns a reference to the LCD driver object
* for the specified LCD driver. NULL is returned on any failure.
*
****************************************************************************/
FAR struct lcd_dev_s* lpm013m091a_initialize(struct lpm013m091a_lcd_s *lcd,
int devno);
#undef EXTERN
#ifdef __cplusplus
}
#endif
#endif /* __INCLUDE_NUTTX_LCD_LPM013M091A_H */