From 27638628c44be1afb605e8859c97be3d41412ab5 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Tue, 3 Feb 2015 07:00:54 -0600 Subject: SAM4CM: Add support for tickless operation --- nuttx/arch/arm/src/sam34/Kconfig | 133 +++ nuttx/arch/arm/src/sam34/Make.defs | 17 +- nuttx/arch/arm/src/sam34/chip/sam_tc.h | 11 +- nuttx/arch/arm/src/sam34/sam4cm_freerun.c | 314 +++++++ nuttx/arch/arm/src/sam34/sam4cm_freerun.h | 156 ++++ nuttx/arch/arm/src/sam34/sam4cm_oneshot.c | 448 ++++++++++ nuttx/arch/arm/src/sam34/sam4cm_oneshot.h | 178 ++++ nuttx/arch/arm/src/sam34/sam4cm_tc.c | 1287 ++++++++++++++++++++++++++++ nuttx/arch/arm/src/sam34/sam4cm_tc.h | 362 ++++++++ nuttx/arch/arm/src/sam34/sam4cm_tickless.c | 376 ++++++++ 10 files changed, 3276 insertions(+), 6 deletions(-) create mode 100644 nuttx/arch/arm/src/sam34/sam4cm_freerun.c create mode 100644 nuttx/arch/arm/src/sam34/sam4cm_freerun.h create mode 100644 nuttx/arch/arm/src/sam34/sam4cm_oneshot.c create mode 100644 nuttx/arch/arm/src/sam34/sam4cm_oneshot.h create mode 100644 nuttx/arch/arm/src/sam34/sam4cm_tc.c create mode 100644 nuttx/arch/arm/src/sam34/sam4cm_tc.h create mode 100644 nuttx/arch/arm/src/sam34/sam4cm_tickless.c (limited to 'nuttx/arch/arm') diff --git a/nuttx/arch/arm/src/sam34/Kconfig b/nuttx/arch/arm/src/sam34/Kconfig index 464bec6b7..2613d7441 100644 --- a/nuttx/arch/arm/src/sam34/Kconfig +++ b/nuttx/arch/arm/src/sam34/Kconfig @@ -929,6 +929,139 @@ config SAM34_GPIOF_IRQ endif # SAM34_GPIO_IRQ endmenu # AT91SAM3/4 GPIO Interrupt Configuration +menu "AT91SAM3/4 Timer/Counter Configuration" + depends on SAM34_TC + +config SAM34_TC0_CLK + bool "Enable TC channel 0 clock input pin" + default n + depends on SAM34_TC0 + +config SAM34_TC0_TIOA + bool "Enable TC channel 0 output A" + default n + depends on SAM34_TC0 + +config SAM34_TC0_TIOB + bool "Enable TC channel 0 output B" + default n + depends on SAM34_TC0 + +config SAM34_TC1_CLK + bool "Enable TC channel 1 clock input pin" + default n + depends on SAM34_TC1 + +config SAM34_TC1_TIOA + bool "Enable TC channel 1 output A" + default n + depends on SAM34_TC1 + +config SAM34_TC1_TIOB + bool "Enable TC channel 1 output B" + default n + depends on SAM34_TC1 + +config SAM34_TC2_CLK + bool "Enable TC channel 2 clock input pin" + default n + depends on SAM34_TC2 + +config SAM34_TC2_TIOA2 + bool "Enable TC channel 2 output A" + default n + depends on SAM34_TC2 + +config SAM34_TC2_TIOB2 + bool "Enable TC channel 2 output B" + default n + depends on SAM34_TC2 + +config SAM34_TC3_CLK + bool "Enable TC channel 3 clock input pin" + default n + depends on SAM34_TC3 + +config SAM34_TC3_TIOA + bool "Enable TC channel 3 output A" + default n + depends on SAM34_TC3 + +config SAM34_TC3_TIOB + bool "Enable TC channel 3 output B" + default n + depends on SAM34_TC3 + +config SAM34_TC4_CLK + bool "Enable TC channel 4 clock input pin" + default n + depends on SAM34_TC4 + +config SAM34_TC4_TIOA + bool "Enable TC channel 4 output A" + default n + depends on SAM34_TC4 + +config SAM34_TC4_TIOB + bool "Enable TC channel 4 output B" + default n + depends on SAM34_TC4 + +config SAM34_TC5_CLK + bool "Enable TC channel 5 clock input pin" + default n + depends on SAM34_TC5 + +config SAM34_TC5_TIOA + bool "Enable TC channel 5 output A" + default n + depends on SAM34_TC5 + +config SAM34_TC5_TIOB + bool "Enable TC channel 5 output B" + default n + depends on SAM34_TC5 + +config SAM34_ONESHOT + bool "TC one-shot wrapper" + default n if !SCHED_TICKLESS + default y if SCHED_TICKLESS + ---help--- + Enable a wrapper around the low level timer/counter functions to + support one-shot timer. + +config SAM34_FREERUN + bool "TC free-running wrapper" + default n if !SCHED_TICKLESS + default y if SCHED_TICKLESS + ---help--- + Enable a wrapper around the low level timer/counter functions to + support a free-running timer. + +endif # ARCH_CHIP_SAM4CM + +if SCHED_TICKLESS + +config SAM34_TICKLESS_ONESHOT + int "Tickless one-shot timer channel" + default 0 + range 0 8 + ---help--- + If the Tickless OS feature is enabled, the one clock must be + assigned to provided the one-shot timer needed by the OS. + +config SAM34_TICKLESS_FREERUN + int "Tickless free-running timer channel" + default 1 + range 0 8 + ---help--- + If the Tickless OS feature is enabled, the one clock must be + assigned to provided the free-running timer needed by the OS. + +endif + +endmenu # AT91SAM3/4 Timer/Counter Configuration + if SAM34_SPI0 || SAM34_SPI1 menu "AT91SAM3/4 SPI device driver options" diff --git a/nuttx/arch/arm/src/sam34/Make.defs b/nuttx/arch/arm/src/sam34/Make.defs index cfe342e0f..258ecd6ff 100644 --- a/nuttx/arch/arm/src/sam34/Make.defs +++ b/nuttx/arch/arm/src/sam34/Make.defs @@ -1,7 +1,7 @@ ############################################################################ # arch/arm/src/sam34/Make.defs # -# Copyright (C) 2009-2011, 2013-2014 Gregory Nutt. All rights reserved. +# Copyright (C) 2009-2011, 2013-2015 Gregory Nutt. All rights reserved. # Author: Gregory Nutt # # Redistribution and use in source and binary forms, with or without @@ -161,3 +161,18 @@ endif ifeq ($(CONFIG_TIMER),y) CHIP_CSRCS += sam_tc.c endif + +ifeq ($(CONFIG_ARCH_CHIP_SAM4CM),y) +ifeq ($(CONFIG_SAM34_TC),y) +CHIP_CSRCS += sam4cm_tc.c +ifeq ($(CONFIG_SAM34_ONESHOT),y) +CHIP_CSRCS += sam4cm_oneshot.c +endif +ifeq ($(CONFIG_SAM34_FREERUN),y) +CHIP_CSRCS += sam4cm_freerun.c +endif +ifeq ($(CONFIG_SCHED_TICKLESS),y) +CHIP_CSRCS += sam4cm_tickless.c +endif +endif +endif diff --git a/nuttx/arch/arm/src/sam34/chip/sam_tc.h b/nuttx/arch/arm/src/sam34/chip/sam_tc.h index 42dd58cc8..bb1bd15f0 100644 --- a/nuttx/arch/arm/src/sam34/chip/sam_tc.h +++ b/nuttx/arch/arm/src/sam34/chip/sam_tc.h @@ -325,6 +325,7 @@ #define TC_CMR_TCCLKS_SHIFT (0) /* Bits 0-2: Clock Selection */ #define TC_CMR_TCCLKS_MASK (7 << TC_CMR_TCCLKS_SHIFT) +# define TC_CMR_TCCLKS(n) ((uint32_t)(n) << TC_CMR_TCCLKS_SHIFT) # define TC_CMR_TCCLKS_TIMERCLOCK1 (0 << TC_CMR_TCCLKS_SHIFT) # define TC_CMR_TCCLKS_TIMERCLOCK2 (1 << TC_CMR_TCCLKS_SHIFT) # define TC_CMR_TCCLKS_TIMERCLOCK3 (2 << TC_CMR_TCCLKS_SHIFT) @@ -335,11 +336,11 @@ # define TC_CMR_TCCLKS_XC2 (7 << TC_CMR_TCCLKS_SHIFT) #define TC_CMR_CLKI (1 << 3) /* Bit 3: Clock Invert */ #define TC_CMR_BURST_SHIFT (4) /* Bits 4-5: Burst Signal Selection */ -#define TC_CMR_BURST_MASK (3 << TC_CMR_BURST_MASK) -# define TC_CMR_BURST_NOTGATED (0 << TC_CMR_BURST_MASK) /* Nott gated by external signal */ -# define TC_CMR_BURST_XC0 (1 << TC_CMR_BURST_MASK) /* XC0 ANDed with selected clock */ -# define TC_CMR_BURST_XC1 (2 << TC_CMR_BURST_MASK) /* XC1 ANDed with selected clock */ -# define TC_CMR_BURST_XC2 (3 << TC_CMR_BURST_MASK) /* XC2 ANDed with selected clock */ +#define TC_CMR_BURST_MASK (3 << TC_CMR_BURST_SHIFT) +# define TC_CMR_BURST_NOTGATED (0 << TC_CMR_BURST_SHIFT) /* Nott gated by external signal */ +# define TC_CMR_BURST_XC0 (1 << TC_CMR_BURST_SHIFT) /* XC0 ANDed with selected clock */ +# define TC_CMR_BURST_XC1 (2 << TC_CMR_BURST_SHIFT) /* XC1 ANDed with selected clock */ +# define TC_CMR_BURST_XC2 (3 << TC_CMR_BURST_SHIFT) /* XC2 ANDed with selected clock */ #define TC_CMR_WAVE (1 << 15) /* Bit 15: Waveform Mode */ /* TC Channel Mode Register -- Capture mode only */ diff --git a/nuttx/arch/arm/src/sam34/sam4cm_freerun.c b/nuttx/arch/arm/src/sam34/sam4cm_freerun.c new file mode 100644 index 000000000..386417109 --- /dev/null +++ b/nuttx/arch/arm/src/sam34/sam4cm_freerun.c @@ -0,0 +1,314 @@ +/**************************************************************************** + * arch/arm/src/sam34/sam_freerun.c + * + * Copyright (C) 2015 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * References: + * + * Atmel NoOS sample code. + * + * The Atmel sample code has a BSD compatible license that requires this + * copyright notice: + * + * Copyright (c) 2011, Atmel Corporation + * + * 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 names NuttX nor Atmel 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 + +#include +#include +#include +#include +#include + +#include +#include + +#include "sam4cm_freerun.h" + +#ifdef CONFIG_SAM34_ONESHOT + +/**************************************************************************** + * Private Functions + ****************************************************************************/ +/**************************************************************************** + * Name: sam_freerun_handler + * + * Description: + * Timer interrupt callback. When the freerun timer counter overflows, + * this interrupt will occur. We will just increment an overflow count. + * + * Input Parameters: + * tch - The handle that represents the timer state + * arg - An opaque argument provided when the interrupt was registered + * sr - The value of the timer interrupt status register at the time + * that the interrupt occurred. + * + * Returned Value: + * None + * + ****************************************************************************/ + +static void sam_freerun_handler(TC_HANDLE tch, void *arg, uint32_t sr) +{ + struct sam_freerun_s *freerun = (struct sam_freerun_s *)arg; + DEBUGASSERT(freerun && freerun->overflow < UINT16_MAX); + freerun->overflow++; +} + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: sam_freerun_initialize + * + * Description: + * Initialize the freerun timer wrapper + * + * Input Parameters: + * freerun Caller allocated instance of the freerun state structure + * chan Timer counter channel to be used. See the TC_CHAN* + * definitions in arch/arm/src/sam34/sam_tc.h. + * resolution The required resolution of the timer in units of + * microseconds. NOTE that the range is restricted to the + * range of uint16_t (excluding zero). + * + * Returned Value: + * Zero (OK) is returned on success; a negated errno value is returned + * on failure. + * + ****************************************************************************/ + +int sam_freerun_initialize(struct sam_freerun_s *freerun, int chan, + uint16_t resolution) +{ + uint32_t frequency; + uint32_t divisor; + uint32_t cmr; + int ret; + + tcvdbg("chan=%d resolution=%d usec\n", chan, resolution); + DEBUGASSERT(freerun && resolution > 0); + + /* Get the TC frequency the corresponds to the requested resolution */ + + frequency = USEC_PER_SEC / (uint32_t)resolution; + + /* The pre-calculate values to use when we start the timer */ + + ret = sam_tc_divisor(frequency, &divisor, &cmr); + if (ret < 0) + { + tcdbg("ERROR: sam_tc_divisor failed: %d\n", ret); + return ret; + } + + tcvdbg("frequency=%lu, divisor=%u, cmr=%08lx\n", + (unsigned long)frequency, (unsigned long)divisor, + (unsigned long)cmr); + + /* Allocate the timer/counter and select its mode of operation + * + * CMR_TCCLKS - Returned by sam_tc_divisor + * TC_CMR_CLKI=0 - Not inverted + * TC_CMR_BURST_NONE - Not gated by an external signal + * TC_CMR_CPCSTOP=0 - Don't stop the clock on an RC compare event + * TC_CMR_CPCDIS=0 - Don't disable the clock on an RC compare event + * TC_CMR_EEVTEDG_NONE - No external events (and, hence, no edges + * TC_CMR_EEVT_TIOB - ???? REVISIT + * TC_CMR_ENET=0 - External event trigger disabled + * TC_CMR_WAVSEL_UP - TC_CV is incremented from 0 to 0xffffffff + * TC_CMR_WAVE - Waveform mode + * TC_CMR_ACPA_NONE - RA compare has no effect on TIOA + * TC_CMR_ACPC_NONE - RC compare has no effect on TIOA + * TC_CMR_AEEVT_NONE - No external event effect on TIOA + * TC_CMR_ASWTRG_NONE - No software trigger effect on TIOA + * TC_CMR_BCPB_NONE - RB compare has no effect on TIOB + * TC_CMR_BCPC_NONE - RC compare has no effect on TIOB + * TC_CMR_BEEVT_NONE - No external event effect on TIOB + * TC_CMR_BSWTRG_NONE - No software trigger effect on TIOB + */ + + cmr |= (TC_CMR_BURST_NOTGATED | TC_CMR_EEVTEDG_NONE | TC_CMR_EEVT_TIOB | + TC_CMR_WAVSEL_UP | TC_CMR_WAVE | TC_CMR_ACPA_NONE | + TC_CMR_ACPC_NONE | TC_CMR_AEEVT_NONE | TC_CMR_ASWTRG_NONE | + TC_CMR_BCPB_NONE | TC_CMR_BCPC_NONE | TC_CMR_BEEVT_NONE | + TC_CMR_BSWTRG_NONE); + + freerun->tch = sam_tc_allocate(chan, cmr); + if (!freerun->tch) + { + tcdbg("ERROR: Failed to allocate timer channel %d\n", chan); + return -EBUSY; + } + + /* Initialize the remaining fields in the state structure and return + * success. + */ + + freerun->chan = chan; + freerun->running = false; + freerun->overflow = 0; + + /* Set up to receive the callback when the counter overflow occurs */ + + (void)sam_tc_attach(freerun->tch, sam_freerun_handler, freerun, + TC_INT_COVFS); + + /* Start the counter */ + + sam_tc_start(freerun->tch); + return OK; +} + +/**************************************************************************** + * Name: sam_freerun_counter + * + * Description: + * Read the counter register of the free-running timer. + * + * Input Parameters: + * freerun Caller allocated instance of the freerun state structure. This + * structure must have been previously initialized via a call to + * sam_freerun_initialize(); + * ts The location in which to return the time from the free-running + * timer. + * + * Returned Value: + * Zero (OK) is returned on success; a negated errno value is returned + * on failure. + * + ****************************************************************************/ + +int sam_freerun_counter(struct sam_freerun_s *freerun, struct timespec *ts) +{ + uint64_t usec; + uint32_t counter; + uint32_t verify; + uint32_t sr; + uint32_t overflow; + uint32_t sec; + irqstate_t flags; + + DEBUGASSERT(freerun && freerun->tch && ts); + + /* Temporarily disable the overflow counter */ + + flags = irqsave(); + overflow = freerun->overflow; + counter = sam_tc_getcounter(freerun->tch); + sr = sam_tc_getpending(freerun->tch); + verify = sam_tc_getcounter(freerun->tch); + irqrestore(flags); + + tcvdbg("counter=%lu (%lu) overflow=%lu, sr=%08lx\n", + (unsigned long)counter, (unsigned long)verify, + (unsigned long)overflow, (unsigned long)sr); + + /* If an interrupt was pending before we re-enabled interrupts, + * then our value of overflow needs to be incremented. + */ + + if ((sr & TC_INT_COVFS) != 0) + { + /* Increment the overflow count and use the value of the + * guaranteed to be AFTER the overflow occurred. + */ + + overflow++; + counter = verify; + + tcvdbg("counter=%lu overflow=%lu\n", + (unsigned long)counter, (unsigned long)overflow); + } + + /* Convert the whole thing to units of microseconds. + * + * frequency = ticks / second + * seconds = ticks * frequency + * usecs = (ticks * USEC_PER_SEC) / frequency; + */ + + usec = ((((uint64_t)overflow << 16) + (uint64_t)counter) * USEC_PER_SEC) / + sam_tc_divfreq(freerun->tch); + + /* And return the value of the timer */ + + sec = (uint32_t)(usec / USEC_PER_SEC); + ts->tv_sec = sec; + ts->tv_nsec = (usec - (sec * USEC_PER_SEC)) * NSEC_PER_USEC; + + tcvdbg("usec=%llu ts=(%lu, %lu)\n", + usec, (unsigned long)ts->tv_sec, (unsigned long)ts->tv_nsec); + + return OK; +} + +/**************************************************************************** + * Name: sam_freerun_uninitialize + * + * Description: + * Stop the free-running timer and release all resources that it uses. + * + * Input Parameters: + * freerun Caller allocated instance of the freerun state structure. This + * structure must have been previously initialized via a call to + * sam_freerun_initialize(); + * + * Returned Value: + * Zero (OK) is returned on success; a negated errno value is returned + * on failure. + * + ****************************************************************************/ + +int sam_freerun_uninitialize(struct sam_freerun_s *freerun) +{ + DEBUGASSERT(freerun && freerun->tch); + + /* Now we can disable the timer interrupt and disable the timer. */ + + sam_tc_attach(freerun->tch, NULL, NULL, 0); + sam_tc_stop(freerun->tch); + + /* Free the timer */ + + sam_tc_free(freerun->tch); + freerun->tch = NULL; + return OK; +} + +#endif /* CONFIG_SAM34_ONESHOT */ diff --git a/nuttx/arch/arm/src/sam34/sam4cm_freerun.h b/nuttx/arch/arm/src/sam34/sam4cm_freerun.h new file mode 100644 index 000000000..052f9ef6f --- /dev/null +++ b/nuttx/arch/arm/src/sam34/sam4cm_freerun.h @@ -0,0 +1,156 @@ +/**************************************************************************** + * arch/arm/src/sam34/sam_freerun.h + * + * Copyright (C) 2015 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * 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. + * + ****************************************************************************/ + +#ifndef __ARCH_ARM_SRC_SAM34_SAM_FREERUN_H +#define __ARCH_ARM_SRC_SAM34_SAM_FREERUN_H + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include + +#include "sam4cm_tc.h" + +#ifdef CONFIG_SAM34_FREERUN + +/**************************************************************************** + * Public Types + ****************************************************************************/ + +/* The freerun client must allocate an instance of this structure and called + * sam_freerun_initialize() before using the freerun facilities. The client + * should not access the contents of this structure directly since the + * contents are subject to change. + */ + +struct sam_freerun_s +{ + uint8_t chan; /* The timer/counter in use */ + bool running; /* True: the timer is running */ + uint16_t overflow; /* Timer counter overflow */ + TC_HANDLE tch; /* Handle returned by sam_tc_initialize() */ +}; + +/**************************************************************************** + * Public Data + ****************************************************************************/ + +#undef EXTERN +#if defined(__cplusplus) +#define EXTERN extern "C" +extern "C" +{ +#else +#define EXTERN extern +#endif + +/**************************************************************************** + * Public Function Prototypes + ****************************************************************************/ + +/**************************************************************************** + * Name: sam_freerun_initialize + * + * Description: + * Initialize the freerun timer wrapper + * + * Input Parameters: + * freerun Caller allocated instance of the freerun state structure + * chan Timer counter channel to be used. See the TC_CHAN* + * definitions in arch/arm/src/sama5/sam_tc.h. + * resolution The required resolution of the timer in units of + * microseconds. NOTE that the range is restricted to the + * range of uint16_t (excluding zero). + * + * Returned Value: + * Zero (OK) is returned on success; a negated errno value is returned + * on failure. + * + ****************************************************************************/ + +int sam_freerun_initialize(struct sam_freerun_s *freerun, int chan, + uint16_t resolution); + +/**************************************************************************** + * Name: sam_freerun_counter + * + * Description: + * Read the counter register of the free-running timer. + * + * Input Parameters: + * freerun Caller allocated instance of the freerun state structure. This + * structure must have been previously initialized via a call to + * sam_freerun_initialize(); + * ts The location in which to return the time remaining on the + * oneshot timer. + * + * Returned Value: + * Zero (OK) is returned on success; a negated errno value is returned + * on failure. + * + ****************************************************************************/ + +int sam_freerun_counter(struct sam_freerun_s *freerun, struct timespec *ts); + +/**************************************************************************** + * Name: sam_freerun_uninitialize + * + * Description: + * Stop the free-running timer and release all resources that it uses. + * + * Input Parameters: + * freerun Caller allocated instance of the freerun state structure. This + * structure must have been previously initialized via a call to + * sam_freerun_initialize(); + * + * Returned Value: + * Zero (OK) is returned on success; a negated errno value is returned + * on failure. + * + ****************************************************************************/ + +int sam_freerun_uninitialize(struct sam_freerun_s *freerun); + +#undef EXTERN +#ifdef __cplusplus +} +#endif + +#endif /* CONFIG_SAM34_FREERUN */ +#endif /* __ARCH_ARM_SRC_SAM34_SAM_FREERUN_H */ diff --git a/nuttx/arch/arm/src/sam34/sam4cm_oneshot.c b/nuttx/arch/arm/src/sam34/sam4cm_oneshot.c new file mode 100644 index 000000000..5a0816528 --- /dev/null +++ b/nuttx/arch/arm/src/sam34/sam4cm_oneshot.c @@ -0,0 +1,448 @@ +/**************************************************************************** + * arch/arm/src/sam34/sam4cm_oneshot.c + * + * Copyright (C) 2015 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * References: + * + * Atmel NoOS sample code. + * + * The Atmel sample code has a BSD compatible license that requires this + * copyright notice: + * + * Copyright (c) 2011, Atmel Corporation + * + * 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 names NuttX nor Atmel 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 + +#include +#include +#include +#include +#include + +#include +#include + +#include "sam4cm_oneshot.h" + +#ifdef CONFIG_SAM34_ONESHOT + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: sam_oneshot_handler + * + * Description: + * Timer interrupt callback. When the oneshot timer interrupt expires, + * this function will be called. It will forward the call to the next + * level up. + * + * Input Parameters: + * tch - The handle that represents the timer state + * arg - An opaque argument provided when the interrupt was registered + * sr - The value of the timer interrupt status register at the time + * that the interrupt occurred. + * + * Returned Value: + * None + * + ****************************************************************************/ + +static void sam_oneshot_handler(TC_HANDLE tch, void *arg, uint32_t sr) +{ + struct sam_oneshot_s *oneshot = (struct sam_oneshot_s *)arg; + oneshot_handler_t oneshot_handler; + void *oneshot_arg; + + tcllvdbg("Expired...\n"); + DEBUGASSERT(oneshot && oneshot->handler); + + /* The clock was stopped, but not disabled when the RC match occurred. + * Disable the TC now and disable any further interrupts. + */ + + sam_tc_attach(oneshot->tch, NULL, NULL, 0); + sam_tc_stop(oneshot->tch); + + /* The timer is no longer running */ + + oneshot->running = false; + + /* Forward the event, clearing out any vestiges */ + + oneshot_handler = (oneshot_handler_t)oneshot->handler; + oneshot->handler = NULL; + oneshot_arg = (void *)oneshot->arg; + oneshot->arg = NULL; + + oneshot_handler(oneshot_arg); +} + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: sam_oneshot_initialize + * + * Description: + * Initialize the oneshot timer wrapper + * + * Input Parameters: + * oneshot Caller allocated instance of the oneshot state structure + * chan Timer counter channel to be used. See the TC_CHAN* + * definitions in arch/arm/src/sam34/sam_tc.h. + * resolution The required resolution of the timer in units of + * microseconds. NOTE that the range is restricted to the + * range of uint16_t (excluding zero). + * + * Returned Value: + * Zero (OK) is returned on success; a negated errno value is returned + * on failure. + * + ****************************************************************************/ + +int sam_oneshot_initialize(struct sam_oneshot_s *oneshot, int chan, + uint16_t resolution) +{ + uint32_t frequency; + uint32_t divisor; + uint32_t cmr; + int ret; + + tcvdbg("chan=%d resolution=%d usec\n", chan, resolution); + DEBUGASSERT(oneshot && resolution > 0); + + /* Get the TC frequency the corresponds to the requested resolution */ + + frequency = USEC_PER_SEC / (uint32_t)resolution; + + /* The pre-calculate values to use when we start the timer */ + + ret = sam_tc_divisor(frequency, &divisor, &cmr); + if (ret < 0) + { + tcdbg("ERROR: sam_tc_divisor failed: %d\n", ret); + return ret; + } + + tcvdbg("frequency=%lu, divisor=%lu, cmr=%08lx\n", + (unsigned long)frequency, (unsigned long)divisor, + (unsigned long)cmr); + + /* Allocate the timer/counter and select its mode of operation + * + * CMR_TCCLKS - Returned by sam_tc_divisor + * TC_CMR_CLKI=0 - Not inverted + * TC_CMR_BURST_NONE - Not gated by an external signal + * TC_CMR_CPCSTOP=1 - Stop the clock on an RC compare event + * TC_CMR_CPCDIS=0 - Don't disable the clock on an RC compare event + * TC_CMR_EEVTEDG_NONE - No external events (and, hence, no edges + * TC_CMR_EEVT_TIOB - ???? REVISIT + * TC_CMR_ENET=0 - External event trigger disabled + * TC_CMR_WAVSEL_UPRC - TC_CV is incremented from 0 to the value of RC, + * then automatically reset on a RC Compare + * TC_CMR_WAVE - Waveform mode + * TC_CMR_ACPA_NONE - RA compare has no effect on TIOA + * TC_CMR_ACPC_NONE - RC compare has no effect on TIOA + * TC_CMR_AEEVT_NONE - No external event effect on TIOA + * TC_CMR_ASWTRG_NONE - No software trigger effect on TIOA + * TC_CMR_BCPB_NONE - RB compare has no effect on TIOB + * TC_CMR_BCPC_NONE - RC compare has no effect on TIOB + * TC_CMR_BEEVT_NONE - No external event effect on TIOB + * TC_CMR_BSWTRG_NONE - No software trigger effect on TIOB + */ + + cmr |= (TC_CMR_BURST_NOTGATED | TC_CMR_CPCSTOP | TC_CMR_EEVTEDG_NONE | + TC_CMR_EEVT_TIOB | TC_CMR_WAVSEL_UPAUTO | TC_CMR_WAVE | + TC_CMR_ACPA_NONE | TC_CMR_ACPC_NONE | TC_CMR_AEEVT_NONE | + TC_CMR_ASWTRG_NONE | TC_CMR_BCPB_NONE | TC_CMR_BCPC_NONE | + TC_CMR_BEEVT_NONE | TC_CMR_BSWTRG_NONE); + + oneshot->tch = sam_tc_allocate(chan, cmr); + if (!oneshot->tch) + { + tcdbg("ERROR: Failed to allocate timer channel %d\n", chan); + return -EBUSY; + } + + /* Initialize the remaining fields in the state structure and return + * success. + */ + + oneshot->chan = chan; + oneshot->running = false; + oneshot->handler = NULL; + oneshot->arg = NULL; + return OK; +} + +/**************************************************************************** + * Name: sam_oneshot_max_delay + * + * Description: + * Determine the maximum delay of the one-shot timer (in microseconds) + * + ****************************************************************************/ + +int sam_oneshot_max_delay(struct sam_oneshot_s *oneshot, uint64_t *usec) +{ + DEBUGASSERT(oneshot && usec); + *usec = (0xffffull * USEC_PER_SEC) / (uint64_t)sam_tc_divfreq(oneshot->tch); + return OK; +} + +/**************************************************************************** + * Name: sam_oneshot_start + * + * Description: + * Start the oneshot timer + * + * Input Parameters: + * oneshot Caller allocated instance of the oneshot state structure. This + * structure must have been previously initialized via a call to + * sam_oneshot_initialize(); + * handler The function to call when when the oneshot timer expires. + * arg An opaque argument that will accompany the callback. + * ts Provides the duration of the one shot timer. + * + * Returned Value: + * Zero (OK) is returned on success; a negated errno value is returned + * on failure. + * + ****************************************************************************/ + +int sam_oneshot_start(struct sam_oneshot_s *oneshot, oneshot_handler_t handler, + void *arg, const struct timespec *ts) +{ + uint64_t usec; + uint64_t regval; + irqstate_t flags; + + tcvdbg("handler=%p arg=%p, ts=(%lu, %lu)\n", + handler, arg, (unsigned long)ts->tv_sec, (unsigned long)ts->tv_nsec); + DEBUGASSERT(oneshot && handler && ts); + + /* Was the oneshot already running? */ + + flags = irqsave(); + if (oneshot->running) + { + /* Yes.. then cancel it */ + + tcvdbg("Already running... cancelling\n"); + (void)sam_oneshot_cancel(oneshot, NULL); + } + + /* Save the new handler and its argument */ + + oneshot->handler = handler; + oneshot->arg = arg; + + /* Express the delay in microseconds */ + + usec = (uint64_t)ts->tv_sec * USEC_PER_SEC + (uint64_t)(ts->tv_nsec / NSEC_PER_USEC); + + /* Get the timer counter frequency and determine the number of counts need to achieve the requested delay. + * + * frequency = ticks / second + * ticks = seconds * frequency + * = (usecs * frequency) / USEC_PER_SEC; + */ + + regval = (usec * (uint64_t)sam_tc_divfreq(oneshot->tch)) / USEC_PER_SEC; + + tcvdbg("usec=%llu regval=%08llx\n", usec, regval); + DEBUGASSERT(regval <= UINT16_MAX); + + /* Set up to receive the callback when the interrupt occurs */ + + (void)sam_tc_attach(oneshot->tch, sam_oneshot_handler, oneshot, + TC_INT_CPCS); + + /* Set RC so that an event will be triggered when TC_CV register counts + * up to RC. + */ + + sam_tc_setregister(oneshot->tch, TC_REGC, (uint32_t)regval); + + /* Start the counter */ + + sam_tc_start(oneshot->tch); + + /* Enable interrupts. We should get the callback when the interrupt + * occurs. + */ + + oneshot->running = true; + irqrestore(flags); + return OK; +} + +/**************************************************************************** + * Name: sam_oneshot_cancel + * + * Description: + * Cancel the oneshot timer and return the time remaining on the timer. + * + * NOTE: This function may execute at a high rate with no timer running (as + * when pre-emption is enabled and disabled). + * + * Input Parameters: + * oneshot Caller allocated instance of the oneshot state structure. This + * structure must have been previously initialized via a call to + * sam_oneshot_initialize(); + * ts The location in which to return the time remaining on the + * oneshot timer. A time of zero is returned if the timer is + * not running. ts may be zero in which case the time remaining + * is not returned. + * + * Returned Value: + * Zero (OK) is returned on success. A call to up_timer_cancel() when + * the timer is not active should also return success; a negated errno + * value is returned on any failure. + * + ****************************************************************************/ + +int sam_oneshot_cancel(struct sam_oneshot_s *oneshot, struct timespec *ts) +{ + irqstate_t flags; + uint64_t usec; + uint64_t sec; + uint64_t nsec; + uint32_t count; + uint32_t rc; + + /* Was the timer running? */ + + flags = irqsave(); + if (!oneshot->running) + { + /* No.. Just return zero timer remaining and successful cancellation. + * This function may execute at a high rate with no timer running + * (as when pre-emption is enabled and disabled). + */ + + ts->tv_sec = 0; + ts->tv_nsec = 0; + irqrestore(flags); + return OK; + } + + /* Yes.. Get the timer counter and rc registers and stop the counter. If + * the counter expires while we are doing this, the counter clock will be + * stopped, but the clock will not be disabled. + * + * The expected behavior is that the the counter register will freezes at + * a value equal to the RC register when the timer expires. The counter + * should have values between 0 and RC in all other cased. + * + * REVISIT: This does not appear to be the case. + */ + + tcvdbg("Cancelling...\n"); + + count = sam_tc_getcounter(oneshot->tch); + rc = sam_tc_getregister(oneshot->tch, TC_REGC); + + /* Now we can disable the interrupt and stop the timer. */ + + sam_tc_attach(oneshot->tch, NULL, NULL, 0); + sam_tc_stop(oneshot->tch); + + oneshot->running = false; + oneshot->handler = NULL; + oneshot->arg = NULL; + irqrestore(flags); + + /* Did the caller provide us with a location to return the time + * remaining? + */ + + if (ts) + { + /* Yes.. then calculate and return the time remaining on the + * oneshot timer. + */ + + tcvdbg("rc=%lu count=%lu usec=%lu\n", + (unsigned long)rc, (unsigned long)count, (unsigned long)usec); + + /* REVISIT: I am not certain why the timer counter value sometimes + * exceeds RC. Might be a bug, or perhaps the counter does not stop + * in all cases. + */ + + if (count >= rc) + { + /* No time remaining (?) */ + + ts->tv_sec = 0; + ts->tv_nsec = 0; + } + else + { + /* The total time remaining is the difference. Convert the that + * to units of microseconds. + * + * frequency = ticks / second + * seconds = ticks * frequency + * usecs = (ticks * USEC_PER_SEC) / frequency; + */ + + usec = (((uint64_t)(rc - count)) * USEC_PER_SEC) / + sam_tc_divfreq(oneshot->tch); + + /* Return the time remaining in the correct form */ + + sec = usec / USEC_PER_SEC; + nsec = ((usec) - (sec * USEC_PER_SEC)) * NSEC_PER_USEC; + + ts->tv_sec = (time_t)sec; + ts->tv_nsec = (unsigned long)nsec; + } + + tcvdbg("remaining (%lu, %lu)\n", + (unsigned long)ts->tv_sec, (unsigned long)ts->tv_nsec); + } + + return OK; +} + +#endif /* CONFIG_SAM34_ONESHOT */ diff --git a/nuttx/arch/arm/src/sam34/sam4cm_oneshot.h b/nuttx/arch/arm/src/sam34/sam4cm_oneshot.h new file mode 100644 index 000000000..78a44d99c --- /dev/null +++ b/nuttx/arch/arm/src/sam34/sam4cm_oneshot.h @@ -0,0 +1,178 @@ +/**************************************************************************** + * arch/arm/src/sam34/sam_oneshot.h + * + * Copyright (C) 2015 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * 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. + * + ****************************************************************************/ + +#ifndef __ARCH_ARM_SRC_SAM34_SAM_ONESHOT_H +#define __ARCH_ARM_SRC_SAM34_SAM_ONESHOT_H + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include + +#include "sam4cm_tc.h" + +#ifdef CONFIG_SAM34_ONESHOT + +/**************************************************************************** + * Public Types + ****************************************************************************/ + +/* This describes the callback function that will be invoked when the oneshot + * timer expires. The oneshot fires, the client will receive: + * + * arg - The opaque argument provided when the interrupt was registered + */ + +typedef void (*oneshot_handler_t)(void *arg); + +/* The oneshot client must allocate an instance of this structure and called + * sam_oneshot_initialize() before using the oneshot facilities. The client + * should not access the contents of this structure directly since the + * contents are subject to change. + */ + +struct sam_oneshot_s +{ + uint8_t chan; /* The timer/counter in use */ + volatile bool running; /* True: the timer is running */ + TC_HANDLE tch; /* Handle returned by + * sam_tc_initialize() */ + volatile oneshot_handler_t handler; /* Oneshot expiration callback */ + volatile void *arg; /* The argument that will accompany + * the callback */ +}; + +/**************************************************************************** + * Public Data + ****************************************************************************/ + +#undef EXTERN +#if defined(__cplusplus) +#define EXTERN extern "C" +extern "C" +{ +#else +#define EXTERN extern +#endif + +/**************************************************************************** + * Public Function Prototypes + ****************************************************************************/ + +/**************************************************************************** + * Name: sam_oneshot_initialize + * + * Description: + * Initialize the oneshot timer wrapper + * + * Input Parameters: + * oneshot Caller allocated instance of the oneshot state structure + * chan Timer counter channel to be used. See the TC_CHAN* + * definitions in arch/arm/src/sama5/sam_tc.h. + * resolution The required resolution of the timer in units of + * microseconds. NOTE that the range is restricted to the + * range of uint16_t (excluding zero). + * + * Returned Value: + * Zero (OK) is returned on success; a negated errno value is returned + * on failure. + * + ****************************************************************************/ + +int sam_oneshot_initialize(struct sam_oneshot_s *oneshot, int chan, + uint16_t resolution); + +int sam_oneshot_max_delay(struct sam_oneshot_s *oneshot, uint64_t *usec); + +/**************************************************************************** + * Name: sam_oneshot_start + * + * Description: + * Start the oneshot timer + * + * Input Parameters: + * oneshot Caller allocated instance of the oneshot state structure. This + * structure must have been previously initialized via a call to + * sam_oneshot_initialize(); + * handler The function to call when when the oneshot timer expires. + * arg An opaque argument that will accompany the callback. + * ts Provides the duration of the one shot timer. + * + * Returned Value: + * Zero (OK) is returned on success; a negated errno value is returned + * on failure. + * + ****************************************************************************/ + +int sam_oneshot_start(struct sam_oneshot_s *oneshot, oneshot_handler_t handler, + void *arg, const struct timespec *ts); + +/**************************************************************************** + * Name: sam_oneshot_cancel + * + * Description: + * Cancel the oneshot timer and return the time remaining on the timer. + * + * NOTE: This function may execute at a high rate with no timer running (as + * when pre-emption is enabled and disabled). + * + * Input Parameters: + * oneshot Caller allocated instance of the oneshot state structure. This + * structure must have been previously initialized via a call to + * sam_oneshot_initialize(); + * ts The location in which to return the time remaining on the + * oneshot timer. A time of zero is returned if the timer is + * not running. + * + * Returned Value: + * Zero (OK) is returned on success. A call to up_timer_cancel() when + * the timer is not active should also return success; a negated errno + * value is returned on any failure. + * + ****************************************************************************/ + +int sam_oneshot_cancel(struct sam_oneshot_s *oneshot, struct timespec *ts); + +#undef EXTERN +#ifdef __cplusplus +} +#endif + +#endif /* CONFIG_SAM34_ONESHOT */ +#endif /* __ARCH_ARM_SRC_SAM34_SAM_ONESHOT_H */ diff --git a/nuttx/arch/arm/src/sam34/sam4cm_tc.c b/nuttx/arch/arm/src/sam34/sam4cm_tc.c new file mode 100644 index 000000000..2ca8cf268 --- /dev/null +++ b/nuttx/arch/arm/src/sam34/sam4cm_tc.c @@ -0,0 +1,1287 @@ +/**************************************************************************** + * arch/arm/src/sam34/sam_tc.c + * + * Copyright (C) 2013-2015 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * References: + * + * SAMA5D3 Series Data Sheet + * Atmel NoOS sample code. + * + * The Atmel sample code has a BSD compatible license that requires this + * copyright notice: + * + * Copyright (c) 2011, Atmel Corporation + * + * 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 names NuttX nor Atmel 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 + +#include +#include +#include +#include +#include +#include +#include + +#include +#include + +#include "up_arch.h" +#include "sam_periphclks.h" +#include "chip/sam_pinmap.h" +#include "chip/sam_pmc.h" +#include "sam_gpio.h" + +#include "sam4cm_tc.h" + +#if defined(CONFIG_SAM34_TC0) || defined(CONFIG_SAM34_TC1) || \ + defined(CONFIG_SAM34_TC2) || defined(CONFIG_SAM34_TC3) || \ + defined(CONFIG_SAM34_TC4) || defined(CONFIG_SAM34_TC5) + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/**************************************************************************** + * Private Types + ****************************************************************************/ +/* This structure describes the static configuration of a TC channel */ + +struct sam_chconfig_s +{ + uintptr_t base; /* Channel register base address */ + uint8_t pid; /* Peripheral ID number */ + uint8_t irq; /* Channel IRQ number */ + uint8_t chan; + gpio_pinset_t clkset; /* CLK input PIO configuration */ + gpio_pinset_t tioaset; /* Output A PIO configuration */ + gpio_pinset_t tiobset; /* Output B PIO configuration */ +}; + +/* This structure describes one timer counter channel */ + +struct sam_chan_s +{ + struct sam_tc_s *tc; /* Parent timer/counter */ + uintptr_t base; /* Channel register base address */ + uint8_t pid; /* Peripheral ID number */ + uint8_t irq; /* Channel IRQ number */ + tc_handler_t handler; /* Attached interrupt handler */ + void *arg; /* Interrupt handler argument */ + uint8_t chan; /* Channel number (0, 1, or 2 OR 3, 4, or 5) */ + sem_t exclsem; /* Assures mutually exclusive access to TC */ + bool initialized; /* True: channel data has been initialized */ + bool inuse; /* True: channel is in use */ + + /* Debug stuff */ + +#ifdef CONFIG_SAM34_TC_REGDEBUG + bool wr; /* True:Last was a write */ + uint32_t regaddr; /* Last address */ + uint32_t regval; /* Last value */ + int ntimes; /* Number of times */ +#endif +}; + +/**************************************************************************** + * Private Function Prototypes + ****************************************************************************/ + +/* Low-level helpers ********************************************************/ + +static void sam_takesem(struct sam_chan_s *chan); +#define sam_givesem(chan) (sem_post(&chan->exclsem)) + +#ifdef CONFIG_SAM34_TC_REGDEBUG +static void sam_regdump(struct sam_chan_s *chan, const char *msg); +static bool sam_checkreg(struct sam_chan_s *chan, bool wr, uint32_t regaddr, + uint32_t regval); +#else +# define sam_regdump(chan,msg) +# define sam_checkreg(chan,wr,regaddr,regval) (false) +#endif + +static inline uint32_t sam_chan_getreg(struct sam_chan_s *chan, + unsigned int offset); +static inline void sam_chan_putreg(struct sam_chan_s *chan, + unsigned int offset, uint32_t regval); + +/* Interrupt Handling *******************************************************/ + +static int sam_tc_interrupt(struct sam_chan_s *tc); +static int sam_raw_interrupt(int irq, void *context); + +/* Initialization ***********************************************************/ + +static int sam_tc_freqdiv_lookup(uint32_t ftcin, int ndx); +static uint32_t sam_tc_divfreq_lookup(uint32_t ftcin, int ndx); +static inline struct sam_chan_s *sam_tc_initialize(int channel); + +/**************************************************************************** + * Private Data + ****************************************************************************/ +/* Static timer configuration */ + +static const struct sam_chconfig_s g_configs[] = +{ +#ifdef CONFIG_SAM34_TC0 + { + .chan = 0, + .base = SAM_TC0_BASE, + .pid = SAM_PID_TC0, + .irq = SAM_IRQ_TC0, +#ifdef CONFIG_SAM34_TC0_CLK + .clkset = PIO_TC0_CLK, +#else + .clkset = 0, +#endif +#ifdef CONFIG_SAM34_TC0_TIOA + .tioaset = PIO_TC0_IOA, +#else + .tioaset = 0, +#endif +#ifdef CONFIG_SAM34_TC0_TIOB + .tiobset = PIO_TC0_IOB, +#else + .tiobset = 0, +#endif + }, +#endif /* CONFIG_SAM34_TC0 */ + +#ifdef CONFIG_SAM34_TC1 + { + .chan = 1, + .base = SAM_TC1_BASE, + .pid = SAM_PID_TC1, + .irq = SAM_IRQ_TC1, +#ifdef CONFIG_SAM34_TC1_CLK + .clkset = PIO_TC1_CLK, +#else + .clkset = 0, +#endif +#ifdef CONFIG_SAM34_TC1_TIOA + .tioaset = PIO_TC1_IOA, +#else + .tioaset = 0, +#endif +#ifdef CONFIG_SAM34_TC1_TIOB + .tiobset = PIO_TC1_IOB, +#else + .tiobset = 0, +#endif + }, +#endif /* CONFIG_SAM34_TC1 */ + +#ifdef CONFIG_SAM34_TC2 + { + .chan = 2, + .base = SAM_TC2_BASE, + .pid = SAM_PID_TC2, + .irq = SAM_IRQ_TC2, +#ifdef CONFIG_SAM34_TC2_CLK + .clkset = PIO_TC2_CLK, +#else + .clkset = 0, +#endif +#ifdef CONFIG_SAM34_TC2_TIOA + .tioaset = PIO_TC2_IOA, +#else + .tioaset = 0, +#endif +#ifdef CONFIG_SAM34_TC2_TIOB + .tiobset = PIO_TC2_IOB, +#else + .tiobset = 0, +#endif + }, +#endif /* CONFIG_SAM34_TC2 */ + +#ifdef CONFIG_SAM34_TC3 + { + .chan = 3, + .base = SAM_TC3_BASE, + .pid = SAM_PID_TC3, + .irq = SAM_IRQ_TC3, +#ifdef CONFIG_SAM34_TC3_CLK + .clkset = PIO_TC3_CLK, +#else + .clkset = 0, +#endif +#ifdef CONFIG_SAM34_TC3_TIOA + .tioaset = PIO_TC3_IOA, +#else + .tioaset = 0, +#endif +#ifdef CONFIG_SAM34_TC3_TIOB + .tiobset = PIO_TC3_IOB, +#else + .tiobset = 0, +#endif + }, +#endif /* CONFIG_SAM34_TC3 */ + +#ifdef CONFIG_SAM34_TC4 + { + .chan = 4, + .base = SAM_TC4_BASE, + .pid = SAM_PID_TC4, + .irq = SAM_IRQ_TC4, +#ifdef CONFIG_SAM34_TC4_CLK + .clkset = PIO_TC4_CLK, +#else + .clkset = 0, +#endif +#ifdef CONFIG_SAM34_TC4_TIOA + .tioaset = PIO_TC4_IOA, +#else + .tioaset = 0, +#endif +#ifdef CONFIG_SAM34_TC4_TIOB + .tiobset = PIO_TC4_IOB, +#else + .tiobset = 0, +#endif + }, +#endif /* CONFIG_SAM34_TC4 */ + +#ifdef CONFIG_SAM34_TC5 + { + .chan = 5, + .base = SAM_TC5_BASE, + .pid = SAM_PID_TC5, + .irq = SAM_IRQ_TC5, +#ifdef CONFIG_SAM34_TC5_CLK + .clkset = PIO_TC5_CLK, +#else + .clkset = 0, +#endif +#ifdef CONFIG_SAM34_TC5_TIOA + .tioaset = PIO_TC5_IOA, +#else + .tioaset = 0, +#endif +#ifdef CONFIG_SAM34_TC5_TIOB + .tiobset = PIO_TC5_IOB, +#else + .tiobset = 0, +#endif + }, +#endif /* CONFIG_SAM34_TC5 */ +}; + +#define ENABLED_CHANNELS (sizeof(g_configs)/sizeof(struct sam_chconfig_s)) + +static struct sam_chan_s g_channels[ENABLED_CHANNELS]; + +/* TC frequency data. This table provides the frequency for each selection of TCCLK */ + +#define TC_NDIVIDERS 4 +#define TC_NDIVOPTIONS 5 + +/* This is the list of divider values: divider = (1 << value) */ + +static const uint8_t g_log2divider[TC_NDIVIDERS] = +{ + 1, /* TIMER_CLOCK1 -> div2 */ + 3, /* TIMER_CLOCK2 -> div8 */ + 5, /* TIMER_CLOCK3 -> div32 */ + 7 /* TIMER_CLOCK4 -> div128 */ +}; + +/* TC register lookup used by sam_tc_setregister */ + +#define TC_NREGISTERS 3 + +static const uint8_t g_regoffset[TC_NREGISTERS] = +{ + SAM_TC_RA_OFFSET, /* Register A */ + SAM_TC_RB_OFFSET, /* Register B */ + SAM_TC_RC_OFFSET /* Register C */ +}; + +/**************************************************************************** + * Private Functions + ****************************************************************************/ +/**************************************************************************** + * Low-level Helpers + ****************************************************************************/ +/**************************************************************************** + * Name: sam_takesem + * + * Description: + * Take the wait semaphore (handling false alarm wakeups due to the receipt + * of signals). + * + * Input Parameters: + * dev - Instance of the SDIO device driver state structure. + * + * Returned Value: + * None + * + ****************************************************************************/ + +static void sam_takesem(struct sam_chan_s *chan) +{ + /* Take the semaphore (perhaps waiting) */ + + while (sem_wait(&chan->exclsem) != 0) + { + /* The only case that an error should occr here is if the wait was + * awakened by a signal. + */ + + ASSERT(errno == EINTR); + } +} + +/**************************************************************************** + * Name: sam_regdump + * + * Description: + * Dump all timer/counter channel and global registers + * + * Input Parameters: + * chan - The timer/counter channel state + * msg - Message to print with the data + * + * Returned Value: + * None + * + ****************************************************************************/ + +#ifdef CONFIG_SAM34_TC_REGDEBUG +static void sam_regdump(struct sam_chan_s *chan, const char *msg) +{ + uintptr_t base; + + base = chan->base; + lldbg("TC%d [%08x]: %s\n", chan->chan, (int)base, msg); + lldbg(" BMR: %08x QIMR: %08x QISR: %08x WPMR: %08x\n", + getreg32(base+SAM_TC_BMR_OFFSET), getreg32(base+SAM_TC_QIMR_OFFSET), + getreg32(base+SAM_TC_QISR_OFFSET), getreg32(base+SAM_TC_WPMR_OFFSET)); + + base = chan->base; + lldbg("TC%d Channel %d [%08x]: %s\n", chan->chan, chan->chan, (int)base, msg); + lldbg(" CMR: %08x SSMR: %08x RAB: %08x CV: %08x\n", + getreg32(base+SAM_TC_CMR_OFFSET), getreg32(base+SAM_TC_SMMR_OFFSET), + getreg32(base+SAM_TC_RAB_OFFSET), getreg32(base+SAM_TC_CV_OFFSET)); + lldbg(" RA: %08x RB: %08x RC: %08x SR: %08x\n", + getreg32(base+SAM_TC_RA_OFFSET), getreg32(base+SAM_TC_RB_OFFSET), + getreg32(base+SAM_TC_RC_OFFSET), getreg32(base+SAM_TC_SR_OFFSET)); + lldbg(" IMR: %08x\n", + getreg32(base+SAM_TC_IMR_OFFSET)); +} +#endif + +/**************************************************************************** + * Name: sam_checkreg + * + * Description: + * Check if the current register access is a duplicate of the preceding. + * + * Input Parameters: + * chan - The timer/counter peripheral state + * wr - True:write access false:read access + * regval - The register value associated with the access + * regaddr - The address of the register being accessed + * + * Returned Value: + * true: This is the first register access of this type. + * flase: This is the same as the preceding register access. + * + ****************************************************************************/ + +#ifdef CONFIG_SAM34_TC_REGDEBUG +static bool sam_checkreg(struct sam_chan_s *chan, bool wr, uint32_t regaddr, + uint32_t regval) +{ + if (wr == chan->wr && /* Same kind of access? */ + regaddr == chan->regaddr && /* Same register address? */ + regval == chan->regval) /* Same register value? */ + { + /* Yes, then just keep a count of the number of times we did this. */ + + chan->ntimes++; + return false; + } + else + { + /* Did we do the previous operation more than once? */ + + if (chan->ntimes > 0) + { + /* Yes... show how many times we did it */ + + lldbg("...[Repeats %d times]...\n", chan->ntimes); + } + + /* Save information about the new access */ + + chan->wr = wr; + chan->regval = regval; + chan->regaddr = regaddr; + chan->ntimes = 0; + } + + /* Return true if this is the first time that we have done this operation */ + + return true; +} +#endif + +/**************************************************************************** + * Name: sam_chan_getreg + * + * Description: + * Read an SPI register + * + ****************************************************************************/ + +static inline uint32_t sam_chan_getreg(struct sam_chan_s *chan, + unsigned int offset) +{ + uint32_t regaddr = chan->base + offset; + uint32_t regval = getreg32(regaddr); + +#ifdef CONFIG_SAM34_TC_REGDEBUG + if (sam_checkreg(chan, false, regaddr, regval)) + { + lldbg("%08x->%08x\n", regaddr, regval); + } +#endif + + return regval; +} + +/**************************************************************************** + * Name: sam_chan_putreg + * + * Description: + * Write a value to an SPI register + * + ****************************************************************************/ + +static inline void sam_chan_putreg(struct sam_chan_s *chan, unsigned int offset, + uint32_t regval) +{ + uint32_t regaddr = chan->base + offset; + +#ifdef CONFIG_SAM34_TC_REGDEBUG + if (sam_checkreg(chan, true, regaddr, regval)) + { + lldbg("%08x<-%08x\n", regaddr, regval); + } +#endif + + putreg32(regval, regaddr); +} + +/**************************************************************************** + * Interrupt Handling + ****************************************************************************/ +/**************************************************************************** + * Name: sam_tc_interrupt + * + * Description: + * Common timer channel interrupt handling. + * + * Input Parameters: + * tc Timer status instance + * + * Returned Value: + * A pointer to the initialized timer channel structure associated with tc + * and channel. NULL is returned on any failure. + * + * On successful return, the caller holds the tc exclusive access semaphore. + * + ****************************************************************************/ + +static int sam_tc_interrupt(struct sam_chan_s *chan) +{ + uint32_t sr; + uint32_t imr; + uint32_t pending; + + /* Process interrupts */ + + /* Get the interrupt status for this channel */ + + sr = sam_chan_getreg(chan, SAM_TC_SR_OFFSET); + imr = sam_chan_getreg(chan, SAM_TC_IMR_OFFSET); + pending = sr & imr; + + /* Are there any pending interrupts for this channel? */ + + if (pending) + { + /* Yes... if we have pending interrupts then interrupts must be + * enabled and we must have a handler attached. + */ + + DEBUGASSERT(chan->handler); + if (chan->handler) + { + /* Execute the callback */ + + chan->handler(chan, chan->arg, sr); + } + else + { + /* Should never happen */ + + sam_chan_putreg(chan, SAM_TC_IDR_OFFSET, TC_INT_ALL); + } + } + + return OK; +} + +/**************************************************************************** + * Name: sam_raw_interrupt + * + * Description: + * Timer block interrupt handlers + * + * Input Parameters: + * irq + * context + * + * Returned Value: + * + ****************************************************************************/ + +static int sam_raw_interrupt(int irq, void *context) +{ + int i; + struct sam_chan_s *chan; + + for (i = 0; i < ENABLED_CHANNELS; i++) + { + chan = &g_channels[i]; + + if (chan->irq == irq) + { + return sam_tc_interrupt(chan); + } + } + + return OK; +} + +/**************************************************************************** + * Initialization + ****************************************************************************/ +/**************************************************************************** + * Name: sam_tc_mckdivider + * + * Description: + * Return the TC clock input divider value. One of n=0..3 corresponding + * to divider values of {1, 2, 4, 8}. + * + * NOTE: The SAMA5D4 has no clock input divider + * + * Input Parameters: + * mck - The MCK frequency to be divider. + * + * Returned Value: + * Log2 of the TC clock divider. + * + ****************************************************************************/ + +#ifdef SAM34_HAVE_PMC_PCR_DIV +static int sam_tc_mckdivider(uint32_t mck) +{ + if (mck <= SAM_TC_MAXPERCLK) + { + return 0; + } + else if ((mck >> 1) <= SAM_TC_MAXPERCLK) + { + return 1; + } + else if ((mck >> 2) <= SAM_TC_MAXPERCLK) + { + return 2; + } + else /* if ((mck >> 3) <= SAM_TC_MAXPERCLK) */ + { + DEBUGASSERT((mck >> 3) <= SAM_TC_MAXPERCLK); + return 3; + } +} +#endif + +/**************************************************************************** + * Name: sam_tc_freqdiv_lookup + * + * Description: + * Given the TC input frequency (Ftcin) and a divider index, return the value of + * the Ftcin divider. + * + * Input Parameters: + * ftcin - TC input frequency + * ndx - Divider index + * + * Returned Value: + * The Ftcin input divider value + * + ****************************************************************************/ + +static int sam_tc_freqdiv_lookup(uint32_t ftcin, int ndx) +{ + /* The final option is to use the SLOW clock */ + + if (ndx >= TC_NDIVIDERS) + { + /* Not really a divider. In this case, the board is actually driven + * by the 32.768KHz slow clock. This returns a value that looks like + * correct divider if MCK were the input. + */ + + return ftcin / BOARD_SLOWCLK_FREQUENCY; + } + else + { + return 1 << g_log2divider[ndx]; + } +} + +/**************************************************************************** + * Name: sam_tc_divfreq_lookup + * + * Description: + * Given the TC input frequency (Ftcin) and a divider index, return the + * value of the divided frequency + * + * Input Parameters: + * ftcin - TC input frequency + * ndx - Divider index + * + * Returned Value: + * The divided frequency value + * + ****************************************************************************/ + +static uint32_t sam_tc_divfreq_lookup(uint32_t ftcin, int ndx) +{ + /* The final option is to use the SLOW clock */ + + if (ndx >= TC_NDIVIDERS) + { + return BOARD_SLOWCLK_FREQUENCY; + } + else + { + return ftcin >> g_log2divider[ndx]; + } +} + +/**************************************************************************** + * Name: sam_tc_initialize + * + * Description: + * There is no global, one-time initialization of timer/counter data + * structures. Rather, this function is called each time that a channel + * is allocated and, if the channel has not been initialized, it will be + * initialized then. + * + * Input Parameters: + * channel TC channel number (see TC_CHANx definitions) + * + * Returned Value: + * A pointer to the initialized timer channel structure associated with tc + * and channel. NULL is returned on any failure. + * + * On successful return, the caller holds the tc exclusive access semaphore. + * + ****************************************************************************/ + +static inline struct sam_chan_s *sam_tc_initialize(int channel) +{ + struct sam_chan_s *chan; + const struct sam_chconfig_s *chconfig; + irqstate_t flags; + int i; + + /* Select the timer/counter and get the index associated with the + * channel. + */ + + chan = NULL; + for (i = 0; i < ENABLED_CHANNELS; i++) + { + if (g_configs[i].chan == channel) + { + chan = &g_channels[i]; + chconfig = &g_configs[i]; + break; + } + } + + if (!chan) + { + /* Timer/counter is not invalid or not enabled */ + + tcdbg("ERROR: Bad channel number: %d\n", channel); + return NULL; + } + + /* Has the timer counter been initialized. We have to be careful here + * because there is no semaphore protection. + */ + + flags = irqsave(); + if (!chan->initialized) + { + /* Initialize the channel. */ + + tcdbg("Initializing TC%d\n", chconfig->chan); + + memset(chan, 0, sizeof(struct sam_chan_s)); + sem_init(&chan->exclsem, 0, 1); + chan->base = chconfig->base; + chan->pid = chconfig->pid; + chan->irq = chconfig->irq; + + /* Configure channel input/output pins */ + + if (chconfig->clkset) + { + /* Configure clock input pin */ + + sam_configgpio(chconfig->clkset); + } + + if (chconfig->tioaset) + { + /* Configure output A pin */ + + sam_configgpio(chconfig->tioaset); + } + + if (chconfig->tiobset) + { + /* Configure output B pin */ + + sam_configgpio(chconfig->tiobset); + } + + /* Disable and clear all channel interrupts */ + + sam_chan_putreg(chan, SAM_TC_IDR_OFFSET, TC_INT_ALL); + (void)sam_chan_getreg(chan, SAM_TC_SR_OFFSET); + + /* Enable clocking to the timer counter */ + + sam_enableperiph0(chan->pid); + + /* Attach the timer interrupt handler and enable the timer interrupts */ + + (void)irq_attach(chan->irq, sam_raw_interrupt); + up_enable_irq(chan->irq); + + /* Now the channel is initialized */ + + chan->initialized = true; + } + + /* Get exclusive access to the timer/count data structure */ + + sam_takesem(chan); + irqrestore(flags); + + /* Is it available? */ + + if (chan->inuse) + { + /* No.. return a failure */ + + tcdbg("Channel %d is in-used\n", channel); + sam_givesem(chan); + return NULL; + } + + /* Mark the channel "inuse" */ + + chan->inuse = true; + + /* And return the channel with the semaphore locked */ + + sam_regdump(chan, "Initialized"); + return chan; +} + +/**************************************************************************** + * Public Functions + ****************************************************************************/ +/**************************************************************************** + * Name: sam_tc_allocate + * + * Description: + * Configures a Timer Counter to operate in the given mode. The timer is + * stopped after configuration and must be restarted with sam_tc_start(). + * All the interrupts of the timer are also disabled. + * + * Input Parameters: + * channel TC channel number (see TC_CHANx definitions) + * mode Operating mode (TC_CMR value). + * + * Returned Value: + * On success, a non-NULL handle value is returned. This handle may be + * used with subsequent timer/counter interfaces to manage the timer. A + * NULL handle value is returned on a failure. + * + ****************************************************************************/ + +TC_HANDLE sam_tc_allocate(int channel, int mode) +{ + struct sam_chan_s *chan; + + /* Initialize the timer/counter data (if necessary) and get exclusive + * access to the requested channel. + */ + + tcvdbg("channel=%d mode=%08x\n", channel, mode); + + chan = sam_tc_initialize(channel); + if (chan) + { + /* Disable TC clock */ + + sam_chan_putreg(chan, SAM_TC_CCR_OFFSET, TC_CCR_CLKDIS); + + /* Disable channel interrupts */ + + sam_chan_putreg(chan, SAM_TC_IDR_OFFSET, TC_INT_ALL); + + /* Clear and pending status */ + + (void)sam_chan_getreg(chan, SAM_TC_SR_OFFSET); + + /* And set the requested mode */ + + sam_chan_putreg(chan, SAM_TC_CMR_OFFSET, mode); + sam_regdump(chan, "Allocated"); + sam_givesem(chan); + } + + /* Return an opaque reference to the channel */ + + tcvdbg("Returning %p\n", chan); + return (TC_HANDLE)chan; +} + +/**************************************************************************** + * Name: sam_tc_free + * + * Description: + * Release the handle previously allocated by sam_tc_allocate(). + * + * Input Parameters: + * handle Channel handle previously allocated by sam_tc_allocate() + * + * Returned Value: + * None + * + ****************************************************************************/ + +void sam_tc_free(TC_HANDLE handle) +{ + struct sam_chan_s *chan = (struct sam_chan_s *)handle; + + tcvdbg("Freeing %p channel=%d inuse=%d\n", chan, chan->chan, chan->inuse); + DEBUGASSERT(chan && chan->inuse); + + /* Make sure that interrupts are detached and disabled and that the channel + * is stopped and disabled. + */ + + sam_tc_attach(handle, NULL, NULL, 0); + sam_tc_stop(handle); + + /* Mark the channel as available */ + + chan->inuse = false; +} + +/**************************************************************************** + * Name: sam_tc_start + * + * Description: + * Reset and Start the TC Channel. Enables the timer clock and performs a + * software reset to start the counting. + * + * Input Parameters: + * handle Channel handle previously allocated by sam_tc_allocate() + * + * Returned Value: + * + ****************************************************************************/ + +void sam_tc_start(TC_HANDLE handle) +{ + struct sam_chan_s *chan = (struct sam_chan_s *)handle; + + tcvdbg("Starting channel %d inuse=%d\n", chan->chan, chan->inuse); + DEBUGASSERT(chan && chan->inuse); + + /* Read the SR to clear any pending interrupts on this channel */ + + (void)sam_chan_getreg(chan, SAM_TC_SR_OFFSET); + + /* Then enable the timer (by setting the CLKEN bit). Setting SWTRIG + * will also reset the timer counter and starting the timer. + */ + + sam_chan_putreg(chan, SAM_TC_CCR_OFFSET, TC_CCR_CLKEN | TC_CCR_SWTRG); + sam_regdump(chan, "Started"); +} + +/**************************************************************************** + * Name: sam_tc_stop + * + * Description: + * Stop TC Channel. Disables the timer clock, stopping the counting. + * + * Input Parameters: + * handle Channel handle previously allocated by sam_tc_allocate() + * + * Returned Value: + * + ****************************************************************************/ + +void sam_tc_stop(TC_HANDLE handle) +{ + struct sam_chan_s *chan = (struct sam_chan_s *)handle; + + tcvdbg("Stopping channel %d inuse=%d\n", chan->chan, chan->inuse); + DEBUGASSERT(chan && chan->inuse); + + sam_chan_putreg(chan, SAM_TC_CCR_OFFSET, TC_CCR_CLKDIS); + sam_regdump(chan, "Stopped"); +} + +/**************************************************************************** + * Name: sam_tc_attach + * + * Description: + * Attach or detach an interrupt handler to the timer interrupt. The + * interrupt is detached if the handler argument is NULL. + * + * Input Parameters: + * handle The handle that represents the timer state + * handler The interrupt handler that will be invoked when the interrupt + * condition occurs + * arg An opaque argument that will be provided when the interrupt + * handler callback is executed. + * mask The value of the timer interrupt mask register that defines + * which interrupts should be disabled. + * + * Returned Value: + * + ****************************************************************************/ + +tc_handler_t sam_tc_attach(TC_HANDLE handle, tc_handler_t handler, + void *arg, uint32_t mask) +{ + struct sam_chan_s *chan = (struct sam_chan_s *)handle; + tc_handler_t oldhandler; + irqstate_t flags; + + DEBUGASSERT(chan); + + /* Remember the old interrupt handler and set the new handler */ + + flags = irqsave(); + oldhandler = chan->handler; + chan->handler = handler; + + /* Don't enable interrupt if we are detaching no matter what the caller + * says. + */ + + if (!handler) + { + arg = NULL; + mask = 0; + } + + chan->arg = arg; + + /* Now enable interrupt as requested */ + + sam_chan_putreg(chan, SAM_TC_IDR_OFFSET, TC_INT_ALL & ~mask); + sam_chan_putreg(chan, SAM_TC_IER_OFFSET, TC_INT_ALL & mask); + irqrestore(flags); + + return oldhandler; +} + +/**************************************************************************** + * Name: sam_tc_getpending + * + * Description: + * Return the current contents of the interrupt status register, clearing + * all pending interrupts. + * + * Input Parameters: + * handle The handle that represents the timer state + * + * Returned Value: + * The value of the channel interrupt status register. + * + ****************************************************************************/ + +uint32_t sam_tc_getpending(TC_HANDLE handle) +{ + struct sam_chan_s *chan = (struct sam_chan_s *)handle; + DEBUGASSERT(chan); + return sam_chan_getreg(chan, SAM_TC_SR_OFFSET); +} + +/**************************************************************************** + * Name: sam_tc_setregister + * + * Description: + * Set TC_REGA, TC_REGB, or TC_REGC register. + * + * Input Parameters: + * handle Channel handle previously allocated by sam_tc_allocate() + * regid One of {TC_REGA, TC_REGB, or TC_REGC} + * regval Then value to set in the register + * + * Returned Value: + * None + * + ****************************************************************************/ + +void sam_tc_setregister(TC_HANDLE handle, int regid, uint32_t regval) +{ + struct sam_chan_s *chan = (struct sam_chan_s *)handle; + + DEBUGASSERT(chan && regid < TC_NREGISTERS); + + tcvdbg("Channel %d: Set register RC%d to %08lx\n", + chan->chan, regid, (unsigned long)regval); + + sam_chan_putreg(chan, g_regoffset[regid], regval); + sam_regdump(chan, "Set register"); +} + +/**************************************************************************** + * Name: sam_tc_getregister + * + * Description: + * Get the current value of the TC_REGA, TC_REGB, or TC_REGC register. + * + * Input Parameters: + * handle Channel handle previously allocated by sam_tc_allocate() + * regid One of {TC_REGA, TC_REGB, or TC_REGC} + * + * Returned Value: + * The value of the specified register. + * + ****************************************************************************/ + +uint32_t sam_tc_getregister(TC_HANDLE handle, int regid) +{ + struct sam_chan_s *chan = (struct sam_chan_s *)handle; + DEBUGASSERT(chan); + return sam_chan_getreg(chan, g_regoffset[regid]); +} + +/**************************************************************************** + * Name: sam_tc_getcounter + * + * Description: + * Return the current value of the timer counter register + * + * Input Parameters: + * handle Channel handle previously allocated by sam_tc_allocate() + * + * Returned Value: + * The current value of the timer counter register for this channel. + * + ****************************************************************************/ + +uint32_t sam_tc_getcounter(TC_HANDLE handle) +{ + struct sam_chan_s *chan = (struct sam_chan_s *)handle; + DEBUGASSERT(chan); + return sam_chan_getreg(chan, SAM_TC_CV_OFFSET); +} + +/**************************************************************************** + * Name: sam_tc_infreq + * + * Description: + * Return the timer input frequency (Ftcin), that is, the MCK frequency + * divided down so that the timer/counter is driven within its maximum + * frequency. + * + * Input Parameters: + * None + * + * Returned Value: + * The timer input frequency. + * + ****************************************************************************/ + +uint32_t sam_tc_infreq(void) +{ + return BOARD_MCK_FREQUENCY; +} + +/**************************************************************************** + * Name: sam_tc_divfreq + * + * Description: + * Return the divided timer input frequency that is currently driving the + * the timer counter. + * + * Input Parameters: + * handle Channel handle previously allocated by sam_tc_allocate() + * + * Returned Value: + * The timer counter frequency. + * + ****************************************************************************/ + +uint32_t sam_tc_divfreq(TC_HANDLE handle) +{ + struct sam_chan_s *chan = (struct sam_chan_s *)handle; + uint32_t ftcin = sam_tc_infreq(); + uint32_t regval; + int tcclks; + + DEBUGASSERT(chan); + + /* Get the the TC_CMR register contents for this channel and extract the + * TCCLKS index. + */ + + regval = sam_chan_getreg(chan, SAM_TC_CMR_OFFSET); + tcclks = (regval & TC_CMR_TCCLKS_MASK) >> TC_CMR_TCCLKS_SHIFT; + + /* And use the TCCLKS index to calculate the timer counter frequency */ + + return sam_tc_divfreq_lookup(ftcin, tcclks); +} + +/**************************************************************************** + * Name: sam_tc_divisor + * + * Description: + * Finds the best MCK divisor given the timer frequency and MCK. The + * result is guaranteed to satisfy the following equation: + * + * (Ftcin / (div * 65536)) <= freq <= (Ftcin / dev) + * + * where: + * freq - the desired frequency + * Ftcin - The timer/counter input frequency + * div - With DIV being the highest possible value. + * + * Input Parameters: + * frequency Desired timer frequency. + * div Divisor value. + * tcclks TCCLKS field value for divisor. + * + * Returned Value: + * Zero (OK) if a proper divisor has been found, otherwise a negated errno + * value indicating the nature of the failure. + * + ****************************************************************************/ + +int sam_tc_divisor(uint32_t frequency, uint32_t *div, uint32_t *tcclks) +{ + uint32_t ftcin = sam_tc_infreq(); + int ndx = 0; + + tcvdbg("frequency=%d\n", frequency); + + /* Satisfy lower bound. That is, the value of the divider such that: + * + * frequency >= (tc_input_frequency * 65536) / divider. + */ + + while (frequency < (sam_tc_divfreq_lookup(ftcin, ndx) >> 16)) + { + if (++ndx > TC_NDIVOPTIONS) + { + /* If no divisor can be found, return -ERANGE */ + + tcdbg("Lower bound search failed\n"); + return -ERANGE; + } + } + + /* Try to maximize DIV while still satisfying upper bound. That the + * value of the divider such that: + * + * frequency < tc_input_frequency / divider. + */ + + for (; ndx < (TC_NDIVOPTIONS-1); ndx++) + { + if (frequency > sam_tc_divfreq_lookup(ftcin, ndx + 1)) + { + break; + } + } + + /* Return the divider value */ + + if (div) + { + uint32_t value = sam_tc_freqdiv_lookup(ftcin, ndx); + tcvdbg("return div=%lu\n", (unsigned long)value); + *div = value; + } + + /* Return the TCCLKS selection */ + + if (tcclks) + { + tcvdbg("return tcclks=%08lx\n", (unsigned long)TC_CMR_TCCLKS(ndx)); + *tcclks = TC_CMR_TCCLKS(ndx); + } + + return OK; +} + +#endif diff --git a/nuttx/arch/arm/src/sam34/sam4cm_tc.h b/nuttx/arch/arm/src/sam34/sam4cm_tc.h new file mode 100644 index 000000000..85520d84d --- /dev/null +++ b/nuttx/arch/arm/src/sam34/sam4cm_tc.h @@ -0,0 +1,362 @@ +/**************************************************************************** + * arch/arm/src/sam34/sam4cm_tc.h + * + * Copyright (C) 2013-2015 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * 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. + * + ****************************************************************************/ + +#ifndef __ARCH_ARM_SRC_SAM34_SAM4CM_TC_H +#define __ARCH_ARM_SRC_SAM34_SAM4CM_TC_H + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include + +#include "chip.h" +#include "chip/sam_tc.h" + +#if defined(CONFIG_SAM34_TC0) || defined(CONFIG_SAM34_TC1) || defined(CONFIG_SAM34_TC2) + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/* The timer/counter and channel arguments to sam_tc_allocate() */ + +#define TC_CHAN0 0 /* TC0 */ +#define TC_CHAN1 1 +#define TC_CHAN2 2 +#define TC_CHAN3 3 /* TC1 */ +#define TC_CHAN4 4 +#define TC_CHAN5 5 + +/* Register identifier used with sam_tc_setregister */ + +#define TC_REGA 0 +#define TC_REGB 1 +#define TC_REGC 2 + +/* Timer debug is enabled if any timer client is enabled */ + +#ifndef CONFIG_DEBUG +# undef CONFIG_DEBUG_ANALOG +# undef CONFIG_SAMA5_TC_REGDEBUG +#endif + +#if !defined(CONFIG_SAM34_TC_DEBUG) && defined(CONFIG_SAM34_ADC) && defined(CONFIG_DEBUG_ANALOG) +# define CONFIG_SAM34_TC_DEBUG 1 +#endif + +/* Timer/counter debug output */ + +#ifdef CONFIG_SAM34_TC_DEBUG +# define tcdbg dbg +# define tcvdbg vdbg +# define tclldbg lldbg +# define tcllvdbg llvdbg +#else +# define tcdbg(x...) +# define tcvdbg(x...) +# define tclldbg(x...) +# define tcllvdbg(x...) +#endif + +/**************************************************************************** + * Public Types + ****************************************************************************/ +/* An opaque handle used to represent a timer channel */ + +typedef void *TC_HANDLE; + +/* Timer interrupt callback. When a timer interrupt expires, the client will + * receive: + * + * tch - The handle that represents the timer state + * arg - An opaque argument provided when the interrupt was registered + * sr - The value of the timer interrupt status register at the time + * that the interrupt occurred. + */ + +typedef void (*tc_handler_t)(TC_HANDLE tch, void *arg, uint32_t sr); + +/**************************************************************************** + * Public Data + ****************************************************************************/ + +#undef EXTERN +#if defined(__cplusplus) +#define EXTERN extern "C" +extern "C" +{ +#else +#define EXTERN extern +#endif + +/**************************************************************************** + * Public Function Prototypes + ****************************************************************************/ + +/**************************************************************************** + * Name: sam_tc_allocate + * + * Description: + * Configures a Timer Counter to operate in the given mode. The timer is + * stopped after configuration and must be restarted with sam_tc_start(). + * All the interrupts of the timer are also disabled. + * + * Input Parameters: + * channel TC channel number (see TC_CHANx definitions) + * mode Operating mode (TC_CMR value). + * + * Returned Value: + * On success, a non-NULL handle value is returned. This handle may be + * used with subsequent timer/counter interfaces to manage the timer. A + * NULL handle value is returned on a failure. + * + ****************************************************************************/ + +TC_HANDLE sam_tc_allocate(int channel, int mode); + +/**************************************************************************** + * Name: sam_tc_free + * + * Description: + * Release the handle previously allocated by sam_tc_allocate(). + * + * Input Parameters: + * handle Channel handle previously allocated by sam_tc_allocate() + * + * Returned Value: + * None + * + ****************************************************************************/ + +void sam_tc_free(TC_HANDLE handle); + +/**************************************************************************** + * Name: sam_tc_start + * + * Description: + * Reset and Start the TC Channel. Enables the timer clock and performs a + * software reset to start the counting. + * + * Input Parameters: + * handle Channel handle previously allocated by sam_tc_allocate() + * + * Returned Value: + * + ****************************************************************************/ + +void sam_tc_start(TC_HANDLE handle); + +/**************************************************************************** + * Name: sam_tc_stop + * + * Description: + * Stop TC Channel. Disables the timer clock, stopping the counting. + * + * Input Parameters: + * handle Channel handle previously allocated by sam_tc_allocate() + * + * Returned Value: + * + ****************************************************************************/ + +void sam_tc_stop(TC_HANDLE handle); + +/**************************************************************************** + * Name: sam_tc_attach/sam_tc_detach + * + * Description: + * Attach or detach an interrupt handler to the timer interrupt. The + * interrupt is detached if the handler argument is NULL. + * + * Input Parameters: + * handle The handle that represents the timer state + * handler The interrupt handler that will be invoked when the interrupt + * condition occurs + * arg An opaque argument that will be provided when the interrupt + * handler callback is executed. Ignored if handler is NULL. + * mask The value of the timer interrupt mask register that defines + * which interrupts should be disabled. Ignored if handler is + * NULL. + * + * Returned Value: + * The address of the previous handler, if any. + * + ****************************************************************************/ + +tc_handler_t sam_tc_attach(TC_HANDLE handle, tc_handler_t handler, + void *arg, uint32_t mask); + +#define sam_tc_detach(h) sam_tc_attach(h, NULL, NULL, 0) + +/**************************************************************************** + * Name: sam_tc_getpending + * + * Description: + * Return the current contents of the interrutp status register, clearing + * all pending interrupts. + * + * Input Parameters: + * handle The handle that represents the timer state + * + * Returned Value: + * The value of the channel interrupt status register. + * + ****************************************************************************/ + +uint32_t sam_tc_getpending(TC_HANDLE handle); + +/**************************************************************************** + * Name: sam_tc_setregister + * + * Description: + * Set TC_REGA, TC_REGB, or TC_REGC register. + * + * Input Parameters: + * handle Channel handle previously allocated by sam_tc_allocate() + * regid One of {TC_REGA, TC_REGB, or TC_REGC} + * regval Then value to set in the register + * + * Returned Value: + * None + * + ****************************************************************************/ + +void sam_tc_setregister(TC_HANDLE handle, int regid, uint32_t regval); + +/**************************************************************************** + * Name: sam_tc_getregister + * + * Description: + * Get the current value of the TC_REGA, TC_REGB, or TC_REGC register. + * + * Input Parameters: + * handle Channel handle previously allocated by sam_tc_allocate() + * regid One of {TC_REGA, TC_REGB, or TC_REGC} + * + * Returned Value: + * The value of the specified register. + * + ****************************************************************************/ + +uint32_t sam_tc_getregister(TC_HANDLE handle, int regid); + +/**************************************************************************** + * Name: sam_tc_getcounter + * + * Description: + * Return the current value of the timer counter register + * + * Input Parameters: + * handle Channel handle previously allocated by sam_tc_allocate() + * + * Returned Value: + * The current value of the timer counter register for this channel. + * + ****************************************************************************/ + +uint32_t sam_tc_getcounter(TC_HANDLE handle); + +/**************************************************************************** + * Name: sam_tc_infreq + * + * Description: + * Return the timer input frequency, that is, the MCK frequency divided + * down so that the timer/counter is driven within its maximum frequency. + * + * Input Parameters: + * None + * + * Returned Value: + * The timer input frequency. + * + ****************************************************************************/ + +uint32_t sam_tc_infreq(void); + +/**************************************************************************** + * Name: sam_tc_divfreq + * + * Description: + * Return the divided timer input frequency that is currently driving the + * the timer counter. + * + * Input Parameters: + * handle Channel handle previously allocated by sam_tc_allocate() + * + * Returned Value: + * The timer counter frequency. + * + ****************************************************************************/ + +uint32_t sam_tc_divfreq(TC_HANDLE handle); + +/**************************************************************************** + * Name: sam_tc_divisor + * + * Description: + * Finds the best MCK divisor given the timer frequency and MCK. The + * result is guaranteed to satisfy the following equation: + * + * (Ftcin / (div * 65536)) <= freq <= (Ftcin / div) + * + * where: + * freq - the desired frequency + * Ftcin - The timer/counter input frequency + * div - With DIV being the highest possible value. + * + * Input Parameters: + * frequency Desired timer frequency. + * div Divisor value. + * tcclks TCCLKS field value for divisor. + * + * Returned Value: + * Zero (OK) if a proper divisor has been found, otherwise a negated errno + * value indicating the nature of the failure. + * + ****************************************************************************/ + +int sam_tc_divisor(uint32_t frequency, uint32_t *div, uint32_t *tcclks); + +#undef EXTERN +#ifdef __cplusplus +} +#endif + +#endif /* CONFIG_SAMA5_TC0 || CONFIG_SAMA5_TC1 || CONFIG_SAMA5_TC2 */ +#endif /* __ARCH_ARM_SRC_SAMA5_SAM_TC_H */ diff --git a/nuttx/arch/arm/src/sam34/sam4cm_tickless.c b/nuttx/arch/arm/src/sam34/sam4cm_tickless.c new file mode 100644 index 000000000..0c86c671e --- /dev/null +++ b/nuttx/arch/arm/src/sam34/sam4cm_tickless.c @@ -0,0 +1,376 @@ +/**************************************************************************** + * arch/arm/src/sam34/sam_tickless.c + * + * Copyright (C) 2015 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * 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. + * + ****************************************************************************/ +/**************************************************************************** + * Tickless OS Support. + * + * When CONFIG_SCHED_TICKLESS is enabled, all support for timer interrupts + * is suppressed and the platform specific code is expected to provide the + * following custom functions. + * + * void up_timer_initialize(void): Initializes the timer facilities. Called + * early in the initialization sequence (by up_intialize()). + * int up_timer_gettime(FAR struct timespec *ts): Returns the current + * time from the platform specific time source. + * int up_timer_cancel(void): Cancels the interval timer. + * int up_timer_start(FAR const struct timespec *ts): Start (or re-starts) + * the interval timer. + * + * The RTOS will provide the following interfaces for use by the platform- + * specific interval timer implementation: + * + * void sched_timer_expiration(void): Called by the platform-specific + * logic when the interval timer expires. + * + ****************************************************************************/ +/**************************************************************************** + * SAM34 Timer Usage + * + * This current implementation uses two timers: A one-shot timer to provide + * the timed events and a free running timer to provide the current time. + * Since timers are a limited resource, that could be an issue on some + * systems. + * + * We could do the job with a single timer if we were to keep the single + * timer in a free-running at all times. The SAM34 timer/counters have + * 16-bit counters with the capability to generate a compare interrupt when + * the timer matches a compare value but also to continue counting without + * stopping (giving another, different interrupt when the timer rolls over + * from 0xffff to zero). So we could potentially just set the compare + * at the number of ticks you want PLUS the current value of timer. Then + * you could have both with a single timer: An interval timer and a free- + * running counter with the same timer! + * + * Patches are welcome! + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include + +#include + +#include "sam4cm_oneshot.h" +#include "sam4cm_freerun.h" + +#ifdef CONFIG_SCHED_TICKLESS + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +#ifndef CONFIG_SAM34_TC +# error Timer/counters must be selected for the Tickless OS option +#endif + +#ifndef CONFIG_SAM34_ONESHOT +# error CONFIG_SAM34_ONESHOT must be selected for the Tickless OS option +#endif + +#ifndef CONFIG_SAM34_FREERUN +# error CONFIG_SAM34_FREERUN must be selected for the Tickless OS option +#endif + +#ifndef CONFIG_SAM34_TICKLESS_FREERUN +# error CONFIG_SAM34_TICKLESS_FREERUN must be selected for the Tickless OS option +#endif + +#ifndef CONFIG_SAM34_TICKLESS_ONESHOT +# error CONFIG_SAM34_TICKLESS_ONESHOT must be selected for the Tickless OS option +#endif + +#if CONFIG_SAM34_TICKLESS_ONESHOT == 0 && !defined(CONFIG_SAM34_TC0) +# error CONFIG_SAM34_TICKLESS_ONESHOT == 0 && CONFIG_SAM34_TC0 not selected +#elif CONFIG_SAM34_TICKLESS_ONESHOT == 1 && !defined(CONFIG_SAM34_TC0) +# error CONFIG_SAM34_TICKLESS_ONESHOT == 1 && CONFIG_SAM34_TC0 not selected +#elif CONFIG_SAM34_TICKLESS_ONESHOT == 2 && !defined(CONFIG_SAM34_TC0) +# error CONFIG_SAM34_TICKLESS_ONESHOT == 2 && CONFIG_SAM34_TC0 not selected +#elif CONFIG_SAM34_TICKLESS_ONESHOT == 3 && !defined(CONFIG_SAM34_TC1) +# error CONFIG_SAM34_TICKLESS_ONESHOT == 3 && CONFIG_SAM34_TC1 not selected +#elif CONFIG_SAM34_TICKLESS_ONESHOT == 4 && !defined(CONFIG_SAM34_TC1) +# error CONFIG_SAM34_TICKLESS_ONESHOT == 4 && CONFIG_SAM34_TC1 not selected +#elif CONFIG_SAM34_TICKLESS_ONESHOT == 5 && !defined(CONFIG_SAM34_TC1) +# error CONFIG_SAM34_TICKLESS_ONESHOT == 5 && CONFIG_SAM34_TC1 not selected +#endif + +#if CONFIG_SAM34_TICKLESS_ONESHOT < 0 || CONFIG_SAM34_TICKLESS_ONESHOT > 5 +# error CONFIG_SAMA5_TICKLESS_ONESHOT is not valid +#endif + +#if CONFIG_SAM34_TICKLESS_FREERUN == 0 && !defined(CONFIG_SAM34_TC0) +# error CONFIG_SAM34_TICKLESS_FREERUN == 0 && CONFIG_SAM34_TC0 not selected +#elif CONFIG_SAM34_TICKLESS_FREERUN == 1 && !defined(CONFIG_SAM34_TC0) +# error CONFIG_SAM34_TICKLESS_FREERUN == 1 && CONFIG_SAM34_TC0 not selected +#elif CONFIG_SAM34_TICKLESS_FREERUN == 2 && !defined(CONFIG_SAM34_TC0) +# error CONFIG_SAM34_TICKLESS_FREERUN == 2 && CONFIG_SAM34_TC0 not selected +#elif CONFIG_SAM34_TICKLESS_FREERUN == 3 && !defined(CONFIG_SAM34_TC1) +# error CONFIG_SAM34_TICKLESS_FREERUN == 3 && CONFIG_SAM34_TC1 not selected +#elif CONFIG_SAM34_TICKLESS_FREERUN == 4 && !defined(CONFIG_SAM34_TC1) +# error CONFIG_SAM34_TICKLESS_FREERUN == 4 && CONFIG_SAM34_TC1 not selected +#elif CONFIG_SAM34_TICKLESS_FREERUN == 5 && !defined(CONFIG_SAM34_TC1) +# error CONFIG_SAM34_TICKLESS_FREERUN == 5 && CONFIG_SAM34_TC1 not selected +#endif + +#if CONFIG_SAM34_TICKLESS_FREERUN < 0 || CONFIG_SAM34_TICKLESS_FREERUN > 5 +# error CONFIG_SAM34_TICKLESS_FREERUN is not valid +#endif + +#if CONFIG_SAM34_TICKLESS_FREERUN == CONFIG_SAM34_TICKLESS_ONESHOT +# error CONFIG_SAM34_TICKLESS_FREERUN is the same as CONFIG_SAM34_TICKLESS_ONESHOT +#endif + +/**************************************************************************** + * Private Types + ****************************************************************************/ + +struct sam_tickless_s +{ + struct sam_oneshot_s oneshot; + struct sam_freerun_s freerun; +}; + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +static struct sam_tickless_s g_tickless; + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: sam_oneshot_handler + * + * Description: + * Called when the one shot timer expires + * + * Input Parameters: + * None + * + * Returned Value: + * None + * + * Assumptions: + * Called early in the initialization sequence before any special + * concurrency protections are required. + * + ****************************************************************************/ + +static void sam_oneshot_handler(void *arg) +{ + tcllvdbg("Expired...\n"); + sched_timer_expiration(); +} + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: up_timer_initialize + * + * Description: + * Initializes all platform-specific timer facilities. This function is + * called early in the initialization sequence by up_intialize(). + * On return, the current up-time should be available from + * up_timer_gettime() and the interval timer is ready for use (but not + * actively timing. + * + * Provided by platform-specific code and called from the architecture- + * specific logic. + * + * Input Parameters: + * None + * + * Returned Value: + * None + * + * Assumptions: + * Called early in the initialization sequence before any special + * concurrency protections are required. + * + ****************************************************************************/ + +void up_timer_initialize(void) +{ + int ret; + + /* Initialize the one-shot timer */ + + ret = sam_oneshot_initialize(&g_tickless.oneshot, + CONFIG_SAM34_TICKLESS_ONESHOT, + CONFIG_USEC_PER_TICK); + if (ret < 0) + { + tclldbg("ERROR: sam_oneshot_initialize failed\n"); + PANIC(); + } + +#ifdef CONFIG_SCHED_TICKLESS_LIMIT_MAX_SLEEP + ret = sam_oneshot_max_delay(&g_tickless.oneshot, &g_oneshot_max_delay_usec); + if (ret < 0) + { + tclldbg("ERROR: sam_oneshot_max_delay failed\n"); + PANIC(); + } +#endif + + /* Initialize the free-running timer */ + + ret = sam_freerun_initialize(&g_tickless.freerun, + CONFIG_SAM34_TICKLESS_FREERUN, + CONFIG_USEC_PER_TICK); + if (ret < 0) + { + tclldbg("ERROR: sam_freerun_initialize failed\n"); + PANIC(); + } +} + +/**************************************************************************** + * Name: up_timer_gettime + * + * Description: + * Return the elapsed time since power-up (or, more correctly, since + * up_timer_initialize() was called). This function is functionally + * equivalent to: + * + * int clock_gettime(clockid_t clockid, FAR struct timespec *ts); + * + * when clockid is CLOCK_MONOTONIC. + * + * This function provides the basis for reporting the current time and + * also is used to eliminate error build-up from small errors in interval + * time calculations. + * + * Provided by platform-specific code and called from the RTOS base code. + * + * Input Parameters: + * ts - Provides the location in which to return the up-time. + * + * Returned Value: + * Zero (OK) is returned on success; a negated errno value is returned on + * any failure. + * + * Assumptions: + * Called from the the normal tasking context. The implementation must + * provide whatever mutual exclusion is necessary for correct operation. + * This can include disabling interrupts in order to assure atomic register + * operations. + * + ****************************************************************************/ + +int up_timer_gettime(FAR struct timespec *ts) +{ + return sam_freerun_counter(&g_tickless.freerun, ts); +} + +/**************************************************************************** + * Name: up_timer_cancel + * + * Description: + * Cancel the interval timer and return the time remaining on the timer. + * These two steps need to be as nearly atomic as possible. + * sched_timer_expiration() will not be called unless the timer is + * restarted with up_timer_start(). + * + * If, as a race condition, the timer has already expired when this + * function is called, then that pending interrupt must be cleared so + * that up_timer_start() and the remaining time of zero should be + * returned. + * + * NOTE: This function may execute at a high rate with no timer running (as + * when pre-emption is enabled and disabled). + * + * Provided by platform-specific code and called from the RTOS base code. + * + * Input Parameters: + * ts - Location to return the remaining time. Zero should be returned + * if the timer is not active. ts may be zero in which case the + * time remaining is not returned. + * + * Returned Value: + * Zero (OK) is returned on success. A call to up_timer_cancel() when + * the timer is not active should also return success; a negated errno + * value is returned on any failure. + * + * Assumptions: + * May be called from interrupt level handling or from the normal tasking + * level. Interrupts may need to be disabled internally to assure + * non-reentrancy. + * + ****************************************************************************/ + +int up_timer_cancel(FAR struct timespec *ts) +{ + return sam_oneshot_cancel(&g_tickless.oneshot, ts); +} + +/**************************************************************************** + * Name: up_timer_start + * + * Description: + * Start the interval timer. sched_timer_expiration() will be + * called at the completion of the timeout (unless up_timer_cancel + * is called to stop the timing. + * + * Provided by platform-specific code and called from the RTOS base code. + * + * Input Parameters: + * ts - Provides the time interval until sched_timer_expiration() is + * called. + * + * Returned Value: + * Zero (OK) is returned on success; a negated errno value is returned on + * any failure. + * + * Assumptions: + * May be called from interrupt level handling or from the normal tasking + * level. Interrupts may need to be disabled internally to assure + * non-reentrancy. + * + ****************************************************************************/ + +int up_timer_start(FAR const struct timespec *ts) +{ + return sam_oneshot_start(&g_tickless.oneshot, sam_oneshot_handler, NULL, ts); +} +#endif /* CONFIG_SCHED_TICKLESS */ -- cgit v1.2.3