diff --git a/apps/examples/lcd_test/example_lcd.c b/apps/examples/lcd_test/example_lcd.c index 8959aff4b9..a8163ee38b 100644 --- a/apps/examples/lcd_test/example_lcd.c +++ b/apps/examples/lcd_test/example_lcd.c @@ -116,7 +116,7 @@ static void test_put_area(void) fd = open(port, O_RDWR | O_SYNC, 0666); if (fd < 0) { printf("ERROR: Failed to open lcd port : %s error:%d\n", port, fd); - return -1; + return; } struct fb_videoinfo_s vinfo; ioctl(fd, LCDDEVIO_GETVIDEOINFO, (unsigned long)(uintptr_t)&vinfo); @@ -140,7 +140,7 @@ static void test_put_run(void) fd = open(port, O_RDWR | O_SYNC, 0666); if (fd < 0) { printf("ERROR: Failed to open lcd port : %s error:%d\n", port, fd); - return -1; + return; } struct lcddev_run_s run; run.planeno = 0; @@ -149,8 +149,8 @@ static void test_put_run(void) run.npixels = NOPIXELS; uint8_t spi_data[2 * NOPIXELS + 1]; - run.data = &spi_data; - for (i = 0; i <= (NOPIXELS * 2); i += 2) { + run.data = spi_data; + for (i = 0; i < (NOPIXELS * 2); i += 2) { spi_data[i + 1] = WHITE & 0X00FF; spi_data[i] = (WHITE & 0xFF00) >> 8; } @@ -167,7 +167,7 @@ static void test_clear(void) fd = open(port, O_RDWR | O_SYNC, 0666); if (fd < 0) { printf("ERROR: Failed to open lcd port : %s error:%d\n", port, fd); - return -1; + return; } struct fb_videoinfo_s vinfo; ioctl(fd, LCDDEVIO_GETVIDEOINFO, (unsigned long)(uintptr_t)&vinfo); @@ -187,7 +187,7 @@ static void test_init(void) fd = open(port, O_RDWR | O_SYNC, 0666); if (fd < 0) { printf("ERROR: Failed to open lcd port : %s error:%d\n", port, fd); - return -1; + return; } ioctl(fd, LCDDEVIO_INIT, &ret); close(fd); @@ -202,7 +202,7 @@ static void test_orientation(void) fd = open(port, O_RDWR | O_SYNC, 0666); if (fd < 0) { printf("ERROR: Failed to open lcd port : %s error:%d\n", port, fd); - return -1; + return; } ioctl(fd, LCDDEVIO_SETORIENTATION, LCD_RLANDSCAPE); @@ -257,4 +257,5 @@ int lcd_test_main(int argc, char *argv[]) sleep(1); count++; } + return 0; } diff --git a/os/arch/arm/src/amebasmart/Make.defs b/os/arch/arm/src/amebasmart/Make.defs index 991c05b1ac..0998cb2ff2 100644 --- a/os/arch/arm/src/amebasmart/Make.defs +++ b/os/arch/arm/src/amebasmart/Make.defs @@ -270,6 +270,9 @@ EXTRA_LIBS += ${TOPDIR}/board/rtl8730e/src/libs/lib_btgap.a #endif endif +ifeq ($(CONFIG_AMEBASMART_MIPI),y) +CHIP_CSRCS += amebasmart_mipi.c +endif ifeq ($(CONFIG_AMEBASMART_TRUSTZONE),y) #CHIP_CSRCS += amebasmart_nsc.c diff --git a/os/arch/arm/src/amebasmart/amebasmart_mipi.c b/os/arch/arm/src/amebasmart/amebasmart_mipi.c new file mode 100755 index 0000000000..63bac0f05f --- /dev/null +++ b/os/arch/arm/src/amebasmart/amebasmart_mipi.c @@ -0,0 +1,345 @@ +/**************************************************************************** + * + * Copyright 2024 Samsung Electronics All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * + ****************************************************************************/ + +/************************************************************************************ + * Included Files + ************************************************************************************/ + +#include + +#include +#include +#include +#include +#include +#include +#include +#include + +#include +#include +#include +#include +#include +#include + +#include "chip.h" +#include "PinNames.h" + +#undef mipierr +#undef mipiinfo +#if defined(CONFIG_DEBUG_MIPI) +#define mipiinfo(format, ...) printf(format, ##__VA_ARGS__) +#define mipierr(format, ...) printf(format, ##__VA_ARGS__) +#else +#define mipiinfo(format, ...) +#endif +#define mipierr(format, ...) printf(format, ##__VA_ARGS__) + +static u32 vo_freq; +static u32 send_cmd_done = 0; + +struct amebasmart_mipi_dsi_host_s { + struct mipi_dsi_host dsi_host; + MIPI_TypeDef *MIPIx; + MIPI_InitTypeDef *MIPI_InitStruct; +}; + +struct irq { + u32 num; + u32 data; + u32 priority; +}; + +/* Helpers */ +static void amebasmart_set_clock(void); +static void amebasmart_check_freq(struct lcd_data *data); +static void amebasmart_mipi_init_helper(FAR struct amebasmart_mipi_dsi_host_s *priv); +static void amebasmart_register_interrupt(void); + +/* MIPI methods */ +static void amebasmart_mipidsi_send_cmd(MIPI_TypeDef *MIPIx, u8 cmd, u8 payload_len, const u8 *para_list); +static int amebasmart_mipi_attach(FAR struct mipi_dsi_host *dsi_host, FAR struct mipi_dsi_device *dsi_device); +static int amebasmart_mipi_detach(FAR struct mipi_dsi_host *dsi_host, FAR struct mipi_dsi_device *dsi_device); +static int amebasmart_mipi_transfer(FAR struct mipi_dsi_host *dsi_host, FAR const struct mipi_dsi_msg *msg); + +/************************************************************************************ + * Private Data + ************************************************************************************/ +/*initialize the MIPI IRQ info*/ +struct irq mipi_irq_info = { + .num = MIPI_DSI_IRQ, + .data = (u32) MIPI, + .priority = INT_PRI_MIDDLE, +}; + +static const struct mipi_dsi_host_ops g_dsi_ops = { + .attach = amebasmart_mipi_attach, + .detach = amebasmart_mipi_detach, + .transfer = amebasmart_mipi_transfer, +}; + +MIPI_InitTypeDef MIPI_InitStruct_g; + +static struct amebasmart_mipi_dsi_host_s g_dsi_host = { + .dsi_host = { + &g_dsi_ops + }, + .MIPIx = MIPI, + .MIPI_InitStruct = &MIPI_InitStruct_g, +}; + +/***********Helpers ***********/ + +static void amebasmart_mipi_fill_buffer(FAR struct mipi_dsi_host *dsi_host) +{ + FAR struct amebasmart_mipi_dsi_host_s *priv = (FAR struct amebasmart_mipi_dsi_host_s *)dsi_host; + u32 vtotal, htotal_bits, bit_per_pixel, overhead_cycles, overhead_bits, total_bits; + switch (priv->MIPI_InitStruct->MIPI_VideoDataFormat) { + case MIPI_VIDEO_DATA_FORMAT_RGB565: + bit_per_pixel = 16; + break; + case MIPI_VIDEO_DATA_FORMAT_RGB666_PACKED: + bit_per_pixel = 18; + break; + case MIPI_VIDEO_DATA_FORMAT_RGB666_LOOSELY: + case MIPI_VIDEO_DATA_FORMAT_RGB888: + default: + bit_per_pixel = 24; + break; + } + priv->MIPI_InitStruct->MIPI_LaneNum = 2; + priv->MIPI_InitStruct->MIPI_FrameRate = MIPI_FRAME_RATE; + priv->MIPI_InitStruct->MIPI_HSA = MIPI_DSI_HSA * bit_per_pixel / 8; //- 10; /* here the unit is pixel but not us */ + if (priv->MIPI_InitStruct->MIPI_VideoModeInterface == MIPI_VIDEO_NON_BURST_MODE_WITH_SYNC_PULSES) { + priv->MIPI_InitStruct->MIPI_HBP = MIPI_DSI_HBP * bit_per_pixel / 8; //- 10; + } else { + priv->MIPI_InitStruct->MIPI_HBP = (MIPI_DSI_HSA + MIPI_DSI_HBP) * bit_per_pixel / 8; //-10 ; + } + priv->MIPI_InitStruct->MIPI_HACT = dsi_host->config.XPixels; + priv->MIPI_InitStruct->MIPI_HFP = MIPI_DSI_HFP * bit_per_pixel / 8; //-12; + priv->MIPI_InitStruct->MIPI_VSA = MIPI_DSI_VSA; + priv->MIPI_InitStruct->MIPI_VBP = MIPI_DSI_VBP; + priv->MIPI_InitStruct->MIPI_VACT = dsi_host->config.YPixels; + priv->MIPI_InitStruct->MIPI_VFP = MIPI_DSI_VFP; + vtotal = priv->MIPI_InitStruct->MIPI_VSA + priv->MIPI_InitStruct->MIPI_VBP + priv->MIPI_InitStruct->MIPI_VACT + priv->MIPI_InitStruct->MIPI_VFP; + htotal_bits = (MIPI_DSI_HSA + MIPI_DSI_HBP + priv->MIPI_InitStruct->MIPI_HACT + MIPI_DSI_HFP) * bit_per_pixel; + overhead_cycles = T_LPX + T_HS_PREP + T_HS_ZERO + T_HS_TRAIL + T_HS_EXIT; + overhead_bits = overhead_cycles * priv->MIPI_InitStruct->MIPI_LaneNum * 8; + total_bits = htotal_bits + overhead_bits; + priv->MIPI_InitStruct->MIPI_VideDataLaneFreq = priv->MIPI_InitStruct->MIPI_FrameRate * total_bits * vtotal / priv->MIPI_InitStruct->MIPI_LaneNum / Mhz + 20; + priv->MIPI_InitStruct->MIPI_LineTime = (priv->MIPI_InitStruct->MIPI_VideDataLaneFreq * Mhz) / 8 / priv->MIPI_InitStruct->MIPI_FrameRate / vtotal; + priv->MIPI_InitStruct->MIPI_BllpLen = priv->MIPI_InitStruct->MIPI_LineTime / 2; + + if (MIPI_DSI_HSA + MIPI_DSI_HBP + dsi_host->config.XPixels + MIPI_DSI_HFP < (512 + MIPI_DSI_RTNI * 16)) { + dbg("!!ERROR!!, LCM NOT SUPPORT\n"); + } + if (priv->MIPI_InitStruct->MIPI_LineTime * priv->MIPI_InitStruct->MIPI_LaneNum < total_bits / 8) { + dbg("!!ERROR!!, LINE TIME TOO SHORT!\n"); + } + if (priv->MIPI_InitStruct->MIPI_VideDataLaneFreq * 2 / 24 >= vo_freq) { + dbg("!!ERROR!!, VO CLK too slow!\n"); + } + dbg("DataLaneFreq: %d, LineTime: %d\n", priv->MIPI_InitStruct->MIPI_VideDataLaneFreq, priv->MIPI_InitStruct->MIPI_LineTime); +} + +static void amebasmart_mipi_init_helper(FAR struct amebasmart_mipi_dsi_host_s *priv) +{ + amebasmart_check_freq(&(priv->dsi_host.config)); + amebasmart_set_clock(); + + MIPI_StructInit(priv->MIPI_InitStruct); + amebasmart_mipi_fill_buffer(&(priv->dsi_host)); + MIPI_Init(priv->MIPIx, priv->MIPI_InitStruct); + + MIPI_DSI_TO1_Set(priv->MIPIx, DISABLE, 0); + MIPI_DSI_TO2_Set(priv->MIPIx, ENABLE, 0x7FFFFFFF); + MIPI_DSI_TO3_Set(priv->MIPIx, DISABLE, 0); + + amebasmart_register_interrupt(); + MIPI_DSI_INT_Config(priv->MIPIx, DISABLE, ENABLE, FALSE); +} + +static void amebasmart_mipidsi_send_cmd(MIPI_TypeDef *MIPIx, u8 cmd, u8 payload_len, const u8 *para_list) +{ + u32 word0, word1, addr, idx; + u8 cmd_addr[128]; + if (payload_len == 0) { + MIPI_DSI_CMD_Send(MIPIx, MIPI_DSI_DCS_SHORT_WRITE, cmd, 0); + return; + } else if (payload_len == 1) { + MIPI_DSI_CMD_Send(MIPIx, MIPI_DSI_DCS_SHORT_WRITE_PARAM, cmd, para_list[0]); + return; + } + + cmd_addr[0] = cmd; + for (idx = 0; idx < payload_len; idx++) { + cmd_addr[idx + 1] = para_list[idx]; + } + + payload_len = payload_len + 1; + + /* the addr payload_len 1 ~ 8 is 0 */ + for (addr = 0; addr < (u32)(payload_len + 7) / 8; addr++) { + idx = addr * 8; + word0 = (cmd_addr[idx + 3] << 24) + (cmd_addr[idx + 2] << 16) + (cmd_addr[idx + 1] << 8) + cmd_addr[idx + 0]; + word1 = (cmd_addr[idx + 7] << 24) + (cmd_addr[idx + 6] << 16) + (cmd_addr[idx + 5] << 8) + cmd_addr[idx + 4]; + + MIPI_DSI_CMD_LongPkt_MemQWordRW(MIPIx, addr, &word0, &word1, FALSE); + } + + MIPI_DSI_CMD_Send(MIPIx, MIPI_DSI_DCS_LONG_WRITE, payload_len, 0); +} + +static void amebasmart_mipidsi_isr(void) +{ + MIPI_TypeDef *MIPIx = g_dsi_host.MIPIx; + u32 reg_val, reg_val2, reg_dphy_err; + + reg_val = MIPI_DSI_INTS_Get(MIPIx); + MIPI_DSI_INTS_Clr(MIPIx, reg_val); + + reg_val2 = MIPI_DSI_INTS_ACPU_Get(MIPIx); + MIPI_DSI_INTS_ACPU_Clr(MIPIx, reg_val2); + if (reg_val & MIPI_BIT_CMD_TXDONE) { + reg_val &= ~MIPI_BIT_CMD_TXDONE; + send_cmd_done = 1; + } + + if (reg_val & MIPI_BIT_ERROR) { + reg_dphy_err = MIPIx->MIPI_DPHY_ERR; + MIPIx->MIPI_DPHY_ERR = reg_dphy_err; + if (MIPIx->MIPI_CONTENTION_DETECTOR_AND_STOPSTATE_DT & MIPI_MASK_DETECT_ENABLE) { + MIPIx->MIPI_CONTENTION_DETECTOR_AND_STOPSTATE_DT &= ~MIPI_MASK_DETECT_ENABLE; + + MIPIx->MIPI_DPHY_ERR = reg_dphy_err; + MIPI_DSI_INTS_Clr(MIPIx, MIPI_BIT_ERROR); + } + + if (MIPIx->MIPI_DPHY_ERR == reg_dphy_err) { + dbg("LPTX Still Error\n"); + MIPI_DSI_INT_Config(MIPIx, ENABLE, DISABLE, FALSE); + } + reg_val &= ~MIPI_BIT_ERROR; + } + + if (reg_val) { + dbg("LPTX Error Occur: 0x%x\n", reg_val); + } + + if (reg_val2) { + dbg("error occured #\n"); + } +} + +static void amebasmart_check_freq(struct lcd_data *data) +{ + u32 totaly = MIPI_DSI_VSA + MIPI_DSI_VBP + MIPI_DSI_VFP + data->YPixels; + u32 totalx = MIPI_DSI_HSA + MIPI_DSI_HBP + MIPI_DSI_HFP + data->XPixels; + vo_freq = totaly * totalx * MIPI_FRAME_RATE / Mhz + 4; + dbg("vo_freq: %d\n", vo_freq); + assert_param(vo_freq < 67); +} + +static void amebasmart_set_clock(void) +{ + u32 PLLDiv = PLL_GET_NPLL_DIVN_SDM(PLL_BASE->PLL_NPPLL_CTRL1) + 2; + u32 PLL_CLK = XTAL_ClkGet() * PLLDiv; + u32 mipi_ckd = PLL_CLK / vo_freq - 1; + HAL_WRITE32(SYSTEM_CTRL_BASE_LP, REG_LSYS_CKD_GRP0, (HAL_READ32(SYSTEM_CTRL_BASE_LP, REG_LSYS_CKD_GRP0) & ~LSYS_MASK_CKD_MIPI) | LSYS_CKD_MIPI(mipi_ckd)); + HAL_WRITE32(SYSTEM_CTRL_BASE_LP, REG_LSYS_CKD_GRP0, (HAL_READ32(SYSTEM_CTRL_BASE_LP, REG_LSYS_CKD_GRP0) & ~LSYS_MASK_CKD_HPERI) | LSYS_CKD_HPERI(3)); + + RCC_PeriphClockCmd(APBPeriph_NULL, APBPeriph_HPERI_CLOCK, ENABLE); + RCC_PeriphClockCmd(APBPeriph_LCDC, APBPeriph_LCDCMIPI_CLOCK, ENABLE); + +} + +static void amebasmart_register_interrupt(void) +{ + InterruptDis(mipi_irq_info.num); + InterruptUnRegister(mipi_irq_info.num); + InterruptRegister((IRQ_FUN) amebasmart_mipidsi_isr, mipi_irq_info.num, (u32) mipi_irq_info.data, mipi_irq_info.priority); + InterruptEn(mipi_irq_info.num, mipi_irq_info.priority); +} + +void mipidsi_mode_switch(bool do_enable){ + if(do_enable){ + MIPI_DSI_Mode_Switch(g_dsi_host.MIPIx, ENABLE); + } + else{ + MIPI_DSI_Mode_Switch(g_dsi_host.MIPIx, DISABLE); + } +} + +void mipidsi_acpu_reg_clear(void){ + MIPI_DSI_INTS_ACPU_Clr(g_dsi_host.MIPIx, MIPI_DSI_INTS_ACPU_Get(g_dsi_host.MIPIx)); +} + +/************************************************************************************ + * Private Functions + ************************************************************************************/ +static int amebasmart_mipi_attach(FAR struct mipi_dsi_host *dsi_host, FAR struct mipi_dsi_device *dsi_device) +{ + return 0; +} + +static int amebasmart_mipi_detach(FAR struct mipi_dsi_host *dsi_host, FAR struct mipi_dsi_device *dsi_device) +{ + return 0; +} + +static int amebasmart_mipi_transfer(FAR struct mipi_dsi_host *dsi_host, FAR const struct mipi_dsi_msg *msg) +{ + FAR struct amebasmart_mipi_dsi_host_s *priv = (FAR struct amebasmart_mipi_dsi_host_s *)dsi_host; + struct mipi_dsi_packet packet; + int count = 0; + + if(msg->type == MIPI_DSI_END_OF_TRANSMISSION){ + MIPI_DSI_INT_Config(g_dsi_host.MIPIx, DISABLE, DISABLE, FALSE); + return OK; + } + + int ret = mipi_dsi_create_packet(&packet, msg); + if (ret != OK) { + return ret; + } + send_cmd_done = 0; + if (mipi_dsi_packet_format_is_short(msg->type)) { + if (packet.header[1] == 0) { + amebasmart_mipidsi_send_cmd(priv->MIPIx, packet.header[0], 0, NULL); + } else { + amebasmart_mipidsi_send_cmd(priv->MIPIx, packet.header[0], 1, packet.header + 1); + } + } else { + amebasmart_mipidsi_send_cmd(priv->MIPIx, packet.header[0], packet.payload_length, packet.payload); + } + while(send_cmd_done != 1){ + DelayMs(1); + } + return OK; +} + +struct mipi_dsi_host *amebasmart_mipi_dsi_host_initialize(struct lcd_data *config) +{ + FAR struct amebasmart_mipi_dsi_host_s *priv = NULL; + priv = &g_dsi_host; + priv->dsi_host.config = *config; + amebasmart_mipi_init_helper(priv); + mipi_dsi_host_register(&priv->dsi_host); + return (struct mipi_dsi_host *)priv; +} diff --git a/os/board/rtl8730e/src/Make.defs b/os/board/rtl8730e/src/Make.defs index 72f9ea5209..12417638e5 100644 --- a/os/board/rtl8730e/src/Make.defs +++ b/os/board/rtl8730e/src/Make.defs @@ -59,3 +59,8 @@ endif ifeq ($(CONFIG_LCD_ST7789), y) CSRCS += rtl8730e_st7789.c endif + +ifeq ($(CONFIG_LCD_ST7701), y) +CSRCS += rtl8730e_st7701.c +endif + diff --git a/os/board/rtl8730e/src/rtl8730e_boot.c b/os/board/rtl8730e/src/rtl8730e_boot.c index 10f112072a..9a132b421e 100644 --- a/os/board/rtl8730e/src/rtl8730e_boot.c +++ b/os/board/rtl8730e/src/rtl8730e_boot.c @@ -407,6 +407,9 @@ void board_initialize(void) #ifdef CONFIG_LCD_ST7789 rtl8730_st7789_initialize(); #endif +#ifdef CONFIG_LCD_ST7701 + rtl8730_st7701_initialize(); +#endif #ifdef CONFIG_WATCHDOG amebasmart_wdg_initialize(CONFIG_WATCHDOG_DEVPATH, 5000); diff --git a/os/board/rtl8730e/src/rtl8730e_st7701.c b/os/board/rtl8730e/src/rtl8730e_st7701.c new file mode 100755 index 0000000000..da089dbbc6 --- /dev/null +++ b/os/board/rtl8730e/src/rtl8730e_st7701.c @@ -0,0 +1,249 @@ +/**************************************************************************** + * + * Copyright 2024 Samsung Electronics All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * + ****************************************************************************/ +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include +#include +#include +#include "objects.h" +#include "PinNames.h" +#include "gpio_api.h" + +#define MIPI_GPIO_RESET_PIN _PA_14 +#define PIN_LOW 0 +#define PIN_HIGH 1 +#define LCD_LAYER 0 + +static void rtl8730_st7701_lcd_init(void); +static void rtl8730_st7701_gpio_reset(void); +static void rtl8730_st7701_cache_invalidate(u32 *buffer, int size); +static void rtl8730_st7701_lcd_reload(void); +static void rtl8730_st7701_lcd_layer_enable(int layer, bool enable); +static void rtl8730_st7701_lcd_put_area(u8 *lcd_img_buffer, u32 x_start, u32 y_start, u32 x_end, u32 y_end); +static void rtl8730_st7701_enable_lcdc(void); +static void rtl8730e_st7701_register_lcdc_isr(void); +FAR void mipidsi_mode_switch(bool do_enable); +FAR void mipidsi_acpu_reg_clear(void); +FAR struct mipi_dsi_host *amebasmart_mipi_dsi_host_initialize(struct lcd_data *config); +FAR struct mipi_dsi_device *mipi_dsi_device_register(FAR struct mipi_dsi_host *host, FAR const char *name, int channel); +FAR struct lcd_dev_s *st7701_lcdinitialize(FAR struct mipi_dsi_device *dsi, struct st7701_config_s *config); + +struct st7701_config_s g_rtl8730_st7701_config_s = { + .init = rtl8730_st7701_lcd_init, + .reset = rtl8730_st7701_gpio_reset, + .cache_invalidate = rtl8730_st7701_cache_invalidate, + .lcd_reload = rtl8730_st7701_lcd_reload, + .lcd_enable = rtl8730_st7701_enable_lcdc, + .lcd_layer_enable = rtl8730_st7701_lcd_layer_enable, + .lcd_put_area = rtl8730_st7701_lcd_put_area, +}; + +struct irq { + u32 num; + u32 data; + u32 priority; +}; + +LCDC_TypeDef *pLCDC = LCDC; +LCDC_InitTypeDef lcdc_init_struct; +static u32 UnderFlowCnt = 0; + +struct irq lcdc_irq_info = { + .num = LCDC_IRQ, + .data = (u32) LCDC, + .priority = INT_PRI_MIDDLE, +}; + +extern struct irq mipi_irq_info; +u8 *lcd_img_buffer1 = (u8 *)(DDR_BASE + LCDC_IMG_BUF_OFFSET2 + LCDC_IMG_BUF_SIZE); + +static void LcdcInitValues(struct lcd_data config) +{ + LCDC_StructInit(&lcdc_init_struct); + lcdc_init_struct.LCDC_ImageWidth = config.XPixels; + lcdc_init_struct.LCDC_ImageHeight = config.YPixels; + for (u8 idx = 0; idx < LCDC_LAYER_MAX_NUM; idx++) { + lcdc_init_struct.layerx[idx].LCDC_LayerImgFormat = LCDC_LAYER_IMG_FORMAT_RGB565; + lcdc_init_struct.layerx[idx].LCDC_LayerImgBaseAddr = (u32) lcd_img_buffer1; + lcdc_init_struct.layerx[idx].LCDC_LayerHorizontalStart = 1; + lcdc_init_struct.layerx[idx].LCDC_LayerHorizontalStop = config.XPixels; + lcdc_init_struct.layerx[idx].LCDC_LayerVerticalStart = 1; + lcdc_init_struct.layerx[idx].LCDC_LayerVerticalStop = config.YPixels; + } +} + +static void rtl8730_st7701_lcd_init(void) +{ + rtl8730_st7701_lcd_layer_enable(LCD_LAYER, true); + rtl8730_st7701_lcd_layer_enable(1, false); + rtl8730_st7701_lcd_layer_enable(2, false); + + LCDC_Init(pLCDC, &lcdc_init_struct); + LCDC_DMAModeConfig(pLCDC, LCDC_LAYER_BURSTSIZE_1X64BYTES); + LCDC_DMADebugConfig(pLCDC, LCDC_DMA_OUT_DISABLE, 0); + + rtl8730e_st7701_register_lcdc_isr(); + + LCDC_LineINTPosConfig(pLCDC, YRES * 4 / 5); + LCDC_INTConfig(pLCDC, LCDC_BIT_LCD_LIN_INTEN | LCDC_BIT_DMA_UN_INTEN, ENABLE); +} + +static void rtl8730_st7701_gpio_reset(void) +{ + return; +} + +static void rtl8730_st7701_cache_invalidate(u32 *buffer, int size) +{ + DCache_CleanInvalidate((u32) buffer, size); +} + +static void rtl8730_st7701_lcd_reload(void) +{ + LCDC_TrigerSHWReload(pLCDC); +} + +static void rtl8730_st7701_lcd_layer_enable(int layer, bool enable) +{ + if (enable) { + lcdc_init_struct.layerx[layer].LCDC_LayerEn = ENABLE; + } else { + lcdc_init_struct.layerx[layer].LCDC_LayerEn = DISABLE; + } +} + +static void rtl8730_st7701_lcd_put_area(u8 *lcd_img_buffer, u32 x_start, u32 y_start, u32 x_end, u32 y_end) +{ + lcdc_init_struct.layerx[LCD_LAYER].LCDC_LayerImgBaseAddr = (u32) lcd_img_buffer; +#ifdef CONFIG_ENABLE_ST7701_CHANGE_WINDOW_SIZE + lcdc_init_struct.layerx[LCD_LAYER].LCDC_LayerHorizontalStart = x_start; + lcdc_init_struct.layerx[LCD_LAYER].LCDC_LayerHorizontalStop = x_end; + lcdc_init_struct.layerx[LCD_LAYER].LCDC_LayerVerticalStart = y_start; + lcdc_init_struct.layerx[LCD_LAYER].LCDC_LayerVerticalStop = y_end; +#else + (void) x_start; + (void) y_start; + (void) x_end; + (void) y_end; +#endif + LCDC_LayerConfig(pLCDC, LCD_LAYER, &lcdc_init_struct.layerx[LCD_LAYER]); + LCDC_TrigerSHWReload(pLCDC); +} + +static void rtl8730e_st7701_reset_pin(u8 Newstatus) +{ + Pinmux_Swdoff(); + Pinmux_Config(MIPI_GPIO_RESET_PIN, PINMUX_FUNCTION_GPIO); + + GPIO_InitTypeDef ResetPin; + ResetPin.GPIO_Pin = MIPI_GPIO_RESET_PIN; + ResetPin.GPIO_PuPd = GPIO_PuPd_NOPULL; + ResetPin.GPIO_Mode = GPIO_Mode_OUT; + GPIO_Init(&ResetPin); + + if (Newstatus) { + GPIO_WriteBit(MIPI_GPIO_RESET_PIN, PIN_HIGH); + } else { + GPIO_WriteBit(MIPI_GPIO_RESET_PIN, PIN_LOW); + } +} + +static void rtl8730_st7701_enable_lcdc(void) +{ + LCDC_Cmd(pLCDC, ENABLE); + while (!LCDC_CheckLCDCReady(pLCDC)) ; + + mipidsi_mode_switch(true); +} + +void rtl8730e_mipidsi_underflowreset(void) +{ + u32 reg_val2 = MIPI_DSI_INTS_ACPU_Get((MIPI_TypeDef *) mipi_irq_info.data); + + if (reg_val2) { + UnderFlowCnt = 0; + MIPI_DSI_INT_Config((MIPI_TypeDef *) mipi_irq_info.data, DISABLE, DISABLE, DISABLE); + mipidsi_acpu_reg_clear(); + + /*Disable the LCDC*/ + LCDC_Cmd(pLCDC, DISABLE); + lcddbg("ERROR: LCDC_CTRL 0x%x\n", pLCDC->LCDC_CTRL); + + rtl8730_st7701_enable_lcdc(); + } +} + +u32 rtl8730e_st7701_hv_isr(void *Data) +{ + /*get LCDC interrupt status*/ + volatile u32 IntId = LCDC_GetINTStatus(pLCDC); + + /*select operations according to interrupt ID*/ + if (IntId & LCDC_BIT_LCD_LIN_INTS) { + LCDC_ClearINT(pLCDC, LCDC_BIT_LCD_LIN_INTS); + } + + if (IntId & LCDC_BIT_DMA_UN_INTS) { + LCDC_ClearINT(pLCDC, LCDC_BIT_DMA_UN_INTS); + UnderFlowCnt++; + if (UnderFlowCnt == 1) { + lcddbg("ERROR: LCDC DMA Underflow-----\n"); + InterruptRegister((IRQ_FUN)rtl8730e_mipidsi_underflowreset, mipi_irq_info.num, (u32)mipi_irq_info.data, mipi_irq_info.priority); + InterruptEn(mipi_irq_info.num, mipi_irq_info.priority); + mipidsi_acpu_reg_clear(); + mipidsi_mode_switch(false); + MIPI_DSI_INT_Config(MIPI, ENABLE, ENABLE, ENABLE); + } + } + return 0; +} + +static void rtl8730e_st7701_register_lcdc_isr(void){ + InterruptDis(lcdc_irq_info.num); + InterruptUnRegister(lcdc_irq_info.num); + InterruptRegister((IRQ_FUN)rtl8730e_st7701_hv_isr, lcdc_irq_info.num, (u32)lcdc_irq_info.data, lcdc_irq_info.priority); + InterruptEn(lcdc_irq_info.num, lcdc_irq_info.priority); +} +void rtl8730_st7701_initialize(void) +{ + struct lcd_data config; + config.XPixels = XRES; + config.YPixels = YRES; + + struct mipi_dsi_host *dsi_host = (struct mipi_dsi_host *)amebasmart_mipi_dsi_host_initialize(&config); + struct mipi_dsi_device *dsi_device = (struct mipi_dsi_device *)mipi_dsi_device_register(dsi_host, "dsi", 0); + struct lcd_dev_s *dev = (struct lcd_dev_s *)st7701_lcdinitialize(dsi_device, &g_rtl8730_st7701_config_s); + LcdcInitValues(config); + rtl8730_st7701_lcd_init(); + + if (lcddev_register(dev) < 0) { + lcddbg("ERROR: LCD driver register fail\n"); + return; + } + lcddbg("LCD driver register success\n"); + rtl8730_st7701_enable_lcdc(); + + rtl8730e_st7701_reset_pin(PIN_HIGH); + DelayMs(10); + rtl8730e_st7701_reset_pin(PIN_LOW); + DelayMs(10); + rtl8730e_st7701_reset_pin(PIN_HIGH); + DelayMs(120); +} diff --git a/os/drivers/Makefile b/os/drivers/Makefile index 0dd439485c..8def194d29 100644 --- a/os/drivers/Makefile +++ b/os/drivers/Makefile @@ -85,6 +85,7 @@ include iotdev$(DELIM)Make.defs include os_api_test$(DELIM)Make.defs include lcd$(DELIM)Make.defs include lwnl${DELIM}Make.defs +include mipidsi$(DELIM)Make.defs include net$(DELIM)Make.defs include otp$(DELIM)Make.defs include pipes$(DELIM)Make.defs diff --git a/os/drivers/lcd/Make.defs b/os/drivers/lcd/Make.defs index 0fbf07d32e..03b9157eec 100644 --- a/os/drivers/lcd/Make.defs +++ b/os/drivers/lcd/Make.defs @@ -103,6 +103,11 @@ ifeq ($(CONFIG_LCD_ST7789),y) CSRCS += st7789.c endif +ifeq ($(CONFIG_LCD_ST7701),y) + CSRCS += st7701.c +endif + + endif # CONFIG_LCD ifeq ($(CONFIG_LCD),y) diff --git a/os/drivers/lcd/st7701.c b/os/drivers/lcd/st7701.c new file mode 100755 index 0000000000..b184566a2c --- /dev/null +++ b/os/drivers/lcd/st7701.c @@ -0,0 +1,368 @@ +/**************************************************************************** + * + * Copyright 2024 Samsung Electronics All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * + ****************************************************************************/ + +#include +#include +#include +#include +#include +#include +#include +#include + +#define REGFLAG_DELAY 0xFC +#define REGFLAG_END_OF_TABLE 0xFD // END OF REGISTERS MARKER + +struct st7701_dev_s { + /* Publicly visible device structure */ + + struct lcd_dev_s dev; + + FAR struct mipi_dsi_device *dsi_dev; + + u8 *lcd_img_buffer[MAX_NO_PLANES]; + u8 *BackupLcdImgBuffer; + int fb_alloc_count; + + struct st7701_config_s *config; +}; + +static struct st7701_dev_s g_lcdcdev; + +typedef struct lcm_setting_table { + u8 cmd; + u8 count; + u8 para_list[128]; +} lcm_setting_table_t; + +static lcm_setting_table_t ST7701S_init_cmd_g[] = { /* DCS Write Long */ + /* ST7701S Reset Sequence */ + /* LCD_Nreset (1); Delayms (1); */ + /* LCD_Nreset (0); Delayms (1); */ + /* LCD_Nreset (1); Delayms (120); */ + {0x11, 0, {0x00}}, + {REGFLAG_DELAY, 120, {}}, /* Delayms (120) */ + + /* Bank0 Setting */ + /* Display Control setting */ + {0xFF, 5, {0x77, 0x01, 0x00, 0x00, 0x10}}, + {0xC0, 2, {0x63, 0x00}}, + {0xC1, 2, {0x0C, 0x02}}, + {0xC2, 2, {0x31, 0x08}}, + {0xCC, 1, {0x10}}, + + /* Gamma Cluster Setting */ + {0xB0, 16, {0x00, 0x11, 0x19, 0x0C, 0x10, 0x06, 0x07, 0x0A, 0x09, 0x22, 0x04, 0x10, 0x0E, 0x28, 0x30, 0x1C}}, + {0xB1, 16, {0x00, 0x12, 0x19, 0x0D, 0x10, 0x04, 0x06, 0x07, 0x08, 0x23, 0x04, 0x12, 0x11, 0x28, 0x30, 0x1C}}, + + /* End Gamma Setting */ + /* End Display Control setting */ + /* End Bank0 Setting */ + + /* Bank1 Setting */ + /* Power Control Registers Initial */ + {0xFF, 5, {0x77, 0x01, 0x00, 0x00, 0x11}}, + {0xB0, 1, {0x4D}}, + + /* Vcom Setting */ + {0xB1, 1, {0x3E}}, /* VCOM */ + /* End End Vcom Setting */ + + {0xB2, 1, {0x09}}, /* 07 */ + {0xB3, 1, {0x80}}, + {0xB5, 1, {0x4B}}, /* 47 4A */ + {0xB7, 1, {0x85}}, + {0xB8, 1, {0x21}}, + {0xB9, 1, {0x10}}, + {0xC1, 1, {0x78}}, + {0xC2, 1, {0x78}}, + {0xD0, 1, {0x88}}, + /* End Power Control Registers Initial */ + {REGFLAG_DELAY, 100, {}}, /* Delayms (100) */ + /* GIP Setting */ + {0xE0, 3, {0x00, 0x00, 0x02}}, + {0xE1, 11, {0x04, 0x00, 0x00, 0x00, 0x05, 0x00, 0x00, 0x00, 0x00, 0x20, 0x20}}, + {0xE2, 13, {0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00}}, + {0xE3, 4, {0x00, 0x00, 0x33, 0x33}}, + {0xE4, 2, {0x22, 0x00}}, + {0xE5, 16, {0x04, 0x34, 0xAA, 0xAA, 0x06, 0x34, 0xAA, 0xAA, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00}}, + {0xE6, 4, {0x00, 0x00, 0x33, 0x00}}, + {0xE7, 2, {0x22, 0x00}}, + {0xE8, 16, {0x05, 0x34, 0xAA, 0xAA, 0x07, 0x34, 0xAA, 0xAA, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00}}, + //{0xEA, 16, {0x10, 0x00, 0x10, 0x00, 0x10, 0x00, 0x10, 0x00, 0x10, 0x00, 0x10, 0x00, 0x10, 0x00, 0x10, 0x00}}, + {0xEB, 7, {0x02, 0x00, 0x40, 0x40, 0x00, 0x00, 0x00}}, + {0xEC, 2, {0x00, 0x00}}, + {0xED, 16, {0xFA, 0x45, 0x0B, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xB0, 0x54, 0xAF}}, + // {0xEF, 12, {0x08, 0x08, 0x08, 0x08, 0x08, 0x08, 0x04, 0x04, 0x04, 0x04, 0x04, 0x04}}, + {0xEF, 6, {0x08, 0x08, 0x08, 0x44, 0x3F, 0x54}}, + /* End GIP Setting */ + + {0xFF, 5, {0x77, 0x01, 0x00, 0x00, 0x00}}, + {0x29, 0, {0x00}}, + {REGFLAG_END_OF_TABLE, 0x00, {}}, +}; + +static int st7701_send_init_cmd(struct mipi_dsi_device *device, lcm_setting_table_t *table) +{ + static u8 send_cmd_idx_s = 0; + u32 payload_len; + u8 cmd; + u8 *cmd_addr; + int transfer_status = 0; + struct mipi_dsi_msg msg; + while (1) { + cmd = table[send_cmd_idx_s].cmd; + switch (cmd) { + case REGFLAG_DELAY: + usleep(table[send_cmd_idx_s].count * 1000); + break; + case REGFLAG_END_OF_TABLE: + msg.type = MIPI_DSI_END_OF_TRANSMISSION; + return mipi_dsi_transfer(device, &msg); + default: + cmd_addr = table[send_cmd_idx_s].para_list; + payload_len = table[send_cmd_idx_s].count; + msg.channel = cmd; + if (payload_len == 0) { + msg.type = MIPI_DSI_DCS_SHORT_WRITE_0_PARAM; + } else if (payload_len == 1) { + msg.type = MIPI_DSI_DCS_SHORT_WRITE_1_PARAM; + } else { + msg.type = MIPI_DSI_DCS_LONG_WRITE; + } + msg.tx_buf = cmd_addr; + msg.tx_len = payload_len; + msg.flags = 0; + transfer_status = mipi_dsi_transfer(device, &msg); + if(transfer_status != OK){ + return transfer_status; + } + } + + send_cmd_idx_s++; + } +} + +/* LCD Data Transfer Methods */ + +/* LCD Specific Controls */ + +/**************************************************************************** + * Name: st7701_putrun + * + * Description: + * This method can be used to write a partial raster line to the LCD: + * + * dev - The 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 written to the LCD + * npixels - The number of pixels to write to the LCD + * (range: 0 < npixels <= xres-col) + * + ****************************************************************************/ + +static int st7701_putrun(FAR struct lcd_dev_s *dev, fb_coord_t row, fb_coord_t col, FAR const uint8_t *buffer, size_t npixels) +{ + return OK; +} + +/**************************************************************************** + * Name: st7701_putarea + * + * Description: + * This method can be used to write a partial area to the LCD: + * + * dev - The lcd device + * row_start - Starting row to write to (range: 0 <= row < yres) + * row_end - Ending row to write to (range: row_start <= row < yres) + * col_start - Starting column to write to (range: 0 <= col <= xres) + * col_end - Ending column to write to + * (range: col_start <= col_end < xres) + * buffer - The buffer containing the area to be written to the LCD + * stride - Length of a line in bytes. This parameter may be necessary + * to allow the LCD driver to calculate the offset for partial + * writes when the buffer needs to be splited for row-by-row + * writing. + * + ****************************************************************************/ + +static int st7701_putarea(FAR struct lcd_dev_s *dev, fb_coord_t row_start, fb_coord_t row_end, fb_coord_t col_start, fb_coord_t col_end, FAR const uint8_t *buffer, fb_coord_t stride) +{ + FAR struct st7701_dev_s *priv = (FAR struct st7701_dev_s *)dev; + //coordinate shift from (0,0) -> (1,1) and (XRES-1,YRES-1) -> (XRES,YRES) + row_start += 1; + row_end += 1; + col_start += 1; + col_end += 1; + priv->config->lcd_put_area(buffer, row_start, col_start, row_end, col_end); + return OK; +} + +/**************************************************************************** + * Name: st7701_getrun + * + * Description: + * This method can be used to read a partial raster line from the LCD: + * + * dev - 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) + * + ****************************************************************************/ + +#ifndef CONFIG_LCD_NOGETRUN +static int st7701_getrun(FAR struct lcd_dev_s *dev, fb_coord_t row, fb_coord_t col, FAR uint8_t *buffer, size_t npixels) +{ + return OK; +} +#endif + +/**************************************************************************** + * Name: st7701_getvideoinfo + * + * Description: + * Get information about the LCD video controller configuration. + * + ****************************************************************************/ + +static int st7701_getvideoinfo(FAR struct lcd_dev_s *dev, FAR struct fb_videoinfo_s *vinfo) +{ + DEBUGASSERT(dev && vinfo); + //vinfo->fmt = ST7701_COLORFMT; /* Color format: RGB16-565: RRRR RGGG GGGB BBBB */ + vinfo->xres = XRES; /* Horizontal resolution in pixel columns */ + vinfo->yres = YRES; /* Vertical resolution in pixel rows */ + vinfo->nplanes = MAX_NO_PLANES; /* Number of color planes supported */ + return OK; +} + +/**************************************************************************** + * Name: st7701_getplaneinfo + * + * Description: + * Get information about the configuration of each LCD color plane. + * + ****************************************************************************/ + +static int st7701_getplaneinfo(FAR struct lcd_dev_s *dev, unsigned int planeno, FAR struct lcd_planeinfo_s *pinfo) +{ + DEBUGASSERT(dev && pinfo && planeno == 0); + pinfo->putrun = &st7701_putrun; /* Put a run into LCD memory */ + pinfo->putarea = &st7701_putarea; /* Put an area into LCD */ +#ifndef CONFIG_LCD_NOGETRUN + pinfo->getrun = &st7701_getrun; /* Get a run from LCD memory */ +#endif + return OK; +} + +/**************************************************************************** + * Name: st7701_getpower + ****************************************************************************/ + +static int st7701_getpower(FAR struct lcd_dev_s *dev, int color) +{ + return OK; +} + +/**************************************************************************** + * Name: st7701_setpower + ****************************************************************************/ + +static int st7701_setpower(FAR struct lcd_dev_s *dev, int power) +{ + return OK; +} + +/**************************************************************************** + * Name: st7701_init + * + * Description: + * init the lcd + * + ****************************************************************************/ + +static int st7701_init(FAR struct lcd_dev_s *dev) +{ + FAR struct st7701_dev_s *priv = (FAR struct st7701_dev_s *)dev; + priv->config->init(); + priv->config->lcd_enable(); + return OK; +} + +/**************************************************************************** + * Name: st7701_setorientation + * + * Description: + * Set LCD orientation(PORTRAIT/LANDSCAPE). + * + ****************************************************************************/ + +static int st7701_setorientation(FAR struct lcd_dev_s *dev, unsigned int orientation) +{ + return OK; +} + +/**************************************************************************** + * Name: st7701_getcontrast + * + * Description: + * Get the current contrast setting (0-CONFIG_LCD_MAXCONTRAST). + * + ****************************************************************************/ + +static int st7701_getcontrast(FAR struct lcd_dev_s *dev) +{ + return OK; +} + +/**************************************************************************** + * Name: st7701_setcontrast + * + * Description: + * Set LCD panel contrast (0-CONFIG_LCD_MAXCONTRAST). + * + ****************************************************************************/ + +static int st7701_setcontrast(FAR struct lcd_dev_s *dev, unsigned int contrast) +{ + return OK; +} + +FAR struct lcd_dev_s *st7701_lcdinitialize(FAR struct mipi_dsi_device *dsi, struct st7701_config_s *config) +{ + FAR struct st7701_dev_s *priv = &g_lcdcdev; + priv->dev.getplaneinfo = st7701_getplaneinfo; + priv->dev.getvideoinfo = st7701_getvideoinfo; + priv->dev.getpower = st7701_getpower; + priv->dev.setpower = st7701_setpower; + priv->dev.getcontrast = st7701_getcontrast; + priv->dev.setcontrast = st7701_setcontrast; + priv->dev.init = st7701_init; + priv->dsi_dev = dsi; + priv->config = config; + if(st7701_send_init_cmd(priv->dsi_dev, ST7701S_init_cmd_g) == OK){ + printf("LCD Init sequence completed\n"); + } + else{ + printf("ERROR: LCD Init sequence failed\n"); + } + return &priv->dev; +} diff --git a/os/drivers/mipidsi/Kconfig b/os/drivers/mipidsi/Kconfig new file mode 100755 index 0000000000..625dfaf539 --- /dev/null +++ b/os/drivers/mipidsi/Kconfig @@ -0,0 +1,19 @@ +# +# For a description of the syntax of this configuration file, +# see kconfig-language at https://www.kernel.org/doc/Documentation/kbuild/kconfig-language.txt +# + +menuconfig MIPI_DSI + bool "Dsi Driver Support" + default n + ---help--- + Enables building of a dsi generic driver. + +if MIPI_DSI + +config MIPI_DSI_DRIVER + bool "MIPI DSI Character Driver" + default n + +endif + diff --git a/os/drivers/mipidsi/Make.defs b/os/drivers/mipidsi/Make.defs new file mode 100755 index 0000000000..fa3ec03e57 --- /dev/null +++ b/os/drivers/mipidsi/Make.defs @@ -0,0 +1,30 @@ +########################################################################## +# +# Copyright 2024 Samsung Electronics All Rights Reserved. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, +# software distributed under the License is distributed on an +# "AS IS" BASIS, WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, +# either express or implied. See the License for the specific +# language governing permissions and limitations under the License. +# +############################################################################ + +ifeq ($(CONFIG_MIPI_DSI),y) + +CSRCS += mipi_dsi_device.c mipi_dsi_host.c mipi_dsi_packet.c mipi_dsi_device_driver.c mipi_dsi_host_driver.c + +ifeq ($(CONFIG_MIPI_DSI_DRIVER),y) + CSRCS += mipi_dsi_device_driver.c mipi_dsi_host_driver.c +endif + +DEPPATH += --dep-path mipidsi +VPATH += :mipidsi +CFLAGS += ${shell $(INCDIR) $(INCDIROPT) "$(CC)" $(TOPDIR)$(DELIM)drivers$(DELIM)mipidsi} +endif # CONFIG_MIPI_DSI diff --git a/os/drivers/mipidsi/mipi_dsi.h b/os/drivers/mipidsi/mipi_dsi.h new file mode 100755 index 0000000000..9ab4b66b11 --- /dev/null +++ b/os/drivers/mipidsi/mipi_dsi.h @@ -0,0 +1,120 @@ +/**************************************************************************** + * + * Copyright 2024 Samsung Electronics All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * + ****************************************************************************/ + +/**************************************************************************** + * drivers/video/mipidsi/mipi_dsi.h + * + * Licensed to the Apache Software Foundation (ASF) under one or more + * contributor license agreements. See the NOTICE file distributed with + * this work for additional information regarding copyright ownership. The + * ASF licenses this file to you under the Apache License, Version 2.0 (the + * "License"); you may not use this file except in compliance with the + * License. You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT + * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the + * License for the specific language governing permissions and limitations + * under the License. + * + ****************************************************************************/ + +#ifndef __DRIVERS_VIDEO_MIPIDSI_MIPI_DSI_H +#define __DRIVERS_VIDEO_MIPIDSI_MIPI_DSI_H + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +/**************************************************************************** + * Public Types + ****************************************************************************/ + +/**************************************************************************** + * Public Functions Definitions + ****************************************************************************/ + +#ifdef __cplusplus +#define EXTERN extern "C" +extern "C" { +#else +#define EXTERN extern +#endif + +/**************************************************************************** + * Name: mipi_dsi_host_driver_register + * + * Description: + * Create and register the dsi host character driver. + * + * The dsi host character driver is a simple character driver that + * supports dsi transfer. + * + * Input Parameters: + * host - An instance of the struct mipi_dsi_host + * + * Returned Value: + * OK if the driver was successfully register; A negated errno value is + * returned on any failure. + * + ****************************************************************************/ + +int mipi_dsi_host_driver_register(FAR struct mipi_dsi_host *host); + +/**************************************************************************** + * Name: mipi_dsi_device_driver_register + * + * Description: + * Create and register the dsi device character driver. + * + * The dsi device character driver is a simple character driver that + * supports get dsi device params. + * + * Input Parameters: + * device - An instance of the struct mipi_dsi_device + * + * Returned Value: + * OK if the driver was successfully register; A negated errno value is + * returned on any failure. + * + ****************************************************************************/ + +int mipi_dsi_device_driver_register(FAR struct mipi_dsi_device *device); + +#undef EXTERN +#ifdef __cplusplus +} +#endif +#endif /* __DRIVERS_VIDEO_MIPIDSI_MIPI_DSI_H */ diff --git a/os/drivers/mipidsi/mipi_dsi_device.c b/os/drivers/mipidsi/mipi_dsi_device.c new file mode 100755 index 0000000000..ab5842daf8 --- /dev/null +++ b/os/drivers/mipidsi/mipi_dsi_device.c @@ -0,0 +1,951 @@ +/**************************************************************************** + * + * Copyright 2024 Samsung Electronics All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * + ****************************************************************************/ + +/**************************************************************************** + * drivers/video/mipidsi/mipi_dsi_device.c + * + * Licensed to the Apache Software Foundation (ASF) under one or more + * contributor license agreements. See the NOTICE file distributed with + * this work for additional information regarding copyright ownership. The + * ASF licenses this file to you under the Apache License, Version 2.0 (the + * "License"); you may not use this file except in compliance with the + * License. You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT + * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the + * License for the specific language governing permissions and limitations + * under the License. + * + ****************************************************************************/ + + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include +#include +#include +#include + +#include +#include + +#include "mipi_dsi.h" + +/**************************************************************************** + * Private Types + ****************************************************************************/ + +/**************************************************************************** + * Private Function Prototypes + ****************************************************************************/ + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +/**************************************************************************** + * Private Functions + ****************************************************************************/ +static int mipi_dsi_fill_tx_buff(FAR struct mipi_dsi_device *device, uint8_t *tx, u32 type){ + struct mipi_dsi_msg msg; + msg.channel = device->channel; + msg.tx_buf = tx; + msg.tx_len = sizeof(tx); + msg.flags = 0; + msg.type = type; + + int ret = mipi_dsi_transfer(device, &msg); + return ret < 0 ? ret : 0; +} + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: mipi_dsi_transfer + * + * Description: + * Transfer message to display modules + * + * Input Parameters: + * device - DSI peripheral + * msg - Message to transfer + * + * Returned Value: + * The number of bytes successfully transfered or a negative error code on + * failure. + * + ****************************************************************************/ + +ssize_t mipi_dsi_transfer(FAR struct mipi_dsi_device *device, FAR struct mipi_dsi_msg *msg) +{ + FAR const struct mipi_dsi_host_ops *ops = device->host->ops; + + if (ops == NULL || ops->transfer == NULL) { + return -ENOSYS; + } + return ops->transfer(device->host, msg); +} + +/**************************************************************************** + * Name: mipi_dsi_attach + * + * Description: + * Attach a DSI device to its DSI host + * + * Input Parameters: + * device - DSI peripheral + * + * Returned Value: + * OK on success or a negative error code on failure. + * + ****************************************************************************/ + +int mipi_dsi_attach(FAR struct mipi_dsi_device *device) +{ + FAR const struct mipi_dsi_host_ops *ops = device->host->ops; + + if (ops == NULL || ops->attach == NULL) { + return -ENOSYS; + } + + return ops->attach(device->host, device); +} + +/**************************************************************************** + * Name: mipi_dsi_detach + * + * Description: + * Detach a DSI device from its DSI host + * + * Input Parameters: + * device - DSI peripheral device + * + * Returned Value: + * OK on success or a negative error code on failure. + * + ****************************************************************************/ + +int mipi_dsi_detach(FAR struct mipi_dsi_device *device) +{ + FAR const struct mipi_dsi_host_ops *ops = device->host->ops; + + if (ops == NULL || ops->detach == NULL) { + return -ENOSYS; + } + + return ops->detach(device->host, device); +} + +/**************************************************************************** + * Name: mipi_dsi_shutdown_peripheral + * + * Description: + * Send a Shutdown Peripheral command to the device device + * + * Input Parameters: + * device - DSI peripheral device + * + * Returned Value: + * OK on success or a negative error code on failure. + * + ****************************************************************************/ + +int mipi_dsi_shutdown_peripheral(FAR struct mipi_dsi_device *device) +{ + uint8_t tx[2] = { + 0, + 0 + }; + return mipi_dsi_fill_tx_buff(device, tx, MIPI_DSI_SHUTDOWN_PERIPHERAL); +} + +/**************************************************************************** + * Name: mipi_dsi_turn_on_peripheral + * + * Description: + * Send a Turn On Peripheral command to the device device + * + * Input Parameters: + * device - DSI peripheral device + * + * Returned Value: + * OK on success or a negative error code on failure. + * + ****************************************************************************/ + +int mipi_dsi_turn_on_peripheral(FAR struct mipi_dsi_device *device) +{ + uint8_t tx[2] = { + 0, + 0 + }; + return mipi_dsi_fill_tx_buff(device, tx, MIPI_DSI_TURN_ON_PERIPHERAL); +} + +/**************************************************************************** + * Name: mipi_dsi_set_maximum_return_packet_size + * + * Description: + * Specify the maximum size of the payload in a long packet transmitted + * from the peripheral back to the device host processor + * + * Input Parameters: + * device - DSI peripheral device + * value - The maximum size of the payload + * + * Returned Value: + * OK on success or a negative error code on failure. + * + ****************************************************************************/ + +int mipi_dsi_set_maximum_return_packet_size(FAR struct mipi_dsi_device *device, uint16_t value) +{ + uint8_t tx[2] = { + value & 0xff, + value >> 8 + }; + return mipi_dsi_fill_tx_buff(device, tx, MIPI_DSI_SET_MAXIMUM_RETURN_PACKET_SIZE); +} + +/**************************************************************************** + * Name: mipi_dsi_compression_mode + * + * Description: + * Enable / disable DSC on the peripheral. Enable or disable Display Stream + * Compression on the peripheral using the default Picture Parameter Set + * and VESA DSC 1.1 algorithm. + * + * Input Parameters: + * device - DSI peripheral device + * enable - Whether to enable or disable the DSC + * + * Returned Value: + * OK on success or a negative error code on failure. + * + ****************************************************************************/ + +int mipi_dsi_compression_mode(FAR struct mipi_dsi_device *device, bool enable) +{ + uint8_t tx[2] = { + enable & 0xff, + 0 + }; + return mipi_dsi_fill_tx_buff(device, tx, MIPI_DSI_COMPRESSION_MODE); +} + +/**************************************************************************** + * Name: mipi_dsi_generic_write + * + * Description: + * Transmit data using a generic write packet + * + * Input Parameters: + * device - DSI peripheral device + * payload - buffer containing the payload + * size - size of the payload + * + * Returned Value: + * OK on success or a negative error code on failure. + * + ****************************************************************************/ + +int mipi_dsi_generic_write(FAR struct mipi_dsi_device *device, FAR const void *payload, size_t size) +{ + int ret; + struct mipi_dsi_msg msg; + + msg.channel = device->channel; + msg.tx_buf = payload; + msg.tx_len = size; + msg.flags = 0; + + switch (size) { + case 0: + msg.type = MIPI_DSI_GENERIC_SHORT_WRITE_0_PARAM; + break; + + case 1: + msg.type = MIPI_DSI_GENERIC_SHORT_WRITE_1_PARAM; + break; + + case 2: + msg.type = MIPI_DSI_GENERIC_SHORT_WRITE_2_PARAM; + break; + + default: + msg.type = MIPI_DSI_LONG_GENERIC_WRITE; + break; + } + + ret = mipi_dsi_transfer(device, &msg); + return ret < 0 ? ret : 0; +} + +/**************************************************************************** + * Name: mipi_dsi_generic_read + * + * Description: + * Receive data using a generic read packet. + * This function will automatically choose the right data type depending on + * the number of parameters passed in. + * + * Input Parameters: + * device - DSI peripheral device + * params - buffer containing the request parameters + * num_params - number of request parameters + * data - buffer in which to return the received data + * size - size of receive buffer + * + * Returned Value: + * The number of bytes successfully read or a negative error code on + * failure. + * + ****************************************************************************/ + +ssize_t mipi_dsi_generic_read(FAR struct mipi_dsi_device *device, FAR const void *params, size_t num_params, FAR void *data, size_t size) +{ + struct mipi_dsi_msg msg; + + msg.channel = device->channel; + msg.tx_len = num_params; + msg.tx_buf = params; + msg.rx_len = size; + msg.rx_buf = data; + msg.flags = 0; + + switch (num_params) { + case 0: + msg.type = MIPI_DSI_GENERIC_READ_0_PARAM; + break; + case 1: + msg.type = MIPI_DSI_GENERIC_READ_1_PARAM; + break; + case 2: + msg.type = MIPI_DSI_GENERIC_READ_2_PARAM; + break; + default: + return -EINVAL; + } + + return mipi_dsi_transfer(device, &msg); +} + +/**************************************************************************** + * Name: mipi_dsi_dcs_write_buffer + * + * Description: + * Transmit a DCS command with payload. + * This function will automatically choose the right data type depending on + * the command payload length. + * + * Input Parameters: + * device - DSI peripheral device + * data - buffer containing data to be transmitted + * len - size of transmission buffer + * + * Returned Value: + * The number of bytes successfully transmitted or a negative error + * code on failure. + * + ****************************************************************************/ + +ssize_t mipi_dsi_dcs_write_buffer(FAR struct mipi_dsi_device *device, FAR const void *data, size_t len) +{ + struct mipi_dsi_msg msg; + + msg.channel = device->channel; + msg.tx_buf = data; + msg.tx_len = len; + msg.flags = 0; + + switch (len) { + case 0: + return -EINVAL; + case 1: + msg.type = MIPI_DSI_DCS_SHORT_WRITE_0_PARAM; + break; + case 2: + msg.type = MIPI_DSI_DCS_SHORT_WRITE_1_PARAM; + break; + default: + msg.type = MIPI_DSI_DCS_LONG_WRITE; + break; + } + + return mipi_dsi_transfer(device, &msg); +} + +/**************************************************************************** + * Name: mipi_dsi_dcs_write + * + * Description: + * Send DCS write command. + * This function will automatically choose the right data type depending on + * the command payload length. + * + * Input Parameters: + * device - DSI peripheral device + * cmd - DCS command + * data - buffer containing the command payload + * len - command payload length + * + * Returned Value: + * The number of bytes successfully transmitted or a negative error + * code on failure. + * + ****************************************************************************/ + +ssize_t mipi_dsi_dcs_write(FAR struct mipi_dsi_device *device, uint8_t cmd, FAR const void *data, size_t len) +{ + ssize_t ret; + uint8_t stack_tx[8]; + FAR uint8_t *tx = stack_tx; + + if (len > sizeof(stack_tx) - 1) { + tx = kmm_malloc(len + 1); + if (tx == NULL) { + return -ENOMEM; + } + } + + /* concatenate the DCS command byte and the payload */ + + tx[0] = cmd; + if (data != NULL) { + memcpy(&tx[1], data, len); + } + + ret = mipi_dsi_dcs_write_buffer(device, tx, len + 1); + + if (tx != stack_tx) { + kmm_free(tx); + } + + return ret; +} + +/**************************************************************************** + * Name: mipi_dsi_dcs_read + * + * Description: + * Send DCS read request command. + * + * Input Parameters: + * device - DSI peripheral device + * cmd - DCS command + * data - buffer in which to receive data + * len - size of receive buffer + * + * Returned Value: + * The number of bytes read or a negative error code on failure. + * + ****************************************************************************/ + +ssize_t mipi_dsi_dcs_read(FAR struct mipi_dsi_device *device, uint8_t cmd, FAR void *data, size_t len) +{ + struct mipi_dsi_msg msg; + + msg.channel = device->channel; + msg.type = MIPI_DSI_DCS_READ_0_PARAM; + msg.tx_buf = &cmd; + msg.tx_len = 1; + msg.rx_buf = data; + msg.rx_len = len; + msg.flags = 0; + + return mipi_dsi_transfer(device, &msg); +} + +/**************************************************************************** + * Name: mipi_dsi_dcs_nop + * + * Description: + * Send DCS nop packet + * + * Input Parameters: + * device - DSI peripheral device + * + * Returned Value: + * OK on success or a negative error code on failure. + * + ****************************************************************************/ + +int mipi_dsi_dcs_nop(FAR struct mipi_dsi_device *device) +{ + int ret; + + ret = mipi_dsi_dcs_write(device, MIPI_DCS_NOP, NULL, 0); + return ret < 0 ? ret : OK; +} + +/**************************************************************************** + * Name: mipi_dsi_dcs_soft_reset + * + * Description: + * Send a software reset of the display module + * + * Input Parameters: + * device - DSI peripheral device + * + * Returned Value: + * OK on success or a negative error code on failure. + * + ****************************************************************************/ + +int mipi_dsi_dcs_soft_reset(FAR struct mipi_dsi_device *device) +{ + int ret; + + ret = mipi_dsi_dcs_write(device, MIPI_DCS_SOFT_RESET, NULL, 0); + return ret < 0 ? ret : OK; +} + +/**************************************************************************** + * Name: mipi_dsi_dcs_get_power_mode + * + * Description: + * Query the display module's current power mode + * + * Input Parameters: + * device - DSI peripheral device + * mode - return location of the current power mode + * + * Returned Value: + * OK on success or a negative error code on failure. + * + ****************************************************************************/ + +int mipi_dsi_dcs_get_power_mode(FAR struct mipi_dsi_device *device, FAR uint8_t *mode) +{ + int ret; + + ret = mipi_dsi_dcs_read(device, MIPI_DCS_GET_POWER_MODE, mode, sizeof(*mode)); + if (ret <= 0) { + if (ret == 0) { + ret = -ENODATA; + } + + return ret; + } + + return OK; +} + +/**************************************************************************** + * Name: mipi_dsi_dcs_get_pixel_format + * + * Description: + * Gets the pixel format for the RGB image data used by the display module. + * + * Input Parameters: + * device - DSI peripheral device + * format - return location of the pixel format + * + * Returned Value: + * OK on success or a negative error code on failure. + * + ****************************************************************************/ + +int mipi_dsi_dcs_get_pixel_format(FAR struct mipi_dsi_device *device, FAR uint8_t *format) +{ + int ret; + + ret = mipi_dsi_dcs_read(device, MIPI_DCS_GET_PIXEL_FORMAT, format, sizeof(*format)); + if (ret <= 0) { + if (ret == 0) { + ret = -ENODATA; + } + + return ret; + } + + return OK; +} + +/**************************************************************************** + * Name: mipi_dsi_dcs_enter_sleep_mode + * + * Description: + * Send a Enter Sleep Mode command to display module. + * + * Input Parameters: + * device - DSI peripheral device + * + * Returned Value: + * OK on success or a negative error code on failure. + * + ****************************************************************************/ + +int mipi_dsi_dcs_enter_sleep_mode(FAR struct mipi_dsi_device *device) +{ + int ret; + + ret = mipi_dsi_dcs_write(device, MIPI_DCS_ENTER_SLEEP_MODE, NULL, 0); + return ret < 0 ? ret : OK; +} + +/**************************************************************************** + * Name: mipi_dsi_dcs_exit_sleep_mode + * + * Description: + * Send a Exit Sleep Mode command to display module. + * + * Input Parameters: + * device - DSI peripheral device + * + * Returned Value: + * OK on success or a negative error code on failure. + * + ****************************************************************************/ + +int mipi_dsi_dcs_exit_sleep_mode(FAR struct mipi_dsi_device *device) +{ + int ret; + + ret = mipi_dsi_dcs_write(device, MIPI_DCS_EXIT_SLEEP_MODE, NULL, 0); + return ret < 0 ? ret : OK; +} + +/**************************************************************************** + * Name: mipi_dsi_dcs_set_display_off + * + * Description: + * Send a Display OFF command to display module. Stop displaying the image + * data on the display device. + * + * Input Parameters: + * device - DSI peripheral device + * + * Returned Value: + * OK on success or a negative error code on failure. + * + ****************************************************************************/ + +int mipi_dsi_dcs_set_display_off(FAR struct mipi_dsi_device *device) +{ + int ret; + + ret = mipi_dsi_dcs_write(device, MIPI_DCS_SET_DISPLAY_OFF, NULL, 0); + return ret < 0 ? ret : OK; +} + +/**************************************************************************** + * Name: mipi_dsi_dcs_set_display_on + * + * Description: + * Send a Display On command to display module. Start displaying the image + * data on the display device. + * + * Input Parameters: + * device - DSI peripheral device + * + * Returned Value: + * OK on success or a negative error code on failure. + * + ****************************************************************************/ + +int mipi_dsi_dcs_set_display_on(FAR struct mipi_dsi_device *device) +{ + int ret; + + ret = mipi_dsi_dcs_write(device, MIPI_DCS_SET_DISPLAY_ON, NULL, 0); + return ret < 0 ? ret : OK; +} + +/**************************************************************************** + * Name: mipi_dsi_dcs_set_column_address + * + * Description: + * Define the column extent of the frame memory accessed by the host + * processor + * + * Input Parameters: + * device - DSI peripheral device + * start - first column address of frame memory + * end - last column address of frame memory + * + * Returned Value: + * OK on success or a negative error code on failure. + * + ****************************************************************************/ + +int mipi_dsi_dcs_set_column_address(FAR struct mipi_dsi_device *device, uint16_t start, uint16_t end) +{ + uint8_t payload[4] = { + start >> 8, + start & 0xff, + end >> 8, + end & 0xff + }; + + int ret; + + ret = mipi_dsi_dcs_write(device, MIPI_DCS_SET_COLUMN_ADDRESS, payload, sizeof(payload)); + return ret < 0 ? ret : OK; +} + +/**************************************************************************** + * Name: mipi_dsi_dcs_set_page_address + * + * Description: + * Define the page extent of the frame memory accessed by the host + * processor + * + * Input Parameters: + * device - DSI peripheral device + * start - first page address of frame memory + * end - last page address of frame memory + * + * Returned Value: + * OK on success or a negative error code on failure. + * + ****************************************************************************/ + +int mipi_dsi_dcs_set_page_address(FAR struct mipi_dsi_device *device, uint16_t start, uint16_t end) +{ + uint8_t payload[4] = { + start >> 8, + start & 0xff, + end >> 8, + end & 0xff + }; + + int ret; + + ret = mipi_dsi_dcs_write(device, MIPI_DCS_SET_PAGE_ADDRESS, payload, sizeof(payload)); + return ret < 0 ? ret : OK; +} + +/**************************************************************************** + * Name: mipi_dsi_dcs_set_tear_off + * + * Description: + * Turn off the display module's Tearing Effect output signal on the TE + * signal line + * + * Input Parameters: + * device - DSI peripheral device + * + * Returned Value: + * OK on success or a negative error code on failure. + * + ****************************************************************************/ + +int mipi_dsi_dcs_set_tear_off(FAR struct mipi_dsi_device *device) +{ + int ret; + + ret = mipi_dsi_dcs_write(device, MIPI_DCS_SET_TEAR_OFF, NULL, 0); + return ret < 0 ? ret : OK; +} + +/**************************************************************************** + * Name: mipi_dsi_dcs_set_tear_on + * + * Description: + * Turn on the display module's Tearing Effect output signal on the TE + * signal line. + * + * Input Parameters: + * device - DSI peripheral device + * mode - Tearing Mode, MIPI_DSI_DCS_TEAR_MODE_VBLANK or + * MIPI_DSI_DCS_TEAR_MODE_VHBLANK + * + * Returned Value: + * OK on success or a negative error code on failure. + * + ****************************************************************************/ + +int mipi_dsi_dcs_set_tear_on(FAR struct mipi_dsi_device *device, uint8_t mode) +{ + int ret; + + ret = mipi_dsi_dcs_write(device, MIPI_DCS_SET_TEAR_ON, &mode, sizeof(mode)); + return ret < 0 ? ret : OK; +} + +/**************************************************************************** + * Name: mipi_dsi_dcs_set_pixel_format + * + * Description: + * Sets the pixel format for the RGB image data used by the display module. + * + * Input Parameters: + * device - DSI peripheral device + * format - pixel format + * + * Returned Value: + * OK on success or a negative error code on failure. + * + ****************************************************************************/ + +int mipi_dsi_dcs_set_pixel_format(FAR struct mipi_dsi_device *device, uint8_t format) +{ + int ret; + + ret = mipi_dsi_dcs_write(device, MIPI_DCS_SET_PIXEL_FORMAT, &format, sizeof(format)); + return ret < 0 ? ret : OK; +} + +/**************************************************************************** + * Name: mipi_dsi_dcs_set_tear_scanline + * + * Description: + * Set the scanline to use as trigger for the Tearing Effect output signal + * of the display module. + * + * Input Parameters: + * device - DSI peripheral device + * scanline - scanline to use as trigger + * + * Returned Value: + * OK on success or a negative error code on failure. + * + ****************************************************************************/ + +int mipi_dsi_dcs_set_tear_scanline(FAR struct mipi_dsi_device *device, uint16_t scanline) +{ + uint8_t payload[2] = { + scanline >> 8, + scanline & 0xff + }; + + int ret; + + ret = mipi_dsi_dcs_write(device, MIPI_DCS_SET_TEAR_SCANLINE, payload, sizeof(payload)); + return ret < 0 ? ret : OK; +} + +/**************************************************************************** + * Name: mipi_dsi_dcs_set_display_brightness + * + * Description: + * Sets the brightness value of the display. + * + * Input Parameters: + * device - DSI peripheral device + * brightness - brightness value + * + * Returned Value: + * OK on success or a negative error code on failure. + * + ****************************************************************************/ + +int mipi_dsi_dcs_set_display_brightness(FAR struct mipi_dsi_device *device, uint16_t brightness) +{ + uint8_t payload[2] = { + brightness & 0xff, + brightness >> 8 + }; + + int ret; + + ret = mipi_dsi_dcs_write(device, MIPI_DCS_SET_DISPLAY_BRIGHTNESS, payload, sizeof(payload)); + return ret < 0 ? ret : OK; +} + +/**************************************************************************** + * Name: mipi_dsi_dcs_get_display_brightness + * + * Description: + * Gets the current brightness value of the display. + * + * Input Parameters: + * device - DSI peripheral device + * brightness - brightness value + * + * Returned Value: + * OK on success or a negative error code on failure. + * + ****************************************************************************/ + +int mipi_dsi_dcs_get_display_brightness(FAR struct mipi_dsi_device *device, FAR uint16_t *brightness) +{ + int ret; + + ret = mipi_dsi_dcs_read(device, MIPI_DCS_GET_DISPLAY_BRIGHTNESS, brightness, sizeof(*brightness)); + if (ret <= 0) { + if (ret == 0) { + ret = -ENODATA; + } + + return ret; + } + + return OK; +} + +/**************************************************************************** + * Name: mipi_dsi_device_register + * + * Description: + * Register mipi dsi device, if defined CONFIG_MIPI_DSI_DRIVER, will create + * character device at /dev/dsiN/dev-xxx. + * + * Input Parameters: + * host - An instance of the dsi host + * name - The name of the dsi device + * channel - The channel used by dsi device + * + * Returned Value: + * struct mipi_dsi_device* if the driver was successfully register; NULL is + * returned on any failure. + * + ****************************************************************************/ + +FAR struct mipi_dsi_device *mipi_dsi_device_register(FAR struct mipi_dsi_host *host, FAR const char *name, int channel) +{ + FAR struct mipi_dsi_device *dev; +#ifdef CONFIG_MIPI_DSI_DRIVER + int ret; +#endif + + DEBUGASSERT(host != NULL && name != NULL); + + if (channel > 3) { + printf("invalid virtual channel: %u\n", channel); + return NULL; + } + + dev = (struct mipi_dsi_device *)kmm_zalloc(sizeof(struct mipi_dsi_device)); + if (dev) { + dev->host = host; + dev->channel = channel; + snprintf(dev->name, sizeof(dev->name), "%s", name); +#ifdef CONFIG_MIPI_DSI_DRIVER + ret = mipi_dsi_device_driver_register(dev); + if (ret < 0) + { + kmm_free(dev); + dev = NULL; + } +#endif + } + + return dev; +} diff --git a/os/drivers/mipidsi/mipi_dsi_device_driver.c b/os/drivers/mipidsi/mipi_dsi_device_driver.c new file mode 100755 index 0000000000..ac28655309 --- /dev/null +++ b/os/drivers/mipidsi/mipi_dsi_device_driver.c @@ -0,0 +1,232 @@ +/**************************************************************************** + * + * Copyright 2024 Samsung Electronics All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * + ****************************************************************************/ + +/**************************************************************************** + * drivers/video/mipidsi/mipi_dsi_device_driver.c + * + * Licensed to the Apache Software Foundation (ASF) under one or more + * contributor license agreements. See the NOTICE file distributed with + * this work for additional information regarding copyright ownership. The + * ASF licenses this file to you under the Apache License, Version 2.0 (the + * "License"); you may not use this file except in compliance with the + * License. You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT + * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the + * License for the specific language governing permissions and limitations + * under the License. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include + +#include + +#include "mipi_dsi.h" + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/* Device naming ************************************************************/ + +#define MIPI_DSI_DEVNAME_FMT "/dev/dsi%d/dev.%d.%s" +#define MIPI_DSI_DEVNAME_LEN 128 + +/**************************************************************************** + * Private Types + ****************************************************************************/ + +struct mipi_dsi_device_driver_s { + FAR struct mipi_dsi_device *dsi_dev; + sem_t sem; +}; + +/**************************************************************************** + * Private Function Prototypes + ****************************************************************************/ + +static ssize_t dsi_dev_read(FAR struct file *filep, FAR char *buffer, size_t buflen); +static ssize_t dsi_dev_write(FAR struct file *filep, FAR const char *buffer, size_t buflen); +static int dsi_dev_ioctl(FAR struct file *filep, int cmd, unsigned long arg); + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +static const struct file_operations g_dsi_dev_fops = { + NULL, /* open */ + NULL, /* close */ + dsi_dev_read, /* read */ + dsi_dev_write, /* write */ + NULL, /* seek */ + dsi_dev_ioctl, /* ioctl */ +}; + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: dsi_dev_read + ****************************************************************************/ + +static ssize_t dsi_dev_read(FAR struct file *filep, FAR char *buffer, size_t buflen) +{ + return 0; /* Return EOF */ +} + +/**************************************************************************** + * Name: dsi_dev_write + ****************************************************************************/ + +static ssize_t dsi_dev_write(FAR struct file *filep, FAR const char *buffer, size_t buflen) +{ + return buflen; /* Say that everything was written */ +} + +/**************************************************************************** + * Name: dsi_dev_ioctl + ****************************************************************************/ + +static int dsi_dev_ioctl(FAR struct file *filep, int cmd, unsigned long arg) +{ + FAR struct inode *inode; + FAR struct mipi_dsi_device_driver_s *priv; + int ret = OK; + + /* Get our private data structure */ + + inode = filep->f_inode; + + priv = inode->i_private; + DEBUGASSERT(priv); + + ret = sem_wait(&priv->sem); + if (ret < 0) { + return ret; + } + + /* Process the IOCTL command */ + + switch (cmd) { + case MIPIDSI_GETDEVLANES: { + FAR uint16_t *planes = (FAR uint16_t *)((uintptr_t) arg); + DEBUGASSERT(planes != NULL); + + *planes = priv->dsi_dev->lanes; + } + break; + case MIPIDSI_GETDEVFMT: { + FAR uint32_t *fmt = (FAR uint32_t *)((uintptr_t) arg); + DEBUGASSERT(fmt != NULL); + + *fmt = priv->dsi_dev->format; + } + break; + case MIPIDSI_GETDEVMODE: { + FAR uint32_t *mode = (FAR uint32_t *)((uintptr_t) arg); + DEBUGASSERT(mode != NULL); + + *mode = priv->dsi_dev->mode_flags; + } + break; + case MIPIDSI_GETDEVHSRATE: { + FAR uint32_t *hsrate = (FAR uint32_t *)((uintptr_t) arg); + DEBUGASSERT(hsrate != NULL); + + *hsrate = priv->dsi_dev->hs_rate; + } + break; + case MIPIDSI_GETDEVLPRATE: { + FAR uint32_t *lprate = (FAR uint32_t *)((uintptr_t) arg); + DEBUGASSERT(lprate != NULL); + + *lprate = priv->dsi_dev->lp_rate; + } + break; + default: + ret = -ENOTTY; + break; + } + + sem_post(&priv->sem); + return ret; +} + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: mipi_dsi_device_driver_register + * + * Description: + * Create and register the dsi device character driver. + * + * The dsi device character driver is a simple character driver that + * supports get dsi device params. + * + * Input Parameters: + * device - An instance of the struct mipi_dsi_device + * + * Returned Value: + * OK if the driver was successfully register; A negated errno value is + * returned on any failure. + * + ****************************************************************************/ + +int mipi_dsi_device_driver_register(FAR struct mipi_dsi_device *device) +{ + FAR struct mipi_dsi_device_driver_s *priv; + FAR struct mipi_dsi_host *host; + char devpath[MIPI_DSI_DEVNAME_LEN]; + int ret = OK; + + DEBUGASSERT(device != NULL && device->host != NULL); + + priv = kmm_zalloc(sizeof(struct mipi_dsi_device_driver_s)); + if (priv == NULL) { + dbg("ERROR: mipi dsi device driver register failed, no memory.\n"); + return -ENOMEM; + } + + priv->dsi_dev = device; + sem_init(&priv->sem, 0, 1); + + host = device->host; + snprintf(devpath, sizeof(devpath), MIPI_DSI_DEVNAME_FMT, host->bus, device->channel, device->name); + + ret = register_driver(devpath, &g_dsi_dev_fops, 0666, priv); + if (ret < 0) { + sem_destroy(&priv->sem); + kmm_free(priv); + } + + return ret; +} diff --git a/os/drivers/mipidsi/mipi_dsi_host.c b/os/drivers/mipidsi/mipi_dsi_host.c new file mode 100755 index 0000000000..79467eef41 --- /dev/null +++ b/os/drivers/mipidsi/mipi_dsi_host.c @@ -0,0 +1,169 @@ +/**************************************************************************** + * + * Copyright 2024 Samsung Electronics All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * + ****************************************************************************/ + +/**************************************************************************** + * drivers/video/mipidsi/mipi_dsi_host.c + * + * Licensed to the Apache Software Foundation (ASF) under one or more + * contributor license agreements. See the NOTICE file distributed with + * this work for additional information regarding copyright ownership. The + * ASF licenses this file to you under the Apache License, Version 2.0 (the + * "License"); you may not use this file except in compliance with the + * License. You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT + * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the + * License for the specific language governing permissions and limitations + * under the License. + * + ****************************************************************************/ + + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include + +#include +#include "mipi_dsi.h" + +/**************************************************************************** + * Private Types + ****************************************************************************/ + +struct mipi_dsi_hosts_s { + int count; + struct mipi_dsi_host *hosts[1]; +}; + +/**************************************************************************** + * Private Function Prototypes + ****************************************************************************/ + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +static FAR struct mipi_dsi_hosts_s *g_hosts; + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: mipi_dsi_host_exist + ****************************************************************************/ + +static bool mipi_dsi_host_exist(int bus) +{ + int i = 0; + + while (g_hosts != NULL && i < g_hosts->count) { + if (g_hosts->hosts[i]->bus == bus) { + return true; + } + + i++; + } + return false; +} + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: mipi_dsi_host_register + * + * Description: + * Register mipi dsi host, if defined CONFIG_MIPI_DSI_DRIVER, will create + * character device at /dev. + * + * Input Parameters: + * host - An instance of the dsi host + * + * Returned Value: + * OK if the driver was successfully register; A negated errno value is + * returned on any failure. + * + ****************************************************************************/ + +int mipi_dsi_host_register(FAR struct mipi_dsi_host *host) +{ + DEBUGASSERT(host != NULL); + DEBUGASSERT(host->ops != NULL); + + if (mipi_dsi_host_exist(host->bus)) { + return -EINVAL; + } + + if (g_hosts == NULL) { + g_hosts = kmm_zalloc(sizeof(struct mipi_dsi_hosts_s)); + } else { + g_hosts = kmm_realloc(g_hosts, sizeof(struct mipi_dsi_hosts_s) + sizeof(FAR struct mipi_dsi_host *) * g_hosts->count); + } + if (g_hosts == NULL) { + return -ENOMEM; + } + + g_hosts->hosts[g_hosts->count] = host; + g_hosts->count++; + +#ifdef CONFIG_MIPI_DSI_DRIVER + return mipi_dsi_host_driver_register(host); +#else + return OK; +#endif +} + +/**************************************************************************** + * Name: mipi_dsi_host_get + * + * Description: + * Find host in list by bus number. Lcd driver can get host by this + * interface to register dsi device. + * + * Input Parameters: + * bus - The dsi host bus number. + * + * Returned Value: + * struct mipi_dsi_host pointer if the host was successfully registered; + * NULL pointer is returned on any failure. + * + ****************************************************************************/ + +FAR struct mipi_dsi_host *mipi_dsi_host_get(int bus) +{ + int i = 0; + + while (g_hosts != NULL && i < g_hosts->count) { + if (g_hosts->hosts[i]->bus == bus) { + return g_hosts->hosts[i]; + } + + i++; + } + + return NULL; +} diff --git a/os/drivers/mipidsi/mipi_dsi_host_driver.c b/os/drivers/mipidsi/mipi_dsi_host_driver.c new file mode 100755 index 0000000000..8c017dfb51 --- /dev/null +++ b/os/drivers/mipidsi/mipi_dsi_host_driver.c @@ -0,0 +1,213 @@ +/**************************************************************************** + * + * Copyright 2024 Samsung Electronics All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * + ****************************************************************************/ + +/**************************************************************************** + * drivers/video/mipidsi/mipi_dsi_host_driver.c + * + * Licensed to the Apache Software Foundation (ASF) under one or more + * contributor license agreements. See the NOTICE file distributed with + * this work for additional information regarding copyright ownership. The + * ASF licenses this file to you under the Apache License, Version 2.0 (the + * "License"); you may not use this file except in compliance with the + * License. You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT + * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the + * License for the specific language governing permissions and limitations + * under the License. + * + ****************************************************************************/ + + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include +#include +#include + +#include + +#include "mipi_dsi.h" + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/* Device naming ************************************************************/ + +#define MIPI_DSI_HOSTNAME_FMT "/dev/dsi%d/host" +#define MIPI_DSI_HOSTNAME_LEN 128 + +/**************************************************************************** + * Private Types + ****************************************************************************/ + +/* Driver state structure */ + +struct mipi_dsi_host_driver_s { + FAR struct mipi_dsi_host *host; + pthread_mutex_t lock; /* Mutual exclusion */ +}; + +/**************************************************************************** + * Private Function Prototypes + ****************************************************************************/ + +static ssize_t dsi_host_read(FAR struct file *filep, FAR char *buffer, size_t len); +static ssize_t dsi_host_write(FAR struct file *filep, FAR const char *buffer, size_t len); +static int dsi_host_ioctl(FAR struct file *filep, int cmd, unsigned long arg); + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +static const struct file_operations g_dsi_host_fops = { + NULL, /* open */ + NULL, /* close */ + dsi_host_read, /* read */ + dsi_host_write, /* write */ + NULL, /* seek */ + dsi_host_ioctl, /* ioctl */ +}; + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: dsi_host_read + ****************************************************************************/ + +static ssize_t dsi_host_read(FAR struct file *filep, FAR char *buffer, size_t len) +{ + return 0; /* Return EOF */ +} + +/**************************************************************************** + * Name: DSI hostdrvr_write + ****************************************************************************/ + +static ssize_t dsi_host_write(FAR struct file *filep, FAR const char *buffer, size_t len) +{ + return len; /* Say that everything was written */ +} + +/**************************************************************************** + * Name: dsi_host_ioctl + ****************************************************************************/ + +static int dsi_host_ioctl(FAR struct file *filep, int cmd, unsigned long arg) +{ + FAR struct mipi_dsi_host_driver_s *priv; + FAR struct inode *inode; + FAR struct mipi_dsi_msg *msg; + FAR struct mipi_dsi_host *host; + int ret; + + /* Get our private data structure */ + + inode = filep->f_inode; + + priv = inode->i_private; + DEBUGASSERT(priv); + + /* Get exclusive access to the dsi host driver state structure */ + + ret = pthread_mutex_lock(&priv->lock); + if (ret < 0) { + return ret; + } + + /* Process the IOCTL command */ + + switch (cmd) { + case MIPIDSI_TRANSFER: + + /* Get the reference to the mipi_dsi_msg structure */ + + msg = (FAR struct mipi_dsi_msg *)((uintptr_t) arg); + + /* Get the reference to the mipi_dsi_host structure */ + + host = priv->host; + DEBUGASSERT(host != NULL && msg != NULL); + + ret = host->ops->transfer(host, msg); + break; + default: + ret = -ENOTTY; + break; + } + + pthread_mutex_unlock(&priv->lock); + return ret; +} + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: mipi_dsi_host_driver_register + * + * Description: + * Create and register the dsi host character driver. + * + * The dsi host character driver is a simple character driver that + * supports dsi transfer. + * + * Input Parameters: + * host - An instance of the struct mipi_dsi_host + * + * Returned Value: + * OK if the driver was successfully register; A negated errno value is + * returned on any failure. + * + ****************************************************************************/ + +int mipi_dsi_host_driver_register(FAR struct mipi_dsi_host *host) +{ + FAR struct mipi_dsi_host_driver_s *priv; + char name[MIPI_DSI_HOSTNAME_LEN]; + int ret = -ENOMEM; + + DEBUGASSERT(host != NULL); + + priv = kmm_zalloc(sizeof(struct mipi_dsi_host_driver_s)); + if (priv != NULL) { + priv->host = host; +#ifndef CONFIG_DISABLE_PSEUDOFS_OPERATIONS + pthread_mutex_init(&priv->lock, NULL); +#endif + + snprintf(name, sizeof(name), MIPI_DSI_HOSTNAME_FMT, host->bus); + ret = register_driver(name, &g_dsi_host_fops, 0666, priv); + if (ret < 0) { +#ifndef CONFIG_DISABLE_PSEUDOFS_OPERATIONS + pthread_mutex_destroy(&priv->lock); +#endif + kmm_free(priv); + } + } + return ret; +} diff --git a/os/drivers/mipidsi/mipi_dsi_packet.c b/os/drivers/mipidsi/mipi_dsi_packet.c new file mode 100755 index 0000000000..77a7b48953 --- /dev/null +++ b/os/drivers/mipidsi/mipi_dsi_packet.c @@ -0,0 +1,235 @@ +/**************************************************************************** + * + * Copyright 2024 Samsung Electronics All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * + ****************************************************************************/ + +/**************************************************************************** + * drivers/video/mipidsi/mipi_dsi_packet.c + * + * Licensed to the Apache Software Foundation (ASF) under one or more + * contributor license agreements. See the NOTICE file distributed with + * this work for additional information regarding copyright ownership. The + * ASF licenses this file to you under the Apache License, Version 2.0 (the + * "License"); you may not use this file except in compliance with the + * License. You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT + * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the + * License for the specific language governing permissions and limitations + * under the License. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include +#include +#include +#include + +#include +#include + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: mipi_dsi_pixel_format_to_bpp + * + * Description: + * Obtain the number of bits per pixel for any given pixel format defined + * by the MIPI DSI specification + * + * Input Parameters: + * fmt - MIPI DSI pixel format + * + * Returned Value: + * The number of bits per pixel of the given pixel format. + * + ****************************************************************************/ + +int mipi_dsi_pixel_format_to_bpp(uint8_t fmt) +{ + switch (fmt) { + case MIPI_DSI_FMT_RGB888: + case MIPI_DSI_FMT_RGB666: + return 24; + case MIPI_DSI_FMT_RGB666_PACKED: + return 18; + case MIPI_DSI_FMT_RGB565: + return 16; + } + + return -EINVAL; +} + +/**************************************************************************** + * Name: mipi_dsi_packet_format_is_short + * + * Description: + * Check if a packet is of the short format + * + * Input Parameters: + * type - MIPI DSI data type of the packet + * + * Returned Value: + * True if the packet for the given data type is a short packet, false + * otherwise. + * + ****************************************************************************/ + +bool mipi_dsi_packet_format_is_short(uint8_t type) +{ + switch (type) { + case MIPI_DSI_VSYNC_START: + case MIPI_DSI_VSYNC_END: + case MIPI_DSI_HSYNC_START: + case MIPI_DSI_HSYNC_END: + case MIPI_DSI_COMPRESSION_MODE: + case MIPI_DSI_END_OF_TRANSMISSION: + case MIPI_DSI_COLOR_MODE_OFF: + case MIPI_DSI_COLOR_MODE_ON: + case MIPI_DSI_SHUTDOWN_PERIPHERAL: + case MIPI_DSI_TURN_ON_PERIPHERAL: + case MIPI_DSI_GENERIC_SHORT_WRITE_0_PARAM: + case MIPI_DSI_GENERIC_SHORT_WRITE_1_PARAM: + case MIPI_DSI_GENERIC_SHORT_WRITE_2_PARAM: + case MIPI_DSI_GENERIC_READ_0_PARAM: + case MIPI_DSI_GENERIC_READ_1_PARAM: + case MIPI_DSI_GENERIC_READ_2_PARAM: + case MIPI_DSI_DCS_SHORT_WRITE_0_PARAM: + case MIPI_DSI_DCS_SHORT_WRITE_1_PARAM: + case MIPI_DSI_DCS_READ_0_PARAM: + case MIPI_DSI_EXECUTE_QUEUE: + case MIPI_DSI_SET_MAXIMUM_RETURN_PACKET_SIZE: + return true; + } + + return false; +} + +/**************************************************************************** + * Name: mipi_dsi_packet_format_is_long + * + * Description: + * Check if a packet is of the long format + * + * Input Parameters: + * type - MIPI DSI data type of the packet + * + * Returned Value: + * True if the packet for the given data type is a long packet, false + * otherwise. + * + ****************************************************************************/ + +bool mipi_dsi_packet_format_is_long(uint8_t type) +{ + switch (type) { + case MIPI_DSI_NULL_PACKET: + case MIPI_DSI_BLANKING_PACKET: + case MIPI_DSI_LONG_GENERIC_WRITE: + case MIPI_DSI_DCS_LONG_WRITE: + case MIPI_DSI_PICTURE_PARAMETER_SET: + case MIPI_DSI_COMPRESSED_PIXEL_STREAM: + case MIPI_DSI_LOOSELY_PACKED_PIXEL_STREAM_YCBCR20: + case MIPI_DSI_PACKED_PIXEL_STREAM_YCBCR24: + case MIPI_DSI_PACKED_PIXEL_STREAM_YCBCR16: + case MIPI_DSI_PACKED_PIXEL_STREAM_RGB30: + case MIPI_DSI_PACKED_PIXEL_STREAM_RGB36: + case MIPI_DSI_PACKED_PIXEL_STREAM_YCBCR12: + case MIPI_DSI_PACKED_PIXEL_STREAM_RGB16: + case MIPI_DSI_PACKED_PIXEL_STREAM_RGB18: + case MIPI_DSI_PIXEL_STREAM_3BYTE_RGB18: + case MIPI_DSI_PACKED_PIXEL_STREAM_RGB24: + return true; + } + + return false; +} + +/**************************************************************************** + * Name: mipi_dsi_create_packet + * + * Description: + * Create a packet from a message according to the DSI protocol + * + * Input Parameters: + * packet - Pointer to a DSI packet structure + * msg - Message to translate into a packet + * + * Returned Value: + * Return: 0 on success or a negative error code on failure. + * + ****************************************************************************/ + +int mipi_dsi_create_packet(FAR struct mipi_dsi_packet *packet, FAR const struct mipi_dsi_msg *msg) +{ + if (packet == NULL) { + printf("packet is NULL \n"); + return -EINVAL; + } + if (msg == NULL) { + printf("msg is NULL \n"); + return -EINVAL; + } + + /* do some minimum sanity checking */ + if (!mipi_dsi_packet_format_is_short(msg->type) && !mipi_dsi_packet_format_is_long(msg->type)) { + printf("msg type issue:%d\n", msg->type); + return -EINVAL; + } + + /*if (msg->channel > 3) + { + printf("msg channel issue :%d\n", msg->channel); + return -EINVAL; + } */ + + memset(packet, 0, sizeof(*packet)); + //packet->header[0] = (msg->channel << 6) | (msg->type & 0x3f); /*anjana - removed or not + packet->header[0] = msg->channel; + + /* TODO: compute ECC if hardware support is not available */ + + /* Long write packets contain the word count in header bytes 1 and 2. + * The payload follows the header and is word count bytes long. + * + * Short write packets encode up to two parameters in header bytes 1 + * and 2. + */ + if (mipi_dsi_packet_format_is_long(msg->type)) { + packet->header[1] = (msg->tx_len >> 0) & 0xff; + packet->header[2] = (msg->tx_len >> 8) & 0xff; + + packet->payload_length = msg->tx_len; + packet->payload = msg->tx_buf; + } else { + FAR const uint8_t *tx = msg->tx_buf; + + packet->header[1] = (msg->tx_len > 0) ? tx[0] : 0; + packet->header[2] = (msg->tx_len > 1) ? tx[1] : 0; + } + + packet->size = sizeof(packet->header) + packet->payload_length; + return OK; +} diff --git a/os/include/tinyara/fs/ioctl.h b/os/include/tinyara/fs/ioctl.h index 97b9dee219..dfde6eb3f9 100644 --- a/os/include/tinyara/fs/ioctl.h +++ b/os/include/tinyara/fs/ioctl.h @@ -397,6 +397,10 @@ #define _LCDIOCVALID(c) (_IOC_TYPE(c)==_SLCDIOCBASE) #define _LCDIOC(nr) _IOC(_SLCDIOCBASE,nr) +#define _MIPIDSIBASE (0x3900) /* Mipidsi device ioctl commands */ + +#define _MIPIDSIIOC(nr) _IOC(_MIPIDSIBASE,nr) +#define _MIPIDSIIOCVALID(c) (_IOC_TYPE(c)==_MIPIDSIBASE) /* boardctl() command definitions *******************************************/ #define _BOARDIOCVALID(c) (_IOC_TYPE(c) == _BOARDBASE) diff --git a/os/include/tinyara/lcd/lcd_dev.h b/os/include/tinyara/lcd/lcd_dev.h index aac7e54f7f..e84ae6540f 100644 --- a/os/include/tinyara/lcd/lcd_dev.h +++ b/os/include/tinyara/lcd/lcd_dev.h @@ -31,7 +31,7 @@ /**************************************************************************** * Pre-processor Definitions ****************************************************************************/ - +#define MAX_NO_PLANES 3 /**************************************************************************** * Type Definitions ****************************************************************************/ diff --git a/os/include/tinyara/lcd/st7701.h b/os/include/tinyara/lcd/st7701.h new file mode 100755 index 0000000000..1fa2eef565 --- /dev/null +++ b/os/include/tinyara/lcd/st7701.h @@ -0,0 +1,57 @@ +/**************************************************************************** + * + * Copyright 2024 Samsung Electronics All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, + * software distributed under the License is distributed on an + * "AS IS" BASIS, WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, + * either express or implied. See the License for the specific + * language governing permissions and limitations under the License. + * + ****************************************************************************/ + +#ifndef __DRIVERS_LCD_ST7701_H +#define __DRIVERS_LCD_ST7701_H + +/**************************************************************************** + * Included Files + ****************************************************************************/ +#include +#include +#include +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ +/* System Function Command Table 1 */ + +#define XRES 480 +#define YRES 800 +/* + 480*800*4 = 1.47MB + 1024*768*4 = 3M +*/ +#define LCDC_IMG_BUF_OFFSET (10 << 20) /*offset is 10M In DDR */ +#define LCDC_IMG_BUF_OFFSET1 (13 << 20) /*offset is 13M In DDR */ +#define LCDC_IMG_BUF_OFFSET2 (16 << 20) /*offset is 16M In DDR */ +#define LCDC_IMG_BUF_OFFSET3 (19 << 20) /*offset is 19M In DDR */ +#define LCDC_IMG_BUF_ALIGNED64B(x) (((x) & ~0x3F) + 0x40)/*Start Addr shall aligned to 64Byte*/ +#define LCDC_IMG_BUF_SIZE LCDC_IMG_BUF_ALIGNED64B(XRES * YRES * 4) + +struct st7701_config_s { + + void (*init)(); + void (*reset)(); + void (*cache_invalidate)(u32 *buffer, int size); //DCache_CleanInvalidate + void (*lcd_reload)(); // LCDC_TrigerSHWReload + void (*lcd_enable)(); //LCDC_Cmd + void (*lcd_layer_enable)(int layer, bool enable); + void (*lcd_put_area)(u8 *lcd_img_buffer, u32 x1, u32 y1, u32 x2, u32 y2); +}; + +#endif /* __DRIVERS_LCD_ST7701_H */ diff --git a/os/include/tinyara/mipidsi/mipi_display.h b/os/include/tinyara/mipidsi/mipi_display.h new file mode 100755 index 0000000000..bbf36c20d4 --- /dev/null +++ b/os/include/tinyara/mipidsi/mipi_display.h @@ -0,0 +1,192 @@ +/**************************************************************************** + * + * Copyright 2024 Samsung Electronics All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * + ****************************************************************************/ + +/**************************************************************************** + * include/nuttx/video/mipi_display.h + * + * Licensed to the Apache Software Foundation (ASF) under one or more + * contributor license agreements. See the NOTICE file distributed with + * this work for additional information regarding copyright ownership. The + * ASF licenses this file to you under the Apache License Version 2.0 (the + * "License"); you may not use this file except in compliance with the + * License. You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing software + * distributed under the License is distributed on an "AS IS" BASIS WITHOUT + * WARRANTIES OR CONDITIONS OF ANY KIND either express or implied. See the + * License for the specific language governing permissions and limitations + * under the License. + * + ****************************************************************************/ + +#ifndef __INCLUDE_NUTTX_VIDEO_MIPI_DISPLAY_H +#define __INCLUDE_NUTTX_VIDEO_MIPI_DISPLAY_H + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ +/* DSI Parameters */ +#define Mhz 1000000UL +#define T_LPX 5 +#define T_HS_PREP 6 +#define T_HS_TRAIL 8 +#define T_HS_EXIT 7 +#define T_HS_ZERO 10 +#define FONT_WIDTH 8 +#define FONT_HEIGHT 16 +#define MIPI_DSI_RTNI 2 //4 +#define MIPI_DSI_HSA 4 +#define MIPI_DSI_HBP 30 +#define MIPI_DSI_HFP 30 + +#define MIPI_DSI_VSA 5 +#define MIPI_DSI_VBP 20 +#define MIPI_DSI_VFP 15 + +#define MIPI_FRAME_RATE 60 + +/* DSI Processor-to-Peripheral transaction types */ + +#define MIPI_DSI_VSYNC_START 0x01 +#define MIPI_DSI_VSYNC_END 0x11 +#define MIPI_DSI_HSYNC_START 0x21 +#define MIPI_DSI_HSYNC_END 0x31 +#define MIPI_DSI_COMPRESSION_MODE 0x07 +#define MIPI_DSI_END_OF_TRANSMISSION 0x08 +#define MIPI_DSI_COLOR_MODE_OFF 0x02 +#define MIPI_DSI_COLOR_MODE_ON 0x12 +#define MIPI_DSI_SHUTDOWN_PERIPHERAL 0x22 +#define MIPI_DSI_TURN_ON_PERIPHERAL 0x32 +#define MIPI_DSI_GENERIC_SHORT_WRITE_0_PARAM 0x03 +#define MIPI_DSI_GENERIC_SHORT_WRITE_1_PARAM 0x13 +#define MIPI_DSI_GENERIC_SHORT_WRITE_2_PARAM 0x23 +#define MIPI_DSI_GENERIC_READ_0_PARAM 0x04 +#define MIPI_DSI_GENERIC_READ_1_PARAM 0x14 +#define MIPI_DSI_GENERIC_READ_2_PARAM 0x24 +#define MIPI_DSI_DCS_SHORT_WRITE_0_PARAM 0x05 +#define MIPI_DSI_DCS_SHORT_WRITE 0x05 +#define MIPI_DSI_DCS_SHORT_WRITE_1_PARAM 0x15 +#define MIPI_DSI_DCS_SHORT_WRITE_PARAM 0x15 +#define MIPI_DSI_DCS_READ_0_PARAM 0x06 +#define MIPI_DSI_EXECUTE_QUEUE 0x16 +#define MIPI_DSI_SET_MAXIMUM_RETURN_PACKET_SIZE 0x37 +#define MIPI_DSI_NULL_PACKET 0x09 +#define MIPI_DSI_BLANKING_PACKET 0x19 +#define MIPI_DSI_LONG_GENERIC_WRITE 0x29 +#define MIPI_DSI_DCS_LONG_WRITE 0x39 +#define MIPI_DSI_PICTURE_PARAMETER_SET 0x0a +#define MIPI_DSI_COMPRESSED_PIXEL_STREAM 0x0b +#define MIPI_DSI_LOOSELY_PACKED_PIXEL_STREAM_YCBCR20 0x0c +#define MIPI_DSI_PACKED_PIXEL_STREAM_YCBCR24 0x1c +#define MIPI_DSI_PACKED_PIXEL_STREAM_YCBCR16 0x2c +#define MIPI_DSI_PACKED_PIXEL_STREAM_RGB30 0x0d +#define MIPI_DSI_PACKED_PIXEL_STREAM_RGB36 0x1d +#define MIPI_DSI_PACKED_PIXEL_STREAM_YCBCR12 0x3d +#define MIPI_DSI_PACKED_PIXEL_STREAM_RGB16 0x0e +#define MIPI_DSI_PACKED_PIXEL_STREAM_RGB18 0x1e +#define MIPI_DSI_PIXEL_STREAM_3BYTE_RGB18 0x2e +#define MIPI_DSI_PACKED_PIXEL_STREAM_RGB24 0x3e + +/* DSI Peripheral-to-Processor transaction data type */ + +#define MIPI_DSI_RX_ACKNOWLEDGE_AND_ERROR_REPORT 0x02 +#define MIPI_DSI_RX_END_OF_TRANSMISSION 0x08 +#define MIPI_DSI_RX_GENERIC_SHORT_READ_RESPONSE_1BYTE 0x11 +#define MIPI_DSI_RX_GENERIC_SHORT_READ_RESPONSE_2BYTE 0x12 +#define MIPI_DSI_RX_GENERIC_LONG_READ_RESPONSE 0x1a +#define MIPI_DSI_RX_DCS_LONG_READ_RESPONSE 0x1c +#define MIPI_DSI_RX_DCS_SHORT_READ_RESPONSE_1BYTE 0x21 +#define MIPI_DSI_RX_DCS_SHORT_READ_RESPONSE_2BYTE 0x22 + +/* DCS commands */ + +#define MIPI_DCS_NOP 0x00 +#define MIPI_DCS_SOFT_RESET 0x01 +#define MIPI_DCS_GET_COMPRESSION_MODE 0x03 +#define MIPI_DCS_GET_DISPLAY_ID 0x04 +#define MIPI_DCS_GET_ERROR_COUNT_ON_DSI 0x05 +#define MIPI_DCS_GET_RED_CHANNEL 0x06 +#define MIPI_DCS_GET_GREEN_CHANNEL 0x07 +#define MIPI_DCS_GET_BLUE_CHANNEL 0x08 +#define MIPI_DCS_GET_DISPLAY_STATUS 0x09 +#define MIPI_DCS_GET_POWER_MODE 0x0a +#define MIPI_DCS_GET_ADDRESS_MODE 0x0b +#define MIPI_DCS_GET_PIXEL_FORMAT 0x0c +#define MIPI_DCS_GET_DISPLAY_MODE 0x0d +#define MIPI_DCS_GET_SIGNAL_MODE 0x0e +#define MIPI_DCS_GET_DIAGNOSTIC_RESULT 0x0f +#define MIPI_DCS_ENTER_SLEEP_MODE 0x10 +#define MIPI_DCS_EXIT_SLEEP_MODE 0x11 +#define MIPI_DCS_ENTER_PARTIAL_MODE 0x12 +#define MIPI_DCS_ENTER_NORMAL_MODE 0x13 +#define MIPI_DCS_GET_IMAGE_CHECKSUM_RGB 0x14 +#define MIPI_DCS_GET_IMAGE_CHECKSUM_CT 0x15 +#define MIPI_DCS_EXIT_INVERT_MODE 0x20 +#define MIPI_DCS_ENTER_INVERT_MODE 0x21 +#define MIPI_DCS_SET_GAMMA_CURVE 0x26 +#define MIPI_DCS_SET_DISPLAY_OFF 0x28 +#define MIPI_DCS_SET_DISPLAY_ON 0x29 +#define MIPI_DCS_SET_COLUMN_ADDRESS 0x2a +#define MIPI_DCS_SET_PAGE_ADDRESS 0x2b +#define MIPI_DCS_WRITE_MEMORY_START 0x2c +#define MIPI_DCS_WRITE_LUT 0x2d +#define MIPI_DCS_READ_MEMORY_START 0x2e +#define MIPI_DCS_SET_PARTIAL_ROWS 0x30 /* MIPI DCS 1.02 - + * MIPI_DCS_SET_PARTIAL_AREA + * before that */ +#define MIPI_DCS_SET_PARTIAL_COLUMNS 0x31 +#define MIPI_DCS_SET_SCROLL_AREA 0x33 +#define MIPI_DCS_SET_TEAR_OFF 0x34 +#define MIPI_DCS_SET_TEAR_ON 0x35 +#define MIPI_DCS_SET_ADDRESS_MODE 0x36 +#define MIPI_DCS_SET_SCROLL_START 0x37 +#define MIPI_DCS_EXIT_IDLE_MODE 0x38 +#define MIPI_DCS_ENTER_IDLE_MODE 0x39 +#define MIPI_DCS_SET_PIXEL_FORMAT 0x3a +#define MIPI_DCS_WRITE_MEMORY_CONTINUE 0x3c +#define MIPI_DCS_SET_3D_CONTROL 0x3d +#define MIPI_DCS_READ_MEMORY_CONTINUE 0x3e +#define MIPI_DCS_GET_3D_CONTROL 0x3f +#define MIPI_DCS_SET_VSYNC_TIMING 0x40 +#define MIPI_DCS_SET_TEAR_SCANLINE 0x44 +#define MIPI_DCS_GET_SCANLINE 0x45 +#define MIPI_DCS_SET_DISPLAY_BRIGHTNESS 0x51 /* MIPI DCS 1.3 */ +#define MIPI_DCS_GET_DISPLAY_BRIGHTNESS 0x52 /* MIPI DCS 1.3 */ +#define MIPI_DCS_WRITE_CONTROL_DISPLAY 0x53 /* MIPI DCS 1.3 */ +#define MIPI_DCS_GET_CONTROL_DISPLAY 0x54 /* MIPI DCS 1.3 */ +#define MIPI_DCS_WRITE_POWER_SAVE 0x55 /* MIPI DCS 1.3 */ +#define MIPI_DCS_GET_POWER_SAVE 0x56 /* MIPI DCS 1.3 */ +#define MIPI_DCS_SET_CABC_MIN_BRIGHTNESS 0x5e /* MIPI DCS 1.3 */ +#define MIPI_DCS_GET_CABC_MIN_BRIGHTNESS 0x5f /* MIPI DCS 1.3 */ +#define MIPI_DCS_READ_DDB_START 0xa1 +#define MIPI_DCS_READ_PPS_START 0xa2 +#define MIPI_DCS_READ_DDB_CONTINUE 0xa8 +#define MIPI_DCS_READ_PPS_CONTINUE 0xa9 + +/* DCS pixel formats */ + +#define MIPI_DCS_PIXEL_FMT_24BIT 7 +#define MIPI_DCS_PIXEL_FMT_18BIT 6 +#define MIPI_DCS_PIXEL_FMT_16BIT 5 +#define MIPI_DCS_PIXEL_FMT_12BIT 3 +#define MIPI_DCS_PIXEL_FMT_8BIT 2 +#define MIPI_DCS_PIXEL_FMT_3BIT 1 + +#endif /* __INCLUDE_NUTTX_VIDEO_MIPI_DISPLAY_H */ diff --git a/os/include/tinyara/mipidsi/mipi_dsi.h b/os/include/tinyara/mipidsi/mipi_dsi.h new file mode 100755 index 0000000000..fdcca2d70d --- /dev/null +++ b/os/include/tinyara/mipidsi/mipi_dsi.h @@ -0,0 +1,897 @@ +/**************************************************************************** + * + * Copyright 2024 Samsung Electronics All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * + ****************************************************************************/ + +/**************************************************************************** + * include/nuttx/video/mipi_dsi.h + * + * Licensed to the Apache Software Foundation (ASF) under one or more + * contributor license agreements. See the NOTICE file distributed with + * this work for additional information regarding copyright ownership. The + * ASF licenses this file to you under the Apache License, Version 2.0 (the + * "License"); you may not use this file except in compliance with the + * License. You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT + * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the + * License for the specific language governing permissions and limitations + * under the License. + * + ****************************************************************************/ + +#ifndef __INCLUDE_NUTTX_VIDEO_MIPI_DSI_H +#define __INCLUDE_NUTTX_VIDEO_MIPI_DSI_H + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/* Define cmd for dsi device */ + +#define MIPIDSI_GETDEVLANES _MIPIDSIIOC(1) +#define MIPIDSI_GETDEVFMT _MIPIDSIIOC(2) +#define MIPIDSI_GETDEVMODE _MIPIDSIIOC(3) +#define MIPIDSI_GETDEVHSRATE _MIPIDSIIOC(4) +#define MIPIDSI_GETDEVLPRATE _MIPIDSIIOC(5) + +/* Define cmd for dsi host */ + +#define MIPIDSI_TRANSFER _MIPIDSIIOC(6) + +/* Define msg flags */ + +#define MIPI_DSI_MSG_REQ_ACK (1 << 0) /* Request ACK from peripheral */ +#define MIPI_DSI_MSG_USE_LPM (1 << 1) /* Use Low Power Mode to + * transmit message */ +#define MIPI_DSI_MSG_AFTER_FRAME (1 << 2) /* Transmit message after frame */ + +/* Tearing Effect Output Line mode */ + +#define MIPI_DSI_DCS_TEAR_MODE_VBLANK 0 /* The TE output line consists of + * V-Blanking information only */ +#define MIPI_DSI_DCS_TEAR_MODE_VHBLANK 1 /* The TE output line consists of + * both V-Blanking and H-Blanking + * information */ + +/* Define pixel color format */ + +#define MIPI_DSI_FMT_RGB888 0 +#define MIPI_DSI_FMT_RGB666 1 +#define MIPI_DSI_FMT_RGB666_PACKED 2 +#define MIPI_DSI_FMT_RGB565 3 + +/* Indicates the status of register 0Ah */ + +#define MIPI_DSI_DCS_POWER_MODE_DISPLAY (1 << 2) +#define MIPI_DSI_DCS_POWER_MODE_NORMAL (1 << 3) +#define MIPI_DSI_DCS_POWER_MODE_SLEEP (1 << 4) +#define MIPI_DSI_DCS_POWER_MODE_PARTIAL (1 << 5) +#define MIPI_DSI_DCS_POWER_MODE_IDLE (1 << 6) + +/* DSI mode flags define */ + +#define MIPI_DSI_MODE_VIDEO (1 << 0) /* Video mode */ +#define MIPI_DSI_MODE_VIDEO_BURST (1 << 1) /* Video burst mode */ +#define MIPI_DSI_MODE_VIDEO_SYNC_PULSE (1 << 2) /* Video pulse mode */ +#define MIPI_DSI_MODE_VIDEO_AUTO_VERT (1 << 3) /* Enable auto vertical + * count mode */ +#define MIPI_DSI_MODE_VIDEO_HSE (1 << 4) /* Enable hsync-end packets + * in vsync-pulse and + * v-porch area */ +#define MIPI_DSI_MODE_VIDEO_NO_HFP (1 << 5) /* Disable hfront-porch area */ +#define MIPI_DSI_MODE_VIDEO_NO_HBP (1 << 6) /* Disable hback-porch area */ +#define MIPI_DSI_MODE_VIDEO_NO_HSA (1 << 7) /* Disable hsync-active area */ +#define MIPI_DSI_MODE_VSYNC_FLUSH (1 << 8) /* Flush display FIFO on vsync + * pulse */ +#define MIPI_DSI_MODE_NO_EOT_PACKET (1 << 9) /* Disable EoT packets in HS + * mode */ +#define MIPI_DSI_CLOCK_NON_CONTINUOUS (1 << 10) /* Device supports + * non-continuous clock + * behavior (DSI spec 5.6.1) */ +#define MIPI_DSI_MODE_LPM (1 << 11) /* Transmit data in low + * power */ +#define MIPI_DSI_MODE_AFTER_FRAME (1 << 12) /* Transmit data after frame + * transfer done */ +#define MIPI_DSI_HS_PKT_END_ALIGNED (1 << 13) /* Transmit data ending at + * the same time for all + * lanes within one hsync */ + +/**************************************************************************** + * Public Types + ****************************************************************************/ + +struct mipi_dsi_host; +struct mipi_dsi_device; + +/* Read/write DSI buffer */ + +struct mipi_dsi_msg +{ + uint8_t channel; /* Virtual channel id */ + uint8_t type; /* Payload data type */ + uint8_t flags; /* Flags controlling this message transmission */ + + size_t tx_len; /* Length of tx_buf */ + FAR const void *tx_buf; /* Data to be written */ + + size_t rx_len; /* Lenght of rx_buf */ + FAR void *rx_buf; /* Data to be read, or NULL */ +}; + +/* Represents a MIPI DSI packet in protocol format */ + +struct mipi_dsi_packet +{ + size_t size; /* Size (in bytes) of the packet */ + uint8_t header[4]; /* The four bytes that make up the header + * (Data ID, Word Count or Packet Data, + * and ECC) */ + size_t payload_length; /* Number of bytes in the payload */ + FAR const uint8_t *payload; /* A pointer to a buffer containing + * the payload */ +}; + +/* DSI bus operations + * + * DSI packets transmitted by .transfer() are passed in as mipi_dsi_msg + * structures. This structure contains information about the type of packet + * being transmitted as well as the transmit and receive buffers. When an + * error is encountered during transmission, this function will return a + * negative error code. On success it shall return the number of bytes + * transmitted for write packets or the number of bytes received for read + * packets. + * + * Note that typically DSI packet transmission is atomic, so the .transfer() + * function will seldomly return anything other than the number of bytes + * contained in the transmit buffer on success. + * + * Also note that those callbacks can be called no matter the state the + * host is in. Drivers that need the underlying device to be powered to + * perform these operations will first need to make sure it's been + * properly enabled. + */ + +struct mipi_dsi_host_ops +{ + /* Attach DSI device to DSI host */ + + CODE int (*attach)(FAR struct mipi_dsi_host *host, + FAR struct mipi_dsi_device *device); + + /* Detach DSI device from DSI host */ + + CODE int (*detach)(FAR struct mipi_dsi_host *host, + FAR struct mipi_dsi_device *device); + + /* Transmit a DSI packet */ + + CODE ssize_t (*transfer)(FAR struct mipi_dsi_host *host, + FAR const struct mipi_dsi_msg *msg); +}; + +struct lcd_data{ + int XPixels; + int YPixels; +}; +/* Dsi host structure */ +struct mipi_dsi_host +{ + FAR const struct mipi_dsi_host_ops *ops; + struct lcd_data config; + int bus; +}; + + +struct mipi_dsi_device_ops +{ + CODE int (*prepare)(FAR struct mipi_dsi_device *device, struct mipi_dsi_msg *msg); + CODE int (*enable)(FAR struct mipi_dsi_device *device); + CODE int (*disable)(FAR struct mipi_dsi_device *device); +}; + + +/* Dsi peripheral device structure panel dsi device */ + +struct mipi_dsi_device +{ + FAR struct mipi_dsi_host *host; /* DSI host for this peripheral, + * almost on the panel */ + char name[32]; /* DSI peripheral chip type */ + uint16_t channel; /* Vitural channel assigned to this */ + uint16_t lanes; /* Number of active data lanes */ + uint8_t format; /* Pixel formal */ + uint32_t mode_flags; /* Dsi operate mode flag */ + uint32_t hs_rate; /* Maximum lane frequency for high speed + * mode in hertz, this shoud be set + * to the real limits of the hardware. */ + uint32_t lp_rate; /* Maximum lane frequency for low power + * mode in hertz, this shoud be set + * to the real limits of the hardware. */ + FAR const struct mipi_dsi_device_ops *ops; +}; + +/**************************************************************************** + * Public Functions Definitions + ****************************************************************************/ + +#ifdef __cplusplus +#define EXTERN extern "C" +extern "C" +{ +#else +#define EXTERN extern +#endif + +/**************************************************************************** + * Name: mipi_dsi_packet_format_is_short + * + * Description: + * Check if a packet is of the short format + * + * Input Parameters: + * type - MIPI DSI data type of the packet + * + * Returned Value: + * True if the packet for the given data type is a short packet, false + * otherwise. + * + ****************************************************************************/ + +bool mipi_dsi_packet_format_is_short(uint8_t type); + +/**************************************************************************** + * Name: mipi_dsi_packet_format_is_long + * + * Description: + * Check if a packet is of the long format + * + * Input Parameters: + * type - MIPI DSI data type of the packet + * + * Returned Value: + * True if the packet for the given data type is a long packet, false + * otherwise. + * + ****************************************************************************/ + +bool mipi_dsi_packet_format_is_long(uint8_t type); + +/**************************************************************************** + * Name: mipi_dsi_create_packet + * + * Description: + * Create a packet from a message according to the DSI protocol + * + * Input Parameters: + * packet - Pointer to a DSI packet structure + * msg - Message to translate into a packet + * + * Returned Value: + * Return: 0 on success or a negative error code on failure. + * + ****************************************************************************/ + +int mipi_dsi_create_packet(FAR struct mipi_dsi_packet *packet, + FAR const struct mipi_dsi_msg *msg); + +/**************************************************************************** + * Name: mipi_dsi_host_register + * + * Description: + * Register mipi dsi host, if defined CONFIG_MIPI_DSI_DRIVER, will create + * character device at /dev. + * + * Input Parameters: + * host - An instance of the dsi host + * + * Returned Value: + * OK if the driver was successfully register; A negated errno value is + * returned on any failure. + * + ****************************************************************************/ + +int mipi_dsi_host_register(FAR struct mipi_dsi_host *host); + +/**************************************************************************** + * Name: mipi_dsi_host_get + * + * Description: + * Find host in list by bus number. Lcd driver can get host by this + * interface to register dsi device. + * + * Input Parameters: + * bus - The dsi host bus number. + * + * Returned Value: + * struct mipi_dsi_host pointer if the host was successfully registered; + * NULL pointer is returned on any failure. + * + ****************************************************************************/ + +FAR struct mipi_dsi_host *mipi_dsi_host_get(int bus); + +/**************************************************************************** + * Name: mipi_dsi_pixel_format_to_bpp + * + * Description: + * Obtain the number of bits per pixel for any given pixel format defined + * by the MIPI DSI specification + * + * Input Parameters: + * fmt - MIPI DSI pixel format + * + * Returned Value: + * The number of bits per pixel of the given pixel format. + * + ****************************************************************************/ + +int mipi_dsi_pixel_format_to_bpp(uint8_t fmt); + +/**************************************************************************** + * Name: mipi_dsi_device_register_full + * + * Description: + * Register mipi dsi device, if defined CONFIG_MIPI_DSI_DRIVER, will create + * character device at /dev/dsiN/dev-xxx. + * + * Input Parameters: + * host - An instance of the dsi host + * name - The name of the dsi device + * channel - The channel used by dsi device + * + * Returned Value: + * struct mipi_dsi_device* if the driver was successfully register; NULL is + * returned on any failure. + * + ****************************************************************************/ + +FAR struct mipi_dsi_device * +mipi_dsi_device_register(FAR struct mipi_dsi_host *host, + FAR const char *name, int channel); + +/**************************************************************************** + * Name: mipi_dsi_attach + * + * Description: + * Attach a DSI device to its DSI host + * + * Input Parameters: + * device - DSI peripheral + * + * Returned Value: + * OK on success or a negative error code on failure. + * + ****************************************************************************/ + +int mipi_dsi_attach(FAR struct mipi_dsi_device *device); + +/**************************************************************************** + * Name: mipi_dsi_detach + * + * Description: + * Detach a DSI device from its DSI host + * + * Input Parameters: + * device - DSI peripheral device + * + * Returned Value: + * OK on success or a negative error code on failure. + * + ****************************************************************************/ + +int mipi_dsi_detach(FAR struct mipi_dsi_device *device); + +/**************************************************************************** + * Name: mipi_dsi_transfer + * + * Description: + * Transfer message to display modules + * + * Input Parameters: + * device - DSI peripheral + * msg - Message to transfer + * + * Returned Value: + * The number of bytes successfully transfered or a negative error code on + * failure. + * + ****************************************************************************/ + +ssize_t mipi_dsi_transfer(FAR struct mipi_dsi_device *device, + FAR struct mipi_dsi_msg *msg); + +/**************************************************************************** + * Name: mipi_dsi_shutdown_peripheral + * + * Description: + * Send a Shutdown Peripheral command to the dsi device + * + * Input Parameters: + * device - DSI peripheral device + * + * Returned Value: + * OK on success or a negative error code on failure. + * + ****************************************************************************/ + +int mipi_dsi_shutdown_peripheral(FAR struct mipi_dsi_device *device); + +/**************************************************************************** + * Name: mipi_dsi_turn_on_peripheral + * + * Description: + * Send a Turn On Peripheral command to the dsi device + * + * Input Parameters: + * device - DSI peripheral device + * + * Returned Value: + * OK on success or a negative error code on failure. + * + ****************************************************************************/ + +int mipi_dsi_turn_on_peripheral(FAR struct mipi_dsi_device *device); + +/**************************************************************************** + * Name: mipi_dsi_set_maximum_return_packet_size + * + * Description: + * Specify the maximum size of the payload in a long packet transmitted + * from the peripheral back to the device host processor + * + * Input Parameters: + * device - DSI peripheral device + * value - The maximum size of the payload + * + * Returned Value: + * OK on success or a negative error code on failure. + * + ****************************************************************************/ + +int mipi_dsi_set_maximum_return_packet_size( + FAR struct mipi_dsi_device *device, uint16_t value); + +/**************************************************************************** + * Name: mipi_dsi_compression_mode + * + * Description: + * Enable / disable DSC on the peripheral. Enable or disable Display Stream + * Compression on the peripheral using the default Picture Parameter Set + * and VESA DSC 1.1 algorithm. + * + * Input Parameters: + * device - DSI peripheral device + * enable - Whether to enable or disable the DSC + * + * Returned Value: + * OK on success or a negative error code on failure. + * + ****************************************************************************/ + +int mipi_dsi_compression_mode(FAR struct mipi_dsi_device *device, + bool enable); + +/**************************************************************************** + * Name: mipi_dsi_generic_write + * + * Description: + * Transmit data using a generic write packet + * + * Input Parameters: + * device - DSI peripheral device + * payload - buffer containing the payload + * size - size of the payload + * + * Returned Value: + * OK on success or a negative error code on failure. + * + ****************************************************************************/ + +int mipi_dsi_generic_write(FAR struct mipi_dsi_device *device, + FAR const void *payload, size_t size); + +/**************************************************************************** + * Name: mipi_dsi_generic_read + * + * Description: + * Receive data using a generic read packet. + * This function will automatically choose the right data type depending on + * the number of parameters passed in. + * + * Input Parameters: + * device - DSI peripheral device + * params - buffer containing the request parameters + * num_params - number of request parameters + * data - buffer in which to return the received data + * size - size of receive buffer + * + * Returned Value: + * The number of bytes successfully read or a negative error code on + * failure. + * + ****************************************************************************/ + +ssize_t mipi_dsi_generic_read(FAR struct mipi_dsi_device *device, + FAR const void *params, size_t num_params, + FAR void *data, size_t size); + +/**************************************************************************** + * Name: mipi_dsi_dcs_write_buffer + * + * Description: + * Transmit a DCS command with payload. + * This function will automatically choose the right data type depending on + * the command payload length. + * + * Input Parameters: + * device - DSI peripheral device + * data - buffer containing data to be transmitted + * len - size of transmission buffer + * + * Returned Value: + * The number of bytes successfully transmitted or a negative error + * code on failure. + * + ****************************************************************************/ + +ssize_t mipi_dsi_dcs_write_buffer(FAR struct mipi_dsi_device *device, + FAR const void *data, size_t len); + +/**************************************************************************** + * Name: mipi_dsi_dcs_write + * + * Description: + * Send DCS write command. + * This function will automatically choose the right data type depending on + * the command payload length. + * + * Input Parameters: + * device - DSI peripheral device + * cmd - DCS command + * data - buffer containing the command payload + * len - command payload length + * + * Returned Value: + * The number of bytes successfully transmitted or a negative error + * code on failure. + * + ****************************************************************************/ + +ssize_t mipi_dsi_dcs_write(FAR struct mipi_dsi_device *device, uint8_t cmd, + FAR const void *data, size_t len); + +/**************************************************************************** + * Name: mipi_dsi_dcs_read + * + * Description: + * Send DCS read request command. + * + * Input Parameters: + * device - DSI peripheral device + * cmd - DCS command + * data - buffer in which to receive data + * len - size of receive buffer + * + * Returned Value: + * The number of bytes read or a negative error code on failure. + * + ****************************************************************************/ + +ssize_t mipi_dsi_dcs_read(FAR struct mipi_dsi_device *device, uint8_t cmd, + FAR void *data, size_t len); + +/**************************************************************************** + * Name: mipi_dsi_dcs_nop + * + * Description: + * Send DCS nop packet + * + * Input Parameters: + * device - DSI peripheral device + * + * Returned Value: + * OK on success or a negative error code on failure. + * + ****************************************************************************/ + +int mipi_dsi_dcs_nop(FAR struct mipi_dsi_device *device); + +/**************************************************************************** + * Name: mipi_dsi_dcs_soft_reset + * + * Description: + * Send a software reset of the display module + * + * Input Parameters: + * device - DSI peripheral device + * + * Returned Value: + * OK on success or a negative error code on failure. + * + ****************************************************************************/ + +int mipi_dsi_dcs_soft_reset(FAR struct mipi_dsi_device *device); + +/**************************************************************************** + * Name: mipi_dsi_dcs_get_power_mode + * + * Description: + * Query the display module's current power mode + * + * Input Parameters: + * device - DSI peripheral device + * mode - return location of the current power mode + * + * Returned Value: + * OK on success or a negative error code on failure. + * + ****************************************************************************/ + +int mipi_dsi_dcs_get_power_mode(FAR struct mipi_dsi_device *device, + FAR uint8_t *mode); + +/**************************************************************************** + * Name: mipi_dsi_dcs_get_pixel_format + * + * Description: + * Gets the pixel format for the RGB image data used by the display module. + * + * Input Parameters: + * device - DSI peripheral device + * format - return location of the pixel format + * + * Returned Value: + * OK on success or a negative error code on failure. + * + ****************************************************************************/ + +int mipi_dsi_dcs_get_pixel_format(FAR struct mipi_dsi_device *device, + FAR uint8_t *format); + +/**************************************************************************** + * Name: mipi_dsi_dcs_enter_sleep_mode + * + * Description: + * Send a Enter Sleep Mode command to display module. + * + * Input Parameters: + * device - DSI peripheral device + * + * Returned Value: + * OK on success or a negative error code on failure. + * + ****************************************************************************/ + +int mipi_dsi_dcs_enter_sleep_mode(FAR struct mipi_dsi_device *device); + +/**************************************************************************** + * Name: mipi_dsi_dcs_exit_sleep_mode + * + * Description: + * Send a Exit Sleep Mode command to display module. + * + * Input Parameters: + * device - DSI peripheral device + * + * Returned Value: + * OK on success or a negative error code on failure. + * + ****************************************************************************/ + +int mipi_dsi_dcs_exit_sleep_mode(FAR struct mipi_dsi_device *device); + +/**************************************************************************** + * Name: mipi_dsi_dcs_set_display_off + * + * Description: + * Send a Display OFF command to display module. Stop displaying the image + * data on the display device. + * + * Input Parameters: + * device - DSI peripheral device + * + * Returned Value: + * OK on success or a negative error code on failure. + * + ****************************************************************************/ + +int mipi_dsi_dcs_set_display_off(FAR struct mipi_dsi_device *device); + +/**************************************************************************** + * Name: mipi_dsi_dcs_set_display_on + * + * Description: + * Send a Display On command to display module. Start displaying the image + * data on the display device. + * + * Input Parameters: + * device - DSI peripheral device + * + * Returned Value: + * OK on success or a negative error code on failure. + * + ****************************************************************************/ + +int mipi_dsi_dcs_set_display_on(FAR struct mipi_dsi_device *device); + +/**************************************************************************** + * Name: mipi_dsi_dcs_set_column_address + * + * Description: + * Define the column extent of the frame memory accessed by the host + * processor + * + * Input Parameters: + * device - DSI peripheral device + * start - first column address of frame memory + * end - last column address of frame memory + * + * Returned Value: + * OK on success or a negative error code on failure. + * + ****************************************************************************/ + +int mipi_dsi_dcs_set_column_address(FAR struct mipi_dsi_device *device, + uint16_t start, uint16_t end); + +/**************************************************************************** + * Name: mipi_dsi_dcs_set_page_address + * + * Description: + * Define the page extent of the frame memory accessed by the host + * processor + * + * Input Parameters: + * device - DSI peripheral device + * start - first page address of frame memory + * end - last page address of frame memory + * + * Returned Value: + * OK on success or a negative error code on failure. + * + ****************************************************************************/ + +int mipi_dsi_dcs_set_page_address(FAR struct mipi_dsi_device *device, + uint16_t start, uint16_t end); + +/**************************************************************************** + * Name: mipi_dsi_dcs_set_tear_off + * + * Description: + * Turn off the display module's Tearing Effect output signal on the TE + * signal line + * + * Input Parameters: + * device - DSI peripheral device + * + * Returned Value: + * OK on success or a negative error code on failure. + * + ****************************************************************************/ + +int mipi_dsi_dcs_set_tear_off(FAR struct mipi_dsi_device *device); + +/**************************************************************************** + * Name: mipi_dsi_dcs_set_tear_on + * + * Description: + * Turn on the display module's Tearing Effect output signal on the TE + * signal line. + * + * Input Parameters: + * device - DSI peripheral device + * mode - Tearing Mode, MIPI_DSI_DCS_TEAR_MODE_VBLANK or + * MIPI_DSI_DCS_TEAR_MODE_VHBLANK + * + * Returned Value: + * OK on success or a negative error code on failure. + * + ****************************************************************************/ + +int mipi_dsi_dcs_set_tear_on(FAR struct mipi_dsi_device *device, + uint8_t mode); + +/**************************************************************************** + * Name: mipi_dsi_dcs_set_pixel_format + * + * Description: + * Sets the pixel format for the RGB image data used by the display module. + * + * Input Parameters: + * device - DSI peripheral device + * format - pixel format + * + * Returned Value: + * OK on success or a negative error code on failure. + * + ****************************************************************************/ + +int mipi_dsi_dcs_set_pixel_format(FAR struct mipi_dsi_device *device, + uint8_t format); + +/**************************************************************************** + * Name: mipi_dsi_dcs_set_tear_scanline + * + * Description: + * Set the scanline to use as trigger for the Tearing Effect output signal + * of the display module. + * + * Input Parameters: + * device - DSI peripheral device + * scanline - scanline to use as trigger + * + * Returned Value: + * OK on success or a negative error code on failure. + * + ****************************************************************************/ + +int mipi_dsi_dcs_set_tear_scanline(FAR struct mipi_dsi_device *device, + uint16_t scanline); + +/**************************************************************************** + * Name: mipi_dsi_dcs_set_display_brightness + * + * Description: + * Sets the brightness value of the display. + * + * Input Parameters: + * device - DSI peripheral device + * brightness - brightness value + * + * Returned Value: + * OK on success or a negative error code on failure. + * + ****************************************************************************/ + +int mipi_dsi_dcs_set_display_brightness(FAR struct mipi_dsi_device *device, + uint16_t brightness); + +/**************************************************************************** + * Name: mipi_dsi_dcs_get_display_brightness + * + * Description: + * Gets the current brightness value of the display. + * + * Input Parameters: + * device - DSI peripheral device + * brightness - brightness value + * + * Returned Value: + * OK on success or a negative error code on failure. + * + ****************************************************************************/ + +int mipi_dsi_dcs_get_display_brightness(FAR struct mipi_dsi_device *device, + FAR uint16_t *brightness); + +#undef EXTERN +#ifdef __cplusplus +} +#endif +#endif /* __INCLUDE_NUTTX_VIDEO_MIPI_DSI_H */