summaryrefslogtreecommitdiff
diff options
context:
space:
mode:
authorGregory Nutt <gnutt@nuttx.org>2015-01-13 10:06:40 -0600
committerGregory Nutt <gnutt@nuttx.org>2015-01-13 10:06:40 -0600
commitedcf7fabf866e78fa927b6d31c6c82d6b1c7c6a4 (patch)
tree300d4a9c34de39fc528fadc29caf82b05ed8d0d0
parentbf6fff346b6bbcd6528848f6edd5160bcaac97d2 (diff)
downloadpx4-nuttx-edcf7fabf866e78fa927b6d31c6c82d6b1c7c6a4.tar.gz
px4-nuttx-edcf7fabf866e78fa927b6d31c6c82d6b1c7c6a4.tar.bz2
px4-nuttx-edcf7fabf866e78fa927b6d31c6c82d6b1c7c6a4.zip
Tiva Timer: Completes implementation of the timer driver lower half
-rw-r--r--nuttx/arch/arm/src/tiva/tiva_timer.h54
-rw-r--r--nuttx/arch/arm/src/tiva/tiva_timerlib.c111
-rw-r--r--nuttx/arch/arm/src/tiva/tiva_timerlow.c71
3 files changed, 202 insertions, 34 deletions
diff --git a/nuttx/arch/arm/src/tiva/tiva_timer.h b/nuttx/arch/arm/src/tiva/tiva_timer.h
index d3f8f98ac..2b16dfb2a 100644
--- a/nuttx/arch/arm/src/tiva/tiva_timer.h
+++ b/nuttx/arch/arm/src/tiva/tiva_timer.h
@@ -183,14 +183,13 @@ typedef FAR void *TIMER_HANDLE;
*
* Input Parameters:
* handle - The same value as returned by tiva_gptm_configure()
- * config - The same value provided as as an input to tiva_gptm_configure()
+ * arg - The same value provided in struct tiva_timer32config_s
* status - The value of the GPTM masked status register that caused the
* interrupt
*/
struct tiva_gptm32config_s;
-typedef void (*timer32_handler_t)(TIMER_HANDLE handle,
- const struct tiva_gptm32config_s *config,
+typedef void (*timer32_handler_t)(TIMER_HANDLE handle, void *arg,
uint32_t status);
/* This structure describes the configuration of one 32-bit timer */
@@ -200,6 +199,9 @@ struct tiva_timer32config_s
uint8_t flags; /* See TIMER_FLAG_* definitions */
timer32_handler_t handler; /* Non-NULL: Interrupts will be enabled
* and forwarded to this function */
+ void *arg; /* Argument that accompanies the handler
+ * callback.
+ */
/* Mode-specific parameters */
@@ -231,7 +233,7 @@ struct tiva_timer32config_s
*
* Input Parameters:
* handle - The same value as returned by tiva_gptm_configure()
- * config - The same value provided as as an input to tiva_gptm_configure()
+ * arg - The same value provided in struct tiva_timer16config_s
* status - The value of the GPTM masked status register that caused the
* interrupt.
* tmndx - Either TIMER16A or TIMER16B. This may be useful in the
@@ -239,8 +241,7 @@ struct tiva_timer32config_s
*/
struct tiva_gptm16config_s;
-typedef void (*timer16_handler_t)(TIMER_HANDLE handle,
- const struct tiva_gptm16config_s *config,
+typedef void (*timer16_handler_t)(TIMER_HANDLE handle, void *arg,
uint32_t status, int tmndx);
/* This structure describes the configuration of one 16-bit timer A/B */
@@ -251,6 +252,9 @@ struct tiva_timer16config_s
uint8_t flags; /* See TIMER_FLAG_* definitions */
timer16_handler_t handler; /* Non-NULL: Interrupts will be enabled
* and forwarded to this function */
+ void *arg; /* Argument that accompanies the handler
+ * callback.
+ */
/* Mode-specific parameters */
@@ -616,6 +620,44 @@ void tiva_timer16_setinterval(TIMER_HANDLE handle, uint16_t interval, int tmndx)
#endif
/****************************************************************************
+ * Name: tiva_timer32_remaining
+ *
+ * Description:
+ * Get the time remaining before a one-shot or periodic 32-bit timer
+ * expires.
+ *
+ * Input Parameters:
+ * handle - The handle value returned by tiva_gptm_configure().
+ *
+ * Returned Value:
+ * Time remaining until the next timeout interrupt.
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_TIVA_TIMER32_PERIODIC
+uint32_t tiva_timer32_remaining(TIMER_HANDLE handle);
+#endif
+
+/****************************************************************************
+ * Name: tiva_timer16_remaining
+ *
+ * Description:
+ * Get the time remaining before a one-shot or periodic 16-bit timer
+ * expires.
+ *
+ * Input Parameters:
+ * handle - The handle value returned by tiva_gptm_configure().
+ *
+ * Returned Value:
+ * Time remaining until the next timeout interrupt.
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_TIVA_TIMER16_PERIODIC
+/* To be provided */
+#endif
+
+/****************************************************************************
* Name: tiva_timer32_absmatch
*
* Description:
diff --git a/nuttx/arch/arm/src/tiva/tiva_timerlib.c b/nuttx/arch/arm/src/tiva/tiva_timerlib.c
index dbaa8d975..f3b3a8b1d 100644
--- a/nuttx/arch/arm/src/tiva/tiva_timerlib.c
+++ b/nuttx/arch/arm/src/tiva/tiva_timerlib.c
@@ -536,7 +536,7 @@ static int tiva_timer32_interrupt(struct tiva_gptmstate_s *priv)
DEBUGASSERT(timer32->handler);
if (timer32->handler)
{
- timer32->handler((TIMER_HANDLE)priv, config32, status);
+ timer32->handler((TIMER_HANDLE)priv, timer32->arg, status);
}
}
@@ -662,7 +662,7 @@ static int tiva_timer16_interrupt(struct tiva_gptmstate_s *priv, int tmndx)
DEBUGASSERT(timer16->handler);
if (timer16->handler)
{
- timer16->handler((TIMER_HANDLE)priv, config16, status, tmndx);
+ timer16->handler((TIMER_HANDLE)priv, timer16->arg, status, tmndx);
}
}
@@ -2589,6 +2589,113 @@ void tiva_timer16_setinterval(TIMER_HANDLE handle, uint16_t interval, int tmndx)
#endif
/****************************************************************************
+ * Name: tiva_timer32_remaining
+ *
+ * Description:
+ * Get the time remaining before a one-shot or periodic 32-bit timer
+ * expires.
+ *
+ * Input Parameters:
+ * handle - The handle value returned by tiva_gptm_configure().
+ *
+ * Returned Value:
+ * Time remaining until the next timeout interrupt.
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_TIVA_TIMER32_PERIODIC
+uint32_t tiva_timer32_remaining(TIMER_HANDLE handle)
+{
+ struct tiva_gptmstate_s *priv = (struct tiva_gptmstate_s *)handle;
+ const struct tiva_gptm32config_s *config;
+ irqstate_t flags;
+ uint32_t counter;
+ uint32_t status;
+ uint32_t interval;
+ uint32_t remaining;
+
+ timvdbg("Entry\n");
+
+ DEBUGASSERT(priv && priv->attr && priv->config &&
+ priv->config->mode != TIMER16_MODE);
+
+ config = (const struct tiva_gptm32config_s *)priv->config;
+ DEBUGASSERT(config->cmn.mode == TIMER32_MODE_ONESHOT ||
+ config->cmn.mode == TIMER32_MODE_PERIODIC);
+
+ /* These values can be modified if a timer interrupt were to occur. Best
+ * to do this is a critical section.
+ */
+
+ flags = irqsave();
+
+ /* Get the time remaining until the timer expires (in clock ticks).
+ * Since we have selected a count-up timer timer and the interval will
+ * expire when the count-up timer equals the timeout value, the
+ * difference between the current count value and the timeout is the
+ * time remaining.
+ *
+ * There is a race condition here. What if the timer expires and
+ * counter rolls over between the time that we disabled interrupts
+ * above and the time that we read the counter below?
+ */
+
+ counter = tiva_getreg(priv, TIVA_TIMER_TAR_OFFSET);
+
+ /* If the timer rolled over, there would be a pending timer interrupt. In
+ * that case, the time remaining time is zero.
+ */
+
+ status = tiva_getreg(priv, TIVA_TIMER_MIS_OFFSET);
+ if ((status & TIMER_INT_TATO) != 0)
+ {
+ remaining = 0;
+ }
+ else
+ {
+ /* Is this a count-up or a count-down timer? */
+
+ if (TIMER_ISCOUNTUP(&config->config))
+ {
+ /* Counting up.. When the timer is counting up and it reaches the
+ * timeout event (the value in the GPTMTAILR, the timer reloads
+ * with zero.
+ *
+ * Get the current timer interval value */
+
+ interval = tiva_getreg(priv, TIVA_TIMER_TAILR_OFFSET);
+
+ /* The time remaining is the current interval reload value minus
+ * the above sampled counter value.
+ *
+ * REVISIT: Or the difference +1?
+ */
+
+ DEBUGASSERT(interval >= counter);
+ remaining = interval - counter;
+ }
+ else
+ {
+ /* Counting down: When the timer is counting down and it reaches
+ * the timeout event (0x0), the timer reloads its start value
+ * from the GPTMTAILR register on the next cycle.
+ *
+ * The time remaining it then just the the value of the counter
+ * register.
+ *
+ * REVISIT: Or the counter value +1?
+ */
+
+ remaining = counter;
+ }
+ }
+
+ irqrestore(flags);
+ return remaining;
+}
+#endif
+
+/****************************************************************************
* Name: tiva_rtc_setalarm
*
* Description:
diff --git a/nuttx/arch/arm/src/tiva/tiva_timerlow.c b/nuttx/arch/arm/src/tiva/tiva_timerlow.c
index 9959d80fe..261421af4 100644
--- a/nuttx/arch/arm/src/tiva/tiva_timerlow.c
+++ b/nuttx/arch/arm/src/tiva/tiva_timerlow.c
@@ -76,7 +76,7 @@ struct tiva_lowerhalf_s
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) */
+ uint32_t adjustment; /* Time lost due to truncation (us) */
bool started; /* True: Timer has been started */
};
@@ -90,8 +90,7 @@ 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);
+static void tiva_handler(TIMER_HANDLE handle, void *arg, uint32_t status);
/* "Lower half" driver methods **********************************************/
@@ -195,16 +194,16 @@ static uint32_t tiva_ticks2usec(struct tiva_lowerhalf_s *priv, uint32_t ticks)
*
****************************************************************************/
-static void tiva_handler(TIMER_HANDLE handle,
- const struct tiva_gptm32config_s *config,
- uint32_t status)
+static void tiva_handler(TIMER_HANDLE handle, void *arg, uint32_t status)
{
- struct tiva_lowerhalf_s *priv;
+ struct tiva_lowerhalf_s *priv = (struct tiva_lowerhalf_s *)arg;
- timvdbg("Entry\n");
+ timvdbg("Entry: status=%08x\n", status);
+ DEBUGASSERT(arg && status);
/* Check if the timeout interrupt is pending */
-#warning Missing logic
+
+ if ((status & TIMER_INT_TATO) != 0)
{
uint32_t timeout;
@@ -219,7 +218,12 @@ static void tiva_handler(TIMER_HANDLE handle,
/* Set next interval interval. TODO: make sure the interval is not
* so soon it will be missed!
*/
-#warning Missing logic
+
+#if 0 /* Too much in this context */
+ tiva_timer32_setinterval(priv->handle, priv->clkticks);
+#else
+ tiva_gptm_putreg(priv->handle, TIVA_TIMER_TAILR_OFFSET, priv->clkticks);
+#endif
/* Calculate the next adjustment */
@@ -327,7 +331,7 @@ 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;
+ uint32_t remaining;
timvdbg("Entry\n");
DEBUGASSERT(priv);
@@ -349,14 +353,14 @@ static int tiva_getstatus(struct timer_lowerhalf_s *lower,
status->timeout = priv->timeout;
- /* Get the time remaining until the timer expires (in microseconds) */
+ /* 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 */
+ remaining = tiva_timer32_remaining(priv->handle);
+ status->timeleft = tiva_ticks2usec(priv, remaining);
timvdbg(" flags : %08x\n", status->flags);
- timvdbg(" timeout : %d\n", status->timeout);
- timvdbg(" timeleft : %d\n", status->timeleft);
+ timvdbg(" timeout : %d\n", status->timeout);
+ timvdbg(" timeleft : %d\n", status->timeleft);
return OK;
}
@@ -519,7 +523,8 @@ int tiva_timer_register(const char *devpath, int gptm, uint32_t timeout,
{
struct tiva_lowerhalf_s *priv;
struct tiva_gptm32config_s *config;
- void *rethandle;
+ void *drvr;
+ int ret;
DEBUGASSERT(devpath);
timvdbg("Entry: devpath=%s\n", devpath);
@@ -537,7 +542,6 @@ int tiva_timer_register(const char *devpath, int gptm, uint32_t timeout,
priv->ops = &g_timer_ops;
priv->clkin = altclk ? ALTCLK_FREQUENCY : SYSCLK_FREQUENCY;
- priv->timeout = timeout;
config = &priv->config;
config->cmn.gptm = gptm;
@@ -545,15 +549,26 @@ int tiva_timer_register(const char *devpath, int gptm, uint32_t timeout,
config->cmn.alternate = altclk;
config->config.flags = TIMER_FLAG_COUNTUP;
config->config.handler = tiva_handler;
+ config->config.arg = priv;
config->config.u.periodic.interval = tiva_usec2ticks(priv, timeout);
+ /* Set the initial timer interval */
+
+ ret = tiva_settimeout((struct timer_lowerhalf_s *)priv, timeout);
+ if (ret < 0)
+ {
+ timdbg("ERROR: Failed to set initial timeout\n");
+ goto errout_with_alloc;
+ }
+
/* 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;
+ ret = -EINVAL;
+ goto errout_with_alloc;
}
/* Register the timer driver as /dev/timerX. The returned value from
@@ -561,23 +576,27 @@ int tiva_timer_register(const char *devpath, int gptm, uint32_t timeout,
* REVISIT: The returned handle is discard here.
*/
- rethandle = timer_register(devpath, (struct timer_lowerhalf_s *)priv);
- if (!rethandle)
+ drvr = timer_register(devpath, (struct timer_lowerhalf_s *)priv);
+ if (!drvr)
{
- /* 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;
+ ret = -EEXIST;
+ goto errout_with_timer;
}
return OK;
+
+errout_with_timer:
+ tiva_gptm_release(priv->handle); /* Free timer resources */
+
+errout_with_alloc:
+ kmm_free(priv); /* Free the allocated state structure */
+ return ret; /* Return the error indication */
}
#endif /* CONFIG_TIMER && CONFIG_TIVA_TIMER */