summaryrefslogtreecommitdiff
diff options
context:
space:
mode:
-rw-r--r--drivers/media/i2c/adv7481.c17
-rw-r--r--drivers/media/i2c/adv7481_reg.h7
-rw-r--r--drivers/media/platform/msm/ais/isp/msm_isp.h19
-rw-r--r--drivers/media/platform/msm/ais/isp/msm_isp47.c32
-rw-r--r--drivers/media/platform/msm/ais/isp/msm_isp_axi_util.c14
-rw-r--r--drivers/media/platform/msm/ais/isp/msm_isp_util.c182
-rw-r--r--drivers/video/msm/ba/msm_ba.c18
-rw-r--r--include/media/msm_ba.h3
-rw-r--r--include/uapi/media/ais/msm_ais_isp.h4
9 files changed, 294 insertions, 2 deletions
diff --git a/drivers/media/i2c/adv7481.c b/drivers/media/i2c/adv7481.c
index 74d7b9584827..b6b89a9eefe2 100644
--- a/drivers/media/i2c/adv7481.c
+++ b/drivers/media/i2c/adv7481.c
@@ -1005,6 +1005,7 @@ static long adv7481_ioctl(struct v4l2_subdev *sd, unsigned int cmd, void *arg)
{
struct adv7481_state *state = to_state(sd);
int *ret_val = arg;
+ uint8_t status = 0;
long ret = 0;
int param = 0;
@@ -1039,6 +1040,22 @@ static long adv7481_ioctl(struct v4l2_subdev *sd, unsigned int cmd, void *arg)
case VIDIOC_HDMI_RX_CEC_S_ENABLE:
ret = adv7481_cec_powerup(state, arg);
break;
+ case VIDIOC_CVBS_G_FIELD_STATUS:
+ /* Select SDP read-only Map 1 */
+ adv7481_wr_byte(&state->i2c_client, state->i2c_sdp_addr,
+ SDP_RW_MAP_REG, 0x02);
+ status = adv7481_rd_byte(&state->i2c_client,
+ state->i2c_sdp_addr, SDP_RO_MAP_1_FIELD_ADDR);
+ adv7481_wr_byte(&state->i2c_client, state->i2c_sdp_addr,
+ SDP_RW_MAP_REG, 0x00);
+ if (ret_val) {
+ *ret_val = ADV_REG_GETFIELD(status,
+ SDP_RO_MAP_1_EVEN_FIELD);
+ } else {
+ pr_err("%s: NULL pointer provided\n", __func__);
+ ret = -EINVAL;
+ }
+ break;
default:
pr_err("Not a typewriter! Command: 0x%x", cmd);
ret = -ENOTTY;
diff --git a/drivers/media/i2c/adv7481_reg.h b/drivers/media/i2c/adv7481_reg.h
index 60b1301abbe6..96f0a5df10c0 100644
--- a/drivers/media/i2c/adv7481_reg.h
+++ b/drivers/media/i2c/adv7481_reg.h
@@ -1,4 +1,4 @@
-/* Copyright (c) 2014-2016, The Linux Foundation. All rights reserved.
+/* Copyright (c) 2014-2017, The Linux Foundation. All rights reserved.
*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License version 2 and
@@ -411,6 +411,11 @@
#define SDP_RO_MAIN_IN_LOCK_BMSK 0x0001
#define SDP_RO_MAIN_IN_LOCK_SHFT 0
+/* SDP R/O Map 1 Registers */
+#define SDP_RO_MAP_1_FIELD_ADDR 0x45
+#define SDP_RO_MAP_1_EVEN_FIELD_BMSK 0x10
+#define SDP_RO_MAP_1_EVEN_FIELD_SHFT 4
+
/*
* CSI Map Registers
diff --git a/drivers/media/platform/msm/ais/isp/msm_isp.h b/drivers/media/platform/msm/ais/isp/msm_isp.h
index 86974eeb4a32..d4c6eba78b78 100644
--- a/drivers/media/platform/msm/ais/isp/msm_isp.h
+++ b/drivers/media/platform/msm/ais/isp/msm_isp.h
@@ -164,6 +164,8 @@ struct msm_vfe_irq_ops {
void (*config_irq)(struct vfe_device *vfe_dev,
uint32_t irq_status0, uint32_t irq_status1,
enum msm_isp_irq_operation);
+ void (*process_sof_irq)(struct vfe_device *vfe_dev,
+ uint32_t irq_status0, uint32_t irq_status1);
void (*process_eof_irq)(struct vfe_device *vfe_dev,
uint32_t irq_status0);
};
@@ -411,6 +413,12 @@ struct msm_vfe_frame_request_queue {
#define MSM_VFE_REQUESTQ_SIZE 8
+struct msm_vfe_fields_info {
+ bool even_field;
+ struct timeval sof_ts;
+ struct timeval field_ts;
+};
+
struct msm_vfe_axi_stream {
uint32_t frame_id;
enum msm_vfe_axi_state state;
@@ -457,6 +465,11 @@ struct msm_vfe_axi_stream {
enum msm_stream_memory_input_t memory_input;
struct msm_isp_sw_framskip sw_skip;
uint8_t sw_ping_pong_bit;
+
+ bool interlaced;
+ struct msm_vfe_fields_info field_info[2];
+ uint32_t field_index;
+ uint32_t field_type;
};
struct msm_vfe_axi_composite_info {
@@ -798,6 +811,12 @@ struct vfe_device {
/* before halt irq info */
uint32_t recovery_irq0_mask;
uint32_t recovery_irq1_mask;
+
+ /* interlaced field info */
+ void *ba_inst_hdl;
+ struct task_struct *field_thread_id;
+ wait_queue_head_t field_waitqueue;
+ bool wakeupflag;
};
struct vfe_parent_device {
diff --git a/drivers/media/platform/msm/ais/isp/msm_isp47.c b/drivers/media/platform/msm/ais/isp/msm_isp47.c
index 04e879fc3bcf..9da7dee59064 100644
--- a/drivers/media/platform/msm/ais/isp/msm_isp47.c
+++ b/drivers/media/platform/msm/ais/isp/msm_isp47.c
@@ -662,6 +662,37 @@ void msm_vfe47_process_epoch_irq(struct vfe_device *vfe_dev,
}
}
+static void msm_isp47_process_sof_irq(struct vfe_device *vfe_dev,
+ uint32_t irq_status0, uint32_t irq_status1)
+{
+ int i, axi_src_idx[4], src_count = 0;
+ struct msm_vfe_axi_stream *pstream_info;
+ struct msm_vfe_axi_shared_data *axi_data = &vfe_dev->axi_data;
+
+ if (irq_status0 & BIT(0))
+ axi_src_idx[src_count++] = CAMIF_RAW;
+ if (irq_status1 & BIT(29))
+ axi_src_idx[src_count++] = RDI_INTF_0;
+ if (irq_status1 & BIT(30))
+ axi_src_idx[src_count++] = RDI_INTF_1;
+ if (irq_status1 & BIT(31))
+ axi_src_idx[src_count++] = RDI_INTF_2;
+
+ if (src_count == 0)
+ return;
+
+ for (i = 0; i < src_count; i++) {
+ pstream_info = &axi_data->stream_info[axi_src_idx[i]];
+
+ if (pstream_info->interlaced) {
+ vfe_dev->wakeupflag = true;
+ wake_up_interruptible(&vfe_dev->field_waitqueue);
+ /* currently we support only 1 interlaced instance */
+ break;
+ }
+ }
+}
+
void msm_isp47_process_eof_irq(struct vfe_device *vfe_dev,
uint32_t irq_status0)
{
@@ -2718,6 +2749,7 @@ struct msm_vfe_hardware_info vfe47_hw_info = {
.process_stats_irq = msm_isp_process_stats_irq,
.process_epoch_irq = msm_vfe47_process_epoch_irq,
.config_irq = msm_vfe47_config_irq,
+ .process_sof_irq = msm_isp47_process_sof_irq,
.process_eof_irq = msm_isp47_process_eof_irq,
},
.axi_ops = {
diff --git a/drivers/media/platform/msm/ais/isp/msm_isp_axi_util.c b/drivers/media/platform/msm/ais/isp/msm_isp_axi_util.c
index a85ee30769c4..9c06ee3b2687 100644
--- a/drivers/media/platform/msm/ais/isp/msm_isp_axi_util.c
+++ b/drivers/media/platform/msm/ais/isp/msm_isp_axi_util.c
@@ -2042,6 +2042,12 @@ static int msm_isp_process_done_buf(struct vfe_device *vfe_dev,
buf_event.u.buf_done.buf_idx = buf->buf_idx;
buf_event.u.buf_done.output_format =
stream_info->runtime_output_format;
+
+ if (stream_info->interlaced)
+ buf_event.u.buf_done.field_type = stream_info->field_type;
+ else
+ buf_event.u.buf_done.field_type = 0;
+
if (vfe_dev->fetch_engine_info.is_busy &&
SRC_TO_INTF(stream_info->stream_src) == VFE_PIX_0) {
vfe_dev->fetch_engine_info.is_busy = 0;
@@ -3132,6 +3138,7 @@ static int msm_isp_stop_axi_stream(struct vfe_device *vfe_dev,
}
}
+ stream_info->interlaced = false;
vfe_dev->reg_update_requested &=
~(BIT(SRC_TO_INTF(stream_info->stream_src)));
}
@@ -3544,13 +3551,18 @@ int msm_isp_axi_output_cfg(struct vfe_device *vfe_dev, void *arg)
INIT_LIST_HEAD(&pstream_info->request_q);
pstream_info->frame_based =
- pCmd->output_path_cfg[axi_src_idx].frame_based;
+ pCmd->output_path_cfg[axi_src_idx].frame_based & BIT(0);
+ pstream_info->interlaced =
+ (pCmd->output_path_cfg[axi_src_idx].frame_based
+ & BIT(INTERLACE_OFFSET)) ? true : false;
/* send buffers to user through vfe dev node */
pstream_info->buf_divert = 1;
pstream_info->output_format =
pCmd->output_path_cfg[axi_src_idx].format;
+ pstream_info->field_index = 0;
+
msm_isp_axi_get_num_planes(
pCmd->output_path_cfg[axi_src_idx].format,
pstream_info);
diff --git a/drivers/media/platform/msm/ais/isp/msm_isp_util.c b/drivers/media/platform/msm/ais/isp/msm_isp_util.c
index 9e5317eb2920..2401ff645057 100644
--- a/drivers/media/platform/msm/ais/isp/msm_isp_util.c
+++ b/drivers/media/platform/msm/ais/isp/msm_isp_util.c
@@ -14,6 +14,8 @@
#include <linux/io.h>
#include <media/v4l2-subdev.h>
#include <linux/ratelimit.h>
+#include <linux/kthread.h>
+#include <linux/sched.h>
#include "msm.h"
#include "msm_isp_util.h"
@@ -23,6 +25,7 @@
#include "cam_smmu_api.h"
#define CREATE_TRACE_POINTS
#include "trace/events/msm_cam.h"
+#include "media/msm_ba.h"
#define MAX_ISP_V4l2_EVENTS 100
#define MAX_ISP_REG_LIST 100
@@ -1974,6 +1977,166 @@ void msm_isp_reset_burst_count_and_frame_drop(
msm_isp_reset_framedrop(vfe_dev, stream_info);
}
+static void msm_isp_field_type_read_thread(void *data)
+{
+ int ret = 0;
+ uint8_t i, j = 0;
+ bool even_field = 0;
+ uint64_t timestamp_us[4];
+ struct msm_isp_timestamp ts;
+ struct msm_vfe_axi_stream *stream_info = NULL;
+ struct vfe_device *vfe_dev = (struct vfe_device *)data;
+
+ pr_debug("Enter field_type_read_thread\n");
+
+ vfe_dev->ba_inst_hdl = msm_ba_open(NULL);
+ if (vfe_dev->ba_inst_hdl == NULL) {
+ pr_err("%s: ba open failed\n", __func__);
+ return;
+ }
+
+ while (!kthread_should_stop()) {
+ ret = 0;
+ wait_event_interruptible(vfe_dev->field_waitqueue,
+ vfe_dev->wakeupflag == true);
+ if (kthread_should_stop()) {
+ pr_debug("%s: field thread has stopped\n", __func__);
+ goto bs_close;
+ }
+
+ for (i = 0; i < VFE_AXI_SRC_MAX; i++) {
+ if (vfe_dev->axi_data.stream_info[i].interlaced)
+ break;
+ }
+ if (i == VFE_AXI_SRC_MAX) {
+ vfe_dev->wakeupflag = false;
+ continue;
+ }
+
+ stream_info = &vfe_dev->axi_data.stream_info[i];
+ j = stream_info->field_index;
+
+ /* Detect field status from bridge chip */
+ ret = msm_ba_private_ioctl(vfe_dev->ba_inst_hdl,
+ VIDIOC_CVBS_G_FIELD_STATUS, &even_field);
+ if (ret) {
+ pr_err("%s: get field status failed: %d\n",
+ __func__, ret);
+ } else {
+ msm_isp_get_timestamp(&ts, vfe_dev);
+ stream_info->field_info[j%2].even_field = even_field;
+ stream_info->field_info[j%2].field_ts.tv_sec =
+ ts.buf_time.tv_sec;
+ stream_info->field_info[j%2].field_ts.tv_usec =
+ ts.buf_time.tv_usec;
+ }
+
+ stream_info->field_index++;
+
+ /* once 2 fields info getting done, do the verification */
+ if (stream_info->field_index%2 == 0) {
+ timestamp_us[0] =
+ stream_info->field_info[0].sof_ts.tv_sec
+ * 1000 * 1000
+ + stream_info->field_info[0].sof_ts.tv_usec;
+ timestamp_us[1] =
+ stream_info->field_info[0].field_ts.tv_sec
+ * 1000 * 1000
+ + stream_info->field_info[0].field_ts.tv_usec;
+ timestamp_us[2] =
+ stream_info->field_info[1].sof_ts.tv_sec
+ * 1000 * 1000
+ + stream_info->field_info[1].sof_ts.tv_usec;
+ timestamp_us[3] =
+ stream_info->field_info[1].field_ts.tv_sec
+ * 1000 * 1000
+ + stream_info->field_info[1].field_ts.tv_usec;
+
+ /*
+ * Expected timing:
+ * field 0 SOF -> field 0 type read ->
+ * field 1 SOF -> field 1 type read
+ */
+ if ((timestamp_us[0] < timestamp_us[1]) &&
+ (timestamp_us[2] < timestamp_us[3]) &&
+ (timestamp_us[1] < timestamp_us[2]) &&
+ (stream_info->field_info[0].even_field !=
+ stream_info->field_info[1].even_field)) {
+ /*
+ * Field type:
+ * 0 - unknown
+ * 1 - odd first
+ * 2 - even first
+ */
+ stream_info->field_type =
+ stream_info->field_info[0].even_field ?
+ 2 : 1;
+ } else {
+ stream_info->field_type = 0;
+ pr_err("Field: %llu %llu %llu %llu %d %d\n",
+ timestamp_us[0], timestamp_us[1],
+ timestamp_us[2], timestamp_us[3],
+ stream_info->field_info[0].even_field,
+ stream_info->field_info[1].even_field);
+ }
+ }
+
+ vfe_dev->wakeupflag = false;
+ }
+
+bs_close:
+ ret = msm_ba_close(vfe_dev->ba_inst_hdl);
+ if (ret)
+ pr_err("%s: msm ba close failed\n", __func__);
+ vfe_dev->ba_inst_hdl = NULL;
+}
+
+static int msm_isp_init_field_type_kthread(struct vfe_device *vfe_dev)
+{
+ init_waitqueue_head(&vfe_dev->field_waitqueue);
+
+ ISP_DBG("%s: Queue initialized\n", __func__);
+ vfe_dev->field_thread_id = kthread_run(
+ (void *)msm_isp_field_type_read_thread,
+ (void *)vfe_dev, "field_type_kthread");
+ if (IS_ERR(vfe_dev->field_thread_id)) {
+ pr_err("%s: Unable to run the thread\n", __func__);
+ return -ENOMEM;
+ }
+
+ return 0;
+}
+
+static void msm_isp_field_timestamp(struct vfe_device *vfe_dev,
+ uint32_t irq_status0, uint32_t irq_status1,
+ struct timeval *timestamp)
+{
+ uint8_t i, j = 0;
+ struct msm_vfe_axi_stream *stream_info = NULL;
+
+ for (i = 0; i < VFE_AXI_SRC_MAX; i++) {
+ if (vfe_dev->axi_data.stream_info[i].interlaced)
+ break;
+ }
+
+ if (i == VFE_AXI_SRC_MAX)
+ return;
+
+ stream_info = &vfe_dev->axi_data.stream_info[i];
+
+ /* SOF timestamp */
+ if (((i == CAMIF_RAW) && (irq_status0 & BIT(0)))
+ || ((i == RDI_INTF_0) && (irq_status1 & BIT(29)))
+ || ((i == RDI_INTF_1) && (irq_status1 & BIT(30)))
+ || ((i == RDI_INTF_2) && (irq_status1 & BIT(31)))) {
+ j = stream_info->field_index;
+ stream_info->field_info[j%2].sof_ts.tv_sec =
+ timestamp->tv_sec;
+ stream_info->field_info[j%2].sof_ts.tv_usec =
+ timestamp->tv_usec;
+ }
+}
+
static void msm_isp_enqueue_tasklet_cmd(struct vfe_device *vfe_dev,
uint32_t irq_status0, uint32_t irq_status1,
uint32_t ping_pong_status)
@@ -1999,6 +2162,10 @@ static void msm_isp_enqueue_tasklet_cmd(struct vfe_device *vfe_dev,
MSM_VFE_TASKLETQ_SIZE;
list_add_tail(&queue_cmd->list, &vfe_dev->tasklet_q);
spin_unlock_irqrestore(&vfe_dev->tasklet_lock, flags);
+
+ msm_isp_field_timestamp(vfe_dev, irq_status0, irq_status1,
+ &queue_cmd->ts.buf_time);
+
tasklet_schedule(&vfe_dev->vfe_tasklet);
}
@@ -2121,6 +2288,7 @@ void msm_isp_do_tasklet(unsigned long data)
spin_unlock_irqrestore(&vfe_dev->tasklet_lock, flags);
ISP_DBG("%s: vfe_id %d status0: 0x%x status1: 0x%x\n",
__func__, vfe_dev->pdev->id, irq_status0, irq_status1);
+
if (vfe_dev->is_split) {
spin_lock(&dump_tasklet_lock);
tasklet_data.arr[tasklet_data.first].
@@ -2139,6 +2307,8 @@ void msm_isp_do_tasklet(unsigned long data)
(tasklet_data.first + 1) % MAX_ISP_PING_PONG_DUMP_SIZE;
spin_unlock(&dump_tasklet_lock);
}
+ irq_ops->process_sof_irq(vfe_dev,
+ irq_status0, irq_status1);
irq_ops->process_reset_irq(vfe_dev,
irq_status0, irq_status1);
irq_ops->process_halt_irq(vfe_dev,
@@ -2291,8 +2461,17 @@ int msm_isp_open_node(struct v4l2_subdev *sd, struct v4l2_subdev_fh *fh)
cam_smmu_reg_client_page_fault_handler(
vfe_dev->buf_mgr->iommu_hdl,
msm_vfe_iommu_fault_handler, vfe_dev);
+
+ /* to detect interlaced frame type through ba driver */
+ rc = msm_isp_init_field_type_kthread(vfe_dev);
+ if (rc) {
+ pr_err("%s: init field thread failed\n", __func__);
+ return rc;
+ }
+
mutex_unlock(&vfe_dev->core_mutex);
mutex_unlock(&vfe_dev->realtime_mutex);
+
return 0;
}
@@ -2361,6 +2540,9 @@ int msm_isp_close_node(struct v4l2_subdev *sd, struct v4l2_subdev_fh *fh)
}
vfe_dev->is_split = 0;
+ vfe_dev->wakeupflag = true;
+ kthread_stop(vfe_dev->field_thread_id);
+
mutex_unlock(&vfe_dev->core_mutex);
mutex_unlock(&vfe_dev->realtime_mutex);
return 0;
diff --git a/drivers/video/msm/ba/msm_ba.c b/drivers/video/msm/ba/msm_ba.c
index 8d1459088b80..0fc251f026b1 100644
--- a/drivers/video/msm/ba/msm_ba.c
+++ b/drivers/video/msm/ba/msm_ba.c
@@ -555,6 +555,24 @@ long msm_ba_private_ioctl(void *instance, int cmd, void *arg)
}
}
break;
+ case VIDIOC_CVBS_G_FIELD_STATUS: {
+ dprintk(BA_DBG, "VIDIOC_CVBS_G_FIELD_STATUS");
+ sd = inst->sd;
+ if (!sd) {
+ dprintk(BA_ERR, "No sd registered");
+ return -EINVAL;
+ }
+ if (s_ioctl) {
+ rc = v4l2_subdev_call(sd, core, ioctl, cmd, s_ioctl);
+ if (rc)
+ dprintk(BA_ERR, "%s failed: %ld on cmd: 0x%x",
+ __func__, rc, cmd);
+ } else {
+ dprintk(BA_ERR, "%s: NULL argument provided", __func__);
+ rc = -EINVAL;
+ }
+ }
+ break;
default:
dprintk(BA_WARN, "Not a typewriter! Command: 0x%x", cmd);
rc = -ENOTTY;
diff --git a/include/media/msm_ba.h b/include/media/msm_ba.h
index d630e441590f..e13509585e5a 100644
--- a/include/media/msm_ba.h
+++ b/include/media/msm_ba.h
@@ -18,6 +18,9 @@
#include <media/v4l2-device.h>
#include <linux/poll.h>
+/* Control ID to fetch register Values */
+#define VIDIOC_CVBS_G_FIELD_STATUS _IOR('V', BASE_VIDIOC_PRIVATE + 5, int)
+
enum msm_ba_ip {
BA_IP_CVBS_0 = 0,
BA_IP_CVBS_1,
diff --git a/include/uapi/media/ais/msm_ais_isp.h b/include/uapi/media/ais/msm_ais_isp.h
index 7c9daafc404d..e093e84ed3f8 100644
--- a/include/uapi/media/ais/msm_ais_isp.h
+++ b/include/uapi/media/ais/msm_ais_isp.h
@@ -23,6 +23,9 @@
#define ISP_STATS_STREAM_BIT 0x80000000
+#define INTERLACE_SUPPORT
+#define INTERLACE_OFFSET (1)
+
struct msm_vfe_cfg_cmd_list;
enum ISP_START_PIXEL_PATTERN {
@@ -733,6 +736,7 @@ struct msm_isp_buf_event {
uint32_t handle;
uint32_t output_format;
int8_t buf_idx;
+ uint8_t field_type;
};
struct msm_isp_fetch_eng_event {
uint32_t session_id;