summaryrefslogtreecommitdiff
diff options
context:
space:
mode:
authorGregory Nutt <gnutt@nuttx.org>2015-01-14 07:33:59 -0600
committerGregory Nutt <gnutt@nuttx.org>2015-01-14 07:33:59 -0600
commita01e06ab4793815792918eafb2c68c2c4f6d32ea (patch)
tree2448ec897d100dae4fca3e6c9f8f046db830cd00
parent8e734a8cc7fb90106e99094653eca86c1f49b2b6 (diff)
downloadpx4-nuttx-a01e06ab4793815792918eafb2c68c2c4f6d32ea.tar.gz
px4-nuttx-a01e06ab4793815792918eafb2c68c2c4f6d32ea.tar.bz2
px4-nuttx-a01e06ab4793815792918eafb2c68c2c4f6d32ea.zip
Tiva Timer: Revert the previous change. Thre is a better way to handler timerout interrupts.
Removed setting of the initial timer interval load value (or, rather, it is always set to zero for a free-running timer). Also, do not unconditional enable the timer out interrupt. The timerout interrupt is not not enabled until tiva_timer32_setinterval() is called.
-rw-r--r--nuttx/arch/arm/src/tiva/tiva_timer.h93
-rw-r--r--nuttx/arch/arm/src/tiva/tiva_timerlib.c264
-rw-r--r--nuttx/arch/arm/src/tiva/tiva_timerlow32.c21
-rw-r--r--nuttx/configs/dk-tm4c129x/Kconfig4
-rw-r--r--nuttx/configs/dk-tm4c129x/README.txt1
-rw-r--r--nuttx/configs/dk-tm4c129x/src/tm4c_timer.c8
6 files changed, 215 insertions, 176 deletions
diff --git a/nuttx/arch/arm/src/tiva/tiva_timer.h b/nuttx/arch/arm/src/tiva/tiva_timer.h
index d1261e9e1..2c521f3a5 100644
--- a/nuttx/arch/arm/src/tiva/tiva_timer.h
+++ b/nuttx/arch/arm/src/tiva/tiva_timer.h
@@ -203,28 +203,7 @@ struct tiva_timer32config_s
* callback.
*/
- /* Mode-specific parameters */
-
- union
- {
-#ifdef CONFIG_TIVA_TIMER32_PERIODIC
- /* 32-bit programmable one-shot or periodic timer */
-
- struct
- {
- uint32_t interval; /* Value for interval load register */
- } periodic;
-#endif
-
-#ifdef CONFIG_TIVA_TIMER32_RTC
- /* 32-bit RTC with external 32.768-KHz input */
-
- struct
- {
- /* No special configuration settings */
- } rtc;
-#endif
- } u;
+ /* Mode-specific parameters may follow */
};
#endif
@@ -256,47 +235,7 @@ struct tiva_timer16config_s
* callback.
*/
- /* Mode-specific parameters */
-
- union
- {
-#ifdef CONFIG_TIVA_TIMER16_PERIODIC
- /* 16-bit programmable one-shot or periodic timer */
-
- struct
- {
- uint8_t prescaler; /* Prescaler-1: 0-255 corresponding to 1-256 */
- uint16_t interval; /* Value for interval load register */
- } periodic;
-#endif
-
-#ifdef CONFIG_TIVA_TIMER32_EDGECOUNT
- /* 16-bit input edge-count capture mode w/8-bit prescaler */
-
- struct
- {
- /* TODO: To be provided */
- } count;
-#endif
-
-#ifdef CONFIG_TIVA_TIMER32_TIMECAP
- /* 16-bit input time capture mode w/8-bit prescaler */
-
- struct
- {
- /* TODO: To be provided */
- } time;
-#endif
-
-#ifdef CONFIG_TIVA_TIMER32_PWM
- /* 16-bit PWM output mode w/8-bit prescaler */
-
- struct
- {
- /* TODO: To be provided */
- } pwm;
-#endif
- } u;
+ /* Mode-specific parameters may follow */
};
#endif
@@ -582,6 +521,12 @@ uint32_t tiva_timer16_counter(TIMER_HANDLE handle, int tmndx);
* This function may be called at any time to change the timer interval
* load value of a 32-bit timer.
*
+ * It the timer is configured as a 32-bit one-shot or periodic timer, then
+ * then function will also enable timeout interrupts.
+ *
+ * NOTE: As of this writing, there is no interface to disable the timeout
+ * interrupts once they have been enabled.
+ *
* Input Parameters:
* handle - The handle value returned by tiva_gptm_configure()
* interval - The value to write to the timer interval load register
@@ -602,6 +547,12 @@ void tiva_timer32_setinterval(TIMER_HANDLE handle, uint32_t interval);
* This function may be called at any time to change the timer interval
* load value of a 16-bit timer.
*
+ * It the timer is configured as a 16-bit one-shot or periodic timer, then
+ * then function will also enable timeout interrupts.
+ *
+ * NOTE: As of this writing, there is no interface to disable the timeout
+ * interrupts once they have been enabled.
+ *
* Input Parameters:
* handle - The handle value returned by tiva_gptm_configure()
* interval - The value to write to the timer interval load register
@@ -886,14 +837,17 @@ static inline void tiva_gptm0_synchronize(uint32_t sync)
* 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.
+ * NOTES:
+ * 1. Only 32-bit periodic timers are supported.
+ * 2. Timeout interrupts are disabled until tiva_timer32_setinterval() is
+ * called.
+ * 3. Match interrupts are disabled until tiva_timer32_relmatch() is
+ * called.
*
* Input Parameters:
- * devpath - The full path to the timer device. This should be of the form
- * /dev/timer0
+ * 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:
@@ -903,8 +857,7 @@ static inline void tiva_gptm0_synchronize(uint32_t sync)
****************************************************************************/
#ifdef CONFIG_TIMER
-int tiva_timer_register(FAR const char *devpath, int gptm, uint32_t timeout,
- bool altclk);
+int tiva_timer_register(FAR const char *devpath, int gptm, bool altclk);
#endif
#endif /* __ARCH_ARM_SRC_TIVA_TIVA_TIMER_H */
diff --git a/nuttx/arch/arm/src/tiva/tiva_timerlib.c b/nuttx/arch/arm/src/tiva/tiva_timerlib.c
index c805dbf76..ceaa37811 100644
--- a/nuttx/arch/arm/src/tiva/tiva_timerlib.c
+++ b/nuttx/arch/arm/src/tiva/tiva_timerlib.c
@@ -855,6 +855,9 @@ static int tiva_oneshot_periodic_mode32(struct tiva_gptmstate_s *priv,
* 0: The timer counts down (default).
* 1: The timer counts up. When counting up, the timer
* starts from a value of 0.
+ *
+ * NOTE: one-shot/periodic timeout interrupts remain disabled until
+ * tiva_timer32_setinterval is called.
*/
/* Setup defaults */
@@ -884,26 +887,6 @@ static int tiva_oneshot_periodic_mode32(struct tiva_gptmstate_s *priv,
*/
#warning Missing Logic
- /* Enable one-shot/periodic interrupts Enable interrupts only if an
- * non-NULL interrupt handler.
- */
-
- if (timer->handler)
- {
- /* Select the interrupt mask that will enable the timer interrupt.
- * Any non-zero value of imr indicates that interrupts are expected.
- */
-
- priv->imr = TIMER_INT_TATO;
-
- /* Clearing the TACINTD bit allows the time-out interrupt to be
- * generated as normal
- */
- /* REVISIT: When will interrupts be enabled? */
-
- regval &= ~TIMER_TnMR_TnCINTD;
- }
-
/* Enable count down? */
if (TIMER_ISCOUNTUP(timer))
@@ -950,25 +933,12 @@ static int tiva_oneshot_periodic_mode32(struct tiva_gptmstate_s *priv,
* 15:0 of the GPTM Timer B Interval Load (GPTMTBILR) register.
* Writes to GPTMTBILR are ignored.
*
- * REVISIT: When the ALTCLK bit is set in the GPTMCC register to enable
- * using the alternate clock source, the synchronization imposes
- * restrictions on the starting count value (down-count), terminal value
- * (up-count) and the match value. This restriction applies to all modes
- * of operation. Each event must be spaced by 4 Timer (ALTCLK) clock
- * periods + 2 system clock periods. If some events do not meet this
- * requirement, then it is possible that the timer block may need to be
- * reset for correct functionality to be restored.
- *
- * Example: ALTCLK= TPIOSC = 62.5ns (16Mhz Trimmed)
- * Thclk = 1us (1Mhz)
- * 4*62.5ns + 2*1us = 2.25us 2.25us/62.5ns = 36 or 0x23
- *
- * The minimum values for the periodic or one-shot with a match
- * interrupt enabled are: GPTMTAMATCHR = 0x23 GPTMTAILR = 0x46"
+ * NOTE: The default is a free-running timer. The timer interval
+ * reload register is clear here. It can be set to any value
+ * desired by calling tiva_timer32_setinterval().
*/
- regval = timer->u.periodic.interval;
- tiva_putreg(priv, TIVA_TIMER_TAILR_OFFSET, regval);
+ tiva_putreg(priv, TIVA_TIMER_TAILR_OFFSET, 0);
/* Preload the timer counter register by setting the timer value register.
* The timer value will be copied to the timer counter register on the
@@ -1090,6 +1060,9 @@ static int tiva_oneshot_periodic_mode16(struct tiva_gptmstate_s *priv,
* 0: The timer counts down (default).
* 1: The timer counts up. When counting up, the timer
* starts from a value of 0.
+ *
+ * NOTE: one-shot/periodic timeout interrupts remain disabled until
+ * tiva_timer32_setinterval is called.
*/
/* Setup defaults */
@@ -1119,26 +1092,6 @@ static int tiva_oneshot_periodic_mode16(struct tiva_gptmstate_s *priv,
*/
#warning Missing Logic
- /* Enable one-shot/periodic interrupts? Enable interrupts only if an
- * interrupt handler was provided.
- */
-
- if (timer->handler)
- {
- /* Select the interrupt mask that will enable the timer interrupt.
- * Any non-zero value of 'imr' indicates that interrupts are expected.
- */
-
- priv->imr |= tmndx ? TIMER_INT_TBTO : TIMER_INT_TATO;
-
- /* Clearing the TnCINTD bit allows the time-out interrupt to be
- * generated as normal
- */
- /* REVISIT: When will interrupts be enabled? */
-
- regval &= ~TIMER_TnMR_TnCINTD;
- }
-
/* Enable count down? */
if (TIMER_ISCOUNTUP(timer))
@@ -1178,34 +1131,19 @@ static int tiva_oneshot_periodic_mode16(struct tiva_gptmstate_s *priv,
*/
#warning Missing Logic
- /* Set the input clock pre-scaler value */
-
- regoffset = tmndx ? TIVA_TIMER_TBPR_OFFSET : TIVA_TIMER_TAPR_OFFSET;
- tiva_putreg(priv, regoffset, (uint32_t)timer->u.periodic.prescaler);
-
/* 5. Load the start value into the GPTM Timer n Interval Load Register
* (GPTMTnILR).
*
- * REVISIT: When the ALTCLK bit is set in the GPTMCC register to enable
- * using the alternate clock source, the synchronization imposes
- * restrictions on the starting count value (down-count), terminal value
- * (up-count) and the match value. This restriction applies to all modes
- * of operation. Each event must be spaced by 4 Timer (ALTCLK) clock
- * periods + 2 system clock periods. If some events do not meet this
- * requirement, then it is possible that the timer block may need to be
- * reset for correct functionality to be restored.
- *
- * Example: ALTCLK= TPIOSC = 62.5ns (16Mhz Trimmed)
- * Thclk = 1us (1Mhz)
- * 4*62.5ns + 2*1us = 2.25us 2.25us/62.5ns = 36 or 0x23
- *
- * The minimum values for the periodic or one-shot with a match
- * interrupt enabled are: GPTMTAMATCHR = 0x23 GPTMTAILR = 0x46"
+ * NOTE: The default is a free-running timer. The timer interval
+ * reload and prescale registers are cleared here. They can be set to
+ * any value desired by calling tiva_timer32_setinterval().
*/
- regval = (uint32_t)timer->u.periodic.interval;
+ regoffset = tmndx ? TIVA_TIMER_TBPR_OFFSET : TIVA_TIMER_TAPR_OFFSET;
+ tiva_putreg(priv, regoffset, 0);
+
regoffset = tmndx ? TIVA_TIMER_TBILR_OFFSET : TIVA_TIMER_TAILR_OFFSET;
- tiva_putreg(priv, regoffset, regval);
+ tiva_putreg(priv, regoffset, 0);
/* Preload the timer counter register by setting the timer value register.
* The timer value will be copied to the timer counter register on the
@@ -2324,6 +2262,12 @@ uint32_t tiva_timer16_counter(TIMER_HANDLE handle, int tmndx)
* This function may be called at any time to change the timer interval
* load value of a 32-bit timer.
*
+ * It the timer is configured as a 32-bit one-shot or periodic timer, then
+ * then function will also enable timeout interrupts.
+ *
+ * NOTE: As of this writing, there is no interface to disable the timeout
+ * interrupts once they have been enabled.
+ *
* REVISIT: When the ALTCLK bit is set in the GPTMCC register to enable
* using the alternate clock source, the synchronization imposes
* restrictions on the starting count value (down-count), terminal value
@@ -2353,13 +2297,80 @@ uint32_t tiva_timer16_counter(TIMER_HANDLE handle, int tmndx)
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 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 enable timeout interrupts? Interrupts are only enabled
+ * if (1) the user has provided a handler, and (2) the timer timer is
+ * configure as a one-short or periodic timer.
+ */
+
+ base = priv->attr->base;
+ toints = false;
+
+ if (timer->handler &&
+ (config->cmn.mode == TIMER32_MODE_ONESHOT ||
+ config->cmn.mode == TIMER32_MODE_PERIODIC))
+ {
+ toints = true;
+ }
+
+ loadr = base + TIVA_TIMER_TAILR_OFFSET;
+ moder = base + TIVA_TIMER_TAMR_OFFSET;
+ imrr = base + TIVA_TIMER_IMR_OFFSET;
+
+ /* Make the following atomic */
+
+ flags = irqsave();
/* Set the new timeout interval */
- tiva_putreg(priv, TIVA_TIMER_TAILR_OFFSET, 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 = getreg32(moder);
+ modev2 = modev1 & ~TIMER_TnMR_TnCINTD;
+ putreg32(modev2, moder);
+
+ /* Set the new interrupt mask */
+
+ priv->imr |= TIMER_INT_TATO;
+ 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);
+ if (toints)
+ {
+ lldbg("%08x->%08x\n", moder, modev1);
+ lldbg("%08x<-%08x\n", moder, modev2);
+ lldbg("%08x<-%08x\n", imrr, priv->imr);
+ }
+#endif
}
#endif
@@ -2370,6 +2381,12 @@ void tiva_timer32_setinterval(TIMER_HANDLE handle, uint32_t interval)
* This function may be called at any time to change the timer interval
* load value of a 16-bit timer.
*
+ * It the timer is configured as a 16-bit one-shot or periodic timer, then
+ * then function will also enable timeout interrupts.
+ *
+ * NOTE: As of this writing, there is no interface to disable the timeout
+ * interrupts once they have been enabled.
+ *
* REVISIT: When the ALTCLK bit is set in the GPTMCC register to enable
* using the alternate clock source, the synchronization imposes
* restrictions on the starting count value (down-count), terminal value
@@ -2400,15 +2417,93 @@ void tiva_timer32_setinterval(TIMER_HANDLE handle, uint32_t interval)
void tiva_timer16_setinterval(TIMER_HANDLE handle, uint16_t interval, int tmndx)
{
struct tiva_gptmstate_s *priv = (struct tiva_gptmstate_s *)handle;
- unsigned int regoffset;
+ 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 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;
+ }
+
+ imrr = base + TIVA_TIMER_IMR_OFFSET;
+
+ /* Do we need to enable timeout interrupts? Interrupts are only enabled
+ * if (1) the user has provided a handler, and (2) the timer timer is
+ * configure as a one-short or periodic timer.
+ */
+
+ toints = false;
+ if (timer->handler &&
+ (config->cmn.mode == TIMER16_MODE_ONESHOT ||
+ config->cmn.mode == TIMER16_MODE_PERIODIC))
+ {
+ toints = true;
+ }
+
+ /* Make the following atomic */
+
+ flags = irqsave();
/* Set the new timeout interval */
- regoffset = tmndx ? TIVA_TIMER_TBILR_OFFSET : TIVA_TIMER_TAILR_OFFSET;
- tiva_putreg(priv, regoffet, 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 = getreg32(moder);
+ modev2 = modev1 & ~TIMER_TnMR_TnCINTD;
+ putreg32(modev2, moder);
+
+ /* Set the new interrupt mask */
+
+ priv->imr |= intbit;
+ 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);
+ if (toints)
+ {
+ lldbg("%08x->%08x\n", moder, modev1);
+ lldbg("%08x<-%08x\n", moder, modev2);
+ lldbg("%08x<-%08x\n", imrr, priv->imr);
+ }
+#endif
}
#endif
@@ -2495,7 +2590,7 @@ uint32_t tiva_timer32_remaining(TIMER_HANDLE handle)
* REVISIT: Or the difference +1?
*/
- DEBUGASSERT(interval >= counter);
+ DEBUGASSERT(interval == 0 || interval >= counter);
remaining = interval - counter;
}
else
@@ -2897,3 +2992,4 @@ void tiva_timer16_relmatch(TIMER_HANDLE handle, uint32_t relmatch, int tmndx)
#endif
}
#endif
+
diff --git a/nuttx/arch/arm/src/tiva/tiva_timerlow32.c b/nuttx/arch/arm/src/tiva/tiva_timerlow32.c
index 20bf600a8..53252e3bf 100644
--- a/nuttx/arch/arm/src/tiva/tiva_timerlow32.c
+++ b/nuttx/arch/arm/src/tiva/tiva_timerlow32.c
@@ -398,7 +398,7 @@ static int tiva_getstatus(struct timer_lowerhalf_s *lower,
/* Get the time remaining until the timer expires (in microseconds). */
remaining = tiva_timer32_remaining(priv->handle);
- status->timeleft = tiva_ticks2usec(priv, remaining);
+ status->timeleft = tiva_ticks2usec(priv, remaining);
timvdbg(" flags : %08x\n", status->flags);
timvdbg(" timeout : %d\n", status->timeout);
@@ -531,14 +531,17 @@ static int tiva_ioctl(struct timer_lowerhalf_s *lower, int cmd,
* 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.
+ * NOTES:
+ * 1. Only 32-bit periodic timers are supported.
+ * 2. Timeout interrupts are disabled until tiva_timer32_setinterval() is
+ * called.
+ * 3. Match interrupts are disabled until tiva_timer32_relmatch() is
+ * called.
*
* Input Parameters:
- * devpath - The full path to the timer device. This should be of the form
- * /dev/timer0
+ * 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:
@@ -547,8 +550,7 @@ static int tiva_ioctl(struct timer_lowerhalf_s *lower, int cmd,
*
****************************************************************************/
-int tiva_timer_register(const char *devpath, int gptm, uint32_t timeout,
- bool altclk)
+int tiva_timer_register(FAR const char *devpath, int gptm, bool altclk)
{
struct tiva_lowerhalf_s *priv;
struct tiva_gptm32config_s *config;
@@ -579,11 +581,10 @@ int tiva_timer_register(const char *devpath, int gptm, uint32_t timeout,
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 */
- tiva_timeout(priv, timeout);
+ tiva_timeout(priv, 0);
/* Create the timer handle */
diff --git a/nuttx/configs/dk-tm4c129x/Kconfig b/nuttx/configs/dk-tm4c129x/Kconfig
index 1c2cd6be7..27e1b933c 100644
--- a/nuttx/configs/dk-tm4c129x/Kconfig
+++ b/nuttx/configs/dk-tm4c129x/Kconfig
@@ -65,10 +65,6 @@ config DK_TM4C129X_TIMER_DEVNAME
string "Timer device name"
default "/dev/timer0"
-config DK_TM4C129X_TIMER_TIMEOUT
- int "Timer interval (microseconds)"
- default 10000
-
config DK_TM4C129X_TIMER_ALTCLK
bool "Use alternate clock source"
default n
diff --git a/nuttx/configs/dk-tm4c129x/README.txt b/nuttx/configs/dk-tm4c129x/README.txt
index 46e633c31..010e91854 100644
--- a/nuttx/configs/dk-tm4c129x/README.txt
+++ b/nuttx/configs/dk-tm4c129x/README.txt
@@ -684,7 +684,6 @@ Timers
Application Configure -> Examples -> Timer Example
CONFIG_EXAMPLES_TIMER=y
CONFIG_EXAMPLE_TIMER_DEVNAME="/dev/timer0"
- CONFIG_EXAMPLE_TIMER_INTERVAL=1000000
CONFIG_EXAMPLE_TIMER_DELAY=100000
CONFIG_EXAMPLE_TIMER_NSAMPLES=20
diff --git a/nuttx/configs/dk-tm4c129x/src/tm4c_timer.c b/nuttx/configs/dk-tm4c129x/src/tm4c_timer.c
index c9a5d51c8..0383ebdd7 100644
--- a/nuttx/configs/dk-tm4c129x/src/tm4c_timer.c
+++ b/nuttx/configs/dk-tm4c129x/src/tm4c_timer.c
@@ -83,10 +83,6 @@
# define CONFIG_DK_TM4C129X_TIMER_DEVNAME "/dev/timer0"
#endif
-#ifndef CONFIG_DK_TM4C129X_TIMER_TIMEOUT
-# define CONFIG_DK_TM4C129X_TIMER_TIMEOUT 10000
-#endif
-
#undef CONFIG_DK_TM4C129X_TIMER_ALTCLK
#define ALTCLK false
@@ -107,10 +103,8 @@ int tiva_timer_initialize(void)
int ret;
timvdbg("Registering TIMER%d at %s\n", GPTM, CONFIG_DK_TM4C129X_TIMER_DEVNAME);
- timvdbg("Initial timer period: %d uS\n", CONFIG_DK_TM4C129X_TIMER_TIMEOUT);
- ret = tiva_timer_register(CONFIG_DK_TM4C129X_TIMER_DEVNAME, GPTM,
- CONFIG_DK_TM4C129X_TIMER_TIMEOUT, ALTCLK);
+ ret = tiva_timer_register(CONFIG_DK_TM4C129X_TIMER_DEVNAME, GPTM, ALTCLK);
if (ret < 0)
{
timdbg("ERROR: Failed to register timer driver: %d\n", ret);