summaryrefslogtreecommitdiff
path: root/nuttx/sched/clock
diff options
context:
space:
mode:
authorGregory Nutt <gnutt@nuttx.org>2014-08-15 03:55:41 -0600
committerGregory Nutt <gnutt@nuttx.org>2014-08-15 03:55:41 -0600
commita6ee65bab25417ed591db423c2bc670a38a1dcba (patch)
tree6b84b3126c91b872b44294370b31d135df034f26 /nuttx/sched/clock
parentfbcb900cc1c4d5f8f647ed45fc43b00eb4949eec (diff)
downloadpx4-nuttx-a6ee65bab25417ed591db423c2bc670a38a1dcba.tar.gz
px4-nuttx-a6ee65bab25417ed591db423c2bc670a38a1dcba.tar.bz2
px4-nuttx-a6ee65bab25417ed591db423c2bc670a38a1dcba.zip
When reading the system timer, don't read a struct timespec, convert it to a fake tick count, then back to a timespec. Remove CLOCK_ACTIVETIME.. it is non-standard, unused, and gets in the way of changes like this
Diffstat (limited to 'nuttx/sched/clock')
-rw-r--r--nuttx/sched/clock/Make.defs2
-rw-r--r--nuttx/sched/clock/clock_gettime.c105
-rw-r--r--nuttx/sched/clock/clock_settime.c8
-rw-r--r--nuttx/sched/clock/clock_systimespec.c140
4 files changed, 176 insertions, 79 deletions
diff --git a/nuttx/sched/clock/Make.defs b/nuttx/sched/clock/Make.defs
index aa7dce762..6e1bbcb9b 100644
--- a/nuttx/sched/clock/Make.defs
+++ b/nuttx/sched/clock/Make.defs
@@ -35,7 +35,7 @@
CLOCK_SRCS = clock_initialize.c clock_settime.c clock_gettime.c clock_getres.c
CLOCK_SRCS += clock_time2ticks.c clock_abstime2ticks.c clock_ticks2time.c
-CLOCK_SRCS += clock_gettimeofday.c clock_systimer.c
+CLOCK_SRCS += clock_gettimeofday.c clock_systimer.c clock_systimespec.c
# Include clock build support
diff --git a/nuttx/sched/clock/clock_gettime.c b/nuttx/sched/clock/clock_gettime.c
index d0cc48370..3b716ffcf 100644
--- a/nuttx/sched/clock/clock_gettime.c
+++ b/nuttx/sched/clock/clock_gettime.c
@@ -92,15 +92,7 @@
int clock_gettime(clockid_t clock_id, struct timespec *tp)
{
-#ifdef CONFIG_SYSTEM_TIME64
- uint64_t msecs;
- uint64_t secs;
- uint64_t nsecs;
-#else
- uint32_t msecs;
- uint32_t secs;
- uint32_t nsecs;
-#endif
+ struct timespec ts;
uint32_t carry;
int ret = OK;
@@ -122,17 +114,11 @@ int clock_gettime(clockid_t clock_id, struct timespec *tp)
if (clock_id == CLOCK_MONOTONIC)
{
- /* Get the time since power-on in seconds and milliseconds */
-
- msecs = TICK2MSEC(clock_systimer());
- secs = msecs / MSEC_PER_SEC;
-
- /* Return the elapsed time in seconds and nanoseconds */
-
- nsecs = (msecs - (secs * MSEC_PER_SEC)) * NSEC_PER_MSEC;
+ /* The the time elapsed since the timer was initialized at power on
+ * reset.
+ */
- tp->tv_sec = (time_t)secs;
- tp->tv_nsec = (long)nsecs;
+ ret = clock_systimespec(tp);
}
else
#endif
@@ -141,85 +127,60 @@ int clock_gettime(clockid_t clock_id, struct timespec *tp)
* represents the machine's best-guess as to the current wall-clock,
* time-of-day time. This means that CLOCK_REALTIME can jump forward and
* backward as the system time-of-day clock is changed.
- *
- * If an RTC is supported, then the non-standard CLOCK_ACTIVETIME is also
- * supported to manage time based on the system timer interrupt separately
- * from the RTC. This may be necessary, for example, in certain cases where
- * the system timer interrupt has been stopped in low power modes.
*/
-#ifdef CONFIG_RTC
- if (clock_id == CLOCK_REALTIME || clock_id == CLOCK_ACTIVETIME)
-#else
if (clock_id == CLOCK_REALTIME)
-#endif
{
- /* Do we have a high-resolution RTC that can provide us with the time? */
-
-#ifdef CONFIG_RTC_HIRES
- if (g_rtc_enabled && clock_id != CLOCK_ACTIVETIME)
- {
- /* Yes.. Get the hi-resolution time from the RTC unless the caller
- * has specifically asked for the system timer (CLOCK_ACTIVETIME)
- */
-
- ret = up_rtc_gettime(tp);
- }
- else
-#endif
+ /* Get the elapsedcd s time since the time-of-day was last set.
+ * clock_systimespec() provides the time since power was applied;
+ * the bias value corresponds to the time when the time-of-day was
+ * last set.
+ */
+
+ ret = clock_systimespec(&ts);
+ if (ret == OK)
{
- /* Get the elapsed time since the time-of-day was last set.
- * clock_systimer() provides the number of clock times since
- * power was applied; the bias value corresponds to the time
- * when the time-of-day was last set.
- */
-
- msecs = TICK2MSEC((clock_systimer() - g_tickbias));
-
- sdbg("msecs = %d g_tickbias=%d\n",
- (int)msecs, (int)g_tickbias);
-
- /* Get the elapsed time in seconds and nanoseconds. */
-
- secs = msecs / MSEC_PER_SEC;
- nsecs = (msecs - (secs * MSEC_PER_SEC)) * NSEC_PER_MSEC;
-
- sdbg("secs = %d + %d nsecs = %d + %d\n",
- (int)msecs, (int)g_basetime.tv_sec,
- (int)nsecs, (int)g_basetime.tv_nsec);
-
/* Add the base time to this. The base time is the time-of-day
* setting. When added to the elapsed time since the time-of-day
* was last set, this gives us the current time.
*/
- secs += (uint32_t)g_basetime.tv_sec;
- nsecs += (uint32_t)g_basetime.tv_nsec;
+ ts.tv_sec += (uint32_t)g_basetime.tv_sec;
+ ts.tv_nsec += (uint32_t)g_basetime.tv_nsec;
/* Handle carry to seconds. */
- if (nsecs > NSEC_PER_SEC)
+ if (ts.tv_nsec > NSEC_PER_SEC)
{
- carry = nsecs / NSEC_PER_SEC;
- secs += carry;
- nsecs -= (carry * NSEC_PER_SEC);
+ carry = ts.tv_nsec / NSEC_PER_SEC;
+ ts.tv_sec += carry;
+ ts.tv_nsec -= (carry * NSEC_PER_SEC);
}
/* And return the result to the caller. */
- tp->tv_sec = (time_t)secs;
- tp->tv_nsec = (long)nsecs;
+ tp->tv_sec = ts.tv_sec;
+ tp->tv_nsec = ts.tv_nsec;
}
-
- sdbg("Returning tp=(%d,%d)\n", (int)tp->tv_sec, (int)tp->tv_nsec);
}
else
{
+ ret = -EINVAL;
+ }
+
+ /* Check for errors and set the errno value if necessary */
+
+ if (ret < 0)
+ {
sdbg("Returning ERROR\n");
- set_errno(EINVAL);
+ set_errno(-ret);
ret = ERROR;
}
+ else
+ {
+ sdbg("Returning tp=(%d,%d)\n", (int)tp->tv_sec, (int)tp->tv_nsec);
+ }
return ret;
}
diff --git a/nuttx/sched/clock/clock_settime.c b/nuttx/sched/clock/clock_settime.c
index 8d26da155..78e9e961f 100644
--- a/nuttx/sched/clock/clock_settime.c
+++ b/nuttx/sched/clock/clock_settime.c
@@ -1,7 +1,7 @@
/************************************************************************
* sched/clock/clock_settime.c
*
- * Copyright (C) 2007, 2009, 2011 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007, 2009, 2011, 2014 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -100,11 +100,7 @@ int clock_settime(clockid_t clock_id, FAR const struct timespec *tp)
* time clock.
*/
-#ifdef CONFIG_RTC
- if (clock_id == CLOCK_REALTIME || clock_id == CLOCK_ACTIVETIME)
-#else
if (clock_id == CLOCK_REALTIME)
-#endif
{
/* Interrupts are disabled here so that the in-memory time
* representation and the RTC setting will be as close as
@@ -127,7 +123,7 @@ int clock_settime(clockid_t clock_id, FAR const struct timespec *tp)
/* Setup the RTC (lo- or high-res) */
#ifdef CONFIG_RTC
- if (g_rtc_enabled && clock_id != CLOCK_ACTIVETIME)
+ if (g_rtc_enabled)
{
up_rtc_settime(tp);
}
diff --git a/nuttx/sched/clock/clock_systimespec.c b/nuttx/sched/clock/clock_systimespec.c
new file mode 100644
index 000000000..cacdf0ae9
--- /dev/null
+++ b/nuttx/sched/clock/clock_systimespec.c
@@ -0,0 +1,140 @@
+/****************************************************************************
+ * sched/clock/clock_systimespec.c
+ *
+ * Copyright (C) 2014 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <stdint.h>
+#include <time.h>
+
+#include <nuttx/arch.h>
+#include <nuttx/clock.h>
+
+#include "clock/clock.h"
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: clock_systimespec
+ *
+ * Description:
+ * Return the current value of the system timer counter as a struct
+ * timespec.
+ *
+ * Parameters:
+ * ts - Location to return the time
+ *
+ * Return Value:
+ * Current version always returns OK
+ *
+ * Assumptions:
+ *
+ ****************************************************************************/
+
+int clock_systimespec(FAR struct timespec *ts)
+{
+ #ifdef CONFIG_RTC_HIRES
+ /* Do we have a high-resolution RTC that can provide us with the time? */
+
+ if (g_rtc_enabled)
+ {
+ /* Get the hi-resolution time from the RTC */
+
+ ret = up_rtc_gettime(tp);
+ }
+ else
+#endif
+
+#if defined(CONFIG_SCHED_TICKLESS)
+ {
+ /* Let the platform time do the work */
+
+ return up_timer_gettime(ts);
+ }
+
+#elif defined(CONFIG_HAVE_LONG_LONG)
+ {
+ uint64_t usecs;
+ uint64_t secs;
+ uint64_t nsecs;
+
+ /* Get the time since power-on in seconds and milliseconds */
+
+ usecs = TICK2MSEC(clock_systimer());
+ secs = usecs / USEC_PER_SEC;
+
+ /* Return the elapsed time in seconds and nanoseconds */
+
+ nsecs = (usecs - (secs * USEC_PER_SEC)) * NSEC_PER_USEC;
+
+ ts->tv_sec = (time_t)secs;
+ ts->tv_nsec = (long)nsecs;
+ return OK;
+ }
+
+#else
+ {
+ uint32_t msecs;
+ uint32_t secs;
+ uint32_t nsecs;
+
+ /* Get the time since power-on in seconds and milliseconds */
+
+ msecs = TICK2MSEC(clock_systimer());
+ secs = msecs / MSEC_PER_SEC;
+
+ /* Return the elapsed time in seconds and nanoseconds */
+
+ nsecs = (msecs - (secs * MSEC_PER_SEC)) * NSEC_PER_MSEC;
+
+ ts->tv_sec = (time_t)secs;
+ ts->tv_nsec = (long)nsecs;
+ return OK;
+ }
+#endif
+}