msm_shared: Cleanup Qtimers.

1. mdelay(), udelay(): The counter wrapping
needs to accounted for while waitng for a
calculated number of ticks.
2. Remove the Virtual timer implementation.
3. Add functions to read the physical count and
counter frequency and move cp15 specific functions
to a new file.
4. Move function declarations and #define's to
header file.
5. Add isb() for each cp15 write.

Change-Id: I5c7efaee4233a8650064e6a9bbcaaf729d836180
diff --git a/arch/arm/ops.S b/arch/arm/ops.S
index c9660e7..2cb2688 100644
--- a/arch/arm/ops.S
+++ b/arch/arm/ops.S
@@ -48,12 +48,12 @@
 #if ARM_ISA_ARMV6 || ARM_ISA_ARMV7
 	/* use load/store exclusive */
 .L_loop_add:
-	ldrex 	r12, [r0]
+	ldrex	r12, [r0]
 	add		r2, r12, r1
-	strex 	r3, r2, [r0]
+	strex	r3, r2, [r0]
 	cmp		r3, #0
-	bne 	.L_loop_add
-	
+	bne	.L_loop_add
+
 	/* save old value */
 	mov		r0, r12
 	bx		lr
@@ -65,7 +65,7 @@
 	msr	cpsr_c, r2
 
 	/* ints disabled, old cpsr state in r12 */
-	
+
 	/* do the add, leave the previous value in r0 */
 	mov	r3, r0
 	ldr	r0, [r3]
@@ -76,18 +76,18 @@
 	msr	cpsr_c, r12
 	bx	lr
 #endif
-	
+
 /* int atomic_and(int *ptr, int val); */
 FUNCTION(atomic_and)
 #if ARM_ISA_ARMV6 || ARM_ISA_ARMV7
 	/* use load/store exclusive */
 .L_loop_and:
-	ldrex 	r12, [r0]
+	ldrex	r12, [r0]
 	and		r2, r12, r1
-	strex 	r3, r2, [r0]
+	strex	r3, r2, [r0]
 	cmp		r3, #0
-	bne 	.L_loop_and
-	
+	bne	.L_loop_and
+
 	/* save old value */
 	mov		r0, r12
 	bx		lr
@@ -99,7 +99,7 @@
 	msr	cpsr_c, r2
 
 	/* ints disabled, old cpsr state in r12 */
-	
+
 	/* do the and, leave the previous value in r0 */
 	mov	r3, r0
 	ldr	r0, [r3]
@@ -110,18 +110,18 @@
 	msr	cpsr_c, r12
 	bx	lr
 #endif
-	
+
 /* int atomic_or(int *ptr, int val); */
 FUNCTION(atomic_or)
 #if ARM_ISA_ARMV6 || ARM_ISA_ARMV7
 	/* use load/store exclusive */
 .L_loop_or:
-	ldrex 	r12, [r0]
+	ldrex	r12, [r0]
 	orr		r2, r12, r1
-	strex 	r3, r2, [r0]
+	strex	r3, r2, [r0]
 	cmp		r3, #0
-	bne 	.L_loop_or
-	
+	bne	.L_loop_or
+
 	/* save old value */
 	mov		r0, r12
 	bx		lr
@@ -133,7 +133,7 @@
 	msr	cpsr_c, r2
 
 	/* ints disabled, old cpsr state in r12 */
-	
+
 	/* do the or, leave the previous value in r0 */
 	mov	r3, r0
 	ldr	r0, [r3]
@@ -183,24 +183,24 @@
 
 /* void arm_write_ttbr(uint32_t val) */
 FUNCTION(arm_write_ttbr)
-	mcr 	p15, 0, r0, c2, c0, 0
+	mcr	p15, 0, r0, c2, c0, 0
 	bx		lr
 
 /* void arm_write_dacr(uint32_t val) */
 FUNCTION(arm_write_dacr)
-	mcr 	p15, 0, r0, c3, c0, 0
+	mcr	p15, 0, r0, c3, c0, 0
 	bx		lr
 
 /* void arm_invalidate_tlb(void) */
 FUNCTION(arm_invalidate_tlb)
 	mov		r0, #0
-	mcr 	p15, 0, r0, c8, c7, 0
+	mcr	p15, 0, r0, c8, c7, 0
 	bx		lr
 
 /* void arch_switch_stacks_and_call(addr_t call, addr_t stack) */
 FUNCTION(arch_switch_stacks_and_call)
 	mov		sp, r1
-	bx		r0	
+	bx		r0
 
 /*void dmb(void) */
 FUNCTION(dmb)
@@ -212,6 +212,16 @@
 #endif
 	bx		lr
 
+/*void isb(void) */
+FUNCTION(isb)
+#if ARM_CPU_CORTEX_A8
+	isb		sy
+#elif ARM_CPU_ARM1136
+	mov		r0, #0
+	mcr		p15, 0, r0, c7, c5, 4
+#endif
+	bx		lr
+
 /*void dsb(void) */
 FUNCTION(dsb)
 #if ARM_CPU_CORTEX_A8
diff --git a/platform/msm_shared/include/qtimer.h b/platform/msm_shared/include/qtimer.h
new file mode 100644
index 0000000..afb27df
--- /dev/null
+++ b/platform/msm_shared/include/qtimer.h
@@ -0,0 +1,46 @@
+/* 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>
+#include <platform/timer.h>
+
+
+#define QTMR_TIMER_CTRL_ENABLE          (1 << 0)
+#define QTMR_TIMER_CTRL_INT_MASK        (1 << 1)
+
+#define QTMR_PHY_CNT_MAX_VALUE          0xFFFFFFFFFFFFFF
+
+void qtimer_set_physical_timer(time_t msecs_interval,
+	platform_timer_callback tmr_callback, void *tmr_arg);
+void disable_qtimer();
+uint64_t qtimer_get_phy_timer_cnt();
+uint32_t qtimer_current_time();
+uint32_t qtimer_get_frequency();
+void uninit_qtimer();
+void qtimer_init();
+uint32_t qtimer_tick_rate();
diff --git a/platform/msm_shared/qtimer.c b/platform/msm_shared/qtimer.c
old mode 100755
new mode 100644
index 9e14b2d..489a70c
--- a/platform/msm_shared/qtimer.c
+++ b/platform/msm_shared/qtimer.c
@@ -1,4 +1,4 @@
-/* Copyright (c) 2011, Code Aurora Forum. All rights reserved.
+/* 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
@@ -28,101 +28,19 @@
 
 #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 <compiler.h>
+#include <qtimer.h>
 #include <kernel/thread.h>
 
-#define QTMR_TIMER_CTRL_ENABLE          (1 << 0)
-#define QTMR_TIMER_CTRL_INT_MASK        (1 << 1)
-
-#define QTMR_TYPE_PHYSICAL     1
-#define QTMR_TYPE_VIRTUAL      2
-
-static platform_timer_callback timer_callback;
-static void *timer_arg;
-static time_t timer_interval;
-static unsigned int timer_type = QTMR_TYPE_PHYSICAL;
-static volatile uint32_t ticks;
-static uint32_t tick_count;
-static uint32_t ppi_num = -1;
-
-static enum handler_return qtimer_irq(void *arg)
-{
-	ticks += timer_interval;
-
-	if (timer_type == QTMR_TYPE_VIRTUAL)
-		__asm__("mcr p15, 0, %0, c14, c3, 0"::"r"(tick_count));
-	else if (timer_type == QTMR_TYPE_PHYSICAL)
-		__asm__("mcr p15, 0, %0, c14, c2, 0" : :"r" (tick_count));
-
-	return timer_callback(timer_arg, ticks);
-}
-
-/* Programs the Virtual Down counter timer.
- * interval : Counter ticks till expiry interrupt is fired.
- */
-static unsigned int qtimer_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.
- */
-static unsigned int qtimer_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;
-
-}
-
+static uint32_t ticks_per_sec;
 
 status_t platform_set_periodic_timer(platform_timer_callback callback,
 	void *arg, time_t interval)
 {
-	tick_count = interval * platform_tick_rate() / 1000;
 
 	enter_critical_section();
 
-	timer_callback = callback;
-	timer_arg = arg;
-	timer_interval = interval;
-
-	if (timer_type == QTMR_TYPE_VIRTUAL)
-		ppi_num = qtimer_set_virtual_timer(tick_count);
-	else if (timer_type == QTMR_TYPE_PHYSICAL)
-		ppi_num = qtimer_set_physical_timer(tick_count);
-
-	register_int_handler(ppi_num, qtimer_irq, 0);
-	unmask_interrupt(ppi_num);
+	qtimer_set_physical_timer(interval, callback, arg);
 
 	exit_critical_section();
 	return 0;
@@ -130,75 +48,78 @@
 
 time_t current_time(void)
 {
-	return ticks;
+	return qtimer_current_time();
 }
 
 void uninit_qtimer()
 {
-	uint32_t ctrl;
+	disable_qtimer();
+}
 
-	if (ppi_num == -1)
-	{
-		dprintf(CRITICAL, "Qtimer unintialized before initializing\n");
-		return;
-	}
+/* Blocking function to wait until the specified ticks of the timer.
+ * Note: ticks to wait for cannot be more than 56 bit.
+ *          Should be sufficient for all practical purposes.
+ */
+static void delay(uint64_t ticks)
+{
+	volatile uint64_t cnt;
+	uint64_t init_cnt;
+	uint64_t timeout = 0;
 
-	mask_interrupt(ppi_num);
+	cnt = qtimer_get_phy_timer_cnt();
+	init_cnt = cnt;
 
-	/* program cntrl register */
-	ctrl =0;
-	ctrl |= ~QTMR_TIMER_CTRL_ENABLE;
-	ctrl &= QTMR_TIMER_CTRL_INT_MASK;
+	/* Calculate timeout = cnt + ticks (mod 2^56)
+	 * to account for timer counter wrapping
+	 */
+	timeout = (cnt + ticks) &
+			(uint64_t)(QTMR_PHY_CNT_MAX_VALUE);
 
-	if (timer_type == QTMR_TYPE_VIRTUAL)
-		__asm__("mcr p15, 0, %0, c14, c3, 1"::"r"(ctrl));
-	else if (timer_type == QTMR_TYPE_PHYSICAL)
-		__asm__("mcr p15, 0, %0, c14, c2, 1" : :"r" (ctrl));
+	/* Wait out till the counter wrapping occurs 
+	 * in cases where there is a wrapping.
+	 */
+	while(timeout < cnt && init_cnt <= cnt)
+		/* read global counter */
+		cnt = qtimer_get_phy_timer_cnt();
+
+	/* Wait till the number of ticks is reached*/
+	while(timeout > cnt)
+		/* read global counter */
+		cnt = qtimer_get_phy_timer_cnt();
 
 }
 
+
 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;
+	uint64_t ticks;
 
-	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);
+	ticks = (msecs * ticks_per_sec) / 1000;
 
+	delay(ticks);
 }
 
 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;
+	uint64_t ticks;
 
-	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;
+	ticks = (usecs * ticks_per_sec) / 1000000;
 
-	/*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);
+	delay(ticks);
 }
 
 /* Return current time in micro seconds */
 bigtime_t current_time_hires(void)
 {
-	return ticks * 1000000ULL;
+	return qtimer_current_time() * 1000000ULL;
+}
+
+void qtimer_init()
+{
+	ticks_per_sec = qtimer_get_frequency();
+}
+
+uint32_t qtimer_tick_rate()
+{
+	return ticks_per_sec;
 }
diff --git a/platform/msm_shared/qtimer_cp15.c b/platform/msm_shared/qtimer_cp15.c
new file mode 100644
index 0000000..4065b81
--- /dev/null
+++ b/platform/msm_shared/qtimer_cp15.c
@@ -0,0 +1,141 @@
+/* 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>
+
+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 void isb();
+
+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
+	 */
+
+	__asm__ volatile("mcr p15, 0, %0, c14, c2, 0" : :"r" (tick_count));
+
+	isb();
+
+	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 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();
+
+	/* Register for timer interrupts */
+
+	register_int_handler(INT_QTMR_SECURE_PHYSICAL_TIMER_EXP, qtimer_irq, 0);
+	unmask_interrupt(INT_QTMR_SECURE_PHYSICAL_TIMER_EXP);
+
+	return;
+
+}
+
+void disable_qtimer()
+{
+	uint32_t ctrl;
+
+	mask_interrupt(INT_QTMR_SECURE_PHYSICAL_TIMER_EXP);
+
+	/* program cntrl 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();
+
+}
+
+/* Function to return the frequency of the timer */
+uint32_t qtimer_get_frequency()
+{
+	uint32_t freq;
+
+	/* Read the Global counter frequency */
+	__asm__ volatile("mrc p15, 0, %0, c14, c0, 0" : "=r" (freq));
+
+	return freq;
+
+}
+
+inline __ALWAYS_INLINE uint64_t qtimer_get_phy_timer_cnt()
+{
+	uint32_t phy_cnt_lo;
+	uint32_t phy_cnt_hi;
+
+	__asm__ volatile("mrrc p15,0,%0,%1, c14":
+		"=r"(phy_cnt_lo),"=r"(phy_cnt_hi));
+	return ((uint64_t)phy_cnt_hi << 32) | phy_cnt_lo;
+}
+
+uint32_t qtimer_current_time()
+{
+	return current_time;
+}
diff --git a/platform/msm_shared/rules.mk b/platform/msm_shared/rules.mk
index 6111b62..5ae6935 100644
--- a/platform/msm_shared/rules.mk
+++ b/platform/msm_shared/rules.mk
@@ -59,6 +59,7 @@
 ifeq ($(PLATFORM),copper)
 	OBJS += $(LOCAL_DIR)/qgic.o \
 			$(LOCAL_DIR)/qtimer.o \
+			$(LOCAL_DIR)/qtimer_cp15.o \
 			$(LOCAL_DIR)/interrupts.o
 endif