Merged in alinjerpelea/nuttx (pull request #935)

drivers: video: add ISX012 Image sensor

* arch: arm: src: cxd56xx: add cisif support

    add cisif support on cxd56xx chip to be able to use cameras

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

* drivers: video: add ISX012 Image sensor

    add driver for ISX012 Image sensor

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

Approved-by: Gregory Nutt <gnutt@nuttx.org>
This commit is contained in:
Alin Jerpelea 2019-07-04 14:02:05 +00:00 committed by Gregory Nutt
parent 128c1f1430
commit 9b8c4a355d
11 changed files with 6640 additions and 0 deletions

View File

@ -0,0 +1,111 @@
/****************************************************************************
* arch/arm/include/cxd56xx/cisif.h
*
* Copyright 2018 Sony Semiconductor Solutions Corporation
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name of Sony Semiconductor Solutions Corporation nor
* the names of its contributors may be used to endorse or promote
* products derived from this software without specific prior written
* permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
#ifndef __ARCH_ARM_INCLUDE_CXD56XX_CISIF_H
#define __ARCH_ARM_INCLUDE_CXD56XX_CISIF_H
/****************************************************************************
* Public Types
****************************************************************************/
typedef void (*notify_callback_t)(uint8_t code, uint32_t size, uint32_t addr);
typedef void (*comp_callback_t)(uint8_t code, uint32_t size, uint32_t addr);
struct cisif_init_yuv_param_s
{
uint16_t hsize;
uint16_t vsize;
uint32_t notify_size;
notify_callback_t notify_func;
};
typedef struct cisif_init_yuv_param_s cisif_init_yuv_param_t;
struct cisif_init_jpeg_param_s
{
uint32_t notify_size;
notify_callback_t notify_func;
};
typedef struct cisif_init_jpeg_param_s cisif_init_jpeg_param_t;
struct cisif_sarea_s
{
uint8_t *strg_addr;
uint32_t strg_size;
};
typedef struct cisif_sarea_s cisif_sarea_t;
struct cisif_param_s
{
uint32_t format;
cisif_init_yuv_param_t yuv_param;
cisif_init_jpeg_param_t jpg_param;
cisif_sarea_t sarea;
comp_callback_t comp_func;
};
typedef struct cisif_param_s cisif_param_t;
#ifndef __ASSEMBLY__
#undef EXTERN
#if defined(__cplusplus)
#define EXTERN extern "C"
extern "C"
{
#else
#define EXTERN extern
#endif
/****************************************************************************
* Public Function Prototypes
****************************************************************************/
int cxd56_cisifinit(void);
int cxd56_cisiffinalize(void);
int cxd56_cisifstartcapture(cisif_param_t *param, cisif_sarea_t *sarea);
int cxd56_cisifstopcapture(void);
int cxd56_cisifsetdmabuf(cisif_sarea_t *sarea);
#undef EXTERN
#if defined(__cplusplus)
}
#endif
#endif /* __ASSEMBLY__ */
#endif /* __ARCH_ARM_INCLUDE_CXD56XX_CISIF_H */

View File

@ -1070,6 +1070,11 @@ config CXD56_UDMAC
Use DMAC for reading sensing data from SCU FIFO.
endif # CXD56_SCU
config CXD56_CISIF
bool "CMOS image sensor interface"
default n
---help---
CMOS image sensor interface for cx5602 chip
endmenu
comment "Storage Options"

View File

@ -160,6 +160,10 @@ ifeq ($(CONFIG_CXD56_GE2D),y)
CHIP_CSRCS += cxd56_ge2d.c
endif
ifeq ($(CONFIG_CXD56_CISIF),y)
CHIP_CSRCS += cxd56_cisif.c
endif
ifeq ($(CONFIG_CXD56_SCU),y)
CHIP_CSRCS += cxd56_scu.c cxd56_scufifo.c
ifeq ($(CONFIG_CXD56_ADC),y)

View File

@ -0,0 +1,910 @@
/****************************************************************************
* arch/arm/src/cxd56xx/cxd56_cisif.c
*
* Copyright 2018 Sony Semiconductor Solutions Corporation
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name of Sony Semiconductor Solutions Corporation nor
* the names of its contributors may be used to endorse or promote
* products derived from this software without specific prior written
* permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
/****************************************************************************
* Included Files
****************************************************************************/
#include <nuttx/config.h>
#include <stdio.h>
#include <stdbool.h>
#include <string.h>
#include <errno.h>
#include <debug.h>
#include <time.h>
#include <nuttx/irq.h>
#include <nuttx/arch.h>
#include <arch/chip/cisif.h>
#include <nuttx/video/video.h>
#include "up_arch.h"
#include "cxd56_clock.h"
#include "hardware/cxd56_cisif.h"
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/
/* To see the interrupt timing of Vsync */
/* #define CISIF_INTR_TRACE */
/* #define CISIF_DBG_CONTI_CAP */
#define YUV_VSIZE_MIN (64)
#define YUV_HSIZE_MIN (96)
#define YUV_VSIZE_MAX (360)
#define YUV_HSIZE_MAX (480)
#define JPG_INT_ALL (JPG_ERR_STATUS_INT | \
JPG_MEM_OVF_INT | \
JPG_FIFO_OVF_INT | \
JPG_AXI_TRERR_INT | \
JPG_MARKER_ERR_INT | \
JPG_AXI_TRDN_INT)
#define YCC_INT_ALL (YCC_MEM_OVF_INT | \
YCC_FIFO_OVF_INT | \
YCC_AXI_TRERR_INT | \
YCC_MARKER_ERR_INT | \
SIZE_UNDER_INT | \
SIZE_OVER_INT | \
YCC_AXI_TRDN_INT)
/* YUV data size with frame v * h */
#define YUV_SIZE(v, h) (v * h * 2)
/* Check Buffer address alignement */
#define CISIF_BUFADDR_ALIGNMENT (32)
#define ILLEGAL_BUFADDR_ALIGNMENT(addr) (((addr) == NULL) || \
(((uint32_t)(addr) % \
CISIF_BUFADDR_ALIGNMENT) != 0))
#ifdef CONFIG_CXD56_CISIF_DEBUG
#define ciferr _err
#define cifwarn _warn
#define cifinfo _info
#else
#define ciferr(x...)
#define cifwarn(x...)
#define cifinfo(x...)
#endif
/****************************************************************************
* Private Types
****************************************************************************/
enum state_e
{
STATE_STANDBY,
STATE_READY,
STATE_CAPTURE,
};
typedef enum state_e state_t;
typedef void (*intc_func_table)(uint8_t code);
/****************************************************************************
* Private Data
****************************************************************************/
static state_t g_state = STATE_STANDBY;
static uint32_t g_storage_addr = 0;
notify_callback_t g_jpg_notify_callback_func;
notify_callback_t g_ycc_notify_callback_func;
comp_callback_t g_comp_callback_func;
static bool g_jpgint_receive;
static bool g_errint_receive;
#ifdef CISIF_INTR_TRACE
static uint32_t g_cisif_vint_count = 0;
static uint32_t g_cisif_vint_count_max = 0;
static uint32_t g_cisif_time_start;
static uint32_t g_cisif_time_stop;
#endif
/****************************************************************************
* Private Function Prototypes
****************************************************************************/
static void cisif_vs_int(uint8_t code);
static void cisif_ycc_axi_trdn_int(uint8_t code);
static void cisif_ycc_nstorage_int(uint8_t code);
static void cisif_jpg_axi_trdn_int(uint8_t code);
static void cisif_jpg_nstorage_int(uint8_t code);
static void cisif_ycc_err_int(uint8_t code);
static void cisif_jpg_err_int(uint8_t code);
static void cisif_reg_write(uint16_t reg, uint32_t val);
static uint32_t cisif_reg_read(uint16_t reg);
static int cisif_check_param(cisif_param_t *p);
static int cisif_set_yuv_param(cisif_param_t *p);
static int cisif_set_jpg_param(cisif_param_t *p);
static int cisif_check_sarea(void *s);
static int cisif_set_yuv_sarea(void *s);
static int cisif_set_jpg_sarea(void *s);
static int cisif_set_intlev_sarea(void *s, uint32_t yuv_size);
int cisif_intc_handler(int irq, FAR void *context, FAR void *arg);
const intc_func_table g_intcomp_func[] =
{
cisif_vs_int, /* VS_INT */
NULL, /* EOY_INT */
NULL, /* SOY_INT */
NULL, /* EOI_INT */
NULL, /* SOI_INT */
NULL, /* YCC_VACT_END_INT */
NULL, /* JPG_VACT_END_INT */
cisif_ycc_axi_trdn_int, /* YCC_AXI_TRDN_INT */
cisif_ycc_nstorage_int, /* YCC_NSTORAGE_INT */
NULL, /* YCC_DAREA_END_INT */
cisif_jpg_axi_trdn_int, /* JPG_AXI_TRDN_INT */
cisif_jpg_nstorage_int, /* JPG_NSTORAGE_INT */
NULL, /* JPG_DAREA_END_INT */
NULL, /* reserve */
NULL, /* reserve */
NULL, /* VLATCH_INT */
cisif_ycc_err_int, /* SIZE_OVER_INT */
cisif_ycc_err_int, /* SIZE_UNDER_INT */
cisif_ycc_err_int, /* YCC_MARKER_ERR_INT */
cisif_ycc_err_int, /* YCC_AXI_TRERR_INT */
cisif_ycc_err_int, /* YCC_FIFO_OVF_INT */
cisif_ycc_err_int, /* YCC_MEM_OVF_INT */
NULL, /* reserve */
NULL, /* reserve */
cisif_jpg_err_int, /* JPG_MARKER_ERR_INT */
cisif_jpg_err_int, /* JPG_AXI_TRERR_INT */
cisif_jpg_err_int, /* JPG_FIFO_OVF_INT */
cisif_jpg_err_int, /* JPG_MEM_OVF_INT */
cisif_jpg_err_int, /* JPG_ERR_STATUS_INT */
};
/****************************************************************************
* Private Functions
****************************************************************************/
#ifdef CISIF_INTR_TRACE
static uint64_t cisif_get_msec_time(void)
{
struct timespec tp;
if (clock_gettime(CLOCK_REALTIME, &tp))
{
return 0;
}
return (((uint64_t)tp.tv_sec) * 1000 + tp.tv_nsec / 1000000);
}
static void cisif_trace_time_start(void)
{
g_cisif_time_start = (uint32_t)cisif_get_msec_time();
}
static void cisif_trace_time_stop(char *str)
{
g_cisif_time_stop = (uint32_t)cisif_get_msec_time();
printf("%s:%d[ms]\n", str, (uint32_t)(g_cisif_time_stop -
g_cisif_time_start));
}
void cisif_intrtrace_start(int max)
{
g_cisif_vint_count_max = max;
g_cisif_vint_count = 0;
cisif_trace_time_start();
}
#endif
/****************************************************************************
* cisif_vs_int
****************************************************************************/
static void cisif_vs_int(uint8_t code)
{
#ifdef CISIF_INTR_TRACE
if (g_cisif_vint_count < g_cisif_vint_count_max)
{
cisif_trace_time_stop("cisif_vs_int");
cisif_trace_time_start();
g_cisif_vint_count++;
}
else
{
g_cisif_vint_count_max = 0;
}
#endif
switch (g_state)
{
case STATE_STANDBY:
cifinfo("invalid state\n");
break;
case STATE_READY:
g_errint_receive = false;
break;
case STATE_CAPTURE:
g_errint_receive = false;
break;
default:
cifinfo("invalid state\n");
break;
}
}
/****************************************************************************
* cisif_callback_for_intlev
****************************************************************************/
static void cisif_callback_for_intlev(uint8_t code)
{
uint32_t size;
uint32_t yuv_size;
if (!g_jpgint_receive)
{
/* In either YUV or JPEG is not received,
* wait receiving.
*/
g_jpgint_receive = true;
return;
}
/* Read received data size */
yuv_size = cisif_reg_read(CISIF_YCC_DSTRG_CONT);
size = yuv_size + cisif_reg_read(CISIF_JPG_DSTRG_CONT);
/* Notify and get next addr */
g_comp_callback_func(0, size, g_storage_addr);
g_jpgint_receive = false;
cisif_reg_write(CISIF_EXE_CMD, 1);
cisif_reg_write(CISIF_YCC_DREAD_CONT, 0);
cisif_reg_write(CISIF_JPG_DREAD_CONT, 0);
return;
}
/****************************************************************************
* cisif_ycc_axi_trdn_int
****************************************************************************/
static void cisif_ycc_axi_trdn_int(uint8_t code)
{
uint32_t size;
uint32_t cisif_mode;
#ifdef CISIF_INTR_TRACE
cisif_trace_time_stop("cisif_ycc_axi_trdn_int");
#endif
if (g_errint_receive)
{
/* In error occured case in the same frame, ignore */
cisif_reg_write(CISIF_YCC_DREAD_CONT, 0);
return;
}
cisif_mode = cisif_reg_read(CISIF_MODE);
if (cisif_mode == MODE_INTLEV_TRS_EN)
{
/* In JPEG + YUV format case */
cisif_callback_for_intlev(code);
}
else
{
size = cisif_reg_read(CISIF_YCC_DSTRG_CONT);
g_comp_callback_func(0, size, g_storage_addr);
cisif_reg_write(CISIF_YCC_DREAD_CONT, 0);
}
}
/****************************************************************************
* cisif_ycc_nstorage_int
****************************************************************************/
static void cisif_ycc_nstorage_int(uint8_t code)
{
uint32_t size;
size = cisif_reg_read(CISIF_YCC_DSTRG_CONT);
g_ycc_notify_callback_func (0, size, g_storage_addr);
cisif_reg_write(CISIF_YCC_DREAD_CONT, size);
}
/****************************************************************************
* cisif_jpg_axi_trdn_int
****************************************************************************/
static void cisif_jpg_axi_trdn_int(uint8_t code)
{
uint32_t size;
uint32_t cisif_mode;
#ifdef CISIF_INTR_TRACE
cisif_trace_time_stop("cisif_jpg_axi_trdn_int");
#endif
if (g_errint_receive)
{
/* In error occured case in the same frame, ignore */
cisif_reg_write(CISIF_JPG_DREAD_CONT, 0);
return;
}
cisif_mode = cisif_reg_read(CISIF_MODE);
if (cisif_mode == MODE_INTLEV_TRS_EN)
{
/* In JPEG + YUV format case */
cisif_callback_for_intlev(code);
}
else
{
size = cisif_reg_read(CISIF_JPG_DSTRG_CONT);
g_comp_callback_func(0, size, g_storage_addr);
cisif_reg_write(CISIF_JPG_DREAD_CONT, 0);
}
}
/****************************************************************************
* cisif_jpg_nstorage_int
****************************************************************************/
static void cisif_jpg_nstorage_int(uint8_t code)
{
uint32_t size;
size = cisif_reg_read(CISIF_JPG_DSTRG_CONT);
g_jpg_notify_callback_func(0, size, g_storage_addr);
cisif_reg_write(CISIF_JPG_DREAD_CONT, size);
}
/****************************************************************************
* cisif_ycc_err_int
****************************************************************************/
static void cisif_ycc_err_int(uint8_t code)
{
uint32_t size;
#ifdef CISIF_INTR_TRACE
cisif_trace_time_stop("cisif_ycc_err_int");
#endif
size = cisif_reg_read(CISIF_YCC_DSTRG_CONT);
g_comp_callback_func(code, size, g_storage_addr);
cisif_reg_write(CISIF_YCC_DREAD_CONT, 0);
g_errint_receive = true;
}
/****************************************************************************
* cisif_jpg_err_int
****************************************************************************/
static void cisif_jpg_err_int(uint8_t code)
{
uint32_t size;
uint32_t addr;
#ifdef CISIF_INTR_TRACE
cisif_trace_time_stop("cisif_jpg_err_int");
#endif
addr = g_storage_addr;
size = cisif_reg_read(CISIF_JPG_DSTRG_CONT);
g_comp_callback_func(code, size, addr);
cisif_reg_write(CISIF_JPG_DREAD_CONT, 0);
g_errint_receive = true;
}
/****************************************************************************
* cisif_intc_handler
****************************************************************************/
int cisif_intc_handler(int irq, FAR void *context, FAR void *arg)
{
uint32_t value;
uint32_t enable;
uint8_t index;
value = cisif_reg_read(CISIF_INTR_STAT);
cisif_reg_write(CISIF_INTR_CLEAR, value & ALL_CLEAR_INT);
cifinfo("int stat %08x\n", value);
enable = cisif_reg_read(CISIF_INTR_ENABLE);
value = (value & enable);
for (index = 0;
index < sizeof(g_intcomp_func) / sizeof(g_intcomp_func[0]);
index++)
{
if ((value & (1 << index)) != 0)
{
g_intcomp_func[index](index);
}
}
return OK;
}
/****************************************************************************
* cisif_reg_write
****************************************************************************/
static void cisif_reg_write(uint16_t reg, uint32_t val)
{
putreg32(val, CXD56_CISIF_BASE + reg);
}
/****************************************************************************
* cisif_reg_read
****************************************************************************/
static uint32_t cisif_reg_read(uint16_t reg)
{
return getreg32(CXD56_CISIF_BASE + reg);
}
/****************************************************************************
* cisif_check_param
****************************************************************************/
static int cisif_check_param(cisif_param_t *p)
{
if (p == NULL)
{
return -EINVAL;
}
if (p->comp_func == NULL)
{
return -EINVAL;
}
switch (p->format)
{
case V4L2_PIX_FMT_UYVY:
case V4L2_PIX_FMT_JPEG:
case V4L2_PIX_FMT_JPEG_WITH_SUBIMG:
break;
default:
return -EINVAL;
}
if (p->format != V4L2_PIX_FMT_JPEG)
{
if (p->yuv_param.hsize < YUV_HSIZE_MIN ||
p->yuv_param.hsize > YUV_HSIZE_MAX ||
p->yuv_param.vsize < YUV_VSIZE_MIN ||
p->yuv_param.vsize > YUV_VSIZE_MAX)
{
return -EINVAL;
}
if (p->yuv_param.notify_func != NULL)
{
if (p->yuv_param.notify_size == 0)
{
return -EINVAL;
}
}
}
if (p->format != V4L2_PIX_FMT_UYVY)
{
if (p->jpg_param.notify_func != NULL)
{
if (p->jpg_param.notify_size == 0)
{
return -EINVAL;
}
}
}
return OK;
}
/****************************************************************************
* cisif_check_sarea
****************************************************************************/
static int cisif_check_sarea(void *s)
{
if (s == NULL)
{
return -EINVAL;
}
cisif_sarea_t *ss = (cisif_sarea_t *)s;
if (ILLEGAL_BUFADDR_ALIGNMENT(ss->strg_addr) ||
ss->strg_size == 0)
{
return -EINVAL;
}
return OK;
}
/****************************************************************************
* cisif_set_yuvparam
****************************************************************************/
static int cisif_set_yuv_param(cisif_param_t *p)
{
uint32_t act_size = 0;
act_size = (p->yuv_param.vsize & 0x1ff) << 16;
act_size |= p->yuv_param.hsize & 0x1ff;
cisif_reg_write(CISIF_ACT_SIZE, act_size);
cisif_reg_write(CISIF_CIS_SIZE, act_size);
/* must align 32 bytes */
cisif_reg_write(CISIF_YCC_NSTRG_SIZE, (p->yuv_param.notify_size
& 0xffffffe0));
g_ycc_notify_callback_func = p->yuv_param.notify_func;
return OK;
}
/****************************************************************************
* cisif_set_yuvsarea
****************************************************************************/
static int cisif_set_yuv_sarea(void *s)
{
cisif_sarea_t *ss = (cisif_sarea_t *)s;
/* must align 32 bytes */
cisif_reg_write(CISIF_YCC_DAREA_SIZE, (ss->strg_size & 0xffffffe0));
cisif_reg_write(CISIF_YCC_START_ADDR, (uint32_t)ss->strg_addr);
return OK;
}
/****************************************************************************
* cisif_set_jpg_param
****************************************************************************/
static int cisif_set_jpg_param(cisif_param_t *p)
{
/* must align 32 bytes */
cisif_reg_write(CISIF_JPG_NSTRG_SIZE, (p->jpg_param.notify_size
& 0xffffffe0));
g_jpg_notify_callback_func = p->jpg_param.notify_func;
return OK;
}
/****************************************************************************
* cisif_set_jpg_sarea
****************************************************************************/
static int cisif_set_jpg_sarea(void *s)
{
cisif_sarea_t *ss = (cisif_sarea_t *)s;
/* must align 32 bytes */
cisif_reg_write(CISIF_JPG_DAREA_SIZE, (ss->strg_size & 0xffffffe0));
cisif_reg_write(CISIF_JPG_START_ADDR, (uint32_t)ss->strg_addr);
return OK;
}
/****************************************************************************
* cisif_set_jpg_sarea
****************************************************************************/
static int cisif_set_intlev_sarea(void *s, uint32_t yuv_size)
{
cisif_sarea_t *sarea = (cisif_sarea_t *)s;
cisif_sarea_t sarea_int;
if (sarea->strg_size < yuv_size)
{
return -EINVAL;
}
/* Set for YUV */
sarea_int.strg_addr = sarea->strg_addr;
sarea_int.strg_size = yuv_size;
cisif_set_yuv_sarea(&sarea_int);
/* Set for JPEG */
sarea_int.strg_addr = sarea->strg_addr + yuv_size;
sarea_int.strg_size = sarea->strg_size - yuv_size;
cisif_set_jpg_sarea(&sarea_int);
return OK;
}
/****************************************************************************
* Public Functions
****************************************************************************/
/****************************************************************************
* cxd56_cisifinit
****************************************************************************/
int cxd56_cisifinit(void)
{
if (g_state != STATE_STANDBY)
{
return -EPERM;
}
/* enable CISIF clock */
cxd56_img_cisif_clock_enable();
/* disable CISIF interrupt */
cisif_reg_write(CISIF_INTR_DISABLE, ALL_CLEAR_INT);
cisif_reg_write(CISIF_INTR_CLEAR, ALL_CLEAR_INT);
/* attach interrupt handler */
irq_attach(CXD56_IRQ_CISIF, cisif_intc_handler, NULL);
/* enable CISIF irq */
up_enable_irq(CXD56_IRQ_CISIF);
#ifdef CISIF_INTR_TRACE
cisif_reg_write(CISIF_INTR_ENABLE, VS_INT);
#endif
g_state = STATE_READY;
return OK;
}
/****************************************************************************
* cxd56_cisiffinalize
****************************************************************************/
int cxd56_cisiffinalize(void)
{
if (g_state != STATE_READY)
{
return -EPERM;
}
/* disable CISIF irq */
up_disable_irq(CXD56_IRQ_CISIF);
/* detach interrupt handler */
irq_detach(CXD56_IRQ_CISIF);
/* disable CISIF interrupt */
cisif_reg_write(CISIF_INTR_DISABLE, ALL_CLEAR_INT);
cisif_reg_write(CISIF_INTR_CLEAR, ALL_CLEAR_INT);
/* disable CISIF clock */
cxd56_img_cisif_clock_disable();
g_state = STATE_STANDBY;
return OK;
}
/****************************************************************************
* cxd56_cisifstartcapturing
****************************************************************************/
int cxd56_cisifstartcapture(
cisif_param_t *param,
cisif_sarea_t *sarea)
{
uint32_t cisif_mode;
uint32_t interrupts = VS_INT;
int ret;
if (g_state != STATE_READY)
{
return -EPERM;
}
ret = cisif_check_param(param);
if (ret != OK)
{
return ret;
}
cisif_reg_write(CISIF_INTR_DISABLE, ALL_CLEAR_INT);
ret = cisif_check_sarea(sarea);
if (ret != OK)
{
return ret;
}
switch (param->format)
{
case V4L2_PIX_FMT_UYVY:
cisif_set_yuv_param(param);
cisif_set_yuv_sarea(sarea);
cisif_mode = MODE_YUV_TRS_EN;
interrupts |= YCC_INT_ALL;
break;
case V4L2_PIX_FMT_JPEG:
cisif_set_jpg_param(param);
cisif_set_jpg_sarea(sarea);
cisif_mode = MODE_JPG_TRS_EN;
interrupts |= JPG_INT_ALL;
break;
case V4L2_PIX_FMT_JPEG_WITH_SUBIMG:
cisif_set_yuv_param(param);
cisif_set_jpg_param(param);
cisif_set_intlev_sarea(sarea,
YUV_SIZE(param->yuv_param.vsize,
param->yuv_param.hsize));
cisif_mode = MODE_INTLEV_TRS_EN;
interrupts |= YCC_INT_ALL | JPG_INT_ALL;
g_jpgint_receive = false;
break;
default:
return -EINVAL;
}
g_comp_callback_func = param->comp_func;
g_storage_addr = (uint32_t)sarea->strg_addr;
g_state = STATE_CAPTURE;
if (g_ycc_notify_callback_func != NULL)
{
interrupts |= YCC_NSTORAGE_INT;
}
if (g_jpg_notify_callback_func != NULL)
{
interrupts |= JPG_NSTORAGE_INT;
}
cisif_reg_write(CISIF_MODE, cisif_mode);
cisif_reg_write(CISIF_INTR_CLEAR, interrupts);
cisif_reg_write(CISIF_INTR_ENABLE, interrupts);
cisif_reg_write(CISIF_DIN_ENABLE, 1);
cisif_reg_write(CISIF_EXE_CMD, 1);
return OK;
}
int cxd56_cisifstopcapture(void)
{
g_state = STATE_READY;
cisif_reg_write(CISIF_DIN_ENABLE, 0);
cisif_reg_write(CISIF_INTR_DISABLE, ALL_CLEAR_INT);
cisif_reg_write(CISIF_EXE_CMD, 1);
return OK;
}
int cxd56_cisifsetdmabuf(cisif_sarea_t *sarea)
{
int ret;
uint32_t cisif_mode;
uint32_t yuv_regsize;
uint32_t yuv_hsize;
uint32_t yuv_vsize;
ret = cisif_check_sarea(sarea);
if (ret != OK)
{
return ret;
}
cisif_mode = cisif_reg_read(CISIF_MODE);
switch (cisif_mode)
{
case MODE_YUV_TRS_EN:
ret = cisif_set_yuv_sarea(sarea);
break;
case MODE_JPG_TRS_EN:
ret = cisif_set_jpg_sarea(sarea);
break;
default: /* MODE_INTLEV_TRS_EN */
/* Get YUV frame size information */
yuv_regsize = cisif_reg_read(CISIF_ACT_SIZE);
yuv_vsize = (yuv_regsize >> 16) & 0x1ff;
yuv_hsize = yuv_regsize & 0x01ff;
ret = cisif_set_intlev_sarea(sarea,
YUV_SIZE(yuv_vsize, yuv_hsize));
break;
}
if (ret != OK)
{
return ret;
}
cisif_reg_write(CISIF_EXE_CMD, 1);
g_storage_addr = (uint32_t)sarea->strg_addr;
return ret;
}

View File

@ -0,0 +1,113 @@
/****************************************************************************
* arch/arm/src/cxd56xx/hardware/cxd56_cisif.h
*
* Copyright 2018 Sony Semiconductor Solutions Corporation
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name of Sony Semiconductor Solutions Corporation nor
* the names of its contributors may be used to endorse or promote
* products derived from this software without specific prior written
* permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
#ifndef __ARCH_ARM_SRC_CXD56XX_CHIP__CXD56_CISIF_H
#define __ARCH_ARM_SRC_CXD56XX_CHIP__CXD56_CISIF_H
/****************************************************************************
* Included Files
****************************************************************************/
#include "hardware/cxd5602_memorymap.h"
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/
/* Register offsets *********************************************************/
/* Common Register Offsets */
#define CISIF_INTR_STAT (0x0000)
#define CISIF_INTR_ENABLE (0x0004)
#define CISIF_INTR_DISABLE (0x0008)
#define CISIF_INTR_CLEAR (0x000C)
#define CISIF_DIN_ENABLE (0x0020)
#define CISIF_CIS_SIZE (0x0024)
#define CISIF_ACT_POS (0x0028)
#define CISIF_ACT_SIZE (0x002C)
#define CISIF_MODE (0x0030)
#define CISIF_ILCODE (0x0034)
#define CISIF_FORMAT (0x0038)
#define CISIF_POL (0x003C)
#define CISIF_YCC_START_ADDR (0x0040)
#define CISIF_YCC_DAREA_SIZE (0x0044)
#define CISIF_YCC_NSTRG_SIZE (0x0048)
#define CISIF_YCC_DSTRG_CONT (0x004C)
#define CISIF_YCC_DREAD_CONT (0x0050)
#define CISIF_JPG_START_ADDR (0x0060)
#define CISIF_JPG_DAREA_SIZE (0x0064)
#define CISIF_JPG_NSTRG_SIZE (0x0068)
#define CISIF_JPG_DSTRG_CONT (0x006C)
#define CISIF_JPG_DREAD_CONT (0x0070)
#define CISIF_EXE_CMD (0x0080)
#define CISIF_NSTANDBY (0x0090)
#define CISIF_NRST (0x0094)
#define CISIF_TEST_INT (0x00F0)
#define JPG_ERR_STATUS_INT (1<<28)
#define JPG_MEM_OVF_INT (1<<27)
#define JPG_FIFO_OVF_INT (1<<26)
#define JPG_AXI_TRERR_INT (1<<25)
#define JPG_MARKER_ERR_INT (1<<24)
#define YCC_MEM_OVF_INT (1<<21)
#define YCC_FIFO_OVF_INT (1<<20)
#define YCC_AXI_TRERR_INT (1<<19)
#define YCC_MARKER_ERR_INT (1<<18)
#define SIZE_UNDER_INT (1<<17)
#define SIZE_OVER_INT (1<<16)
#define VLATCH_INT (1<<15)
#define JPG_DAREA_END_INT (1<<12)
#define JPG_NSTORAGE_INT (1<<11)
#define JPG_AXI_TRDN_INT (1<<10)
#define YCC_DAREA_END_INT (1<<9)
#define YCC_NSTORAGE_INT (1<<8)
#define YCC_AXI_TRDN_INT (1<<7)
#define JPG_VACT_END_INT (1<<6)
#define YCC_VACT_END_INT (1<<5)
#define SOI_INT (1<<4)
#define EOI_INT (1<<3)
#define SOY_INT (1<<2)
#define EOY_INT (1<<1)
#define VS_INT (1<<0)
#define ALL_CLEAR_INT (0xFFFFFFFF)
#define ALL_DISABLE_INT (0x01ffffff)
#define MODE_YUV_TRS_EN (0x00000004)
#define MODE_JPG_TRS_EN (0x00000109)
#define MODE_INTLEV_TRS_EN (0x0000010E)
#endif /* __ARCH_ARM_SRC_CXD56XX_CHIP__CXD56_CISIF_H */

View File

@ -36,6 +36,11 @@ config VIDEO_MAX7456
Support for the Maxim 7456 monochrome on-screen display
multiplexer.
config VIDEO_ISX012
bool "ISX012 Image sensor"
default n
select I2C
config VIDEO_OV2640
bool "OV2640 camera chip"
default n

View File

@ -49,6 +49,10 @@ endif
ifeq ($(CONFIG_I2C),y)
ifeq ($(CONFIG_VIDEO_ISX012),y)
CSRCS += isx012.c
endif
ifeq ($(CONFIG_VIDEO_OV2640),y)
CSRCS += ov2640.c
endif

3684
drivers/video/isx012.c Normal file

File diff suppressed because it is too large Load Diff

View File

@ -0,0 +1,74 @@
/****************************************************************************
* include/nuttx/video/isx012.h
*
* Copyright 2018 Sony Semiconductor Solutions Corporation
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name of Sony Semiconductor Solutions Corporation nor
* the names of its contributors may be used to endorse or promote
* products derived from this software without specific prior written
* permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
#ifndef __INCLUDE_NUTTX_VIDEO_ISX012_H
#define __INCLUDE_NUTTX_VIDEO_ISX012_H
/****************************************************************************
* Included Files
****************************************************************************/
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/
/****************************************************************************
* Public Types
****************************************************************************/
/****************************************************************************
* Public Data
****************************************************************************/
#ifdef __cplusplus
#define EXTERN extern "C"
extern "C"
{
#else
#define EXTERN extern
#endif
/****************************************************************************
* Public Function Prototypes
****************************************************************************/
FAR struct video_devops_s *isx012_initialize(void);
int isx012_uninitialize(void);
#undef EXTERN
#ifdef __cplusplus
}
#endif
#endif /* __INCLUDE_NUTTX_VIDEO_ISX012_H */

View File

@ -0,0 +1,338 @@
/****************************************************************************
* drivers/video/isx012_range.h
*
* Copyright 2018 Sony Semiconductor Solutions Corporation
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name of Sony Semiconductor Solutions Corporation nor
* the names of its contributors may be used to endorse or promote
* products derived from this software without specific prior written
* permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
/****************************************************************************
* Included Files
****************************************************************************/
#include "isx012_reg.h"
#ifndef __DRIVERS_VIDEO_ISX012_RANGE_H
#define __DRIVERS_VIDEO_ISX012_RANGE_H
/* Definition for control brightness */
#define ISX012_TYPE_BRIGHTNESS V4L2_CTRL_TYPE_INTEGER
#define ISX012_NAME_BRIGHTNESS "Brightness"
#define ISX012_DEF_BRIGHTNESS (0)
#define ISX012_MIN_BRIGHTNESS (-128)
#define ISX012_MAX_BRIGHTNESS (127)
#define ISX012_STEP_BRIGHTNESS (1)
#define ISX012_REG_BRIGHTNESS UIBRIGHTNESS
#define ISX012_SIZE_BRIGHTNESS (1)
/* Definition for control contrast */
#define ISX012_TYPE_CONTRAST V4L2_CTRL_TYPE_U8FIXEDPOINT_Q7
#define ISX012_NAME_CONTRAST "Contrast"
#define ISX012_DEF_CONTRAST (0x80)
#define ISX012_MIN_CONTRAST (0x00)
#define ISX012_MAX_CONTRAST (0xFF)
#define ISX012_STEP_CONTRAST (1)
#define ISX012_REG_CONTRAST UICONTRAST
#define ISX012_SIZE_CONTRAST (1)
/* Definition for control saturation */
#define ISX012_TYPE_SATURATION V4L2_CTRL_TYPE_INTEGER
#define ISX012_NAME_SATURATION "Saturation"
#define ISX012_DEF_SATURATION (0)
#define ISX012_MIN_SATURATION (0)
#define ISX012_MAX_SATURATION (255)
#define ISX012_STEP_SATURATION (1)
#define ISX012_REG_SATURATION UISATURATION_TYPE1
#define ISX012_SIZE_SATURATION (1)
/* Definition for control hue */
#define ISX012_TYPE_HUE V4L2_CTRL_TYPE_INTEGER
#define ISX012_NAME_HUE "Hue"
#define ISX012_DEF_HUE (0)
#define ISX012_MIN_HUE (0)
#define ISX012_MAX_HUE (255)
#define ISX012_STEP_HUE (1)
#define ISX012_REG_HUE UIHUE_TYPE1
#define ISX012_SIZE_HUE (1)
/* Definition for control auto white balance */
#define ISX012_TYPE_AUTOWB V4L2_CTRL_TYPE_BOOLEAN
#define ISX012_NAME_AUTOWB "Automatic white balance"
#define ISX012_DEF_AUTOWB true
#define ISX012_MIN_AUTOWB false
#define ISX012_MAX_AUTOWB true
#define ISX012_STEP_AUTOWB (1)
#define ISX012_REG_AUTOWB CPUEXT
#define ISX012_SIZE_AUTOWB (1)
/* Definition for control red balance */
#define ISX012_TYPE_REDBALANCE V4L2_CTRL_TYPE_INTEGER
#define ISX012_NAME_REDBALANCE "Red balance"
#define ISX012_DEF_REDBALANCE (0)
#define ISX012_MIN_REDBALANCE (0)
#define ISX012_MAX_REDBALANCE (65535)
#define ISX012_STEP_REDBALANCE (1)
#define ISX012_REG_REDBALANCE RATIO_R_AUTO
#define ISX012_SIZE_REDBALANCE (2)
/* Definition for control blue balance */
#define ISX012_TYPE_BLUEBALANCE V4L2_CTRL_TYPE_INTEGER
#define ISX012_NAME_BLUEBALANCE "Red balance"
#define ISX012_DEF_BLUEBALANCE (0)
#define ISX012_MIN_BLUEBALANCE (0)
#define ISX012_MAX_BLUEBALANCE (65535)
#define ISX012_STEP_BLUEBALANCE (1)
#define ISX012_REG_BLUEBALANCE RATIO_B_AUTO
#define ISX012_SIZE_BLUEBALANCE (2)
/* Definition for control gamma curve */
#define ISX012_TYPE_GAMMACURVE V4L2_CTRL_TYPE_U16
#define ISX012_NAME_GAMMACURVE "Gamma adjustment(curve)"
#define ISX012_DEF_GAMMACURVE (0)
#define ISX012_MIN_GAMMACURVE (0)
#define ISX012_MAX_GAMMACURVE (511)
#define ISX012_STEP_GAMMACURVE (1)
#define ISX012_ELEMSIZE_GAMMACURVE (1)
#define ISX012_ELEMS_GAMMACURVE (19)
#define ISX012_REG_GAMMACURVE GAMMA_BASE
#define ISX012_SIZE_GAMMACURVE (2)
/* Definition for control exposure value */
#define ISX012_TYPE_EXPOSURE V4L2_CTRL_TYPE_INTEGER_TIMES_3
#define ISX012_NAME_EXPOSURE "Exposure value"
#define ISX012_DEF_EXPOSURE (0)
#define ISX012_MIN_EXPOSURE (-6)
#define ISX012_MAX_EXPOSURE (6)
#define ISX012_STEP_EXPOSURE (1)
#define ISX012_REG_EXPOSURE EVSEL
#define ISX012_SIZE_EXPOSURE (1)
/* Definition for control horizontal mirroring(V4L2_BUF_TYPE_VIDEO_CAPTURE) */
#define ISX012_TYPE_HFLIP V4L2_CTRL_TYPE_BOOLEAN
#define ISX012_NAME_HFLIP "Mirror horizontally(VIDEO)"
#define ISX012_DEF_HFLIP false
#define ISX012_MIN_HFLIP false
#define ISX012_MAX_HFLIP true
#define ISX012_STEP_HFLIP (1)
#define ISX012_REG_HFLIP READVECT_MONI
#define ISX012_SIZE_HFLIP (1)
/* Definition for control vertical mirroring(V4L2_BUF_TYPE_VIDEO_CAPTURE) */
#define ISX012_TYPE_VFLIP V4L2_CTRL_TYPE_BOOLEAN
#define ISX012_NAME_VFLIP "Mirror vertically(VIDEO)"
#define ISX012_DEF_VFLIP false
#define ISX012_MIN_VFLIP false
#define ISX012_MAX_VFLIP true
#define ISX012_STEP_VFLIP (1)
#define ISX012_REG_VFLIP READVECT_MONI
#define ISX012_SIZE_VFLIP (1)
/* Definition for control horizontal mirroring(V4L2_BUF_TYPE_STILL_CAPTURE) */
#define ISX012_TYPE_HFLIP_STILL V4L2_CTRL_TYPE_BOOLEAN
#define ISX012_NAME_HFLIP_STILL "Mirror horizontally(STILL)"
#define ISX012_DEF_HFLIP_STILL false
#define ISX012_MIN_HFLIP_STILL false
#define ISX012_MAX_HFLIP_STILL true
#define ISX012_STEP_HFLIP_STILL (1)
#define ISX012_REG_HFLIP_STILL READVECT_CAP
#define ISX012_SIZE_HFLIP_STILL (1)
/* Definition for control vertical mirroring(V4L2_BUF_TYPE_STILL_CAPTURE) */
#define ISX012_TYPE_VFLIP_STILL V4L2_CTRL_TYPE_BOOLEAN
#define ISX012_NAME_VFLIP_STILL "Mirror vertically(STILL)"
#define ISX012_DEF_VFLIP_STILL false
#define ISX012_MIN_VFLIP_STILL false
#define ISX012_MAX_VFLIP_STILL true
#define ISX012_STEP_VFLIP_STILL (1)
#define ISX012_REG_VFLIP_STILL READVECT_CAP
#define ISX012_SIZE_VFLIP_STILL (1)
/* Definition for control sharpness */
#define ISX012_TYPE_SHARPNESS V4L2_CTRL_TYPE_INTEGER
#define ISX012_NAME_SHARPNESS "Sharpness"
#define ISX012_DEF_SHARPNESS (0)
#define ISX012_MIN_SHARPNESS (0)
#define ISX012_MAX_SHARPNESS (255)
#define ISX012_STEP_SHARPNESS (1)
#define ISX012_REG_SHARPNESS UISHARPNESS_POS_TYPE1
#define ISX012_SIZE_SHARPNESS (1)
/* Definition for control color killer */
#define ISX012_TYPE_COLORKILLER V4L2_CTRL_TYPE_BOOLEAN
#define ISX012_NAME_COLORKILLER "Color killer"
#define ISX012_DEF_COLORKILLER false
#define ISX012_MIN_COLORKILLER false
#define ISX012_MAX_COLORKILLER true
#define ISX012_STEP_COLORKILLER (1)
#define ISX012_REG_COLORKILLER FMODE
#define ISX012_SIZE_COLORKILLER (1)
/* Definition for control color effect */
#define ISX012_TYPE_COLOREFFECT V4L2_CTRL_TYPE_INTEGER_MENU
#define ISX012_NAME_COLOREFFECT "Color effect"
#define ISX012_DEF_COLOREFFECT V4L2_COLORFX_NONE
#define ISX012_MIN_COLOREFFECT (0)
#define ISX012_MAX_COLOREFFECT (6)
#define ISX012_STEP_COLOREFFECT (1)
#define ISX012_REG_COLOREFFECT FMODE
#define ISX012_SIZE_COLOREFFECT (1)
/* Definition for control auto exposure */
#define ISX012_TYPE_EXPOSUREAUTO V4L2_CTRL_TYPE_INTEGER
#define ISX012_NAME_EXPOSUREAUTO "Auto Exposure"
#define ISX012_DEF_EXPOSUREAUTO (0)
#define ISX012_MIN_EXPOSUREAUTO (0)
#define ISX012_MAX_EXPOSUREAUTO (1)
#define ISX012_STEP_EXPOSUREAUTO (1)
#define ISX012_REG_EXPOSUREAUTOVALUE_LSB SHT_TIME_AUTO_L
#define ISX012_REG_EXPOSUREAUTOVALUE_MSB SHT_TIME_AUTO_H
#define ISX012_SIZE_EXPOSUREAUTOVALUE (2)
/* Definition for control exposure time */
#define ISX012_TYPE_EXPOSURETIME V4L2_CTRL_TYPE_INTEGER
#define ISX012_NAME_EXPOSURETIME "Exposure time(usec)"
#define ISX012_DEF_EXPOSURETIME (0)
#define ISX012_MIN_EXPOSURETIME (1)
#define ISX012_MAX_EXPOSURETIME (10000)
#define ISX012_STEP_EXPOSURETIME (1)
#define ISX012_REG_EXPOSURETIME SHT_PREMODE_TYPE1
#define ISX012_SIZE_EXPOSURETIME (2)
#define ISX012_UNIT_EXPOSURETIME_US (100)
/* Definition for control photometry */
#define ISX012_TYPE_PHOTOMETRY V4L2_CTRL_TYPE_INTEGER_MENU
#define ISX012_NAME_PHOTOMETRY "Photometry"
#define ISX012_DEF_PHOTOMETRY V4L2_EXPOSURE_METERING_AVERAGE
#define ISX012_MIN_PHOTOMETRY (0)
#define ISX012_MAX_PHOTOMETRY (3)
#define ISX012_STEP_PHOTOMETRY (1)
#define ISX012_REG_PHOTOMETRY AE_SUB_SN1
#define ISX012_SIZE_PHOTOMETRY (1)
/* Definition for control zoom */
#define ISX012_TYPE_ZOOM V4L2_CTRL_TYPE_U16FIXEDPOINT_Q8
#define ISX012_NAME_ZOOM "Zoom"
#define ISX012_DEF_ZOOM (0x0100)
#define ISX012_MIN_ZOOM (0x0100)
#define ISX012_MAX_ZOOM (0x1000)
#define ISX012_STEP_ZOOM (1)
#define ISX012_REG_ZOOM EZOOM_MAG
#define ISX012_SIZE_ZOOM (2)
/* Definition for control preset white balance */
#define ISX012_TYPE_PRESETWB V4L2_CTRL_TYPE_INTEGER_MENU
#define ISX012_NAME_PRESETWB "Preset white balance"
#define ISX012_DEF_PRESETWB V4L2_WHITE_BALANCE_AUTO
#define ISX012_MIN_PRESETWB (0)
#define ISX012_MAX_PRESETWB (5)
#define ISX012_STEP_PRESETWB (1)
#define ISX012_REG_PRESETWB AWB_SN1
#define ISX012_SIZE_PRESETWB (2)
/* Definition for control YGAMMA adujust */
#define ISX012_TYPE_YGAMMA V4L2_CTRL_TYPE_BOOLEAN
#define ISX012_NAME_YGAMMA "Wide dynamic range"
#define ISX012_DEF_YGAMMA (false)
#define ISX012_MIN_YGAMMA (false)
#define ISX012_MAX_YGAMMA (true)
#define ISX012_STEP_YGAMMA (1)
#define ISX012_REG_YGAMMA YGAMMA_MODE
#define ISX012_SIZE_YGAMMA (1)
/* Definition for control ISO sensitivity */
#define ISX012_TYPE_ISO V4L2_CTRL_TYPE_INTEGER_MENU
#define ISX012_NAME_ISO "ISO sensitivity"
#define ISX012_DEF_ISO (0)
#define ISX012_MIN_ISO (0)
#define ISX012_MAX_ISO (18)
#define ISX012_STEP_ISO (1)
#define ISX012_REG_ISO ISO_TYPE1
#define ISX012_SIZE_ISO (1)
/* Definition for control ISO automatic */
#define ISX012_TYPE_ISOAUTO V4L2_CTRL_TYPE_INTEGER_MENU
#define ISX012_NAME_ISOAUTO "Automatic ISO sensitivity"
#define ISX012_DEF_ISOAUTO (false)
#define ISX012_MIN_ISOAUTO (0)
#define ISX012_MAX_ISOAUTO (1)
#define ISX012_STEP_ISOAUTO (1)
#define ISX012_REG_ISOAUTO ISO_TYPE1
#define ISX012_SIZE_ISOAUTO (1)
#define ISX012_REG_ISOAUTOVALUE ISOSENS_OUT
#define ISX012_SIZE_ISOAUTOVALUE (1)
/* Definition for control 3A lock */
#define ISX012_TYPE_3ALOCK V4L2_CTRL_TYPE_BITMASK
#define ISX012_NAME_3ALOCK "Lock AWB/AE"
#define ISX012_DEF_3ALOCK (0)
#define ISX012_MIN_3ALOCK (0)
#define ISX012_MAX_3ALOCK (3)
#define ISX012_STEP_3ALOCK (1)
#define ISX012_REG_3ALOCK CPUEXT
#define ISX012_SIZE_3ALOCK (1)
/* Definition for control JPEG compression quality */
#define ISX012_TYPE_JPGQUALITY V4L2_CTRL_TYPE_INTEGER
#define ISX012_NAME_JPGQUALITY "JPEG compression quality"
#define ISX012_DEF_JPGQUALITY (75)
#define ISX012_MIN_JPGQUALITY (1)
#define ISX012_MAX_JPGQUALITY (100)
#define ISX012_STEP_JPGQUALITY (1)
#define ISX012_REG_JPGQUALITY INT_QLTY2
#define ISX012_SIZE_JPGQUALITY (1)
#endif /* __DRIVERS_VIDEO_ISX012_RANGE_H */

File diff suppressed because it is too large Load Diff