nsekar@codeaurora.org has uploaded this change for review.

View Change

qcs405: Add blsp spi driver and enable SPI-NOR

Add the blsp spi driver required for qcs405 and also
enable the support for WINBOND spi-nor flash

Change-Id: I340eb3bf77b25fe3502d4b29ef4bf7c06b282c02
Signed-off-by: Nitheesh Sekar <nsekar@codeaurora.org>
Signed-off-by: Sricharan R <sricharan@codeaurora.org>
---
M src/mainboard/google/mistral/Kconfig
M src/soc/qualcomm/qcs405/Kconfig
M src/soc/qualcomm/qcs405/Makefile.inc
M src/soc/qualcomm/qcs405/clock.c
M src/soc/qualcomm/qcs405/include/soc/mmu.h
A src/soc/qualcomm/qcs405/include/soc/qup.h
A src/soc/qualcomm/qcs405/include/soc/spi.h
M src/soc/qualcomm/qcs405/spi.c
8 files changed, 1,138 insertions(+), 46 deletions(-)

git pull ssh://review.coreboot.org:29418/coreboot refs/changes/68/29968/1
diff --git a/src/mainboard/google/mistral/Kconfig b/src/mainboard/google/mistral/Kconfig
index f8e8ac7..b614a37 100644
--- a/src/mainboard/google/mistral/Kconfig
+++ b/src/mainboard/google/mistral/Kconfig
@@ -10,6 +10,8 @@
select COMMON_CBFS_SPI_WRAPPER
select SOC_QUALCOMM_QCS405
select SPI_FLASH
+ select SPI_FLASH_GIGADEVICE
+ select SPI_FLASH_WINBOND
select MAINBOARD_HAS_CHROMEOS
select MISSING_BOARD_RESET

diff --git a/src/soc/qualcomm/qcs405/Kconfig b/src/soc/qualcomm/qcs405/Kconfig
index b24dc9e..29960d4 100644
--- a/src/soc/qualcomm/qcs405/Kconfig
+++ b/src/soc/qualcomm/qcs405/Kconfig
@@ -21,9 +21,13 @@
select VBOOT_OPROM_MATTERS
select VBOOT_STARTS_IN_BOOTBLOCK

-config QC_SOC_SIMULATE
- bool
- prompt "Build for Early Simulation Environment"
- default y

+config QCS405_BLSP_SPI
+ bool
+ default y
+ prompt "Build Flash Using SPI-NOR"
+
+config BOOT_DEVICE_SPI_FLASH_BUS
+ int
+ default 5
endif
diff --git a/src/soc/qualcomm/qcs405/Makefile.inc b/src/soc/qualcomm/qcs405/Makefile.inc
index 5e255e2..ee68751 100644
--- a/src/soc/qualcomm/qcs405/Makefile.inc
+++ b/src/soc/qualcomm/qcs405/Makefile.inc
@@ -9,14 +9,14 @@
bootblock-y += gpio.c
bootblock-y += clock.c
bootblock-$(CONFIG_DRIVERS_UART) += uart.c
-bootblock-$(CONFIG_QC_SOC_SIMULATE) += flash_controller.c
+bootblock-y += flash_controller.c

################################################################################
verstage-y += spi.c
verstage-y += timer.c
verstage-y += gpio.c
verstage-$(CONFIG_DRIVERS_UART) += uart.c
-verstage-$(CONFIG_QC_SOC_SIMULATE) += flash_controller.c
+verstage-y += flash_controller.c

################################################################################
romstage-y += spi.c
@@ -26,9 +26,9 @@
romstage-y += clock.c
romstage-y += mmu.c
romstage-$(CONFIG_DRIVERS_UART) += uart.c
-romstage-$(CONFIG_QC_SOC_SIMULATE) += flash_controller.c
romstage-y += usb.c
romstage-y += qclib_execute.c
+romstage-y+= flash_controller.c

################################################################################
ramstage-y += soc.c
@@ -38,8 +38,8 @@
ramstage-y += gpio.c
ramstage-y += clock.c
ramstage-$(CONFIG_DRIVERS_UART) += uart.c
-ramstage-$(CONFIG_QC_SOC_SIMULATE) += flash_controller.c
ramstage-y += usb.c
+ramstage-y += flash_controller.c

################################################################################

diff --git a/src/soc/qualcomm/qcs405/clock.c b/src/soc/qualcomm/qcs405/clock.c
index 6307259..f26face 100644
--- a/src/soc/qualcomm/qcs405/clock.c
+++ b/src/soc/qualcomm/qcs405/clock.c
@@ -203,6 +203,8 @@
clock_configure(blsp2_qup0_spi_clk, spi_cfg, 50000000,
ARRAY_SIZE(spi_cfg));
clock_enable(REG(GCC_BLSP2_QUP0_SPI_APPS_CBCR));
-
+ clock_enable_vote(REG(GCC_BLSP1_AHB_CBCR),
+ REG(GCC_APCS_CLOCK_BRANCH_ENA_VOTE),
+ BLSP2_AHB_CLK_ENA);
}

diff --git a/src/soc/qualcomm/qcs405/include/soc/mmu.h b/src/soc/qualcomm/qcs405/include/soc/mmu.h
index 7bf024f..bb8aa30 100644
--- a/src/soc/qualcomm/qcs405/include/soc/mmu.h
+++ b/src/soc/qualcomm/qcs405/include/soc/mmu.h
@@ -19,8 +19,8 @@
#define DRAMSIZE1GB 0x40000000

void qcs405_mmu_init(void);
-#ifdef CONFIG_QC_SOC_SIMULATE
+//#ifdef CONFIG_QC_SOC_SIMULATE
void qcs405_mmu_dram_config_c(void);
-#endif
+//#endif

#endif // _SOC_QUALCOMM_QCS405_MMU_H_
diff --git a/src/soc/qualcomm/qcs405/include/soc/qup.h b/src/soc/qualcomm/qcs405/include/soc/qup.h
new file mode 100644
index 0000000..211b44e
--- /dev/null
+++ b/src/soc/qualcomm/qcs405/include/soc/qup.h
@@ -0,0 +1,230 @@
+/*
+ * This file is part of the coreboot project.
+ *
+ * Copyright (C) 2018 - 2019 The Linux Foundation. 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 Linux Foundation 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 "AS IS" AND ANY EXPRESS OR IMPLIED
+ * WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF
+ * MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NON-INFRINGEMENT
+ * 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 __QUP_H__
+#define __QUP_H__
+
+
+/* QUP block registers */
+#define QUP_CONFIG 0x000
+#define QUP_STATE 0x004
+#define QUP_IO_MODES 0x008
+#define QUP_SW_RESET 0x00C
+#define QUP_TRANSFER_CANCEL 0x014
+#define QUP_OPERATIONAL 0x018
+#define QUP_ERROR_FLAGS 0x01C
+#define QUP_ERROR_FLAGS_EN 0x020
+#define QUP_TEST_CTRL 0x024
+#define QUP_OPERATIONAL_MASK 0x028
+#define QUP_HW_VERSION 0x030
+#define QUP_MX_OUTPUT_COUNT 0x100
+#define QUP_MX_OUTPUT_CNT_CURRENT 0x104
+#define QUP_OUTPUT_DEBUG 0x108
+#define QUP_OUTPUT_FIFO_WORD_CNT 0x10C
+#define QUP_OUTPUT_FIFO 0x110
+#define QUP_OUTPUT_FIFO_SIZE 64 /* bytes */
+#define QUP_MX_WRITE_COUNT 0x150
+#define QUP_MX_WRITE_CNT_CURRENT 0x154
+#define QUP_MX_INPUT_COUNT 0x200
+#define QUP_MX_INPUT_CNT_CURRENT 0x204
+#define QUP_MX_READ_COUNT 0x208
+#define QUP_MX_READ_CNT_CURRENT 0x20C
+#define QUP_INPUT_DEBUG 0x210
+#define QUP_INPUT_FIFO_WORD_CNT 0x214
+#define QUP_INPUT_FIFO 0x218
+#define QUP_INPUT_FIFO_SIZE 64 /* bytes */
+#define QUP_I2C_MASTER_CLK_CTL 0x400
+#define QUP_I2C_MASTER_STATUS 0x404
+#define QUP_I2C_MASTER_CONFIG 0x408
+#define QUP_I2C_MASTER_BUS_CLEAR 0x40C
+#define QUP_I2C_MASTER_LOCAL_ID 0x410
+#define QUP_I2C_MASTER_COMMAND 0x414
+
+#define OUTPUT_FIFO_FULL (1<<6)
+#define INPUT_FIFO_NOT_EMPTY (1<<5)
+#define OUTPUT_FIFO_NOT_EMPTY (1<<4)
+#define INPUT_SERVICE_FLAG (1<<9)
+#define OUTPUT_SERVICE_FLAG (1<<8)
+#define QUP_UNPACK_EN (1<<14)
+#define QUP_PACK_EN (1<<15)
+#define QUP_OUTPUT_BIT_SHIFT_EN (1<<16)
+
+#define QUP_MODE_MASK (0x03)
+#define QUP_OUTPUT_MODE_SHFT (10)
+#define QUP_INPUT_MODE_SHFT (12)
+
+#define QUP_FS_DIVIDER_MASK (0xFF)
+
+#define QUP_APP_CLK_ON_EN (1 << 12)
+#define QUP_CORE_CLK_ON_EN (1 << 13)
+#define QUP_MINI_CORE_PROTO_SHFT (8)
+#define QUP_MINI_CORE_PROTO_MASK (0x0F)
+
+/* Mini-core states */
+#define QUP_STATE_RESET 0x0
+#define QUP_STATE_RUN 0x1
+#define QUP_STATE_PAUSE 0x3
+#define QUP_STATE_VALID (1<<2)
+#define QUP_STATE_MASK 0x3
+#define QUP_STATE_VALID_MASK (1<<2)
+
+/* Tags for output FIFO */
+#define QUP_I2C_1CLK_NOOP_SEQ 0x1 /*MSB 8-bit NOP, LSB 8-bits 1 clk.*/
+#define QUP_I2C_START_SEQ (0x1 << 8)
+#define QUP_I2C_DATA_SEQ (0x2 << 8)
+#define QUP_I2C_STOP_SEQ (0x3 << 8)
+#define QUP_I2C_RECV_SEQ (0x4 << 8)
+
+/* Tags for input FIFO */
+#define QUP_I2C_MIDATA_SEQ (0x5 << 8)
+#define QUP_I2C_MISTOP_SEQ (0x6 << 8)
+#define QUP_I2C_MINACK_SEQ (0x7 << 8)
+
+#define QUP_I2C_ADDR(x) ((x & 0xFF) << 1)
+#define QUP_I2C_DATA(x) (x & 0xFF)
+#define QUP_I2C_MI_TAG(x) (x & 0xFF00)
+#define QUP_I2C_SLAVE_READ (0x1)
+
+/*Bit vals for I2C_MASTER_CLK_CTL register */
+#define QUP_HS_DIVIDER_SHFT (8)
+#define QUP_DIVIDER_MIN_VAL (0x3)
+
+/* Bit masks for I2C_MASTER_STATUS register */
+#define QUP_I2C_INVALID_READ_SEQ (1 << 25)
+#define QUP_I2C_INVALID_READ_ADDR (1 << 24)
+#define QUP_I2C_INVALID_TAG (1 << 23)
+#define QUP_I2C_FAILED_MASK (0x3 << 6)
+#define QUP_I2C_INVALID_WRITE (1 << 5)
+#define QUP_I2C_ARB_LOST (1 << 4)
+#define QUP_I2C_PACKET_NACK (1 << 3)
+#define QUP_I2C_BUS_ERROR (1 << 2)
+
+typedef enum {
+ QUP_SUCCESS = 0,
+ QUP_ERR_BAD_PARAM,
+ QUP_ERR_STATE_SET,
+ QUP_ERR_TIMEOUT,
+ QUP_ERR_UNSUPPORTED,
+ QUP_ERR_I2C_FAILED,
+ QUP_ERR_I2C_ARB_LOST,
+ QUP_ERR_I2C_BUS_ERROR,
+ QUP_ERR_I2C_INVALID_SLAVE_ADDR,
+ QUP_ERR_XFER_FAIL,
+ QUP_ERR_I2C_NACK,
+ QUP_ERR_I2C_INVALID_WRITE,
+ QUP_ERR_I2C_INVALID_TAG,
+ QUP_ERR_UNDEFINED,
+} qup_return_t;
+
+typedef enum {
+ QUP_MINICORE_SPI = 1,
+ QUP_MINICORE_I2C_MASTER,
+ QUP_MINICORE_I2C_SLAVE
+} qup_protocol_t;
+
+typedef enum {
+ QUP_MODE_FIFO = 0,
+ QUP_MODE_BLOCK,
+ QUP_MODE_DATAMOVER,
+} qup_mode_t;
+
+typedef struct {
+ qup_protocol_t protocol;
+ unsigned clk_frequency;
+ unsigned src_frequency;
+ qup_mode_t mode;
+ unsigned initialized;
+} qup_config_t;
+
+typedef struct {
+ qup_protocol_t protocol;
+ union {
+ struct {
+ uint8_t addr;
+ uint8_t *data;
+ unsigned data_len;
+ } iic;
+ struct {
+ void *in;
+ void *out;
+ unsigned size;
+ } spi;
+ } p;
+} qup_data_t;
+
+/*
+ * Initialize BLSP QUP block for FIFO I2C transfers.
+ * id[IN]: BLSP for which QUP is to be initialized.
+ * config_ptr[IN]: configurations parameters for the QUP.
+ *
+ * return: QUP_SUCCESS, if initialization succeeds.
+ */
+qup_return_t qup_init(blsp_qup_id_t id, const qup_config_t *config_ptr);
+
+/*
+ * Set QUP state to run, pause, reset.
+ * id[IN]: BLSP block for which QUP state is to be set.
+ * state[IN]: New state to transition to.
+ *
+ * return: QUP_SUCCESS, if state transition succeeds.
+ */
+qup_return_t qup_set_state(blsp_qup_id_t id, uint32_t state);
+
+/*
+ * Reset the status bits set during an i2c transfer.
+ * id[IN]: BLSP block for which i2c status bits are to be cleared.
+ *
+ * return: QUP_SUCCESS, if status bits are cleared successfully.
+ */
+qup_return_t qup_reset_i2c_master_status(blsp_qup_id_t id);
+
+/*
+ * Send data to the peripheral on the bus.
+ * id[IN]: BLSP block for which data is to be sent.
+ * p_tx_obj[IN]: Data to be sent to the slave on the bus.
+ * stop_seq[IN]: When set to non-zero QUP engine sends i2c stop sequnce.
+ *
+ * return: QUP_SUCCESS, when data is sent successfully to the peripheral.
+ */
+qup_return_t qup_send_data(blsp_qup_id_t id, qup_data_t *p_tx_obj,
+ uint8_t stop_seq);
+
+/*
+ * Receive data from peripheral on the bus.
+ * id[IN]: BLSP block from which data is to be received.
+ * p_tx_obj[IN]: length of data to be received, slave address.
+ * [OUT]: buffer filled with data from slave.
+ *
+ * return: QUP_SUCCESS, when data is received successfully.
+ */
+qup_return_t qup_recv_data(blsp_qup_id_t id, qup_data_t *p_tx_obj);
+
+#endif //__QUP_H__
diff --git a/src/soc/qualcomm/qcs405/include/soc/spi.h b/src/soc/qualcomm/qcs405/include/soc/spi.h
new file mode 100644
index 0000000..5da709f
--- /dev/null
+++ b/src/soc/qualcomm/qcs405/include/soc/spi.h
@@ -0,0 +1,189 @@
+/*
+ * Register definitions for the IPQ BLSP SPI Controller
+ *
+ * Copyright (c) 2012 The Linux Foundation. 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 Linux Foundation 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 "AS IS" AND ANY EXPRESS OR IMPLIED
+ * WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF
+ * MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NON-INFRINGEMENT
+ * 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 _IPQ40XX_SPI_H_
+#define _IPQ40XX_SPI_H_
+
+#include <soc/iomap.h>
+#include <soc/qup.h>
+#include <spi-generic.h>
+
+#define BLSP0_QUP_REG_BASE ((void *)0x78b5000u)
+#define BLSP5_QUP_REG_BASE ((void *)0x7af5000u)
+
+#define BLSP0_SPI_CONFIG_REG (BLSP0_QUP_REG_BASE + 0x00000300)
+#define BLSP5_SPI_CONFIG_REG (BLSP5_QUP_REG_BASE + 0x00000300)
+
+#define BLSP0_SPI_IO_CONTROL_REG (BLSP0_QUP_REG_BASE + 0x00000304)
+#define BLSP5_SPI_IO_CONTROL_REG (BLSP5_QUP_REG_BASE + 0x00000304)
+
+#define BLSP0_SPI_ERROR_FLAGS_REG (BLSP0_QUP_REG_BASE + 0x00000308)
+#define BLSP5_SPI_ERROR_FLAGS_REG (BLSP5_QUP_REG_BASE + 0x00000308)
+
+#define BLSP0_SPI_DEASSERT_WAIT_REG (BLSP0_QUP_REG_BASE + 0x00000310)
+#define BLSP5_SPI_DEASSERT_WAIT_REG (BLSP5_QUP_REG_BASE + 0x00000310)
+#define BLSP0_SPI_ERROR_FLAGS_EN_REG (BLSP0_QUP_REG_BASE + 0x0000030c)
+#define BLSP5_SPI_ERROR_FLAGS_EN_REG (BLSP5_QUP_REG_BASE + 0x0000030c)
+
+#define BLSP0_QUP_CONFIG_REG (BLSP0_QUP_REG_BASE + 0x00000000)
+#define BLSP5_QUP_CONFIG_REG (BLSP5_QUP_REG_BASE + 0x00000000)
+
+#define BLSP0_QUP_ERROR_FLAGS_REG (BLSP0_QUP_REG_BASE + 0x0000001c)
+#define BLSP5_QUP_ERROR_FLAGS_REG (BLSP5_QUP_REG_BASE + 0x0000001c)
+
+#define BLSP0_QUP_ERROR_FLAGS_EN_REG (BLSP0_QUP_REG_BASE + 0x00000020)
+#define BLSP5_QUP_ERROR_FLAGS_EN_REG (BLSP5_QUP_REG_BASE + 0x00000020)
+
+#define BLSP0_QUP_OPERATIONAL_MASK (BLSP0_QUP_REG_BASE + 0x00000028)
+#define BLSP5_QUP_OPERATIONAL_MASK (BLSP5_QUP_REG_BASE + 0x00000028)
+
+#define BLSP0_QUP_OPERATIONAL_REG (BLSP0_QUP_REG_BASE + 0x00000018)
+#define BLSP5_QUP_OPERATIONAL_REG (BLSP5_QUP_REG_BASE + 0x00000018)
+
+#define BLSP0_QUP_IO_MODES_REG (BLSP0_QUP_REG_BASE + 0x00000008)
+#define BLSP5_QUP_IO_MODES_REG (BLSP5_QUP_REG_BASE + 0x00000008)
+
+#define BLSP0_QUP_STATE_REG (BLSP0_QUP_REG_BASE + 0x00000004)
+#define BLSP5_QUP_STATE_REG (BLSP5_QUP_REG_BASE + 0x00000004)
+
+#define BLSP0_QUP_INPUT_FIFOc_REG(c) \
+ (BLSP0_QUP_REG_BASE + 0x00000218 + 4 * (c))
+#define BLSP5_QUP_INPUT_FIFOc_REG(c) \
+ (BLSP5_QUP_REG_BASE + 0x00000218 + 4 * (c))
+
+#define BLSP0_QUP_OUTPUT_FIFOc_REG(c) \
+ (BLSP0_QUP_REG_BASE + 0x00000110 + 4 * (c))
+#define BLSP5_QUP_OUTPUT_FIFOc_REG(c) \
+ (BLSP5_QUP_REG_BASE + 0x00000110 + 4 * (c))
+
+#define BLSP0_QUP_MX_INPUT_COUNT_REG (BLSP0_QUP_REG_BASE + 0x00000200)
+#define BLSP5_QUP_MX_INPUT_COUNT_REG (BLSP5_QUP_REG_BASE + 0x00000200)
+
+#define BLSP0_QUP_MX_OUTPUT_COUNT_REG (BLSP0_QUP_REG_BASE + 0x00000100)
+#define BLSP5_QUP_MX_OUTPUT_COUNT_REG (BLSP5_QUP_REG_BASE + 0x00000100)
+
+#define BLSP0_QUP_SW_RESET_REG (BLSP0_QUP_REG_BASE + 0x0000000c)
+#define BLSP5_QUP_SW_RESET_REG (BLSP5_QUP_REG_BASE + 0x0000000c)
+
+#define QUP_CONFIG_MINI_CORE_MSK (0x0F << 8)
+#define QUP_CONFIG_MINI_CORE_SPI (1 << 8)
+#define QUP_CONF_INPUT_MSK (1 << 7)
+#define QUP_CONF_INPUT_ENA (0 << 7)
+#define QUP_CONF_NO_INPUT (1 << 7)
+#define QUP_CONF_OUTPUT_MSK (1 << 6)
+#define QUP_CONF_OUTPUT_ENA (0 << 6)
+#define QUP_CONF_NO_OUTPUT (1 << 6)
+#define QUP_CONF_N_MASK 0x1F
+#define QUP_CONF_N_SPI_8_BIT_WORD 0x07
+
+#define SPI_CONFIG_INPUT_FIRST (1 << 9)
+#define SPI_CONFIG_INPUT_FIRST_BACK (0 << 9)
+#define SPI_CONFIG_LOOP_BACK_MSK (1 << 8)
+#define SPI_CONFIG_NO_LOOP_BACK (0 << 8)
+#define SPI_CONFIG_NO_SLAVE_OPER_MSK (1 << 5)
+#define SPI_CONFIG_NO_SLAVE_OPER (0 << 5)
+
+#define SPI_IO_CTRL_CLK_ALWAYS_ON (0 << 9)
+#define SPI_IO_CTRL_MX_CS_MODE (1 << 8)
+#define SPI_IO_CTRL_NO_TRI_STATE (1 << 0)
+#define SPI_IO_CTRL_FORCE_CS_MSK (1 << 11)
+#define SPI_IO_CTRL_FORCE_CS_EN (1 << 11)
+#define SPI_IO_CTRL_FORCE_CS_DIS (0 << 11)
+#define SPI_IO_CTRL_CLOCK_IDLE_HIGH (1 << 10)
+
+#define QUP_IO_MODES_OUTPUT_BIT_SHIFT_MSK (1 << 16)
+#define QUP_IO_MODES_OUTPUT_BIT_SHIFT_EN (1 << 16)
+#define QUP_IO_MODES_INPUT_MODE_MSK (0x03 << 12)
+#define QUP_IO_MODES_INPUT_BLOCK_MODE (0x01 << 12)
+#define QUP_IO_MODES_OUTPUT_MODE_MSK (0x03 << 10)
+#define QUP_IO_MODES_OUTPUT_BLOCK_MODE (0x01 << 10)
+
+#define SPI_INPUT_BLOCK_SIZE 4
+#define SPI_OUTPUT_BLOCK_SIZE 4
+
+#define MAX_COUNT_SIZE 0xffff
+
+#define SPI_CORE_RESET 0
+#define SPI_CORE_RUNNING 1
+#define SPI_MODE0 0
+#define SPI_MODE1 1
+#define SPI_MODE2 2
+#define SPI_MODE3 3
+#define BLSP0_SPI 0
+#define BLSP5_SPI 5
+
+struct blsp_spi {
+ void *spi_config;
+ void *io_control;
+ void *error_flags;
+ void *error_flags_en;
+ void *qup_config;
+ void *qup_error_flags;
+ void *qup_error_flags_en;
+ void *qup_operational;
+ void *qup_io_modes;
+ void *qup_state;
+ void *qup_input_fifo;
+ void *qup_output_fifo;
+ void *qup_mx_input_count;
+ void *qup_mx_output_count;
+ void *qup_sw_reset;
+ void *qup_ns_reg;
+ void *qup_md_reg;
+ void *qup_op_mask;
+ void *qup_deassert_wait;
+};
+
+
+#define SUCCESS 0
+
+#define DUMMY_DATA_VAL 0
+#define TIMEOUT_CNT 100
+
+#define ETIMEDOUT -10
+#define EINVAL -11
+#define EIO -12
+
+/* MX_INPUT_COUNT and MX_OUTPUT_COUNT are 16-bits. Zero has a special meaning
+ * (count function disabled) and does not hold significance in the count. */
+#define MAX_PACKET_COUNT ((64 * KiB) - 1)
+
+
+struct ipq_spi_slave {
+ struct spi_slave slave;
+ const struct blsp_spi *regs;
+ unsigned int mode;
+ unsigned int initialized;
+ unsigned long freq;
+ int allocated;
+};
+
+#endif /* _IPQ40XX_SPI_H_ */
diff --git a/src/soc/qualcomm/qcs405/spi.c b/src/soc/qualcomm/qcs405/spi.c
index 73e538e..7801be8 100644
--- a/src/soc/qualcomm/qcs405/spi.c
+++ b/src/soc/qualcomm/qcs405/spi.c
@@ -1,71 +1,736 @@
/*
- * This file is part of the coreboot project.
+ * Copyright (c) 2012 The Linux Foundation. All rights reserved.
*
- * Copyright (C) 2018, The Linux Foundation. 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 Linux Foundation nor the names of its
+ * contributors may be used to endorse or promote products derived
+ * from this software without specific prior written permission.
*
- * 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
- * only version 2 as published by the Free Software Foundation.
- *
- * This program is distributed in the hope that it will be useful,
- * but WITHOUT ANY WARRANTY; without even the implied warranty of
- * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
- * GNU General Public License for more details.
+ * THIS SOFTWARE IS PROVIDED "AS IS" AND ANY EXPRESS OR IMPLIED
+ * WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF
+ * MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NON-INFRINGEMENT
+ * 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.
*/

-#include <spi-generic.h>
+#include <arch/io.h>
+#include <console/console.h>
+#include <delay.h>
+#include <gpio.h>
+#include <soc/iomap.h>
+#include <soc/spi.h>
+#include <stdlib.h>
+#include <string.h>
#include <spi_flash.h>

-#if IS_ENABLED(CONFIG_QC_SOC_SIMULATE)
-
-extern int spi_simulate_ram_flash_probe(const struct spi_slave *spi,
- struct spi_flash *flash);
-
-static const struct spi_ctrlr spi_ctrlr = {
- .flash_probe = spi_simulate_ram_flash_probe,
-};
-
-const struct spi_ctrlr_buses spi_ctrlr_bus_map[] = {
+static const struct blsp_spi spi_reg[] = {
+ /* BLSP0 registers for SPI interface */
{
- .ctrlr = &spi_ctrlr,
- .bus_start = CONFIG_BOOT_DEVICE_SPI_FLASH_BUS,
- .bus_end = CONFIG_BOOT_DEVICE_SPI_FLASH_BUS,
- }
+ BLSP0_SPI_CONFIG_REG,
+ BLSP0_SPI_IO_CONTROL_REG,
+ BLSP0_SPI_ERROR_FLAGS_REG,
+ BLSP0_SPI_ERROR_FLAGS_EN_REG,
+ BLSP0_QUP_CONFIG_REG,
+ BLSP0_QUP_ERROR_FLAGS_REG,
+ BLSP0_QUP_ERROR_FLAGS_EN_REG,
+ BLSP0_QUP_OPERATIONAL_REG,
+ BLSP0_QUP_IO_MODES_REG,
+ BLSP0_QUP_STATE_REG,
+ BLSP0_QUP_INPUT_FIFOc_REG(0),
+ BLSP0_QUP_OUTPUT_FIFOc_REG(0),
+ BLSP0_QUP_MX_INPUT_COUNT_REG,
+ BLSP0_QUP_MX_OUTPUT_COUNT_REG,
+ BLSP0_QUP_SW_RESET_REG,
+ 0,
+ 0,
+ BLSP0_QUP_OPERATIONAL_MASK,
+ BLSP0_SPI_DEASSERT_WAIT_REG,
+ },
+ {0},{0},{0},{0},
+ /* BLSP5 registers for SPI interface */
+ {
+ BLSP5_SPI_CONFIG_REG,
+ BLSP5_SPI_IO_CONTROL_REG,
+ BLSP5_SPI_ERROR_FLAGS_REG,
+ BLSP5_SPI_ERROR_FLAGS_EN_REG,
+ BLSP5_QUP_CONFIG_REG,
+ BLSP5_QUP_ERROR_FLAGS_REG,
+ BLSP5_QUP_ERROR_FLAGS_EN_REG,
+ BLSP5_QUP_OPERATIONAL_REG,
+ BLSP5_QUP_IO_MODES_REG,
+ BLSP5_QUP_STATE_REG,
+ BLSP5_QUP_INPUT_FIFOc_REG(0),
+ BLSP5_QUP_OUTPUT_FIFOc_REG(0),
+ BLSP5_QUP_MX_INPUT_COUNT_REG,
+ BLSP5_QUP_MX_OUTPUT_COUNT_REG,
+ BLSP5_QUP_SW_RESET_REG,
+ 0,
+ 0,
+ BLSP5_QUP_OPERATIONAL_MASK,
+ BLSP5_SPI_DEASSERT_WAIT_REG,
+ },
+
};

-#else
+static int check_bit_state(void *reg_addr, int mask,
+ int val, int us_delay)
+{
+ unsigned int count = TIMEOUT_CNT;
+
+ while ((read32(reg_addr) & mask) != val) {
+ count--;
+ if (count == 0)
+ return -ETIMEDOUT;
+ udelay(us_delay);
+ }
+
+ return SUCCESS;
+}
+
+/*
+ * Check whether QUPn State is valid
+ */
+static int check_qup_state_valid(struct ipq_spi_slave *ds)
+{
+
+ return check_bit_state(ds->regs->qup_state, QUP_STATE_VALID_MASK,
+ QUP_STATE_VALID, 1);
+
+}
+
+/*
+ * Configure QUPn Core state
+ */
+static int config_spi_state(struct ipq_spi_slave *ds, unsigned int state)
+{
+ uint32_t val;
+ int ret = SUCCESS;
+
+ ret = check_qup_state_valid(ds);
+ if (ret != SUCCESS)
+ return ret;
+
+ switch (state) {
+ case QUP_STATE_RUN:
+ /* Set the state to RUN */
+ val = ((read32(ds->regs->qup_state) & ~QUP_STATE_MASK)
+ | QUP_STATE_RUN);
+ write32(ds->regs->qup_state, val);
+ ret = check_qup_state_valid(ds);
+ break;
+ case QUP_STATE_RESET:
+ /* Set the state to RESET */
+ val = ((read32(ds->regs->qup_state) & ~QUP_STATE_MASK)
+ | QUP_STATE_RESET);
+ write32(ds->regs->qup_state, val);
+ ret = check_qup_state_valid(ds);
+ break;
+ default:
+ printk(BIOS_ERR, "unsupported QUP SPI state : %d\n", state);
+ ret = -EINVAL;
+ break;
+ }
+
+ return ret;
+}
+
+/*
+ * Set QUPn SPI Mode
+ */
+static void spi_set_mode(struct ipq_spi_slave *ds, unsigned int mode)
+{
+ unsigned int clk_idle_state;
+ unsigned int input_first_mode;
+ uint32_t val;
+
+ switch (mode) {
+ case SPI_MODE0:
+ clk_idle_state = 0;
+ input_first_mode = SPI_CONFIG_INPUT_FIRST;
+ break;
+ case SPI_MODE1:
+ clk_idle_state = 0;
+ input_first_mode = 0;
+ break;
+ case SPI_MODE2:
+ clk_idle_state = 1;
+ input_first_mode = SPI_CONFIG_INPUT_FIRST;
+ break;
+ case SPI_MODE3:
+ clk_idle_state = 1;
+ input_first_mode = 0;
+ break;
+ default:
+ printk(BIOS_ERR, "unsupported spi mode : %d\n", mode);
+ return;
+ }
+
+
+ val = read32(ds->regs->spi_config);
+ val |= input_first_mode;
+ write32(ds->regs->spi_config, val);
+
+ val = read32(ds->regs->io_control);
+ if (clk_idle_state)
+ val |= SPI_IO_CTRL_CLOCK_IDLE_HIGH;
+ else
+ val &= ~SPI_IO_CTRL_CLOCK_IDLE_HIGH;
+
+ write32(ds->regs->io_control, val);
+}
+
+/*
+ * Reset entire QUP and all mini cores
+ */
+static void spi_reset(struct ipq_spi_slave *ds)
+{
+ write32(ds->regs->qup_sw_reset, 0x1);
+ udelay(5);
+ check_qup_state_valid(ds);
+}
+
+static struct ipq_spi_slave spi_slave_pool[2];
+
+static struct ipq_spi_slave *to_ipq_spi(const struct spi_slave *slave)
+{
+ struct ipq_spi_slave *ds;
+ size_t i;
+
+ for (i = 0; i < ARRAY_SIZE(spi_slave_pool); i++) {
+ ds = spi_slave_pool + i;
+
+ if (!ds->allocated)
+ continue;
+
+ if ((ds->slave.bus == slave->bus) &&
+ (ds->slave.cs == slave->cs))
+ return ds;
+ }
+
+ return NULL;
+}
+
+/*
+ * BLSP QUPn SPI Hardware Initialisation
+ */
+static int spi_hw_init(struct ipq_spi_slave *ds)
+{
+ int ret;
+
+ ds->initialized = 0;
+
+ /* QUPn module configuration */
+ spi_reset(ds);
+
+ /* Set the QUPn state */
+ ret = config_spi_state(ds, QUP_STATE_RESET);
+ if (ret)
+ return ret;
+
+ /*
+ * Configure Mini core to SPI core with Input Output enabled,
+ * SPI master, N = 8 bits
+ */
+ clrsetbits_le32(ds->regs->qup_config, QUP_CONFIG_MINI_CORE_MSK |
+ QUP_CONF_INPUT_MSK |
+ QUP_CONF_OUTPUT_MSK |
+ QUP_CONF_N_MASK,
+ QUP_CONFIG_MINI_CORE_SPI |
+ QUP_CONF_INPUT_ENA |
+ QUP_CONF_OUTPUT_ENA |
+ QUP_CONF_N_SPI_8_BIT_WORD);
+
+ /*
+ * Configure Input first SPI protocol,
+ * SPI master mode and no loopback
+ */
+ clrsetbits_le32(ds->regs->spi_config, SPI_CONFIG_LOOP_BACK_MSK |
+ SPI_CONFIG_NO_SLAVE_OPER_MSK,
+ SPI_CONFIG_NO_LOOP_BACK |
+ SPI_CONFIG_NO_SLAVE_OPER);
+
+ /*
+ * Configure SPI IO Control Register
+ * CLK_ALWAYS_ON = 0
+ * MX_CS_MODE = 0
+ * NO_TRI_STATE = 1
+ */
+ write32(ds->regs->io_control, SPI_IO_CTRL_CLK_ALWAYS_ON |
+ SPI_IO_CTRL_NO_TRI_STATE | SPI_IO_CTRL_MX_CS_MODE);
+
+ /*
+ * Configure SPI IO Modes.
+ * OUTPUT_BIT_SHIFT_EN = 1
+ * INPUT_MODE = Block Mode
+ * OUTPUT MODE = Block Mode
+ */
+ clrsetbits_le32(ds->regs->qup_io_modes,
+ QUP_IO_MODES_OUTPUT_BIT_SHIFT_MSK |
+ QUP_IO_MODES_INPUT_MODE_MSK |
+ QUP_IO_MODES_OUTPUT_MODE_MSK,
+ QUP_IO_MODES_OUTPUT_BIT_SHIFT_EN |
+ QUP_IO_MODES_INPUT_BLOCK_MODE |
+ QUP_IO_MODES_OUTPUT_BLOCK_MODE);
+
+ spi_set_mode(ds, ds->mode);
+
+ /* Disable Error mask */
+ write32(ds->regs->error_flags_en, 0);
+ write32(ds->regs->qup_error_flags_en, 0);
+
+ write32(ds->regs->qup_deassert_wait, 0);
+
+ ds->initialized = 1;
+
+ return SUCCESS;
+}

static int spi_ctrlr_claim_bus(const struct spi_slave *slave)
{
- return 0;
+ struct ipq_spi_slave *ds = to_ipq_spi(slave);
+ unsigned int ret;
+
+ ret = spi_hw_init(ds);
+ if (ret)
+ return -EIO;
+ switch(slave->bus) {
+ case 5:
+
+ gpio_configure(GPIO(26), 3, GPIO_NO_PULL, GPIO_16MA, GPIO_INPUT);
+ gpio_configure(GPIO(27), 3, GPIO_NO_PULL, GPIO_16MA, GPIO_INPUT);
+ gpio_configure(GPIO(28), 4, GPIO_PULL_UP, GPIO_16MA, GPIO_INPUT);
+ gpio_configure(GPIO(29), 4, GPIO_NO_PULL, GPIO_16MA, GPIO_INPUT);
+
+ break;
+ default:
+ printk(BIOS_ERR, "SPI error: unsupported bus %d (Supported busses 0, 1, 2, 3, 4, 5) ", slave->bus);
+ break;
+ }
+
+
+ return SUCCESS;
}

static void spi_ctrlr_release_bus(const struct spi_slave *slave)
{
+ struct ipq_spi_slave *ds = to_ipq_spi(slave);

+ /* Reset the SPI hardware */
+ spi_reset(ds);
+ ds->initialized = 0;
}

-static int spi_ctrlr_xfer(const struct spi_slave *slave, const void *dout,
- size_t bytes_out, void *din, size_t bytes_in)
+static void write_force_cs(const struct spi_slave *slave, int assert)
{
+ struct ipq_spi_slave *ds = to_ipq_spi(slave);
+#if 0
+ io = read32(ds->regs->io_control);
+
+ io &= ~(3 << 2);
+ write32(ds->regs->io_control, io);
+#else
+ if (assert)
+ clrsetbits_le32(ds->regs->io_control,
+ SPI_IO_CTRL_FORCE_CS_MSK, SPI_IO_CTRL_FORCE_CS_EN);
+ else
+ clrsetbits_le32(ds->regs->io_control,
+ SPI_IO_CTRL_FORCE_CS_MSK, SPI_IO_CTRL_FORCE_CS_DIS);
+#endif
+ return;
+}
+
+/*
+ * Function to write data to OUTPUT FIFO
+ */
+static void spi_write_byte(struct ipq_spi_slave *ds, unsigned char data)
+{
+ /* Wait for space in the FIFO */
+ while ((read32(ds->regs->qup_operational) & OUTPUT_FIFO_FULL))
+ udelay(1);
+
+ /* Write the byte of data */
+ write32(ds->regs->qup_output_fifo, data);
+}
+
+/*
+ * Function to read data from Input FIFO
+ */
+static unsigned char spi_read_byte(struct ipq_spi_slave *ds)
+{
+ /* Wait for Data in FIFO */
+ while (!(read32(ds->regs->qup_operational) & INPUT_FIFO_NOT_EMPTY))
+ udelay(1);
+
+ /* Read a byte of data */
+ return read32(ds->regs->qup_input_fifo) & 0xff;
+}
+
+/*
+ * Function to check wheather Input or Output FIFO
+ * has data to be serviced
+ */
+static int check_fifo_status(void *reg_addr)
+{
+ unsigned int count = TIMEOUT_CNT;
+ unsigned int status_flag;
+ unsigned int val;
+
+ do {
+ val = read32(reg_addr);
+ count--;
+ if (count == 0)
+ return -ETIMEDOUT;
+ status_flag = ((val & OUTPUT_SERVICE_FLAG) |
+ (val & INPUT_SERVICE_FLAG));
+ } while (!status_flag);
+
+ return SUCCESS;
+}
+
+/*
+ * Function to configure Input and Output enable/disable
+ */
+static void enable_io_config(struct ipq_spi_slave *ds,
+ uint32_t write_cnt, uint32_t read_cnt)
+{
+
+ if (write_cnt) {
+ clrsetbits_le32(ds->regs->qup_config,
+ QUP_CONF_OUTPUT_MSK, QUP_CONF_OUTPUT_ENA);
+ } else {
+ clrsetbits_le32(ds->regs->qup_config,
+ QUP_CONF_OUTPUT_MSK, QUP_CONF_NO_OUTPUT);
+ }
+
+ if (read_cnt) {
+ clrsetbits_le32(ds->regs->qup_config,
+ QUP_CONF_INPUT_MSK, QUP_CONF_INPUT_ENA);
+ } else {
+ clrsetbits_le32(ds->regs->qup_config,
+ QUP_CONF_INPUT_MSK, QUP_CONF_NO_INPUT);
+ }
+
+ return;
+}
+
+/*
+ * Function to read bytes number of data from the Input FIFO
+ */
+static int __blsp_spi_read(struct ipq_spi_slave *ds, u8 *data_buffer,
+ unsigned int bytes)
+{
+ uint32_t val;
+ unsigned int i;
+ unsigned int fifo_count;
+ int ret = SUCCESS;
+ int state_config;
+
+ /* Configure no of bytes to read */
+ state_config = config_spi_state(ds, QUP_STATE_RESET);
+ if (state_config)
+ return state_config;
+
+ /* Configure input and output enable */
+ enable_io_config(ds, 0, bytes);
+
+ write32(ds->regs->qup_mx_input_count, bytes);
+
+ state_config = config_spi_state(ds, QUP_STATE_RUN);
+ if (state_config)
+ return state_config;
+
+ while (bytes) {
+ ret = check_fifo_status(ds->regs->qup_operational);
+ if (ret != SUCCESS)
+ goto out;
+
+ val = read32(ds->regs->qup_operational);
+ if (val & INPUT_SERVICE_FLAG) {
+ /*
+ * acknowledge to hw that software will
+ * read input data
+ */
+ val &= INPUT_SERVICE_FLAG;
+ write32(ds->regs->qup_operational, val);
+
+ fifo_count = ((bytes > SPI_INPUT_BLOCK_SIZE) ?
+ SPI_INPUT_BLOCK_SIZE : bytes);
+
+ for (i = 0; i < fifo_count; i++) {
+ *data_buffer = spi_read_byte(ds);
+ data_buffer++;
+ bytes--;
+ }
+ }
+ }
+
+out:
+ /*
+ * Put the SPI Core back in the Reset State
+ * to end the transfer
+ */
+ (void)config_spi_state(ds, QUP_STATE_RESET);
+ return ret;
+}
+
+static int blsp_spi_read(struct ipq_spi_slave *ds, u8 *data_buffer,
+ unsigned int bytes)
+{
+ int length, ret;
+
+ while (bytes) {
+ length = (bytes < MAX_COUNT_SIZE) ? bytes : MAX_COUNT_SIZE;
+
+ ret = __blsp_spi_read(ds, data_buffer, length);
+ if (ret != SUCCESS)
+ return ret;
+
+ data_buffer += length;
+ bytes -= length;
+ }
+
return 0;
}

+/*
+ * Function to write data to the Output FIFO
+ */
+static int __blsp_spi_write(struct ipq_spi_slave *ds, const u8 *cmd_buffer,
+ unsigned int bytes)
+{
+ uint32_t val;
+ unsigned int i;
+ unsigned int write_len = bytes;
+ unsigned int read_len = 3; //bytes; hack for now
+ unsigned int fifo_count;
+ int ret = SUCCESS;
+ int state_config;
+
+ state_config = config_spi_state(ds, QUP_STATE_RESET);
+ if (state_config)
+ return state_config;
+
+ /* No of bytes to be written in Output FIFO */
+ write32(ds->regs->qup_mx_output_count, bytes);
+ write32(ds->regs->qup_mx_input_count, bytes);
+ state_config = config_spi_state(ds, QUP_STATE_RUN);
+ if (state_config)
+ return state_config;
+
+ /* Configure input and output enable */
+ enable_io_config(ds, write_len, read_len);
+
+ /*
+ * read_len considered to ensure that we read the dummy data for the
+ * write we performed. This is needed to ensure with WR-RD transaction
+ * to get the actual data on the subsequent read cycle that happens
+ */
+ while (write_len || read_len) {
+
+ ret = check_fifo_status(ds->regs->qup_operational);
+ if (ret != SUCCESS)
+ goto out;
+
+ val = read32(ds->regs->qup_operational);
+ if (val & OUTPUT_SERVICE_FLAG) {
+ /*
+ * acknowledge to hw that software will write
+ * expected output data
+ */
+ val &= OUTPUT_SERVICE_FLAG;
+ write32(ds->regs->qup_operational, val);
+
+ if (write_len > SPI_OUTPUT_BLOCK_SIZE)
+ fifo_count = SPI_OUTPUT_BLOCK_SIZE;
+ else
+ fifo_count = write_len;
+
+ for (i = 0; i < fifo_count; i++) {
+ /* Write actual data to output FIFO */
+ spi_write_byte(ds, *cmd_buffer);
+ cmd_buffer++;
+ write_len--;
+ }
+ }
+ if (val & INPUT_SERVICE_FLAG) {
+ /*
+ * acknowledge to hw that software
+ * will read input data
+ */
+ val &= INPUT_SERVICE_FLAG;
+ write32(ds->regs->qup_operational, val);
+
+ if (read_len > SPI_INPUT_BLOCK_SIZE)
+ fifo_count = SPI_INPUT_BLOCK_SIZE;
+ else
+ fifo_count = read_len;
+
+ for (i = 0; i < fifo_count; i++) {
+ /* Read dummy data for the data written */
+ (void)spi_read_byte(ds);
+
+ /* Decrement the read count after reading the
+ * dummy data from the device. This is to make
+ * sure we read dummy data before we write the
+ * data to fifo
+ */
+ read_len--;
+ }
+ }
+ }
+
+out:
+ /*
+ * Put the SPI Core back in the Reset State
+ * to end the transfer
+ */
+ (void)config_spi_state(ds, QUP_STATE_RESET);
+
+ return ret;
+}
+
+static int blsp_spi_write(struct ipq_spi_slave *ds, u8 *cmd_buffer,
+ unsigned int bytes)
+{
+ int length, ret;
+
+ while (bytes) {
+ length = (bytes < MAX_COUNT_SIZE) ? bytes : MAX_COUNT_SIZE;
+
+ ret = __blsp_spi_write(ds, cmd_buffer, length);
+ if (ret != SUCCESS)
+ return ret;
+
+ cmd_buffer += length;
+ bytes -= length;
+ }
+
+ return 0;
+}
+
+/*
+ * This function is invoked with either tx_buf or rx_buf.
+ * Calling this function with both null does a chip select change.
+ */
+static int spi_ctrlr_xfer(const struct spi_slave *slave, const void *dout,
+ size_t out_bytes, void *din, size_t in_bytes)
+{
+ struct ipq_spi_slave *ds = to_ipq_spi(slave);
+ u8 *txp = (u8 *)dout;
+ u8 *rxp = (u8 *)din;
+ int ret;
+
+#if 0
+ /* Driver implementation does not support full duplex. */
+ if (dout && din)
+ return -1;
+#endif
+ ret = config_spi_state(ds, QUP_STATE_RESET);
+ if (ret != SUCCESS)
+ return ret;
+
+ write_force_cs(slave, 1);
+
+ if (dout != NULL) {
+ ret = blsp_spi_write(ds, txp, (unsigned int) out_bytes);
+ if (ret != SUCCESS)
+ goto out;
+ }
+
+ if (din != NULL) {
+ ret = blsp_spi_read(ds, rxp, in_bytes);
+ if (ret != SUCCESS)
+ goto out;
+ }
+
+out:
+ write_force_cs(slave, 0);
+
+ /*
+ * Put the SPI Core back in the Reset State
+ * to end the transfer
+ */
+ (void)config_spi_state(ds, QUP_STATE_RESET);
+
+ return ret;
+}
+
+static int spi_ctrlr_setup(const struct spi_slave *slave)
+{
+ struct ipq_spi_slave *ds = NULL;
+ int i;
+ unsigned int bus = slave->bus;
+ unsigned int cs = slave->cs;
+
+ if ((bus < BLSP0_SPI) || (bus > BLSP5_SPI)
+ || ((bus == BLSP0_SPI) && (cs > 2))
+ || ((bus == BLSP5_SPI) && (cs > 0))) {
+ printk(BIOS_ERR,
+ "SPI error: unsupported bus %d (Supported busses 0, 1 and 2) "
+ "or chipselect\n", bus);
+ return -1;
+ }
+
+ for (i = 0; i < ARRAY_SIZE(spi_slave_pool); i++) {
+ if (spi_slave_pool[i].allocated)
+ continue;
+ ds = spi_slave_pool + i;
+
+ ds->slave.bus = bus;
+ ds->slave.cs = cs;
+ ds->regs = &spi_reg[bus];
+
+ /*
+ * TODO(vbendeb):
+ * hardcoded frequency and mode - we might need to find a way
+ * to configure this
+ */
+ ds->freq = 10000000;
+ ds->mode = SPI_MODE0;
+ ds->allocated = 1;
+
+ return 0;
+ }
+
+ printk(BIOS_ERR, "SPI error: all %d pools busy\n", i);
+ return -1;
+}
+
+static int xfer_vectors(const struct spi_slave *slave,
+ struct spi_op vectors[], size_t count)
+ {
+ return spi_flash_vector_helper(slave, vectors, count, spi_ctrlr_xfer);
+ }
+
static const struct spi_ctrlr spi_ctrlr = {
+ .setup = spi_ctrlr_setup,
.claim_bus = spi_ctrlr_claim_bus,
.release_bus = spi_ctrlr_release_bus,
- .xfer = spi_ctrlr_xfer,
- .max_xfer_size = 65535,
+ //.xfer = spi_ctrlr_xfer,
+ .xfer_vector = xfer_vectors,
+ .max_xfer_size = MAX_PACKET_COUNT,
};

const struct spi_ctrlr_buses spi_ctrlr_bus_map[] = {
{
.ctrlr = &spi_ctrlr,
- .bus_start = 0,
- .bus_end = 0,
+ .bus_start = BLSP5_SPI,
+ .bus_end = BLSP5_SPI,
},
};

-#endif
-
const size_t spi_ctrlr_bus_map_count = ARRAY_SIZE(spi_ctrlr_bus_map);

To view, visit change 29968. To unsubscribe, or for help writing mail filters, visit settings.

Gerrit-Project: coreboot
Gerrit-Branch: master
Gerrit-Change-Id: I340eb3bf77b25fe3502d4b29ef4bf7c06b282c02
Gerrit-Change-Number: 29968
Gerrit-PatchSet: 1
Gerrit-Owner: nsekar@codeaurora.org
Gerrit-Reviewer: Martin Roth <martinroth@google.com>
Gerrit-Reviewer: Patrick Georgi <pgeorgi@google.com>
Gerrit-Reviewer: nsekar@codeaurora.org
Gerrit-MessageType: newchange