Merge "msmzirc: platform: add initial support for msmzirc"
diff --git a/platform/msmzirc/acpuclock.c b/platform/msmzirc/acpuclock.c
new file mode 100644
index 0000000..950049b
--- /dev/null
+++ b/platform/msmzirc/acpuclock.c
@@ -0,0 +1,181 @@
+/*
+ * Copyright (c) 2013-2014, 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 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 BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "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 <err.h>
+#include <assert.h>
+#include <debug.h>
+#include <reg.h>
+#include <clock.h>
+#include <mmc.h>
+#include <platform/clock.h>
+#include <platform/iomap.h>
+#include <platform/timer.h>
+
+void clock_config_uart_dm(uint8_t id)
+{
+	int ret;
+	char clk_name[64];
+
+	snprintf(clk_name, sizeof(clk_name), "uart%u_iface_clk", id);
+	ret = clk_get_set_enable(clk_name, 0, 1);
+	if (ret)
+	{
+		dprintf(CRITICAL, "failed to set %s ret = %d\n", clk_name, ret);
+		ASSERT(0);
+	}
+
+	snprintf(clk_name, sizeof(clk_name), "uart%u_core_clk", id);
+	ret = clk_get_set_enable(clk_name, 7372800, 1);
+	if (ret)
+	{
+		dprintf(CRITICAL, "failed to set %s ret = %d\n", clk_name, ret);
+		ASSERT(0);
+	}
+}
+
+/*
+ * Disable power collapse using GDSCR:
+ * Globally Distributed Switch Controller Register
+ */
+void clock_usb30_gdsc_enable(void)
+{
+	uint32_t reg = readl(GCC_USB30_GDSCR);
+
+	reg &= ~(0x1);
+
+	writel(reg, GCC_USB30_GDSCR);
+}
+
+/* enables usb30 clocks */
+void clock_usb30_init(void)
+{
+	int ret;
+
+	ret = clk_get_set_enable("usb30_iface_clk", 0, 1);
+	if(ret)
+	{
+		dprintf(CRITICAL, "failed to set usb30_iface_clk. ret = %d\n", ret);
+		ASSERT(0);
+	}
+
+	clock_usb30_gdsc_enable();
+
+	ret = clk_get_set_enable("usb30_master_clk", 125000000, 1);
+	if(ret)
+	{
+		dprintf(CRITICAL, "failed to set usb30_master_clk. ret = %d\n", ret);
+		ASSERT(0);
+	}
+
+	ret = clk_get_set_enable("usb30_pipe_clk", 19200000, 1);
+	if(ret)
+	{
+		dprintf(CRITICAL, "failed to set usb30_pipe_clk. ret = %d\n", ret);
+		ASSERT(0);
+	}
+
+	ret = clk_get_set_enable("usb30_aux_clk", 1000000, 1);
+	if(ret)
+	{
+		dprintf(CRITICAL, "failed to set usb30_aux_clk. ret = %d\n", ret);
+		ASSERT(0);
+	}
+
+	ret = clk_get_set_enable("usb_phy_cfg_ahb_clk", 0, 1);
+	if(ret)
+	{
+		dprintf(CRITICAL, "failed to set usb_phy_cfg_ahb_clk ret = %d\n", ret);
+		ASSERT(0);
+	}
+}
+
+void clock_init_mmc(uint32_t interface)
+{
+	char clk_name[64];
+	int ret;
+
+	snprintf(clk_name, sizeof(clk_name), "sdc%u_iface_clk", interface);
+
+	/* enable interface clock */
+	ret = clk_get_set_enable(clk_name, 0, 1);
+	if(ret)
+	{
+		dprintf(CRITICAL, "failed to set sdc1_iface_clk ret = %d\n", ret);
+		ASSERT(0);
+	}
+}
+
+/* Configure MMC clock */
+void clock_config_mmc(uint32_t interface, uint32_t freq)
+{
+	int ret;
+	uint32_t reg;
+	char clk_name[64];
+
+	snprintf(clk_name, sizeof(clk_name), "sdc%u_core_clk", interface);
+
+	if(freq == MMC_CLK_400KHZ)
+	{
+		ret = clk_get_set_enable(clk_name, 400000, 1);
+	}
+	else if(freq == MMC_CLK_50MHZ)
+	{
+		ret = clk_get_set_enable(clk_name, 50000000, 1);
+	}
+	else if(freq == MMC_CLK_200MHZ)
+	{
+		ret = clk_get_set_enable(clk_name, 200000000, 1);
+	}
+	else if(freq == MMC_CLK_177MHZ)
+	{
+		ret = clk_get_set_enable(clk_name, 177770000, 1);
+	}
+	else
+	{
+		dprintf(CRITICAL, "sdc frequency (%u) is not supported\n", freq);
+		ASSERT(0);
+	}
+
+	if(ret)
+	{
+		dprintf(CRITICAL, "failed to set %s ret = %d\n", clk_name, ret);
+		ASSERT(0);
+	}
+}
+
+void clock_bumpup_pipe3_clk()
+{
+	int ret = 0;
+
+	ret = clk_get_set_enable("usb30_pipe_clk", 125000000, 0);
+	if(ret)
+	{
+		dprintf(CRITICAL, "failed to set usb30_pipe_clk. ret = %d\n", ret);
+		ASSERT(0);
+	}
+}
diff --git a/platform/msmzirc/gpio.c b/platform/msmzirc/gpio.c
new file mode 100644
index 0000000..98ff2e4
--- /dev/null
+++ b/platform/msmzirc/gpio.c
@@ -0,0 +1,80 @@
+/*
+ * Copyright (c) 2013-2014, 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 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 BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "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 <reg.h>
+#include <debug.h>
+#include <platform/iomap.h>
+#include <platform/gpio.h>
+
+void gpio_tlmm_config(uint32_t gpio,
+					  uint8_t  func,
+					  uint8_t  dir,
+					  uint8_t  pull,
+					  uint8_t  drvstr,
+					  uint32_t enable)
+{
+	uint32_t val = 0;
+
+	val |= pull;
+	val |= func << 2;
+	val |= drvstr << 6;
+	val |= enable << 9;
+
+	writel(val, GPIO_CONFIG_ADDR(gpio));
+
+	return;
+}
+
+void gpio_set(uint32_t gpio, uint32_t dir)
+{
+	writel(dir, GPIO_IN_OUT_ADDR(gpio));
+
+	return;
+}
+
+uint32_t gpio_get_state(uint32_t gpio)
+{
+	return readl(GPIO_IN_OUT_ADDR(gpio));
+}
+
+void gpio_config_uart_dm(uint8_t id)
+{
+	if (id == 2)
+	{
+		/* configure rx gpio. */
+		gpio_tlmm_config(9, 1, GPIO_INPUT, GPIO_NO_PULL, GPIO_8MA, GPIO_DISABLE);
+
+		/* configure tx gpio. */
+		gpio_tlmm_config(8, 1, GPIO_OUTPUT, GPIO_NO_PULL, GPIO_8MA, GPIO_DISABLE);
+	}
+	else
+	{
+		dprintf(CRITICAL, "GPIO config for UART id = %d not supported.\n", id);
+		ASSERT(0);
+	}
+}
diff --git a/platform/msmzirc/include/platform/clock.h b/platform/msmzirc/include/platform/clock.h
new file mode 100644
index 0000000..19efae5
--- /dev/null
+++ b/platform/msmzirc/include/platform/clock.h
@@ -0,0 +1,38 @@
+/*
+ * Copyright (c) 2013-2014, 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 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 BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "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 __PLATFORM_MSMZIRC_CLOCK_H
+#define __PLATFORM_MSMZIRC_CLOCK_H
+
+#define UART_DM_CLK_RX_TX_BIT_RATE 0xCC
+
+void hsusb_clock_init(void);
+void clock_config_uart_dm(uint8_t id);
+void clock_usb30_init(void);
+
+#endif
diff --git a/platform/msmzirc/include/platform/gpio.h b/platform/msmzirc/include/platform/gpio.h
new file mode 100644
index 0000000..792565f
--- /dev/null
+++ b/platform/msmzirc/include/platform/gpio.h
@@ -0,0 +1,69 @@
+/*
+ * Copyright (c) 2013-2014, 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 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 BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "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 __PLATFORM_MSMZIRC_GPIO_H
+#define __PLATFORM_MSMZIRC_GPIO_H
+
+#include <bits.h>
+#include <gpio.h>
+
+/* GPIO TLMM: Direction */
+#define GPIO_INPUT      0
+#define GPIO_OUTPUT     1
+
+/* GPIO TLMM: Pullup/Pulldown */
+#define GPIO_NO_PULL    0
+#define GPIO_PULL_DOWN  1
+#define GPIO_KEEPER     2
+#define GPIO_PULL_UP    3
+
+/* GPIO TLMM: Drive Strength */
+#define GPIO_2MA        0
+#define GPIO_4MA        1
+#define GPIO_6MA        2
+#define GPIO_8MA        3
+#define GPIO_10MA       4
+#define GPIO_12MA       5
+#define GPIO_14MA       6
+#define GPIO_16MA       7
+
+/* GPIO TLMM: Status */
+#define GPIO_ENABLE     0
+#define GPIO_DISABLE    1
+
+void gpio_tlmm_config(uint32_t gpio,
+					  uint8_t  func,
+					  uint8_t  dir,
+					  uint8_t  pull,
+					  uint8_t  drvstr,
+					  uint32_t enable);
+uint32_t gpio_get_state(uint32_t gpio);
+void gpio_set(uint32_t gpio, uint32_t dir);
+void gpio_config_uart_dm(uint8_t id);
+
+#endif
diff --git a/platform/msmzirc/include/platform/iomap.h b/platform/msmzirc/include/platform/iomap.h
new file mode 100644
index 0000000..a35ed30
--- /dev/null
+++ b/platform/msmzirc/include/platform/iomap.h
@@ -0,0 +1,180 @@
+/* Copyright (c) 2014, 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 _PLATFORM_MSMZIRC_IOMAP_H_
+#define _PLATFORM_MSMZIRC_IOMAP_H_
+
+/* NAND */
+#define MSM_NAND_BASE               0x079B0000
+/* NAND BAM */
+#define MSM_NAND_BAM_BASE           0x07984000
+
+#define APPS_SS_BASE                0x0B000000
+
+#define MSM_IOMAP_BASE              0x0078000
+#define MSM_IOMAP_END               0x0BFFFFFF
+
+#define SYSTEM_IMEM_BASE            0x08600000
+#define MSM_SHARED_IMEM_BASE        0x08600000
+
+#define RESTART_REASON_ADDR         (MSM_SHARED_IMEM_BASE + 0x65C)
+#define BS_INFO_OFFSET              (0x6B0)
+#define BS_INFO_ADDR                (MSM_SHARED_IMEM_BASE + BS_INFO_OFFSET)
+#define SDRAM_START_ADDR            0x80000000
+
+#define MSM_SHARED_BASE             0x8E200000
+
+#define MSM_GIC_DIST_BASE           APPS_SS_BASE
+#define MSM_GIC_CPU_BASE            (APPS_SS_BASE + 0x2000)
+#define APPS_APCS_QTMR_AC_BASE      (APPS_SS_BASE + 0x00020000)
+#define APPS_APCS_F0_QTMR_V1_BASE   (APPS_SS_BASE + 0x00021000)
+#define QTMR_BASE                   APPS_APCS_F0_QTMR_V1_BASE
+
+#define PERIPH_SS_BASE              0x07800000
+
+#define MSM_SDC1_BASE               (PERIPH_SS_BASE + 0x00024000)
+#define MSM_SDC1_SDHCI_BASE         (PERIPH_SS_BASE + 0x00024900)
+
+/* SDHCI */
+#define SDCC_MCI_HC_MODE            (0x00000078)
+#define SDCC_HC_PWRCTL_STATUS_REG   (0x000000DC)
+#define SDCC_HC_PWRCTL_MASK_REG     (0x000000E0)
+#define SDCC_HC_PWRCTL_CLEAR_REG    (0x000000E4)
+#define SDCC_HC_PWRCTL_CTL_REG      (0x000000E8)
+#define BLSP1_UART0_BASE            (PERIPH_SS_BASE + 0x000AF000)
+#define BLSP1_UART1_BASE            (PERIPH_SS_BASE + 0x000B0000)
+#define MSM_USB30_BASE              0x08A00000
+#define MSM_USB30_QSCRATCH_BASE     0x08AF8800
+
+#define CLK_CTL_BASE                0x1800000
+
+#define SPMI_BASE                   0x02000000
+#define SPMI_GENI_BASE              (SPMI_BASE + 0xA000)
+#define SPMI_PIC_BASE               (SPMI_BASE +  0x01800000)
+#define PMIC_ARB_CORE               0x200F000
+
+#define TLMM_BASE_ADDR              0x1000000
+#define GPIO_CONFIG_ADDR(x)         (TLMM_BASE_ADDR + (x)*0x1000)
+#define GPIO_IN_OUT_ADDR(x)         (TLMM_BASE_ADDR + 0x00000004 + (x)*0x1000)
+
+#define MPM2_MPM_CTRL_BASE          0x004A0000
+#define MPM2_MPM_PS_HOLD            0x004AB000
+#define MPM2_MPM_SLEEP_TIMETICK_COUNT_VAL  0x004A3000
+
+/* CRYPTO ENGINE */
+#define  GCC_CRYPTO_BCR             (CLK_CTL_BASE + 0x16000)
+#define  GCC_CRYPTO_CMD_RCGR        (CLK_CTL_BASE + 0x16004)
+#define  GCC_0RYPTO_CFG_RCGR        (CLK_CTL_BASE + 0x16008)
+#define  GCC_CRYPTO_CBCR            (CLK_CTL_BASE + 0x1601C)
+#define  GCC_CRYPTO_AXI_CBCR        (CLK_CTL_BASE + 0x16020)
+#define  GCC_CRYPTO_AHB_CBCR        (CLK_CTL_BASE + 0x16024)
+/* GPLL */
+#define GPLL0_STATUS                (CLK_CTL_BASE + 0x21000)
+#define APCS_GPLL_ENA_VOTE          (CLK_CTL_BASE + 0x45000)
+#define APCS_CLOCK_BRANCH_ENA_VOTE  (CLK_CTL_BASE + 0x45004)
+
+/* SDCC */
+#define SDC1_HDRV_PULL_CTL          (TLMM_BASE_ADDR + 0x10A000)
+#define SDCC1_BCR                   (CLK_CTL_BASE + 0x42000)
+#define SDCC1_APPS_CBCR             (CLK_CTL_BASE + 0x42018)
+#define SDCC1_AHB_CBCR              (CLK_CTL_BASE + 0x4201C)
+#define SDCC1_CMD_RCGR              (CLK_CTL_BASE + 0x42004)
+#define SDCC1_CFG_RCGR              (CLK_CTL_BASE + 0x42008)
+#define SDCC1_M                     (CLK_CTL_BASE + 0x4200C)
+#define SDCC1_N                     (CLK_CTL_BASE + 0x42010)
+#define SDCC1_D                     (CLK_CTL_BASE + 0x42014)
+
+/* UART */
+#define BLSP1_AHB_CBCR              (CLK_CTL_BASE + 0x1008)
+#define BLSP1_UART1_APPS_CBCR       (CLK_CTL_BASE + 0x203C)
+#define BLSP1_UART1_APPS_CMD_RCGR   (CLK_CTL_BASE + 0x2044)
+#define BLSP1_UART1_APPS_CFG_RCGR   (CLK_CTL_BASE + 0x2048)
+#define BLSP1_UART1_APPS_M          (CLK_CTL_BASE + 0x204C)
+#define BLSP1_UART1_APPS_N          (CLK_CTL_BASE + 0x2050)
+#define BLSP1_UART1_APPS_D          (CLK_CTL_BASE + 0x2054)
+
+#define BLSP1_UART2_APPS_CBCR       (CLK_CTL_BASE + 0x302C)
+#define BLSP1_UART2_APPS_CMD_RCGR   (CLK_CTL_BASE + 0x3034)
+#define BLSP1_UART2_APPS_CFG_RCGR   (CLK_CTL_BASE + 0x3038)
+#define BLSP1_UART2_APPS_M          (CLK_CTL_BASE + 0x303C)
+#define BLSP1_UART2_APPS_N          (CLK_CTL_BASE + 0x3040)
+#define BLSP1_UART2_APPS_D          (CLK_CTL_BASE + 0x3044)
+
+#define BLSP1_UART3_APPS_CBCR       (CLK_CTL_BASE + 0x403C)
+#define BLSP1_UART3_APPS_CMD_RCGR   (CLK_CTL_BASE + 0x4044)
+#define BLSP1_UART3_APPS_CFG_RCGR   (CLK_CTL_BASE + 0x4848)
+#define BLSP1_UART3_APPS_M          (CLK_CTL_BASE + 0x484C)
+#define BLSP1_UART3_APPS_N          (CLK_CTL_BASE + 0x4050)
+#define BLSP1_UART3_APPS_D          (CLK_CTL_BASE + 0x4054)
+
+
+/* USB */
+#define USB_HS_BCR                  (CLK_CTL_BASE + 0x41000)
+#define USB_HS_SYSTEM_CBCR          (CLK_CTL_BASE + 0x41004)
+#define USB_HS_AHB_CBCR             (CLK_CTL_BASE + 0x41008)
+#define USB_HS_SYSTEM_CMD_RCGR      (CLK_CTL_BASE + 0x41010)
+#define USB_HS_SYSTEM_CFG_RCGR      (CLK_CTL_BASE + 0x41014)
+
+/* USB 3.0 clock */
+#define SYS_NOC_USB3_AXI_CBCR       (CLK_CTL_BASE + 0x5E084)
+#define GCC_USB30_MASTER_CBCR       (CLK_CTL_BASE + 0x5E000)
+#define GCC_USB30_GDSCR             (CLK_CTL_BASE + 0x5E078)
+#define GCC_USB30_MASTER_CMD_RCGR   (CLK_CTL_BASE + 0x5E00C)
+#define GCC_USB30_MASTER_CFG_RCGR   (CLK_CTL_BASE + 0x5E010)
+#define GCC_USB30_MASTER_M          (CLK_CTL_BASE + 0x5E014)
+#define GCC_USB30_MASTER_N          (CLK_CTL_BASE + 0x5E018)
+#define GCC_USB30_MASTER_D          (CLK_CTL_BASE + 0x5E01C)
+
+/* USB 3.0 base */
+#define USB3_PIPE_CMD_RCGR          (CLK_CTL_BASE + 0x5E048)
+#define USB3_PIPE_CFG_RCGR          (CLK_CTL_BASE + 0x5E04C)
+#define USB_PHY_CFG_AHB_CBCR        (CLK_CTL_BASE + 0x5E080)
+#define USB3_PIPE_CBCR              (CLK_CTL_BASE + 0x5E040)
+
+#define USB3_AUX_CMD_RCGR           (CLK_CTL_BASE + 0x5E05C)
+#define USB3_AUX_CFG_RCGR           (CLK_CTL_BASE + 0x5E060)
+#define USB3_AUX_M                  (CLK_CTL_BASE + 0x5E064)
+#define USB3_AUX_N                  (CLK_CTL_BASE + 0x5E068)
+#define USB3_AUX_D                  (CLK_CTL_BASE + 0x5E06C)
+#define USB3_AUX_CBCR               (CLK_CTL_BASE + 0x5E044)
+
+/* USB 3.0 phy */
+#define USB3_PHY_BCR                (CLK_CTL_BASE + 0x0005E034)
+
+/* SS QMP (Qulacomm Multi Protocol) */
+#define QMP_PHY_BASE                0x78000
+
+/* QMP register offset */
+#define PLATFORM_QMP_OFFSET         0x8
+
+/* Boot config */
+#define SEC_CTRL_CORE_BASE          0x00058000
+#define BOOT_CONFIG_OFFSET          0x0000602C
+#define BOOT_CONFIG_REG             (SEC_CTRL_CORE_BASE + BOOT_CONFIG_OFFSET)
+
+#endif
diff --git a/platform/msmzirc/include/platform/irqs.h b/platform/msmzirc/include/platform/irqs.h
new file mode 100644
index 0000000..302badd
--- /dev/null
+++ b/platform/msmzirc/include/platform/irqs.h
@@ -0,0 +1,62 @@
+/* Copyright (c) 2013-2014, 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 BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "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 __IRQS_MSMZIRC_H
+#define __IRQS_MSMZIRC_H
+
+/* TBD: The numbers need to be reviewed */
+
+/* 0-15:  STI/SGI (software triggered/generated interrupts)
+ * 16-31: PPI (private peripheral interrupts)
+ * 32+:   SPI (shared peripheral interrupts)
+ */
+
+#define GIC_PPI_START                          16
+#define GIC_SPI_START                          32
+
+#define INT_QTMR_FRM_0_PHYSICAL_TIMER_EXP      (GIC_SPI_START + 8)
+
+#define USB1_HS_IRQ                            (GIC_SPI_START + 134)
+
+#define USB30_EE1_IRQ                          (GIC_SPI_START + 131)
+
+#define SDCC1_PWRCTL_IRQ                       (GIC_SPI_START + 138)
+
+/* Retrofit universal macro names */
+#define INT_USB_HS                             USB1_HS_IRQ
+
+#define EE0_KRAIT_HLOS_SPMI_PERIPH_IRQ         (GIC_SPI_START + 190)
+
+#define NR_MSM_IRQS                            256
+#define NR_GPIO_IRQS                           173
+#define NR_BOARD_IRQS                          0
+
+#define NR_IRQS                                (NR_MSM_IRQS + NR_GPIO_IRQS + \
+                                               NR_BOARD_IRQS)
+
+#endif /* __IRQS_9635_H */
diff --git a/platform/msmzirc/msmzirc-clock.c b/platform/msmzirc/msmzirc-clock.c
new file mode 100644
index 0000000..721268e
--- /dev/null
+++ b/platform/msmzirc/msmzirc-clock.c
@@ -0,0 +1,428 @@
+/* Copyright (c) 2014, 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.
+ */
+
+#include <assert.h>
+#include <reg.h>
+#include <err.h>
+#include <clock.h>
+#include <clock_pll.h>
+#include <clock_lib2.h>
+#include <platform/clock.h>
+#include <platform/iomap.h>
+
+
+/* Mux source select values */
+#define cxo_source_val    0
+#define gpll0_source_val  1
+#define usb30_pipe_source_val    2
+
+struct clk_freq_tbl rcg_dummy_freq = F_END;
+
+
+/* Clock Operations */
+static struct clk_ops clk_ops_reset =
+{
+	.reset     = clock_lib2_reset_clk_reset,
+};
+
+static struct clk_ops clk_ops_branch =
+{
+	.enable     = clock_lib2_branch_clk_enable,
+	.disable    = clock_lib2_branch_clk_disable,
+	.set_rate   = clock_lib2_branch_set_rate,
+};
+
+static struct clk_ops clk_ops_rcg_mnd =
+{
+	.enable     = clock_lib2_rcg_enable,
+	.set_rate   = clock_lib2_rcg_set_rate,
+};
+
+static struct clk_ops clk_ops_rcg =
+{
+	.enable     = clock_lib2_rcg_enable,
+	.set_rate   = clock_lib2_rcg_set_rate,
+};
+
+static struct clk_ops clk_ops_cxo =
+{
+	.enable     = cxo_clk_enable,
+	.disable    = cxo_clk_disable,
+};
+
+static struct clk_ops clk_ops_pll_vote =
+{
+	.enable     = pll_vote_clk_enable,
+	.disable    = pll_vote_clk_disable,
+	.auto_off   = pll_vote_clk_disable,
+	.is_enabled = pll_vote_clk_is_enabled,
+};
+
+static struct clk_ops clk_ops_vote =
+{
+	.enable     = clock_lib2_vote_clk_enable,
+	.disable    = clock_lib2_vote_clk_disable,
+};
+
+/* Clock Sources */
+static struct fixed_clk cxo_clk_src =
+{
+	.c = {
+		.rate     = 19200000,
+		.dbg_name = "cxo_clk_src",
+		.ops      = &clk_ops_cxo,
+	},
+};
+
+static struct pll_vote_clk gpll0_clk_src =
+{
+	.en_reg       = (void *) APCS_GPLL_ENA_VOTE,
+	.en_mask      = BIT(0),
+	.status_reg   = (void *) GPLL0_STATUS,
+	.status_mask  = BIT(30),
+	.parent       = &cxo_clk_src.c,
+
+	.c = {
+		.rate     = 800000000,
+		.dbg_name = "gpll0_clk_src",
+		.ops      = &clk_ops_pll_vote,
+	},
+};
+
+/* SDCC Clocks */
+static struct clk_freq_tbl ftbl_gcc_sdcc1_2_apps_clk[] =
+{
+	F(   144000,    cxo,  16,   3,  25),
+	F(   400000,    cxo,  12,   1,   4),
+	F( 20000000,  gpll0,  10,   1,   4),
+	F( 25000000,  gpll0,  16,   1,   2),
+	F( 50000000,  gpll0,  16,   0,   0),
+	F(100000000,  gpll0,   8,   0,   0),
+	F(177770000,  gpll0, 4.5,   0,   0),
+	F(200000000,  gpll0,   4,   0,   0),
+	F_END
+};
+
+static struct rcg_clk sdcc1_apps_clk_src =
+{
+	.cmd_reg      = (uint32_t *) SDCC1_CMD_RCGR,
+	.cfg_reg      = (uint32_t *) SDCC1_CFG_RCGR,
+	.m_reg        = (uint32_t *) SDCC1_M,
+	.n_reg        = (uint32_t *) SDCC1_N,
+	.d_reg        = (uint32_t *) SDCC1_D,
+
+	.set_rate     = clock_lib2_rcg_set_rate_mnd,
+	.freq_tbl     = ftbl_gcc_sdcc1_2_apps_clk,
+	.current_freq = &rcg_dummy_freq,
+
+	.c = {
+		.dbg_name = "sdc1_clk",
+		.ops      = &clk_ops_rcg_mnd,
+	},
+};
+
+static struct branch_clk gcc_sdcc1_apps_clk =
+{
+	.cbcr_reg     = (uint32_t *) SDCC1_APPS_CBCR,
+	.parent       = &sdcc1_apps_clk_src.c,
+
+	.c = {
+		.dbg_name = "gcc_sdcc1_apps_clk",
+		.ops      = &clk_ops_branch,
+	},
+};
+
+static struct branch_clk gcc_sdcc1_ahb_clk =
+{
+	.cbcr_reg     = (uint32_t *) SDCC1_AHB_CBCR,
+	.has_sibling  = 1,
+
+	.c = {
+		.dbg_name = "gcc_sdcc1_ahb_clk",
+		.ops      = &clk_ops_branch,
+	},
+};
+
+/* UART Clocks */
+static struct clk_freq_tbl ftbl_gcc_blsp1_2_uart1_6_apps_clk[] =
+{
+	F( 3686400,  gpll0,    1,  72,  15625),
+	F( 7372800,  gpll0,    1, 144,  15625),
+	F(14745600,  gpll0,    1, 288,  15625),
+	F(16000000,  gpll0,   10,   1,      5),
+	F(19200000,    cxo,    1,   0,      0),
+	F(24000000,  gpll0,    1,   3,    100),
+	F(25000000,  gpll0,   16,   1,      2),
+	F(32000000,  gpll0,    1,   1,     25),
+	F(40000000,  gpll0,    1,   1,     20),
+	F(46400000,  gpll0,    1,  29,    500),
+	F(48000000,  gpll0,    1,   3,     50),
+	F(51200000,  gpll0,    1,   8,    125),
+	F(56000000,  gpll0,    1,   7,    100),
+	F(58982400,  gpll0,    1,1152,  15625),
+	F(60000000,  gpll0,    1,   3,     40),
+	F_END
+};
+
+static struct rcg_clk blsp1_uart2_apps_clk_src =
+{
+	.cmd_reg      = (uint32_t *) BLSP1_UART2_APPS_CMD_RCGR,
+	.cfg_reg      = (uint32_t *) BLSP1_UART2_APPS_CFG_RCGR,
+	.m_reg        = (uint32_t *) BLSP1_UART2_APPS_M,
+	.n_reg        = (uint32_t *) BLSP1_UART2_APPS_N,
+	.d_reg        = (uint32_t *) BLSP1_UART2_APPS_D,
+
+	.set_rate     = clock_lib2_rcg_set_rate_mnd,
+	.freq_tbl     = ftbl_gcc_blsp1_2_uart1_6_apps_clk,
+	.current_freq = &rcg_dummy_freq,
+
+	.c = {
+		.dbg_name = "blsp1_uart2_apps_clk",
+		.ops      = &clk_ops_rcg_mnd,
+	},
+};
+
+static struct branch_clk gcc_blsp1_uart2_apps_clk =
+{
+	.cbcr_reg     = (uint32_t *) BLSP1_UART2_APPS_CBCR,
+	.parent       = &blsp1_uart2_apps_clk_src.c,
+
+	.c = {
+		.dbg_name = "gcc_blsp1_uart2_apps_clk",
+		.ops      = &clk_ops_branch,
+	},
+};
+
+static struct vote_clk gcc_blsp1_ahb_clk = {
+	.cbcr_reg     = (uint32_t *) BLSP1_AHB_CBCR,
+	.vote_reg     = (uint32_t *) APCS_CLOCK_BRANCH_ENA_VOTE,
+	.en_mask      = BIT(10),
+
+	.c = {
+		.dbg_name = "gcc_blsp1_ahb_clk",
+		.ops      = &clk_ops_vote,
+	},
+};
+
+/* USB Clocks */
+static struct clk_freq_tbl ftbl_gcc_usb_hs_system_clk[] =
+{
+	F(80000000,  gpll0,   10,   0,   0),
+	F_END
+};
+
+static struct rcg_clk usb_hs_system_clk_src =
+{
+	.cmd_reg      = (uint32_t *) USB_HS_SYSTEM_CMD_RCGR,
+	.cfg_reg      = (uint32_t *) USB_HS_SYSTEM_CFG_RCGR,
+
+	.set_rate     = clock_lib2_rcg_set_rate_hid,
+	.freq_tbl     = ftbl_gcc_usb_hs_system_clk,
+	.current_freq = &rcg_dummy_freq,
+
+	.c = {
+		.dbg_name = "usb_hs_system_clk",
+		.ops      = &clk_ops_rcg,
+	},
+};
+
+static struct branch_clk gcc_usb_hs_system_clk =
+{
+	.cbcr_reg     = (uint32_t *) USB_HS_SYSTEM_CBCR,
+	.parent       = &usb_hs_system_clk_src.c,
+
+	.c = {
+		.dbg_name = "gcc_usb_hs_system_clk",
+		.ops      = &clk_ops_branch,
+	},
+};
+
+static struct branch_clk gcc_usb_hs_ahb_clk =
+{
+	.cbcr_reg     = (uint32_t *) USB_HS_AHB_CBCR,
+	.has_sibling  = 1,
+
+	.c = {
+		.dbg_name = "gcc_usb_hs_ahb_clk",
+		.ops      = &clk_ops_branch,
+	},
+};
+
+static struct branch_clk gcc_sys_noc_usb30_axi_clk =
+{
+	.cbcr_reg     = (uint32_t *) SYS_NOC_USB3_AXI_CBCR,
+	.has_sibling  = 1,
+
+	.c = {
+		.dbg_name = "gcc_sys_noc_usb3_axi_clk",
+		.ops      = &clk_ops_branch,
+	},
+};
+
+static struct branch_clk gcc_usb_phy_cfg_ahb_clk = {
+	.cbcr_reg    = (uint32_t *) USB_PHY_CFG_AHB_CBCR,
+	.has_sibling = 1,
+
+	.c = {
+		.dbg_name = "gcc_usb_phy_cfg_ahb_clk",
+		.ops      = &clk_ops_branch,
+	},
+};
+
+static struct clk_freq_tbl ftbl_gcc_usb30_master_clk[] =
+{
+	F(125000000, gpll0, 1, 5, 24),
+	F_END
+};
+
+static struct rcg_clk usb30_master_clk_src =
+{
+	.cmd_reg      = (uint32_t *) GCC_USB30_MASTER_CMD_RCGR,
+	.cfg_reg      = (uint32_t *) GCC_USB30_MASTER_CFG_RCGR,
+	.m_reg        = (uint32_t *) GCC_USB30_MASTER_M,
+	.n_reg        = (uint32_t *) GCC_USB30_MASTER_N,
+	.d_reg        = (uint32_t *) GCC_USB30_MASTER_D,
+
+	.set_rate     = clock_lib2_rcg_set_rate_mnd,
+	.freq_tbl     = ftbl_gcc_usb30_master_clk,
+	.current_freq = &rcg_dummy_freq,
+
+	.c = {
+		.dbg_name = "usb30_master_clk_src",
+		.ops      = &clk_ops_rcg,
+	},
+};
+
+
+static struct branch_clk gcc_usb30_master_clk =
+{
+	.cbcr_reg     = (uint32_t *) GCC_USB30_MASTER_CBCR,
+	.parent       = &usb30_master_clk_src.c,
+
+	.c = {
+		.dbg_name = "gcc_usb30_master_clk",
+		.ops      = &clk_ops_branch,
+	},
+};
+
+static struct clk_freq_tbl ftbl_gcc_usb30_pipe_clk[] = {
+	F(          19200000,            cxo,    1,    0,     0),
+	F_EXT_SRC(	125000000,    usb30_pipe,    1,    0,     0),
+	F_END
+};
+
+static struct rcg_clk usb30_pipe_clk_src = {
+	.cmd_reg      = (uint32_t *) USB3_PIPE_CMD_RCGR,
+	.cfg_reg      = (uint32_t *) USB3_PIPE_CFG_RCGR,
+	.set_rate     = clock_lib2_rcg_set_rate_hid,
+	.freq_tbl     = ftbl_gcc_usb30_pipe_clk,
+	.current_freq = &rcg_dummy_freq,
+
+	.c = {
+		.dbg_name = "usb30_pipe_clk_src",
+		.ops      = &clk_ops_rcg,
+	},
+};
+
+static struct branch_clk gcc_usb30_pipe_clk = {
+	.cbcr_reg     = (uint32_t *) USB3_PIPE_CBCR,
+	.parent       = &usb30_pipe_clk_src.c,
+	.has_sibling  = 0,
+
+	.c = {
+		.dbg_name = "gcc_usb30_pipe_clk",
+		.ops      = &clk_ops_branch,
+	},
+};
+
+static struct clk_freq_tbl ftbl_gcc_usb30_aux_clk[] = {
+	F(   1000000,         cxo,    1,    5,    96),
+	F_END
+};
+
+static struct rcg_clk usb30_aux_clk_src = {
+	.cmd_reg      = (uint32_t *) USB3_AUX_CMD_RCGR,
+	.cfg_reg      = (uint32_t *) USB3_AUX_CFG_RCGR,
+	.m_reg        = (uint32_t *) USB3_AUX_M,
+	.n_reg        = (uint32_t *) USB3_AUX_N,
+	.d_reg        = (uint32_t *) USB3_AUX_D,
+
+	.set_rate     = clock_lib2_rcg_set_rate_mnd,
+	.freq_tbl     = ftbl_gcc_usb30_aux_clk,
+	.current_freq = &rcg_dummy_freq,
+
+	.c = {
+		.dbg_name = "usb30_aux_clk_src",
+		.ops      = &clk_ops_rcg_mnd,
+	},
+};
+
+static struct branch_clk gcc_usb30_aux_clk = {
+	.cbcr_reg = (uint32_t *) USB3_AUX_CBCR,
+	.parent   = &usb30_aux_clk_src.c,
+
+	.c = {
+		.dbg_name = "gcc_usb30_aux_clk",
+		.ops      = &clk_ops_branch,
+	},
+};
+
+static struct reset_clk gcc_usb30_phy_reset = {
+	.bcr_reg = (uint32_t *) USB3_PHY_BCR,
+
+	.c = {
+		.dbg_name = "usb30_phy_reset",
+		.ops      = &clk_ops_reset,
+	},
+};
+
+static struct clk_lookup msm_clocks_zirc[] =
+{
+	CLK_LOOKUP("sdc1_iface_clk", gcc_sdcc1_ahb_clk.c),
+	CLK_LOOKUP("sdc1_core_clk",  gcc_sdcc1_apps_clk.c),
+
+	CLK_LOOKUP("uart2_iface_clk", gcc_blsp1_ahb_clk.c),
+	CLK_LOOKUP("uart2_core_clk",  gcc_blsp1_uart2_apps_clk.c),
+
+	CLK_LOOKUP("usb_iface_clk",  gcc_usb_hs_ahb_clk.c),
+	CLK_LOOKUP("usb_core_clk",   gcc_usb_hs_system_clk.c),
+
+	CLK_LOOKUP("usb30_iface_clk",  gcc_sys_noc_usb30_axi_clk.c),
+	CLK_LOOKUP("usb30_master_clk", gcc_usb30_master_clk.c),
+	CLK_LOOKUP("usb30_pipe_clk",   gcc_usb30_pipe_clk.c),
+	CLK_LOOKUP("usb30_aux_clk",    gcc_usb30_aux_clk.c),
+
+	CLK_LOOKUP("usb30_phy_reset",     gcc_usb30_phy_reset.c),
+
+	CLK_LOOKUP("usb_phy_cfg_ahb_clk", gcc_usb_phy_cfg_ahb_clk.c),
+};
+
+void platform_clock_init(void)
+{
+	clk_init(msm_clocks_zirc, ARRAY_SIZE(msm_clocks_zirc));
+}
diff --git a/platform/msmzirc/platform.c b/platform/msmzirc/platform.c
new file mode 100644
index 0000000..bed6f22
--- /dev/null
+++ b/platform/msmzirc/platform.c
@@ -0,0 +1,230 @@
+/* Copyright (c) 2013-2014, 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 BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "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 <debug.h>
+#include <platform.h>
+#include <qgic.h>
+#include <qtimer.h>
+#include <board.h>
+#include <mmu.h>
+#include <arch/arm/mmu.h>
+#include <platform/iomap.h>
+#include <smem.h>
+#include <reg.h>
+#include <board.h>
+#include <qpic_nand.h>
+#include <target.h>
+
+extern struct smem_ram_ptable* target_smem_ram_ptable_init();
+
+#define MB                                  (1024*1024)
+
+#define MSM_IOMAP_SIZE                      ((MSM_IOMAP_END - MSM_IOMAP_BASE)/MB)
+
+/* LK memory - Strongly ordered, executable */
+#define LK_MEMORY                             (MMU_MEMORY_TYPE_NORMAL_WRITE_THROUGH | \
+                                              MMU_MEMORY_AP_READ_WRITE)
+/* Scratch memory - Strongly ordered, non-executable */
+#define SCRATCH_MEMORY                        (MMU_MEMORY_TYPE_NORMAL | \
+                                              MMU_MEMORY_AP_READ_WRITE | MMU_MEMORY_XN)
+/* Peripherals - shared device */
+#define IOMAP_MEMORY                          (MMU_MEMORY_TYPE_DEVICE_SHARED | \
+                                              MMU_MEMORY_AP_READ_WRITE | MMU_MEMORY_XN)
+
+#define SCRATCH_REGION1_VIRT_START            SCRATCH_REGION1
+#define SCRATCH_REGION2_VIRT_START            SCRATCH_REGION2
+
+#define SDRAM_BANK0_LAST_FIXED_ADDR           (SCRATCH_REGION2 + SCRATCH_REGION2_SIZE)
+
+/* Map all the accesssible memory according to the following rules:
+ * 1. Map 1MB from MSM_SHARED_BASE with 1 -1 mapping.
+ * 2. Map MEMBASE - MEMSIZE with 1 -1 mapping.
+ * 3. Map all the scratch regions immediately after Appsbl memory.
+ *     Virtual addresses start right after Appsbl Virtual address.
+ * 4. Map all the IOMAP space with 1 - 1 mapping.
+ * 5. Map all the rest of the SDRAM/ IMEM regions as 1 -1.
+ */
+mmu_section_t mmu_section_table[] = {
+/*   Physical addr,         Virtual addr,               Size (in MB),              Flags   */
+	{MSM_SHARED_BASE,       MSM_SHARED_BASE,            1,                         SCRATCH_MEMORY},
+	{MEMBASE,               MEMBASE,                    MEMSIZE / MB,              LK_MEMORY},
+	{MSM_IOMAP_BASE,        MSM_IOMAP_BASE,             MSM_IOMAP_SIZE,            IOMAP_MEMORY},
+	{SCRATCH_REGION1,       SCRATCH_REGION1_VIRT_START, SCRATCH_REGION1_SIZE / MB, SCRATCH_MEMORY},
+	{SCRATCH_REGION2,       SCRATCH_REGION2_VIRT_START, SCRATCH_REGION2_SIZE / MB, SCRATCH_MEMORY},
+};
+
+void platform_early_init(void)
+{
+	/* Initialize board identifier data */
+	board_init();
+
+	/* Initialize clock driver */
+	platform_clock_init();
+
+	/* Initialize interrupt controller */
+	qgic_init();
+
+	/* timer */
+	qtimer_init();
+}
+
+void platform_init(void)
+{
+	dprintf(INFO, "platform_init()\n");
+}
+
+void platform_uninit(void)
+{
+	qtimer_uninit();
+	if (!platform_boot_dev_isemmc())
+		qpic_nand_uninit();
+}
+
+/* Do not use default identitiy mappings. */
+int platform_use_identity_mmu_mappings(void)
+{
+	return 0;
+}
+
+uint32_t platform_get_sclk_count(void)
+{
+	return readl(MPM2_MPM_SLEEP_TIMETICK_COUNT_VAL);
+}
+
+addr_t get_bs_info_addr()
+{
+	return ((addr_t)BS_INFO_ADDR);
+}
+
+/* Setup memory for this platform */
+void platform_init_mmu_mappings(void)
+{
+	uint32_t i;
+	uint32_t sections;
+	ram_partition ptn_entry;
+	uint32_t table_size = ARRAY_SIZE(mmu_section_table);
+	uint32_t len = 0;
+
+	ASSERT(smem_ram_ptable_init_v1());
+
+	len = smem_get_ram_ptable_len();
+
+	/* Configure the MMU page entries for SDRAM and IMEM memory read
+	   from the smem ram table*/
+	for(i = 0; i < len; i++)
+	{
+		smem_get_ram_ptable_entry(&ptn_entry, i);
+		if(ptn_entry.type == SYS_MEMORY)
+		{
+			if((ptn_entry.category == SDRAM) ||
+			   (ptn_entry.category == IMEM))
+			{
+				/* Check to ensure that start address is 1MB aligned */
+				ASSERT((ptn_entry.start & (MB-1)) == 0);
+
+				sections = (ptn_entry.size) / MB;
+				while(sections--)
+				{
+					arm_mmu_map_section(ptn_entry.start +
+										sections * MB,
+										ptn_entry.start +
+										sections * MB,
+										(MMU_MEMORY_TYPE_NORMAL_WRITE_THROUGH |
+										 MMU_MEMORY_AP_READ_WRITE |
+										 MMU_MEMORY_XN));
+				}
+			}
+		}
+	}
+
+	/* Configure the MMU page entries for memory read from the
+	   mmu_section_table */
+	for (i = 0; i < table_size; i++)
+	{
+		sections = mmu_section_table[i].num_of_sections;
+
+		while (sections--)
+		{
+			arm_mmu_map_section(mmu_section_table[i].paddress +
+								sections * MB,
+								mmu_section_table[i].vaddress +
+								sections * MB,
+								mmu_section_table[i].flags);
+		}
+	}
+}
+
+addr_t platform_get_virt_to_phys_mapping(addr_t virt_addr)
+{
+	uint32_t paddr;
+	uint32_t table_size = ARRAY_SIZE(mmu_section_table);
+	uint32_t limit;
+
+	for (uint32_t i = 0; i < table_size; i++)
+	{
+		limit = (mmu_section_table[i].num_of_sections * MB) - 0x1;
+
+		if (virt_addr >= mmu_section_table[i].vaddress &&
+			virt_addr <= (mmu_section_table[i].vaddress + limit))
+		{
+				paddr = mmu_section_table[i].paddress + (virt_addr - mmu_section_table[i].vaddress);
+				return paddr;
+		}
+	}
+	/* No special mapping found.
+	 * Assume 1-1 mapping.
+	 */
+	 paddr = virt_addr;
+	return paddr;
+}
+
+addr_t platform_get_phys_to_virt_mapping(addr_t phys_addr)
+{
+	uint32_t vaddr;
+	uint32_t table_size = ARRAY_SIZE(mmu_section_table);
+	uint32_t limit;
+
+	for (uint32_t i = 0; i < table_size; i++)
+	{
+		limit = (mmu_section_table[i].num_of_sections * MB) - 0x1;
+
+		if (phys_addr >= mmu_section_table[i].paddress &&
+			phys_addr <= (mmu_section_table[i].paddress + limit))
+		{
+				vaddr = mmu_section_table[i].vaddress + (phys_addr - mmu_section_table[i].paddress);
+				return vaddr;
+		}
+	}
+
+	/* No special mapping found.
+	 * Assume 1-1 mapping.
+	 */
+	 vaddr = phys_addr;
+
+	return vaddr;
+}
diff --git a/platform/msmzirc/rules.mk b/platform/msmzirc/rules.mk
new file mode 100644
index 0000000..91fb286
--- /dev/null
+++ b/platform/msmzirc/rules.mk
@@ -0,0 +1,20 @@
+LOCAL_DIR := $(GET_LOCAL_DIR)
+
+ARCH    := arm
+ARM_CPU := cortex-a8
+CPU     := generic
+
+DEFINES += ARM_CPU_CORE_A7
+
+INCLUDES += -I$(LOCAL_DIR)/include -I$(LK_TOP_DIR)/platform/msm_shared/include
+
+OBJS += \
+	$(LOCAL_DIR)/platform.o \
+	$(LOCAL_DIR)/gpio.o \
+	$(LOCAL_DIR)/acpuclock.o \
+	$(LOCAL_DIR)/msmzirc-clock.o
+
+LINKER_SCRIPT += $(BUILDDIR)/system-onesegment.ld
+
+include platform/msm_shared/rules.mk
+