提交 880fc2f5 编写于 作者: T Ting Liu 提交者: guo

[imxrt 1060] support touchpad

Signed-off-by: NTing Liu <ting.liu@nxp.com>
上级 f92c26a6
/*
* Copyright (c) 2006-2022, RT-Thread Development Team
* Copyright 2022 NXP
*
* SPDX-License-Identifier: Apache-2.0
*
* Change Logs:
* Date Author Notes
* 2021-10-18 Meco Man The first version
* 2022-05-17 Ting Liu Support touchpad
*/
#define LOG_TAG "LVGL.port.indev"
#include <drv_log.h>
#include "lvgl.h"
#include "board.h"
#include "fsl_video_common.h"
#include "fsl_lpi2c.h"
#include "fsl_gpio.h"
#ifdef DEMO_PANEL_RK043FN66HS
#include "fsl_gt911.h"
#else
#include "fsl_ft5406_rt.h"
#endif
#if LV_USE_GPU_NXP_PXP
#include "src/gpu/lv_gpu_nxp_pxp.h"
#include "src/gpu/lv_gpu_nxp_pxp_osa.h"
#endif
/*******************************************************************************
* Definitions
******************************************************************************/
/* @Brief Board touch panel configuration */
#define BOARD_TOUCH_I2C_BASEADDR LPI2C1
#define BOARD_TOUCH_RST_GPIO GPIO1
#define BOARD_TOUCH_RST_PIN 2
#define BOARD_TOUCH_INT_GPIO GPIO1
#define BOARD_TOUCH_INT_PIN 11
/* Macros for the touch touch controller. */
#define TOUCH_I2C LPI2C1
/* Select USB1 PLL (480 MHz) as master lpi2c clock source */
#define TOUCH_LPI2C_CLOCK_SOURCE_SELECT (0U)
/* Clock divider for master lpi2c clock source */
#define TOUCH_LPI2C_CLOCK_SOURCE_DIVIDER (5U)
#define TOUCH_I2C_CLOCK_FREQ ((CLOCK_GetFreq(kCLOCK_Usb1PllClk) / 8) / (TOUCH_LPI2C_CLOCK_SOURCE_DIVIDER + 1U))
#define TOUCH_I2C_BAUDRATE 100000U
/*******************************************************************************
* Prototypes
******************************************************************************/
static void DEMO_InitTouch(void);
static void DEMO_ReadTouch(lv_indev_drv_t *drv, lv_indev_data_t *data);
#ifdef DEMO_PANEL_RK043FN66HS
static void BOARD_PullTouchResetPin(bool pullUp);
static void BOARD_ConfigTouchIntPin(gt911_int_pin_mode_t mode);
#endif
/*******************************************************************************
* Variables
******************************************************************************/
#ifdef DEMO_PANEL_RK043FN66HS
static gt911_handle_t s_touchHandle;
static const gt911_config_t s_touchConfig = {
.I2C_SendFunc = BOARD_Touch_I2C_Send,
.I2C_ReceiveFunc = BOARD_Touch_I2C_Receive,
.pullResetPinFunc = BOARD_PullTouchResetPin,
.intPinFunc = BOARD_ConfigTouchIntPin,
.timeDelayMsFunc = VIDEO_DelayMs,
.touchPointNum = 1,
.i2cAddrMode = kGT911_I2cAddrMode0,
.intTrigMode = kGT911_IntRisingEdge,
};
static int s_touchResolutionX;
static int s_touchResolutionY;
#else
static ft5406_rt_handle_t touchHandle;
#endif
void lv_port_indev_init(void)
{
static lv_indev_drv_t indev_drv;
/*------------------
* Touchpad
* -----------------*/
/*Initialize your touchpad */
DEMO_InitTouch();
/*Register a touchpad input device*/
lv_indev_drv_init(&indev_drv);
indev_drv.type = LV_INDEV_TYPE_POINTER;
indev_drv.read_cb = DEMO_ReadTouch;
lv_indev_drv_register(&indev_drv);
}
#ifdef DEMO_PANEL_RK043FN66HS
static void BOARD_PullTouchResetPin(bool pullUp)
{
if (pullUp)
{
GPIO_PinWrite(BOARD_TOUCH_RST_GPIO, BOARD_TOUCH_RST_PIN, 1);
}
else
{
GPIO_PinWrite(BOARD_TOUCH_RST_GPIO, BOARD_TOUCH_RST_PIN, 0);
}
}
static void BOARD_ConfigTouchIntPin(gt911_int_pin_mode_t mode)
{
if (mode == kGT911_IntPinInput)
{
BOARD_TOUCH_INT_GPIO->GDIR &= ~(1UL << BOARD_TOUCH_INT_PIN);
}
else
{
if (mode == kGT911_IntPinPullDown)
{
GPIO_PinWrite(BOARD_TOUCH_INT_GPIO, BOARD_TOUCH_INT_PIN, 0);
}
else
{
GPIO_PinWrite(BOARD_TOUCH_INT_GPIO, BOARD_TOUCH_INT_PIN, 1);
}
BOARD_TOUCH_INT_GPIO->GDIR |= (1UL << BOARD_TOUCH_INT_PIN);
}
}
/*Initialize your touchpad*/
static void DEMO_InitTouch(void)
{
status_t status;
const gpio_pin_config_t resetPinConfig = {
.direction = kGPIO_DigitalOutput, .outputLogic = 0, .interruptMode = kGPIO_NoIntmode};
GPIO_PinInit(BOARD_TOUCH_INT_GPIO, BOARD_TOUCH_INT_PIN, &resetPinConfig);
GPIO_PinInit(BOARD_TOUCH_RST_GPIO, BOARD_TOUCH_RST_PIN, &resetPinConfig);
/*Clock setting for LPI2C*/
CLOCK_SetMux(kCLOCK_Lpi2cMux, TOUCH_LPI2C_CLOCK_SOURCE_SELECT);
CLOCK_SetDiv(kCLOCK_Lpi2cDiv, TOUCH_LPI2C_CLOCK_SOURCE_DIVIDER);
BOARD_LPI2C_Init(TOUCH_I2C, TOUCH_I2C_CLOCK_FREQ);
status = GT911_Init(&s_touchHandle, &s_touchConfig);
if (kStatus_Success != status)
{
//PRINTF("Touch IC initialization failed\r\n");
assert(false);
}
GT911_GetResolution(&s_touchHandle, &s_touchResolutionX, &s_touchResolutionY);
}
/* Will be called by the library to read the touchpad */
static void DEMO_ReadTouch(lv_indev_drv_t *drv, lv_indev_data_t *data)
{
static int touch_x = 0;
static int touch_y = 0;
if (kStatus_Success == GT911_GetSingleTouch(&s_touchHandle, &touch_x, &touch_y))
{
data->state = LV_INDEV_STATE_PR;
}
else
{
data->state = LV_INDEV_STATE_REL;
}
/*Set the last pressed coordinates*/
data->point.x = touch_x * LCD_WIDTH / s_touchResolutionX;
data->point.y = touch_y * LCD_HEIGHT / s_touchResolutionY;
}
#else
/*Initialize your touchpad*/
static void DEMO_InitTouch(void)
{
status_t status;
lpi2c_master_config_t masterConfig = {0};
/*Clock setting for LPI2C*/
CLOCK_SetMux(kCLOCK_Lpi2cMux, TOUCH_LPI2C_CLOCK_SOURCE_SELECT);
CLOCK_SetDiv(kCLOCK_Lpi2cDiv, TOUCH_LPI2C_CLOCK_SOURCE_DIVIDER);
/*
* masterConfig.debugEnable = false;
* masterConfig.ignoreAck = false;
* masterConfig.pinConfig = kLPI2C_2PinOpenDrain;
* masterConfig.baudRate_Hz = 100000U;
* masterConfig.busIdleTimeout_ns = 0;
* masterConfig.pinLowTimeout_ns = 0;
* masterConfig.sdaGlitchFilterWidth_ns = 0;
* masterConfig.sclGlitchFilterWidth_ns = 0;
*/
LPI2C_MasterGetDefaultConfig(&masterConfig);
/* Change the default baudrate configuration */
masterConfig.baudRate_Hz = TOUCH_I2C_BAUDRATE;
/* Initialize the LPI2C master peripheral */
LPI2C_MasterInit(TOUCH_I2C, &masterConfig, TOUCH_I2C_CLOCK_FREQ);
/* Initialize touch panel controller */
status = FT5406_RT_Init(&touchHandle, TOUCH_I2C);
if (status != kStatus_Success)
{
//PRINTF("Touch panel init failed\n");
assert(0);
}
}
/* Will be called by the library to read the touchpad */
static void DEMO_ReadTouch(lv_indev_drv_t *drv, lv_indev_data_t *data)
{
touch_event_t touch_event;
static int touch_x = 0;
static int touch_y = 0;
data->state = LV_INDEV_STATE_REL;
if (kStatus_Success == FT5406_RT_GetSingleTouch(&touchHandle, &touch_event, &touch_x, &touch_y))
{
if ((touch_event == kTouch_Down) || (touch_event == kTouch_Contact))
{
data->state = LV_INDEV_STATE_PR;
}
}
/*Set the last pressed coordinates*/
data->point.x = touch_y;
data->point.y = touch_x;
}
#endif
......@@ -68,11 +68,32 @@ menu "Onboard Peripheral Drivers"
default 2
endif
menuconfig BSP_USING_TOUCHPAD
bool "Enable TOUCHPAD"
select BSP_USING_PXP
select BSP_USING_CACHE
select BSP_USING_I2C
select BSP_USING_LCD
default n
if BSP_USING_TOUCHPAD
choice
prompt "Select panel"
default DEMO_PANEL_RK043FN02H
config DEMO_PANEL_RK043FN02H
bool "RK043FN02H-CT"
config DEMO_PANEL_RK043FN66HS
bool "RK043FN66HS-CTG"
endchoice
endif
config BSP_USING_LVGL
bool "Enable LVGL for LCD"
select BSP_USING_PXP
select BSP_USING_CACHE
select BSP_USING_LCD
select BSP_USING_TOUCHPAD
select PKG_USING_LVGL
default n
......@@ -100,6 +121,26 @@ menu "On-chip Peripheral Drivers"
select RT_USING_PIN
default y
menuconfig BSP_USING_I2C
bool "Enable I2C"
select RT_USING_I2C
default y
if BSP_USING_I2C
config BSP_USING_I2C1
bool
default y
choice
prompt "Select I2C1 badurate"
default HW_I2C1_BADURATE_100kHZ
config HW_I2C1_BADURATE_100kHZ
bool "Badurate 100kHZ"
config HW_I2C1_BADURATE_400kHZ
bool "Badurate 400kHZ"
endchoice
endif
menuconfig BSP_USING_LPUART
bool "Enable UART"
select RT_USING_SERIAL
......
......@@ -12,6 +12,9 @@ MCUX_Config/pin_mux.c
MCUX_Config/dcd.c
""")
if GetDepend(['BSP_USING_TOUCHPAD']):
src += ['ports/touchpad.c']
CPPPATH = [cwd,cwd + '/MCUX_Config',cwd + '/ports']
CPPDEFINES = ['CPU_MIMXRT1062DVL6A', 'SKIP_SYSCLK_INIT', 'EVK_MCIMXRM', 'FSL_SDK_ENABLE_DRIVER_CACHE_CONTROL=1','XIP_EXTERNAL_FLASH=1', 'XIP_BOOT_HEADER_ENABLE=1', 'FSL_SDK_DRIVER_QUICK_ACCESS_ENABLE=1', 'XIP_BOOT_HEADER_DCD_ENABLE=1', 'DATA_SECTION_IS_CACHEABLE=1']
......
/*
* Copyright 2022 NXP
* All rights reserved.
*
* SPDX-License-Identifier: BSD-3-Clause
*/
#include "touchpad.h"
void BOARD_LPI2C_Init(LPI2C_Type *base, uint32_t clkSrc_Hz)
{
lpi2c_master_config_t lpi2cConfig = {0};
/*
* lpi2cConfig.debugEnable = false;
* lpi2cConfig.ignoreAck = false;
* lpi2cConfig.pinConfig = kLPI2C_2PinOpenDrain;
* lpi2cConfig.baudRate_Hz = 100000U;
* lpi2cConfig.busIdleTimeout_ns = 0;
* lpi2cConfig.pinLowTimeout_ns = 0;
* lpi2cConfig.sdaGlitchFilterWidth_ns = 0;
* lpi2cConfig.sclGlitchFilterWidth_ns = 0;
*/
LPI2C_MasterGetDefaultConfig(&lpi2cConfig);
LPI2C_MasterInit(base, &lpi2cConfig, clkSrc_Hz);
}
status_t BOARD_LPI2C_Send(LPI2C_Type *base,
uint8_t deviceAddress,
uint32_t subAddress,
uint8_t subAddressSize,
uint8_t *txBuff,
uint8_t txBuffSize)
{
lpi2c_master_transfer_t xfer;
xfer.flags = kLPI2C_TransferDefaultFlag;
xfer.slaveAddress = deviceAddress;
xfer.direction = kLPI2C_Write;
xfer.subaddress = subAddress;
xfer.subaddressSize = subAddressSize;
xfer.data = txBuff;
xfer.dataSize = txBuffSize;
return LPI2C_MasterTransferBlocking(base, &xfer);
}
status_t BOARD_LPI2C_Receive(LPI2C_Type *base,
uint8_t deviceAddress,
uint32_t subAddress,
uint8_t subAddressSize,
uint8_t *rxBuff,
uint8_t rxBuffSize)
{
lpi2c_master_transfer_t xfer;
xfer.flags = kLPI2C_TransferDefaultFlag;
xfer.slaveAddress = deviceAddress;
xfer.direction = kLPI2C_Read;
xfer.subaddress = subAddress;
xfer.subaddressSize = subAddressSize;
xfer.data = rxBuff;
xfer.dataSize = rxBuffSize;
return LPI2C_MasterTransferBlocking(base, &xfer);
}
status_t BOARD_LPI2C_SendSCCB(LPI2C_Type *base,
uint8_t deviceAddress,
uint32_t subAddress,
uint8_t subAddressSize,
uint8_t *txBuff,
uint8_t txBuffSize)
{
lpi2c_master_transfer_t xfer;
xfer.flags = kLPI2C_TransferDefaultFlag;
xfer.slaveAddress = deviceAddress;
xfer.direction = kLPI2C_Write;
xfer.subaddress = subAddress;
xfer.subaddressSize = subAddressSize;
xfer.data = txBuff;
xfer.dataSize = txBuffSize;
return LPI2C_MasterTransferBlocking(base, &xfer);
}
status_t BOARD_LPI2C_ReceiveSCCB(LPI2C_Type *base,
uint8_t deviceAddress,
uint32_t subAddress,
uint8_t subAddressSize,
uint8_t *rxBuff,
uint8_t rxBuffSize)
{
status_t status;
lpi2c_master_transfer_t xfer;
xfer.flags = kLPI2C_TransferDefaultFlag;
xfer.slaveAddress = deviceAddress;
xfer.direction = kLPI2C_Write;
xfer.subaddress = subAddress;
xfer.subaddressSize = subAddressSize;
xfer.data = NULL;
xfer.dataSize = 0;
status = LPI2C_MasterTransferBlocking(base, &xfer);
if (kStatus_Success == status)
{
xfer.subaddressSize = 0;
xfer.direction = kLPI2C_Read;
xfer.data = rxBuff;
xfer.dataSize = rxBuffSize;
status = LPI2C_MasterTransferBlocking(base, &xfer);
}
return status;
}
status_t BOARD_Touch_I2C_Send(
uint8_t deviceAddress, uint32_t subAddress, uint8_t subAddressSize, const uint8_t *txBuff, uint8_t txBuffSize)
{
return BOARD_LPI2C_Send(BOARD_TOUCH_I2C_BASEADDR, deviceAddress, subAddress, subAddressSize, (uint8_t *)txBuff,
txBuffSize);
}
status_t BOARD_Touch_I2C_Receive(
uint8_t deviceAddress, uint32_t subAddress, uint8_t subAddressSize, uint8_t *rxBuff, uint8_t rxBuffSize)
{
return BOARD_LPI2C_Receive(BOARD_TOUCH_I2C_BASEADDR, deviceAddress, subAddress, subAddressSize, rxBuff, rxBuffSize);
}
/*
* Copyright 2022 NXP
* All rights reserved.
*
* SPDX-License-Identifier: BSD-3-Clause
*/
#ifndef __TOUCHPAD_PORT_H__
#define __TOUCHPAD_PORT_H__
#ifdef __cplusplus
extern "C" {
#endif
#include "fsl_common.h"
#include "clock_config.h"
#include "fsl_lpi2c.h"
#include "fsl_gpio.h"
/* @Brief Board touch panel configuration */
#define BOARD_TOUCH_I2C_BASEADDR LPI2C1
#define BOARD_TOUCH_RST_GPIO GPIO1
#define BOARD_TOUCH_RST_PIN 2
#define BOARD_TOUCH_INT_GPIO GPIO1
#define BOARD_TOUCH_INT_PIN 11
void BOARD_LPI2C_Init(LPI2C_Type *base, uint32_t clkSrc_Hz);
status_t BOARD_LPI2C_Send(LPI2C_Type *base,
uint8_t deviceAddress,
uint32_t subAddress,
uint8_t subaddressSize,
uint8_t *txBuff,
uint8_t txBuffSize);
status_t BOARD_LPI2C_Receive(LPI2C_Type *base,
uint8_t deviceAddress,
uint32_t subAddress,
uint8_t subaddressSize,
uint8_t *rxBuff,
uint8_t rxBuffSize);
status_t BOARD_LPI2C_SendSCCB(LPI2C_Type *base,
uint8_t deviceAddress,
uint32_t subAddress,
uint8_t subaddressSize,
uint8_t *txBuff,
uint8_t txBuffSize);
status_t BOARD_LPI2C_ReceiveSCCB(LPI2C_Type *base,
uint8_t deviceAddress,
uint32_t subAddress,
uint8_t subaddressSize,
uint8_t *rxBuff,
uint8_t rxBuffSize);
status_t BOARD_Touch_I2C_Send(
uint8_t deviceAddress, uint32_t subAddress, uint8_t subAddressSize, const uint8_t *txBuff, uint8_t txBuffSize);
status_t BOARD_Touch_I2C_Receive(
uint8_t deviceAddress, uint32_t subAddress, uint8_t subAddressSize, uint8_t *rxBuff, uint8_t rxBuffSize);
#ifdef __cplusplus
} /*extern "C"*/
#endif
#endif
/*
* Copyright (c) 2016, Freescale Semiconductor, Inc.
* Copyright 2016-2019 NXP
* All rights reserved.
*
* SPDX-License-Identifier: BSD-3-Clause
*/
#include "fsl_common.h"
#include "fsl_lpi2c.h"
#include "fsl_ft5406_rt.h"
typedef struct _ft5406_rt_touch_point
{
uint8_t XH;
uint8_t XL;
uint8_t YH;
uint8_t YL;
uint8_t RESERVED[2];
} ft5406_rt_touch_point_t;
typedef struct _ft5406_rt_touch_data
{
uint8_t GEST_ID;
uint8_t TD_STATUS;
ft5406_rt_touch_point_t TOUCH[FT5406_RT_MAX_TOUCHES];
} ft5406_rt_touch_data_t;
#define TOUCH_POINT_GET_EVENT(T) ((touch_event_t)((T).XH >> 6))
#define TOUCH_POINT_GET_ID(T) ((T).YH >> 4)
#define TOUCH_POINT_GET_X(T) ((((T).XH & 0x0f) << 8) | (T).XL)
#define TOUCH_POINT_GET_Y(T) ((((T).YH & 0x0f) << 8) | (T).YL)
status_t FT5406_RT_Init(ft5406_rt_handle_t *handle, LPI2C_Type *base)
{
lpi2c_master_transfer_t *xfer = &(handle->xfer);
status_t status;
uint8_t mode;
assert(handle);
assert(base);
if (!handle || !base)
{
return kStatus_InvalidArgument;
}
handle->base = base;
/* clear transfer structure and buffer */
memset(xfer, 0, sizeof(*xfer));
memset(handle->touch_buf, 0, FT5406_RT_TOUCH_DATA_LEN);
/* set device mode to normal operation */
mode = 0;
xfer->slaveAddress = FT5406_RT_I2C_ADDRESS;
xfer->direction = kLPI2C_Write;
xfer->subaddress = 0;
xfer->subaddressSize = 1;
xfer->data = &mode;
xfer->dataSize = 1;
xfer->flags = kLPI2C_TransferDefaultFlag;
status = LPI2C_MasterTransferBlocking(handle->base, &handle->xfer);
/* prepare transfer structure for reading touch data */
xfer->slaveAddress = FT5406_RT_I2C_ADDRESS;
xfer->direction = kLPI2C_Read;
xfer->subaddress = 1;
xfer->subaddressSize = 1;
xfer->data = handle->touch_buf;
xfer->dataSize = FT5406_RT_TOUCH_DATA_LEN;
xfer->flags = kLPI2C_TransferDefaultFlag;
return status;
}
status_t FT5406_RT_Denit(ft5406_rt_handle_t *handle)
{
assert(handle);
if (!handle)
{
return kStatus_InvalidArgument;
}
handle->base = NULL;
return kStatus_Success;
}
status_t FT5406_RT_ReadTouchData(ft5406_rt_handle_t *handle)
{
assert(handle);
if (!handle)
{
return kStatus_InvalidArgument;
}
return LPI2C_MasterTransferBlocking(handle->base, &handle->xfer);
}
status_t FT5406_RT_GetSingleTouch(ft5406_rt_handle_t *handle, touch_event_t *touch_event, int *touch_x, int *touch_y)
{
status_t status;
touch_event_t touch_event_local;
status = FT5406_RT_ReadTouchData(handle);
if (status == kStatus_Success)
{
ft5406_rt_touch_data_t *touch_data = (ft5406_rt_touch_data_t *)(void *)(handle->touch_buf);
if (touch_event == NULL)
{
touch_event = &touch_event_local;
}
*touch_event = TOUCH_POINT_GET_EVENT(touch_data->TOUCH[0]);
/* Update coordinates only if there is touch detected */
if ((*touch_event == kTouch_Down) || (*touch_event == kTouch_Contact))
{
if (touch_x)
{
*touch_x = TOUCH_POINT_GET_X(touch_data->TOUCH[0]);
}
if (touch_y)
{
*touch_y = TOUCH_POINT_GET_Y(touch_data->TOUCH[0]);
}
}
}
return status;
}
status_t FT5406_RT_GetMultiTouch(ft5406_rt_handle_t *handle,
int *touch_count,
touch_point_t touch_array[FT5406_RT_MAX_TOUCHES])
{
status_t status;
status = FT5406_RT_ReadTouchData(handle);
if (status == kStatus_Success)
{
ft5406_rt_touch_data_t *touch_data = (ft5406_rt_touch_data_t *)(void *)(handle->touch_buf);
int i;
/* Check for valid number of touches - otherwise ignore touch information */
if (touch_data->TD_STATUS > FT5406_RT_MAX_TOUCHES)
{
touch_data->TD_STATUS = 0;
}
/* Decode number of touches */
if (touch_count)
{
*touch_count = touch_data->TD_STATUS;
}
/* Decode valid touch points */
for (i = 0; i < touch_data->TD_STATUS; i++)
{
touch_array[i].TOUCH_ID = TOUCH_POINT_GET_ID(touch_data->TOUCH[i]);
touch_array[i].TOUCH_EVENT = TOUCH_POINT_GET_EVENT(touch_data->TOUCH[i]);
touch_array[i].TOUCH_X = TOUCH_POINT_GET_X(touch_data->TOUCH[i]);
touch_array[i].TOUCH_Y = TOUCH_POINT_GET_Y(touch_data->TOUCH[i]);
}
/* Clear vacant elements of touch_array */
for (; i < FT5406_RT_MAX_TOUCHES; i++)
{
touch_array[i].TOUCH_ID = 0;
touch_array[i].TOUCH_EVENT = kTouch_Reserved;
touch_array[i].TOUCH_X = 0;
touch_array[i].TOUCH_Y = 0;
}
}
return status;
}
/*
* Copyright (c) 2016, Freescale Semiconductor, Inc.
* Copyright 2016-2017 NXP
* All rights reserved.
*
* SPDX-License-Identifier: BSD-3-Clause
*/
#ifndef _FSL_FT5406_RT_H_
#define _FSL_FT5406_RT_H_
#include "fsl_common.h"
/*!
* @addtogroup ft5406_rt
* @{
*/
/*******************************************************************************
* Definitions
******************************************************************************/
/*! @brief FT5406_RT I2C address. */
#define FT5406_RT_I2C_ADDRESS (0x38)
/*! @brief FT5406_RT maximum number of simultaneously detected touches. */
#define FT5406_RT_MAX_TOUCHES (5U)
/*! @brief FT5406_RT register address where touch data begin. */
#define FT5406_RT_TOUCH_DATA_SUBADDR (1)
/*! @brief FT5406_RT raw touch data length. */
#define FT5406_RT_TOUCH_DATA_LEN (0x20)
typedef enum _touch_event
{
kTouch_Down = 0, /*!< The state changed to touched. */
kTouch_Up = 1, /*!< The state changed to not touched. */
kTouch_Contact = 2, /*!< There is a continuous touch being detected. */
kTouch_Reserved = 3 /*!< No touch information available. */
} touch_event_t;
typedef struct _touch_point
{
touch_event_t TOUCH_EVENT; /*!< Indicates the state or event of the touch point. */
uint8_t TOUCH_ID; /*!< Id of the touch point. This numeric value stays constant between down and up event. */
uint16_t TOUCH_X; /*!< X coordinate of the touch point */
uint16_t TOUCH_Y; /*!< Y coordinate of the touch point */
} touch_point_t;
typedef struct _ft5406_rt_handle
{
LPI2C_Type *base;
lpi2c_master_transfer_t xfer;
uint8_t touch_buf[FT5406_RT_TOUCH_DATA_LEN];
} ft5406_rt_handle_t;
status_t FT5406_RT_Init(ft5406_rt_handle_t *handle, LPI2C_Type *base);
status_t FT5406_RT_Denit(ft5406_rt_handle_t *handle);
status_t FT5406_RT_GetSingleTouch(ft5406_rt_handle_t *handle, touch_event_t *touch_event, int *touch_x, int *touch_y);
status_t FT5406_RT_GetMultiTouch(ft5406_rt_handle_t *handle,
int *touch_count,
touch_point_t touch_array[FT5406_RT_MAX_TOUCHES]);
#endif
/*
* Copyright 2019-2020 NXP
* All rights reserved.
*
* SPDX-License-Identifier: BSD-3-Clause
*/
#include "fsl_gt911.h"
/*******************************************************************************
* Definitions
******************************************************************************/
/*! @brief GT911 I2C address. */
#define GT911_I2C_ADDRESS0 (0x5D)
#define GT911_I2C_ADDRESS1 (0x14)
#define GT911_REG_ADDR_SIZE 2
/*! @brief GT911 registers. */
#define GT911_REG_ID 0x8140U
#define GT911_CONFIG_ADDR 0x8047U
#define GT911_REG_XL 0x8048U
#define GT911_REG_XH 0x8049U
#define GT911_REG_YL 0x804AU
#define GT911_REG_YH 0x804BU
#define GT911_REG_TOUCH_NUM 0x804CU
#define GT911_REG_CONFIG_VERSION 0x8047U
#define GT911_REG_MODULE_SWITCH1 0x804DU
#define GT911_REG_STAT 0x814EU
#define GT911_REG_FIRST_POINT 0x814FU
#define GT911_STAT_BUF_MASK (1U << 7U)
#define GT911_STAT_POINT_NUMBER_MASK (0xFU << 0U)
#define GT911_MODULE_SWITCH_X2Y_MASK (1U << 3U)
#define GT911_MODULE_SWITCH_INT_MASK (3U << 0U)
#define GT911_CONFIG_SIZE (186U)
/*******************************************************************************
* Prototypes
******************************************************************************/
/* Verify firmware, return true if pass. */
static bool GT911_VerifyFirmware(const uint8_t *firmware);
static uint8_t GT911_GetFirmwareCheckSum(const uint8_t *firmware);
/*******************************************************************************
* Variables
******************************************************************************/
/*******************************************************************************
* Code
******************************************************************************/
static uint8_t GT911_GetFirmwareCheckSum(const uint8_t *firmware)
{
uint8_t sum = 0;
uint16_t i = 0;
for (i = 0; i < GT911_CONFIG_SIZE - 2U; i++)
{
sum += (*firmware);
firmware++;
}
return (~sum + 1U);
}
static bool GT911_VerifyFirmware(const uint8_t *firmware)
{
return ((firmware[GT911_REG_CONFIG_VERSION - GT911_CONFIG_ADDR] != 0U) &&
(GT911_GetFirmwareCheckSum(firmware) == firmware[GT911_CONFIG_SIZE - 2U]));
}
status_t GT911_Init(gt911_handle_t *handle, const gt911_config_t *config)
{
status_t status;
uint32_t deviceID;
uint8_t gt911Config[GT911_CONFIG_SIZE];
assert(NULL != handle);
(void)memset(handle, 0, sizeof(*handle));
handle->I2C_SendFunc = config->I2C_SendFunc;
handle->I2C_ReceiveFunc = config->I2C_ReceiveFunc;
handle->timeDelayMsFunc = config->timeDelayMsFunc;
handle->pullResetPinFunc = config->pullResetPinFunc;
/* Reset the panel and set the I2C address mode. */
config->intPinFunc(kGT911_IntPinPullDown);
config->pullResetPinFunc(false);
/* >= 10ms. */
handle->timeDelayMsFunc(20);
if (kGT911_I2cAddrAny == config->i2cAddrMode)
{
config->pullResetPinFunc(true);
/* >= 55ms */
handle->timeDelayMsFunc(55);
config->intPinFunc(kGT911_IntPinInput);
/* Try address 0 */
handle->i2cAddr = GT911_I2C_ADDRESS0;
status = handle->I2C_ReceiveFunc(handle->i2cAddr, GT911_REG_ID, GT911_REG_ADDR_SIZE, (uint8_t *)&deviceID, 4);
if (kStatus_Success != status)
{
/* Try address 1 */
handle->i2cAddr = GT911_I2C_ADDRESS1;
status =
handle->I2C_ReceiveFunc(handle->i2cAddr, GT911_REG_ID, GT911_REG_ADDR_SIZE, (uint8_t *)&deviceID, 4);
if (kStatus_Success != status)
{
return status;
}
}
}
else
{
if (kGT911_I2cAddrMode1 == config->i2cAddrMode)
{
config->intPinFunc(kGT911_IntPinPullUp);
handle->i2cAddr = GT911_I2C_ADDRESS1;
}
else
{
handle->i2cAddr = GT911_I2C_ADDRESS0;
}
/* >= 100us */
handle->timeDelayMsFunc(1);
config->pullResetPinFunc(true);
/* >= 5ms */
handle->timeDelayMsFunc(5);
config->intPinFunc(kGT911_IntPinPullDown);
/* >= 50ms */
handle->timeDelayMsFunc(50);
config->intPinFunc(kGT911_IntPinInput);
status = handle->I2C_ReceiveFunc(handle->i2cAddr, GT911_REG_ID, GT911_REG_ADDR_SIZE, (uint8_t *)&deviceID, 4);
if (kStatus_Success != status)
{
return status;
}
}
/* Verify the device. */
if (deviceID != 0x00313139U)
{
return kStatus_Fail;
}
/* Initialize the IC. */
status = handle->I2C_ReceiveFunc(handle->i2cAddr, GT911_CONFIG_ADDR, GT911_REG_ADDR_SIZE, gt911Config,
GT911_CONFIG_SIZE);
if (kStatus_Success != status)
{
return status;
}
/*
* GT911 driver gets the original firmware from touch panel control IC, modify
* the configuration, then set it to the IC again. The original firmware
* read from the touch IC must be correct, otherwise setting wrong firmware
* to the touch IC will break it.
*/
if (true != GT911_VerifyFirmware(gt911Config))
{
return kStatus_Fail;
}
handle->resolutionX = ((uint16_t)gt911Config[GT911_REG_XH - GT911_CONFIG_ADDR]) << 8U;
handle->resolutionX += gt911Config[GT911_REG_XL - GT911_CONFIG_ADDR];
handle->resolutionY = ((uint16_t)gt911Config[GT911_REG_YH - GT911_CONFIG_ADDR]) << 8U;
handle->resolutionY += gt911Config[GT911_REG_YL - GT911_CONFIG_ADDR];
gt911Config[GT911_REG_TOUCH_NUM - GT911_CONFIG_ADDR] = (config->touchPointNum) & 0x0FU;
gt911Config[GT911_REG_MODULE_SWITCH1 - GT911_CONFIG_ADDR] &= (uint8_t)(~GT911_MODULE_SWITCH_INT_MASK);
gt911Config[GT911_REG_MODULE_SWITCH1 - GT911_CONFIG_ADDR] |= (uint8_t)(config->intTrigMode);
gt911Config[GT911_CONFIG_SIZE - 2U] = GT911_GetFirmwareCheckSum(gt911Config);
gt911Config[GT911_CONFIG_SIZE - 1U] = 1U; /* Mark the firmware as valid. */
return handle->I2C_SendFunc(handle->i2cAddr, GT911_CONFIG_ADDR, GT911_REG_ADDR_SIZE, gt911Config,
GT911_CONFIG_SIZE);
}
status_t GT911_Deinit(gt911_handle_t *handle)
{
handle->pullResetPinFunc(false);
return kStatus_Success;
}
static status_t GT911_ReadRawTouchData(gt911_handle_t *handle, uint8_t *touchPointNum)
{
status_t status;
uint8_t gt911Stat;
status = handle->I2C_ReceiveFunc(handle->i2cAddr, GT911_REG_STAT, GT911_REG_ADDR_SIZE, &gt911Stat, 1);
if (kStatus_Success != status)
{
*touchPointNum = 0;
return status;
}
*touchPointNum = gt911Stat & GT911_STAT_POINT_NUMBER_MASK;
if (0U != (gt911Stat & GT911_STAT_BUF_MASK))
{
if (*touchPointNum > 0U)
{
status = handle->I2C_ReceiveFunc(handle->i2cAddr, GT911_REG_FIRST_POINT, GT911_REG_ADDR_SIZE,
(void *)handle->pointReg, (*touchPointNum) * sizeof(gt911_point_reg_t));
}
/* Must set the status register to 0 after read. */
gt911Stat = 0;
status = handle->I2C_SendFunc(handle->i2cAddr, GT911_REG_STAT, GT911_REG_ADDR_SIZE, &gt911Stat, 1);
}
return status;
}
status_t GT911_GetSingleTouch(gt911_handle_t *handle, int *touch_x, int *touch_y)
{
status_t status;
uint8_t touchPointNum;
status = GT911_ReadRawTouchData(handle, &touchPointNum);
if (kStatus_Success == status)
{
if (touchPointNum > 0U)
{
*touch_x =
(int)(uint16_t)((uint16_t)handle->pointReg[0].lowX + (((uint16_t)handle->pointReg[0].highX) << 8U));
*touch_y =
(int)(uint16_t)((uint16_t)handle->pointReg[0].lowY + (((uint16_t)handle->pointReg[0].highY) << 8U));
}
else
{
status = (status_t)kStatus_TOUCHPANEL_NotTouched;
}
}
else
{
status = kStatus_Fail;
}
return status;
}
status_t GT911_GetMultiTouch(gt911_handle_t *handle, uint8_t *touch_count, touch_point_t touch_array[])
{
status_t status;
uint32_t i;
uint8_t desiredTouchPointNum;
uint8_t actualTouchPointNum;
status = GT911_ReadRawTouchData(handle, &actualTouchPointNum);
if (kStatus_Success == status)
{
desiredTouchPointNum = *touch_count;
if (0U == actualTouchPointNum)
{
status = (status_t)kStatus_TOUCHPANEL_NotTouched;
}
else if (actualTouchPointNum > desiredTouchPointNum)
{
actualTouchPointNum = desiredTouchPointNum;
}
else
{
/* MISRA compatible. */
}
for (i = 0; i < actualTouchPointNum; i++)
{
touch_array[i].valid = true;
touch_array[i].touchID = handle->pointReg[i].id;
touch_array[i].x = handle->pointReg[i].lowX + (((uint16_t)handle->pointReg[i].highX) << 8U);
touch_array[i].y = handle->pointReg[i].lowY + (((uint16_t)handle->pointReg[i].highY) << 8U);
}
for (; i < desiredTouchPointNum; i++)
{
touch_array[i].valid = false;
}
}
else
{
status = kStatus_Fail;
}
*touch_count = actualTouchPointNum;
return status;
}
status_t GT911_GetResolution(gt911_handle_t *handle, int *resolutionX, int *resolutionY)
{
*resolutionX = (int)handle->resolutionX;
*resolutionY = (int)handle->resolutionY;
return kStatus_Success;
}
/*
* Copyright 2019-2020 NXP
* All rights reserved.
*
* SPDX-License-Identifier: BSD-3-Clause
*/
#ifndef _FSL_GT911_H_
#define _FSL_GT911_H_
#include "fsl_common.h"
/*
* Change Log:
*
* 1.0.3:
* - Fixed MISRA 2012 issues.
*
* 1.0.2:
* - Fixed the issue that INT pin is output low when using kGT911_I2cAddrAny.
*
* 1.0.1:
* - Update GT911_GetMultiTouch and GT911_GetSingleTouch to return
* kStatus_TOUCHPANEL_NotTouched when no touch happens.
*
* 1.0.0:
* - Initial version.
*/
/*!
* @addtogroup gt911
* @{
*/
/*******************************************************************************
* Definitions
******************************************************************************/
/*! @brief GT911 maximum number of simultaneously detected touches. */
#define GT911_MAX_TOUCHES (10U)
/*! @brief Error code definition. */
enum _touch_status
{
kStatus_TOUCHPANEL_NotTouched = MAKE_STATUS(kStatusGroup_TOUCH_PANEL, 0) /*!< No touch happen. */
};
/*! @brief Touch point definition. */
typedef struct
{
bool valid; /*!< Whether the touch point coordinate value is valid. */
uint8_t touchID; /*!< Id of the touch point. This numeric value stays constant between down and up event. */
uint16_t x; /*!< X coordinate of the touch point */
uint16_t y; /*!< Y coordinate of the touch point */
} touch_point_t;
/*! @brief gt911 I2C address mode.*/
typedef enum _gt911_i2c_addr_mode
{
kGT911_I2cAddrMode0, /*!< 7-bit address 0x5D, or 8-bit 0xBA/0xBB */
kGT911_I2cAddrMode1, /*!< 7-bit address 0x14, or 8-bit 0x28/0x29 */
kGT911_I2cAddrAny, /*!< Use 0x5D or 0x14, driver selects the right one to use,
this is used for the case that MCU could not pull
the INT pin level.
*/
} gt911_i2c_addr_mode_t;
/*! @brief gt911 interrupt pin mode.*/
typedef enum _gt911_int_pin_mode
{
kGT911_IntPinPullDown, /*!< Interrupt pin output pull down. */
kGT911_IntPinPullUp, /*!< Interrupt pin output pull up. */
kGT911_IntPinInput, /*!< Interrupt pin set to input mode. */
} gt911_int_pin_mode_t;
/*! @brief gt911 interrupt trigger mode.*/
typedef enum _gt911_int_trig_mode
{
kGT911_IntRisingEdge, /*!< Rising edge. */
kGT911_IntFallingEdge, /*!< Falling edge. */
kGT911_IntLowLevel, /*!< Low level. */
kGT911_IntHighLevel, /*!< High edge. */
} gt911_int_trig_mode_t;
typedef status_t (*gt911_i2c_send_func_t)(
uint8_t deviceAddress, uint32_t subAddress, uint8_t subaddressSize, const uint8_t *txBuff, uint8_t txBuffSize);
typedef status_t (*gt911_i2c_receive_func_t)(
uint8_t deviceAddress, uint32_t subAddress, uint8_t subaddressSize, uint8_t *rxBuff, uint8_t rxBuffSize);
typedef void (*gt911_int_pin_func_t)(gt911_int_pin_mode_t mode);
typedef void (*gt911_reset_pin_func_t)(bool pullUp);
/*! @brief gt911 configure structure.*/
typedef struct _gt911_point_reg
{
uint8_t id; /*!< Track ID. */
uint8_t lowX; /*!< Low byte of x coordinate. */
uint8_t highX; /*!< High byte of x coordinate. */
uint8_t lowY; /*!< Low byte of y coordinate. */
uint8_t highY; /*!< High byte of x coordinate. */
uint8_t lowSize; /*!< Low byte of point size. */
uint8_t highSize; /*!< High byte of point size. */
uint8_t reserved; /*!< Reserved. */
} gt911_point_reg_t;
/*! @brief gt911 configure structure.*/
typedef struct _gt911_config
{
gt911_i2c_send_func_t I2C_SendFunc; /*!< Function to send I2C data. */
gt911_i2c_receive_func_t I2C_ReceiveFunc; /*!< Function to receive I2C data. */
void (*timeDelayMsFunc)(uint32_t delayMs); /*!< Function to delay some MS. */
gt911_int_pin_func_t intPinFunc; /*!< Function to set interrupt pin to different mode. */
gt911_reset_pin_func_t pullResetPinFunc; /*!< Function to pull reset pin high or low. */
uint8_t touchPointNum; /*!< How many touch points to enable. */
gt911_i2c_addr_mode_t i2cAddrMode; /*!< I2C address mode. */
gt911_int_trig_mode_t intTrigMode; /*!< Interrupt trigger mode. */
} gt911_config_t;
/*! @brief gt911 driver structure.*/
typedef struct _gt911_handle
{
gt911_i2c_send_func_t I2C_SendFunc; /*!< Function to send I2C data. */
gt911_i2c_receive_func_t I2C_ReceiveFunc; /*!< Function to receive I2C data. */
void (*timeDelayMsFunc)(uint32_t delayMs); /*!< Function to delay some MS. */
gt911_reset_pin_func_t pullResetPinFunc; /*!< Function to pull reset pin high or low. */
gt911_point_reg_t pointReg[GT911_MAX_TOUCHES]; /*!< Buffer to receive touch point raw data. */
uint8_t touchPointNum; /*!< How many touch points to enable. */
uint8_t i2cAddr; /*!< I2C address. */
uint16_t resolutionX; /*!< Resolution. */
uint16_t resolutionY; /*!< Resolution. */
} gt911_handle_t;
/*******************************************************************************
* API
******************************************************************************/
#if defined(__cplusplus)
extern "C" {
#endif
/*!
* @brief Initialize the driver.
*
* @param[in] handle Pointer to the GT911 driver.
* @param[in] config Pointer to the configuration.
* @return Returns @ref kStatus_Success if succeeded, otherwise return error code.
*/
status_t GT911_Init(gt911_handle_t *handle, const gt911_config_t *config);
/*!
* @brief De-initialize the driver.
*
* @param[in] handle Pointer to the GT911 driver.
* @return Returns @ref kStatus_Success if succeeded, otherwise return error code.
*/
status_t GT911_Deinit(gt911_handle_t *handle);
/*!
* @brief Get single touch point coordinate.
*
* @param[in] handle Pointer to the GT911 driver.
* @param[out] touch_x X coordinate of the touch point.
* @param[out] touch_y Y coordinate of the touch point.
* @return Returns @ref kStatus_Success if succeeded, otherwise return error code.
*/
status_t GT911_GetSingleTouch(gt911_handle_t *handle, int *touch_x, int *touch_y);
/*!
* @brief Get multiple touch points coordinate.
*
* When calling this function, parameter @ref touch_count means the array size
* of @p touch_array. After the function returns, the @p touch_count means how
* many valid touch points there are in the @p touch_array.
*
* @param[in] handle Pointer to the GT911 driver.
* @param[in, out] touch_count The touch point number.
* @param[out] touch_array Array of touch points coordinate.
* @return Returns @ref kStatus_Success if succeeded, otherwise return error code.
*/
status_t GT911_GetMultiTouch(gt911_handle_t *handle, uint8_t *touch_count, touch_point_t touch_array[]);
/*!
* @brief Get touch IC resolution.
*
* Note the touch resolution might be different with display resolution.
*
* @param handle Pointer to the driver.
* @param touch_x X resolution.
* @param touch_y Y resolution.
* @return Returns @ref kStatus_Success if succeeded, otherwise return error code.
*/
status_t GT911_GetResolution(gt911_handle_t *handle, int *resolutionX, int *resolutionY);
#if defined(__cplusplus)
}
#endif
/*! @} */
#endif /* _FSL_GT911_H_ */
/*
* Copyright 2017, 2020-2021 NXP
* All rights reserved.
*
*
* SPDX-License-Identifier: BSD-3-Clause
*/
#include "fsl_video_common.h"
#if defined(SDK_OS_FREE_RTOS)
#include "FreeRTOS.h"
#include "task.h"
#endif
/*******************************************************************************
* Code
******************************************************************************/
bool VIDEO_IsYUV(video_pixel_format_t format)
{
if ((kVIDEO_PixelFormatYUYV == format) || (kVIDEO_PixelFormatYVYU == format) ||
(kVIDEO_PixelFormatUYVY == format) || (kVIDEO_PixelFormatVYUY == format) ||
(kVIDEO_PixelFormatXYVU == format) || (kVIDEO_PixelFormatXYUV == format))
{
return true;
}
else
{
return false;
}
}
void VIDEO_DelayMs(uint32_t ms)
{
#if defined(SDK_OS_FREE_RTOS)
TickType_t tick;
tick = ms * configTICK_RATE_HZ / 1000U;
tick = (0U == tick) ? 1U : tick;
vTaskDelay(tick);
#else
while (0U != (ms--))
{
SDK_DelayAtLeastUs(1000U, SystemCoreClock);
}
#endif
}
uint8_t VIDEO_GetPixelSizeBits(video_pixel_format_t pixelFormat)
{
uint8_t ret;
switch (pixelFormat)
{
case kVIDEO_PixelFormatXRGB8888:
case kVIDEO_PixelFormatRGBX8888:
case kVIDEO_PixelFormatXBGR8888:
case kVIDEO_PixelFormatBGRX8888:
case kVIDEO_PixelFormatXYUV:
case kVIDEO_PixelFormatXYVU:
ret = 32;
break;
case kVIDEO_PixelFormatRGB888:
case kVIDEO_PixelFormatBGR888:
ret = 24;
break;
case kVIDEO_PixelFormatRGB565:
case kVIDEO_PixelFormatBGR565:
case kVIDEO_PixelFormatXRGB1555:
case kVIDEO_PixelFormatRGBX5551:
case kVIDEO_PixelFormatXBGR1555:
case kVIDEO_PixelFormatBGRX5551:
case kVIDEO_PixelFormatXRGB4444:
case kVIDEO_PixelFormatRGBX4444:
case kVIDEO_PixelFormatXBGR4444:
case kVIDEO_PixelFormatBGRX4444:
case kVIDEO_PixelFormatYUYV:
case kVIDEO_PixelFormatYVYU:
case kVIDEO_PixelFormatUYVY:
case kVIDEO_PixelFormatVYUY:
ret = 16;
break;
default:
ret = 0;
break;
}
return ret;
}
status_t VIDEO_RINGBUF_Init(video_ringbuf_t *ringbuf, void **buf, uint32_t size)
{
assert(ringbuf);
ringbuf->rear = 0;
ringbuf->front = 0;
ringbuf->size = size;
ringbuf->buf = buf;
return kStatus_Success;
}
status_t VIDEO_RINGBUF_Get(video_ringbuf_t *ringbuf, void **item)
{
uint32_t front_next;
/* To fix IAR Pa082 warning. */
uint32_t rear = ringbuf->rear;
uint32_t front = ringbuf->front;
if (rear != front)
{
*item = ringbuf->buf[ringbuf->front];
/*
* Here don't use ringbuf->front = (ringbuf->front + 1) % ringbuf->size,
* because mod operation might be slow.
*/
front_next = (ringbuf->front + 1U);
/* Use two steps to make sure ringbuf->front is always a valid value. */
ringbuf->front = (front_next == ringbuf->size) ? 0UL : front_next;
return kStatus_Success;
}
else
{
return kStatus_Fail;
}
}
status_t VIDEO_RINGBUF_Put(video_ringbuf_t *ringbuf, void *item)
{
/*
* Here don't use ringbuf->rear = (ringbuf->rear + 1) % ringbuf->size,
* because mod operation might be slow.
*/
uint32_t rear_next = ringbuf->rear + 1U;
rear_next = (rear_next == ringbuf->size) ? 0U : rear_next;
if (rear_next != ringbuf->front)
{
ringbuf->buf[ringbuf->rear] = item;
ringbuf->rear = rear_next;
return kStatus_Success;
}
/* No room. */
else
{
return kStatus_Fail;
}
}
uint32_t VIDEO_RINGBUF_GetLength(video_ringbuf_t *ringbuf)
{
uint32_t ret;
/* To fix IAR Pa082 warning. */
uint32_t rear = ringbuf->rear;
uint32_t front = ringbuf->front;
ret = (rear + ringbuf->size) - front;
if (ret >= ringbuf->size)
{
ret -= ringbuf->size;
}
return ret;
}
bool VIDEO_RINGBUF_IsEmpty(video_ringbuf_t *ringbuf)
{
/* To fix IAR Pa082 warning. */
uint32_t rear = ringbuf->rear;
uint32_t front = ringbuf->front;
if (rear == front)
{
return true;
}
else
{
return false;
}
}
bool VIDEO_RINGBUF_IsFull(video_ringbuf_t *ringbuf)
{
uint32_t rear = ringbuf->rear;
uint32_t front = ringbuf->front;
rear++;
if (rear >= ringbuf->size)
{
rear = 0;
}
if (rear == front)
{
return true;
}
else
{
return false;
}
}
status_t VIDEO_MEMPOOL_Init(video_mempool_t *mempool, void *initMem, uint32_t size, uint32_t count)
{
(void)memset(mempool, 0, sizeof(video_mempool_t));
while (0U != (count--))
{
VIDEO_MEMPOOL_Put(mempool, initMem);
initMem = &((uint8_t *)initMem)[size];
}
return kStatus_Success;
}
void VIDEO_MEMPOOL_InitEmpty(video_mempool_t *mempool)
{
mempool->pool = NULL;
mempool->cnt = 0;
}
void VIDEO_MEMPOOL_Put(video_mempool_t *mempool, void *mem)
{
*(void **)mem = mempool->pool;
mempool->pool = mem;
mempool->cnt++;
}
void *VIDEO_MEMPOOL_Get(video_mempool_t *mempool)
{
void *mem = mempool->pool;
if (NULL != mem)
{
mempool->cnt--;
mempool->pool = *(void **)mem;
}
return mem;
}
uint32_t VIDEO_MEMPOOL_GetCount(video_mempool_t *mempool)
{
return mempool->cnt;
}
/*
* Copyright 2017, 2020-2021 NXP
* All rights reserved.
*
*
* SPDX-License-Identifier: BSD-3-Clause
*/
#ifndef _FSL_VIDEO_COMMON_H_
#define _FSL_VIDEO_COMMON_H_
#include "fsl_common.h"
/*
* Change log:
*
* 1.0.5
* - Fix IAR Pa082 warning.
*
* 1.0.4
* - Add LUT8 definition.
*
* 1.0.3
* - Add RAW8 definition.
*
* 1.0.2
* - Fixed MISRA-C 2012 issues.
*
* 1.0.1
* - Update the VIDEO_DelayMs for bare metal.
*
* 1.0.0
* - Initial version
*/
/*******************************************************************************
* Definitions
******************************************************************************/
/*! @brief Pixel format FOURCC. */
#define FSL_VIDEO_FOURCC(a, b, c, d) \
((uint32_t)(a) | ((uint32_t)(b) << 8U) | ((uint32_t)(c) << 16U) | ((uint32_t)(d) << 24U))
/*! @brief Macro to define resolution. */
#define FSL_VIDEO_RESOLUTION(width, height) ((uint32_t)(width) | ((uint32_t)(height) << 16U))
#define FSL_VIDEO_EXTRACT_WIDTH(resolution) ((uint16_t)((resolution)&0xFFFFU))
#define FSL_VIDEO_EXTRACT_HEIGHT(resolution) ((uint16_t)((resolution) >> 16U))
/*! @brief Pixel format definition. */
typedef enum _video_pixel_format
{
/* RAW */
kVIDEO_PixelFormatRAW8 = FSL_VIDEO_FOURCC('G', 'R', 'B', 'G'), /*!< RAW8, GRBG. */
/* LUT/palette */
kVIDEO_PixelFormatLUT8 = FSL_VIDEO_FOURCC('L', 'U', 'T', '8'), /*!< 8-bit Indexed Color. */
/* RGB */
kVIDEO_PixelFormatXRGB8888 = FSL_VIDEO_FOURCC('X', 'R', '2', '4'), /*!< 32-bit XRGB8888. */
kVIDEO_PixelFormatRGBX8888 = FSL_VIDEO_FOURCC('R', 'X', '2', '4'), /*!< 32-bit RGBX8888. */
kVIDEO_PixelFormatXBGR8888 = FSL_VIDEO_FOURCC('X', 'B', '2', '4'), /*!< 32-bit XBGR8888. */
kVIDEO_PixelFormatBGRX8888 = FSL_VIDEO_FOURCC('B', 'X', '2', '4'), /*!< 32-bit BGRX8888. */
kVIDEO_PixelFormatRGB888 = FSL_VIDEO_FOURCC('R', 'G', '2', '4'), /*!< 24-bit RGB888. */
kVIDEO_PixelFormatBGR888 = FSL_VIDEO_FOURCC('B', 'G', '2', '4'), /*!< 24-bit BGR888. */
kVIDEO_PixelFormatRGB565 = FSL_VIDEO_FOURCC('R', 'G', '1', '6'), /*!< 16-bit RGB565. */
kVIDEO_PixelFormatBGR565 = FSL_VIDEO_FOURCC('B', 'G', '1', '6'), /*!< 16-bit BGR565. */
kVIDEO_PixelFormatXRGB1555 = FSL_VIDEO_FOURCC('X', 'R', '1', '5'), /*!< 16-bit XRGB1555. */
kVIDEO_PixelFormatRGBX5551 = FSL_VIDEO_FOURCC('R', 'X', '1', '5'), /*!< 16-bit RGBX5551. */
kVIDEO_PixelFormatXBGR1555 = FSL_VIDEO_FOURCC('X', 'B', '1', '5'), /*!< 16-bit XBGR1555. */
kVIDEO_PixelFormatBGRX5551 = FSL_VIDEO_FOURCC('B', 'X', '1', '5'), /*!< 16-bit BGRX5551. */
kVIDEO_PixelFormatXRGB4444 = FSL_VIDEO_FOURCC('X', 'R', '1', '2'), /*!< 16-bit XRGB4444. */
kVIDEO_PixelFormatRGBX4444 = FSL_VIDEO_FOURCC('R', 'X', '1', '2'), /*!< 16-bit RGBX4444. */
kVIDEO_PixelFormatXBGR4444 = FSL_VIDEO_FOURCC('X', 'B', '1', '2'), /*!< 16-bit XBGR4444. */
kVIDEO_PixelFormatBGRX4444 = FSL_VIDEO_FOURCC('B', 'X', '1', '2'), /*!< 16-bit BGRX4444. */
/* YUV. */
kVIDEO_PixelFormatYUYV = FSL_VIDEO_FOURCC('Y', 'U', 'Y', 'V'), /*!< YUV422, Y-U-Y-V. */
kVIDEO_PixelFormatYVYU = FSL_VIDEO_FOURCC('Y', 'V', 'Y', 'U'), /*!< YUV422, Y-V-Y-U. */
kVIDEO_PixelFormatUYVY = FSL_VIDEO_FOURCC('U', 'Y', 'V', 'Y'), /*!< YUV422, U-Y-V-Y. */
kVIDEO_PixelFormatVYUY = FSL_VIDEO_FOURCC('V', 'Y', 'U', 'Y'), /*!< YUV422, V-Y-U-Y. */
kVIDEO_PixelFormatXYUV = FSL_VIDEO_FOURCC('X', 'Y', 'U', 'V'), /*!< YUV444, X-Y-U-V. */
kVIDEO_PixelFormatXYVU = FSL_VIDEO_FOURCC('X', 'Y', 'V', 'U'), /*!< YUV444, X-Y-V-U. */
} video_pixel_format_t;
/*! @brief Resolution definition. */
typedef enum _video_resolution
{
kVIDEO_ResolutionVGA = FSL_VIDEO_RESOLUTION(640, 480), /*!< VGA, 640 * 480 */
kVIDEO_ResolutionQVGA = FSL_VIDEO_RESOLUTION(320, 240), /*!< QVGA, 320 * 240 */
kVIDEO_ResolutionQQVGA = FSL_VIDEO_RESOLUTION(160, 120), /*!< QQVGA, 160 * 120 */
kVIDEO_ResolutionCIF = FSL_VIDEO_RESOLUTION(352, 288), /*!< CIF, 352 * 288 */
kVIDEO_ResolutionQCIF = FSL_VIDEO_RESOLUTION(176, 144), /*!< QCIF, 176 * 144 */
kVIDEO_ResolutionQQCIF = FSL_VIDEO_RESOLUTION(88, 72), /*!< QQCIF, 88 * 72 */
kVIDEO_Resolution720P = FSL_VIDEO_RESOLUTION(1280, 720), /*!< 720P, 1280 * 720 */
kVIDEO_Resolution1080P = FSL_VIDEO_RESOLUTION(1920, 1080), /*!< 1080P, 1920 * 1280*/
kVIDEO_ResolutionWXGA = FSL_VIDEO_RESOLUTION(1280, 800), /*!< WXGA, 1280 * 800 */
} video_resolution_t;
/*!
* @brief Ring buffer structure.
*
* There is one empty room reserved in the ring buffer, used to distinguish
* whether the ring buffer is full or empty. When rear equals front, it is empty;
* when rear+1 equals front, it is full.
*/
typedef struct
{
volatile uint32_t rear; /*!< Pointer to save the incoming item. */
volatile uint32_t front; /*!< Pointer to read out the item. */
void *volatile *buf; /*!< Memory to the ring buffer. */
uint32_t size; /*!< Ring buffer total size. */
} video_ringbuf_t;
/*!
* @brief Memory pool structure.
*/
typedef struct
{
void *volatile pool; /*!< Pointer to the pool. */
volatile uint32_t cnt; /*!< Count of memory blocks in the pool. */
} video_mempool_t;
/*******************************************************************************
* API
******************************************************************************/
#if defined(__cplusplus)
extern "C" {
#endif
/*!
* @name Common
* @{
*/
/*!
* @brief Check the pixel format is YUV or not.
*
* @param format Pixel format.
*/
bool VIDEO_IsYUV(video_pixel_format_t format);
/*!
* @brief Delay the specific time.
*
* @param ms How many milli-second to delay.
*/
void VIDEO_DelayMs(uint32_t ms);
/*!
* @brief Get the pixel size in bits.
*
* @param pixelFormat The pixel format.
* @return Bits per pixel.
*/
uint8_t VIDEO_GetPixelSizeBits(video_pixel_format_t pixelFormat);
/* @} */
/*!
* @name Ring buffer.
* @{
*/
/*!
* @brief Initializes ring buffer.
*
* @param ringbuf Pointer to the ring buffer handle.
* @param buf Memory to save the items.
* @param size Size of the @p buf.
* @return Returns @ref kStatus_Success if initialize success, otherwise returns
* error code.
*/
status_t VIDEO_RINGBUF_Init(video_ringbuf_t *ringbuf, void **buf, uint32_t size);
/*!
* @brief Get one item from the ring buffer.
*
* @param ringbuf Pointer to the ring buffer handle.
* @param item Memory to save the item.
* @return Returns @ref kStatus_Success if get success, otherwise returns
* error code.
*/
status_t VIDEO_RINGBUF_Get(video_ringbuf_t *ringbuf, void **item);
/*!
* @brief Put one item to the ring buffer.
*
* @param ringbuf Pointer to the ring buffer handle.
* @param item The new item to save.
* @return Returns @ref kStatus_Success if put success, otherwise returns
* error code.
*/
status_t VIDEO_RINGBUF_Put(video_ringbuf_t *ringbuf, void *item);
/*!
* @brief Get current count of items in the ring buffer.
*
* @param ringbuf Pointer to the ring buffer handle.
* @return Returns the item count.
*/
uint32_t VIDEO_RINGBUF_GetLength(video_ringbuf_t *ringbuf);
/*!
* @brief Check whether the ring buffer is empty.
*
* @param ringbuf Pointer to the ring buffer handle.
* @return Returns true if the ring buffer is empty, otherwise returns false.
*/
bool VIDEO_RINGBUF_IsEmpty(video_ringbuf_t *ringbuf);
/*!
* @brief Check whether the ring buffer is full.
*
* @param ringbuf Pointer to the ring buffer handle.
* @return Returns true if the ring buffer is full, otherwise returns false.
*/
bool VIDEO_RINGBUF_IsFull(video_ringbuf_t *ringbuf);
/* @} */
/*!
* @name Memory Pool
*
* User can put memory block to the pool, or get memory block from the pool.
* There is no count limitation to put memory block in to the pool. The memory
* content in the pool might be modified.
*
* The memory block should be 4-byte aligned, and the dividable by 4-byte.
*
* @{
*/
/*!
* @brief Initializes memory pool.
*
* Initializes memory pool. Initial memory blocks in the memory pool is optional.
* If initial blocks are used, user should specify the initial block size and count.
*
* @param mempool Pointer to the memory pool handle.
* @param initMem Initial memory blocks to saved in the pool.
* @param size Every memory block's size (bytes) in the @p initMem.
* @param count Number of memory blocks @p initMem.
* @return Returns @ref kStatus_Success if initialize success, otherwise returns
* error code.
*/
status_t VIDEO_MEMPOOL_Init(video_mempool_t *mempool, void *initMem, uint32_t size, uint32_t count);
/*!
* @brief Create an empty memory pool.
*
* @param mempool Pointer to the memory pool handle.
*/
void VIDEO_MEMPOOL_InitEmpty(video_mempool_t *mempool);
/*!
* @brief Put memory block in the pool.
*
* @param mempool Pointer to the memory pool handle.
* @param mem Pointer to the memory block.
*/
void VIDEO_MEMPOOL_Put(video_mempool_t *mempool, void *mem);
/*!
* @brief Get memory block in the pool.
*
* @param mempool Pointer to the memory pool handle.
* @return The memory block get from pool. If the pool is empty, returns NULL.
*/
void *VIDEO_MEMPOOL_Get(video_mempool_t *mempool);
/*!
* @brief How many memory blocks in the pool.
*
* @param mempool Pointer to the memory pool handle.
* @return The memory block count in the pool
*/
uint32_t VIDEO_MEMPOOL_GetCount(video_mempool_t *mempool);
/* @} */
#if defined(__cplusplus)
}
#endif
#endif /* _FSL_VIDEO_COMMON_H_ */
......@@ -6,6 +6,7 @@ path = [cwd + '/CMSIS/Include',cwd + '/MIMXRT1060', cwd + '/MIMXRT1060/drivers']
src = Split('''
MIMXRT1060/system_MIMXRT1062.c
MIMXRT1060/drivers/fsl_common.c
MIMXRT1060/drivers/fsl_common_arm.c
MIMXRT1060/drivers/fsl_clock.c
MIMXRT1060/drivers/fsl_cache.c
''')
......@@ -53,6 +54,12 @@ if GetDepend(['BSP_USING_SDRAM']):
if GetDepend(['BSP_USING_LCD']):
src += ['MIMXRT1060/drivers/fsl_elcdif.c']
if GetDepend(['DEMO_PANEL_RK043FN02H']):
src += ['MIMXRT1060/drivers/fsl_ft5406_rt.c']
if GetDepend(['DEMO_PANEL_RK043FN66HS']):
src += ['MIMXRT1060/drivers/fsl_video_common.c', 'MIMXRT1060/drivers/fsl_gt911.c']
if GetDepend(['BSP_USING_CACHE']):
src += ['MIMXRT1060/drivers/fsl_cache.c']
......
Markdown is supported
0% .
You are about to add 0 people to the discussion. Proceed with caution.
先完成此消息的编辑!
想要评论请 注册