add camera driver and examples for edu-riscv64
This commit is contained in:
parent
f22fbc3c94
commit
06ed03337a
|
@ -105,6 +105,8 @@ menu "test app"
|
|||
menuconfig USER_TEST_HWTIMER
|
||||
select BSP_USING_HWTIMER
|
||||
select BSP_USING_GPIO
|
||||
select RESOURCES_PIN
|
||||
select BSP_USING_LED
|
||||
bool "Config test hwtimer"
|
||||
default n
|
||||
if USER_TEST_HWTIMER
|
||||
|
@ -139,6 +141,18 @@ menu "test app"
|
|||
endif
|
||||
endif
|
||||
|
||||
menuconfig USER_TEST_TOUCH
|
||||
select BSP_USING_TOUCH
|
||||
bool "Config test touch"
|
||||
default n
|
||||
if USER_TEST_TOUCH
|
||||
if ADD_XIZI_FETURES
|
||||
config TOUCH_DEV_DRIVER
|
||||
string "Set touch dev path"
|
||||
default "/dev/touch_dev"
|
||||
endif
|
||||
endif
|
||||
|
||||
menuconfig USER_TEST_I2C
|
||||
select BSP_USING_I2C
|
||||
bool "Config test i2c"
|
||||
|
@ -151,6 +165,22 @@ menu "test app"
|
|||
endif
|
||||
endif
|
||||
|
||||
menuconfig USER_TEST_CAMERA
|
||||
select BSP_USING_CAMERA
|
||||
select BSP_USING_LCD
|
||||
bool "Config test camera with lcd"
|
||||
default n
|
||||
if USER_TEST_CAMERA
|
||||
if ADD_XIZI_FETURES
|
||||
config CAMERA_DEV_DRIVER
|
||||
string "Set camera dev path"
|
||||
default "/dev/camera_dev"
|
||||
config CAMERA_LCD_DEV_DRIVER
|
||||
string "Set lcd dev path"
|
||||
default "/dev/lcd_dev"
|
||||
endif
|
||||
endif
|
||||
|
||||
config USER_TEST_SEMC
|
||||
bool "Config test semc sdram"
|
||||
default n
|
||||
|
|
|
@ -67,7 +67,15 @@ ifeq ($(CONFIG_ADD_XIZI_FETURES),y)
|
|||
|
||||
ifeq ($(CONFIG_USER_TEST_WDT),y)
|
||||
SRC_FILES += test_wdt.c
|
||||
endif
|
||||
endif
|
||||
|
||||
ifeq ($(CONFIG_USER_TEST_TOUCH),y)
|
||||
SRC_FILES += test_touch.c
|
||||
endif
|
||||
|
||||
ifeq ($(CONFIG_USER_TEST_CAMERA),y)
|
||||
SRC_FILES += test_camera.c
|
||||
endif
|
||||
|
||||
include $(KERNEL_ROOT)/compiler.mk
|
||||
endif
|
||||
|
|
|
@ -0,0 +1,108 @@
|
|||
#include <stdio.h>
|
||||
#include <string.h>
|
||||
#include <transform.h>
|
||||
|
||||
#define NULL_PARAMETER 0
|
||||
|
||||
#define DVP_INIT 0x00U
|
||||
#define REG_SCCB_READ 0x12U
|
||||
#define REG_SCCB_WRITE 0x13U
|
||||
#define OUTPUT_CONFIG 0x20U
|
||||
#define LCD_STRING_TYPE 0
|
||||
#define LCD_DOT_TYPE 1
|
||||
#define LCD_SIZE 320
|
||||
|
||||
static uint16_t image_buff[384000];
|
||||
|
||||
void TestCamera(int argc, char *argv[])
|
||||
{
|
||||
int frame_counter = 10000;
|
||||
if (argc > 1)
|
||||
{
|
||||
frame_counter = atoi(argv[1]);
|
||||
}
|
||||
printf("This test will refresh %d frames\n", frame_counter);
|
||||
|
||||
int camera_fd = PrivOpen(CAMERA_DEV_DRIVER, O_RDWR);
|
||||
if (camera_fd < 0)
|
||||
{
|
||||
printf("open camera fd error:%d\n", camera_fd);
|
||||
return;
|
||||
}
|
||||
int lcd_fd = PrivOpen(CAMERA_LCD_DEV_DRIVER, O_RDWR);
|
||||
if (lcd_fd < 0)
|
||||
{
|
||||
printf("open lcd fd error:%d\n", lcd_fd);
|
||||
return;
|
||||
}
|
||||
|
||||
//configure the camera's output address
|
||||
struct PrivIoctlCfg ioctl_cfg;
|
||||
ioctl_cfg.ioctl_driver_type = CAMERA_TYPE;
|
||||
struct CameraCfg camera_cfg ={
|
||||
.gain_manu_enable = 0,
|
||||
.gain = 0xFF,
|
||||
.window_w = 800,
|
||||
.window_h = 600,
|
||||
.output_w = IMAGE_WIDTH,
|
||||
.output_h = IMAGE_HEIGHT,
|
||||
.window_xoffset = 0,
|
||||
.window_yoffset = 0
|
||||
};
|
||||
ioctl_cfg.args = &camera_cfg;
|
||||
if (0 != PrivIoctl(camera_fd, OPE_CFG, &ioctl_cfg))
|
||||
{
|
||||
printf("camera pin fd error %d\n", camera_fd);
|
||||
PrivClose(camera_fd);
|
||||
return;
|
||||
}
|
||||
|
||||
ioctl_cfg.args = (void *)image_buff;
|
||||
|
||||
if (0 != PrivRead(camera_fd, image_buff, NULL_PARAMETER))
|
||||
{
|
||||
printf("camera pin fd error %d\n", camera_fd);
|
||||
PrivClose(camera_fd);
|
||||
return;
|
||||
}
|
||||
|
||||
printf("address buff is %x\n", image_buff);
|
||||
|
||||
|
||||
LcdWriteParam graph_param;
|
||||
graph_param.type = LCD_DOT_TYPE;
|
||||
|
||||
//clear the LCD
|
||||
uint16_t back_color[LCD_SIZE];
|
||||
memset(back_color,0,sizeof(back_color));
|
||||
for (int i = 0; i < LCD_SIZE; i++)
|
||||
{
|
||||
graph_param.pixel_info.pixel_color = &back_color;
|
||||
graph_param.pixel_info.x_startpos = 0;
|
||||
graph_param.pixel_info.y_startpos = i;
|
||||
graph_param.pixel_info.x_endpos = LCD_SIZE -1;
|
||||
graph_param.pixel_info.y_endpos = i;
|
||||
PrivWrite(lcd_fd, &graph_param, NULL_PARAMETER);
|
||||
}
|
||||
|
||||
//refresh the LCD using photo of camera
|
||||
while (frame_counter--)
|
||||
{
|
||||
for (int i = 0; i < IMAGE_HEIGHT; i++)
|
||||
{
|
||||
graph_param.pixel_info.pixel_color = image_buff + i * IMAGE_WIDTH;
|
||||
graph_param.pixel_info.x_startpos = 0;
|
||||
graph_param.pixel_info.y_startpos = i + (LCD_SIZE - IMAGE_HEIGHT) / 2;
|
||||
graph_param.pixel_info.x_endpos = IMAGE_WIDTH - 1;
|
||||
graph_param.pixel_info.y_endpos = i + (LCD_SIZE - IMAGE_HEIGHT) / 2;
|
||||
PrivWrite(lcd_fd, &graph_param, NULL_PARAMETER);
|
||||
}
|
||||
}
|
||||
|
||||
// close test
|
||||
PrivClose(lcd_fd);
|
||||
PrivClose(camera_fd);
|
||||
printf("The camera test is finished successfully\n");
|
||||
}
|
||||
|
||||
PRIV_SHELL_CMD_FUNCTION(TestCamera, a camera test sample, PRIV_SHELL_CMD_MAIN_ATTR);
|
|
@ -6,28 +6,23 @@
|
|||
#define NULL_PARAMETER 0
|
||||
|
||||
static uint16_t pinval=0;
|
||||
static uint16_t pin_fd=0;
|
||||
|
||||
void ledflip(void *parameter)
|
||||
{
|
||||
int tmp_fd = *(int*)parameter;
|
||||
struct PinStat pin_led;
|
||||
pin_led.pin = BSP_LED_PIN;
|
||||
pin_led.val = !pinval;
|
||||
pinval = !pinval;
|
||||
PrivWrite(tmp_fd,&pin_led,NULL_PARAMETER);
|
||||
printf("Timer has callback once\n");
|
||||
PrivWrite(pin_fd,&pin_led,NULL_PARAMETER);
|
||||
// printf("Timer has callback once:%d\n",pinval);
|
||||
}
|
||||
|
||||
void TestHwTimer(int argc, char *argv[])
|
||||
void TestHwTimer(void)
|
||||
{
|
||||
x_ticks_t period = 100;//uint:10ms
|
||||
|
||||
if(argc>1){
|
||||
period = (x_ticks_t)atoi(argv[1]);
|
||||
}
|
||||
|
||||
|
||||
int pin_fd = PrivOpen(HWTIMER_PIN_DEV_DRIVER, O_RDWR);
|
||||
pin_fd = PrivOpen(HWTIMER_PIN_DEV_DRIVER, O_RDWR);
|
||||
if(pin_fd<0){
|
||||
printf("open pin fd error:%d\n",pin_fd);
|
||||
return;
|
||||
|
@ -52,10 +47,6 @@ void TestHwTimer(int argc, char *argv[])
|
|||
int32 timer_handle = KCreateTimer("LED on and off by 1s",&ledflip,&pin_fd,period,TIMER_TRIGGER_PERIODIC);
|
||||
|
||||
KTimerStartRun(timer_handle);
|
||||
PrivTaskDelay(10000);
|
||||
KTimerQuitRun(timer_handle);
|
||||
|
||||
KDeleteTimer(timer_handle);
|
||||
|
||||
}
|
||||
|
||||
|
|
|
@ -0,0 +1,30 @@
|
|||
#include <stdio.h>
|
||||
#include <string.h>
|
||||
#include <transform.h>
|
||||
|
||||
#define NULL_PARAMETER 0
|
||||
|
||||
void TestTouch(void)
|
||||
{
|
||||
int touch_fd = PrivOpen(TOUCH_DEV_DRIVER, O_RDWR);
|
||||
if (touch_fd < 0)
|
||||
{
|
||||
printf("open touch fd error:%d\n", touch_fd);
|
||||
return;
|
||||
}
|
||||
|
||||
// draw text
|
||||
struct TouchDataStandard touch_pixel;
|
||||
memset(&touch_pixel,0,sizeof(touch_pixel));
|
||||
|
||||
while(1){
|
||||
if(0 > PrivRead(touch_fd, &touch_pixel, NULL_PARAMETER)){
|
||||
printf("read touch error\n");
|
||||
return;
|
||||
}
|
||||
printf("touch pixel position x:%d,y:%d\n",touch_pixel.x,touch_pixel.y);
|
||||
}
|
||||
PrivClose(touch_fd);
|
||||
}
|
||||
|
||||
PRIV_SHELL_CMD_FUNCTION(TestTouch, a touch test sample, PRIV_SHELL_CMD_MAIN_ATTR);
|
|
@ -173,6 +173,7 @@ int PrivIoctl(int fd, int cmd, void *args)
|
|||
case ADC_TYPE:
|
||||
case DAC_TYPE:
|
||||
case WDT_TYPE:
|
||||
case CAMERA_TYPE:
|
||||
ret = ioctl(fd, cmd, ioctl_cfg->args);
|
||||
break;
|
||||
default:
|
||||
|
|
|
@ -150,9 +150,18 @@ enum IoctlDriverType
|
|||
DAC_TYPE,
|
||||
WDT_TYPE,
|
||||
RTC_TYPE,
|
||||
CAMERA_TYPE,
|
||||
DEFAULT_TYPE,
|
||||
};
|
||||
|
||||
|
||||
struct DvpRegConfigureInfo
|
||||
{
|
||||
uint8_t device_addr;
|
||||
uint16_t reg_addr;
|
||||
uint8_t reg_value;
|
||||
} ;
|
||||
|
||||
struct PrivIoctlCfg
|
||||
{
|
||||
enum IoctlDriverType ioctl_driver_type;
|
||||
|
@ -180,6 +189,18 @@ typedef struct
|
|||
void* pixel_color;
|
||||
}LcdPixelParam;
|
||||
|
||||
struct CameraCfg
|
||||
{
|
||||
uint16_t window_w;
|
||||
uint16_t window_h;
|
||||
uint16_t window_xoffset;
|
||||
uint16_t window_yoffset;
|
||||
uint16_t output_w;
|
||||
uint16_t output_h;
|
||||
uint8_t gain;
|
||||
uint8_t gain_manu_enable;
|
||||
};
|
||||
|
||||
typedef struct
|
||||
{
|
||||
char type; // 0:write string;1:write dot
|
||||
|
|
|
@ -1,5 +1,4 @@
|
|||
# include $(LVGL_DIR)/$(LVGL_DIR_NAME)/examples/examples.mk
|
||||
include $(LVGL_DIR)/$(LVGL_DIR_NAME)/porting/porting.mk
|
||||
include $(LVGL_DIR)/$(LVGL_DIR_NAME)/examples/examples.mk
|
||||
include $(LVGL_DIR)/$(LVGL_DIR_NAME)/src/extra/extra.mk
|
||||
include $(LVGL_DIR)/$(LVGL_DIR_NAME)/src/core/lv_core.mk
|
||||
include $(LVGL_DIR)/$(LVGL_DIR_NAME)/src/draw/lv_draw.mk
|
||||
|
@ -7,4 +6,4 @@ include $(LVGL_DIR)/$(LVGL_DIR_NAME)/src/font/lv_font.mk
|
|||
include $(LVGL_DIR)/$(LVGL_DIR_NAME)/src/gpu/lv_gpu.mk
|
||||
include $(LVGL_DIR)/$(LVGL_DIR_NAME)/src/hal/lv_hal.mk
|
||||
include $(LVGL_DIR)/$(LVGL_DIR_NAME)/src/misc/lv_misc.mk
|
||||
include $(LVGL_DIR)/$(LVGL_DIR_NAME)/src/widgets/lv_widgets.mk
|
||||
include $(LVGL_DIR)/$(LVGL_DIR_NAME)/src/widgets/lv_widgets.mk
|
|
@ -48,6 +48,7 @@ Modification:
|
|||
#include "connect_rtc.h"
|
||||
#include "connect_hwtimer.h"
|
||||
#include "connect_wdt.h"
|
||||
#include "connect_dvp.h"
|
||||
|
||||
// #if defined(FS_VFS)
|
||||
// #include <iot-vfs.h>
|
||||
|
@ -210,6 +211,9 @@ struct InitSequenceDesc _board_init[] =
|
|||
#endif
|
||||
#ifdef BSP_USING_WDT
|
||||
{"hw_wdt", HwWdtInit },
|
||||
#endif
|
||||
#ifdef BSP_USING_CAMERA
|
||||
{"hw_camera", HwDvpInit },
|
||||
#endif
|
||||
{ " NONE ",NONE },
|
||||
};
|
||||
|
@ -222,6 +226,7 @@ void InitBoardHardware(void)
|
|||
|
||||
SysctlPllSetFreq(SYSCTL_PLL0, 800000000UL);
|
||||
SysctlPllSetFreq(SYSCTL_PLL1, 400000000UL);
|
||||
SysctlPllSetFreq(SYSCTL_PLL2, 45158400UL);
|
||||
#ifdef BSP_USING_GPIO
|
||||
/* Init FPIOA */
|
||||
FpioaInit();
|
||||
|
@ -235,7 +240,9 @@ void InitBoardHardware(void)
|
|||
#ifdef BSP_USING_UART
|
||||
HwUartInit();
|
||||
#endif
|
||||
|
||||
// #ifdef BSP_USING_CAMERA
|
||||
// HwDvpInit();
|
||||
// #endif
|
||||
/* initialize memory system */
|
||||
InitBoardMemory(MEMORY_START_ADDRESS, MEMORY_END_ADDRESS);
|
||||
|
||||
|
|
|
@ -112,3 +112,12 @@ menuconfig BSP_USING_WDT
|
|||
if BSP_USING_WDT
|
||||
source "$BSP_DIR/third_party_driver/watchdog/Kconfig"
|
||||
endif
|
||||
|
||||
menuconfig BSP_USING_CAMERA
|
||||
bool "Using camera device"
|
||||
default y
|
||||
select RESOURCES_CAMERA
|
||||
if BSP_USING_CAMERA
|
||||
source "$BSP_DIR/third_party_driver/dvp/Kconfig"
|
||||
endif
|
||||
|
||||
|
|
|
@ -56,5 +56,9 @@ ifeq ($(CONFIG_BSP_USING_WDT),y)
|
|||
SRC_DIR += watchdog
|
||||
endif
|
||||
|
||||
ifeq ($(CONFIG_BSP_USING_CAMERA),y)
|
||||
SRC_DIR += dvp
|
||||
endif
|
||||
|
||||
|
||||
include $(KERNEL_ROOT)/compiler.mk
|
||||
|
|
|
@ -0,0 +1,46 @@
|
|||
if BSP_USING_CAMERA
|
||||
config DVP_XCLK_RATE
|
||||
int "Camera interface clk rate"
|
||||
default 24000000
|
||||
config IMAGE_WIDTH
|
||||
int "Camera photo width"
|
||||
default 320
|
||||
config IMAGE_HEIGHT
|
||||
int "Camera photo height"
|
||||
default 240
|
||||
config DVP_BURST_ENABLE
|
||||
bool "brust mode enable"
|
||||
default y
|
||||
config DVP_AUTO_ENABLE
|
||||
bool "auto recv image mode enable"
|
||||
default n
|
||||
config DVP_AI_OUTPUT
|
||||
bool "ai output enable"
|
||||
default n
|
||||
config DVP_INTERRUPT_ENABLE
|
||||
bool "interrupt enable"
|
||||
default y
|
||||
|
||||
config CAMERA_BUS_NAME
|
||||
string "camera bus name"
|
||||
default "camera"
|
||||
config CAMERA_DRV_NAME
|
||||
string "camera driver name"
|
||||
default "camera_drv"
|
||||
config CAMERA_DEVICE_NAME
|
||||
string "camera device name"
|
||||
default "camera_dev"
|
||||
|
||||
choice
|
||||
prompt "set camera framesize and fps"
|
||||
default SVGA_25FPS_MODE
|
||||
|
||||
config UXGA_15FPS_MODE
|
||||
bool "using uxga in 15fps"
|
||||
|
||||
config SVGA_25FPS_MODE
|
||||
bool "using svag in 25fps"
|
||||
endchoice
|
||||
|
||||
|
||||
endif
|
|
@ -0,0 +1,4 @@
|
|||
SRC_FILES := connect_dvp.c dvp.c ov2640.c
|
||||
|
||||
|
||||
include $(KERNEL_ROOT)/compiler.mk
|
|
@ -0,0 +1,242 @@
|
|||
#include <connect_dvp.h>
|
||||
#include <dvp.h>
|
||||
#include <board.h>
|
||||
#include "sysctl.h"
|
||||
#include "bsp.h"
|
||||
#include "plic.h"
|
||||
#include <ov2640.h>
|
||||
|
||||
#define REG_SCCB_READ 0x12U
|
||||
#define REG_SCCB_WRITE 0x13U
|
||||
#define SCCB_REG_LENGTH 0x08U
|
||||
|
||||
// irq interrupt function
|
||||
static int on_irq_dvp(int irq, void *arg)
|
||||
{
|
||||
if (dvp_get_interrupt(DVP_STS_FRAME_FINISH))
|
||||
{
|
||||
dvp_clear_interrupt(DVP_STS_FRAME_FINISH);
|
||||
}
|
||||
else
|
||||
{
|
||||
dvp_start_convert();
|
||||
dvp_clear_interrupt(DVP_STS_FRAME_START);
|
||||
}
|
||||
return 0;
|
||||
}
|
||||
|
||||
struct DvpRegConfigureInfo
|
||||
{
|
||||
uint8_t device_addr;
|
||||
uint16_t reg_addr;
|
||||
uint8_t reg_value;
|
||||
};
|
||||
|
||||
static struct CameraCfg sensor_config = {
|
||||
.output_h = IMAGE_HEIGHT,//will be resize from window below in ov2640
|
||||
.output_w = IMAGE_WIDTH,
|
||||
.window_h = 600, //register configure in ov2640.h
|
||||
.window_w = 800, //to make window as large as cmos selected size
|
||||
.window_xoffset = 0,
|
||||
.window_yoffset = 0,
|
||||
.gain_manu_enable = 0,
|
||||
.gain = 0x00
|
||||
};
|
||||
|
||||
static uint32 dvpDrvInit(void)
|
||||
{
|
||||
x_err_t ret = EOK;
|
||||
dvp_init(SCCB_REG_LENGTH);
|
||||
dvp_set_xclk_rate(DVP_XCLK_RATE);
|
||||
dvp_set_image_format(DVP_CFG_RGB_FORMAT);
|
||||
dvp_set_image_size(IMAGE_WIDTH, IMAGE_HEIGHT);
|
||||
dvp_set_output_enable(DVP_OUTPUT_DISPLAY, 0);
|
||||
dvp_set_output_enable(DVP_OUTPUT_AI, 0);
|
||||
ov2640_init();
|
||||
sensorConfigure(&sensor_config);
|
||||
|
||||
sysctl_set_spi0_dvp_data(1);
|
||||
#ifdef DVP_BURST_ENABLE
|
||||
dvp_enable_burst();
|
||||
#endif
|
||||
#ifdef DVP_AUTO_ENABLE
|
||||
dvp_disable_auto();
|
||||
#endif
|
||||
#ifdef DVP_AI_OUTPUT
|
||||
dvp_set_output_enable(DVP_OUTPUT_AI, 1);
|
||||
dvp_set_ai_addr((uint32_t)DVP_AI_RED_ADRESS, (uint32_t)DVP_AI_GREEN_ADRESS, (uint32_t)DVP_AI_BLUE_ADRESS);
|
||||
#endif
|
||||
#ifdef DVP_INTERRUPT_ENABLE
|
||||
dvp_config_interrupt(DVP_CFG_START_INT_ENABLE | DVP_CFG_FINISH_INT_ENABLE, 0);
|
||||
isrManager.done->registerIrq(IRQN_DVP_INTERRUPT, (IsrHandlerType)on_irq_dvp, NULL);
|
||||
isrManager.done->enableIrq(IRQN_DVP_INTERRUPT);
|
||||
dvp_clear_interrupt(DVP_STS_FRAME_START | DVP_STS_FRAME_FINISH);
|
||||
dvp_config_interrupt(DVP_CFG_START_INT_ENABLE | DVP_CFG_FINISH_INT_ENABLE, 1);
|
||||
KPrintf("camera interrupt has open!\n");
|
||||
#endif
|
||||
return ret;
|
||||
}
|
||||
|
||||
static uint32 readDvpReg(void *drv, struct DvpRegConfigureInfo *reg_info)
|
||||
{
|
||||
x_err_t ret = EOK;
|
||||
reg_info->reg_value = dvp_sccb_receive_data(reg_info->device_addr, reg_info->reg_addr);
|
||||
return ret;
|
||||
}
|
||||
|
||||
static uint32 writeDvpReg(void *drv, struct DvpRegConfigureInfo *reg_info)
|
||||
{
|
||||
x_err_t ret = EOK;
|
||||
dvp_sccb_send_data(reg_info->device_addr, reg_info->reg_addr, reg_info->reg_value);
|
||||
return ret;
|
||||
}
|
||||
|
||||
static uint32 dvpOpen(void *dev)
|
||||
{
|
||||
x_err_t ret = EOK;
|
||||
dvpDrvInit();
|
||||
return ret;
|
||||
}
|
||||
|
||||
static uint32 dvpClose(void *dev)
|
||||
{
|
||||
x_err_t ret = EOK;
|
||||
dvp_config_interrupt(DVP_CFG_START_INT_ENABLE | DVP_CFG_FINISH_INT_ENABLE, 0);
|
||||
dvp_set_output_enable(DVP_OUTPUT_AI, 0);
|
||||
dvp_set_output_enable(DVP_OUTPUT_DISPLAY, 0);
|
||||
return ret;
|
||||
}
|
||||
|
||||
static uint32 dvpRead(void *dev, struct BusBlockReadParam *read_param)
|
||||
{
|
||||
x_err_t ret = EOK;
|
||||
|
||||
// change the output buff address by read
|
||||
dvp_set_output_enable(DVP_OUTPUT_DISPLAY, 0);
|
||||
dvp_set_display_addr((uintptr_t)read_param->buffer);
|
||||
dvp_set_output_enable(DVP_OUTPUT_DISPLAY, 1);
|
||||
|
||||
return ret;
|
||||
}
|
||||
|
||||
static uint32 dvpDrvConfigure(void *drv, struct BusConfigureInfo *args)
|
||||
{
|
||||
|
||||
x_err_t ret = EOK;
|
||||
int cmd_type = args->configure_cmd;
|
||||
struct CameraCfg* tmp_cfg;
|
||||
switch (cmd_type)
|
||||
{
|
||||
case OPE_INT:
|
||||
break;
|
||||
case OPE_CFG:
|
||||
tmp_cfg = (struct CameraCfg *)args->private_data;
|
||||
sensorConfigure(tmp_cfg);
|
||||
dvp_set_image_size(tmp_cfg->output_w, tmp_cfg->output_h);
|
||||
break;
|
||||
case REG_SCCB_READ:
|
||||
readDvpReg(drv, (struct DvpRegConfigureInfo *)args->private_data);
|
||||
break;
|
||||
case REG_SCCB_WRITE:
|
||||
writeDvpReg(drv, (struct DvpRegConfigureInfo *)args->private_data);
|
||||
break;
|
||||
default:
|
||||
break;
|
||||
}
|
||||
return ret;
|
||||
}
|
||||
|
||||
/*manage the camera device operations*/
|
||||
static const struct CameraDevDone camera_dev_done =
|
||||
{
|
||||
.dev_open = dvpOpen,
|
||||
.dev_close = dvpClose,
|
||||
.dev_write = NONE,
|
||||
.dev_read = dvpRead,
|
||||
};
|
||||
|
||||
/*Init camera bus*/
|
||||
static int BoardCameraBusInit(struct CameraBus *camera_bus, struct CameraDriver *camera_driver)
|
||||
{
|
||||
x_err_t ret = EOK;
|
||||
|
||||
/*Init the camera bus */
|
||||
camera_bus->private_data = (void *)&camera_dev_done;
|
||||
ret = CameraBusInit(camera_bus, CAMERA_BUS_NAME);
|
||||
if (EOK != ret)
|
||||
{
|
||||
KPrintf("board_camera_init CameraBusInit error %d\n", ret);
|
||||
return ERROR;
|
||||
}
|
||||
|
||||
/*Init the camera driver*/
|
||||
camera_driver->private_data = (void *)&camera_dev_done;
|
||||
ret = CameraDriverInit(camera_driver, CAMERA_DRV_NAME);
|
||||
if (EOK != ret)
|
||||
{
|
||||
KPrintf("board_camera_init CameraDriverInit error %d\n", ret);
|
||||
return ERROR;
|
||||
}
|
||||
|
||||
/*Attach the camera driver to the camera bus*/
|
||||
ret = CameraDriverAttachToBus(CAMERA_DRV_NAME, CAMERA_BUS_NAME);
|
||||
if (EOK != ret)
|
||||
{
|
||||
KPrintf("board_camera_init CameraDriverAttachToBus error %d\n", ret);
|
||||
return ERROR;
|
||||
}
|
||||
|
||||
return ret;
|
||||
}
|
||||
|
||||
/*Attach the camera device to the camera bus*/
|
||||
static int BoardCameraDevBend(void)
|
||||
{
|
||||
x_err_t ret = EOK;
|
||||
static struct CameraHardwareDevice camera_device;
|
||||
memset(&camera_device, 0, sizeof(struct CameraHardwareDevice));
|
||||
|
||||
camera_device.camera_dev_done = &camera_dev_done;
|
||||
|
||||
ret = CameraDeviceRegister(&camera_device, NONE, CAMERA_DEVICE_NAME);
|
||||
if (EOK != ret)
|
||||
{
|
||||
KPrintf("board_camera_init CameraDeviceInit device %s error %d\n", CAMERA_DEVICE_NAME, ret);
|
||||
return ERROR;
|
||||
}
|
||||
|
||||
ret = CameraDeviceAttachToBus(CAMERA_DEVICE_NAME, CAMERA_BUS_NAME);
|
||||
if (EOK != ret)
|
||||
{
|
||||
KPrintf("board_camera_init CameraDeviceAttachToBus device %s error %d\n", CAMERA_DEVICE_NAME, ret);
|
||||
return ERROR;
|
||||
}
|
||||
|
||||
return ret;
|
||||
}
|
||||
|
||||
int HwDvpInit(void)
|
||||
{
|
||||
x_err_t ret = EOK;
|
||||
static struct CameraBus camera_bus;
|
||||
memset(&camera_bus, 0, sizeof(struct CameraBus));
|
||||
|
||||
static struct CameraDriver camera_driver;
|
||||
memset(&camera_driver, 0, sizeof(struct CameraDriver));
|
||||
|
||||
camera_driver.configure = dvpDrvConfigure;
|
||||
ret = BoardCameraBusInit(&camera_bus, &camera_driver);
|
||||
if (EOK != ret)
|
||||
{
|
||||
KPrintf("board_camera_Init error ret %u\n", ret);
|
||||
return ERROR;
|
||||
}
|
||||
|
||||
ret = BoardCameraDevBend();
|
||||
if (EOK != ret)
|
||||
{
|
||||
KPrintf("board_camera_Init error ret %u\n", ret);
|
||||
return ERROR;
|
||||
}
|
||||
return ret;
|
||||
}
|
|
@ -0,0 +1,288 @@
|
|||
/* Copyright 2018 Canaan Inc.
|
||||
*
|
||||
* 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 <stddef.h>
|
||||
#include <stdint.h>
|
||||
#include "dvp.h"
|
||||
#include "utils.h"
|
||||
#include "fpioa.h"
|
||||
#include "sysctl.h"
|
||||
#include <math.h>
|
||||
#include <sleep.h>
|
||||
|
||||
volatile dvp_t* const dvp = (volatile dvp_t*)DVP_BASE_ADDR;
|
||||
static uint8_t g_sccb_reg_len = 8;
|
||||
|
||||
|
||||
static void dvp_sccb_clk_init(void)
|
||||
{
|
||||
uint32_t tmp;
|
||||
|
||||
tmp = dvp->sccb_cfg & (~(DVP_SCCB_SCL_LCNT_MASK | DVP_SCCB_SCL_HCNT_MASK));
|
||||
tmp |= DVP_SCCB_SCL_LCNT(255) | DVP_SCCB_SCL_HCNT(255);
|
||||
|
||||
dvp->sccb_cfg = tmp;
|
||||
}
|
||||
|
||||
uint32_t dvp_sccb_set_clk_rate(uint32_t clk_rate)
|
||||
{
|
||||
uint32_t tmp;
|
||||
uint32_t v_sccb_freq = SysctlClockGetFreq(SYSCTL_CLOCK_APB1);
|
||||
uint16_t v_period_clk_cnt = round(v_sccb_freq / clk_rate / 2.0);
|
||||
if(v_period_clk_cnt > 255)
|
||||
{
|
||||
return 0;
|
||||
}
|
||||
tmp = dvp->sccb_cfg & (~(DVP_SCCB_SCL_LCNT_MASK | DVP_SCCB_SCL_HCNT_MASK));
|
||||
tmp |= DVP_SCCB_SCL_LCNT(v_period_clk_cnt) | DVP_SCCB_SCL_HCNT(v_period_clk_cnt);
|
||||
dvp->sccb_cfg = tmp;
|
||||
return SysctlClockGetFreq(SYSCTL_CLOCK_DVP) / (v_period_clk_cnt * 2);
|
||||
}
|
||||
|
||||
static void dvp_sccb_start_transfer(void)
|
||||
{
|
||||
while (dvp->sts & DVP_STS_SCCB_EN)
|
||||
;
|
||||
dvp->sts = DVP_STS_SCCB_EN | DVP_STS_SCCB_EN_WE;
|
||||
while (dvp->sts & DVP_STS_SCCB_EN)
|
||||
;
|
||||
}
|
||||
|
||||
void dvp_sccb_send_data(uint8_t dev_addr, uint16_t reg_addr, uint8_t reg_data)
|
||||
{
|
||||
uint32_t tmp;
|
||||
|
||||
tmp = dvp->sccb_cfg & (~DVP_SCCB_BYTE_NUM_MASK);
|
||||
|
||||
(g_sccb_reg_len == 8) ? (tmp |= DVP_SCCB_BYTE_NUM_3) : (tmp |= DVP_SCCB_BYTE_NUM_4);
|
||||
|
||||
dvp->sccb_cfg = tmp;
|
||||
|
||||
if (g_sccb_reg_len == 8)
|
||||
{
|
||||
dvp->sccb_ctl = DVP_SCCB_WRITE_DATA_ENABLE | DVP_SCCB_DEVICE_ADDRESS(dev_addr) | DVP_SCCB_REG_ADDRESS(reg_addr) | DVP_SCCB_WDATA_BYTE0(reg_data);
|
||||
}
|
||||
else
|
||||
{
|
||||
dvp->sccb_ctl = DVP_SCCB_WRITE_DATA_ENABLE | DVP_SCCB_DEVICE_ADDRESS(dev_addr) | DVP_SCCB_REG_ADDRESS(reg_addr >> 8) | DVP_SCCB_WDATA_BYTE0(reg_addr & 0xff) | DVP_SCCB_WDATA_BYTE1(reg_data);
|
||||
}
|
||||
dvp_sccb_start_transfer();
|
||||
}
|
||||
|
||||
uint8_t dvp_sccb_receive_data(uint8_t dev_addr, uint16_t reg_addr)
|
||||
{
|
||||
uint32_t tmp;
|
||||
|
||||
tmp = dvp->sccb_cfg & (~DVP_SCCB_BYTE_NUM_MASK);
|
||||
|
||||
if (g_sccb_reg_len == 8)
|
||||
tmp |= DVP_SCCB_BYTE_NUM_2;
|
||||
else
|
||||
tmp |= DVP_SCCB_BYTE_NUM_3;
|
||||
|
||||
dvp->sccb_cfg = tmp;
|
||||
|
||||
if (g_sccb_reg_len == 8)
|
||||
{
|
||||
dvp->sccb_ctl = DVP_SCCB_WRITE_DATA_ENABLE | DVP_SCCB_DEVICE_ADDRESS(dev_addr) | DVP_SCCB_REG_ADDRESS(reg_addr);
|
||||
}
|
||||
else
|
||||
{
|
||||
dvp->sccb_ctl = DVP_SCCB_WRITE_DATA_ENABLE | DVP_SCCB_DEVICE_ADDRESS(dev_addr) | DVP_SCCB_REG_ADDRESS(reg_addr >> 8) | DVP_SCCB_WDATA_BYTE0(reg_addr & 0xff);
|
||||
}
|
||||
dvp_sccb_start_transfer();
|
||||
|
||||
dvp->sccb_ctl = DVP_SCCB_DEVICE_ADDRESS(dev_addr);
|
||||
|
||||
dvp_sccb_start_transfer();
|
||||
|
||||
return (uint8_t) DVP_SCCB_RDATA_BYTE(dvp->sccb_cfg);
|
||||
}
|
||||
|
||||
static void dvp_reset(void)
|
||||
{
|
||||
/* First power down */
|
||||
dvp->cmos_cfg |= DVP_CMOS_POWER_DOWN;
|
||||
msleep(200);
|
||||
dvp->cmos_cfg &= ~DVP_CMOS_POWER_DOWN;
|
||||
msleep(200);
|
||||
|
||||
/* Second reset */
|
||||
dvp->cmos_cfg &= ~DVP_CMOS_RESET;
|
||||
msleep(200);
|
||||
dvp->cmos_cfg |= DVP_CMOS_RESET;
|
||||
msleep(200);
|
||||
}
|
||||
|
||||
void dvp_init(uint8_t reg_len)
|
||||
{
|
||||
g_sccb_reg_len = reg_len;
|
||||
sysctl_clock_enable(SYSCTL_CLOCK_DVP);
|
||||
sysctl_reset(SYSCTL_RESET_DVP);
|
||||
dvp->cmos_cfg &= (~DVP_CMOS_CLK_DIV_MASK);
|
||||
dvp->cmos_cfg |= DVP_CMOS_CLK_DIV(3) | DVP_CMOS_CLK_ENABLE;
|
||||
dvp_sccb_clk_init();
|
||||
dvp_reset();
|
||||
}
|
||||
|
||||
uint32_t dvp_set_xclk_rate(uint32_t xclk_rate)
|
||||
{
|
||||
uint32_t v_apb1_clk = SysctlClockGetFreq(SYSCTL_CLOCK_APB1);
|
||||
uint32_t v_period;
|
||||
if(v_apb1_clk > xclk_rate * 2)
|
||||
v_period = round(v_apb1_clk / (xclk_rate * 2.0)) - 1;
|
||||
else
|
||||
v_period = 0;
|
||||
if(v_period > 255)
|
||||
v_period = 255;
|
||||
dvp->cmos_cfg &= (~DVP_CMOS_CLK_DIV_MASK);
|
||||
dvp->cmos_cfg |= DVP_CMOS_CLK_DIV(v_period) | DVP_CMOS_CLK_ENABLE;
|
||||
dvp_reset();
|
||||
return v_apb1_clk / ((v_period + 1) * 2);
|
||||
}
|
||||
|
||||
void dvp_set_image_format(uint32_t format)
|
||||
{
|
||||
uint32_t tmp;
|
||||
|
||||
tmp = dvp->dvp_cfg & (~DVP_CFG_FORMAT_MASK);
|
||||
dvp->dvp_cfg = tmp | format;
|
||||
}
|
||||
|
||||
void dvp_enable_burst(void)
|
||||
{
|
||||
dvp->dvp_cfg |= DVP_CFG_BURST_SIZE_4BEATS;
|
||||
|
||||
dvp->axi &= (~DVP_AXI_GM_MLEN_MASK);
|
||||
dvp->axi |= DVP_AXI_GM_MLEN_4BYTE;
|
||||
}
|
||||
|
||||
void dvp_disable_burst(void)
|
||||
{
|
||||
dvp->dvp_cfg &= (~DVP_CFG_BURST_SIZE_4BEATS);
|
||||
|
||||
dvp->axi &= (~DVP_AXI_GM_MLEN_MASK);
|
||||
dvp->axi |= DVP_AXI_GM_MLEN_1BYTE;
|
||||
}
|
||||
|
||||
void dvp_set_image_size(uint32_t width, uint32_t height)
|
||||
{
|
||||
uint32_t tmp;
|
||||
|
||||
tmp = dvp->dvp_cfg & (~(DVP_CFG_HREF_BURST_NUM_MASK | DVP_CFG_LINE_NUM_MASK));
|
||||
|
||||
tmp |= DVP_CFG_LINE_NUM(height);
|
||||
|
||||
if (dvp->dvp_cfg & DVP_CFG_BURST_SIZE_4BEATS)
|
||||
tmp |= DVP_CFG_HREF_BURST_NUM(width / 8 / 4);
|
||||
else
|
||||
tmp |= DVP_CFG_HREF_BURST_NUM(width / 8 / 1);
|
||||
|
||||
dvp->dvp_cfg = tmp;
|
||||
}
|
||||
|
||||
void dvp_set_ai_addr(uint32_t r_addr, uint32_t g_addr, uint32_t b_addr)
|
||||
{
|
||||
dvp->r_addr = r_addr;
|
||||
dvp->g_addr = g_addr;
|
||||
dvp->b_addr = b_addr;
|
||||
}
|
||||
|
||||
void dvp_set_display_addr(uint32_t addr)
|
||||
{
|
||||
dvp->rgb_addr = addr;
|
||||
}
|
||||
|
||||
void dvp_start_frame(void)
|
||||
{
|
||||
while (!(dvp->sts & DVP_STS_FRAME_START))
|
||||
;
|
||||
dvp->sts = (DVP_STS_FRAME_START | DVP_STS_FRAME_START_WE);
|
||||
}
|
||||
|
||||
void dvp_start_convert(void)
|
||||
{
|
||||
dvp->sts = DVP_STS_DVP_EN | DVP_STS_DVP_EN_WE;
|
||||
}
|
||||
|
||||
void dvp_finish_convert(void)
|
||||
{
|
||||
while (!(dvp->sts & DVP_STS_FRAME_FINISH))
|
||||
;
|
||||
dvp->sts = DVP_STS_FRAME_FINISH | DVP_STS_FRAME_FINISH_WE;
|
||||
}
|
||||
|
||||
void dvp_get_image(void)
|
||||
{
|
||||
while (!(dvp->sts & DVP_STS_FRAME_START))
|
||||
;
|
||||
dvp->sts = DVP_STS_FRAME_START | DVP_STS_FRAME_START_WE;
|
||||
while (!(dvp->sts & DVP_STS_FRAME_START))
|
||||
;
|
||||
dvp->sts = DVP_STS_FRAME_FINISH | DVP_STS_FRAME_FINISH_WE | DVP_STS_FRAME_START | DVP_STS_FRAME_START_WE | DVP_STS_DVP_EN | DVP_STS_DVP_EN_WE;
|
||||
while (!(dvp->sts & DVP_STS_FRAME_FINISH))
|
||||
;
|
||||
}
|
||||
|
||||
void dvp_config_interrupt(uint32_t interrupt, uint8_t enable)
|
||||
{
|
||||
if (enable)
|
||||
dvp->dvp_cfg |= interrupt;
|
||||
else
|
||||
dvp->dvp_cfg &= (~interrupt);
|
||||
}
|
||||
|
||||
int dvp_get_interrupt(uint32_t interrupt)
|
||||
{
|
||||
if (dvp->sts & interrupt)
|
||||
return 1;
|
||||
return 0;
|
||||
}
|
||||
|
||||
void dvp_clear_interrupt(uint32_t interrupt)
|
||||
{
|
||||
interrupt |= (interrupt << 1);
|
||||
dvp->sts |= interrupt;
|
||||
}
|
||||
|
||||
void dvp_enable_auto(void)
|
||||
{
|
||||
dvp->dvp_cfg |= DVP_CFG_AUTO_ENABLE;
|
||||
}
|
||||
|
||||
void dvp_disable_auto(void)
|
||||
{
|
||||
dvp->dvp_cfg &= (~DVP_CFG_AUTO_ENABLE);
|
||||
}
|
||||
|
||||
void dvp_set_output_enable(dvp_output_mode_t index, int enable)
|
||||
{
|
||||
configASSERT(index < 2);
|
||||
|
||||
if (index == 0)
|
||||
{
|
||||
if (enable)
|
||||
dvp->dvp_cfg |= DVP_CFG_AI_OUTPUT_ENABLE;
|
||||
else
|
||||
dvp->dvp_cfg &= ~DVP_CFG_AI_OUTPUT_ENABLE;
|
||||
}
|
||||
else
|
||||
{
|
||||
if (enable)
|
||||
dvp->dvp_cfg |= DVP_CFG_DISPLAY_OUTPUT_ENABLE;
|
||||
else
|
||||
dvp->dvp_cfg &= ~DVP_CFG_DISPLAY_OUTPUT_ENABLE;
|
||||
}
|
||||
}
|
||||
|
|
@ -0,0 +1,457 @@
|
|||
/* Copyright 2018 Canaan Inc.
|
||||
*
|
||||
* 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 <stdio.h>
|
||||
#include "ov2640.h"
|
||||
#include "dvp.h"
|
||||
#include "plic.h"
|
||||
#include "board.h"
|
||||
|
||||
#if defined SVGA_25FPS_MODE
|
||||
const uint8_t ov2640_config[][2]=
|
||||
{
|
||||
{0xff, 0x01},
|
||||
{0x12, 0x80},
|
||||
{0xff, 0x00},
|
||||
{0x2c, 0xff},
|
||||
{0x2e, 0xdf},
|
||||
{0xff, 0x01},
|
||||
{0x3c, 0x32},
|
||||
{0x11, 0x00},
|
||||
{0x09, 0x02},
|
||||
{0x04, 0x58},
|
||||
{0x13, 0xe5},
|
||||
{0x14, 0x48},
|
||||
{0x2c, 0x0c},
|
||||
{0x33, 0x78},
|
||||
{0x3a, 0x33},
|
||||
{0x3b, 0xfb},
|
||||
{0x3e, 0x00},
|
||||
{0x43, 0x11},
|
||||
{0x16, 0x10},
|
||||
{0x39, 0x92},
|
||||
{0x35, 0xda},
|
||||
{0x22, 0x1a},
|
||||
{0x37, 0xc3},
|
||||
{0x23, 0x00},
|
||||
{0x34, 0xc0},
|
||||
{0x36, 0x1a},
|
||||
{0x06, 0x88},
|
||||
{0x07, 0xc0},
|
||||
{0x0d, 0x87},
|
||||
{0x0e, 0x41},
|
||||
{0x4c, 0x00},
|
||||
{0x48, 0x00},
|
||||
{0x5b, 0x00},
|
||||
{0x42, 0x03},
|
||||
{0x4a, 0x81},
|
||||
{0x21, 0x99},
|
||||
{0x24, 0x40},
|
||||
{0x25, 0x38},
|
||||
{0x26, 0x82},
|
||||
{0x5c, 0x00},
|
||||
{0x63, 0x00},
|
||||
{0x46, 0x22},
|
||||
{0x0c, 0x3c},
|
||||
{0x61, 0x70},
|
||||
{0x62, 0x80},
|
||||
{0x7c, 0x05},
|
||||
{0x20, 0x80},
|
||||
{0x28, 0x30},
|
||||
{0x6c, 0x00},
|
||||
{0x6d, 0x80},
|
||||
{0x6e, 0x00},
|
||||
{0x70, 0x02},
|
||||
{0x71, 0x94},
|
||||
{0x73, 0xc1},
|
||||
{0x3d, 0x34},
|
||||
{0x5a, 0x57},
|
||||
{0x12, 0x40},
|
||||
{0x17, 0x11},
|
||||
{0x18, 0x43},
|
||||
{0x19, 0x00},
|
||||
{0x1a, 0x97},
|
||||
{0x32, 0x09},
|
||||
{0x37, 0xc0},
|
||||
{0x4f, 0xca},
|
||||
{0x50, 0xa8},
|
||||
{0x5a, 0x23},
|
||||
{0x6d, 0x00},
|
||||
{0x3d, 0x38},
|
||||
{0xff, 0x00},
|
||||
{0xe5, 0x7f},
|
||||
{0xf9, 0xc0},
|
||||
{0x41, 0x24},
|
||||
{0xe0, 0x14},
|
||||
{0x76, 0xff},
|
||||
{0x33, 0xa0},
|
||||
{0x42, 0x20},
|
||||
{0x43, 0x18},
|
||||
{0x4c, 0x00},
|
||||
{0x87, 0xd5},
|
||||
{0x88, 0x3f},
|
||||
{0xd7, 0x03},
|
||||
{0xd9, 0x10},
|
||||
{0xd3, 0x82},
|
||||
{0xc8, 0x08},
|
||||
{0xc9, 0x80},
|
||||
{0x7c, 0x00},
|
||||
{0x7d, 0x00},
|
||||
{0x7c, 0x03},
|
||||
{0x7d, 0x48},
|
||||
{0x7d, 0x48},
|
||||
{0x7c, 0x08},
|
||||
{0x7d, 0x20},
|
||||
{0x7d, 0x10},
|
||||
{0x7d, 0x0e},
|
||||
{0x90, 0x00},
|
||||
{0x91, 0x0e},
|
||||
{0x91, 0x1a},
|
||||
{0x91, 0x31},
|
||||
{0x91, 0x5a},
|
||||
{0x91, 0x69},
|
||||
{0x91, 0x75},
|
||||
{0x91, 0x7e},
|
||||
{0x91, 0x88},
|
||||
{0x91, 0x8f},
|
||||
{0x91, 0x96},
|
||||
{0x91, 0xa3},
|
||||
{0x91, 0xaf},
|
||||
{0x91, 0xc4},
|
||||
{0x91, 0xd7},
|
||||
{0x91, 0xe8},
|
||||
{0x91, 0x20},
|
||||
{0x92, 0x00},
|
||||
{0x93, 0x06},
|
||||
{0x93, 0xe3},
|
||||
{0x93, 0x05},
|
||||
{0x93, 0x05},
|
||||
{0x93, 0x00},
|
||||
{0x93, 0x04},
|
||||
{0x93, 0x00},
|
||||
{0x93, 0x00},
|
||||
{0x93, 0x00},
|
||||
{0x93, 0x00},
|
||||
{0x93, 0x00},
|
||||
{0x93, 0x00},
|
||||
{0x93, 0x00},
|
||||
{0x96, 0x00},
|
||||
{0x97, 0x08},
|
||||
{0x97, 0x19},
|
||||
{0x97, 0x02},
|
||||
{0x97, 0x0c},
|
||||
{0x97, 0x24},
|
||||
{0x97, 0x30},
|
||||
{0x97, 0x28},
|
||||
{0x97, 0x26},
|
||||
{0x97, 0x02},
|
||||
{0x97, 0x98},
|
||||
{0x97, 0x80},
|
||||
{0x97, 0x00},
|
||||
{0x97, 0x00},
|
||||
{0xc3, 0xed},
|
||||
{0xa4, 0x00},
|
||||
{0xa8, 0x00},
|
||||
{0xc5, 0x11},
|
||||
{0xc6, 0x51},
|
||||
{0xbf, 0x80},
|
||||
{0xc7, 0x10},
|
||||
{0xb6, 0x66},
|
||||
{0xb8, 0xa5},
|
||||
{0xb7, 0x64},
|
||||
{0xb9, 0x7c},
|
||||
{0xb3, 0xaf},
|
||||
{0xb4, 0x97},
|
||||
{0xb5, 0xff},
|
||||
{0xb0, 0xc5},
|
||||
{0xb1, 0x94},
|
||||
{0xb2, 0x0f},
|
||||
{0xc4, 0x5c},
|
||||
{0xc0, 0x64},
|
||||
{0xc1, 0x4b},
|
||||
{0x8c, 0x00},
|
||||
{0x86, 0x3d},
|
||||
{0x50, 0x00},
|
||||
{0x51, 0xc8},
|
||||
{0x52, 0x96},
|
||||
{0x53, 0x00},
|
||||
{0x54, 0x00},
|
||||
{0x55, 0x00},
|
||||
{0x5a, 0xc8},
|
||||
{0x5b, 0x96},
|
||||
{0x5c, 0x00},
|
||||
{0xd3, 0x02},
|
||||
{0xc3, 0xed},
|
||||
{0x7f, 0x00},
|
||||
{0xda, 0x08},
|
||||
{0xe5, 0x1f},
|
||||
{0xe1, 0x67},
|
||||
{0xe0, 0x00},
|
||||
{0xdd, 0x7f},
|
||||
{0x05, 0x00},
|
||||
{0xff, 0x00},
|
||||
{0xe0, 0x04},
|
||||
{0x5a, 0x50},
|
||||
{0x5b, 0x3c},
|
||||
{0x5c, 0x00},
|
||||
{0xe0, 0x00},
|
||||
{0x00, 0x00}
|
||||
};
|
||||
#elif defined UXGA_15FPS_MODE
|
||||
const uint8_t ov2640_config[][2]=
|
||||
{
|
||||
{0xFF, 0x00},
|
||||
{0x2C, 0xFF},
|
||||
{0x2E, 0xDF},
|
||||
{0xFF, 0x01},
|
||||
{0x3C, 0x32},
|
||||
{0x11, 0x00},
|
||||
{0x09, 0x02},
|
||||
{0x04, 0xA8},
|
||||
{0x13, 0xE5},
|
||||
{0x14, 0x48},
|
||||
{0x2C, 0x0C},
|
||||
{0x33, 0x78},
|
||||
{0x3A, 0x33},
|
||||
{0x3B, 0xFB},
|
||||
{0x3E, 0x00},
|
||||
{0x43, 0x11},
|
||||
{0x16, 0x10},
|
||||
{0x39, 0x92},
|
||||
{0x35, 0xDA},
|
||||
{0x22, 0x1A},
|
||||
{0x37, 0xC3},
|
||||
{0x23, 0x00},
|
||||
{0x34, 0xC0},
|
||||
{0x36, 0x1A},
|
||||
{0x06, 0x88},
|
||||
{0x07, 0xC0},
|
||||
{0x0D, 0x87},
|
||||
{0x0E, 0x41},
|
||||
{0x4C, 0x00},
|
||||
{0x48, 0x00},
|
||||
{0x5B, 0x00},
|
||||
{0x42, 0x03},
|
||||
{0x4A, 0x81},
|
||||
{0x21, 0x99},
|
||||
{0x24, 0x40},
|
||||
{0x25, 0x38},
|
||||
{0x26, 0x82},
|
||||
{0x5C, 0x00},
|
||||
{0x63, 0x00},
|
||||
{0x46, 0x00},
|
||||
{0x0C, 0x3C},
|
||||
{0x61, 0x70},
|
||||
{0x62, 0x80},
|
||||
{0x7C, 0x05},
|
||||
{0x20, 0x80},
|
||||
{0x28, 0x30},
|
||||
{0x6C, 0x00},
|
||||
{0x6D, 0x80},
|
||||
{0x6E, 0x00},
|
||||
{0x70, 0x02},
|
||||
{0x71, 0x94},
|
||||
{0x73, 0xC1},
|
||||
{0x3D, 0x34},
|
||||
{0x5A, 0x57},
|
||||
{0x12, 0x00},
|
||||
{0x17, 0x11},
|
||||
{0x18, 0x75},
|
||||
{0x19, 0x01},
|
||||
{0x1A, 0x97},
|
||||
{0x32, 0x36},
|
||||
{0x03, 0x0F},
|
||||
{0x37, 0x40},
|
||||
{0x4F, 0xCA},
|
||||
{0x50, 0xA8},
|
||||
{0x5A, 0x23},
|
||||
{0x6D, 0x00},
|
||||
{0x6D, 0x38},
|
||||
{0xFF, 0x00},
|
||||
{0xE5, 0x7F},
|
||||
{0xF9, 0xC0},
|
||||
{0x41, 0x24},
|
||||
{0xE0, 0x14},
|
||||
{0x76, 0xFF},
|
||||
{0x33, 0xA0},
|
||||
{0x42, 0x20},
|
||||
{0x43, 0x18},
|
||||
{0x4C, 0x00},
|
||||
{0x87, 0xD5},
|
||||
{0x88, 0x3F},
|
||||
{0xD7, 0x03},
|
||||
{0xD9, 0x10},
|
||||
{0xD3, 0x82},
|
||||
{0xC8, 0x08},
|
||||
{0xC9, 0x80},
|
||||
{0x7C, 0x00},
|
||||
{0x7D, 0x00},
|
||||
{0x7C, 0x03},
|
||||
{0x7D, 0x48},
|
||||
{0x7D, 0x48},
|
||||
{0x7C, 0x08},
|
||||
{0x7D, 0x20},
|
||||
{0x7D, 0x10},
|
||||
{0x7D, 0x0E},
|
||||
{0x90, 0x00},
|
||||
{0x91, 0x0E},
|
||||
{0x91, 0x1A},
|
||||
{0x91, 0x31},
|
||||
{0x91, 0x5A},
|
||||
{0x91, 0x69},
|
||||
{0x91, 0x75},
|
||||
{0x91, 0x7E},
|
||||
{0x91, 0x88},
|
||||
{0x91, 0x8F},
|
||||
{0x91, 0x96},
|
||||
{0x91, 0xA3},
|
||||
{0x91, 0xAF},
|
||||
{0x91, 0xC4},
|
||||
{0x91, 0xD7},
|
||||
{0x91, 0xE8},
|
||||
{0x91, 0x20},
|
||||
{0x92, 0x00},
|
||||
{0x93, 0x06},
|
||||
{0x93, 0xE3},
|
||||
{0x93, 0x05},
|
||||
{0x93, 0x05},
|
||||
{0x93, 0x00},
|
||||
{0x93, 0x04},
|
||||
{0x93, 0x00},
|
||||
{0x93, 0x00},
|
||||
{0x93, 0x00},
|
||||
{0x93, 0x00},
|
||||
{0x93, 0x00},
|
||||
{0x93, 0x00},
|
||||
{0x93, 0x00},
|
||||
{0x96, 0x00},
|
||||
{0x97, 0x08},
|
||||
{0x97, 0x19},
|
||||
{0x97, 0x02},
|
||||
{0x97, 0x0C},
|
||||
{0x97, 0x24},
|
||||
{0x97, 0x30},
|
||||
{0x97, 0x28},
|
||||
{0x97, 0x26},
|
||||
{0x97, 0x02},
|
||||
{0x97, 0x98},
|
||||
{0x97, 0x80},
|
||||
{0x97, 0x00},
|
||||
{0x97, 0x00},
|
||||
{0xC3, 0xEF},
|
||||
{0xA4, 0x00},
|
||||
{0xA8, 0x00},
|
||||
{0xC5, 0x11},
|
||||
{0xC6, 0x51},
|
||||
{0xBF, 0x80},
|
||||
{0xC7, 0x10},
|
||||
{0xB6, 0x66},
|
||||
{0xB8, 0xA5},
|
||||
{0xB7, 0x64},
|
||||
{0xB9, 0x7C},
|
||||
{0xB3, 0xAF},
|
||||
{0xB4, 0x97},
|
||||
{0xB5, 0xFF},
|
||||
{0xB0, 0xC5},
|
||||
{0xB1, 0x94},
|
||||
{0xB2, 0x0F},
|
||||
{0xC4, 0x5C},
|
||||
{0xC0, 0xC8},
|
||||
{0xC1, 0x96},
|
||||
{0x8C, 0x00},
|
||||
{0x86, 0x3D},
|
||||
{0x50, 0x00},
|
||||
{0x51, 0x90},
|
||||
{0x52, 0x2C},
|
||||
{0x53, 0x00},
|
||||
{0x54, 0x00},
|
||||
{0x55, 0x88},
|
||||
{0x5A, 0x90},
|
||||
{0x5B, 0x2C},
|
||||
{0x5C, 0x05},
|
||||
{0xD3, 0x02},
|
||||
{0xC3, 0xED},
|
||||
{0x7F, 0x00},
|
||||
{0xDA, 0x08},
|
||||
{0xE5, 0x1F},
|
||||
{0xE1, 0x67},
|
||||
{0xE0, 0x00},
|
||||
{0xDD, 0x7F},
|
||||
{0x00, 0x00}
|
||||
};
|
||||
#else
|
||||
const uint8_t ov2640_config[][2]=
|
||||
{
|
||||
{0x00,x00}
|
||||
}
|
||||
#endif
|
||||
|
||||
|
||||
|
||||
int ov2640_init(void)
|
||||
{
|
||||
uint16_t v_manuf_id;
|
||||
uint16_t v_device_id;
|
||||
ov2640_read_id(&v_manuf_id, &v_device_id);
|
||||
printf("manuf_id:0x%04x,device_id:0x%04x\n", v_manuf_id, v_device_id);
|
||||
uint16_t index = 0;
|
||||
for (index = 0; ov2640_config[index][0]; index++)
|
||||
dvp_sccb_send_data(OV2640_ADDR, ov2640_config[index][0], ov2640_config[index][1]);
|
||||
return 0;
|
||||
}
|
||||
|
||||
int ov2640_read_id(uint16_t *manuf_id, uint16_t *device_id)
|
||||
{
|
||||
dvp_sccb_send_data(OV2640_ADDR, 0xFF, 0x01);
|
||||
*manuf_id = (dvp_sccb_receive_data(OV2640_ADDR, 0x1C) << 8) | dvp_sccb_receive_data(OV2640_ADDR, 0x1D);
|
||||
*device_id = (dvp_sccb_receive_data(OV2640_ADDR, 0x0A) << 8) | dvp_sccb_receive_data(OV2640_ADDR, 0x0B);
|
||||
return 0;
|
||||
}
|
||||
|
||||
int sensorConfigure(struct CameraCfg *cfg_info)
|
||||
{
|
||||
uint8_t reg_tmp;
|
||||
|
||||
//set reg mode to sensor
|
||||
dvp_sccb_send_data(OV2640_ADDR, 0xFF, 0x00);
|
||||
|
||||
//configure the window size and position
|
||||
dvp_sccb_send_data(OV2640_ADDR, 0x51, cfg_info->window_w>>2);
|
||||
dvp_sccb_send_data(OV2640_ADDR, 0x52, cfg_info->window_h>>2);
|
||||
dvp_sccb_send_data(OV2640_ADDR, 0x53, (uint8_t)(cfg_info->window_xoffset&0xFF));
|
||||
dvp_sccb_send_data(OV2640_ADDR, 0x54, (uint8_t)(cfg_info->window_yoffset&0xFF));
|
||||
dvp_sccb_send_data(OV2640_ADDR, 0x55, (((cfg_info->window_h/4)&0x100)>>1)+
|
||||
((cfg_info->window_yoffset&0x700)>>4)+
|
||||
(((cfg_info->window_w/4)&0x100)>>5)+
|
||||
((cfg_info->window_xoffset&0x700)>>8));
|
||||
dvp_sccb_send_data(OV2640_ADDR, 0x57, ((cfg_info->window_w/4)&0x200)>>2);
|
||||
dvp_sccb_send_data(OV2640_ADDR, 0x5A, cfg_info->output_w>>2);
|
||||
dvp_sccb_send_data(OV2640_ADDR, 0x5B, cfg_info->output_h>>2);
|
||||
|
||||
//set reg mode to dsp
|
||||
dvp_sccb_send_data(OV2640_ADDR, 0xFF, 0x01);
|
||||
|
||||
//configure dsp gain
|
||||
if(cfg_info->gain_manu_enable){
|
||||
reg_tmp = dvp_sccb_receive_data(OV2640_ADDR, 0x13);
|
||||
dvp_sccb_send_data(OV2640_ADDR, 0x13, reg_tmp&0xFB);
|
||||
dvp_sccb_send_data(OV2640_ADDR, 0x00, cfg_info->gain);
|
||||
}else{
|
||||
reg_tmp = dvp_sccb_receive_data(OV2640_ADDR, 0x13);
|
||||
dvp_sccb_send_data(OV2640_ADDR, 0x13, reg_tmp|0x04);
|
||||
}
|
||||
|
||||
|
||||
return 1;
|
||||
}
|
|
@ -72,30 +72,16 @@ static struct io_config
|
|||
IOCONFIG(BSP_UART2_RXD_PIN, FUNC_UART2_RX),
|
||||
#endif
|
||||
#ifdef BSP_USING_UART3
|
||||
IOCONFIG(BSP_UART3_TXD_PIN, FUNC_UART3_RX),
|
||||
IOCONFIG(BSP_UART3_RXD_PIN, FUNC_UART3_TX),
|
||||
IOCONFIG(BSP_UART3_TXD_PIN, FUNC_UART3_TX),
|
||||
IOCONFIG(BSP_UART3_RXD_PIN, FUNC_UART3_RX),
|
||||
#endif
|
||||
#ifdef BSP_USING_I2C
|
||||
IOCONFIG(BSP_I2C_SDA, FUNC_GPIO3),
|
||||
IOCONFIG(BSP_I2C_SCL, FUNC_GPIO4),
|
||||
#endif
|
||||
#ifdef BSP_USING_TOUCH
|
||||
IOCONFIG(BSP_TOUCH_TP_INT, HS_GPIO(FPIOA_TOUCH_TP_INT)),
|
||||
#endif
|
||||
|
||||
#ifdef BSP_USING_CH438
|
||||
IOCONFIG(BSP_CH438_ALE_PIN, HS_GPIO(FPIOA_CH438_ALE)),
|
||||
IOCONFIG(BSP_CH438_NWR_PIN, HS_GPIO(FPIOA_CH438_NWR)),
|
||||
IOCONFIG(BSP_CH438_NRD_PIN, HS_GPIO(FPIOA_CH438_NRD)),
|
||||
IOCONFIG(BSP_CH438_INT_PIN, HS_GPIO(FPIOA_CH438_INT)),
|
||||
IOCONFIG(BSP_CH438_D0_PIN, HS_GPIO(FPIOA_CH438_D0)),
|
||||
IOCONFIG(BSP_CH438_D1_PIN, HS_GPIO(FPIOA_CH438_D1)),
|
||||
IOCONFIG(BSP_CH438_D2_PIN, HS_GPIO(FPIOA_CH438_D2)),
|
||||
IOCONFIG(BSP_CH438_D3_PIN, HS_GPIO(FPIOA_CH438_D3)),
|
||||
IOCONFIG(BSP_CH438_D4_PIN, HS_GPIO(FPIOA_CH438_D4)),
|
||||
IOCONFIG(BSP_CH438_D5_PIN, HS_GPIO(FPIOA_CH438_D5)),
|
||||
IOCONFIG(BSP_CH438_D6_PIN, HS_GPIO(FPIOA_CH438_D6)),
|
||||
IOCONFIG(BSP_CH438_D7_PIN, HS_GPIO(FPIOA_CH438_D7)),
|
||||
// IOCONFIG(BSP_TOUCH_TP_INT, HS_GPIO(FPIOA_TOUCH_TP_INT)),
|
||||
IOCONFIG(BSP_TOUCH_TP_INT, HS_GPIO(FUNC_GPIOHS30)),
|
||||
#endif
|
||||
|
||||
#ifdef BSP_USING_SOFT_SPI
|
||||
|
@ -105,6 +91,17 @@ static struct io_config
|
|||
IOCONFIG(BSP_SOFT_SPI_NCS_PIN, HS_GPIO(FPIOA_SOFT_SPI_NCS)),
|
||||
#endif
|
||||
|
||||
#ifdef BSP_USING_CAMERA
|
||||
IOCONFIG(BSP_DVP_RST_PIN,FUNC_CMOS_RST),
|
||||
IOCONFIG(BSP_DVP_PWDN_PIN, FUNC_CMOS_PWDN),
|
||||
IOCONFIG(BSP_DVP_XCLK_PIN,FUNC_CMOS_XCLK),
|
||||
IOCONFIG(BSP_DVP_PCLK_PIN,FUNC_CMOS_PCLK),
|
||||
IOCONFIG(BSP_DVP_HSYNC_PIN,FUNC_CMOS_HREF),
|
||||
IOCONFIG(BSP_DVP_VSYNC_PIN,FUNC_CMOS_VSYNC),
|
||||
IOCONFIG(BSP_DVP_SCL_PIN,FUNC_SCCB_SCLK),
|
||||
IOCONFIG(BSP_DVP_SDA_PIN,FUNC_SCCB_SDA),
|
||||
#endif
|
||||
|
||||
#ifdef BSP_USING_LORA
|
||||
IOCONFIG(BSP_E220_M0_PIN, HS_GPIO(FUNC_GPIOHS10)),
|
||||
IOCONFIG(BSP_E220_M1_PIN, HS_GPIO(FUNC_GPIOHS11)),
|
||||
|
@ -158,6 +155,11 @@ int IoConfigInit(void)
|
|||
sysctl_set_power_mode(SYSCTL_POWER_BANK3, SYSCTL_POWER_V33);
|
||||
#endif
|
||||
|
||||
#ifdef BSP_USING_CAMERA
|
||||
sysctl_set_power_mode(SYSCTL_POWER_BANK7,SYSCTL_POWER_V18);
|
||||
// sysctl_set_power_mode(SYSCTL_POWER_BANK7,SYSCTL_POWER_V18);
|
||||
#endif
|
||||
|
||||
for(i = 0; i < count; i++)
|
||||
{
|
||||
ret = FpioaSetFunction(io_config[i].io_num, io_config[i].func);
|
||||
|
|
|
@ -0,0 +1,15 @@
|
|||
#ifndef CONNECT_DVP_H
|
||||
#define CONNECT_DVP_H
|
||||
#include <device.h>
|
||||
|
||||
#ifdef __cplusplus
|
||||
extern "C" {
|
||||
#endif
|
||||
|
||||
int HwDvpInit(void);
|
||||
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif
|
|
@ -50,33 +50,6 @@ enum HS_GPIO_CONFIG
|
|||
GPIO_ALLOC_START /* index of gpio driver start */
|
||||
};
|
||||
|
||||
#ifdef BSP_USING_CH438
|
||||
#define FPIOA_CH438_ALE 12
|
||||
#define FPIOA_CH438_NWR 13
|
||||
#define FPIOA_CH438_NRD 14
|
||||
#define FPIOA_CH438_D0 15
|
||||
#define FPIOA_CH438_D1 16
|
||||
#define FPIOA_CH438_D2 17
|
||||
#define FPIOA_CH438_D3 18
|
||||
#define FPIOA_CH438_D4 19
|
||||
#define FPIOA_CH438_D5 20
|
||||
#define FPIOA_CH438_D6 21
|
||||
#define FPIOA_CH438_D7 22
|
||||
#define FPIOA_CH438_INT 23
|
||||
|
||||
#define BSP_CH438_ALE_PIN 24
|
||||
#define BSP_CH438_NWR_PIN 25
|
||||
#define BSP_CH438_NRD_PIN 26
|
||||
#define BSP_CH438_D0_PIN 27
|
||||
#define BSP_CH438_D1_PIN 28
|
||||
#define BSP_CH438_D2_PIN 29
|
||||
#define BSP_CH438_D3_PIN 30
|
||||
#define BSP_CH438_D4_PIN 31
|
||||
#define BSP_CH438_D5_PIN 32
|
||||
#define BSP_CH438_D6_PIN 33
|
||||
#define BSP_CH438_D7_PIN 34
|
||||
#define BSP_CH438_INT_PIN 35
|
||||
#endif
|
||||
|
||||
#ifdef BSP_USING_SOFT_SPI
|
||||
#define FPIOA_SOFT_SPI_SCK 26
|
||||
|
@ -88,7 +61,17 @@ enum HS_GPIO_CONFIG
|
|||
#define BSP_SOFT_SPI_MIOS_PIN 25
|
||||
#define BSP_SOFT_SPI_MSOI_PIN 27
|
||||
#define BSP_SOFT_SPI_NCS_PIN 28
|
||||
#endif
|
||||
|
||||
#ifdef BSP_USING_CAMERA
|
||||
#define BSP_DVP_RST_PIN 40
|
||||
#define BSP_DVP_PWDN_PIN 41
|
||||
#define BSP_DVP_XCLK_PIN 42
|
||||
#define BSP_DVP_PCLK_PIN 43
|
||||
#define BSP_DVP_HSYNC_PIN 44
|
||||
#define BSP_DVP_VSYNC_PIN 45
|
||||
#define BSP_DVP_SCL_PIN 46
|
||||
#define BSP_DVP_SDA_PIN 47
|
||||
#endif
|
||||
|
||||
#ifdef BSP_USING_LED
|
||||
|
|
|
@ -0,0 +1,38 @@
|
|||
/* Copyright 2018 Canaan Inc.
|
||||
*
|
||||
* 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 _OV2640_H
|
||||
#define _OV2640_H
|
||||
|
||||
#include <stdint.h>
|
||||
|
||||
#define OV2640_ADDR 0x60
|
||||
|
||||
struct CameraCfg
|
||||
{
|
||||
uint16_t window_w;
|
||||
uint16_t window_h;
|
||||
uint16_t window_xoffset;
|
||||
uint16_t window_yoffset;
|
||||
uint16_t output_w;
|
||||
uint16_t output_h;
|
||||
uint8_t gain;
|
||||
uint8_t gain_manu_enable;
|
||||
};
|
||||
|
||||
int ov2640_init(void);
|
||||
int ov2640_read_id(uint16_t *manuf_id, uint16_t *device_id);
|
||||
int sensorConfigure(struct CameraCfg* cfg_info);
|
||||
|
||||
#endif /* _OV2640_H */
|
|
@ -342,7 +342,7 @@ static void DrvLcdRectUpdate(uint16_t x1, uint16_t y1, uint16_t width, uint16_t
|
|||
}
|
||||
}
|
||||
|
||||
x_err_t DrvLcdInit(Lcd8080DeviceType dev)
|
||||
static x_err_t DrvLcdInit(Lcd8080DeviceType dev)
|
||||
{
|
||||
x_err_t ret = EOK;
|
||||
aiit_lcd = (Lcd8080DeviceType)dev;
|
||||
|
@ -366,6 +366,8 @@ x_err_t DrvLcdInit(Lcd8080DeviceType dev)
|
|||
data = 0x55;
|
||||
DrvLcdDataByte(&data, 1);
|
||||
|
||||
DrvLcdCmd(INVERSION_DISPALY_ON);
|
||||
|
||||
/* set direction */
|
||||
DrvLcdSetDirection(DIR_YX_RLUD);
|
||||
|
||||
|
@ -476,7 +478,6 @@ static uint32 LcdWrite(void *dev, struct BusBlockWriteParam *write_param)
|
|||
}
|
||||
else if(1 == show->type) //output dot
|
||||
{
|
||||
// DrvLcdSetPixel(show->pixel_info.x_pos, show->pixel_info.y_pos, show->pixel_info.pixel_color);
|
||||
DrvLcdSetPixelDot(show->pixel_info.x_startpos,show->pixel_info.y_startpos, show->pixel_info.x_endpos, show->pixel_info.y_endpos,show->pixel_info.pixel_color);
|
||||
return EOK;
|
||||
}
|
||||
|
@ -549,7 +550,7 @@ static int BoardLcdDevBend(struct LcdHardwareDevice *lcd_device, void *param, co
|
|||
|
||||
return ret;
|
||||
}
|
||||
|
||||
static int flag = 1;
|
||||
int HwLcdInit(void)
|
||||
{
|
||||
x_err_t ret = EOK;
|
||||
|
@ -613,7 +614,11 @@ int HwLcdInit(void)
|
|||
|
||||
KPrintf("LCD driver inited ...\r\n");
|
||||
|
||||
DrvLcdInit(lcd_dev);
|
||||
if(flag){
|
||||
DrvLcdInit(lcd_dev);
|
||||
flag = 0;
|
||||
}
|
||||
|
||||
|
||||
return ret;
|
||||
}
|
||||
|
|
|
@ -100,26 +100,3 @@ if BSP_USING_SPI1
|
|||
endif
|
||||
endif
|
||||
|
||||
config BSP_USING_TP
|
||||
bool "Using LCD touch "
|
||||
default n
|
||||
|
||||
if BSP_USING_TP
|
||||
config BSP_TP_SCK_PIN
|
||||
int "TP SCK pin number"
|
||||
default 42
|
||||
config BSP_TP_NCS_PIN
|
||||
int "TP NCS pin number"
|
||||
default 43
|
||||
config BSP_TP_MISO_PIN
|
||||
int "TP MISO pin number"
|
||||
default 44
|
||||
config BSP_TP_IRQ_PIN
|
||||
int "TP IRQ pin number"
|
||||
default 45
|
||||
config BSP_TP_MOSI_PIN
|
||||
int "TP MOSI pin number"
|
||||
default 46
|
||||
|
||||
endif
|
||||
|
||||
|
|
|
@ -10,8 +10,8 @@ if BSP_USING_TOUCH
|
|||
default "touch_dev"
|
||||
config BSP_TOUCH_TP_INT
|
||||
int "touch int pin"
|
||||
default 36
|
||||
default 30
|
||||
config FPIOA_TOUCH_TP_INT
|
||||
int "fpioa touch int pin"
|
||||
default 12
|
||||
default 30
|
||||
endif
|
||||
|
|
|
@ -24,21 +24,33 @@
|
|||
#include <bus.h>
|
||||
#include <gpiohs.h>
|
||||
#include <fpioa.h>
|
||||
#include "gsl2038firmware.h"
|
||||
|
||||
|
||||
struct Finger {
|
||||
uint8_t fingerID;
|
||||
uint32_t x;
|
||||
uint32_t y;
|
||||
};
|
||||
struct Touch_event {
|
||||
uint8_t NBfingers;
|
||||
struct Finger fingers[5];
|
||||
};
|
||||
|
||||
// #define LCD_HEIGHT BSP_LCD_X_MAX
|
||||
// #define LCD_WIDTH BSP_LCD_Y_MAX
|
||||
#define DEFAULT_NUM 0x0D
|
||||
|
||||
#define TOUCH_ADDRESS 0x44
|
||||
volatile bool SemReleaseFlag = 0;
|
||||
|
||||
static struct Bus* i2c_bus = NONE;
|
||||
static struct Bus* pin_bus = NONE;
|
||||
int touch_sem = 0;
|
||||
POINT Pre_Touch_Point;
|
||||
|
||||
#define DATA_REG 0x80
|
||||
#define STATUS_REG 0xE0
|
||||
|
||||
/* HERE WE IMPLEMENT I2C READING AND WRITING FROM SENSOR */
|
||||
/* write sensor register data */
|
||||
static x_err_t WriteReg(struct HardwareDev* dev, uint8 len, uint8* buf)
|
||||
static x_err_t WriteReg(struct HardwareDev* dev, char* buf, int len)
|
||||
{
|
||||
struct BusBlockWriteParam write_param;
|
||||
write_param.pos = 0;
|
||||
|
@ -62,150 +74,10 @@ static x_err_t ReadRegs(struct HardwareDev* dev, uint8 len, uint8* buf)
|
|||
return BusDevReadData(dev, &read_param);
|
||||
}
|
||||
|
||||
/**
|
||||
* i2c_transfer - execute a single I2C message
|
||||
* @msgs: One or more messages to execute before STOP is issued to
|
||||
* terminate the operation; each message begins with a START.
|
||||
*/
|
||||
int I2C_Transfer(struct i2c_msg* msg)
|
||||
{
|
||||
int16 ret = 0;
|
||||
|
||||
if (msg->flags & I2C_M_RD) //根据flag判断是读数据还是写数据
|
||||
{
|
||||
ret = ReadRegs(i2c_bus->owner_haldev, msg->len, msg->buf); //IIC读取数据
|
||||
}
|
||||
else
|
||||
{
|
||||
ret = WriteReg(i2c_bus->owner_haldev, msg->len, msg->buf); //IIC写入数据
|
||||
} //正常完成的传输结构个数
|
||||
|
||||
return ret;
|
||||
}
|
||||
|
||||
static int32_t GtpI2cWrite(uint8_t* buf, int32_t len)
|
||||
{
|
||||
struct i2c_msg msg;
|
||||
int32_t ret = -1;
|
||||
int32_t retries = 0;
|
||||
|
||||
msg.flags = !I2C_M_RD;
|
||||
msg.len = len;
|
||||
msg.buf = buf;
|
||||
//msg.scl_rate = 300 * 1000; // for Rockchip, etc
|
||||
while (retries < 5)
|
||||
{
|
||||
ret = I2C_Transfer(&msg);
|
||||
if (ret == 1) { break; }
|
||||
retries++;
|
||||
}
|
||||
if (retries >= 5)
|
||||
{
|
||||
KPrintf("I2C Write: 0x%04X, %d bytes failed, errcode: %d! Process reset.", (((uint16_t)(buf[0] << 8)) | buf[1]), len - 2, ret);
|
||||
ret = -1;
|
||||
}
|
||||
return ret;
|
||||
}
|
||||
static int32_t GtpI2cRead(uint8_t* buf, int32_t len)
|
||||
{
|
||||
struct i2c_msg msgs[2];
|
||||
int32_t ret = -1;
|
||||
int32_t retries = 0;
|
||||
|
||||
// write reading addr.
|
||||
msgs[0].flags = !I2C_M_RD;
|
||||
msgs[0].len = GTP_ADDR_LENGTH;
|
||||
msgs[0].buf = buf;
|
||||
|
||||
// read data at addr sended.
|
||||
msgs[1].flags = I2C_M_RD;
|
||||
msgs[1].len = len - GTP_ADDR_LENGTH;
|
||||
msgs[1].buf = &buf[GTP_ADDR_LENGTH];
|
||||
|
||||
while (retries < 5)
|
||||
{
|
||||
ret = I2C_Transfer(&msgs[0]);
|
||||
ret += I2C_Transfer(&msgs[1]);
|
||||
if (ret == 2)break;
|
||||
retries++;
|
||||
}
|
||||
if (retries >= 5)
|
||||
{
|
||||
KPrintf("I2C Read: 0x%04X, %d bytes %d times failed, errcode: %d! Process reset.\n", (((uint16_t)(buf[0] << 8)) | buf[1]), len - 2, retries, ret);
|
||||
ret = -1;
|
||||
}
|
||||
return ret;
|
||||
}
|
||||
|
||||
/* HERE WE IMPLEMENT TOUCH INIT */
|
||||
int32_t GtpReadVersion(void)
|
||||
{
|
||||
int32_t ret = -1;
|
||||
uint8_t buf[8] = { GTP_REG_VERSION >> 8, GTP_REG_VERSION & 0xff };
|
||||
|
||||
ret = GtpI2cRead(buf, sizeof(buf));
|
||||
if (ret < 0)
|
||||
{
|
||||
KPrintf("GTP read version failed.\n");
|
||||
return ret;
|
||||
}
|
||||
|
||||
if (buf[5] == 0x00)
|
||||
{
|
||||
KPrintf("IC1 Version: %c%c%c_%02x%02x\n", buf[2], buf[3], buf[4], buf[7], buf[6]);
|
||||
}
|
||||
else
|
||||
{
|
||||
KPrintf("IC2 Version: %c%c%c%c_%02x%02x\n", buf[2], buf[3], buf[4], buf[5], buf[7], buf[6]);
|
||||
}
|
||||
return ret;
|
||||
}
|
||||
|
||||
static int32_t GtpGetInfo(void)
|
||||
{
|
||||
uint8_t end_cmd[3] = { GTP_READ_COOR_ADDR >> 8, GTP_READ_COOR_ADDR & 0xFF, 0 };
|
||||
uint8_t opr_buf[6] = { 0 };
|
||||
int32_t ret = 0;
|
||||
|
||||
uint16_t abs_x_max = GTP_MAX_WIDTH;
|
||||
uint16_t abs_y_max = GTP_MAX_HEIGHT;
|
||||
uint8_t int_trigger_type = GTP_INT_TRIGGER;
|
||||
|
||||
opr_buf[0] = (uint8_t)((GTP_REG_CONFIG_DATA + 1) >> 8);
|
||||
opr_buf[1] = (uint8_t)((GTP_REG_CONFIG_DATA + 1) & 0xFF);
|
||||
|
||||
if (GtpI2cRead(opr_buf, 6) < 0)
|
||||
{
|
||||
return -1;
|
||||
}
|
||||
|
||||
abs_x_max = (opr_buf[3] << 8) + opr_buf[2];
|
||||
abs_y_max = (opr_buf[5] << 8) + opr_buf[4];
|
||||
|
||||
opr_buf[0] = (uint8_t)((GTP_REG_CONFIG_DATA + 6) >> 8);
|
||||
opr_buf[1] = (uint8_t)((GTP_REG_CONFIG_DATA + 6) & 0xFF);
|
||||
|
||||
if (GtpI2cRead(opr_buf, 3) < 0)
|
||||
{
|
||||
return 0;
|
||||
}
|
||||
|
||||
int_trigger_type = opr_buf[2] & 0x03;
|
||||
KPrintf("X_MAX = %d, Y_MAX = %d, TRIGGER = 0x%02x\n",
|
||||
abs_x_max, abs_y_max, int_trigger_type);
|
||||
|
||||
if (GtpI2cWrite(end_cmd, 3) < 0)
|
||||
{
|
||||
KPrintf("I2C write end_cmd error!\n");
|
||||
ret = 0;
|
||||
}
|
||||
return 0; ;
|
||||
}
|
||||
|
||||
// not used in polling mode
|
||||
static void GT9xx_PEN_IRQHandler(void* arg)
|
||||
static void touch_pin_irqhandler(void* arg)
|
||||
{
|
||||
KPrintf("int hdr working.\n");
|
||||
// KPrintf("int hdr working.\n");
|
||||
if (!SemReleaseFlag)
|
||||
{
|
||||
KSemaphoreAbandon(touch_sem);
|
||||
|
@ -213,20 +85,20 @@ static void GT9xx_PEN_IRQHandler(void* arg)
|
|||
}
|
||||
}
|
||||
|
||||
int32_t GT9xx_INT_INIT() {
|
||||
int32_t touch_irq_init()
|
||||
{
|
||||
int32_t ret = -ERROR;
|
||||
|
||||
pin_bus = PinBusInitGet();
|
||||
|
||||
struct PinParam pin_param;
|
||||
struct BusConfigureInfo pin_configure_info;
|
||||
|
||||
pin_bus = PinBusInitGet();
|
||||
|
||||
pin_configure_info.configure_cmd = OPE_CFG;
|
||||
pin_configure_info.private_data = (void*)&pin_param;
|
||||
|
||||
pin_param.cmd = GPIO_CONFIG_MODE;
|
||||
pin_param.pin = BSP_TOUCH_TP_INT;
|
||||
pin_param.mode = GPIO_CFG_INPUT_PULLUP;
|
||||
pin_param.mode = GPIO_CFG_INPUT;
|
||||
ret = BusDrvConfigure(pin_bus->owner_driver, &pin_configure_info);
|
||||
if (ret != EOK) {
|
||||
KPrintf("config pin_param %d input failed!\n", pin_param.pin);
|
||||
|
@ -235,8 +107,8 @@ int32_t GT9xx_INT_INIT() {
|
|||
|
||||
pin_param.cmd = GPIO_IRQ_REGISTER;
|
||||
pin_param.pin = BSP_TOUCH_TP_INT;
|
||||
pin_param.irq_set.irq_mode = GPIO_IRQ_EDGE_FALLING;
|
||||
pin_param.irq_set.hdr = GT9xx_PEN_IRQHandler;
|
||||
pin_param.irq_set.irq_mode = GPIO_IRQ_EDGE_BOTH;
|
||||
pin_param.irq_set.hdr = touch_pin_irqhandler;
|
||||
pin_param.irq_set.args = NONE;
|
||||
ret = BusDrvConfigure(pin_bus->owner_driver, &pin_configure_info);
|
||||
if (ret != EOK) {
|
||||
|
@ -264,7 +136,7 @@ int32_t GT9xx_INT_INIT() {
|
|||
return EOK;
|
||||
}
|
||||
|
||||
int32_t I2C_Touch_Init() {
|
||||
int32_t I2cTouchInit() {
|
||||
// using static bus information
|
||||
int32_t ret = -1;
|
||||
/* find I2C device and get I2C handle */
|
||||
|
@ -294,116 +166,68 @@ int32_t I2C_Touch_Init() {
|
|||
|
||||
// memset(&i2c_configure_info, 0, sizeof(struct BusConfigureInfo));
|
||||
i2c_configure_info.configure_cmd = OPE_INT;
|
||||
uint16 i2c_address = GTP_ADDRESS >> 1;
|
||||
uint16 i2c_address = TOUCH_ADDRESS;
|
||||
i2c_configure_info.private_data = (void*)&i2c_address;
|
||||
BusDrvConfigure(i2c_bus->owner_driver, &i2c_configure_info);
|
||||
|
||||
// 3. init interruption
|
||||
return GT9xx_INT_INIT();
|
||||
return touch_irq_init();
|
||||
}
|
||||
|
||||
|
||||
/* HERE WE IMPLEMENT GET COORDINATE FUNCTION */
|
||||
/**
|
||||
* @brief 触屏处理函数,轮询或者在触摸中断调用
|
||||
* @param 无
|
||||
* @retval 无
|
||||
*/
|
||||
bool GetTouchEvent(POINT* touch_point, touch_event_t* touch_event)
|
||||
void loadfw(struct HardwareDev *dev)
|
||||
{
|
||||
uint8_t addr;
|
||||
uint8_t Wrbuf[5];
|
||||
size_t source_len = sizeof(GSL2038_FW) / sizeof(struct fw_data);
|
||||
|
||||
for (size_t source_line = 0; source_line < source_len; source_line++) {
|
||||
// addr = GSL2038_FW[source_line].offset;
|
||||
memset(Wrbuf, 0 , 5);
|
||||
Wrbuf[0] = GSL2038_FW[source_line].offset;
|
||||
Wrbuf[1] = (char)(GSL2038_FW[source_line].val & 0x000000ff);
|
||||
Wrbuf[2] = (char)((GSL2038_FW[source_line].val & 0x0000ff00) >> 8);
|
||||
Wrbuf[3] = (char)((GSL2038_FW[source_line].val & 0x00ff0000) >> 16);
|
||||
Wrbuf[4] = (char)((GSL2038_FW[source_line].val & 0xff000000) >> 24);
|
||||
|
||||
uint8_t end_cmd[3] = { GTP_READ_COOR_ADDR >> 8, GTP_READ_COOR_ADDR & 0xFF, 0 };
|
||||
uint8_t point_data[2 + 1 + 8 * GTP_MAX_TOUCH + 1] = { GTP_READ_COOR_ADDR >> 8, GTP_READ_COOR_ADDR & 0xFF };
|
||||
uint8_t touch_num = 0;
|
||||
uint8_t finger = 0;
|
||||
static uint16_t pre_touch = 0;
|
||||
|
||||
uint8_t* coor_data = NULL;
|
||||
int32_t input_x = 0;
|
||||
int32_t input_y = 0;
|
||||
int32_t input_w = 0;
|
||||
|
||||
int32_t ret = -1;
|
||||
|
||||
ret = GtpI2cRead(point_data, 12);//10字节寄存器加2字节地址
|
||||
if (ret < 0)
|
||||
{
|
||||
KPrintf("I2C transfer error. errno:%d\n ", ret);
|
||||
return 0;
|
||||
WriteReg(dev, Wrbuf,5);
|
||||
}
|
||||
}
|
||||
|
||||
finger = point_data[GTP_ADDR_LENGTH];//状态寄存器数据
|
||||
void reset()
|
||||
{
|
||||
uint8_t REG[6] = {STATUS_REG, 0xE4, 0xbc, 0xbd, 0xbe, 0xbf};
|
||||
uint8_t DATA[6] = {0x88, 0x04, 0x00, 0x00, 0x00, 0x00};
|
||||
char reg_data[2];
|
||||
|
||||
if (finger == 0x00) //没有数据,退出
|
||||
int i;
|
||||
for (i = 0; i < sizeof(REG); ++i)
|
||||
{
|
||||
ret = 0;
|
||||
goto exit_work_func;
|
||||
// WriteReg(i2c_bus->owner_haldev, ®[i],1);
|
||||
// WriteReg(i2c_bus->owner_haldev, &DATA[i],1);
|
||||
reg_data[0] = REG[i];
|
||||
reg_data[1] = DATA[i];
|
||||
WriteReg(i2c_bus->owner_haldev, reg_data,2);
|
||||
MdelayKTask(10);
|
||||
}
|
||||
}
|
||||
|
||||
if ((finger & 0x80) == 0)//判断buffer status位
|
||||
{
|
||||
ret = 0;
|
||||
goto exit_work_func;//坐标未就绪,数据无效
|
||||
}
|
||||
void startchip()
|
||||
{
|
||||
char reg_data[] = {0xE0, 0x00};
|
||||
|
||||
touch_num = finger & 0x0f;//坐标点数
|
||||
if (touch_num > GTP_MAX_TOUCH)
|
||||
{
|
||||
ret = 0;
|
||||
goto exit_work_func;//大于最大支持点数,错误退出
|
||||
}
|
||||
|
||||
if (touch_num)
|
||||
{
|
||||
coor_data = &point_data[0 * 8 + 3];
|
||||
input_x = coor_data[1] | (coor_data[2] << 8); //x坐标
|
||||
input_y = coor_data[3] | (coor_data[4] << 8); //y坐标
|
||||
input_w = coor_data[5] | (coor_data[6] << 8); //size
|
||||
touch_point->X = input_x;
|
||||
touch_point->Y = input_y;
|
||||
*touch_event = kTouch_Down;
|
||||
Pre_Touch_Point = *touch_point;
|
||||
|
||||
}
|
||||
else if (pre_touch) //touch_ num=0 且pre_touch!=0
|
||||
{
|
||||
*touch_point = Pre_Touch_Point;
|
||||
*touch_event = kTouch_Up;
|
||||
Pre_Touch_Point.X = -1;
|
||||
Pre_Touch_Point.Y = -1;
|
||||
}
|
||||
pre_touch = touch_num;
|
||||
|
||||
exit_work_func:
|
||||
{
|
||||
ret = GtpI2cWrite(end_cmd, 3);
|
||||
if (ret < 0)
|
||||
{
|
||||
KPrintf("I2C write end_cmd error!\n");
|
||||
ret = 0;
|
||||
}
|
||||
}
|
||||
return ret;
|
||||
WriteReg(i2c_bus->owner_haldev, reg_data,2); // Registre
|
||||
}
|
||||
|
||||
static uint32 TouchOpen(void* dev)
|
||||
{
|
||||
int32_t ret = -1;
|
||||
int32_t ret = 0;
|
||||
|
||||
I2C_Touch_Init();
|
||||
ret = GtpReadVersion();
|
||||
if (ret < 0)
|
||||
{
|
||||
KPrintf("gtp read version error\n");
|
||||
return ret;
|
||||
}
|
||||
I2cTouchInit();
|
||||
|
||||
ret = GtpGetInfo();
|
||||
if (ret < 0)
|
||||
{
|
||||
KPrintf("gtp read info error\n");
|
||||
return ret;
|
||||
}
|
||||
reset();
|
||||
loadfw(i2c_bus->owner_haldev);
|
||||
reset();
|
||||
startchip();
|
||||
|
||||
touch_sem = KSemaphoreCreate(0);
|
||||
if (touch_sem < 0) {
|
||||
|
@ -415,8 +239,32 @@ static uint32 TouchOpen(void* dev)
|
|||
}
|
||||
|
||||
static uint32 TouchClose(void* dev)
|
||||
{
|
||||
{
|
||||
int32_t ret = -ERROR;
|
||||
struct PinParam pin_param;
|
||||
struct BusConfigureInfo pin_configure_info;
|
||||
|
||||
pin_configure_info.configure_cmd = OPE_CFG;
|
||||
pin_configure_info.private_data = (void*)&pin_param;
|
||||
|
||||
pin_param.cmd = GPIO_IRQ_DISABLE;
|
||||
pin_param.pin = BSP_TOUCH_TP_INT;
|
||||
ret = BusDrvConfigure(pin_bus->owner_driver, &pin_configure_info);
|
||||
if (ret != EOK) {
|
||||
KPrintf("disable pin_param %d irq failed!\n", pin_param.pin);
|
||||
return -ERROR;
|
||||
}
|
||||
|
||||
pin_param.cmd = GPIO_IRQ_FREE;
|
||||
pin_param.pin = BSP_TOUCH_TP_INT;
|
||||
ret = BusDrvConfigure(pin_bus->owner_driver, &pin_configure_info);
|
||||
if (ret != EOK) {
|
||||
KPrintf("register pin_param %d irq failed!\n", pin_param.pin);
|
||||
return -ERROR;
|
||||
}
|
||||
|
||||
KSemaphoreDelete(touch_sem);
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
|
@ -424,23 +272,35 @@ static uint32 TouchRead(void* dev, struct BusBlockReadParam* read_param)
|
|||
{
|
||||
uint32 ret = -1;
|
||||
x_err_t result;
|
||||
POINT touch_point;
|
||||
touch_point.X = -1;
|
||||
touch_point.Y = -1;
|
||||
touch_event_t touch_event;
|
||||
uint8_t TOUCHRECDATA[24] = {0};
|
||||
struct Touch_event ts_event;
|
||||
char status_reg = 0x80;
|
||||
|
||||
struct TouchDataStandard* data = (struct TouchDataStandard*)read_param->buffer;
|
||||
read_param->read_length = 0;
|
||||
result = KSemaphoreObtain(touch_sem, 100);
|
||||
if (GetTouchEvent(&touch_point, &touch_event))
|
||||
{
|
||||
data->x = touch_point.X;
|
||||
data->y = touch_point.Y;
|
||||
result = KSemaphoreObtain(touch_sem, 1000);
|
||||
// if (EOK == result)
|
||||
// {
|
||||
memset(TOUCHRECDATA, 0, 24);
|
||||
memset(&ts_event, 0, sizeof(struct Touch_event));
|
||||
|
||||
read_param->read_length = read_param->size;
|
||||
ret = EOK;
|
||||
}
|
||||
SemReleaseFlag = 0;
|
||||
WriteReg(i2c_bus->owner_haldev, &status_reg, 1);
|
||||
ReadRegs(i2c_bus->owner_haldev, 24, TOUCHRECDATA);
|
||||
ts_event.NBfingers = TOUCHRECDATA[0];
|
||||
|
||||
for (int i = 0; i < ts_event.NBfingers; i++)
|
||||
{
|
||||
ts_event.fingers[i].x = ((((uint32_t)TOUCHRECDATA[(i * 4) + 5]) << 8) | (uint32_t)TOUCHRECDATA[(i * 4) + 4]) & 0x00000FFF; // 12 bits of X coord
|
||||
ts_event.fingers[i].y = ((((uint32_t)TOUCHRECDATA[(i * 4) + 7]) << 8) | (uint32_t)TOUCHRECDATA[(i * 4) + 6]) & 0x00000FFF;
|
||||
ts_event.fingers[i].fingerID = (uint32_t)TOUCHRECDATA[(i * 4) + 7] >> 4; // finger that did the touch
|
||||
printf("fingers[%d] x %d y %d id %d\n",i,ts_event.fingers[i].x,ts_event.fingers[i].y,ts_event.fingers[i].fingerID);
|
||||
}
|
||||
|
||||
data->x = ts_event.fingers[ts_event.NBfingers - 1].x;
|
||||
data->y = ts_event.fingers[ts_event.NBfingers - 1].y;
|
||||
|
||||
SemReleaseFlag = 0;
|
||||
// }
|
||||
|
||||
return ret;
|
||||
}
|
||||
|
|
File diff suppressed because it is too large
Load Diff
|
@ -163,3 +163,9 @@ if BSP_USING_DAC
|
|||
bool "Using DAC bus drivers"
|
||||
default n
|
||||
endif
|
||||
|
||||
if BSP_USING_CAMERA
|
||||
config RESOURCES_CAMERA
|
||||
bool "Using Camera bus drivers"
|
||||
default n
|
||||
endif
|
||||
|
|
|
@ -65,4 +65,8 @@ ifeq ($(CONFIG_RESOURCES_DAC),y)
|
|||
SRC_DIR += dac
|
||||
endif
|
||||
|
||||
ifeq ($(CONFIG_RESOURCES_CAMERA),y)
|
||||
SRC_DIR += camera
|
||||
endif
|
||||
|
||||
include $(KERNEL_ROOT)/compiler.mk
|
||||
|
|
|
@ -0,0 +1,5 @@
|
|||
SRC_FILES += dev_camera.c drv_camera.c bus_camera.c
|
||||
|
||||
|
||||
|
||||
include $(KERNEL_ROOT)/compiler.mk
|
|
@ -0,0 +1,123 @@
|
|||
/*
|
||||
* Copyright (c) 2020 AIIT XUOS Lab
|
||||
* XiUOS is licensed under Mulan PSL v2.
|
||||
* You can use this software according to the terms and conditions of the Mulan PSL v2.
|
||||
* You may obtain a copy of Mulan PSL v2 at:
|
||||
* http://license.coscl.org.cn/MulanPSL2
|
||||
* THIS SOFTWARE IS PROVIDED ON AN "AS IS" BASIS, WITHOUT WARRANTIES OF ANY KIND,
|
||||
* EITHER EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO NON-INFRINGEMENT,
|
||||
* MERCHANTABILITY OR FIT FOR A PARTICULAR PURPOSE.
|
||||
* See the Mulan PSL v2 for more details.
|
||||
*/
|
||||
|
||||
/**
|
||||
* @file bus_camera.c
|
||||
* @brief register camera bus function using bus driver framework
|
||||
* @version 1.0
|
||||
* @author AIIT XUOS Lab
|
||||
* @date 2021-04-24
|
||||
*/
|
||||
|
||||
#include <bus_camera.h>
|
||||
#include <dev_camera.h>
|
||||
|
||||
/*Register the CAMERA BUS*/
|
||||
int CameraBusInit(struct CameraBus *camera_bus, const char *bus_name)
|
||||
{
|
||||
NULL_PARAM_CHECK(camera_bus);
|
||||
NULL_PARAM_CHECK(bus_name);
|
||||
|
||||
x_err_t ret = EOK;
|
||||
|
||||
if (BUS_INSTALL != camera_bus->bus.bus_state) {
|
||||
strncpy(camera_bus->bus.bus_name, bus_name, NAME_NUM_MAX);
|
||||
|
||||
camera_bus->bus.bus_type = TYPE_CAMERA_BUS;
|
||||
camera_bus->bus.bus_state = BUS_INSTALL;
|
||||
camera_bus->bus.private_data = camera_bus->private_data;
|
||||
|
||||
ret = BusRegister(&camera_bus->bus);
|
||||
if (EOK != ret) {
|
||||
KPrintf("CameraBusInit BusRegister error %u\n", ret);
|
||||
return ret;
|
||||
}
|
||||
} else {
|
||||
KPrintf("CameraBusInit BusRegister bus has been register state%u\n", camera_bus->bus.bus_state);
|
||||
}
|
||||
|
||||
return ret;
|
||||
}
|
||||
|
||||
/*Register the CAMERA Driver*/
|
||||
int CameraDriverInit(struct CameraDriver *camera_driver, const char *driver_name)
|
||||
{
|
||||
NULL_PARAM_CHECK(camera_driver);
|
||||
NULL_PARAM_CHECK(driver_name);
|
||||
|
||||
x_err_t ret = EOK;
|
||||
|
||||
if (DRV_INSTALL != camera_driver->driver.driver_state) {
|
||||
camera_driver->driver.driver_type = TYPE_CAMERA_DRV;
|
||||
camera_driver->driver.driver_state = DRV_INSTALL;
|
||||
|
||||
strncpy(camera_driver->driver.drv_name, driver_name, NAME_NUM_MAX);
|
||||
|
||||
camera_driver->driver.private_data = camera_driver->private_data;
|
||||
|
||||
camera_driver->driver.configure = camera_driver->configure;
|
||||
|
||||
ret = CameraDriverRegister(&camera_driver->driver);
|
||||
if (EOK != ret) {
|
||||
KPrintf("CameraDriverInit DriverRegister error %u\n", ret);
|
||||
return ret;
|
||||
}
|
||||
} else {
|
||||
KPrintf("CameraDriverInit DriverRegister driver has been register state%u\n", camera_driver->driver.driver_state);
|
||||
}
|
||||
|
||||
return ret;
|
||||
}
|
||||
|
||||
/*Release the CAMERA device*/
|
||||
int CameraReleaseBus(struct CameraBus *camera_bus)
|
||||
{
|
||||
NULL_PARAM_CHECK(camera_bus);
|
||||
|
||||
return BusRelease(&camera_bus->bus);
|
||||
}
|
||||
|
||||
/*Register the CAMERA Driver to the CAMERA BUS*/
|
||||
int CameraDriverAttachToBus(const char *drv_name, const char *bus_name)
|
||||
{
|
||||
NULL_PARAM_CHECK(drv_name);
|
||||
NULL_PARAM_CHECK(bus_name);
|
||||
|
||||
x_err_t ret = EOK;
|
||||
|
||||
struct Bus *bus;
|
||||
struct Driver *driver;
|
||||
|
||||
bus = BusFind(bus_name);
|
||||
if (NONE == bus) {
|
||||
KPrintf("CameraDriverAttachToBus find camera bus error!name %s\n", bus_name);
|
||||
return ERROR;
|
||||
}
|
||||
|
||||
if (TYPE_CAMERA_BUS == bus->bus_type) {
|
||||
driver = CameraDriverFind(drv_name, TYPE_CAMERA_DRV);
|
||||
if (NONE == driver) {
|
||||
KPrintf("CameraDriverAttachToBus find camera driver error!name %s\n", drv_name);
|
||||
return ERROR;
|
||||
}
|
||||
|
||||
if (TYPE_CAMERA_DRV == driver->driver_type) {
|
||||
ret = DriverRegisterToBus(bus, driver);
|
||||
if (EOK != ret) {
|
||||
KPrintf("CameraDriverAttachToBus DriverRegisterToBus error %u\n", ret);
|
||||
return ERROR;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
return ret;
|
||||
}
|
|
@ -0,0 +1,200 @@
|
|||
/*
|
||||
* Copyright (c) 2006-2018, RT-Thread Development Team
|
||||
*
|
||||
* SPDX-License-Identifier: Apache-2.0
|
||||
*
|
||||
* Change Logs:
|
||||
* Date Author Notes
|
||||
* 2006-03-13 bernard first version
|
||||
* 2012-05-15 lgnq modified according bernard's implementation.
|
||||
* 2012-05-28 bernard code cleanup
|
||||
* 2012-11-23 bernard fix compiler warning.
|
||||
* 2013-02-20 bernard use RT_CAMERA_RB_BUFSZ to define
|
||||
* the size of ring buffer.
|
||||
* 2014-07-10 bernard rewrite camera framework
|
||||
* 2014-12-31 bernard use open_flag for poll_tx stream mode.
|
||||
* 2015-05-19 Quintin fix DMA tx mod tx_dma->activated flag !=RT_FALSE BUG
|
||||
* in open function.
|
||||
* 2015-11-10 bernard fix the poll rx issue when there is no data.
|
||||
* 2016-05-10 armink add fifo mode to DMA rx when camera->config.bufsz != 0.
|
||||
* 2017-01-19 aubr.cool prevent change camera rx bufsz when camera is opened.
|
||||
* 2017-11-07 JasonJia fix data bits error issue when using tcsetattr.
|
||||
* 2017-11-15 JasonJia fix poll rx issue when data is full.
|
||||
* add TCFLSH and FIONREAD support.
|
||||
* 2018-12-08 Ernest Chen add DMA choice
|
||||
* 2020-09-14 WillianChan add a line feed to the carriage return character
|
||||
* when using interrupt tx
|
||||
*/
|
||||
|
||||
/**
|
||||
* @file dev_camera.c
|
||||
* @brief register camera dev function using bus driver framework
|
||||
* @version 1.0
|
||||
* @author AIIT XUOS Lab
|
||||
* @date 2021-04-24
|
||||
*/
|
||||
|
||||
/*************************************************
|
||||
File name: dev_camera.c
|
||||
Description: support camera dev INT and DMA configure、transfer data
|
||||
Others: take RT-Thread v4.0.2/components/driver/camera/camera.c for references
|
||||
https://github.com/RT-Thread/rt-thread/tree/v4.0.2
|
||||
History:
|
||||
1. Date: 2021-04-24
|
||||
Author: AIIT XUOS Lab
|
||||
Modification:
|
||||
1. support camera dev register, configure, write and read
|
||||
2. add bus driver framework support, include INT and DMA mode
|
||||
*************************************************/
|
||||
|
||||
#include <bus_camera.h>
|
||||
#include <dev_camera.h>
|
||||
|
||||
static DoubleLinklistType cameradev_linklist;
|
||||
|
||||
static uint32 CameraDevOpen(void *dev)
|
||||
{
|
||||
NULL_PARAM_CHECK(dev);
|
||||
|
||||
x_err_t ret = EOK;
|
||||
struct CameraHardwareDevice *camera_dev = (struct CameraHardwareDevice *)dev;
|
||||
|
||||
ret = camera_dev->camera_dev_done->dev_open(dev);
|
||||
|
||||
return EOK;
|
||||
}
|
||||
|
||||
static uint32 CameraDevClose(void *dev)
|
||||
{
|
||||
NULL_PARAM_CHECK(dev);
|
||||
|
||||
x_err_t ret = EOK;
|
||||
struct CameraHardwareDevice *camera_dev = (struct CameraHardwareDevice *)dev;
|
||||
|
||||
ret = camera_dev->camera_dev_done->dev_close(dev);
|
||||
return EOK;
|
||||
}
|
||||
|
||||
static uint32 CameraDevWrite(void *dev, struct BusBlockWriteParam *write_param)
|
||||
{
|
||||
NULL_PARAM_CHECK(dev);
|
||||
NULL_PARAM_CHECK(write_param);
|
||||
|
||||
x_err_t ret = EOK;
|
||||
|
||||
struct CameraHardwareDevice *camera_dev = (struct CameraHardwareDevice *)dev;
|
||||
ret = camera_dev->camera_dev_done->dev_write(dev,write_param);
|
||||
|
||||
return ret;
|
||||
}
|
||||
|
||||
static uint32 CameraDevRead(void *dev, struct BusBlockReadParam *read_param)
|
||||
{
|
||||
NULL_PARAM_CHECK(dev);
|
||||
NULL_PARAM_CHECK(read_param);
|
||||
|
||||
x_err_t ret = EOK;
|
||||
|
||||
struct CameraHardwareDevice *camera_dev = (struct CameraHardwareDevice *)dev;
|
||||
ret = camera_dev->camera_dev_done->dev_read(dev,read_param);
|
||||
|
||||
return EOK;
|
||||
}
|
||||
|
||||
|
||||
static const struct HalDevDone dev_done =
|
||||
{
|
||||
.open = CameraDevOpen,
|
||||
.close = CameraDevClose,
|
||||
.write = CameraDevWrite,
|
||||
.read = CameraDevRead,
|
||||
};
|
||||
|
||||
/*Create the camera device linklist*/
|
||||
static void CameraDeviceLinkInit()
|
||||
{
|
||||
InitDoubleLinkList(&cameradev_linklist);
|
||||
}
|
||||
|
||||
HardwareDevType CameraDeviceFind(const char *dev_name, enum DevType dev_type)
|
||||
{
|
||||
NULL_PARAM_CHECK(dev_name);
|
||||
|
||||
struct HardwareDev *device = NONE;
|
||||
|
||||
DoubleLinklistType *node = NONE;
|
||||
DoubleLinklistType *head = &cameradev_linklist;
|
||||
|
||||
for (node = head->node_next; node != head; node = node->node_next) {
|
||||
device = SYS_DOUBLE_LINKLIST_ENTRY(node, struct HardwareDev, dev_link);
|
||||
if ((!strcmp(device->dev_name, dev_name)) && (dev_type == device->dev_type)) {
|
||||
return device;
|
||||
}
|
||||
}
|
||||
|
||||
KPrintf("CameraDeviceFind cannot find the %s device.return NULL\n", dev_name);
|
||||
return NONE;
|
||||
}
|
||||
|
||||
int CameraDeviceRegister(struct CameraHardwareDevice *camera_device, void *camera_param, const char *device_name)
|
||||
{
|
||||
NULL_PARAM_CHECK(camera_device);
|
||||
NULL_PARAM_CHECK(device_name);
|
||||
|
||||
x_err_t ret = EOK;
|
||||
static x_bool dev_link_flag = RET_FALSE;
|
||||
|
||||
if (!dev_link_flag) {
|
||||
CameraDeviceLinkInit();
|
||||
dev_link_flag = RET_TRUE;
|
||||
}
|
||||
|
||||
if (DEV_INSTALL != camera_device->haldev.dev_state) {
|
||||
strncpy(camera_device->haldev.dev_name, device_name, NAME_NUM_MAX);
|
||||
camera_device->haldev.dev_type = TYPE_CAMERA_DEV;
|
||||
camera_device->haldev.dev_state = DEV_INSTALL;
|
||||
camera_device->haldev.dev_done = (struct HalDevDone *)&dev_done;
|
||||
|
||||
|
||||
DoubleLinkListInsertNodeAfter(&cameradev_linklist, &(camera_device->haldev.dev_link));
|
||||
} else {
|
||||
KPrintf("CameraDeviceRegister device has been register state%u\n", camera_device->haldev.dev_state);
|
||||
}
|
||||
|
||||
return ret;
|
||||
}
|
||||
|
||||
int CameraDeviceAttachToBus(const char *dev_name, const char *bus_name)
|
||||
{
|
||||
NULL_PARAM_CHECK(dev_name);
|
||||
NULL_PARAM_CHECK(bus_name);
|
||||
|
||||
x_err_t ret = EOK;
|
||||
|
||||
struct Bus *bus;
|
||||
struct HardwareDev *device;
|
||||
|
||||
bus = BusFind(bus_name);
|
||||
if (NONE == bus) {
|
||||
KPrintf("CameraDeviceAttachToBus find camera bus error!name %s\n", bus_name);
|
||||
return ERROR;
|
||||
}
|
||||
|
||||
if (TYPE_CAMERA_BUS == bus->bus_type) {
|
||||
device = CameraDeviceFind(dev_name, TYPE_CAMERA_DEV);
|
||||
if (NONE == device) {
|
||||
KPrintf("CameraDeviceAttachToBus find camera device error!name %s\n", dev_name);
|
||||
return ERROR;
|
||||
}
|
||||
|
||||
if (TYPE_CAMERA_DEV == device->dev_type) {
|
||||
ret = DeviceRegisterToBus(bus, device);
|
||||
if (EOK != ret) {
|
||||
KPrintf("CameraDeviceAttachToBus DeviceRegisterToBus error %u\n", ret);
|
||||
return ERROR;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
return EOK;
|
||||
}
|
|
@ -0,0 +1,68 @@
|
|||
/*
|
||||
* Copyright (c) 2020 AIIT XUOS Lab
|
||||
* XiUOS is licensed under Mulan PSL v2.
|
||||
* You can use this software according to the terms and conditions of the Mulan PSL v2.
|
||||
* You may obtain a copy of Mulan PSL v2 at:
|
||||
* http://license.coscl.org.cn/MulanPSL2
|
||||
* THIS SOFTWARE IS PROVIDED ON AN "AS IS" BASIS, WITHOUT WARRANTIES OF ANY KIND,
|
||||
* EITHER EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO NON-INFRINGEMENT,
|
||||
* MERCHANTABILITY OR FIT FOR A PARTICULAR PURPOSE.
|
||||
* See the Mulan PSL v2 for more details.
|
||||
*/
|
||||
|
||||
/**
|
||||
* @file drv_camera.c
|
||||
* @brief register camera drv function using bus driver framework
|
||||
* @version 1.0
|
||||
* @author AIIT XUOS Lab
|
||||
* @date 2021-04-24
|
||||
*/
|
||||
|
||||
#include <bus_camera.h>
|
||||
#include <dev_camera.h>
|
||||
|
||||
static DoubleLinklistType camera_drv_linklist;
|
||||
|
||||
/*Create the driver linklist*/
|
||||
static void CameraDrvLinkInit()
|
||||
{
|
||||
InitDoubleLinkList(&camera_drv_linklist);
|
||||
}
|
||||
|
||||
DriverType CameraDriverFind(const char *drv_name, enum DriverType_e drv_type)
|
||||
{
|
||||
NULL_PARAM_CHECK(drv_name);
|
||||
|
||||
struct Driver *driver = NONE;
|
||||
|
||||
DoubleLinklistType *node = NONE;
|
||||
DoubleLinklistType *head = &camera_drv_linklist;
|
||||
|
||||
for (node = head->node_next; node != head; node = node->node_next) {
|
||||
driver = SYS_DOUBLE_LINKLIST_ENTRY(node, struct Driver, driver_link);
|
||||
|
||||
if ((!strcmp(driver->drv_name, drv_name)) && (drv_type == driver->driver_type)) {
|
||||
return driver;
|
||||
}
|
||||
}
|
||||
|
||||
KPrintf("CameraDriverFind cannot find the %s driver.return NULL\n", drv_name);
|
||||
return NONE;
|
||||
}
|
||||
|
||||
int CameraDriverRegister(struct Driver *driver)
|
||||
{
|
||||
NULL_PARAM_CHECK(driver);
|
||||
|
||||
x_err_t ret = EOK;
|
||||
static x_bool driver_link_flag = RET_FALSE;
|
||||
|
||||
if (!driver_link_flag) {
|
||||
CameraDrvLinkInit();
|
||||
driver_link_flag = RET_TRUE;
|
||||
}
|
||||
|
||||
DoubleLinkListInsertNodeAfter(&camera_drv_linklist, &(driver->driver_link));
|
||||
|
||||
return ret;
|
||||
}
|
|
@ -54,6 +54,7 @@ enum BusType_e
|
|||
TYPE_SERIAL_BUS,
|
||||
TYPE_ADC_BUS,
|
||||
TYPE_DAC_BUS,
|
||||
TYPE_CAMERA_BUS,
|
||||
TYPE_BUS_END,
|
||||
};
|
||||
|
||||
|
@ -80,6 +81,7 @@ enum DevType
|
|||
TYPE_SERIAL_DEV,
|
||||
TYPE_ADC_DEV,
|
||||
TYPE_DAC_DEV,
|
||||
TYPE_CAMERA_DEV,
|
||||
TYPE_DEV_END,
|
||||
};
|
||||
|
||||
|
@ -106,6 +108,7 @@ enum DriverType_e
|
|||
TYPE_SERIAL_DRV,
|
||||
TYPE_ADC_DRV,
|
||||
TYPE_DAC_DRV,
|
||||
TYPE_CAMERA_DRV,
|
||||
TYPE_DRV_END,
|
||||
};
|
||||
|
||||
|
|
|
@ -0,0 +1,69 @@
|
|||
/*
|
||||
* Copyright (c) 2020 AIIT XUOS Lab
|
||||
* XiUOS is licensed under Mulan PSL v2.
|
||||
* You can use this software according to the terms and conditions of the Mulan PSL v2.
|
||||
* You may obtain a copy of Mulan PSL v2 at:
|
||||
* http://license.coscl.org.cn/MulanPSL2
|
||||
* THIS SOFTWARE IS PROVIDED ON AN "AS IS" BASIS, WITHOUT WARRANTIES OF ANY KIND,
|
||||
* EITHER EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO NON-INFRINGEMENT,
|
||||
* MERCHANTABILITY OR FIT FOR A PARTICULAR PURPOSE.
|
||||
* See the Mulan PSL v2 for more details.
|
||||
*/
|
||||
|
||||
/**
|
||||
* @file bus_camera.h
|
||||
* @brief define camera bus and drv function using bus driver framework
|
||||
* @version 1.0
|
||||
* @author AIIT XUOS Lab
|
||||
* @date 2021-11-16
|
||||
*/
|
||||
|
||||
#ifndef BUS_CAMERA_H
|
||||
#define BUS_CAMERA_H
|
||||
|
||||
#include <bus.h>
|
||||
|
||||
#ifdef __cplusplus
|
||||
extern "C" {
|
||||
#endif
|
||||
|
||||
|
||||
struct CameraDriver
|
||||
{
|
||||
struct Driver driver;
|
||||
|
||||
uint32 (*configure) (void *drv, struct BusConfigureInfo *configure_info);
|
||||
|
||||
void *private_data;
|
||||
};
|
||||
|
||||
struct CameraBus
|
||||
{
|
||||
struct Bus bus;
|
||||
|
||||
void *private_data;
|
||||
};
|
||||
|
||||
/*Register the CAMERA bus*/
|
||||
int CameraBusInit(struct CameraBus *camera_bus, const char *bus_name);
|
||||
|
||||
/*Register the CAMERA driver*/
|
||||
int CameraDriverInit(struct CameraDriver *camera_driver, const char *driver_name);
|
||||
|
||||
/*Release the CAMERA device*/
|
||||
int CameraReleaseBus(struct CameraBus *camera_bus);
|
||||
|
||||
/*Register the CAMERA driver to the CAMERA bus*/
|
||||
int CameraDriverAttachToBus(const char *drv_name, const char *bus_name);
|
||||
|
||||
/*Register the driver, manage with the double linklist*/
|
||||
int CameraDriverRegister(struct Driver *driver);
|
||||
|
||||
/*Find the register driver*/
|
||||
DriverType CameraDriverFind(const char *drv_name, enum DriverType_e drv_type);
|
||||
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif
|
|
@ -0,0 +1,69 @@
|
|||
/*
|
||||
* Copyright (c) 2020 AIIT XUOS Lab
|
||||
* XiUOS is licensed under Mulan PSL v2.
|
||||
* You can use this software according to the terms and conditions of the Mulan PSL v2.
|
||||
* You may obtain a copy of Mulan PSL v2 at:
|
||||
* http://license.coscl.org.cn/MulanPSL2
|
||||
* THIS SOFTWARE IS PROVIDED ON AN "AS IS" BASIS, WITHOUT WARRANTIES OF ANY KIND,
|
||||
* EITHER EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO NON-INFRINGEMENT,
|
||||
* MERCHANTABILITY OR FIT FOR A PARTICULAR PURPOSE.
|
||||
* See the Mulan PSL v2 for more details.
|
||||
*/
|
||||
|
||||
/**
|
||||
* @file dev_camera.h
|
||||
* @brief define camera dev function using bus driver framework
|
||||
* @version 1.0
|
||||
* @author AIIT XUOS Lab
|
||||
* @date 2021-04-24
|
||||
*/
|
||||
|
||||
#ifndef DEV_CAMERA_H
|
||||
#define DEV_CAMERA_H
|
||||
|
||||
#include <bus.h>
|
||||
|
||||
#ifdef __cplusplus
|
||||
extern "C" {
|
||||
#endif
|
||||
|
||||
|
||||
struct CameraDataStandard
|
||||
{
|
||||
uint16 addr;
|
||||
uint16 flags;
|
||||
uint16 len;
|
||||
uint16 retries;
|
||||
uint8 *buf;
|
||||
|
||||
struct CameraDataStandard *next;
|
||||
};
|
||||
|
||||
struct CameraDevDone
|
||||
{
|
||||
uint32 (*dev_open) (void *camera_device);
|
||||
uint32 (*dev_close) (void *camera_device);
|
||||
uint32 (*dev_write) (void *camera_device, struct BusBlockWriteParam *msg);
|
||||
uint32 (*dev_read) (void *camera_device, struct BusBlockReadParam *msg);
|
||||
};
|
||||
|
||||
struct CameraHardwareDevice
|
||||
{
|
||||
struct HardwareDev haldev;
|
||||
const struct CameraDevDone *camera_dev_done;
|
||||
};
|
||||
|
||||
/*Register the CAMERA device*/
|
||||
int CameraDeviceRegister(struct CameraHardwareDevice *camera_device, void *camera_param, const char *device_name);
|
||||
|
||||
/*Register the CAMERA device to the CAMERA bus*/
|
||||
int CameraDeviceAttachToBus(const char *dev_name, const char *bus_name);
|
||||
|
||||
/*Find the register CAMERA device*/
|
||||
HardwareDevType CameraDeviceFind(const char *dev_name, enum DevType dev_type);
|
||||
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif
|
|
@ -104,4 +104,9 @@ HardwareDevType ObtainConsole(void);
|
|||
#include <dev_dac.h>
|
||||
#endif
|
||||
|
||||
#ifdef RESOURCES_CAMERA
|
||||
#include <bus_camera.h>
|
||||
#include <dev_camera.h>
|
||||
#endif
|
||||
|
||||
#endif
|
||||
|
|
|
@ -384,6 +384,7 @@ static char *const bus_type_str[] =
|
|||
"SERIAL_BUS",
|
||||
"ADC_BUS",
|
||||
"DAC_BUS",
|
||||
"CAMERA_BUS",
|
||||
"Unknown"
|
||||
};
|
||||
|
||||
|
|
Loading…
Reference in New Issue