mmc: mmci: Add sdio enable mask in variant data
[deliverable/linux.git] / drivers / mmc / host / mmci.c
index 7ad463e9741c0e4359b0c2c10a43f83ea3683995..370cd5ad111ce7fce35f9cfdc3340436d94c48a6 100644 (file)
@@ -43,6 +43,7 @@
 #include <asm/sizes.h>
 
 #include "mmci.h"
+#include "mmci_qcom_dml.h"
 
 #define DRIVER_NAME "mmci-pl18x"
 
@@ -52,34 +53,57 @@ static unsigned int fmax = 515633;
  * struct variant_data - MMCI variant-specific quirks
  * @clkreg: default value for MCICLOCK register
  * @clkreg_enable: enable value for MMCICLOCK register
+ * @clkreg_8bit_bus_enable: enable value for 8 bit bus
+ * @clkreg_neg_edge_enable: enable value for inverted data/cmd output
  * @datalength_bits: number of bits in the MMCIDATALENGTH register
  * @fifosize: number of bytes that can be written when MMCI_TXFIFOEMPTY
  *           is asserted (likewise for RX)
  * @fifohalfsize: number of bytes that can be written when MCI_TXFIFOHALFEMPTY
  *               is asserted (likewise for RX)
+ * @data_cmd_enable: enable value for data commands.
  * @sdio: variant supports SDIO
  * @st_clkdiv: true if using a ST-specific clock divider algorithm
+ * @datactrl_mask_ddrmode: ddr mode mask in datactrl register.
  * @blksz_datactrl16: true if Block size is at b16..b30 position in datactrl register
+ * @blksz_datactrl4: true if Block size is at b4..b16 position in datactrl
+ *                  register
+ * @datactrl_mask_sdio: SDIO enable mask in datactrl register
  * @pwrreg_powerup: power up value for MMCIPOWER register
+ * @f_max: maximum clk frequency supported by the controller.
  * @signal_direction: input/out direction of bus signals can be indicated
  * @pwrreg_clkgate: MMCIPOWER register must be used to gate the clock
  * @busy_detect: true if busy detection on dat0 is supported
  * @pwrreg_nopower: bits in MMCIPOWER don't controls ext. power supply
+ * @explicit_mclk_control: enable explicit mclk control in driver.
+ * @qcom_fifo: enables qcom specific fifo pio read logic.
+ * @qcom_dml: enables qcom specific dma glue for dma transfers.
+ * @reversed_irq_handling: handle data irq before cmd irq.
  */
 struct variant_data {
        unsigned int            clkreg;
        unsigned int            clkreg_enable;
+       unsigned int            clkreg_8bit_bus_enable;
+       unsigned int            clkreg_neg_edge_enable;
        unsigned int            datalength_bits;
        unsigned int            fifosize;
        unsigned int            fifohalfsize;
+       unsigned int            data_cmd_enable;
+       unsigned int            datactrl_mask_ddrmode;
+       unsigned int            datactrl_mask_sdio;
        bool                    sdio;
        bool                    st_clkdiv;
        bool                    blksz_datactrl16;
+       bool                    blksz_datactrl4;
        u32                     pwrreg_powerup;
+       u32                     f_max;
        bool                    signal_direction;
        bool                    pwrreg_clkgate;
        bool                    busy_detect;
        bool                    pwrreg_nopower;
+       bool                    explicit_mclk_control;
+       bool                    qcom_fifo;
+       bool                    qcom_dml;
+       bool                    reversed_irq_handling;
 };
 
 static struct variant_data variant_arm = {
@@ -87,6 +111,8 @@ static struct variant_data variant_arm = {
        .fifohalfsize           = 8 * 4,
        .datalength_bits        = 16,
        .pwrreg_powerup         = MCI_PWR_UP,
+       .f_max                  = 100000000,
+       .reversed_irq_handling  = true,
 };
 
 static struct variant_data variant_arm_extended_fifo = {
@@ -94,6 +120,7 @@ static struct variant_data variant_arm_extended_fifo = {
        .fifohalfsize           = 64 * 4,
        .datalength_bits        = 16,
        .pwrreg_powerup         = MCI_PWR_UP,
+       .f_max                  = 100000000,
 };
 
 static struct variant_data variant_arm_extended_fifo_hwfc = {
@@ -102,15 +129,19 @@ static struct variant_data variant_arm_extended_fifo_hwfc = {
        .clkreg_enable          = MCI_ARM_HWFCEN,
        .datalength_bits        = 16,
        .pwrreg_powerup         = MCI_PWR_UP,
+       .f_max                  = 100000000,
 };
 
 static struct variant_data variant_u300 = {
        .fifosize               = 16 * 4,
        .fifohalfsize           = 8 * 4,
        .clkreg_enable          = MCI_ST_U300_HWFCEN,
+       .clkreg_8bit_bus_enable = MCI_ST_8BIT_BUS,
        .datalength_bits        = 16,
+       .datactrl_mask_sdio     = MCI_ST_DPSM_SDIOEN,
        .sdio                   = true,
        .pwrreg_powerup         = MCI_PWR_ON,
+       .f_max                  = 100000000,
        .signal_direction       = true,
        .pwrreg_clkgate         = true,
        .pwrreg_nopower         = true,
@@ -121,9 +152,11 @@ static struct variant_data variant_nomadik = {
        .fifohalfsize           = 8 * 4,
        .clkreg                 = MCI_CLK_ENABLE,
        .datalength_bits        = 24,
+       .datactrl_mask_sdio     = MCI_ST_DPSM_SDIOEN,
        .sdio                   = true,
        .st_clkdiv              = true,
        .pwrreg_powerup         = MCI_PWR_ON,
+       .f_max                  = 100000000,
        .signal_direction       = true,
        .pwrreg_clkgate         = true,
        .pwrreg_nopower         = true,
@@ -134,10 +167,14 @@ static struct variant_data variant_ux500 = {
        .fifohalfsize           = 8 * 4,
        .clkreg                 = MCI_CLK_ENABLE,
        .clkreg_enable          = MCI_ST_UX500_HWFCEN,
+       .clkreg_8bit_bus_enable = MCI_ST_8BIT_BUS,
+       .clkreg_neg_edge_enable = MCI_ST_UX500_NEG_EDGE,
        .datalength_bits        = 24,
+       .datactrl_mask_sdio     = MCI_ST_DPSM_SDIOEN,
        .sdio                   = true,
        .st_clkdiv              = true,
        .pwrreg_powerup         = MCI_PWR_ON,
+       .f_max                  = 100000000,
        .signal_direction       = true,
        .pwrreg_clkgate         = true,
        .busy_detect            = true,
@@ -149,17 +186,40 @@ static struct variant_data variant_ux500v2 = {
        .fifohalfsize           = 8 * 4,
        .clkreg                 = MCI_CLK_ENABLE,
        .clkreg_enable          = MCI_ST_UX500_HWFCEN,
+       .clkreg_8bit_bus_enable = MCI_ST_8BIT_BUS,
+       .clkreg_neg_edge_enable = MCI_ST_UX500_NEG_EDGE,
+       .datactrl_mask_ddrmode  = MCI_ST_DPSM_DDRMODE,
        .datalength_bits        = 24,
+       .datactrl_mask_sdio     = MCI_ST_DPSM_SDIOEN,
        .sdio                   = true,
        .st_clkdiv              = true,
        .blksz_datactrl16       = true,
        .pwrreg_powerup         = MCI_PWR_ON,
+       .f_max                  = 100000000,
        .signal_direction       = true,
        .pwrreg_clkgate         = true,
        .busy_detect            = true,
        .pwrreg_nopower         = true,
 };
 
+static struct variant_data variant_qcom = {
+       .fifosize               = 16 * 4,
+       .fifohalfsize           = 8 * 4,
+       .clkreg                 = MCI_CLK_ENABLE,
+       .clkreg_enable          = MCI_QCOM_CLK_FLOWENA |
+                                 MCI_QCOM_CLK_SELECT_IN_FBCLK,
+       .clkreg_8bit_bus_enable = MCI_QCOM_CLK_WIDEBUS_8,
+       .datactrl_mask_ddrmode  = MCI_QCOM_CLK_SELECT_IN_DDR_MODE,
+       .data_cmd_enable        = MCI_QCOM_CSPM_DATCMD,
+       .blksz_datactrl4        = true,
+       .datalength_bits        = 24,
+       .pwrreg_powerup         = MCI_PWR_UP,
+       .f_max                  = 208000000,
+       .explicit_mclk_control  = true,
+       .qcom_fifo              = true,
+       .qcom_dml               = true,
+};
+
 static int mmci_card_busy(struct mmc_host *mmc)
 {
        struct mmci_host *host = mmc_priv(mmc);
@@ -260,7 +320,9 @@ static void mmci_set_clkreg(struct mmci_host *host, unsigned int desired)
        host->cclk = 0;
 
        if (desired) {
-               if (desired >= host->mclk) {
+               if (variant->explicit_mclk_control) {
+                       host->cclk = host->mclk;
+               } else if (desired >= host->mclk) {
                        clk = MCI_CLK_BYPASS;
                        if (variant->st_clkdiv)
                                clk |= MCI_ST_UX500_NEG_EDGE;
@@ -299,11 +361,11 @@ static void mmci_set_clkreg(struct mmci_host *host, unsigned int desired)
        if (host->mmc->ios.bus_width == MMC_BUS_WIDTH_4)
                clk |= MCI_4BIT_BUS;
        if (host->mmc->ios.bus_width == MMC_BUS_WIDTH_8)
-               clk |= MCI_ST_8BIT_BUS;
+               clk |= variant->clkreg_8bit_bus_enable;
 
        if (host->mmc->ios.timing == MMC_TIMING_UHS_DDR50 ||
            host->mmc->ios.timing == MMC_TIMING_MMC_DDR52)
-               clk |= MCI_ST_UX500_NEG_EDGE;
+               clk |= variant->clkreg_neg_edge_enable;
 
        mmci_write_clkreg(host, clk);
 }
@@ -369,6 +431,7 @@ static void mmci_dma_setup(struct mmci_host *host)
 {
        const char *rxname, *txname;
        dma_cap_mask_t mask;
+       struct variant_data *variant = host->variant;
 
        host->dma_rx_channel = dma_request_slave_channel(mmc_dev(host->mmc), "rx");
        host->dma_tx_channel = dma_request_slave_channel(mmc_dev(host->mmc), "tx");
@@ -419,6 +482,10 @@ static void mmci_dma_setup(struct mmci_host *host)
                if (max_seg_size < host->mmc->max_seg_size)
                        host->mmc->max_seg_size = max_seg_size;
        }
+
+       if (variant->qcom_dml && host->dma_rx_channel && host->dma_tx_channel)
+               if (dml_hw_init(host, host->mmc->parent->of_node))
+                       variant->qcom_dml = false;
 }
 
 /*
@@ -520,6 +587,7 @@ static int __mmci_dma_prep_data(struct mmci_host *host, struct mmc_data *data,
        struct dma_async_tx_descriptor *desc;
        enum dma_data_direction buffer_dirn;
        int nr_sg;
+       unsigned long flags = DMA_CTRL_ACK;
 
        if (data->flags & MMC_DATA_READ) {
                conf.direction = DMA_DEV_TO_MEM;
@@ -544,9 +612,12 @@ static int __mmci_dma_prep_data(struct mmci_host *host, struct mmc_data *data,
        if (nr_sg == 0)
                return -EINVAL;
 
+       if (host->variant->qcom_dml)
+               flags |= DMA_PREP_INTERRUPT;
+
        dmaengine_slave_config(chan, &conf);
        desc = dmaengine_prep_slave_sg(chan, data->sg, nr_sg,
-                                           conf.direction, DMA_CTRL_ACK);
+                                           conf.direction, flags);
        if (!desc)
                goto unmap_exit;
 
@@ -595,6 +666,9 @@ static int mmci_dma_start_data(struct mmci_host *host, unsigned int datactrl)
        dmaengine_submit(host->dma_desc_current);
        dma_async_issue_pending(host->dma_current);
 
+       if (host->variant->qcom_dml)
+               dml_start_xfer(host, data);
+
        datactrl |= MCI_DPSM_DMAENABLE;
 
        /* Trigger the DMA transfer */
@@ -719,7 +793,7 @@ static void mmci_start_data(struct mmci_host *host, struct mmc_data *data)
        data->bytes_xfered = 0;
 
        clks = (unsigned long long)data->timeout_ns * host->cclk;
-       do_div(clks, 1000000000UL);
+       do_div(clks, NSEC_PER_SEC);
 
        timeout = data->timeout_clks + (unsigned int)clks;
 
@@ -732,22 +806,18 @@ static void mmci_start_data(struct mmci_host *host, struct mmc_data *data)
 
        if (variant->blksz_datactrl16)
                datactrl = MCI_DPSM_ENABLE | (data->blksz << 16);
+       else if (variant->blksz_datactrl4)
+               datactrl = MCI_DPSM_ENABLE | (data->blksz << 4);
        else
                datactrl = MCI_DPSM_ENABLE | blksz_bits << 4;
 
        if (data->flags & MMC_DATA_READ)
                datactrl |= MCI_DPSM_DIRECTION;
 
-       /* The ST Micro variants has a special bit to enable SDIO */
        if (variant->sdio && host->mmc->card)
                if (mmc_card_sdio(host->mmc->card)) {
-                       /*
-                        * The ST Micro variants has a special bit
-                        * to enable SDIO.
-                        */
                        u32 clk;
-
-                       datactrl |= MCI_ST_DPSM_SDIOEN;
+                       datactrl |= variant->datactrl_mask_sdio;
 
                        /*
                         * The ST Micro variant for SDIO small write transfers
@@ -767,7 +837,7 @@ static void mmci_start_data(struct mmci_host *host, struct mmc_data *data)
 
        if (host->mmc->ios.timing == MMC_TIMING_UHS_DDR50 ||
            host->mmc->ios.timing == MMC_TIMING_MMC_DDR52)
-               datactrl |= MCI_ST_DPSM_DDRMODE;
+               datactrl |= variant->datactrl_mask_ddrmode;
 
        /*
         * Attempt to use DMA operation mode, if this
@@ -812,7 +882,7 @@ mmci_start_command(struct mmci_host *host, struct mmc_command *cmd, u32 c)
 
        if (readl(base + MMCICOMMAND) & MCI_CPSM_ENABLE) {
                writel(0, base + MMCICOMMAND);
-               udelay(1);
+               mmci_reg_delay(host);
        }
 
        c |= cmd->opcode | MCI_CPSM_ENABLE;
@@ -824,6 +894,9 @@ mmci_start_command(struct mmci_host *host, struct mmc_command *cmd, u32 c)
        if (/*interrupt*/0)
                c |= MCI_CPSM_INTERRUPT;
 
+       if (mmc_cmd_type(cmd) == MMC_CMD_ADTC)
+               c |= host->variant->data_cmd_enable;
+
        host->cmd = cmd;
 
        writel(cmd->arg, base + MMCIARGUMENT);
@@ -834,6 +907,10 @@ static void
 mmci_data_irq(struct mmci_host *host, struct mmc_data *data,
              unsigned int status)
 {
+       /* Make sure we have data to handle */
+       if (!data)
+               return;
+
        /* First check for errors */
        if (status & (MCI_DATACRCFAIL|MCI_DATATIMEOUT|MCI_STARTBITERR|
                      MCI_TXUNDERRUN|MCI_RXOVERRUN)) {
@@ -902,9 +979,17 @@ mmci_cmd_irq(struct mmci_host *host, struct mmc_command *cmd,
             unsigned int status)
 {
        void __iomem *base = host->base;
-       bool sbc = (cmd == host->mrq->sbc);
-       bool busy_resp = host->variant->busy_detect &&
-                       (cmd->flags & MMC_RSP_BUSY);
+       bool sbc, busy_resp;
+
+       if (!cmd)
+               return;
+
+       sbc = (cmd == host->mrq->sbc);
+       busy_resp = host->variant->busy_detect && (cmd->flags & MMC_RSP_BUSY);
+
+       if (!((status|host->busy_status) & (MCI_CMDCRCFAIL|MCI_CMDTIMEOUT|
+               MCI_CMDSENT|MCI_CMDRESPEND)))
+               return;
 
        /* Check if we need to wait for busy completion. */
        if (host->busy_status && (status & MCI_ST_CARDBUSY))
@@ -957,15 +1042,34 @@ mmci_cmd_irq(struct mmci_host *host, struct mmc_command *cmd,
        }
 }
 
+static int mmci_get_rx_fifocnt(struct mmci_host *host, u32 status, int remain)
+{
+       return remain - (readl(host->base + MMCIFIFOCNT) << 2);
+}
+
+static int mmci_qcom_get_rx_fifocnt(struct mmci_host *host, u32 status, int r)
+{
+       /*
+        * on qcom SDCC4 only 8 words are used in each burst so only 8 addresses
+        * from the fifo range should be used
+        */
+       if (status & MCI_RXFIFOHALFFULL)
+               return host->variant->fifohalfsize;
+       else if (status & MCI_RXDATAAVLBL)
+               return 4;
+
+       return 0;
+}
+
 static int mmci_pio_read(struct mmci_host *host, char *buffer, unsigned int remain)
 {
        void __iomem *base = host->base;
        char *ptr = buffer;
-       u32 status;
+       u32 status = readl(host->base + MMCISTATUS);
        int host_remain = host->size;
 
        do {
-               int count = host_remain - (readl(base + MMCIFIFOCNT) << 2);
+               int count = host->get_rx_fifocnt(host, status, host_remain);
 
                if (count > remain)
                        count = remain;
@@ -1132,9 +1236,6 @@ static irqreturn_t mmci_irq(int irq, void *dev_id)
        spin_lock(&host->lock);
 
        do {
-               struct mmc_command *cmd;
-               struct mmc_data *data;
-
                status = readl(host->base + MMCISTATUS);
 
                if (host->singleirq) {
@@ -1154,16 +1255,13 @@ static irqreturn_t mmci_irq(int irq, void *dev_id)
 
                dev_dbg(mmc_dev(host->mmc), "irq0 (data+cmd) %08x\n", status);
 
-               cmd = host->cmd;
-               if ((status|host->busy_status) & (MCI_CMDCRCFAIL|MCI_CMDTIMEOUT|
-                       MCI_CMDSENT|MCI_CMDRESPEND) && cmd)
-                       mmci_cmd_irq(host, cmd, status);
-
-               data = host->data;
-               if (status & (MCI_DATACRCFAIL|MCI_DATATIMEOUT|MCI_STARTBITERR|
-                             MCI_TXUNDERRUN|MCI_RXOVERRUN|MCI_DATAEND|
-                             MCI_DATABLOCKEND) && data)
-                       mmci_data_irq(host, data, status);
+               if (host->variant->reversed_irq_handling) {
+                       mmci_data_irq(host, host->data, status);
+                       mmci_cmd_irq(host, host->cmd, status);
+               } else {
+                       mmci_cmd_irq(host, host->cmd, status);
+                       mmci_data_irq(host, host->data, status);
+               }
 
                /* Don't poll for busy completion in irq context. */
                if (host->busy_status)
@@ -1296,6 +1394,17 @@ static void mmci_set_ios(struct mmc_host *mmc, struct mmc_ios *ios)
        if (!ios->clock && variant->pwrreg_clkgate)
                pwr &= ~MCI_PWR_ON;
 
+       if (host->variant->explicit_mclk_control &&
+           ios->clock != host->clock_cache) {
+               ret = clk_set_rate(host->clk, ios->clock);
+               if (ret < 0)
+                       dev_err(mmc_dev(host->mmc),
+                               "Error setting clock rate (%d)\n", ret);
+               else
+                       host->mclk = clk_get_rate(host->clk);
+       }
+       host->clock_cache = ios->clock;
+
        spin_lock_irqsave(&host->lock, flags);
 
        mmci_set_clkreg(host, ios->clock);
@@ -1443,6 +1552,11 @@ static int mmci_probe(struct amba_device *dev,
        if (ret)
                goto host_free;
 
+       if (variant->qcom_fifo)
+               host->get_rx_fifocnt = mmci_qcom_get_rx_fifocnt;
+       else
+               host->get_rx_fifocnt = mmci_get_rx_fifocnt;
+
        host->plat = plat;
        host->variant = variant;
        host->mclk = clk_get_rate(host->clk);
@@ -1451,8 +1565,8 @@ static int mmci_probe(struct amba_device *dev,
         * so we try to adjust the clock down to this,
         * (if possible).
         */
-       if (host->mclk > 100000000) {
-               ret = clk_set_rate(host->clk, 100000000);
+       if (host->mclk > variant->f_max) {
+               ret = clk_set_rate(host->clk, variant->f_max);
                if (ret < 0)
                        goto clk_disable;
                host->mclk = clk_get_rate(host->clk);
@@ -1471,9 +1585,12 @@ static int mmci_probe(struct amba_device *dev,
         * The ARM and ST versions of the block have slightly different
         * clock divider equations which means that the minimum divider
         * differs too.
+        * on Qualcomm like controllers get the nearest minimum clock to 100Khz
         */
        if (variant->st_clkdiv)
                mmc->f_min = DIV_ROUND_UP(host->mclk, 257);
+       else if (variant->explicit_mclk_control)
+               mmc->f_min = clk_round_rate(host->clk, 100000);
        else
                mmc->f_min = DIV_ROUND_UP(host->mclk, 512);
        /*
@@ -1483,9 +1600,14 @@ static int mmci_probe(struct amba_device *dev,
         * the block, of course.
         */
        if (mmc->f_max)
-               mmc->f_max = min(host->mclk, mmc->f_max);
+               mmc->f_max = variant->explicit_mclk_control ?
+                               min(variant->f_max, mmc->f_max) :
+                               min(host->mclk, mmc->f_max);
        else
-               mmc->f_max = min(host->mclk, fmax);
+               mmc->f_max = variant->explicit_mclk_control ?
+                               fmax : min(host->mclk, fmax);
+
+
        dev_dbg(mmc_dev(mmc), "clocking block at %u Hz\n", mmc->f_max);
 
        /* Get regulators and the supported OCR mask */
@@ -1552,16 +1674,35 @@ static int mmci_probe(struct amba_device *dev,
        writel(0, host->base + MMCIMASK1);
        writel(0xfff, host->base + MMCICLEAR);
 
-       /* If DT, cd/wp gpios must be supplied through it. */
-       if (!np && gpio_is_valid(plat->gpio_cd)) {
-               ret = mmc_gpio_request_cd(mmc, plat->gpio_cd, 0);
-               if (ret)
-                       goto clk_disable;
-       }
-       if (!np && gpio_is_valid(plat->gpio_wp)) {
-               ret = mmc_gpio_request_ro(mmc, plat->gpio_wp);
-               if (ret)
-                       goto clk_disable;
+       /*
+        * If:
+        * - not using DT but using a descriptor table, or
+        * - using a table of descriptors ALONGSIDE DT, or
+        * look up these descriptors named "cd" and "wp" right here, fail
+        * silently of these do not exist and proceed to try platform data
+        */
+       if (!np) {
+               ret = mmc_gpiod_request_cd(mmc, "cd", 0, false, 0);
+               if (ret < 0) {
+                       if (ret == -EPROBE_DEFER)
+                               goto clk_disable;
+                       else if (gpio_is_valid(plat->gpio_cd)) {
+                               ret = mmc_gpio_request_cd(mmc, plat->gpio_cd, 0);
+                               if (ret)
+                                       goto clk_disable;
+                       }
+               }
+
+               ret = mmc_gpiod_request_ro(mmc, "wp", 0, false, 0);
+               if (ret < 0) {
+                       if (ret == -EPROBE_DEFER)
+                               goto clk_disable;
+                       else if (gpio_is_valid(plat->gpio_wp)) {
+                               ret = mmc_gpio_request_ro(mmc, plat->gpio_wp);
+                               if (ret)
+                                       goto clk_disable;
+                       }
+               }
        }
 
        ret = devm_request_irq(&dev->dev, dev->irq[0], mmci_irq, IRQF_SHARED,
@@ -1752,6 +1893,12 @@ static struct amba_id mmci_ids[] = {
                .mask   = 0xf0ffffff,
                .data   = &variant_ux500v2,
        },
+       /* Qualcomm variants */
+       {
+               .id     = 0x00051180,
+               .mask   = 0x000fffff,
+               .data   = &variant_qcom,
+       },
        { 0, 0 },
 };
 
This page took 0.032638 seconds and 5 git commands to generate.