summaryrefslogtreecommitdiff
diff options
context:
space:
mode:
authorGregory Nutt <gnutt@nuttx.org>2013-12-12 20:12:33 -0600
committerGregory Nutt <gnutt@nuttx.org>2013-12-12 20:12:33 -0600
commit599e2d697b461695f74e595b439c0107c4dc112d (patch)
tree4cd92eab1184dbb5f8368922f55d7c17d2d06104
parentb47637171ea85e8fb1b97a3533d18267771faaa6 (diff)
downloadpx4-nuttx-599e2d697b461695f74e595b439c0107c4dc112d.tar.gz
px4-nuttx-599e2d697b461695f74e595b439c0107c4dc112d.tar.bz2
px4-nuttx-599e2d697b461695f74e595b439c0107c4dc112d.zip
Add nanosleep()
-rw-r--r--nuttx/ChangeLog2
-rw-r--r--nuttx/include/time.h45
-rw-r--r--nuttx/sched/Makefile2
-rw-r--r--nuttx/sched/clock_abstime2ticks.c4
-rw-r--r--nuttx/sched/clock_time2ticks.c2
-rw-r--r--nuttx/sched/nanosleep.c215
6 files changed, 245 insertions, 25 deletions
diff --git a/nuttx/ChangeLog b/nuttx/ChangeLog
index fd407f53f..e3bc66089 100644
--- a/nuttx/ChangeLog
+++ b/nuttx/ChangeLog
@@ -6210,4 +6210,4 @@
(incomplete on initial check-in) (2013-12-12).
* lbc/time/lib_strftime.c: Need null-termination on the the string
generated by strftime(). From Max Holtzberg (2013-12-12).
-
+ * sched/nanosleep.c and include/time.h: Add nanosleep() (2013-12-12).
diff --git a/nuttx/include/time.h b/nuttx/include/time.h
index 623f9afb2..f89b0ad29 100644
--- a/nuttx/include/time.h
+++ b/nuttx/include/time.h
@@ -1,7 +1,7 @@
/********************************************************************************
* include/time.h
*
- * Copyright (C) 2007-2011 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007-2011, 2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -49,7 +49,7 @@
* Pre-processor Definitions
********************************************************************************/
-/* Clock tick of the system (frequency Hz).
+/* Clock tick of the system (frequency Hz).
*
* NOTE: This symbolic name CLK_TCK has been removed from the standard. It is
* replaced with CLOCKS_PER_SEC. Both are defined here.
@@ -100,7 +100,7 @@
#define localtime_r(c,r) gmtime_r(c,r)
/********************************************************************************
- * Global Type Declarations
+ * Public Types
********************************************************************************/
typedef uint32_t time_t; /* Holds time in seconds */
@@ -147,13 +147,13 @@ struct itimerspec
struct sigevent;
/********************************************************************************
- * Global Variables
+ * Public Data
********************************************************************************/
/* extern char *tznames[]; not supported */
/********************************************************************************
- * Global Function Prototypes
+ * Public Function Prototypes
********************************************************************************/
#undef EXTERN
@@ -164,25 +164,30 @@ extern "C" {
#define EXTERN extern
#endif
-EXTERN clock_t clock(void);
+clock_t clock(void);
-EXTERN int clock_settime(clockid_t clockid, const struct timespec *tp);
-EXTERN int clock_gettime(clockid_t clockid, struct timespec *tp);
-EXTERN int clock_getres(clockid_t clockid, struct timespec *res);
+int clock_settime(clockid_t clockid, FAR const struct timespec *tp);
+int clock_gettime(clockid_t clockid, FAR struct timespec *tp);
+int clock_getres(clockid_t clockid, FAR struct timespec *res);
-EXTERN time_t mktime(const struct tm *tp);
-EXTERN FAR struct tm *gmtime(FAR const time_t *timer);
-EXTERN FAR struct tm *gmtime_r(FAR const time_t *timer, FAR struct tm *result);
-EXTERN size_t strftime(char *s, size_t max, const char *format, const struct tm *tm);
+time_t mktime(FAR const struct tm *tp);
+FAR struct tm *gmtime(FAR const time_t *timer);
+FAR struct tm *gmtime_r(FAR const time_t *timer, FAR struct tm *result);
+size_t strftime(char *s, size_t max, FAR const char *format,
+ FAR const struct tm *tm);
-EXTERN time_t time(time_t *tloc);
+time_t time(FAR time_t *tloc);
-EXTERN int timer_create(clockid_t clockid, FAR struct sigevent *evp, FAR timer_t *timerid);
-EXTERN int timer_delete(timer_t timerid);
-EXTERN int timer_settime(timer_t timerid, int flags, FAR const struct itimerspec *value,
- FAR struct itimerspec *ovalue);
-EXTERN int timer_gettime(timer_t timerid, FAR struct itimerspec *value);
-EXTERN int timer_getoverrun(timer_t timerid);
+int timer_create(clockid_t clockid, FAR struct sigevent *evp,
+ FAR timer_t *timerid);
+int timer_delete(timer_t timerid);
+int timer_settime(timer_t timerid, int flags,
+ FAR const struct itimerspec *value,
+ FAR struct itimerspec *ovalue);
+int timer_gettime(timer_t timerid, FAR struct itimerspec *value);
+int timer_getoverrun(timer_t timerid);
+
+int nanosleep(FAR const struct timespec *rqtp, FAR struct timespec *rmtp);
#undef EXTERN
#if defined(__cplusplus)
diff --git a/nuttx/sched/Makefile b/nuttx/sched/Makefile
index 18b95b68c..60d280cb8 100644
--- a/nuttx/sched/Makefile
+++ b/nuttx/sched/Makefile
@@ -114,7 +114,7 @@ WDOG_SRCS += wd_gettime.c
TIME_SRCS = sched_processtimer.c
ifneq ($(CONFIG_DISABLE_SIGNALS),y)
-TIME_SRCS += sleep.c usleep.c
+TIME_SRCS += sleep.c usleep.c nanosleep.c
endif
CLOCK_SRCS = clock_initialize.c clock_settime.c clock_gettime.c clock_getres.c
diff --git a/nuttx/sched/clock_abstime2ticks.c b/nuttx/sched/clock_abstime2ticks.c
index c55865635..4f436dc14 100644
--- a/nuttx/sched/clock_abstime2ticks.c
+++ b/nuttx/sched/clock_abstime2ticks.c
@@ -1,7 +1,7 @@
/********************************************************************************
* clock_abstime2ticks.c
*
- * Copyright (C) 2007, 2008 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007, 2008, 2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -120,7 +120,7 @@ int clock_abstime2ticks(clockid_t clockid, FAR const struct timespec *abstime,
reltime.tv_sec -= 1;
}
- /* Convert this relative time into microseconds. */
+ /* Convert this relative time into clock ticks. */
return clock_time2ticks(&reltime, ticks);
}
diff --git a/nuttx/sched/clock_time2ticks.c b/nuttx/sched/clock_time2ticks.c
index 012f4e4f1..fc900c18c 100644
--- a/nuttx/sched/clock_time2ticks.c
+++ b/nuttx/sched/clock_time2ticks.c
@@ -98,7 +98,7 @@ int clock_time2ticks(FAR const struct timespec *reltime, FAR int *ticks)
relnsec = (int64_t)reltime->tv_sec * NSEC_PER_SEC +
(int64_t)reltime->tv_nsec;
-
+
/* Convert nanoseconds to clock ticks, rounding up to the smallest integer
* that is greater than or equal to the exact number of tick.
*/
diff --git a/nuttx/sched/nanosleep.c b/nuttx/sched/nanosleep.c
new file mode 100644
index 000000000..8a092c32b
--- /dev/null
+++ b/nuttx/sched/nanosleep.c
@@ -0,0 +1,215 @@
+/****************************************************************************
+ * sched/nanosleep.c
+ *
+ * Copyright (C) 2013 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 <time.h>
+#include <signal.h>
+#include <assert.h>
+#include <errno.h>
+
+#include <nuttx/clock.h>
+#include <arch/irq.h>
+
+#include "clock_internal.h"
+
+/****************************************************************************
+ * Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Type Declarations
+ ****************************************************************************/
+
+/****************************************************************************
+ * Global Variables
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Variables
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Function Prototypes
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: nanosleep
+ *
+ * Description:
+ * The nanosleep() function causes the current thread to be suspended from
+ * execution until either the time interval specified by the rqtp argument
+ * has elapsed or a signal is delivered to the calling thread and its
+ * action is to invoke a signal-catching function or to terminate the
+ * process. The suspension time may be longer than requested because the
+ * argument value is rounded up to an integer multiple of the sleep
+ * resolution or because of the scheduling of other activity by the
+ * system. But, except for the case of being interrupted by a signal, the
+ * suspension time will not be less than the time specified by rqtp, as
+ * measured by the system clock, CLOCK_REALTIME.
+ *
+ * The use of the nanosleep() function has no effect on the action or
+ * blockage of any signal.
+ *
+ * Parameters:
+ * rqtp - The amount of time to be suspended from execution.
+ * rmtp - If the rmtp argument is non-NULL, the timespec structure
+ * referenced by it is updated to contain the amount of time
+ * remaining in the interval (the requested time minus the time
+ * actually slept)
+ *
+ * Returned Value:
+ * If the nanosleep() function returns because the requested time has
+ * elapsed, its return value is zero.
+ *
+ * If the nanosleep() function returns because it has been interrupted by
+ * a signal, the function returns a value of -1 and sets errno to indicate
+ * the interruption. If the rmtp argument is non-NULL, the timespec
+ * structure referenced by it is updated to contain the amount of time
+ * remaining in the interval (the requested time minus the time actually
+ * slept). If the rmtp argument is NULL, the remaining time is not
+ * returned.
+ *
+ * If nanosleep() fails, it returns a value of -1 and sets errno to
+ * indicate the error. The nanosleep() function will fail if:
+ *
+ * EINTR - The nanosleep() function was interrupted by a signal.
+ * EINVAL - The rqtp argument specified a nanosecond value less than
+ * zero or greater than or equal to 1000 million.
+ * ENOSYS - The nanosleep() function is not supported by this
+ * implementation.
+ *
+ ****************************************************************************/
+
+int nanosleep(FAR const struct timespec *rqtp, FAR struct timespec *rmtp)
+{
+ irqstate_t flags;
+ uint32_t starttick;
+ sigset_t set;
+ struct siginfo value;
+ int errval;
+ int ret;
+
+ if (!rqtp || rqtp->tv_nsec < 0 || rqtp->tv_nsec >= 1000000000)
+ {
+ errval = EINVAL;
+ goto errout;
+ }
+
+ /* Get the start time of the wait. Interrupts are disabled to prevent
+ * timer interrupts while we do tick-related calculations before and
+ * after the wait.
+ */
+
+ flags = irqsave();
+ starttick = clock_systimer();
+
+ /* Set up for the sleep. Using the empty set means that we are not
+ * waiting for any particular signal. However, any unmasked signal can
+ * still awaken sigtimedwait().
+ */
+
+ (void)sigemptyset(&set);
+
+ /* nanosleep is a simple application of sigtimedwait. */
+
+ ret = sigtimedwait(&set, &value, rqtp);
+
+ /* sigtimedwait() cannot succeed. It should always return error with
+ * either (1) EAGAIN meaning that the timeout occurred, or (2) EINTR
+ * meaning that some other unblocked signal was caught.
+ */
+
+ errval = get_errno();
+ DEBUGASSERT(ret < 0 && (errval == EAGAIN || errval == EINTR));
+
+ if (errval == EAGAIN)
+ {
+ /* The timeout "error" is the normal, successful result */
+
+ return OK;
+ }
+
+ /* If we get there, the wait has fail because we were awakened by a
+ * signal. Return the amount of "unwaited" time if rmtp is non-NULL.
+ */
+
+ if (rmtp)
+ {
+ uint32_t elapsed;
+ uint32_t remaining;
+ int ticks;
+
+ /* First get the number of clock ticks that we were requested to
+ * wait.
+ */
+
+ (void)clock_time2ticks(rqtp, &ticks);
+
+ /* Get the number of ticks that we actually waited */
+
+ elapsed = clock_systimer() - starttick;
+
+ /* The difference between the number of ticks that we were requested
+ * to wait and the number of ticks that we actualy waited is that
+ * amount of time that we failed to wait.
+ */
+
+ if (elapsed >= (uint32_t)ticks)
+ {
+ remaining = 0;
+ }
+ else
+ {
+ remaining = (uint32_t)ticks - elapsed;
+ }
+
+ (void)clock_ticks2time((int)remaining, rmtp);
+ }
+
+ irqrestore(flags);
+
+errout:
+ set_errno(errval);
+ return ERROR;
+}