summaryrefslogtreecommitdiff
diff options
context:
space:
mode:
authorGregory Nutt <gnutt@nuttx.org>2015-01-12 15:52:48 -0600
committerGregory Nutt <gnutt@nuttx.org>2015-01-12 15:52:48 -0600
commitc0fb82fe8d97a89010d96f16a1ca7078e1a6a1ff (patch)
tree6846ff51fab589cbea3a11bd61124edcca4a6021
parent03db209bd059f62b68f642476dee0abd37fc402b (diff)
downloadpx4-nuttx-c0fb82fe8d97a89010d96f16a1ca7078e1a6a1ff.tar.gz
px4-nuttx-c0fb82fe8d97a89010d96f16a1ca7078e1a6a1ff.tar.bz2
px4-nuttx-c0fb82fe8d97a89010d96f16a1ca7078e1a6a1ff.zip
Tiva Timer: First cut at timer driver lower half (still incomplete)
-rw-r--r--nuttx/arch/arm/src/tiva/Make.defs3
-rw-r--r--nuttx/arch/arm/src/tiva/tiva_timer.c306
-rw-r--r--nuttx/arch/arm/src/tiva/tiva_timer.h100
-rw-r--r--nuttx/arch/arm/src/tiva/tiva_timerlow.c583
4 files changed, 958 insertions, 34 deletions
diff --git a/nuttx/arch/arm/src/tiva/Make.defs b/nuttx/arch/arm/src/tiva/Make.defs
index aa4d9269f..9851dcbb6 100644
--- a/nuttx/arch/arm/src/tiva/Make.defs
+++ b/nuttx/arch/arm/src/tiva/Make.defs
@@ -98,6 +98,9 @@ endif
ifeq ($(CONFIG_TIVA_TIMER),y)
CHIP_CSRCS += tiva_timer.c
+ifeq ($(CONFIG_TIMER),y)
+CHIP_CSRCS += tiva_timerlow.c
+endif
endif
ifeq ($(CONFIG_NET),y)
diff --git a/nuttx/arch/arm/src/tiva/tiva_timer.c b/nuttx/arch/arm/src/tiva/tiva_timer.c
index 5327c6847..eab2a4ba7 100644
--- a/nuttx/arch/arm/src/tiva/tiva_timer.c
+++ b/nuttx/arch/arm/src/tiva/tiva_timer.c
@@ -820,10 +820,11 @@ static int tiva_oneshot_periodic_mode32(struct tiva_gptmstate_s *priv,
#warning Missing Logic
/* Enable one-shot/periodic interrupts? Enable interrupts only if an
- * interrupt handler was provided.
+ * non-NULL interrupt handler and non-zero timeout interval were
+ * provided.
*/
- if (timer->handler)
+ if (timer->handler && timer->u.periodic.interval > 0)
{
/* Select the interrupt mask that will enable the timer interrupt.
* Any non-zero value of imr indicates that interrupts are expected.
@@ -1527,8 +1528,8 @@ static int tiva_timer16_configure(struct tiva_gptmstate_s *priv,
TIMER_HANDLE tiva_gptm_configure(const struct tiva_gptmconfig_s *config)
{
- static const struct tiva_gptmattr_s *attr;
- static struct tiva_gptmstate_s *priv;
+ const struct tiva_gptmattr_s *attr;
+ struct tiva_gptmstate_s *priv;
uint32_t regval;
int ret;
@@ -1542,7 +1543,7 @@ TIMER_HANDLE tiva_gptm_configure(const struct tiva_gptmconfig_s *config)
case 0:
/* Enable GPTM0 clocking and power */
-
+
attr = &g_gptm0_attr;
priv = &g_gptm0_state;
break;
@@ -1632,7 +1633,7 @@ TIMER_HANDLE tiva_gptm_configure(const struct tiva_gptmconfig_s *config)
while (!tiva_gpio_periphrdy(config->gptm));
- /* Reset the time to be certain that it is in the disabled state */
+ /* Reset the timer to be certain that it is in the disabled state */
regval = tiva_getreg(priv, TIVA_SYSCON_SRTIMER);
regval |= SYSCON_SRTIMER(config->gptm);
@@ -1745,6 +1746,64 @@ TIMER_HANDLE tiva_gptm_configure(const struct tiva_gptmconfig_s *config)
}
/****************************************************************************
+ * Name: tiva_gptm_release
+ *
+ * Description:
+ * Release resources held by the timer instance. After this function is
+ * called, the timer handle is invalid and must not be used further.
+ *
+ * Input Parameters:
+ * handle - The handle value returned by tiva_gptm_configure()
+ *
+ * Returned Value:
+ * None.
+ *
+ ****************************************************************************/
+
+void tiva_gptm_release(TIMER_HANDLE handle)
+{
+ struct tiva_gptmstate_s *priv = (struct tiva_gptmstate_s *)handle;
+ const struct tiva_gptmconfig_s *config;
+ const struct tiva_gptmattr_s *attr;
+ uint32_t regval;
+
+ DEBUGASSERT(priv && priv->attr && priv->config);
+ config = priv->config;
+ attr = priv->attr;
+
+ /* Disable and detach interrupt handlers */
+
+ up_disable_irq(attr->irq[TIMER16A]);
+ up_disable_irq(attr->irq[TIMER16B]);
+
+ (void)irq_detach(attr->irq[TIMER16A]);
+ (void)irq_detach(attr->irq[TIMER16B]);
+
+ /* Reset the time to be certain that it is in the disabled state */
+
+ regval = tiva_getreg(priv, TIVA_SYSCON_SRTIMER);
+ regval |= SYSCON_SRTIMER(config->gptm);
+ tiva_putreg(priv, TIVA_SYSCON_SRTIMER, regval);
+
+ regval &= ~SYSCON_SRTIMER(config->gptm);
+ tiva_putreg(priv, TIVA_SYSCON_SRTIMER, regval);
+
+ /* Wait for the reset to complete */
+
+ while (!tiva_emac_periphrdy());
+ up_udelay(250);
+
+ /* Disable power and clocking to the GPTM module */
+
+ tiva_gptm_disableclk(config->gptm);
+ tiva_gptm_disablepwr(config->gptm);
+
+ /* Un-initialize the state structure */
+
+ memset(priv, 0, sizeof(struct tiva_gptmstate_s));
+}
+
+/****************************************************************************
* Name: tiva_gptm_putreg
*
* Description:
@@ -2084,6 +2143,241 @@ uint32_t tiva_timer16_counter(TIMER_HANDLE handle, int tmndx)
}
/****************************************************************************
+ * Name: tiva_timer32_setinterval
+ *
+ * Description:
+ * This function may be called at any time to change the timer interval
+ * load value of a 32-bit timer.
+ *
+ * Input Parameters:
+ * handle - The handle value returned by tiva_gptm_configure()
+ * interval - The value to write to the timer interval load register
+ *
+ * Returned Value:
+ * None.
+ *
+ ****************************************************************************/
+
+void tiva_timer32_setinterval(TIMER_HANDLE handle, uint32_t interval)
+{
+ struct tiva_gptmstate_s *priv = (struct tiva_gptmstate_s *)handle;
+ const struct tiva_gptm32config_s *config;
+ const struct tiva_timer32config_s *timer;
+ irqstate_t flags;
+ uintptr_t base;
+ uintptr_t moder;
+ uintptr_t loadr;
+ uintptr_t icrr;
+ uintptr_t imrr;
+ uint32_t modev1;
+ uint32_t modev2;
+ bool toints;
+
+ DEBUGASSERT(priv && priv->attr && priv->config &&
+ priv->config->mode != TIMER16_MODE);
+ config = (const struct tiva_gptm32config_s *)priv->config;
+ timer = &config->config;
+
+ /* Do we need to control timeout interrupts? */
+
+ base = priv->attr->base;
+ if (timer->handler && interval > 0 &&
+ (config->cmn.mode == TIMER32_MODE_ONESHOT ||
+ config->cmn.mode == TIMER32_MODE_PERIODIC))
+ {
+ priv->imr |= TIMER_INT_TATO;
+ toints = true;
+ }
+ else
+ {
+ priv->imr &= ~TIMER_INT_TATO;
+ toints = false;
+ }
+
+ loadr = base + TIVA_TIMER_TAILR_OFFSET;
+ moder = base + TIVA_TIMER_TAMR_OFFSET;
+ icrr = base + TIVA_TIMER_ICR_OFFSET;
+ imrr = base + TIVA_TIMER_IMR_OFFSET;
+
+ /* Make the following atomic */
+
+ flags = irqsave();
+
+ /* Set the new timeout interval */
+
+ putreg32(interval, loadr);
+
+ /* Enable/disable timeout interrupts */
+
+ if (toints)
+ {
+ /* Clearing the TACINTD bit allows the time-out interrupt to be
+ * generated as normal
+ */
+
+ modev1 = tiva_getreg(priv, moder);
+ modev2 = modev1 & ~TIMER_TnMR_TnCINTD;
+ putreg32(modev2, moder);
+ }
+ else
+ {
+ /* Setting the TACINTD bit prevents the time-out interrupt */
+
+ modev1 = tiva_getreg(priv, moder);
+ modev2 = modev1 | TIMER_TnMR_TnCINTD;
+ putreg32(modev2, moder);
+
+ /* Clear any pending timeout interrupts */
+
+ putreg32(TIMER_INT_TATO, icrr);
+ }
+
+ /* Set the new interrupt mask */
+
+ putreg32(priv->imr, imrr);
+ irqrestore(flags);
+
+#ifdef CONFIG_TIVA_TIMER_REGDEBUG
+ /* Generate low-level debug output outside of the critical section */
+
+ lldbg("%08x<-%08x\n", loadr, interval);
+ lldbg("%08x->%08x\n", moder, modev1);
+ lldbg("%08x<-%08x\n", moder, modev2);
+ if (!toints)
+ {
+ lldbg("%08x->%08x\n", icrr, TIMER_INT_TATO);
+ }
+
+ lldbg("%08x<-%08x\n", imrr, priv->imr);
+#endif
+}
+
+/****************************************************************************
+ * Name: tiva_timer16_setinterval
+ *
+ * Description:
+ * This function may be called at any time to change the timer interval
+ * load value of a 16-bit timer.
+ *
+ * Input Parameters:
+ * handle - The handle value returned by tiva_gptm_configure()
+ * interval - The value to write to the timer interval load register
+ * tmndx - Either TIMER16A or TIMER16B to select the 16-bit timer
+ *
+ * Returned Value:
+ * None.
+ *
+ ****************************************************************************/
+
+void tiva_timer16_setinterval(TIMER_HANDLE handle, uint16_t interval, int tmndx)
+{
+ struct tiva_gptmstate_s *priv = (struct tiva_gptmstate_s *)handle;
+ const struct tiva_gptm16config_s *config;
+ const struct tiva_timer16config_s *timer;
+ irqstate_t flags;
+ uintptr_t base;
+ uintptr_t moder;
+ uintptr_t loadr;
+ uintptr_t icrr;
+ uintptr_t imrr;
+ uint32_t intbit;
+ uint32_t modev1;
+ uint32_t modev2;
+ bool toints;
+
+ DEBUGASSERT(priv && priv->attr && priv->config &&
+ priv->config->mode != TIMER16_MODE);
+ config = (const struct tiva_gptm16config_s *)priv->config;
+ timer = &config->config[tmndx];
+
+ /* Pre-calculate as much as possible outside of the critical section */
+
+ base = priv->attr->base;
+ if (tmndx)
+ {
+ intbit = TIMER_INT_TBTO;
+ loadr = base + TIVA_TIMER_TBILR_OFFSET;
+ moder = base + TIVA_TIMER_TBMR_OFFSET;
+ }
+ else
+ {
+ intbit = TIMER_INT_TATO;
+ loadr = base + TIVA_TIMER_TAILR_OFFSET;
+ moder = base + TIVA_TIMER_TAMR_OFFSET;
+ }
+
+ icrr = base + TIVA_TIMER_ICR_OFFSET;
+ imrr = base + TIVA_TIMER_IMR_OFFSET;
+
+ /* Do we need to control timeout interrupts? */
+
+ if (timer->handler && interval > 0 &&
+ (config->cmn.mode == TIMER16_MODE_ONESHOT ||
+ config->cmn.mode == TIMER16_MODE_PERIODIC))
+ {
+ priv->imr |= intbit;
+ toints = true;
+ }
+ else
+ {
+ priv->imr &= ~intbit;
+ toints = false;
+ }
+
+ /* Make the following atomic */
+
+ flags = irqsave();
+
+ /* Set the new timeout interval */
+
+ putreg32(interval, loadr);
+
+ /* Enable/disable timeout interrupts */
+
+ if (toints)
+ {
+ /* Clearing the TACINTD bit allows the time-out interrupt to be
+ * generated as normal
+ */
+
+ modev1 = tiva_getreg(priv, moder);
+ modev2 = modev1 & ~TIMER_TnMR_TnCINTD;
+ putreg32(modev2, moder);
+ }
+ else
+ {
+ /* Setting the TACINTD bit prevents the time-out interrupt */
+
+ modev1 = tiva_getreg(priv, moder);
+ modev2 = modev1 | TIMER_TnMR_TnCINTD;
+ putreg32(modev2, moder);
+
+ /* Clear any pending timeout interrupts */
+
+ putreg32(intbit, icrr);
+ }
+
+ /* Set the new interrupt mask */
+
+ putreg32(priv->imr, imrr);
+ irqrestore(flags);
+
+#ifdef CONFIG_TIVA_TIMER_REGDEBUG
+ /* Generate low-level debug output outside of the critical section */
+
+ lldbg("%08x<-%08x\n", loadr, interval);
+ lldbg("%08x->%08x\n", moder, modev1);
+ lldbg("%08x<-%08x\n", moder, modev2);
+ if (!toints)
+ {
+ lldbg("%08x->%08x\n", icrr, intbit);
+ }
+
+ lldbg("%08x<-%08x\n", imrr, priv->imr);
+#endif
+}
+
+/****************************************************************************
* Name: tiva_rtc_setalarm
*
* Description:
diff --git a/nuttx/arch/arm/src/tiva/tiva_timer.h b/nuttx/arch/arm/src/tiva/tiva_timer.h
index a7b809c32..4d5ed1e87 100644
--- a/nuttx/arch/arm/src/tiva/tiva_timer.h
+++ b/nuttx/arch/arm/src/tiva/tiva_timer.h
@@ -47,6 +47,8 @@
#include <arch/tiva/chip.h>
+#include "up_arch.h"
+#include "chip.h"
#include "chip/tiva_timer.h"
/****************************************************************************
@@ -125,6 +127,20 @@
#define TIMER_ISDMARTCM(c) ((((c)->flags) & TIMER_FLAG_DMARTCM) != 0)
#define TIMER_ISDMAMATCH(c) ((((c)->flags) & TIMER_FLAG_DMAMATCH) != 0)
+/* Debug ********************************************************************/
+/* Non-standard debug that may be enabled just for testing the timer
+ * driver. NOTE: that only lldbg types are used so that the output is
+ * immediately available.
+ */
+
+#ifdef CONFIG_DEBUG_TIMER
+# define timdbg lldbg
+# define timvdbg llvdbg
+#else
+# define timdbg(x...)
+# define timvdbg(x...)
+#endif
+
/****************************************************************************
* Public Types
****************************************************************************/
@@ -321,6 +337,23 @@ struct tiva_gptm16config_s
TIMER_HANDLE tiva_gptm_configure(const struct tiva_gptmconfig_s *gptm);
/****************************************************************************
+ * Name: tiva_gptm_release
+ *
+ * Description:
+ * Release resources held by the timer instance. After this function is
+ * called, the timer handle is invalid and must not be used further.
+ *
+ * Input Parameters:
+ * handle - The handle value returned by tiva_gptm_configure()
+ *
+ * Returned Value:
+ * None.
+ *
+ ****************************************************************************/
+
+void tiva_gptm_release(TIMER_HANDLE handle);
+
+/****************************************************************************
* Name: tiva_gptm_putreg
*
* Description:
@@ -504,61 +537,44 @@ static inline uint32_t tiva_timer32_counter(TIMER_HANDLE handle)
uint32_t tiva_timer16_counter(TIMER_HANDLE handle, int tmndx);
/****************************************************************************
- * Name: tiva_timer32_setload
+ * Name: tiva_timer32_setinterval
*
* Description:
* This function may be called at any time to change the timer interval
* load value of a 32-bit timer.
*
* Input Parameters:
- * handle - The handle value returned by tiva_gptm_configure()
- * load - The value to write to the timer interval load register
+ * handle - The handle value returned by tiva_gptm_configure()
+ * interval - The value to write to the timer interval load register
*
* Returned Value:
* None.
*
****************************************************************************/
-static inline void tiva_timer32_setload(TIMER_HANDLE handle, uint32_t load)
-{
- tiva_gptm_putreg(handle, TIVA_TIMER_TAILR_OFFSET, load);
-}
+void tiva_timer32_setinterval(TIMER_HANDLE handle, uint32_t interval);
/****************************************************************************
- * Name: tiva_timer16_setload
+ * Name: tiva_timer16_setinterval
*
* Description:
* This function may be called at any time to change the timer interval
* load value of a 16-bit timer.
*
* Input Parameters:
- * handle - The handle value returned by tiva_gptm_configure()
- * load - The value to write to the timer interval load register
- * tmndx - Either TIMER16A or TIMER16B to select the 16-bit timer
+ * handle - The handle value returned by tiva_gptm_configure()
+ * interval - The value to write to the timer interval load register
+ * tmndx - Either TIMER16A or TIMER16B to select the 16-bit timer
*
* Returned Value:
* None.
*
****************************************************************************/
-static inline void tiva_timer16_setload(TIMER_HANDLE handle, uint16_t load,
- int tmndx)
-{
- unsigned int regoffset =
- tmndx ? TIVA_TIMER_TBILR_OFFSET : TIVA_TIMER_TAILR_OFFSET;
-
- tiva_gptm_putreg(handle, regoffset, load);
-}
-
-static inline void tiva_timer16a_setload(TIMER_HANDLE handle, uint16_t load)
-{
- tiva_gptm_putreg(handle, TIVA_TIMER_TAILR_OFFSET, load);
-}
+void tiva_timer16_setinterval(TIMER_HANDLE handle, uint16_t interval, int tmndx);
-static inline void tiva_timer16b_setload(TIMER_HANDLE handle, uint16_t load)
-{
- tiva_gptm_putreg(handle, TIVA_TIMER_TBILR_OFFSET, load);
-}
+#define tiva_timer16a_setinterval(h,l) tiva_timer16_setinterval(h,l,TIMER16A)
+#define tiva_timer16b_setinterval(h,l) tiva_timer16_setinterval(h,l,TIMER16B)
/****************************************************************************
* Name: tiva_timer32_absmatch
@@ -768,4 +784,32 @@ static inline void tiva_gptm0_synchronize(uint32_t sync)
putreg32(sync, TIVA_TIMER0_SYNC);
}
+/****************************************************************************
+ * Name: tiva_timer_register
+ *
+ * Description:
+ * Bind the configuration timer to a timer lower half instance and
+ * register the timer drivers at 'devpath'
+ *
+ * NOTE: Only 32-bit periodic timers are supported.
+ *
+ * Input Parameters:
+ * devpath - The full path to the timer device. This should be of the form
+ * /dev/timer0
+ * gptm - General purpose timer number
+ * timeout - Timeout interval in milliseconds. Set to a non-zero value
+ * to enable timeout interrupts
+ * altlck - True: Use alternate clock source.
+ *
+ * Returned Values:
+ * Zero (OK) is returned on success; A negated errno value is returned
+ * to indicate the nature of any failure.
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_TIMER
+int tiva_timer_register(FAR const char *devpath, int gptm, uint32_t timeout,
+ bool altclk);
+#endif
+
#endif /* __ARCH_ARM_SRC_TIVA_TIVA_TIMER_H */
diff --git a/nuttx/arch/arm/src/tiva/tiva_timerlow.c b/nuttx/arch/arm/src/tiva/tiva_timerlow.c
new file mode 100644
index 000000000..9959d80fe
--- /dev/null
+++ b/nuttx/arch/arm/src/tiva/tiva_timerlow.c
@@ -0,0 +1,583 @@
+/****************************************************************************
+ * arch/arm/src/tiva/tiva_timerlow.c
+ *
+ * Copyright (C) 2015 Gregory Nutt. All rights reserved.
+ * Authors: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. 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.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE 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.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <sys/types.h>
+
+#include <stdint.h>
+#include <errno.h>
+#include <assert.h>
+#include <debug.h>
+
+#include <nuttx/kmalloc.h>
+#include <nuttx/timer.h>
+
+#include <arch/board/board.h>
+
+#include "tiva_timer.h"
+
+#if defined(CONFIG_TIMER) && defined(CONFIG_TIVA_TIMER)
+
+/****************************************************************************
+ * Pre-Processor Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Types
+ ****************************************************************************/
+/* This structure provides the private representation of the "lower-half"
+ * driver state structure. This structure must be cast-compatible with the
+ * timer_lowerhalf_s structure.
+ */
+
+struct tiva_lowerhalf_s
+{
+ const struct timer_ops_s *ops; /* Lower half operations */
+ struct tiva_gptm32config_s config; /* Persistent timer configuration */
+ TIMER_HANDLE handle; /* Contained timer handle */
+ tccb_t handler; /* Current user interrupt handler */
+ uint32_t clkin; /* Input clock frequency */
+ uint32_t timeout; /* The current timeout value (us) */
+ uint32_t clkticks; /* Actual clock ticks for current interval */
+ uint32_t adjustment; /* Time lost due to clock resolution truncation (us) */
+ bool started; /* True: Timer has been started */
+};
+
+/****************************************************************************
+ * Private Function Prototypes
+ ****************************************************************************/
+/* Helper functions *********************************************************/
+
+static uint32_t tiva_usec2ticks(struct tiva_lowerhalf_s *priv, uint32_t usecs);
+static uint32_t tiva_ticks2usec(struct tiva_lowerhalf_s *priv, uint32_t ticks);
+
+/* Interrupt handling *******************************************************/
+
+static void tiva_handler(TIMER_HANDLE handle,
+ const struct tiva_gptm32config_s *config, uint32_t status);
+
+/* "Lower half" driver methods **********************************************/
+
+static int tiva_start(struct timer_lowerhalf_s *lower);
+static int tiva_stop(struct timer_lowerhalf_s *lower);
+static int tiva_getstatus(struct timer_lowerhalf_s *lower,
+ struct timer_status_s *status);
+static int tiva_settimeout(struct timer_lowerhalf_s *lower,
+ uint32_t timeout);
+static tccb_t tiva_sethandler(struct timer_lowerhalf_s *lower,
+ tccb_t handler);
+static int tiva_ioctl(struct timer_lowerhalf_s *lower, int cmd,
+ unsigned long arg);
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+/* "Lower half" driver methods */
+
+static const struct timer_ops_s g_timer_ops =
+{
+ .start = tiva_start,
+ .stop = tiva_stop,
+ .getstatus = tiva_getstatus,
+ .settimeout = tiva_settimeout,
+ .sethandler = tiva_sethandler,
+ .ioctl = tiva_ioctl,
+};
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: tiva_usec2ticks
+ *
+ * Description:
+ * Convert microseconds to timer clock ticks.
+ *
+ * Input Parameters:
+ * priv - A pointer to a private timer driver lower half instance
+ * usecs - The number of usecs to convert
+ *
+ * Returned Values:
+ * The time converted to clock ticks.
+ *
+ ****************************************************************************/
+
+static uint32_t tiva_usec2ticks(struct tiva_lowerhalf_s *priv, uint32_t usecs)
+{
+ uint64_t bigticks;
+
+ bigticks = ((uint64_t)usecs * (uint64_t)priv->clkin) / 1000000;
+ if (bigticks > UINT32_MAX)
+ {
+ return UINT32_MAX;
+ }
+
+ return (uint32_t)bigticks;
+}
+
+/****************************************************************************
+ * Name: tiva_ticks2usec
+ *
+ * Description:
+ * Convert timer clock ticks to microseconds.
+ *
+ * Input Parameters:
+ * priv - A pointer to a private timer driver lower half instance
+ * usecs - The number of ticks to convert
+ *
+ * Returned Values:
+ * The time converted to microseconds.
+ *
+ ****************************************************************************/
+
+static uint32_t tiva_ticks2usec(struct tiva_lowerhalf_s *priv, uint32_t ticks)
+{
+ uint64_t bigusec;
+
+ bigusec = (1000000ull * (uint64_t)ticks) / priv->clkin;
+ if (bigusec > UINT32_MAX)
+ {
+ return UINT32_MAX;
+ }
+
+ return (uint32_t)bigusec;
+}
+
+/****************************************************************************
+ * Name: tiva_handler
+ *
+ * Description:
+ * 32-bit timer interrupt handler
+ *
+ * Input Parameters:
+ * Usual 32-bit timer interrupt handler arguments.
+ *
+ * Returned Values:
+ * None
+ *
+ ****************************************************************************/
+
+static void tiva_handler(TIMER_HANDLE handle,
+ const struct tiva_gptm32config_s *config,
+ uint32_t status)
+{
+ struct tiva_lowerhalf_s *priv;
+
+ timvdbg("Entry\n");
+
+ /* Check if the timeout interrupt is pending */
+#warning Missing logic
+ {
+ uint32_t timeout;
+
+ /* Is there a registered handler? */
+
+ if (priv->handler && priv->handler(&priv->timeout))
+ {
+ /* Calculate new ticks / dither adjustment */
+
+ priv->clkticks = tiva_usec2ticks(priv, priv->adjustment + priv->timeout);
+
+ /* Set next interval interval. TODO: make sure the interval is not
+ * so soon it will be missed!
+ */
+#warning Missing logic
+
+ /* Calculate the next adjustment */
+
+ timeout = tiva_ticks2usec(priv, priv->clkticks);
+ priv->adjustment = (priv->adjustment + priv->timeout) - timeout;
+ }
+ else /* stop */
+ {
+ tiva_timer32_stop(priv->handle);
+ }
+ }
+}
+
+/****************************************************************************
+ * Name: tiva_start
+ *
+ * Description:
+ * Start the timer, resetting the time to the current timeout,
+ *
+ * Input Parameters:
+ * lower - A pointer the publicly visible representation of the "lower-half"
+ * driver state structure.
+ *
+ * Returned Values:
+ * Zero on success; a negated errno value on failure.
+ *
+ ****************************************************************************/
+
+static int tiva_start(struct timer_lowerhalf_s *lower)
+{
+ struct tiva_lowerhalf_s *priv = (struct tiva_lowerhalf_s *)lower;
+
+ timvdbg("Entry: started %d\n", priv->started);
+
+ /* Has the timer already been started? */
+
+ if (!priv->started)
+ {
+ /* Start the timer */
+
+ tiva_timer32_start(priv->handle);
+ priv->started = true;
+ return OK;
+ }
+
+ /* Return EBUSY to indicate that the timer was already running */
+
+ return -EBUSY;
+}
+
+/****************************************************************************
+ * Name: tiva_stop
+ *
+ * Description:
+ * Stop the timer
+ *
+ * Input Parameters:
+ * lower - A pointer the publicly visible representation of the "lower-half"
+ * driver state structure.
+ *
+ * Returned Values:
+ * Zero on success; a negated errno value on failure.
+ *
+ ****************************************************************************/
+
+static int tiva_stop(struct timer_lowerhalf_s *lower)
+{
+ struct tiva_lowerhalf_s *priv = (struct tiva_lowerhalf_s *)lower;
+
+ timvdbg("Entry: started %d\n", priv->started);
+
+ /* Has the timer already been started? */
+
+ if (priv->started)
+ {
+ /* Stop the timer */
+
+ tiva_timer32_stop(priv->handle);
+ priv->started = false;
+ return OK;
+ }
+
+ /* Return ENODEV to indicate that the timer was not running */
+
+ return -ENODEV;
+}
+
+/****************************************************************************
+ * Name: tiva_getstatus
+ *
+ * Description:
+ * Get the current timer status
+ *
+ * Input Parameters:
+ * lower - A pointer the publicly visible representation of the "lower-half"
+ * driver state structure.
+ * status - The location to return the status information.
+ *
+ * Returned Values:
+ * Zero on success; a negated errno value on failure.
+ *
+ ****************************************************************************/
+
+static int tiva_getstatus(struct timer_lowerhalf_s *lower,
+ struct timer_status_s *status)
+{
+ struct tiva_lowerhalf_s *priv = (struct tiva_lowerhalf_s *)lower;
+ uint32_t elapsed;
+
+ timvdbg("Entry\n");
+ DEBUGASSERT(priv);
+
+ /* Return the status bit */
+
+ status->flags = 0;
+ if (priv->started)
+ {
+ status->flags |= TCFLAGS_ACTIVE;
+ }
+
+ if (priv->handler)
+ {
+ status->flags |= TCFLAGS_HANDLER;
+ }
+
+ /* Return the actual timeout in microseconds */
+
+ status->timeout = priv->timeout;
+
+ /* Get the time remaining until the timer expires (in microseconds) */
+
+ //elapsed = ;
+ status->timeleft = ((uint64_t)priv->timeout * elapsed) / (priv->clkticks + 1); /* TODO - check on this +1 */
+
+ timvdbg(" flags : %08x\n", status->flags);
+ timvdbg(" timeout : %d\n", status->timeout);
+ timvdbg(" timeleft : %d\n", status->timeleft);
+ return OK;
+}
+
+/****************************************************************************
+ * Name: tiva_settimeout
+ *
+ * Description:
+ * Set a new timeout value (and reset the timer)
+ *
+ * Input Parameters:
+ * lower - A pointer the publicly visible representation of the "lower-half"
+ * driver state structure.
+ * timeout - The new timeout value in microseconds.
+ *
+ * Returned Values:
+ * Zero on success; a negated errno value on failure.
+ *
+ ****************************************************************************/
+
+static int tiva_settimeout(struct timer_lowerhalf_s *lower,
+ uint32_t timeout)
+{
+ struct tiva_lowerhalf_s *priv = (struct tiva_lowerhalf_s *)lower;
+
+ DEBUGASSERT(priv);
+
+ if (priv->started)
+ {
+ return -EPERM;
+ }
+
+ timvdbg("Entry: timeout=%d\n", timeout);
+
+ /* Save the desired timeout value */
+
+ priv->timeout = timeout;
+
+ /* Calculate the actual timeout value in clock ticks */
+
+ priv->clkticks = tiva_usec2ticks(priv, timeout);
+
+ /* Calculate an adjustment due to truncation in timer resolution */
+
+ timeout = tiva_ticks2usec(priv, priv->clkticks);
+ priv->adjustment = priv->timeout - timeout;
+
+ timvdbg("clkin=%d clkticks=%d timout=%d, adjustment=%d\n",
+ priv->clkin, priv->clkticks, priv->timeout, priv->adjustment);
+
+ /* Reset the timer interval */
+
+ tiva_timer32_setinterval(priv->handle, priv->clkticks);
+ return OK;
+}
+
+/****************************************************************************
+ * Name: tiva_sethandler
+ *
+ * Description:
+ * Call this user provided timeout handler.
+ *
+ * Input Parameters:
+ * lower - A pointer the publicly visible representation of the "lower-half"
+ * driver state structure.
+ * newhandler - The new timer expiration function pointer. If this
+ * function pointer is NULL, then the reset-on-expiration
+ * behavior is restored,
+ *
+ * Returned Values:
+ * The previous timer expiration function pointer or NULL is there was
+ * no previous function pointer.
+ *
+ ****************************************************************************/
+
+static tccb_t tiva_sethandler(struct timer_lowerhalf_s *lower,
+ tccb_t handler)
+{
+ struct tiva_lowerhalf_s *priv = (struct tiva_lowerhalf_s *)lower;
+ irqstate_t flags;
+ tccb_t oldhandler;
+
+ flags = irqsave();
+
+ DEBUGASSERT(priv);
+ timvdbg("Entry: handler=%p\n", handler);
+
+ /* Get the old handler return value */
+
+ oldhandler = priv->handler;
+
+ /* Save the new handler */
+
+ priv->handler = handler;
+
+ irqrestore(flags);
+ return oldhandler;
+}
+
+/****************************************************************************
+ * Name: tiva_ioctl
+ *
+ * Description:
+ * Any ioctl commands that are not recognized by the "upper-half" driver
+ * are forwarded to the lower half driver through this method.
+ *
+ * Input Parameters:
+ * lower - A pointer the publicly visible representation of the "lower-half"
+ * driver state structure.
+ * cmd - The ioctl command value
+ * arg - The optional argument that accompanies the 'cmd'. The
+ * interpretation of this argument depends on the particular
+ * command.
+ *
+ * Returned Values:
+ * Zero on success; a negated errno value on failure.
+ *
+ ****************************************************************************/
+
+static int tiva_ioctl(struct timer_lowerhalf_s *lower, int cmd,
+ unsigned long arg)
+{
+ struct tiva_lowerhalf_s *priv = (struct tiva_lowerhalf_s *)lower;
+ int ret = -ENOTTY;
+
+ DEBUGASSERT(priv);
+ timvdbg("Entry: cmd=%d arg=%ld\n", cmd, arg);
+
+ return ret;
+}
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: tiva_timer_register
+ *
+ * Description:
+ * Bind the configuration timer to a timer lower half instance and
+ * register the timer drivers at 'devpath'
+ *
+ * NOTE: Only 32-bit periodic timers are supported.
+ *
+ * Input Parameters:
+ * devpath - The full path to the timer device. This should be of the form
+ * /dev/timer0
+ * gptm - General purpose timer number
+ * timeout - Timeout interval in microseconds. Set to a non-zero value
+ * to enable timeout interrupts
+ * altlck - True: Use alternate clock source.
+ *
+ * Returned Values:
+ * Zero (OK) is returned on success; A negated errno value is returned
+ * to indicate the nature of any failure.
+ *
+ ****************************************************************************/
+
+int tiva_timer_register(const char *devpath, int gptm, uint32_t timeout,
+ bool altclk)
+{
+ struct tiva_lowerhalf_s *priv;
+ struct tiva_gptm32config_s *config;
+ void *rethandle;
+
+ DEBUGASSERT(devpath);
+ timvdbg("Entry: devpath=%s\n", devpath);
+
+ /* Allocate an instance of the lower half state structure */
+
+ priv = (struct tiva_lowerhalf_s *)kmm_zalloc(sizeof(struct tiva_lowerhalf_s));
+ if (!priv)
+ {
+ timdbg("ERROR: Failed to allocate driver structure\n");
+ return -ENOMEM;
+ }
+
+ /* Initialize the non-zero elements of lower half state structure */
+
+ priv->ops = &g_timer_ops;
+ priv->clkin = altclk ? ALTCLK_FREQUENCY : SYSCLK_FREQUENCY;
+ priv->timeout = timeout;
+
+ config = &priv->config;
+ config->cmn.gptm = gptm;
+ config->cmn.mode = TIMER32_MODE_PERIODIC;
+ config->cmn.alternate = altclk;
+ config->config.flags = TIMER_FLAG_COUNTUP;
+ config->config.handler = tiva_handler;
+ config->config.u.periodic.interval = tiva_usec2ticks(priv, timeout);
+
+ /* Create the timer handle */
+
+ priv->handle = tiva_gptm_configure((const struct tiva_gptmconfig_s *)&priv->config);
+ if (!priv->handle)
+ {
+ timdbg("ERROR: Failed to create timer handle\n");
+ return -EINVAL;
+ }
+
+ /* Register the timer driver as /dev/timerX. The returned value from
+ * timer_register is a handle that could be used with timer_unregister().
+ * REVISIT: The returned handle is discard here.
+ */
+
+ rethandle = timer_register(devpath, (struct timer_lowerhalf_s *)priv);
+ if (!rethandle)
+ {
+ /* Free the allocated state structure */
+
+ kmm_free(priv);
+
+ /* The actual cause of the failure may have been a failure to allocate
+ * perhaps a failure to register the timer driver (such as if the
+ * 'depath' were not unique). We know here but we return EEXIST to
+ * indicate the failure (implying the non-unique devpath).
+ */
+
+ return -EEXIST;
+ }
+
+ return OK;
+}
+
+#endif /* CONFIG_TIMER && CONFIG_TIVA_TIMER */