msm_shared: Add support for memory mapped interface for Qtimers.

Change-Id: I04338cb89b6486c395f724df1a7e9a29ebd2a42d
diff --git a/arch/arm/ops.S b/arch/arm/ops.S
index 2cb2688..2581273 100644
--- a/arch/arm/ops.S
+++ b/arch/arm/ops.S
@@ -77,6 +77,46 @@
 	bx	lr
 #endif
 
+/* uint64_t atomic_dw_read(uint32_t rd_addr,
+ * uint32_t st_addr_lo, uint32_t st_addr_hi);
+ */
+/* Reads a double word from memory atomically */
+FUNCTION(atomic_dw_read)
+#if ARM_ISA_ARMV6 || ARM_ISA_ARMV7
+	stmfd	sp!, {r4-r5}
+	/* use load/store exclusive */
+	ldrexd	r4, [r0]
+	str		r4, [r1]
+	str		r5, [r2]
+
+	/* Restore registers */
+	ldmfd	sp!, {r4-r5}
+
+	bx		lr
+#else
+	stmfd	sp!, {r4-r5}
+	/* disable interrupts, do read, and reenable */
+	mrs		r2, cpsr
+	mov		r12, r2
+	orr		r2, r2, #(3<<6)
+	msr		cpsr_c, r2
+
+	/* ints disabled, old cpsr state in r12 */
+
+	/* do memory read, return the double word read */
+	ldr		r4, [r0]
+	ldr		r5, [r0, #4]
+	str		r4, [r1]
+	str		r5, [r2]
+
+	/* restore interrupts */
+	msr		cpsr_c, r12
+	/* restore registers */
+	ldmfd	sp!, {r4-r5}
+
+	bx		lr
+#endif
+
 /* int atomic_and(int *ptr, int val); */
 FUNCTION(atomic_and)
 #if ARM_ISA_ARMV6 || ARM_ISA_ARMV7
diff --git a/platform/copper/include/platform/iomap.h b/platform/copper/include/platform/iomap.h
index d645969..37d8cf5 100644
--- a/platform/copper/include/platform/iomap.h
+++ b/platform/copper/include/platform/iomap.h
@@ -42,6 +42,9 @@
 #define APCS_APC_KPSS_PLL_BASE      (KPSS_BASE + 0x0000A000)
 #define APCS_KPSS_CFG_BASE          (KPSS_BASE + 0x00010000)
 #define APCS_KPSS_WDT_BASE          (KPSS_BASE + 0x00017000)
+#define KPSS_APCS_QTMR_AC_BASE      (KPSS_BASE + 0x20000)
+#define KPSS_APCS_F0_QTMR_V1_BASE   (KPSS_BASE + 0x21000)
+#define QTMR_BASE                   KPSS_APCS_F0_QTMR_V1_BASE
 
 #define PERIPH_SS_BASE              0xF9800000
 #define MSM_SDC1_BASE               (PERIPH_SS_BASE + 0x00024000)
@@ -57,4 +60,5 @@
 #define GPIO_CONFIG_ADDR(x)         (TLMM_BASE_ADDR + 0x1000 + (x)*0x10)
 #define GPIO_IN_OUT_ADDR(x)         (TLMM_BASE_ADDR + 0x1004 + (x)*0x10)
 
+#define MPM2_MPM_CTRL_BASE          0xFC4A1000
 #endif
diff --git a/platform/copper/include/platform/irqs.h b/platform/copper/include/platform/irqs.h
index 149ac1a..c3a927e 100644
--- a/platform/copper/include/platform/irqs.h
+++ b/platform/copper/include/platform/irqs.h
@@ -43,6 +43,8 @@
 #define INT_QTMR_NON_SECURE_PHY_TIMER_EXP      (GIC_PPI_START + 3)
 #define INT_QTMR_VIRTUAL_TIMER_EXP             (GIC_PPI_START + 4)
 
+#define INT_QTMR_FRM_0_PHYSICAL_TIMER_EXP      (GIC_SPI_START + 3)
+
 #define USB1_HS_BAM_IRQ                        (GIC_SPI_START + 135)
 #define USB1_HS_IRQ                            (GIC_SPI_START + 134)
 #define USB2_IRQ                               (GIC_SPI_START + 141)
diff --git a/platform/msm_shared/include/qtimer.h b/platform/msm_shared/include/qtimer.h
index 5d66f7a..480efd6 100644
--- a/platform/msm_shared/include/qtimer.h
+++ b/platform/msm_shared/include/qtimer.h
@@ -37,7 +37,7 @@
 
 void qtimer_set_physical_timer(time_t msecs_interval,
 	platform_timer_callback tmr_callback, void *tmr_arg);
-void disable_qtimer();
+void qtimer_disable();
 uint64_t qtimer_get_phy_timer_cnt();
 uint32_t qtimer_current_time();
 uint32_t qtimer_get_frequency();
diff --git a/platform/msm_shared/include/qtimer_mmap_hw.h b/platform/msm_shared/include/qtimer_mmap_hw.h
new file mode 100644
index 0000000..3adaffb
--- /dev/null
+++ b/platform/msm_shared/include/qtimer_mmap_hw.h
@@ -0,0 +1,43 @@
+
+/* 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.
+ */
+
+#ifndef __PLATFORM_MSM_SHARED_QTMR_MMAP_H
+#define __PLATFORM_MSM_SHARED_QRMR_MMAP_H
+
+#include <platform/iomap.h>
+
+#define QTMR_V1_CNTPCT_LO                (0x00000000 + QTMR_BASE)
+#define QTMR_V1_CNTPCT_HI                (0x00000004 + QTMR_BASE)
+#define QTMR_V1_CNTFRQ                   (0x00000010 + QTMR_BASE)
+#define QTMR_V1_CNTP_CVAL_LO             (0x00000020 + QTMR_BASE)
+#define QTMR_V1_CNTP_CVAL_HI             (0x00000024 + QTMR_BASE)
+#define QTMR_V1_CNTP_TVAL                (0x00000028 + QTMR_BASE)
+#define QTMR_V1_CNTP_CTL                 (0x0000002C + QTMR_BASE)
+
+#endif
diff --git a/platform/msm_shared/qtimer.c b/platform/msm_shared/qtimer.c
index dd0c11c..2ae2757 100644
--- a/platform/msm_shared/qtimer.c
+++ b/platform/msm_shared/qtimer.c
@@ -53,7 +53,7 @@
 
 void qtimer_uninit()
 {
-	disable_qtimer();
+	qtimer_disable();
 }
 
 /* Blocking function to wait until the specified ticks of the timer.
@@ -75,7 +75,7 @@
 	timeout = (cnt + ticks) &
 			(uint64_t)(QTMR_PHY_CNT_MAX_VALUE);
 
-	/* Wait out till the counter wrapping occurs 
+	/* Wait out till the counter wrapping occurs
 	 * in cases where there is a wrapping.
 	 */
 	while(timeout < cnt && init_cnt <= cnt)
diff --git a/platform/msm_shared/qtimer_cp15.c b/platform/msm_shared/qtimer_cp15.c
index e08bb1a..a9a5496 100644
--- a/platform/msm_shared/qtimer_cp15.c
+++ b/platform/msm_shared/qtimer_cp15.c
@@ -42,6 +42,7 @@
 static uint32_t tick_count;
 
 extern void isb();
+static void qtimer_enable();
 
 static enum handler_return qtimer_irq(void *arg)
 {
@@ -65,28 +66,18 @@
 	platform_timer_callback tmr_callback,
 	void *tmr_arg)
 {
-	uint32_t ctrl;
-
 	/* Save the timer interval and call back data*/
 	tick_count = msecs_interval * qtimer_tick_rate() / 1000;;
 	timer_interval = msecs_interval;
 	timer_arg = tmr_arg;
 	timer_callback = tmr_callback;
 
-	/* Program CTRL Register */
-	ctrl =0;
-	ctrl |= QTMR_TIMER_CTRL_ENABLE;
-	ctrl &= ~QTMR_TIMER_CTRL_INT_MASK;
-
-	__asm__ volatile("mcr p15, 0, %0, c14, c2, 1" : :"r" (ctrl));
-
-	isb();
-
 	/* Set Physical Down Counter */
 	__asm__ volatile("mcr p15, 0, %0, c14, c2, 0" : :"r" (tick_count));
-
 	isb();
 
+	qtimer_enable();
+
 	/* Register for timer interrupts */
 
 	register_int_handler(INT_QTMR_NON_SECURE_PHY_TIMER_EXP, qtimer_irq, 0);
@@ -96,21 +87,37 @@
 
 }
 
-void disable_qtimer()
+static void qtimer_enable()
+{
+	uint32_t ctrl;
+
+	/* read ctrl value */
+	__asm__ volatile("mrc p15, 0, %0, c14, c2, 1" : :"r" (ctrl));
+
+	ctrl |= QTMR_TIMER_CTRL_ENABLE;
+	ctrl &= ~QTMR_TIMER_CTRL_INT_MASK;
+
+	/* write ctrl value */
+	__asm__ volatile("mcr p15, 0, %0, c14, c2, 1" : :"r" (ctrl));
+	isb();
+}
+
+void qtimer_disable()
 {
 	uint32_t ctrl;
 
 	mask_interrupt(INT_QTMR_NON_SECURE_PHY_TIMER_EXP);
 
-	/* program cntrl register */
-	ctrl = 0;
-	ctrl |= ~QTMR_TIMER_CTRL_ENABLE;
-	ctrl &= QTMR_TIMER_CTRL_INT_MASK;
+	/* read ctrl value */
+	__asm__ volatile("mrc p15, 0, %0, c14, c2, 1" : :"r" (ctrl));
 
+	ctrl &= ~QTMR_TIMER_CTRL_ENABLE;
+	ctrl |= QTMR_TIMER_CTRL_INT_MASK;
+
+	/* write ctrl value */
 	__asm__ volatile("mcr p15, 0, %0, c14, c2, 1" : :"r" (ctrl));
 
 	isb();
-
 }
 
 /* Function to return the frequency of the timer */
diff --git a/platform/msm_shared/qtimer_mmap.c b/platform/msm_shared/qtimer_mmap.c
new file mode 100644
index 0000000..31ae62a
--- /dev/null
+++ b/platform/msm_shared/qtimer_mmap.c
@@ -0,0 +1,149 @@
+/* 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 <debug.h>
+#include <reg.h>
+#include <compiler.h>
+#include <qtimer.h>
+#include <platform/irqs.h>
+#include <platform/iomap.h>
+#include <platform/interrupts.h>
+#include <qtimer_mmap_hw.h>
+
+static platform_timer_callback timer_callback;
+static void *timer_arg;
+static time_t timer_interval;
+/* time in ms from start of LK. */
+static volatile uint32_t current_time;
+static uint32_t tick_count;
+
+extern uint64_t atomic_dw_read(uint32_t, uint32_t *, uint32_t *);
+extern void dsb();
+static void qtimer_enable();
+
+static enum handler_return qtimer_irq(void *arg)
+{
+	current_time += timer_interval;
+
+	/* Program the down counter again to get
+	 * an interrupt after timer_interval msecs
+	 */
+
+	writel(tick_count, QTMR_V1_CNTP_TVAL);
+
+	dsb();
+
+	return timer_callback(timer_arg, current_time);
+}
+
+/* Programs the Physical Secure Down counter timer.
+ * interval : Counter ticks till expiry interrupt is fired.
+ */
+void qtimer_set_physical_timer(time_t msecs_interval,
+	platform_timer_callback tmr_callback, void *tmr_arg)
+{
+	uint32_t ppi_num;
+
+	qtimer_disable();
+
+	/* Save the timer interval and call back data*/
+	tick_count = msecs_interval * qtimer_tick_rate() / 1000;;
+	timer_interval = msecs_interval;
+	timer_arg = tmr_arg;
+	timer_callback = tmr_callback;
+
+	/* Set Physical Down Counter */
+	writel(tick_count, QTMR_V1_CNTP_TVAL);
+	dsb();
+
+	qtimer_enable();
+
+	ppi_num = INT_QTMR_FRM_0_PHYSICAL_TIMER_EXP;
+	register_int_handler(ppi_num, qtimer_irq, 0);
+	unmask_interrupt(ppi_num);
+}
+
+
+/* Function to return the frequency of the timer */
+uint32_t qtimer_get_frequency()
+{
+	uint32_t freq;
+
+	/* Read the Global counter frequency */
+	freq = readl(QTMR_V1_CNTFRQ);
+
+	return freq;
+
+}
+
+static void qtimer_enable()
+{
+	uint32_t ctrl;
+
+	ctrl = readl(QTMR_V1_CNTP_CTL);
+
+	/* Program CTRL Register */
+	ctrl |= QTMR_TIMER_CTRL_ENABLE;
+	ctrl &= ~QTMR_TIMER_CTRL_INT_MASK;
+
+	writel(ctrl, QTMR_V1_CNTP_CTL);
+
+	dsb();
+}
+
+void qtimer_disable()
+{
+	uint32_t ctrl;
+
+	mask_interrupt(INT_QTMR_FRM_0_PHYSICAL_TIMER_EXP);
+
+	ctrl = readl(QTMR_V1_CNTP_CTL);
+
+	/* program cntrl register */
+	ctrl &= ~QTMR_TIMER_CTRL_ENABLE;
+	ctrl |= QTMR_TIMER_CTRL_INT_MASK;
+
+	writel(ctrl, QTMR_V1_CNTP_CTL);
+
+	dsb();
+}
+
+inline __ALWAYS_INLINE uint64_t qtimer_get_phy_timer_cnt()
+{
+	uint32_t phy_cnt_lo;
+	uint32_t phy_cnt_hi;
+
+	atomic_dw_read(QTMR_V1_CNTPCT_LO, &phy_cnt_lo, &phy_cnt_hi);
+
+	return ((uint64_t)phy_cnt_hi << 32) | phy_cnt_lo;
+}
+
+uint32_t qtimer_current_time()
+{
+	return current_time;
+}