Merge "mdm9x15: Add support to identify the presence of DSP3 image"
diff --git a/app/tests/led_tests.c b/app/tests/led_tests.c
index 97c6039..36172b0 100644
--- a/app/tests/led_tests.c
+++ b/app/tests/led_tests.c
@@ -1,3 +1,32 @@
+/*
+ * Copyright (c) 2011, Code Aurora Forum. 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 Code Aurora Forum, Inc. 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<dev/pm8921_leds.h>
 #include<dev/pm8921.h>
 
diff --git a/dev/pmic/pm8921/include/dev/pm8921.h b/dev/pmic/pm8921/include/dev/pm8921.h
index bff76e9..2a41690 100644
--- a/dev/pmic/pm8921/include/dev/pm8921.h
+++ b/dev/pmic/pm8921/include/dev/pm8921.h
@@ -77,7 +77,8 @@
 
 #define PM_GPIO_BLOCK_ID(gpio)         (PM_IRQ_BLOCK_GPIO_START + (gpio)/8)
 #define PM_GPIO_ID_TO_BIT_MASK(gpio)   (1 << ((gpio)%8))
-
+#define PM_PWRKEY_BLOCK_ID		6
+#define PM_PWRKEY_PRESS_BIT		(1 << 3)
 
 typedef int (*pm8921_read_func)(uint8_t *data, uint32_t length, uint32_t addr);
 typedef int (*pm8921_write_func)(uint8_t *data, uint32_t length, uint32_t addr);
@@ -110,6 +111,7 @@
 int  pm8921_ldo_set_voltage(uint32_t ldo_id, uint32_t voltage);
 int  pm8921_config_reset_pwr_off(unsigned reset);
 int  pm8921_gpio_get(uint8_t gpio, uint8_t *status);
+int  pm8921_pwrkey_status(uint8_t *status);
 int pm8921_config_led_current(enum pm8921_leds led_num,
 	uint8_t current,
 	enum led_mode sink,
@@ -118,4 +120,5 @@
 	unsigned int flash_logic,
 	unsigned int flash_ensel);
 
+
 #endif
diff --git a/dev/pmic/pm8921/pm8921.c b/dev/pmic/pm8921/pm8921.c
index c6ee438..3200c47 100644
--- a/dev/pmic/pm8921/pm8921.c
+++ b/dev/pmic/pm8921/pm8921.c
@@ -203,6 +203,23 @@
 	return ret;
 }
 
+int pm8921_pwrkey_status(uint8_t *is_pwrkey_pressed)
+{
+	int ret = 0;
+	uint8_t block_status;
+
+	ret = pm8921_irq_get_block_status(PM_PWRKEY_BLOCK_ID, &block_status);
+
+	if (!ret)
+	{
+		if(block_status & PM_PWRKEY_PRESS_BIT)
+			*is_pwrkey_pressed = 1;
+		else
+			*is_pwrkey_pressed = 0;
+	}
+	return ret;
+}
+
 int pm8921_ldo_set_voltage(uint32_t ldo_id, uint32_t voltage)
 {
 	uint8_t mult;
diff --git a/dev/ssbi/ssbi.c b/dev/ssbi/ssbi.c
index 1686cdc..09ca4c6 100644
--- a/dev/ssbi/ssbi.c
+++ b/dev/ssbi/ssbi.c
@@ -34,6 +34,9 @@
 #include <reg.h>
 #include <sys/types.h>
 #include <dev/ssbi.h>
+#ifdef TARGET_USES_RSPIN_LOCK
+#include <platform/remote_spinlock.h>
+#endif
 
 int i2c_ssbi_poll_for_device_ready(void)
 {
@@ -70,8 +73,17 @@
 	unsigned char *buf = buffer;
 	unsigned short len = length;
 	unsigned short addr = slave_addr;
-	unsigned long read_cmd = SSBI_CMD_READ(addr);
-	unsigned long mode2 = readl(MSM_SSBI_BASE + SSBI2_MODE2);
+	unsigned long read_cmd = 0;
+	unsigned long mode2 = 0;
+
+	/*
+	 * Use remote spin locks since SSBI2 controller is shared with nonHLOS proc
+	 */
+#ifdef TARGET_USES_RSPIN_LOCK
+	remote_spin_lock(rlock);
+#endif
+	read_cmd = SSBI_CMD_READ(addr);
+	mode2 = readl(MSM_SSBI_BASE + SSBI2_MODE2);
 
 	//buf = alloc(len * sizeof(8));
 	if (mode2 & SSBI_MODE2_SSBI2_MODE)
@@ -82,7 +94,7 @@
 		ret = i2c_ssbi_poll_for_device_ready();
 		if (ret) {
 		        dprintf (CRITICAL, "Error: device not ready\n");
-			return ret;
+			goto end;
 		}
 
 		writel(read_cmd, MSM_SSBI_BASE + SSBI2_CMD);
@@ -90,13 +102,17 @@
 		ret = i2c_ssbi_poll_for_read_completed();
 		if (ret) {
 		        dprintf (CRITICAL, "Error: read not completed\n");
-			return ret;
+			goto end;
 		}
 
 		*buf++ = readl(MSM_SSBI_BASE + SSBI2_RD) & SSBI_RD_REG_DATA_MASK;
 		len--;
 	}
-	return 0;
+end:
+#ifdef TARGET_USES_RSPIN_LOCK
+	remote_spin_unlock(rlock);
+#endif
+	return ret;
 }
 
 int i2c_ssbi_write_bytes(unsigned char  *buffer, unsigned short length,
@@ -107,7 +123,15 @@
 	unsigned char *buf = buffer;
 	unsigned short len = length;
 	unsigned short addr = slave_addr;
-	unsigned long mode2 = readl(MSM_SSBI_BASE + SSBI2_MODE2);
+	unsigned long mode2 = 0;
+
+	/*
+	 * Use remote spin locks since SSBI2 controller is shared with nonHLOS proc
+	 */
+#ifdef TARGET_USES_RSPIN_LOCK
+	remote_spin_lock(rlock);
+#endif
+	mode2 = readl(MSM_SSBI_BASE + SSBI2_MODE2);
 
 	if (mode2 & SSBI_MODE2_SSBI2_MODE)
 		writel(SSBI_MODE2_REG_ADDR_15_8(mode2, addr),
@@ -117,19 +141,24 @@
 		ret = i2c_ssbi_poll_for_device_ready();
 		if (ret) {
 		        dprintf (CRITICAL, "Error: device not ready\n");
-			return ret;
+			goto end;
 		}
 
 		writel(SSBI_CMD_WRITE(addr, *buf++), MSM_SSBI_BASE + SSBI2_CMD);
 
 		while (readl(MSM_SSBI_BASE + SSBI2_STATUS) & SSBI_STATUS_MCHN_BUSY) {
 		  if (--timeout == 0) {
-		    dprintf(INFO, "In Device ready function:Timeout, status %x\n", readl(MSM_SSBI_BASE + SSBI2_STATUS));
-		    return 1;
+			dprintf(INFO, "In Device ready function:Timeout, status %x\n", readl(MSM_SSBI_BASE + SSBI2_STATUS));
+			ret = 1;
+			goto end;
 		  }
 		}
 		len--;
 	}
+end:
+#ifdef TARGET_USES_RSPIN_LOCK
+	remote_spin_unlock(rlock);
+#endif
 	return 0;
 }
 
diff --git a/include/platform.h b/include/platform.h
index cff84c3..309bfef 100644
--- a/include/platform.h
+++ b/include/platform.h
@@ -40,6 +40,7 @@
 void display_image_on_screen(void);
 
 unsigned board_machtype(void);
+unsigned board_platform_id(void);
 unsigned check_reboot_mode(void);
 void platform_uninit_timer(void);
 void reboot_device(unsigned);
diff --git a/lib/openssl/crypto/rules.mk b/lib/openssl/crypto/rules.mk
index d2fc6f0..ff710c4 100644
--- a/lib/openssl/crypto/rules.mk
+++ b/lib/openssl/crypto/rules.mk
@@ -313,7 +313,9 @@
 	$(LOCAL_DIR)/x509v3/v3_skey.o \
 	$(LOCAL_DIR)/x509v3/v3_sxnet.o \
 	$(LOCAL_DIR)/x509v3/v3err.o \
-	$(LOCAL_DIR)/x509v3/v3_utl.o
+	$(LOCAL_DIR)/x509v3/v3_utl.o \
+	$(LOCAL_DIR)/sha/asm/sha1-armv4-large.o \
+	$(LOCAL_DIR)/sha/asm/sha256-armv4.o
 
 include $(LOCAL_PATH)/android-config.mk
 
@@ -322,8 +324,6 @@
 arm_src_files := \
     $(LOCAL_DIR)/aes/asm/aes-armv4.o \
     $(LOCAL_DIR)/bn/asm/armv4-mont.o \
-    $(LOCAL_DIR)/sha/asm/sha1-armv4-large.o \
-    $(LOCAL_DIR)/sha/asm/sha256-armv4.o \
     $(LOCAL_DIR)/sha/asm/sha512-armv4.o
 
 non_arm_src_files := aes/aes_core.c
diff --git a/lib/openssl/crypto/sha/asm/sha1-armv4-large.s b/lib/openssl/crypto/sha/asm/sha1-armv4-large.S
similarity index 100%
rename from lib/openssl/crypto/sha/asm/sha1-armv4-large.s
rename to lib/openssl/crypto/sha/asm/sha1-armv4-large.S
diff --git a/lib/openssl/crypto/sha/asm/sha256-armv4.s b/lib/openssl/crypto/sha/asm/sha256-armv4.S
similarity index 100%
rename from lib/openssl/crypto/sha/asm/sha256-armv4.s
rename to lib/openssl/crypto/sha/asm/sha256-armv4.S
diff --git a/platform/mdm9x15/platform.c b/platform/mdm9x15/platform.c
index 99e1ad4..eea6f81 100644
--- a/platform/mdm9x15/platform.c
+++ b/platform/mdm9x15/platform.c
@@ -49,8 +49,10 @@
 {
 	uint8_t cfg_bid = 0x1;
 	uint8_t cfg_pid = 0x1;
+	uint8_t gsbi_id = target_uart_gsbi();
 
-	uart_init(target_uart_gsbi());
+	uart_dm_init(gsbi_id, GSBI_BASE(gsbi_id), GSBI_UART_DM_BASE(gsbi_id));
+
 	/* Timers - QGIC Config */
 	writel((cfg_bid << 7 | cfg_pid << 10), APCS_GLB_QGIC_CFG);
 	qgic_init();
diff --git a/platform/msm7x27a/include/platform/iomap.h b/platform/msm7x27a/include/platform/iomap.h
index 1a9ce81..5ce8a02 100644
--- a/platform/msm7x27a/include/platform/iomap.h
+++ b/platform/msm7x27a/include/platform/iomap.h
@@ -113,4 +113,5 @@
 
 #define MDP_TEST_MODE_CLK                     REG_MDP(0xF0000)
 #define MDP_INTR_STATUS                       REG_MDP(0x00054)
+#define MSM_CRYPTO_BASE                       (0xA0C00000)
 #endif
diff --git a/platform/msm7x30/include/platform/remote_spinlock.h b/platform/msm7x30/include/platform/remote_spinlock.h
new file mode 100644
index 0000000..61711c6
--- /dev/null
+++ b/platform/msm7x30/include/platform/remote_spinlock.h
@@ -0,0 +1,60 @@
+/* Copyright (c) 2012, Code Aurora Forum. 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 Code Aurora Forum, Inc. 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 <sys/types.h>
+
+#define RLOCK_CHUNK_NAME_LENGTH 10
+#define RLOCK_CHUNK_NAME        "PMIC_SSBI"
+#define DEK_LOCK_REQUEST        1
+#define DEK_LOCK_YIELD          (!DEK_LOCK_REQUEST)
+#define DEK_YIELD_TURN_SELF     0
+
+struct rlock_chunk_header {
+	uint32_t size;
+	char name[RLOCK_CHUNK_NAME_LENGTH];
+	uint32_t lock;
+	uint32_t reserved;
+	uint32_t type;
+	uint32_t version;
+};
+struct dek_spinlock {
+	volatile uint8_t self_lock;
+	volatile uint8_t other_lock;
+	volatile uint8_t next_yield;
+	uint8_t pad;
+};
+
+typedef union {
+	volatile uint32_t lock;
+	struct dek_spinlock dek;
+} raw_remote_spinlock_t;
+
+typedef raw_remote_spinlock_t *remote_spinlock_t;
+
+remote_spinlock_t rlock;
diff --git a/platform/msm7x30/remote_spinlock.c b/platform/msm7x30/remote_spinlock.c
new file mode 100644
index 0000000..93a509a
--- /dev/null
+++ b/platform/msm7x30/remote_spinlock.c
@@ -0,0 +1,108 @@
+/* Copyright (c) 2012, Code Aurora Forum. 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 Code Aurora Forum, Inc. 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 <platform/iomap.h>
+#include <platform/remote_spinlock.h>
+#include <debug.h>
+#include <smem.h>
+#include <reg.h>
+
+static struct smem *smem = (void *)(MSM_SHARED_BASE);
+
+void *smem_rlock_get_entry(unsigned id, unsigned *size)
+{
+	struct smem_alloc_info *ainfo;
+	void *ret = 0;
+	unsigned long flags = 0;
+
+	ainfo = &smem->alloc_info[id];
+
+	if (readl(&ainfo->allocated) == 0) {
+		dprintf(SPEW,"Shared memory is not allocated\n");
+		return ret;
+	}
+	/* Read the DAL area */
+	*size = readl(&ainfo->size);
+	ret = (void *) (MSM_SHARED_BASE +  readl(&ainfo->offset));
+
+	return ret;
+}
+
+int remote_spinlock_init(remote_spinlock_t *lock)
+{
+	struct rlock_chunk_header *cur_header;
+	void *rlock_smem_start, *rlock_smem_end;
+	uint32_t rlock_smem_size = 0;
+	int smem_status = 0;
+
+	rlock_smem_start = smem_rlock_get_entry(SMEM_RLOCK_AREA, &rlock_smem_size);
+
+	if (!rlock_smem_start) {
+		dprintf(CRITICAL,"Failed to get smem entry for remote spin lock\n");
+		return 1;
+	}
+
+	rlock_smem_end = rlock_smem_start + rlock_smem_size;
+
+	cur_header = (struct rlock_chunk_header *)
+			(((uint32_t)rlock_smem_start + (4095)) & ~4095);
+	*lock = NULL;
+	/* Find the lock from the list */
+	while (cur_header->size != 0
+		&& ((uint32_t)(cur_header + 1) < (uint32_t)rlock_smem_end)) {
+		/* If we found the lock, get the address */
+		if (!strncmp(cur_header->name, RLOCK_CHUNK_NAME,
+				RLOCK_CHUNK_NAME_LENGTH)) {
+			*lock = (remote_spinlock_t)&cur_header->lock;
+			return 0;
+		}
+		cur_header = (void *)cur_header + cur_header->size;
+	}
+	dprintf(CRITICAL,"%s: remote lock not found: %s\n",RLOCK_CHUNK_NAME,__FILE__);
+	return 1;
+}
+
+void remote_spin_lock(raw_remote_spinlock_t *lock)
+{
+	lock->dek.self_lock = DEK_LOCK_REQUEST;
+
+	/* check if the lock is available*/
+	while(lock->dek.other_lock) {
+		if(lock->dek.next_yield == DEK_YIELD_TURN_SELF)
+		while (lock->dek.other_lock);
+		lock->dek.self_lock = DEK_LOCK_REQUEST;
+	}
+	/* We acquired the lock */
+	lock->dek.next_yield = DEK_YIELD_TURN_SELF;
+	dmb();
+}
+void remote_spin_unlock(raw_remote_spinlock_t *lock)
+{
+	dmb();
+	lock->dek.self_lock = DEK_LOCK_YIELD;
+}
diff --git a/platform/msm7x30/rules.mk b/platform/msm7x30/rules.mk
index 41dd665..dccc08a 100644
--- a/platform/msm7x30/rules.mk
+++ b/platform/msm7x30/rules.mk
@@ -23,7 +23,8 @@
 	$(LOCAL_DIR)/gpio.o \
 	$(LOCAL_DIR)/panel.o \
 	$(LOCAL_DIR)/panel_sharp_wvga.o \
-	$(LOCAL_DIR)/acpuclock.o
+	$(LOCAL_DIR)/acpuclock.o \
+	$(LOCAL_DIR)/remote_spinlock.o
 
 ifeq ($(ENABLE_TRUSTZONE),1)
 	ifeq ($(ENABLE_ROMLITE_LOCAL_TEST), 1)
diff --git a/platform/msm8960/acpuclock.c b/platform/msm8960/acpuclock.c
index 1b4a11e..0301de8 100644
--- a/platform/msm8960/acpuclock.c
+++ b/platform/msm8960/acpuclock.c
@@ -264,3 +264,25 @@
 	writel((1 << 4), CE1_CORE_CLK_CTL);
 	return;
 }
+
+/* Async Reset CE1 */
+void ce_async_reset()
+{
+	/* Enable Async reset bit for HCLK CE1 */
+	writel((1<<7) | (1 << 4), CE1_HCLK_CTL);
+	/* Enable Async reset bit for core clk for CE1 */
+	writel((1<<7) | (1 << 4), CE1_CORE_CLK_CTL);
+
+	/* Add a small delay between switching the
+	 * async intput from high to low
+	 */
+	 udelay(2);
+
+	/* Disable Async reset bit for HCLK for CE1 */
+	writel((1 << 4), CE1_HCLK_CTL);
+	/* Disable Async reset bit for core clk for CE1 */
+	writel((1 << 4), CE1_CORE_CLK_CTL);
+
+	return;
+}
+
diff --git a/platform/msm8960/gpio.c b/platform/msm8960/gpio.c
index 52db863..9403be0 100644
--- a/platform/msm8960/gpio.c
+++ b/platform/msm8960/gpio.c
@@ -33,6 +33,7 @@
 #include <gsbi.h>
 #include <dev/pm8921.h>
 #include <sys/types.h>
+#include <smem.h>
 
 void gpio_tlmm_config(uint32_t gpio, uint8_t func,
 		      uint8_t dir, uint8_t pull,
@@ -55,31 +56,65 @@
 	return;
 }
 
+/* TODO: this and other code below in this file should ideally by in target dir.
+ * keeping it here for this brigup.
+ */
+
 /* Configure gpio for uart - based on gsbi id */
 void gpio_config_uart_dm(uint8_t id)
 {
-	switch (id) {
+	if(board_platform_id() == APQ8064)
+	{
+		switch (id) {
 
-	case GSBI_ID_3:
-		/* configure rx gpio */
-		gpio_tlmm_config(15, 1, GPIO_INPUT, GPIO_NO_PULL,
-				 GPIO_8MA, GPIO_DISABLE);
-		/* configure tx gpio */
-		gpio_tlmm_config(14, 1, GPIO_OUTPUT, GPIO_NO_PULL,
-				 GPIO_8MA, GPIO_DISABLE);
-		break;
+		case GSBI_ID_1:
+			/* configure rx gpio */
+			gpio_tlmm_config(19, 1, GPIO_INPUT, GPIO_NO_PULL,
+							 GPIO_8MA, GPIO_DISABLE);
+			/* configure tx gpio */
+			gpio_tlmm_config(18, 1, GPIO_OUTPUT, GPIO_NO_PULL,
+							 GPIO_8MA, GPIO_DISABLE);
+			break;
 
-	case GSBI_ID_5:
-		/* configure rx gpio */
-		gpio_tlmm_config(23, 1, GPIO_INPUT, GPIO_NO_PULL,
-				 GPIO_8MA, GPIO_DISABLE);
-		/* configure tx gpio */
-		gpio_tlmm_config(22, 1, GPIO_OUTPUT, GPIO_NO_PULL,
-				 GPIO_8MA, GPIO_DISABLE);
-		break;
 
-	default:
-		ASSERT(0);
+		case GSBI_ID_7:
+			/* configure rx gpio */
+			gpio_tlmm_config(83, 1, GPIO_INPUT, GPIO_NO_PULL,
+							 GPIO_8MA, GPIO_DISABLE);
+			/* configure tx gpio */
+			gpio_tlmm_config(82, 2, GPIO_OUTPUT, GPIO_NO_PULL,
+							 GPIO_8MA, GPIO_DISABLE);
+			break;
+
+		default:
+			ASSERT(0);
+		}
+	}
+	else
+	{
+		switch (id) {
+
+		case GSBI_ID_3:
+			/* configure rx gpio */
+			gpio_tlmm_config(15, 1, GPIO_INPUT, GPIO_NO_PULL,
+							 GPIO_8MA, GPIO_DISABLE);
+			/* configure tx gpio */
+			gpio_tlmm_config(14, 1, GPIO_OUTPUT, GPIO_NO_PULL,
+							 GPIO_8MA, GPIO_DISABLE);
+			break;
+
+		case GSBI_ID_5:
+			/* configure rx gpio */
+			gpio_tlmm_config(23, 1, GPIO_INPUT, GPIO_NO_PULL,
+							 GPIO_8MA, GPIO_DISABLE);
+			/* configure tx gpio */
+			gpio_tlmm_config(22, 1, GPIO_OUTPUT, GPIO_NO_PULL,
+							 GPIO_8MA, GPIO_DISABLE);
+			break;
+
+		default:
+			ASSERT(0);
+		}
 	}
 }
 
@@ -137,6 +172,14 @@
 	PM8XXX_GPIO_OUTPUT(PM_GPIO(9), 0),
 };
 
+/* pm8921 GPIO configuration for APQ8064 keypad */
+static struct pm8xxx_gpio_init pm8921_keypad_gpios_apq[] = {
+	/* keys GPIOs */
+	PM8XXX_GPIO_INPUT(PM_GPIO(35), PM_GPIO_PULL_UP_31_5),
+	PM8XXX_GPIO_INPUT(PM_GPIO(38), PM_GPIO_PULL_UP_31_5),
+	PM8XXX_GPIO_OUTPUT(PM_GPIO(9), 0),
+};
+
 void msm8960_keypad_gpio_init()
 {
 		int i = 0;
@@ -164,3 +207,18 @@
 								&(pm8038_keypad_gpios[i].config));
 		}
 }
+
+void apq8064_keypad_gpio_init()
+{
+		int i = 0;
+		int num = 0;
+
+		num = ARRAY_SIZE(pm8921_keypad_gpios_apq);
+
+		for(i=0; i < num; i++)
+		{
+			pm8921_gpio_config(pm8921_keypad_gpios_apq[i].gpio,
+								&(pm8921_keypad_gpios_apq[i].config));
+		}
+}
+
diff --git a/platform/msm8960/include/platform/iomap.h b/platform/msm8960/include/platform/iomap.h
index f653437..08f8a4b 100644
--- a/platform/msm8960/include/platform/iomap.h
+++ b/platform/msm8960/include/platform/iomap.h
@@ -83,11 +83,6 @@
 #define GPIO_CONFIG_ADDR(x) (TLMM_BASE_ADDR + 0x1000 + (x)*0x10)
 #define GPIO_IN_OUT_ADDR(x) (TLMM_BASE_ADDR + 0x1004 + (x)*0x10)
 
-#define GSBI_BASE(id)         ((id) <= 7 ? (0x16000000 + (((id)-1) << 20)) : \
-                                           (0x1A000000 + (((id)-8) << 20)))
-#define GSBI_UART_DM_BASE(id) (GSBI_BASE(id) + 0x40000)
-#define QUP_BASE(id)          (GSBI_BASE(id) + 0x80000)
-
 #define EBI2_CHIP_SELECT_CFG0   0x1A100000
 #define EBI2_XMEM_CS3_CFG1      0x1A110034
 
diff --git a/platform/msm8960/platform.c b/platform/msm8960/platform.c
index 1233ce7..d45b699 100644
--- a/platform/msm8960/platform.c
+++ b/platform/msm8960/platform.c
@@ -36,7 +36,6 @@
 #include <dev/fbcon.h>
 #include <mmu.h>
 #include <arch/arm/mmu.h>
-#include <partition_parser.h>
 
 extern void platform_init_timer(void);
 extern void platform_panel_backlight_on(void);
@@ -49,6 +48,7 @@
 extern void mipi_dsi_shutdown(void);
 
 static uint32_t ticks_per_sec = 0;
+static uint8_t display_enabled = 0;
 
 #define MB (1024*1024)
 
@@ -108,30 +108,14 @@
 
 	fb_cfg = mipi_init();
 	fbcon_setup(fb_cfg);
+
+	display_enabled = 1;
 }
 
 void display_shutdown(void)
 {
-	mipi_dsi_shutdown();
-}
-
-/*
- * Write-protect partition list.
- *
- * Partition added in this list should have (size + padding) in multiple of
- * mmc write protect group size. Otherwise this can end up write protecting
- * some blocks from next partition.
- */
-char *wp_list[] = {"fsg", NULL};
-
-void platform_wp_paritition(void)
-{
-	int count = 0;
-	while(wp_list[count] != NULL)
-	{
-		paritition_wp_by_name(wp_list[count]);
-		count++;
-	}
+	if(display_enabled)
+		mipi_dsi_shutdown();
 }
 
 void platform_uninit(void)
@@ -139,7 +123,7 @@
 #if DISPLAY_SPLASH_SCREEN
 	display_shutdown();
 #endif
-	platform_wp_paritition();
+
 	platform_uninit_timer();
 }
 
@@ -182,4 +166,3 @@
 {
 	return ticks_per_sec;
 }
-
diff --git a/platform/msm8x60/platform.c b/platform/msm8x60/platform.c
index e2369f7..478aec9 100755
--- a/platform/msm8x60/platform.c
+++ b/platform/msm8x60/platform.c
@@ -108,7 +108,8 @@
 
 void platform_early_init(void)
 {
-	uart_init(target_uart_gsbi());
+	uint8_t gsbi_id = target_uart_gsbi();
+	uart_dm_init(gsbi_id, GSBI_BASE(gsbi_id), GSBI_UART_DM_BASE(gsbi_id));
 	qgic_init();
 	platform_init_timer();
 }
diff --git a/platform/msm_shared/crypto4_eng.c b/platform/msm_shared/crypto4_eng.c
old mode 100644
new mode 100755
index 2f7cdc5..62f5666
--- a/platform/msm_shared/crypto4_eng.c
+++ b/platform/msm_shared/crypto4_eng.c
@@ -34,8 +34,10 @@
 #include <platform/iomap.h>
 #include <crypto4_eng.h>
 #include <crypto_hash.h>
+#include <scm.h>
 
 extern void dsb(void);
+extern void ce_async_reset();
 
 /*
  * Function to reset the crypto engine.
@@ -43,9 +45,27 @@
 
 void crypto_eng_reset(void)
 {
+	ce_async_reset();
 	return;
 }
 
+
+/* Function to switch the CE1 context
+ * from register to ADM
+ */
+void crypto_eng_cleanup(void)
+{
+
+    unsigned int val;
+
+    enum ap_ce_channel_type chn = AP_CE_ADM_USE;
+    /* Make a SMC call to TZ to make CE1 use ADM interface for HLOS*/
+    val = switch_ce_chn_cmd(chn);
+    dprintf(INFO, "TZ channel swith returned %d\n", val);
+
+}
+
+
 /*
  * Function to initialize the crypto engine for a new session. It enables the
  * auto shutdown feature of CRYPTO and mask various interrupts since we use
@@ -55,12 +75,12 @@
 void crypto_eng_init(void)
 {
 	unsigned int val;
-	val = (AUTO_SHUTDOWN_EN | MASK_ERR_INTR | MASK_DIN_INTR |
-	       MASK_DOUT_INTR | HIGH_SPD_IN_EN_N | HIGH_SPD_OUT_EN_N);
 
-	val |= MASK_OP_DONE_INTR;
+	enum ap_ce_channel_type chn = AP_CE_REGISTER_USE;
+	/* Make a SMC call to TZ to make CE1 use register interface */
+	val = switch_ce_chn_cmd(chn);
+	dprintf(INFO, "TZ channel swith returned %d\n", val);
 
-	wr_ce(val, CRYPTO_CONFIG);
 }
 
 /*
diff --git a/platform/msm_shared/crypto_hash.c b/platform/msm_shared/crypto_hash.c
index d431f42..363e682 100644
--- a/platform/msm_shared/crypto_hash.c
+++ b/platform/msm_shared/crypto_hash.c
@@ -37,6 +37,10 @@
 
 extern void ce_clock_init(void);
 
+__WEAK void crypto_eng_cleanup()
+{
+}
+
 /*
  * Top level function which calculates SHAx digest with given data and size.
  * Digest varies based on the authentication algorithm.
@@ -50,14 +54,27 @@
 	crypto_result_type ret_val = CRYPTO_SHA_ERR_NONE;
 
 	if (auth_alg == 1) {
+#ifdef NO_CRYPTO_ENG
+		/* Hardware CE is not present , use software hashing */
+		digest = SHA1(addr, size, digest);
+#else
 		ret_val = crypto_sha1(addr, size, digest);
+#endif
 	} else if (auth_alg == 2) {
+#ifdef NO_CRYPTO_ENG
+		/* Hardware CE is not present , use software hashing */
+		digest = SHA256(addr, size, digest);
+#else
 		ret_val = crypto_sha256(addr, size, digest);
+#endif
 	}
 
 	if (ret_val != CRYPTO_SHA_ERR_NONE) {
 		dprintf(CRITICAL, "crypto_sha256 returns error %d\n", ret_val);
 	}
+
+	crypto_eng_cleanup();
+
 }
 
 /*
diff --git a/platform/msm_shared/include/gsbi.h b/platform/msm_shared/include/gsbi.h
index 8d504a7..2b1ad75 100644
--- a/platform/msm_shared/include/gsbi.h
+++ b/platform/msm_shared/include/gsbi.h
@@ -31,7 +31,7 @@
 #include <platform/iomap.h>
 
 /* GSBI Registers */
-#define GSBI_CTRL_REG(id)        (GSBI_BASE(id) + 0x0)
+#define GSBI_CTRL_REG(base)        ((base) + 0x0)
 
 #define GSBI_CTRL_REG_PROTOCOL_CODE_S   4
 #define GSBI_PROTOCOL_CODE_I2C          0x2
diff --git a/platform/msm_shared/include/mmc.h b/platform/msm_shared/include/mmc.h
index 6c754ff..a07d169 100644
--- a/platform/msm_shared/include/mmc.h
+++ b/platform/msm_shared/include/mmc.h
@@ -374,7 +374,6 @@
 #define MMC_BOOT_E_DATA_ADM_ERR           21
 
 /* EXT_CSD */
-#define MMC_BOOT_ACCESS_BIT_SET           0x1
 #define MMC_BOOT_ACCESS_WRITE             0x3
 
 #define MMC_BOOT_EXT_USER_WP              171
@@ -594,10 +593,6 @@
 unsigned int mmc_erase_card(unsigned long long data_addr,
 			    unsigned long long data_len);
 
-unsigned int mmc_wp(unsigned int sector, unsigned int size,
-				unsigned char set_clear_wp);
-
 struct mmc_boot_host *get_mmc_host(void);
 struct mmc_boot_card *get_mmc_card(void);
-
 #endif
diff --git a/platform/msm_shared/include/partition_parser.h b/platform/msm_shared/include/partition_parser.h
index 48fd982..8e0f2ee 100644
--- a/platform/msm_shared/include/partition_parser.h
+++ b/platform/msm_shared/include/partition_parser.h
@@ -176,7 +176,6 @@
 		       struct mmc_boot_host *mmc_host,
 		       struct mmc_boot_card *mmc_card);
 unsigned int write_partition(unsigned size, unsigned char *partition);
-unsigned int paritition_wp_by_name(const char *name);
 
 /* For Debugging */
 void partition_dump(void);
diff --git a/platform/msm_shared/include/scm.h b/platform/msm_shared/include/scm.h
old mode 100644
new mode 100755
index 3e78cf7..668e32c
--- a/platform/msm_shared/include/scm.h
+++ b/platform/msm_shared/include/scm.h
@@ -67,11 +67,27 @@
 static uint32 smc(uint32 cmd_addr);
 int decrypt_img_scm(uint32 ** img_ptr, uint32 * img_len_ptr);
 
-#define SCM_SVC_FUSE            0x08
-#define SCM_BLOW_SW_FUSE_ID     0x01
-#define SCM_IS_SW_FUSE_BLOWN_ID 0x02
+#define SCM_SVC_FUSE                0x08
+#define SCM_BLOW_SW_FUSE_ID         0x01
+#define SCM_IS_SW_FUSE_BLOWN_ID     0x02
 
-#define HLOS_IMG_TAMPER_FUSE    0
+#define HLOS_IMG_TAMPER_FUSE        0
+
+
+#define SCM_SVC_CE_CHN_SWITCH_ID    0x04
+#define SCM_CE_CHN_SWITCH_ID        0x02
+
+enum ap_ce_channel_type {
+AP_CE_REGISTER_USE = 0,
+AP_CE_ADM_USE = 1
+};
+
+/* Apps CE resource. */
+#define TZ_RESOURCE_CE_AP  2
+
+uint8_t switch_ce_chn_cmd(enum ap_ce_channel_type channel);
+
+
 void set_tamper_fuse_cmd();
 
 /**
@@ -118,4 +134,6 @@
 	uint32_t is_complete;
 };
 
+
+
 #endif
diff --git a/platform/msm_shared/include/uart_dm.h b/platform/msm_shared/include/uart_dm.h
index c3c5718..484e7b5 100644
--- a/platform/msm_shared/include/uart_dm.h
+++ b/platform/msm_shared/include/uart_dm.h
@@ -67,19 +67,19 @@
 /* UART_DM Registers */
 
 /* UART Operational Mode Register */
-#define MSM_BOOT_UART_DM_MR1(id)             (GSBI_UART_DM_BASE(id) + 0x00)
-#define MSM_BOOT_UART_DM_MR2(id)             (GSBI_UART_DM_BASE(id) + 0x04)
+#define MSM_BOOT_UART_DM_MR1(base)             ((base) + 0x00)
+#define MSM_BOOT_UART_DM_MR2(base)             ((base) + 0x04)
 #define MSM_BOOT_UART_DM_RXBRK_ZERO_CHAR_OFF (1 << 8)
 #define MSM_BOOT_UART_DM_LOOPBACK            (1 << 7)
 
 /* UART Clock Selection Register */
-#define MSM_BOOT_UART_DM_CSR(id)             (GSBI_UART_DM_BASE(id) + 0x08)
+#define MSM_BOOT_UART_DM_CSR(base)             ((base) + 0x08)
 
 /* UART DM TX FIFO Registers - 4 */
-#define MSM_BOOT_UART_DM_TF(id, x)         (GSBI_UART_DM_BASE(id) + 0x70+(4*(x)))
+#define MSM_BOOT_UART_DM_TF(base, x)         ((base) + 0x70+(4*(x)))
 
 /* UART Command Register */
-#define MSM_BOOT_UART_DM_CR(id)              (GSBI_UART_DM_BASE(id) + 0x10)
+#define MSM_BOOT_UART_DM_CR(base)              ((base) + 0x10)
 #define MSM_BOOT_UART_DM_CR_RX_ENABLE        (1 << 0)
 #define MSM_BOOT_UART_DM_CR_RX_DISABLE       (1 << 1)
 #define MSM_BOOT_UART_DM_CR_TX_ENABLE        (1 << 2)
@@ -121,7 +121,7 @@
 #define MSM_BOOT_UART_DM_GCMD_DIS_STALE_EVT   MSM_BOOT_UART_DM_CR_GENERAL_CMD(6)
 
 /* UART Interrupt Mask Register */
-#define MSM_BOOT_UART_DM_IMR(id)             (GSBI_UART_DM_BASE(id) + 0x14)
+#define MSM_BOOT_UART_DM_IMR(base)             ((base) + 0x14)
 #define MSM_BOOT_UART_DM_TXLEV               (1 << 0)
 #define MSM_BOOT_UART_DM_RXHUNT              (1 << 1)
 #define MSM_BOOT_UART_DM_RXBRK_CHNG          (1 << 2)
@@ -142,42 +142,42 @@
                                               MSM_BOOT_UART_DM_RXSTALE)
 
 /* UART Interrupt Programming Register */
-#define MSM_BOOT_UART_DM_IPR(id)             (GSBI_UART_DM_BASE(id) + 0x18)
+#define MSM_BOOT_UART_DM_IPR(base)             ((base) + 0x18)
 #define MSM_BOOT_UART_DM_STALE_TIMEOUT_LSB   0x0f
 #define MSM_BOOT_UART_DM_STALE_TIMEOUT_MSB   0	/* Not used currently */
 
 /* UART Transmit/Receive FIFO Watermark Register */
-#define MSM_BOOT_UART_DM_TFWR(id)            (GSBI_UART_DM_BASE(id) + 0x1C)
+#define MSM_BOOT_UART_DM_TFWR(base)            ((base) + 0x1C)
 /* Interrupt is generated when FIFO level is less than or equal to this value */
 #define MSM_BOOT_UART_DM_TFW_VALUE           0
 
-#define MSM_BOOT_UART_DM_RFWR(id)            (GSBI_UART_DM_BASE(id) + 0x20)
+#define MSM_BOOT_UART_DM_RFWR(base)            ((base) + 0x20)
 /*Interrupt generated when no of words in RX FIFO is greater than this value */
 #define MSM_BOOT_UART_DM_RFW_VALUE           0
 
 /* UART Hunt Character Register */
-#define MSM_BOOT_UART_DM_HCR(id)             (GSBI_UART_DM_BASE(id) + 0x24)
+#define MSM_BOOT_UART_DM_HCR(base)             ((base) + 0x24)
 
 /* Used for RX transfer initialization */
-#define MSM_BOOT_UART_DM_DMRX(id)            (GSBI_UART_DM_BASE(id) + 0x34)
+#define MSM_BOOT_UART_DM_DMRX(base)            ((base) + 0x34)
 
 /* Default DMRX value - any value bigger than FIFO size would be fine */
 #define MSM_BOOT_UART_DM_DMRX_DEF_VALUE    0x220
 
 /* Register to enable IRDA function */
-#define MSM_BOOT_UART_DM_IRDA(id)            (GSBI_UART_DM_BASE(id) + 0x38)
+#define MSM_BOOT_UART_DM_IRDA(base)            ((base) + 0x38)
 
 /* UART Data Mover Enable Register */
-#define MSM_BOOT_UART_DM_DMEN(id)            (GSBI_UART_DM_BASE(id) + 0x3C)
+#define MSM_BOOT_UART_DM_DMEN(base)            ((base) + 0x3C)
 
 /* Number of characters for Transmission */
-#define MSM_BOOT_UART_DM_NO_CHARS_FOR_TX(id) (GSBI_UART_DM_BASE(id) + 0x040)
+#define MSM_BOOT_UART_DM_NO_CHARS_FOR_TX(base) ((base) + 0x040)
 
 /* UART RX FIFO Base Address */
-#define MSM_BOOT_UART_DM_BADR(id)            (GSBI_UART_DM_BASE(id) + 0x44)
+#define MSM_BOOT_UART_DM_BADR(base)            ((base) + 0x44)
 
 /* UART Status Register */
-#define MSM_BOOT_UART_DM_SR(id)              (GSBI_UART_DM_BASE(id) + 0x008)
+#define MSM_BOOT_UART_DM_SR(base)              ((base) + 0x008)
 #define MSM_BOOT_UART_DM_SR_RXRDY            (1 << 0)
 #define MSM_BOOT_UART_DM_SR_RXFULL           (1 << 1)
 #define MSM_BOOT_UART_DM_SR_TXRDY            (1 << 2)
@@ -189,26 +189,26 @@
 #define MSM_BOOT_UART_DM_RX_BRK_START_LAST   (1 << 8)
 
 /* UART Receive FIFO Registers - 4 in numbers */
-#define MSM_BOOT_UART_DM_RF(id, x)      (GSBI_UART_DM_BASE(id) + 0x70 + (4*(x)))
+#define MSM_BOOT_UART_DM_RF(base, x)      ((base) + 0x70 + (4*(x)))
 
 /* UART Masked Interrupt Status Register */
-#define MSM_BOOT_UART_DM_MISR(id)         (GSBI_UART_DM_BASE(id) + 0x10)
+#define MSM_BOOT_UART_DM_MISR(base)         ((base) + 0x10)
 
 /* UART Interrupt Status Register */
-#define MSM_BOOT_UART_DM_ISR(id)          (GSBI_UART_DM_BASE(id) + 0x14)
+#define MSM_BOOT_UART_DM_ISR(base)          ((base) + 0x14)
 
 /* Number of characters received since the end of last RX transfer */
-#define MSM_BOOT_UART_DM_RX_TOTAL_SNAP(id)  (GSBI_UART_DM_BASE(id) + 0x38)
+#define MSM_BOOT_UART_DM_RX_TOTAL_SNAP(base)  ((base) + 0x38)
 
 /* UART TX FIFO Status Register */
-#define MSM_BOOT_UART_DM_TXFS(id)           (GSBI_UART_DM_BASE(id) + 0x4C)
+#define MSM_BOOT_UART_DM_TXFS(base)           ((base) + 0x4C)
 #define MSM_BOOT_UART_DM_TXFS_STATE_LSB(x)   MSM_BOOT_UART_DM_EXTR_BITS(x,0,6)
 #define MSM_BOOT_UART_DM_TXFS_STATE_MSB(x)   MSM_BOOT_UART_DM_EXTR_BITS(x,14,31)
 #define MSM_BOOT_UART_DM_TXFS_BUF_STATE(x)   MSM_BOOT_UART_DM_EXTR_BITS(x,7,9)
 #define MSM_BOOT_UART_DM_TXFS_ASYNC_STATE(x) MSM_BOOT_UART_DM_EXTR_BITS(x,10,13)
 
 /* UART RX FIFO Status Register */
-#define MSM_BOOT_UART_DM_RXFS(id)           (GSBI_UART_DM_BASE(id) + 0x50)
+#define MSM_BOOT_UART_DM_RXFS(base)           ((base) + 0x50)
 #define MSM_BOOT_UART_DM_RXFS_STATE_LSB(x)   MSM_BOOT_UART_DM_EXTR_BITS(x,0,6)
 #define MSM_BOOT_UART_DM_RXFS_STATE_MSB(x)   MSM_BOOT_UART_DM_EXTR_BITS(x,14,31)
 #define MSM_BOOT_UART_DM_RXFS_BUF_STATE(x)   MSM_BOOT_UART_DM_EXTR_BITS(x,7,9)
@@ -222,5 +222,7 @@
 #define MSM_BOOT_UART_DM_E_MALLOC_FAIL       4
 #define MSM_BOOT_UART_DM_E_RX_NOT_READY      5
 
-void uart_init(uint8_t gsbi_id);
+void uart_dm_init(uint8_t id,
+				  uint32_t gsbi_base,
+				  uint32_t uart_dm_base);
 #endif				/* __UART_DM_H__ */
diff --git a/platform/msm_shared/lcdc.c b/platform/msm_shared/lcdc.c
index 0ff9150..2b20154 100644
--- a/platform/msm_shared/lcdc.c
+++ b/platform/msm_shared/lcdc.c
@@ -128,12 +128,7 @@
 
 	dprintf(INFO, "lcdc_init(): panel is %d x %d\n", fb_cfg.width,
 		fb_cfg.height);
-#if PLATFORM_MSM8X60
 	fb_cfg.base = LCDC_FB_ADDR;
-#else
-	fb_cfg.base =
-	    memalign(4096, fb_cfg.width * fb_cfg.height * (fb_cfg.bpp / 8));
-#endif
 
 	writel((unsigned)fb_cfg.base, MSM_MDP_BASE1 + 0x90008);
 
diff --git a/platform/msm_shared/mmc.c b/platform/msm_shared/mmc.c
index 2d86ba1..b1fc977 100644
--- a/platform/msm_shared/mmc.c
+++ b/platform/msm_shared/mmc.c
@@ -85,6 +85,8 @@
 struct mmc_boot_host mmc_host;
 struct mmc_boot_card mmc_card;
 
+static unsigned int mmc_wp(unsigned int addr, unsigned int size,
+			   unsigned char set_clear_wp);
 static unsigned int mmc_boot_send_ext_cmd(struct mmc_boot_card *card,
 					  unsigned char *buf);
 static unsigned int mmc_boot_read_reg(struct mmc_boot_card *card,
@@ -2282,7 +2284,7 @@
 	       sizeof(struct mmc_boot_command));
 
 	/* Disabling PERM_WP for USER AREA (CMD6) */
-	mmc_ret = mmc_boot_switch_cmd(card, MMC_BOOT_ACCESS_BIT_SET,
+	mmc_ret = mmc_boot_switch_cmd(card, MMC_BOOT_ACCESS_WRITE,
 				      MMC_BOOT_EXT_USER_WP,
 				      MMC_BOOT_US_PERM_WP_DIS);
 
@@ -2336,14 +2338,14 @@
 		    (card->csd.erase_grp_mult + 1) * (card->csd.wp_grp_size +
 						      1);
 	}
-	dprintf(SPEW, "Write protect size: %d bytes\n", (wp_group_size * MMC_BOOT_WR_BLOCK_LEN));
+
 	if (wp_group_size == 0) {
 		return MMC_BOOT_E_FAILURE;
 	}
 
 	/* Setting POWER_ON_WP for USER AREA (CMD6) */
 
-	mmc_ret = mmc_boot_switch_cmd(card, MMC_BOOT_ACCESS_BIT_SET,
+	mmc_ret = mmc_boot_switch_cmd(card, MMC_BOOT_ACCESS_WRITE,
 				      MMC_BOOT_EXT_USER_WP,
 				      MMC_BOOT_US_PWR_WP_EN);
 
@@ -2371,9 +2373,6 @@
 
 	if (size % wp_group_size) {
 		loop_count = (size / wp_group_size) + 1;
-		dprintf(CRITICAL, "WARNING: Size passed to write protect is not multiple of wp_group_size!\n");
-		dprintf(CRITICAL, "WARNING: Write protecting %d extra bytes.\n",
-						((loop_count * wp_group_size) - size) * MMC_BOOT_WR_BLOCK_LEN);
 	} else {
 		loop_count = (size / wp_group_size);
 	}
@@ -2434,9 +2433,9 @@
 }
 
 /*
- * Function for setting Write protect for given sector
+ * Test Function for setting Write protect for given sector
  */
-unsigned int
+static unsigned int
 mmc_wp(unsigned int sector, unsigned int size, unsigned char set_clear_wp)
 {
 	unsigned int rc = MMC_BOOT_E_SUCCESS;
diff --git a/platform/msm_shared/partition_parser.c b/platform/msm_shared/partition_parser.c
index 2becaed..45f5413 100644
--- a/platform/msm_shared/partition_parser.c
+++ b/platform/msm_shared/partition_parser.c
@@ -946,42 +946,3 @@
 
 	return 0;
 }
-
-/*
- * Power on write protect partition by name.
- *
- * Partition passed to this function should have (size + padding) in multiple
- * of mmc write protect group size. Otherwise this can end up write protecting
- * some blocks from next partition.
- */
-
-unsigned int paritition_wp_by_name(const char *name)
-{
-	unsigned long long ptn = 0;
-	unsigned long long size = 0;
-	int index = INVALID_PTN;
-	unsigned int ret = MMC_BOOT_E_SUCCESS;
-
-	index = partition_get_index(name);
-	ptn = partition_get_offset(index);
-	if(ptn == 0) {
-		dprintf(CRITICAL, "%s partition not found.\n", name);
-		return 1;
-	}
-
-	size = partition_get_size(index);
-
-	/* Offset in sectors */
-	ptn = ptn / MMC_BOOT_RD_BLOCK_LEN;
-
-	/* Size in sectors */
-	size = size / MMC_BOOT_RD_BLOCK_LEN;
-
-	ret = mmc_wp((unsigned)ptn, (unsigned)size, 1);
-	if(ret)
-	{
-		dprintf(CRITICAL, "Failed to write protect: %s\n", name);
-		return 1;
-	}
-	return 0;
-}
diff --git a/platform/msm_shared/qtimer.c b/platform/msm_shared/qtimer.c
new file mode 100755
index 0000000..8af01f4
--- /dev/null
+++ b/platform/msm_shared/qtimer.c
@@ -0,0 +1,198 @@
+/* Copyright (c) 2011, Code Aurora Forum. 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 Code Aurora Forum, Inc. 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 <debug.h>
+#include <reg.h>
+#include <sys/types.h>
+
+#include <platform/timer.h>
+#include <platform/irqs.h>
+#include <platform/iomap.h>
+#include <platform/interrupts.h>
+#include <kernel/thread.h>
+
+#define QTMR_TIMER_CTRL_ENABLE          (1 << 0)
+#define QTMR_TIMER_CTRL_INT_MASK        (1 << 1)
+
+#define PLATFORM_TIMER_TYPE_PHYSICAL     1
+#define PLATFORM_TIMER_TYPE_VIRTUAL      2
+
+static platform_timer_callback timer_callback;
+static void *timer_arg;
+static time_t timer_interval;
+static unsigned int timer_type = PLATFORM_TIMER_TYPE_PHYSICAL;
+static volatile uint32_t ticks;
+
+static enum handler_return timer_irq(void *arg)
+{
+	ticks += timer_interval;
+
+	if (timer_type == PLATFORM_TIMER_TYPE_VIRTUAL)
+		__asm__("mcr p15, 0, %0, c14, c3, 0"::"r"(timer_interval));
+	else if (timer_type == PLATFORM_TIMER_TYPE_PHYSICAL)
+		__asm__("mcr p15, 0, %0, c14, c2, 0" : :"r" (timer_interval));
+
+	return timer_callback(timer_arg, ticks);
+}
+
+/* Programs the Virtual Down counter timer.
+ * interval : Counter ticks till expiry interrupt is fired.
+ */
+unsigned int platform_set_virtual_timer(uint32_t interval)
+{
+	uint32_t ctrl;
+
+	/* Program CTRL Register */
+	ctrl =0;
+	ctrl |= QTMR_TIMER_CTRL_ENABLE;
+	ctrl &= ~QTMR_TIMER_CTRL_INT_MASK;
+
+	__asm__("mcr p15, 0, %0, c14, c3, 1"::"r"(ctrl));
+
+	/* Set Virtual Down Counter */
+	__asm__("mcr p15, 0, %0, c14, c3, 0"::"r"(interval));
+
+	return INT_QTMR_VIRTUAL_TIMER_EXP;
+
+}
+
+/* Programs the Physical Secure Down counter timer.
+ * interval : Counter ticks till expiry interrupt is fired.
+ */
+unsigned int platform_set_physical_timer(uint32_t interval)
+{
+	uint32_t ctrl;
+
+	/* Program CTRL Register */
+	ctrl =0;
+	ctrl |= QTMR_TIMER_CTRL_ENABLE;
+	ctrl &= ~QTMR_TIMER_CTRL_INT_MASK;
+
+	__asm__("mcr p15, 0, %0, c14, c2, 1" : :"r" (ctrl));
+
+	/* Set Physical Down Counter */
+	__asm__("mcr p15, 0, %0, c14, c2, 0" : :"r" (interval));
+
+	return INT_QTMR_SECURE_PHYSICAL_TIMER_EXP;
+
+}
+
+
+status_t platform_set_periodic_timer(platform_timer_callback callback,
+	void *arg, time_t interval)
+{
+	uint32_t ppi_num;
+	unsigned long ctrl;
+	uint32_t tick_count = interval * platform_tick_rate() / 1000;
+
+	enter_critical_section();
+
+	timer_callback = callback;
+	timer_arg = arg;
+	timer_interval = interval;
+
+	if (timer_type == PLATFORM_TIMER_TYPE_VIRTUAL)
+		ppi_num = platform_set_virtual_timer(tick_count);
+	else if (timer_type == PLATFORM_TIMER_TYPE_PHYSICAL)
+		ppi_num = platform_set_physical_timer(tick_count);
+
+	register_int_handler(ppi_num, timer_irq, 0);
+	unmask_interrupt(ppi_num);
+
+	exit_critical_section();
+	return 0;
+}
+
+time_t current_time(void)
+{
+	return ticks;
+}
+
+void platform_uninit_timer(void)
+{
+	uint32_t ctrl;
+
+	unmask_interrupt(INT_DEBUG_TIMER_EXP);
+
+	/* program cntrl register */
+	ctrl =0;
+	ctrl |= ~QTMR_TIMER_CTRL_ENABLE;
+	ctrl &= QTMR_TIMER_CTRL_INT_MASK;
+
+	if (timer_type == PLATFORM_TIMER_TYPE_VIRTUAL)
+		__asm__("mcr p15, 0, %0, c14, c3, 1"::"r"(ctrl));
+	else if (timer_type == PLATFORM_TIMER_TYPE_PHYSICAL)
+		__asm__("mcr p15, 0, %0, c14, c2, 1" : :"r" (ctrl));
+
+}
+
+void mdelay(unsigned msecs)
+{
+	uint32_t phy_cnt_lo, phy_cnt_hi, cnt, timeout = 0;
+	uint64_t phy_cnt;
+	msecs = msecs *  platform_tick_rate() / 1000;
+
+	do{
+	/* read global counter */
+	__asm__("mrrc p15,0,%0,%1, c14":"=r"(phy_cnt_lo),"=r"(phy_cnt_hi));
+	phy_cnt = ((uint64_t)phy_cnt_hi << 32) | phy_cnt_lo;
+	/*Actual counter used in the simulation is only 32 bits
+	 * in reality the counter is actually 56 bits.
+	 */
+	cnt = phy_cnt & (uint32_t)~0;
+	if (timeout == 0)
+		timeout = cnt + msecs;
+	} while (cnt < timeout);
+
+}
+
+void udelay(unsigned usecs)
+{
+	uint32_t phy_cnt_lo, phy_cnt_hi, cnt, timeout = 0;
+	uint64_t phy_cnt;
+	usecs = (usecs * platform_tick_rate()) / 1000000;
+
+	do{
+	/* read global counter */
+	__asm__("mrrc p15,0,%0,%1, c14":"=r"(phy_cnt_lo),"=r"(phy_cnt_hi));
+	phy_cnt = ((uint64_t)phy_cnt_hi << 32) | phy_cnt_lo;
+
+	/*Actual counter used in the simulation is only 32 bits
+	 * in reality the counter is actually 56 bits.
+	 */
+	cnt = phy_cnt & (uint32_t)~0;
+	if (timeout == 0)
+		timeout = cnt + usecs;
+	} while (cnt < timeout);
+}
+
+/* Return current time in micro seconds */
+bigtime_t current_time_hires(void)
+{
+	return ticks * 1000000ULL;
+}
diff --git a/platform/msm_shared/rules.mk b/platform/msm_shared/rules.mk
index eb5635a..bf5134d 100644
--- a/platform/msm_shared/rules.mk
+++ b/platform/msm_shared/rules.mk
@@ -50,9 +50,12 @@
 ifeq ($(PLATFORM),msm7x27a)
 	OBJS += $(LOCAL_DIR)/uart.o \
 			$(LOCAL_DIR)/proc_comm.o \
-			$(LOCAL_DIR)/lcdc.o \
 			$(LOCAL_DIR)/mdp3.o \
-			$(LOCAL_DIR)/mipi_dsi.o
+			$(LOCAL_DIR)/mipi_dsi.o \
+			$(LOCAL_DIR)/crypto_eng.o \
+			$(LOCAL_DIR)/crypto_hash.o \
+			$(LOCAL_DIR)/certificate.o \
+			$(LOCAL_DIR)/image_verify.o
 endif
 
 ifeq ($(PLATFORM),msm7k)
diff --git a/platform/msm_shared/scm.c b/platform/msm_shared/scm.c
old mode 100644
new mode 100755
index 4905a9e..4c371d3
--- a/platform/msm_shared/scm.c
+++ b/platform/msm_shared/scm.c
@@ -249,3 +249,38 @@
 	scm_call(svc_id, cmd_id, cmd_buf, cmd_len, &resp_buf, resp_len);
 	return resp_buf;
 }
+
+/*
+ * Switches the CE1 channel between ADM and register usage.
+ * channel : AP_CE_REGISTER_USE, CE1 uses register interface
+ *         : AP_CE_ADM_USE, CE1 uses ADM interface
+ */
+uint8_t switch_ce_chn_cmd(enum ap_ce_channel_type channel)
+{
+	uint32_t svc_id;
+	uint32_t cmd_id;
+	void *cmd_buf;
+	size_t cmd_len;
+	size_t resp_len = 0;
+	uint8_t resp_buf;
+
+	struct {
+		uint32_t resource;
+		uint32_t chn_id;
+		}__PACKED switch_ce_chn_buf;
+
+	switch_ce_chn_buf.resource = TZ_RESOURCE_CE_AP;
+	switch_ce_chn_buf.chn_id = channel;
+	cmd_buf = (void *)&switch_ce_chn_buf;
+	cmd_len = sizeof(switch_ce_chn_buf);
+
+	/*response */
+	resp_len = sizeof(resp_buf);
+
+	svc_id = SCM_SVC_CE_CHN_SWITCH_ID;
+	cmd_id = SCM_CE_CHN_SWITCH_ID;
+
+	scm_call(svc_id, cmd_id, cmd_buf, cmd_len, &resp_buf, resp_len);
+	return resp_buf;
+}
+
diff --git a/platform/msm_shared/smem.h b/platform/msm_shared/smem.h
index e3a1389..0813be3 100644
--- a/platform/msm_shared/smem.h
+++ b/platform/msm_shared/smem.h
@@ -222,6 +222,8 @@
 
 	SMEM_POWER_ON_STATUS_INFO = 403,
 
+	SMEM_RLOCK_AREA = 404,
+
 	SMEM_BOOT_INFO_FOR_APPS = 418,
 
 	SMEM_FIRST_VALID_TYPE = SMEM_SPINLOCK_ARRAY,
diff --git a/platform/msm_shared/uart_dm.c b/platform/msm_shared/uart_dm.c
index 614bd56..d3f2a05 100644
--- a/platform/msm_shared/uart_dm.c
+++ b/platform/msm_shared/uart_dm.c
@@ -70,22 +70,21 @@
                                               }
 
 /* Static Function Prototype Declarations */
-static unsigned int msm_boot_uart_dm_gsbi_init(uint8_t id);
 static unsigned int msm_boot_uart_replace_lr_with_cr(char *data_in,
 						     int num_of_chars,
 						     char *data_out,
 						     int *num_of_chars_out);
-static unsigned int msm_boot_uart_dm_init(uint8_t id);
-static unsigned int msm_boot_uart_dm_read(uint8_t id, unsigned int *data,
-					  int wait);
-static unsigned int msm_boot_uart_dm_write(uint8_t id, char *data,
-					   unsigned int num_of_chars);
-static unsigned int msm_boot_uart_dm_init_rx_transfer(uint8_t id);
-static unsigned int msm_boot_uart_dm_reset(uint8_t id);
+static unsigned int msm_boot_uart_dm_init(uint32_t base);
+static unsigned int msm_boot_uart_dm_read(uint32_t base, unsigned int *data,
+										  int wait);
+static unsigned int msm_boot_uart_dm_write(uint32_t base, char *data,
+										   unsigned int num_of_chars);
+static unsigned int msm_boot_uart_dm_init_rx_transfer(uint32_t base);
+static unsigned int msm_boot_uart_dm_reset(uint32_t base);
 
 /* Keep track of gsbi vs port mapping.
  */
-static uint8_t gsbi_lookup[4];
+static uint32_t gsbi_lookup[4];
 
 /* Extern functions */
 void udelay(unsigned usecs);
@@ -120,47 +119,15 @@
 }
 
 /*
- * Initialize and configure GSBI for operation
- */
-static unsigned int msm_boot_uart_dm_gsbi_init(uint8_t id)
-{
-	/* Configure the uart clock */
-	clock_config_uart_dm(id);
-	dsb();
-
-	/* Configure GPIO to provide connectivity between GSBI
-	   product ports and chip pads */
-	gpio_config_uart_dm(id);
-	dsb();
-
-	/* Configure Data Mover for GSBI operation.
-	 * Currently not supported. */
-
-	/* Configure GSBI for UART_DM protocol.
-	 * I2C on 2 ports, UART (without HS flow control) on the other 2. */
-	writel(GSBI_PROTOCOL_CODE_I2C_UART << GSBI_CTRL_REG_PROTOCOL_CODE_S,
-	       GSBI_CTRL_REG(id));
-	dsb();
-
-	/* Configure clock selection register for tx and rx rates.
-	 * Selecting 115.2k for both RX and TX.
-	 */
-	writel(UART_DM_CLK_RX_TX_BIT_RATE, MSM_BOOT_UART_DM_CSR(id));
-	dsb();
-
-	return MSM_BOOT_UART_DM_E_SUCCESS;
-}
-
-/*
  * Reset the UART
  */
-static unsigned int msm_boot_uart_dm_reset(uint8_t id)
+static unsigned int msm_boot_uart_dm_reset(uint32_t base)
 {
-	writel(MSM_BOOT_UART_DM_CMD_RESET_RX, MSM_BOOT_UART_DM_CR(id));
-	writel(MSM_BOOT_UART_DM_CMD_RESET_TX, MSM_BOOT_UART_DM_CR(id));
-	writel(MSM_BOOT_UART_DM_CMD_RESET_ERR_STAT, MSM_BOOT_UART_DM_CR(id));
-	writel(MSM_BOOT_UART_DM_CMD_RES_TX_ERR, MSM_BOOT_UART_DM_CR(id));
-	writel(MSM_BOOT_UART_DM_CMD_RES_STALE_INT, MSM_BOOT_UART_DM_CR(id));
+	writel(MSM_BOOT_UART_DM_CMD_RESET_RX, MSM_BOOT_UART_DM_CR(base));
+	writel(MSM_BOOT_UART_DM_CMD_RESET_TX, MSM_BOOT_UART_DM_CR(base));
+	writel(MSM_BOOT_UART_DM_CMD_RESET_ERR_STAT, MSM_BOOT_UART_DM_CR(base));
+	writel(MSM_BOOT_UART_DM_CMD_RES_TX_ERR, MSM_BOOT_UART_DM_CR(base));
+	writel(MSM_BOOT_UART_DM_CMD_RES_STALE_INT, MSM_BOOT_UART_DM_CR(base));
 
 	return MSM_BOOT_UART_DM_E_SUCCESS;
 }
@@ -168,42 +135,39 @@
 /*
  * Initialize UART_DM - configure clock and required registers.
  */
-static unsigned int msm_boot_uart_dm_init(uint8_t id)
+static unsigned int msm_boot_uart_dm_init(uint32_t uart_dm_base)
 {
-	/* Configure GSBI for uart dm */
-	msm_boot_uart_dm_gsbi_init(id);
-
 	/* Configure UART mode registers MR1 and MR2 */
 	/* Hardware flow control isn't supported */
-	writel(0x0, MSM_BOOT_UART_DM_MR1(id));
+	writel(0x0, MSM_BOOT_UART_DM_MR1(uart_dm_base));
 
 	/* 8-N-1 configuration: 8 data bits - No parity - 1 stop bit */
-	writel(MSM_BOOT_UART_DM_8_N_1_MODE, MSM_BOOT_UART_DM_MR2(id));
+	writel(MSM_BOOT_UART_DM_8_N_1_MODE, MSM_BOOT_UART_DM_MR2(uart_dm_base));
 
 	/* Configure Interrupt Mask register IMR */
-	writel(MSM_BOOT_UART_DM_IMR_ENABLED, MSM_BOOT_UART_DM_IMR(id));
+	writel(MSM_BOOT_UART_DM_IMR_ENABLED, MSM_BOOT_UART_DM_IMR(uart_dm_base));
 
 	/* Configure Tx and Rx watermarks configuration registers */
 	/* TX watermark value is set to 0 - interrupt is generated when
 	 * FIFO level is less than or equal to 0 */
-	writel(MSM_BOOT_UART_DM_TFW_VALUE, MSM_BOOT_UART_DM_TFWR(id));
+	writel(MSM_BOOT_UART_DM_TFW_VALUE, MSM_BOOT_UART_DM_TFWR(uart_dm_base));
 
 	/* RX watermark value */
-	writel(MSM_BOOT_UART_DM_RFW_VALUE, MSM_BOOT_UART_DM_RFWR(id));
+	writel(MSM_BOOT_UART_DM_RFW_VALUE, MSM_BOOT_UART_DM_RFWR(uart_dm_base));
 
 	/* Configure Interrupt Programming Register */
 	/* Set initial Stale timeout value */
-	writel(MSM_BOOT_UART_DM_STALE_TIMEOUT_LSB, MSM_BOOT_UART_DM_IPR(id));
+	writel(MSM_BOOT_UART_DM_STALE_TIMEOUT_LSB, MSM_BOOT_UART_DM_IPR(uart_dm_base));
 
 	/* Configure IRDA if required */
 	/* Disabling IRDA mode */
-	writel(0x0, MSM_BOOT_UART_DM_IRDA(id));
+	writel(0x0, MSM_BOOT_UART_DM_IRDA(uart_dm_base));
 
 	/* Configure and enable sim interface if required */
 
 	/* Configure hunt character value in HCR register */
 	/* Keep it in reset state */
-	writel(0x0, MSM_BOOT_UART_DM_HCR(id));
+	writel(0x0, MSM_BOOT_UART_DM_HCR(uart_dm_base));
 
 	/* Configure Rx FIFO base address */
 	/* Both TX/RX shares same SRAM and default is half-n-half.
@@ -212,18 +176,18 @@
 	 * We have found RAM_ADDR_WIDTH = 0x7f */
 
 	/* Issue soft reset command */
-	msm_boot_uart_dm_reset(id);
+	msm_boot_uart_dm_reset(uart_dm_base);
 
 	/* Enable/Disable Rx/Tx DM interfaces */
 	/* Data Mover not currently utilized. */
-	writel(0x0, MSM_BOOT_UART_DM_DMEN(id));
+	writel(0x0, MSM_BOOT_UART_DM_DMEN(uart_dm_base));
 
 	/* Enable transmitter and receiver */
-	writel(MSM_BOOT_UART_DM_CR_RX_ENABLE, MSM_BOOT_UART_DM_CR(id));
-	writel(MSM_BOOT_UART_DM_CR_TX_ENABLE, MSM_BOOT_UART_DM_CR(id));
+	writel(MSM_BOOT_UART_DM_CR_RX_ENABLE, MSM_BOOT_UART_DM_CR(uart_dm_base));
+	writel(MSM_BOOT_UART_DM_CR_TX_ENABLE, MSM_BOOT_UART_DM_CR(uart_dm_base));
 
 	/* Initialize Receive Path */
-	msm_boot_uart_dm_init_rx_transfer(id);
+	msm_boot_uart_dm_init_rx_transfer(uart_dm_base);
 
 	return MSM_BOOT_UART_DM_E_SUCCESS;
 }
@@ -231,12 +195,12 @@
 /*
  * Initialize Receive Path
  */
-static unsigned int msm_boot_uart_dm_init_rx_transfer(uint8_t id)
+static unsigned int msm_boot_uart_dm_init_rx_transfer(uint32_t uart_dm_base)
 {
-	writel(MSM_BOOT_UART_DM_GCMD_DIS_STALE_EVT, MSM_BOOT_UART_DM_CR(id));
-	writel(MSM_BOOT_UART_DM_CMD_RES_STALE_INT, MSM_BOOT_UART_DM_CR(id));
-	writel(MSM_BOOT_UART_DM_DMRX_DEF_VALUE, MSM_BOOT_UART_DM_DMRX(id));
-	writel(MSM_BOOT_UART_DM_GCMD_ENA_STALE_EVT, MSM_BOOT_UART_DM_CR(id));
+	writel(MSM_BOOT_UART_DM_GCMD_DIS_STALE_EVT, MSM_BOOT_UART_DM_CR(uart_dm_base));
+	writel(MSM_BOOT_UART_DM_CMD_RES_STALE_INT, MSM_BOOT_UART_DM_CR(uart_dm_base));
+	writel(MSM_BOOT_UART_DM_DMRX_DEF_VALUE, MSM_BOOT_UART_DM_DMRX(uart_dm_base));
+	writel(MSM_BOOT_UART_DM_GCMD_ENA_STALE_EVT, MSM_BOOT_UART_DM_CR(uart_dm_base));
 
 	return MSM_BOOT_UART_DM_E_SUCCESS;
 }
@@ -246,7 +210,7 @@
  * Reads a word from the RX FIFO.
  */
 static unsigned int
-msm_boot_uart_dm_read(uint8_t id, unsigned int *data, int wait)
+msm_boot_uart_dm_read(uint32_t base, unsigned int *data, int wait)
 {
 	static int rx_last_snap_count = 0;
 	static int rx_chars_read_since_last_xfer = 0;
@@ -256,7 +220,7 @@
 	}
 
 	/* We will be polling RXRDY status bit */
-	while (!(readl(MSM_BOOT_UART_DM_SR(id)) & MSM_BOOT_UART_DM_SR_RXRDY)) {
+	while (!(readl(MSM_BOOT_UART_DM_SR(base)) & MSM_BOOT_UART_DM_SR_RXRDY)) {
 		/* if this is not a blocking call, we'll just return */
 		if (!wait) {
 			return MSM_BOOT_UART_DM_E_RX_NOT_READY;
@@ -264,13 +228,13 @@
 	}
 
 	/* Check for Overrun error. We'll just reset Error Status */
-	if (readl(MSM_BOOT_UART_DM_SR(id)) & MSM_BOOT_UART_DM_SR_UART_OVERRUN) {
+	if (readl(MSM_BOOT_UART_DM_SR(base)) & MSM_BOOT_UART_DM_SR_UART_OVERRUN) {
 		writel(MSM_BOOT_UART_DM_CMD_RESET_ERR_STAT,
-		       MSM_BOOT_UART_DM_CR(id));
+		       MSM_BOOT_UART_DM_CR(base));
 	}
 
 	/* RX FIFO is ready; read a word. */
-	*data = readl(MSM_BOOT_UART_DM_RF(id, 0));
+	*data = readl(MSM_BOOT_UART_DM_RF(base, 0));
 
 	/* increment the total count of chars we've read so far */
 	rx_chars_read_since_last_xfer += 4;
@@ -284,15 +248,15 @@
 	/* If RX transfer has not ended yet */
 	if (rx_last_snap_count == 0) {
 		/* Check if we've received stale event */
-		if (readl(MSM_BOOT_UART_DM_MISR(id)) & MSM_BOOT_UART_DM_RXSTALE) {
+		if (readl(MSM_BOOT_UART_DM_MISR(base)) & MSM_BOOT_UART_DM_RXSTALE) {
 			/* Send command to reset stale interrupt */
 			writel(MSM_BOOT_UART_DM_CMD_RES_STALE_INT,
-			       MSM_BOOT_UART_DM_CR(id));
+			       MSM_BOOT_UART_DM_CR(base));
 		}
 
 		/* Check if we haven't read more than DMRX value */
 		else if ((unsigned int)rx_chars_read_since_last_xfer <
-			 readl(MSM_BOOT_UART_DM_DMRX(id))) {
+			 readl(MSM_BOOT_UART_DM_DMRX(base))) {
 			/* We can still continue reading before initializing RX transfer */
 			return MSM_BOOT_UART_DM_E_SUCCESS;
 		}
@@ -301,7 +265,7 @@
 
 		/* Read UART_DM_RX_TOTAL_SNAP register to know how many valid chars
 		 * we've read so far since last transfer */
-		rx_last_snap_count = readl(MSM_BOOT_UART_DM_RX_TOTAL_SNAP(id));
+		rx_last_snap_count = readl(MSM_BOOT_UART_DM_RX_TOTAL_SNAP(base));
 
 	}
 
@@ -311,7 +275,7 @@
 		return MSM_BOOT_UART_DM_E_SUCCESS;
 	}
 
-	msm_boot_uart_dm_init_rx_transfer(id);
+	msm_boot_uart_dm_init_rx_transfer(base);
 	rx_last_snap_count = 0;
 	rx_chars_read_since_last_xfer = 0;
 
@@ -322,7 +286,7 @@
  * UART transmit operation
  */
 static unsigned int
-msm_boot_uart_dm_write(uint8_t id, char *data, unsigned int num_of_chars)
+msm_boot_uart_dm_write(uint32_t base, char *data, unsigned int num_of_chars)
 {
 	unsigned int tx_word_count = 0;
 	unsigned int tx_char_left = 0, tx_char = 0;
@@ -349,9 +313,9 @@
 
 	/* Check if transmit FIFO is empty.
 	 * If not we'll wait for TX_READY interrupt. */
-	if (!(readl(MSM_BOOT_UART_DM_SR(id)) & MSM_BOOT_UART_DM_SR_TXEMT)) {
+	if (!(readl(MSM_BOOT_UART_DM_SR(base)) & MSM_BOOT_UART_DM_SR_TXEMT)) {
 		while (!
-		       (readl(MSM_BOOT_UART_DM_ISR(id)) &
+		       (readl(MSM_BOOT_UART_DM_ISR(base)) &
 			MSM_BOOT_UART_DM_TX_READY)) {
 			udelay(1);
 			/* Kick watchdog? */
@@ -360,10 +324,10 @@
 
 	/* We are here. FIFO is ready to be written. */
 	/* Write number of characters to be written */
-	writel(num_of_chars, MSM_BOOT_UART_DM_NO_CHARS_FOR_TX(id));
+	writel(num_of_chars, MSM_BOOT_UART_DM_NO_CHARS_FOR_TX(base));
 
 	/* Clear TX_READY interrupt */
-	writel(MSM_BOOT_UART_DM_GCMD_RES_TX_RDY_INT, MSM_BOOT_UART_DM_CR(id));
+	writel(MSM_BOOT_UART_DM_GCMD_RES_TX_RDY_INT, MSM_BOOT_UART_DM_CR(base));
 
 	/* We use four-character word FIFO. So we need to divide data into
 	 * four characters and write in UART_DM_TF register */
@@ -377,13 +341,13 @@
 
 		/* Wait till TX FIFO has space */
 		while (!
-		       (readl(MSM_BOOT_UART_DM_SR(id)) &
+		       (readl(MSM_BOOT_UART_DM_SR(base)) &
 			MSM_BOOT_UART_DM_SR_TXRDY)) {
 			udelay(1);
 		}
 
 		/* TX FIFO has space. Write the chars */
-		writel(tx_word, MSM_BOOT_UART_DM_TF(id, 0));
+		writel(tx_word, MSM_BOOT_UART_DM_TF(base, 0));
 		tx_char_left = num_of_chars - (i + 1) * 4;
 		tx_data = tx_data + 4;
 	}
@@ -395,16 +359,39 @@
  * existing uart implemention. These functions are being called to initialize
  * UART and print debug messages in bootloader.
  */
-void uart_init(uint8_t gsbi_id)
+void uart_dm_init(uint8_t id, uint32_t gsbi_base, uint32_t uart_dm_base)
 {
 	static uint8_t port = 0;
 	char *data = "Android Bootloader - UART_DM Initialized!!!\n";
 
-	msm_boot_uart_dm_init(gsbi_id);
-	msm_boot_uart_dm_write(gsbi_id, data, 44);
+	/* Configure the uart clock */
+	clock_config_uart_dm(id);
+	dsb();
+
+	/* Configure GPIO to provide connectivity between GSBI
+	   product ports and chip pads */
+	gpio_config_uart_dm(id);
+	dsb();
+
+	/* Configure GSBI for UART_DM protocol.
+	 * I2C on 2 ports, UART (without HS flow control) on the other 2. */
+	writel(GSBI_PROTOCOL_CODE_I2C_UART << GSBI_CTRL_REG_PROTOCOL_CODE_S,
+	       GSBI_CTRL_REG(gsbi_base));
+	dsb();
+
+	/* Configure clock selection register for tx and rx rates.
+	 * Selecting 115.2k for both RX and TX.
+	 */
+	writel(UART_DM_CLK_RX_TX_BIT_RATE, MSM_BOOT_UART_DM_CSR(uart_dm_base));
+	dsb();
+
+	/* Intialize UART_DM */
+	msm_boot_uart_dm_init(uart_dm_base);
+
+	msm_boot_uart_dm_write(uart_dm_base, data, 44);
 
 	ASSERT(port < ARRAY_SIZE(gsbi_lookup));
-	gsbi_lookup[port++] = gsbi_id;
+	gsbi_lookup[port++] = uart_dm_base;
 
 	/* Set UART init flag */
 	uart_init_flag = 1;
@@ -417,13 +404,13 @@
  */
 int uart_putc(int port, char c)
 {
-	uint8_t gsbi_id = gsbi_lookup[port];
+	uint32_t gsbi_base = gsbi_lookup[port];
 
 	/* Don't do anything if UART is not initialized */
 	if (!uart_init_flag)
-		return;
+		return -1;
 
-	msm_boot_uart_dm_write(gsbi_id, &c, 1);
+	msm_boot_uart_dm_write(gsbi_base, &c, 1);
 
 	return 0;
 }
@@ -436,16 +423,16 @@
 {
 	int byte;
 	static unsigned int word = 0;
-	uint8_t gsbi_id = gsbi_lookup[port];
+	uint32_t gsbi_base = gsbi_lookup[port];
 
 	/* Don't do anything if UART is not initialized */
 	if (!uart_init_flag)
-		return;
+		return -1;
 
 	if (!word) {
 		/* Read from FIFO only if it's a first read or all the four
 		 * characters out of a word have been read */
-		if (msm_boot_uart_dm_read(gsbi_id, &word, wait) !=
+		if (msm_boot_uart_dm_read(gsbi_base, &word, wait) !=
 		    MSM_BOOT_UART_DM_E_SUCCESS) {
 			return -1;
 		}
diff --git a/target/mdm9615/init.c b/target/mdm9615/init.c
index d1fc7b6..c285735 100644
--- a/target/mdm9615/init.c
+++ b/target/mdm9615/init.c
@@ -177,8 +177,8 @@
 {
 	int ret;
 	ret = fake_key_get_state();
-	/* Want to trigger when dip switch is off */
-	return (!ret);
+	/* Want to trigger when dip switch is on */
+	return (ret);
 }
 
 void update_ptable_modem_partitions(void)
diff --git a/target/mdm9615/keypad.c b/target/mdm9615/keypad.c
index 93eeeeb..79855cf 100644
--- a/target/mdm9615/keypad.c
+++ b/target/mdm9615/keypad.c
@@ -30,17 +30,21 @@
 #include <platform/gpio.h>
 #include <platform/iomap.h>
 
+/* GPIO that controls the Dip Switch
+ * for FASTBOOT.
+ */
+#define DIP_SWITCH_GPIO        49
 /*
  * Fake keypad for 9x15
- * Returns 1 if dip switch is on, 0 if off
+ * Returns 0 if dip switch is off, 1 if on
  */
 int fake_key_get_state(void)
 {
 	int ret;
 	/* GPIO 49 connects to Boot Config5 */
-	gpio_tlmm_config(49, 0, GPIO_OUTPUT, GPIO_PULL_DOWN,
+	gpio_tlmm_config(DIP_SWITCH_GPIO, 0, GPIO_OUTPUT, GPIO_PULL_DOWN,
 			 GPIO_2MA, GPIO_ENABLE);
 
-	ret = readl(GPIO_IN_OUT_ADDR(49));
+	ret = readl(GPIO_IN_OUT_ADDR(DIP_SWITCH_GPIO));
 	return ret;
 }
diff --git a/target/msm7627_surf/rules.mk b/target/msm7627_surf/rules.mk
index f9e8104..7bfa2e8 100644
--- a/target/msm7627_surf/rules.mk
+++ b/target/msm7627_surf/rules.mk
@@ -13,6 +13,7 @@
 KERNEL_ADDR      := BASE_ADDR+0x00008000
 RAMDISK_ADDR     := BASE_ADDR+0x01000000
 SCRATCH_ADDR     := BASE_ADDR+0xA00000
+LCDC_FB_ADDR     := 0x0D300000
 
 KEYS_USE_GPIO_KEYPAD := 1
 
@@ -33,7 +34,8 @@
 	TAGS_ADDR=$(TAGS_ADDR) \
 	KERNEL_ADDR=$(KERNEL_ADDR) \
 	RAMDISK_ADDR=$(RAMDISK_ADDR) \
-	SCRATCH_ADDR=$(SCRATCH_ADDR)
+	SCRATCH_ADDR=$(SCRATCH_ADDR) \
+	LCDC_FB_ADDR=$(LCDC_FB_ADDR)
 
 
 OBJS += \
diff --git a/target/msm7627_surf/tools/makefile b/target/msm7627_surf/tools/makefile
index f4fcd56..94357a2 100644
--- a/target/msm7627_surf/tools/makefile
+++ b/target/msm7627_surf/tools/makefile
@@ -38,3 +38,4 @@
 
 mkheader: $(SRC_DIR)/mkheader.c
 	${COMPILER} $(SRC_DIR)/mkheader.c -o $(SRC_DIR)/mkheader
+	cp -f $(SRC_DIR)/mkheader $(BUILDDIR)/mkheader
diff --git a/target/msm7627a/atags.c b/target/msm7627a/atags.c
index f96c34e..8425916 100644
--- a/target/msm7627a/atags.c
+++ b/target/msm7627a/atags.c
@@ -70,5 +70,5 @@
 
 unsigned target_get_max_flash_size(void)
 {
-	return (208 * 1024 * 1024);
+	return (253 * 1024 * 1024);
 }
diff --git a/target/msm7627a/include/target/display.h b/target/msm7627a/include/target/display.h
index 5ce673b..adb7e7a 100644
--- a/target/msm7627a/include/target/display.h
+++ b/target/msm7627a/include/target/display.h
@@ -68,7 +68,7 @@
 #define MIPI_VSYNC_BACK_PORCH_LINES_HVGA  50
 #define MIPI_VSYNC_FRONT_PORCH_LINES_HVGA 101
 
-#define MIPI_FB_ADDR  0x0D300000
+#define MIPI_FB_ADDR  0x20000000
 
 extern int mipi_dsi_phy_init(struct mipi_dsi_panel_config *);
 extern void config_renesas_dsi_video_mode(void);
diff --git a/target/msm7627a/init.c b/target/msm7627a/init.c
index 875781d..7af1875 100644
--- a/target/msm7627a/init.c
+++ b/target/msm7627a/init.c
@@ -48,6 +48,7 @@
 #define MSM7X25A_SURF	3772
 #define MSM7X25A_FFA	3771
 #define MSM7X27A_EVB	3934
+#define MSM7X27A_QRD3	4005
 
 #define LINUX_MACHTYPE  MSM7X27A_SURF
 
@@ -81,7 +82,7 @@
 	 },
 	{
 	 .start = DIFF_START_ADDR,
-	 .length = 208 /* In MB */ ,
+	 .length = 253 /* In MB */ ,
 	 .name = "system",
 	 },
 	{
@@ -264,7 +265,10 @@
 				hw_platform = MSM7X27A_FFA;
 			break;
 		case 0xB:
-			hw_platform = MSM7X27A_QRD1;
+			if(target_is_emmc_boot())
+				hw_platform = MSM7X27A_QRD1;
+			else
+				hw_platform = MSM7X27A_QRD3;
 			break;
 		case 0xC:
 			hw_platform = MSM7X27A_EVB;
@@ -418,3 +422,19 @@
 	else
 		return 0;
 }
+
+int machine_is_7x27a_qrd3()
+{
+	if (board_machtype() == MSM7X27A_QRD3)
+		return 1;
+	else
+		return 0;
+}
+
+int machine_is_7x27a_qrd1()
+{
+	if (board_machtype() == MSM7X27A_QRD1)
+		return 1;
+	else
+		return 0;
+}
diff --git a/target/msm7627a/keypad.c b/target/msm7627a/keypad.c
index 386a40a..7244133 100644
--- a/target/msm7627a/keypad.c
+++ b/target/msm7627a/keypad.c
@@ -34,8 +34,6 @@
 #include <dev/ssbi.h>
 #include <dev/gpio_keypad.h>
 
-#define LINUX_MACHTYPE_7x27A_QRD 3756
-
 #define ARRAY_SIZE(x) (sizeof(x)/sizeof((x)[0]))
 
 /* don't turn this on without updating the ffa support */
@@ -138,10 +136,7 @@
 
 void keypad_init(void)
 {
-	unsigned int mach_id;
-	mach_id = board_machtype();
-
-	if (mach_id == LINUX_MACHTYPE_7x27A_QRD)
+	if (machine_is_7x27a_qrd1() || machine_is_7x27a_qrd3())
 		gpio_keypad_init(&halibut_keypad_info_qrd);
 	else if (machine_is_7x27a_evb())
 		gpio_keypad_init(&halibut_keypad_info_evb);
diff --git a/target/msm7627a/rules.mk b/target/msm7627a/rules.mk
index d9b4fed..555ba90 100644
--- a/target/msm7627a/rules.mk
+++ b/target/msm7627a/rules.mk
@@ -21,6 +21,7 @@
 DEFINES += DISPLAY_SPLASH_SCREEN=1
 DEFINES += DISPLAY_TYPE_MIPI=1
 DEFINES += DISPLAY_MIPI_PANEL_RENESAS=1
+DEFINES += NO_CRYPTO_ENG=1
 
 MODULES += \
 	dev/keys \
diff --git a/target/msm7627a/tools/makefile b/target/msm7627a/tools/makefile
index f4fcd56..94357a2 100644
--- a/target/msm7627a/tools/makefile
+++ b/target/msm7627a/tools/makefile
@@ -38,3 +38,4 @@
 
 mkheader: $(SRC_DIR)/mkheader.c
 	${COMPILER} $(SRC_DIR)/mkheader.c -o $(SRC_DIR)/mkheader
+	cp -f $(SRC_DIR)/mkheader $(BUILDDIR)/mkheader
diff --git a/target/msm7630_surf/init.c b/target/msm7630_surf/init.c
index 234cc25..9ebcc76 100644
--- a/target/msm7630_surf/init.c
+++ b/target/msm7630_surf/init.c
@@ -41,6 +41,9 @@
 #include <mmc.h>
 #include <platform/iomap.h>
 #include <platform/machtype.h>
+#ifdef TARGET_USES_RSPIN_LOCK
+#include <platform/remote_spinlock.h>
+#endif
 #include <platform.h>
 
 #define MSM8255_ID                 74
@@ -68,7 +71,7 @@
 static struct ptentry board_part_list[] = {
 	{
 	 .start = 0,
-	 .length = 5 /* In MB */ ,
+	 .length = 10 /* In MB */ ,
 	 .name = "boot",
 	 },
 	{
@@ -103,7 +106,7 @@
 	 },
 	{
 	 .start = DIFF_START_ADDR,
-	 .length = 5 /* In MB */ ,
+	 .length = 10 /* In MB */ ,
 	 .name = "recovery",
 	 },
 };
@@ -179,6 +182,11 @@
 
 	dprintf(INFO, "target_init()\n");
 
+#ifdef TARGET_USES_RSPIN_LOCK
+	if(remote_spinlock_init(&rlock))
+		dprintf(SPEW,"Failed to Initialize remote spin locks\n");
+#endif
+
 #if (!ENABLE_NANDWRITE)
 	keys_init();
 	keypad_init();
diff --git a/target/msm7630_surf/rules.mk b/target/msm7630_surf/rules.mk
index 8b377ed..801d427 100644
--- a/target/msm7630_surf/rules.mk
+++ b/target/msm7630_surf/rules.mk
@@ -14,13 +14,15 @@
 RAMDISK_ADDR         := BASE_ADDR+0x01000000
 SCRATCH_ADDR         := 0x08008000
 FASTBOOT_BUF_SIZE    := 0x10000000
+LCDC_FB_ADDR         := 0x08008000
 
 KEYS_USE_GPIO_KEYPAD := 1
 
-DEFINES += DISPLAY_SPLASH_SCREEN=0
+DEFINES += DISPLAY_SPLASH_SCREEN=1
 DEFINES += DISPLAY_TYPE_MDDI=0
-DEFINES += DISPLAY_TYPE_LCDC=0
+DEFINES += DISPLAY_TYPE_LCDC=1
 DEFINES += MMC_BOOT_ADM=0
+DEFINES += TARGET_USES_RSPIN_LOCK=1
 
 MODULES += \
 	dev/keys \
@@ -35,10 +37,11 @@
 	KERNEL_ADDR=$(KERNEL_ADDR) \
 	RAMDISK_ADDR=$(RAMDISK_ADDR) \
 	SCRATCH_ADDR=$(SCRATCH_ADDR) \
-	FASTBOOT_BUF_SIZE=$(FASTBOOT_BUF_SIZE)
+	FASTBOOT_BUF_SIZE=$(FASTBOOT_BUF_SIZE) \
+	LCDC_FB_ADDR=$(LCDC_FB_ADDR)
 
 
 OBJS += \
 	$(LOCAL_DIR)/init.o \
 	$(LOCAL_DIR)/atags.o \
-	$(LOCAL_DIR)/keypad.o \
+	$(LOCAL_DIR)/keypad.o
diff --git a/target/msm7630_surf/tools/makefile b/target/msm7630_surf/tools/makefile
index aedda70..5a33035 100644
--- a/target/msm7630_surf/tools/makefile
+++ b/target/msm7630_surf/tools/makefile
@@ -41,3 +41,4 @@
 
 mkheader: $(SRC_DIR)/mkheader.c
 	${COMPILER} -DMEMBASE=$(MEMBASE) $(SRC_DIR)/mkheader.c -o $(SRC_DIR)/mkheader
+	cp -f $(SRC_DIR)/mkheader $(BUILDDIR)/mkheader
diff --git a/target/msm8660_surf/tools/makefile b/target/msm8660_surf/tools/makefile
index aedda70..5a33035 100644
--- a/target/msm8660_surf/tools/makefile
+++ b/target/msm8660_surf/tools/makefile
@@ -41,3 +41,4 @@
 
 mkheader: $(SRC_DIR)/mkheader.c
 	${COMPILER} -DMEMBASE=$(MEMBASE) $(SRC_DIR)/mkheader.c -o $(SRC_DIR)/mkheader
+	cp -f $(SRC_DIR)/mkheader $(BUILDDIR)/mkheader
diff --git a/target/msm8960/init.c b/target/msm8960/init.c
index d6afcec..0673dea 100644
--- a/target/msm8960/init.c
+++ b/target/msm8960/init.c
@@ -44,6 +44,7 @@
 #include <target.h>
 #include <platform.h>
 #include <baseband.h>
+#include <uart_dm.h>
 
 /* 8960 */
 #define LINUX_MACHTYPE_8960_SIM     3230
@@ -66,6 +67,9 @@
 /* 8064 */
 #define LINUX_MACHTYPE_8064_SIM     3572
 #define LINUX_MACHTYPE_8064_RUMI3   3679
+#define LINUX_MACHTYPE_8064_CDP     3948
+#define LINUX_MACHTYPE_8064_MTP     3949
+#define LINUX_MACHTYPE_8064_LIQUID  3951
 
 extern void dmb(void);
 extern void msm8960_keypad_init(void);
@@ -81,14 +85,14 @@
 static pm8921_dev_t pmic;
 
 static void target_detect(void);
-static uint8_t get_uart_gsbi(void);
+static void target_uart_init(void);
 
 void target_early_init(void)
 {
 	target_detect();
 
 #if WITH_DEBUG_UART
-	uart_init(get_uart_gsbi());
+	target_uart_init();
 #endif
 }
 
@@ -128,6 +132,10 @@
 	{
 		msm8930_keypad_init();
 	}
+	else if(platform_id == APQ8064)
+	{
+		apq8064_keypad_init();
+	}
 
 	/* Display splash screen if enabled */
 #if DISPLAY_SPLASH_SCREEN
@@ -162,6 +170,11 @@
 	return target_id;
 }
 
+unsigned board_platform_id(void)
+{
+	return platform_id;
+}
+
 void target_detect(void)
 {
 	struct smem_board_info_v6 board_info_v6;
@@ -236,10 +249,16 @@
 	} else if (platform_id == APQ8064) {
 		switch (id) {
 		case HW_PLATFORM_SURF:
-			target_id = LINUX_MACHTYPE_8064_SIM;
+			target_id = LINUX_MACHTYPE_8064_CDP;
+			break;
+		case HW_PLATFORM_MTP:
+			target_id = LINUX_MACHTYPE_8064_MTP;
+			break;
+		case HW_PLATFORM_LIQUID:
+			target_id = LINUX_MACHTYPE_8064_LIQUID;
 			break;
 		default:
-			target_id = LINUX_MACHTYPE_8064_RUMI3;
+			target_id = LINUX_MACHTYPE_8064_CDP;
 		}
 	} else {
 		dprintf(CRITICAL, "platform_id (%d) is not identified.\n",
@@ -274,6 +293,9 @@
 				else if (board_info_v6.board_info_v3.msm_id ==
 					 APQ8060)
 					baseband = BASEBAND_APQ;
+				else if (board_info_v6.board_info_v3.msm_id ==
+					 APQ8064)
+					baseband = BASEBAND_APQ;
 				else
 					baseband = BASEBAND_MSM;
 			}
@@ -359,7 +381,7 @@
 	pm8921_boot_done();
 }
 
-uint8_t get_uart_gsbi(void)
+void target_uart_init(void)
 {
 	switch (target_id) {
 	case LINUX_MACHTYPE_8960_SIM:
@@ -370,23 +392,32 @@
 	case LINUX_MACHTYPE_8960_APQ:
 	case LINUX_MACHTYPE_8960_LIQUID:
 
-		return GSBI_ID_5;
+		uart_dm_init(5, 0x16400000, 0x16440000);
+		break;
 
 	case LINUX_MACHTYPE_8930_CDP:
 	case LINUX_MACHTYPE_8930_MTP:
 	case LINUX_MACHTYPE_8930_FLUID:
 
-		return GSBI_ID_5;
+		uart_dm_init(5, 0x16400000, 0x16440000);
+		break;
 
 	case LINUX_MACHTYPE_8064_SIM:
 	case LINUX_MACHTYPE_8064_RUMI3:
+		uart_dm_init(3, 0x16200000, 0x16240000);
+		break;
 
-		return GSBI_ID_3;
+	case LINUX_MACHTYPE_8064_CDP:
+	case LINUX_MACHTYPE_8064_MTP:
+	case LINUX_MACHTYPE_8064_LIQUID:
+		uart_dm_init(7, 0x16600000, 0x16640000);
+		break;
 
 	case LINUX_MACHTYPE_8627_CDP:
 	case LINUX_MACHTYPE_8627_MTP:
 
-		return GSBI_ID_5;
+		uart_dm_init(5, 0x16400000, 0x16440000);
+		break;
 
 	default:
 		dprintf(CRITICAL, "uart gsbi not defined for target: %d\n",
diff --git a/target/msm8960/keypad.c b/target/msm8960/keypad.c
index 8bbd005..e63a449 100644
--- a/target/msm8960/keypad.c
+++ b/target/msm8960/keypad.c
@@ -77,6 +77,26 @@
 	.poll_time = 20 /* msec */ ,
 };
 
+unsigned int apq8064_qwerty_keymap[] = {
+	[KEYMAP_INDEX(0, 0)] = KEY_VOLUMEUP,	/* Volume key on the device/CDP */
+	[KEYMAP_INDEX(0, 1)] = KEY_VOLUMEDOWN,	/* Volume key on the device/CDP */
+};
+
+unsigned int apq8064_keys_gpiomap[] = {
+	[KEYMAP_INDEX(0, 0)] = PM_GPIO(35),	/* Volume key on the device/CDP */
+	[KEYMAP_INDEX(0, 1)] = PM_GPIO(38),	/* Volume key on the device/CDP */
+};
+
+
+struct qwerty_keypad_info apq8064_qwerty_keypad = {
+	.keymap = apq8064_qwerty_keymap,
+	.gpiomap = apq8064_keys_gpiomap,
+	.mapsize = ARRAY_SIZE(apq8064_qwerty_keymap),
+	.key_gpio_get = &pm8921_gpio_get,
+	.settle_time = 5 /* msec */ ,
+	.poll_time = 20 /* msec */ ,
+};
+
 void msm8960_keypad_init(void)
 {
 	msm8960_keypad_gpio_init();
@@ -89,6 +109,12 @@
 	ssbi_gpio_keypad_init(&msm8930_qwerty_keypad);
 }
 
+void apq8064_keypad_init(void)
+{
+	apq8064_keypad_gpio_init();
+	ssbi_gpio_keypad_init(&apq8064_qwerty_keypad);
+}
+
 /* Configure keypad_drv through pwm or DBUS inputs or manually */
 int led_kp_set( int current,
 	enum kp_backlight_mode mode,
diff --git a/target/msm8960/tools/makefile b/target/msm8960/tools/makefile
index aedda70..5a33035 100644
--- a/target/msm8960/tools/makefile
+++ b/target/msm8960/tools/makefile
@@ -41,3 +41,4 @@
 
 mkheader: $(SRC_DIR)/mkheader.c
 	${COMPILER} -DMEMBASE=$(MEMBASE) $(SRC_DIR)/mkheader.c -o $(SRC_DIR)/mkheader
+	cp -f $(SRC_DIR)/mkheader $(BUILDDIR)/mkheader