[Sound-open-firmware] [PATCH] ssp: add ssp support for APL and CNL

Rander Wang rander.wang at intel.com
Thu Feb 8 08:54:47 CET 2018


Now it supports I2S & TDM4 master mode and no MN devide used.
For 19.2M clock, 16bit 48K stream maybe need to pack to 20bit
48K.

Signed-off-by: Rander Wang <rander.wang at intel.com>
---
 configure.ac            |   1 +
 src/drivers/Makefile.am |   9 +-
 src/drivers/apl-ssp.c   | 547 ++++++++++++++++++++++++++++++++++++++++++++++++
 src/include/reef/ssp.h  |  66 +++++-
 4 files changed, 612 insertions(+), 11 deletions(-)
 create mode 100644 src/drivers/apl-ssp.c

diff --git a/configure.ac b/configure.ac
index 05a3bee..1c84020 100644
--- a/configure.ac
+++ b/configure.ac
@@ -212,6 +212,7 @@ AM_CONDITIONAL(BUILD_APOLLOLAKE,  test "$FW_NAME" = "apl")
 AM_CONDITIONAL(BUILD_CANNONLAKE,  test "$FW_NAME" = "cnl")
 AM_CONDITIONAL(BUILD_BOOTLOADER,  test "$FW_NAME" = "cnl")
 AM_CONDITIONAL(BUILD_MODULE,  test "$FW_NAME" = "apl" -o "$FW_NAME" = "cnl")
+AM_CONDITIONAL(BUILD_APL_SSP,  test "$FW_NAME" = "apl" -o "$FW_NAME" = "cnl")
 
 # DSP core support (Optional)
 AC_ARG_WITH([dsp-core],
diff --git a/src/drivers/Makefile.am b/src/drivers/Makefile.am
index 8c507fa..53b52af 100644
--- a/src/drivers/Makefile.am
+++ b/src/drivers/Makefile.am
@@ -1,9 +1,16 @@
 noinst_LIBRARIES = libdrivers.a
 
 libdrivers_a_SOURCES = \
-	ssp.c \
 	dw-dma.c
 
+if BUILD_APL_SSP
+libdrivers_a_SOURCES += \
+	apl-ssp.c
+else
+	libdrivers_a_SOURCES += \
+	ssp.c
+endif
+
 libdrivers_a_CFLAGS = \
 	$(ARCH_CFLAGS) \
 	$(REEF_INCDIR) \
diff --git a/src/drivers/apl-ssp.c b/src/drivers/apl-ssp.c
new file mode 100644
index 0000000..09adee2
--- /dev/null
+++ b/src/drivers/apl-ssp.c
@@ -0,0 +1,547 @@
+/*
+ * Copyright (c) 2016, Intel Corporation
+ * All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions are met:
+ *   * Redistributions of source code must retain the above copyright
+ *     notice, this list of conditions and the following disclaimer.
+ *   * 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.
+ *   * Neither the name of the Intel 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.
+ *
+ * Author: Liam Girdwood <liam.r.girdwood at linux.intel.com>
+ *         Keyon Jie <yang.jie at linux.intel.com>
+ *         Rander Wang <rander.wang at linux.intel.com>
+ */
+
+#include <errno.h>
+#include <stdbool.h>
+#include <reef/stream.h>
+#include <reef/ssp.h>
+#include <reef/alloc.h>
+#include <reef/interrupt.h>
+
+/* tracing */
+#define trace_ssp(__e)	trace_event(TRACE_CLASS_SSP, __e)
+#define trace_ssp_error(__e)	trace_error(TRACE_CLASS_SSP, __e)
+#define tracev_ssp(__e)	tracev_event(TRACE_CLASS_SSP, __e)
+
+/* save SSP context prior to entering D3 */
+static int ssp_context_store(struct dai *dai)
+{
+	struct ssp_pdata *ssp = dai_get_drvdata(dai);
+
+	ssp->sscr0 = ssp_read(dai, SSCR0);
+	ssp->sscr1 = ssp_read(dai, SSCR1);
+
+	/* FIXME: need to store sscr2,3,4,5 */
+	ssp->psp = ssp_read(dai, SSPSP);
+
+	return 0;
+}
+
+/* restore SSP context after leaving D3 */
+static int ssp_context_restore(struct dai *dai)
+{
+	struct ssp_pdata *ssp = dai_get_drvdata(dai);
+
+	ssp_write(dai, SSCR0, ssp->sscr0);
+	ssp_write(dai, SSCR1, ssp->sscr1);
+	/* FIXME: need to restore sscr2,3,4,5 */
+	ssp_write(dai, SSPSP, ssp->psp);
+
+	return 0;
+}
+
+/* Digital Audio interface formatting */
+static inline int ssp_set_config(struct dai *dai,
+	struct sof_ipc_dai_config *config)
+{
+	struct ssp_pdata *ssp = dai_get_drvdata(dai);
+	uint32_t sscr0;
+	uint32_t sscr1;
+	uint32_t sscr2;
+	uint32_t sscr3;
+	uint32_t sspsp;
+	uint32_t sspsp2;
+	uint32_t sstsa;
+	uint32_t ssrsa;
+	uint32_t ssto;
+	uint32_t ssioc;
+	uint32_t mdiv;
+	uint32_t bdiv;
+	uint32_t mdivc;
+	uint32_t mdivr;
+	uint32_t i2s_m;
+	uint32_t i2s_n;
+	uint32_t data_size;
+	uint32_t start_delay;
+	uint32_t frame_len = 0;
+	bool inverted_frame = false;
+	int ret = 0;
+
+	spin_lock(&ssp->lock);
+
+	/* is playback/capture already running */
+	if (ssp->state[DAI_DIR_PLAYBACK] == COMP_STATE_ACTIVE ||
+		ssp->state[DAI_DIR_CAPTURE] == COMP_STATE_ACTIVE) {
+		trace_ssp_error("ec1");
+		ret = -EINVAL;
+		goto out;
+	}
+
+	trace_ssp("cos");
+
+	/* reset SSP settings */
+	/* sscr0 dynamic settings are DSS, EDSS, SCR, FRDC, ECS */
+	/*
+	 * FIXME: MOD, ACS, NCS are not set,
+	 * no support for network mode for now
+	 */
+	sscr0 = SSCR0_PSP | SSCR0_RIM | SSCR0_TIM;
+
+	/* sscr1 dynamic settings are SFRMDIR, SCLKDIR, SCFR */
+	sscr1 = SSCR1_TTE | SSCR1_TTELP | SSCR1_RWOT | SSCR1_TRAIL;
+//	sscr1 |= SSCR1_TIE | SSCR1_RIE;
+
+	/* sscr2 dynamic setting is LJDFD */
+	sscr2 = SSCR2_SDFD | SSCR2_TURM1;
+
+	/* sscr3 dynamic settings are TFT, RFT */
+	sscr3 = 0;
+
+	/* sspsp dynamic settings are SCMODE, SFRMP, DMYSTRT, SFRMWDTH */
+//	sspsp = SSPSP_ETDS; /* make sure SDO line is tri-stated when inactive */
+	sspsp = 0;
+
+	ssp->config = *config;
+	ssp->params = config->ssp[0];
+
+	/* sspsp2 no dynamic setting */
+	sspsp2 = 0x0;
+
+	/* ssioc dynamic setting is SFCR */
+	ssioc = SSIOC_SCOE;
+
+	/* i2s_m M divider setting, default 1 */
+	i2s_m = 0x1;
+
+	/* i2s_n N divider setting, default 1 */
+	i2s_n = 0x1;
+
+	/* ssto no dynamic setting */
+	ssto = 0x0;
+
+	/* sstsa dynamic setting is TTSA, default 2 slots */
+	sstsa = config->tx_slot_mask;
+
+	/* ssrsa dynamic setting is RTSA, default 2 slots */
+	ssrsa = config->rx_slot_mask;
+
+	/* clock masters */
+	sscr1 &= ~SSCR1_SFRMDIR;
+
+	trace_value(config->format);
+	switch (config->format & SOF_DAI_FMT_MASTER_MASK) {
+	case SOF_DAI_FMT_CBM_CFM:
+		sscr0 |= SSCR0_ECS; /* external clock used */
+		sscr1 |= SSCR1_SCLKDIR;
+		/*
+		 * FIXME: does SSRC1.SCFR need to be set
+		 * when codec is master ?
+		 */
+		break;
+	case SOF_DAI_FMT_CBS_CFS:
+		sscr1 |= SSCR1_SCFR;
+		ssioc |= SSIOC_SFCR;
+		break;
+	case SOF_DAI_FMT_CBM_CFS:
+		sscr0 |= SSCR0_ECS; /* external clock used */
+		sscr1 |= SSCR1_SCLKDIR;
+		/*
+		 * FIXME: does SSRC1.SCFR need to be set
+		 * when codec is master ?
+		 */
+		/* FIXME: this mode has not been tested */
+		break;
+	case SOF_DAI_FMT_CBS_CFM:
+		sscr1 |= SSCR1_SCFR;
+		/* FIXME: this mode has not been tested */
+		break;
+	default:
+		trace_ssp_error("ec2");
+		ret = -EINVAL;
+		goto out;
+	}
+
+	/* clock signal polarity */
+	switch (config->format & SOF_DAI_FMT_INV_MASK) {
+	case SOF_DAI_FMT_NB_NF:
+		break;
+	case SOF_DAI_FMT_NB_IF:
+		break;
+	case SOF_DAI_FMT_IB_IF:
+		sspsp |= SSPSP_SCMODE(2);
+		inverted_frame = true; /* handled later with format */
+		break;
+	case SOF_DAI_FMT_IB_NF:
+		sspsp |= SSPSP_SCMODE(2);
+		inverted_frame = true; /* handled later with format */
+		break;
+	default:
+		trace_ssp_error("ec3");
+		ret = -EINVAL;
+		goto out;
+	}
+
+#ifdef CLK_TYPE /* not enabled, keep the code for reference */
+	/* TODO: allow topology to define SSP clock type */
+	config->ssp[0].clk_id = SSP_CLK_EXT;
+
+	/* clock source */
+	switch (config->ssp[0].clk_id) {
+	case SSP_CLK_AUDIO:
+		sscr0 |= SSCR0_ACS;
+		break;
+	case SSP_CLK_NET_PLL:
+		sscr0 |= SSCR0_MOD;
+		break;
+	case SSP_CLK_EXT:
+		sscr0 |= SSCR0_ECS;
+		break;
+	case SSP_CLK_NET:
+		sscr0 |= SSCR0_NCS | SSCR0_MOD;
+		break;
+	default:
+		trace_ssp_error("ec4");
+		ret = -EINVAL;
+		goto out;
+	}
+#else
+	sscr0 |= SSCR0_MOD | SSCR0_ACS;
+#endif
+
+	/* BCLK is generated from MCLK - must be divisable */
+	if (config->mclk % config->bclk) {
+		trace_ssp_error("ec5");
+		ret = -EINVAL;
+		goto out;
+	}
+
+	/* divisor must be within SCR range */
+	mdiv = (config->mclk / config->bclk) - 1;
+	if (mdiv > (SSCR0_SCR_MASK >> 8)) {
+		trace_ssp_error("ec6");
+		ret = -EINVAL;
+		goto out;
+	}
+
+	/* set the SCR divisor */
+	sscr0 |= SSCR0_SCR(mdiv);
+
+	/* calc frame width based on BCLK and rate - must be divisable */
+	if (config->bclk % config->fclk) {
+		trace_ssp_error("ec7");
+		ret = -EINVAL;
+		goto out;
+	}
+
+	/* must be enouch BCLKs for data */
+	bdiv = config->bclk / config->fclk;
+	if (bdiv < config->sample_container_bits *
+			((config->rx_slot_mask + 1) / 2)) {
+		trace_ssp_error("ec8");
+		ret = -EINVAL;
+		goto out;
+	}
+
+	/* sample_container_bits must be <= 38 for SSP */
+	if (config->sample_container_bits > 38) {
+		trace_ssp_error("ec9");
+		ret = -EINVAL;
+		goto out;
+	}
+
+	/* format */
+	switch (config->format & SOF_DAI_FMT_FORMAT_MASK) {
+	case SOF_DAI_FMT_I2S:
+
+		start_delay = config->sample_container_bits >
+			config->sample_valid_bits ? 1 : 0;
+
+		sscr0 |= SSCR0_FRDC(config->num_slots);
+
+		/* set asserted frame length */
+		frame_len = config->sample_container_bits;
+
+		/* handle frame polarity, I2S default is falling/active low */
+		sspsp |= SSPSP_SFRMP(!inverted_frame);
+
+		break;
+
+	case SOF_DAI_FMT_LEFT_J:
+
+		start_delay = 0;
+
+		sscr0 |= SSCR0_FRDC(config->num_slots);
+
+		/* LJDFD enable */
+		sscr2 &= ~SSCR2_LJDFD;
+
+		/* set asserted frame length */
+		frame_len = config->sample_container_bits;
+
+		/* LEFT_J default is rising/active high, opposite of I2S */
+		sspsp |= SSPSP_SFRMP(inverted_frame);
+
+		break;
+	case SOF_DAI_FMT_DSP_A:
+
+		start_delay = config->sample_container_bits >
+			config->sample_valid_bits ? 1 : 0;
+
+		sscr0 |= SSCR0_MOD | SSCR0_FRDC(config->num_slots);
+
+		/* set asserted frame length */
+		frame_len = config->sample_container_bits;
+
+		/* handle frame polarity, DSP_A default is rising/active high */
+		sspsp |= SSPSP_SFRMP(inverted_frame);
+
+		break;
+	case SOF_DAI_FMT_DSP_B:
+
+		start_delay = 0;
+
+		sscr0 |= SSCR0_MOD | SSCR0_FRDC(config->num_slots);
+
+		/* set asserted frame length */
+		frame_len = config->sample_container_bits;
+
+		/* handle frame polarity, DSP_A default is rising/active high */
+		sspsp |= SSPSP_SFRMP(inverted_frame);
+
+		break;
+	default:
+		trace_ssp_error("eca");
+		ret = -EINVAL;
+		goto out;
+	}
+
+	sspsp |= SSPSP_DMYSTRT(start_delay);
+	sspsp |= SSPSP_SFRMWDTH(frame_len);
+
+	data_size = config->sample_valid_bits;
+
+	if (data_size > 16)
+		sscr0 |= (SSCR0_EDSS | SSCR0_DSIZE(data_size - 16));
+	else
+		sscr0 |= SSCR0_DSIZE(data_size);
+
+	mdivc = 0x00100001;
+	/* bypass divider for MCLK */
+	mdivr = 0x00000fff;
+
+	trace_ssp("coe");
+	ssp_write(dai, SSCR0, sscr0);
+	ssp_write(dai, SSCR1, sscr1);
+	ssp_write(dai, SSCR2, sscr2);
+	ssp_write(dai, SSCR3, sscr3);
+	ssp_write(dai, SSPSP, sspsp);
+	ssp_write(dai, SSPSP2, sspsp2);
+	ssp_write(dai, SSIOC, ssioc);
+	ssp_write(dai, SSTO, ssto);
+	ssp_write(dai, SSTSA, sstsa);
+	ssp_write(dai, SSRSA, ssrsa);
+
+	trace_value(sscr0);
+	trace_value(sscr1);
+	trace_value(ssto);
+	trace_value(sspsp);
+	trace_value(sstsa);
+	trace_value(ssrsa);
+	trace_value(sscr2);
+	trace_value(sspsp2);
+	trace_value(sscr3);
+	trace_value(ssioc);
+
+	mn_reg_write(0x0, mdivc);
+	mn_reg_write(0x80, mdivr);
+	mn_reg_write(0x100 + config->id * 0x8 + 0x0, i2s_m);
+	mn_reg_write(0x100 + config->id * 0x8 + 0x4, i2s_n);
+
+	ssp->state[DAI_DIR_PLAYBACK] = COMP_STATE_PREPARE;
+	ssp->state[DAI_DIR_CAPTURE] = COMP_STATE_PREPARE;
+
+out:
+	spin_unlock(&ssp->lock);
+
+	return ret;
+}
+
+/* Digital Audio interface formatting */
+static inline int ssp_set_loopback_mode(struct dai *dai, uint32_t lbm)
+{
+	struct ssp_pdata *ssp = dai_get_drvdata(dai);
+
+	trace_ssp("loo");
+	spin_lock(&ssp->lock);
+
+	ssp_update_bits(dai, SSCR1, SSCR1_LBM, lbm ? SSCR1_LBM : 0);
+
+	spin_unlock(&ssp->lock);
+
+	return 0;
+}
+
+/* start the SSP for either playback or capture */
+static void ssp_start(struct dai *dai, int direction)
+{
+	struct ssp_pdata *ssp = dai_get_drvdata(dai);
+
+	spin_lock(&ssp->lock);
+
+	/* enable port */
+	ssp_update_bits(dai, SSCR0, SSCR0_SSE, SSCR0_SSE);
+	ssp->state[direction] = COMP_STATE_ACTIVE;
+
+	trace_ssp("sta");
+
+	/* enable DMA */
+	if (direction == DAI_DIR_PLAYBACK) {
+		ssp_update_bits(dai, SSCR1, SSCR1_TSRE, SSCR1_TSRE);
+		ssp_update_bits(dai, SSTSA, 0x1 << 8, 0x1 << 8);
+	} else {
+		ssp_update_bits(dai, SSCR1, SSCR1_RSRE, SSCR1_RSRE);
+		ssp_update_bits(dai, SSRSA, 0x1 << 8, 0x1 << 8);
+	}
+
+	spin_unlock(&ssp->lock);
+}
+
+/* stop the SSP for either playback or capture */
+static void ssp_stop(struct dai *dai)
+{
+	struct ssp_pdata *ssp = dai_get_drvdata(dai);
+
+	spin_lock(&ssp->lock);
+
+	/* stop Rx if we are not capturing */
+	if (ssp->state[SOF_IPC_STREAM_CAPTURE] != COMP_STATE_ACTIVE) {
+		ssp_update_bits(dai, SSCR1, SSCR1_RSRE, 0);
+		ssp_update_bits(dai, SSTSA, 0x1 << 8, 0x0 << 8);
+		trace_ssp("Ss0");
+	}
+
+	/* stop Tx if we are not playing */
+	if (ssp->state[SOF_IPC_STREAM_PLAYBACK] != COMP_STATE_ACTIVE) {
+		ssp_update_bits(dai, SSCR1, SSCR1_TSRE, 0);
+		ssp_update_bits(dai, SSRSA, 0x1 << 8, 0x0 << 8);
+		trace_ssp("Ss1");
+	}
+
+	/* disable SSP port if no users */
+	if (ssp->state[SOF_IPC_STREAM_CAPTURE] != COMP_STATE_ACTIVE &&
+		ssp->state[SOF_IPC_STREAM_PLAYBACK] != COMP_STATE_ACTIVE) {
+		ssp_update_bits(dai, SSCR0, SSCR0_SSE, 0);
+		ssp->state[SOF_IPC_STREAM_CAPTURE] = COMP_STATE_PREPARE;
+		ssp->state[SOF_IPC_STREAM_PLAYBACK] = COMP_STATE_PREPARE;
+		trace_ssp("Ss2");
+	}
+
+	spin_unlock(&ssp->lock);
+}
+
+static int ssp_trigger(struct dai *dai, int cmd, int direction)
+{
+	struct ssp_pdata *ssp = dai_get_drvdata(dai);
+
+	trace_ssp("tri");
+
+	switch (cmd) {
+	case COMP_CMD_START:
+		if (ssp->state[direction] == COMP_STATE_PREPARE ||
+			ssp->state[direction] == COMP_STATE_PAUSED)
+			ssp_start(dai, direction);
+		break;
+	case COMP_CMD_RELEASE:
+		if (ssp->state[direction] == COMP_STATE_PAUSED ||
+			ssp->state[direction] == COMP_STATE_PREPARE)
+			ssp_start(dai, direction);
+		break;
+	case COMP_CMD_STOP:
+	case COMP_CMD_PAUSE:
+		ssp->state[direction] = COMP_STATE_PAUSED;
+		ssp_stop(dai);
+		break;
+	case COMP_CMD_RESUME:
+		ssp_context_restore(dai);
+		break;
+	case COMP_CMD_SUSPEND:
+		ssp_context_store(dai);
+		break;
+	default:
+		break;
+	}
+
+	return 0;
+}
+
+/* clear IRQ sources atm */
+static void ssp_irq_handler(void *data)
+{
+	struct dai *dai = data;
+
+	trace_ssp("irq");
+	trace_value(ssp_read(dai, SSSR));
+
+	/* clear IRQ */
+	ssp_write(dai, SSSR, ssp_read(dai, SSSR));
+	platform_interrupt_clear(ssp_irq(dai), 1);
+}
+
+static int ssp_probe(struct dai *dai)
+{
+	struct ssp_pdata *ssp;
+
+	/* allocate private data */
+	ssp = rzalloc(RZONE_SYS, RFLAGS_NONE, sizeof(*ssp));
+	dai_set_drvdata(dai, ssp);
+
+	spinlock_init(&ssp->lock);
+
+	ssp->state[DAI_DIR_PLAYBACK] = COMP_STATE_READY;
+	ssp->state[DAI_DIR_CAPTURE] = COMP_STATE_READY;
+
+	/* register our IRQ handler */
+	interrupt_register(ssp_irq(dai), ssp_irq_handler, dai);
+	platform_interrupt_unmask(ssp_irq(dai), 1);
+	interrupt_enable(ssp_irq(dai));
+
+	return 0;
+}
+
+const struct dai_ops ssp_ops = {
+	.trigger		= ssp_trigger,
+	.set_config		= ssp_set_config,
+	.pm_context_store	= ssp_context_store,
+	.pm_context_restore	= ssp_context_restore,
+	.probe			= ssp_probe,
+	.set_loopback_mode	= ssp_set_loopback_mode,
+};
diff --git a/src/include/reef/ssp.h b/src/include/reef/ssp.h
index c00d14c..e041121 100644
--- a/src/include/reef/ssp.h
+++ b/src/include/reef/ssp.h
@@ -38,6 +38,8 @@
 #include <reef/trace.h>
 #include <reef/wait.h>
 
+#define BIT(x) (1 << (x))
+
 #define SSP_CLK_AUDIO	0
 #define SSP_CLK_NET_PLL	1
 #define SSP_CLK_EXT	2
@@ -55,11 +57,17 @@
 #define SSTSA		0x30
 #define SSRSA		0x34
 #define SSTSS		0x38
+
+#if defined CONFIG_BAYTRAIL ||\
+	defined CONFIG_CHERRYTRAIL ||\
+	defined CONFIG_BROADWELL ||\
+	defined CONFIG_HASWELL
 #define SSCR2		0x40
 #define SFIFOTT		0x6C
 #define SSCR3		0x70
 #define SSCR4		0x74
 #define SSCR5		0x78
+#endif
 
 extern const struct dai_ops ssp_ops;
 
@@ -112,17 +120,28 @@ extern const struct dai_ops ssp_ops;
 #define SSCR1_TTE	(1 << 30)
 #define SSCR1_TTELP	(1 << 31)
 
+#if defined CONFIG_BAYTRAIL ||\
+	defined CONFIG_CHERRYTRAIL ||\
+	defined CONFIG_BROADWELL ||\
+	defined CONFIG_HASWELL
 /* SSCR2 bits */
-#define SSCR2_URUN_FIX0	(1 << 0)
-#define SSCR2_URUN_FIX1	(1 << 1)
-#define SSCR2_SLV_EXT_CLK_RUN_EN	(1 << 2)
-#define SSCR2_CLK_DEL_EN		(1 << 3)
-#define SSCR2_UNDRN_FIX_EN		(1 << 6)
-#define SSCR2_FIFO_EMPTY_FIX_EN		(1 << 7)
-#define SSCR2_ASRC_CNTR_EN		(1 << 8)
-#define SSCR2_ASRC_CNTR_CLR		(1 << 9)
-#define SSCR2_ASRC_FRM_CNRT_EN		(1 << 10)
-#define SSCR2_ASRC_INTR_MASK		(1 << 11)
+#define SSCR2_URUN_FIX0	BIT(0)
+#define SSCR2_URUN_FIX1	BIT(1)
+#define SSCR2_SLV_EXT_CLK_RUN_EN	BIT(2)
+#define SSCR2_CLK_DEL_EN		BIT(3)
+#define SSCR2_UNDRN_FIX_EN		BIT(6)
+#define SSCR2_FIFO_EMPTY_FIX_EN		BIT(7)
+#define SSCR2_ASRC_CNTR_EN		BIT(8)
+#define SSCR2_ASRC_CNTR_CLR		BIT(9)
+#define SSCR2_ASRC_FRM_CNRT_EN		BIT(10)
+#define SSCR2_ASRC_INTR_MASK		BIT(11)
+#elif defined CONFIG_APOLLOLAKE || defined CONFIG_CANNONLAKE
+#define SSCR2_TURM1		BIT(1)
+#define SSCR2_SDFD		BIT(14)
+#define SSCR2_SDPM		BIT(16)
+#define SSCR2_LJDFD		BIT(17)
+#endif
+
 
 /* SSR bits */
 #define SSSR_TNF	(1 << 2)
@@ -143,6 +162,17 @@ extern const struct dai_ops ssp_ops;
 #define SSPSP_DMYSTOP(x)	((x) << 23)
 #define SSPSP_FSRT		(1 << 25)
 
+#if defined CONFIG_APOLLOLAKE || defined CONFIG_CANNONLAKE
+#define SSPSP_EDMYSTOP(x)	((x) << 26)
+#define SSTSS		0x38
+#define SSCR2		0x40
+#define SSPSP2	0x44
+#define SSCR3		0x48
+#define SSIOC		0x4C
+
+#define SSP_REG_MAX	SSIOC
+#endif
+
 /* SSCR3 bits */
 #define SSCR3_FRM_MST_EN	(1 << 0)
 #define SSCR3_I2S_MODE_EN	(1 << 1)
@@ -169,6 +199,22 @@ extern const struct dai_ops ssp_ops;
 #define SFIFOTT_TX(x)		((x) - 1)
 #define SFIFOTT_RX(x)		(((x) - 1) << 16)
 
+#if defined CONFIG_APOLLOLAKE || defined CONFIG_CANNONLAKE
+#define SSTSA_TSEN			BIT(8)
+#define SSRSA_RSEN			BIT(8)
+
+#define SSCR3_TFL_MASK	(0x0000003f)
+#define SSCR3_RFL_MASK	(0x00003f00)
+#define SSCR3_TFT_MASK	(0x003f0000)
+#define SSCR3_TX(x) (((x) - 1) << 16)
+#define SSCR3_RFT_MASK	(0x3f000000)
+#define SSCR3_RX(x) (((x) - 1) << 24)
+
+#define SSIOC_TXDPDEB	BIT(1)
+#define SSIOC_SFCR	BIT(4)
+#define SSIOC_SCOE	BIT(5)
+#endif
+
 /* tracing */
 #define trace_ssp(__e)	trace_event(TRACE_CLASS_SSP, __e)
 #define trace_ssp_error(__e)	trace_error(TRACE_CLASS_SSP, __e)
-- 
2.14.1



More information about the Sound-open-firmware mailing list