summaryrefslogtreecommitdiff
path: root/nuttx/libc
diff options
context:
space:
mode:
authorGregory Nutt <gnutt@nuttx.org>2015-02-12 11:10:46 -0600
committerGregory Nutt <gnutt@nuttx.org>2015-02-12 11:10:46 -0600
commit7881095dcc9ce16c67163cc3d9b8fb7c2adf4c66 (patch)
tree3e19b46c12a2c7f69b667e8af63c0edc21b22fd4 /nuttx/libc
parent3d8e5f1f984e800f6224e6433882668f907111bd (diff)
downloadpx4-nuttx-7881095dcc9ce16c67163cc3d9b8fb7c2adf4c66.tar.gz
px4-nuttx-7881095dcc9ce16c67163cc3d9b8fb7c2adf4c66.tar.bz2
px4-nuttx-7881095dcc9ce16c67163cc3d9b8fb7c2adf4c66.zip
gettimeofday() and settimeofday(): Move gittimeofdady() from sched/clock to libc/time. All remove gettimeofday() from NuttX system calls. It is only a wrapper around clock_settime() and does not need a trap. gettimeofday() is no longer tried as a core OS interface.
gettimeofday has been decremented in POSIX 2008. settimeofday() was never part of POSIX, but I decided to add it to libc as well just for symmetry.
Diffstat (limited to 'nuttx/libc')
-rw-r--r--nuttx/libc/time/Make.defs2
-rw-r--r--nuttx/libc/time/lib_gettimeofday.c99
-rw-r--r--nuttx/libc/time/lib_settimeofday.c92
-rw-r--r--nuttx/libc/time/lib_time.c26
4 files changed, 199 insertions, 20 deletions
diff --git a/nuttx/libc/time/Make.defs b/nuttx/libc/time/Make.defs
index 721057f34..1d599ec93 100644
--- a/nuttx/libc/time/Make.defs
+++ b/nuttx/libc/time/Make.defs
@@ -36,7 +36,7 @@
# Add the time C files to the build
CSRCS += lib_strftime.c lib_calendar2utc.c lib_daysbeforemonth.c
-CSRCS += lib_isleapyear.c lib_time.c
+CSRCS += lib_gettimeofday.c lib_isleapyear.c lib_settimeofday.c lib_time.c
ifdef CONFIG_LIBC_LOCALTIME
CSRCS += lib_localtime.c
diff --git a/nuttx/libc/time/lib_gettimeofday.c b/nuttx/libc/time/lib_gettimeofday.c
new file mode 100644
index 000000000..e14d0af34
--- /dev/null
+++ b/nuttx/libc/time/lib_gettimeofday.c
@@ -0,0 +1,99 @@
+/****************************************************************************
+ * libc/time/lib_gettimeofday.c
+ *
+ * Copyright (C) 2009, 2015 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 <sys/time.h>
+#include <time.h>
+#include <errno.h>
+
+#include <nuttx/clock.h>
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: gettimeofday
+ *
+ * Description:
+ * Get the current time
+ *
+ * Conforming to SVr4, 4.3BSD. POSIX.1-2001 describes gettimeofday().
+ * POSIX.1-2008 marks gettimeofday() as obsolete, recommending the use of
+ * clock_gettime(2) instead.
+ *
+ * NuttX implements gettimeofday() as a thin layer around clock_gettime();
+ *
+ * Input Parameters:
+ * tv - The location to return the current time
+ * tz - Ignored
+ *
+ * Returned value:
+ * Zero (OK) on success; -1 is returned on failure with the errno variable
+ * set appropriately.
+ *
+ ****************************************************************************/
+
+int gettimeofday(FAR struct timeval *tv, FAR struct timezone *tz)
+{
+ struct timespec ts;
+ int ret;
+
+#ifdef CONFIG_DEBUG
+ if (!tv)
+ {
+ set_errno(EINVAL);
+ return ERROR;
+ }
+#endif
+
+ /* Let clock_gettime do most of the work */
+
+ ret = clock_gettime(CLOCK_REALTIME, &ts);
+ if (ret == OK)
+ {
+ /* Convert the struct timespec to a struct timeval */
+
+ tv->tv_sec = ts.tv_sec;
+ tv->tv_usec = ts.tv_nsec / NSEC_PER_USEC;
+ }
+
+ return ret;
+}
diff --git a/nuttx/libc/time/lib_settimeofday.c b/nuttx/libc/time/lib_settimeofday.c
new file mode 100644
index 000000000..bef088c38
--- /dev/null
+++ b/nuttx/libc/time/lib_settimeofday.c
@@ -0,0 +1,92 @@
+/****************************************************************************
+ * libc/time/lib_settimeofday.c
+ *
+ * Copyright (C) 2015 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 <sys/time.h>
+#include <time.h>
+#include <errno.h>
+
+#include <nuttx/clock.h>
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: settimeofday
+ *
+ * Description:
+ * Set the current time
+ *
+ * Conforming to SVr4, 4.3BSD. POSIX.1-2001 describes gettimeofday() but
+ * not settimeofday().
+ *
+ * NuttX implements settimeofday() as a thin layer around clock_settime();
+ *
+ * Input Parameters:
+ * tv - The net to time to be set
+ * tz - Ignored
+ *
+ * Returned value:
+ * Zero (OK) on success; -1 is returned on failure with the errno variable
+ * set appropriately.
+ *
+ ****************************************************************************/
+
+int settimeofday(FAR const struct timeval *tv, FAR struct timezone *tz)
+{
+ struct timespec ts;
+
+#ifdef CONFIG_DEBUG
+ if (!tv || tv->tv_usec >= USEC_PER_SEC)
+ {
+ set_errno(EINVAL);
+ return ERROR;
+ }
+#endif
+ /* Convert the timeval to a timespec */
+
+ ts.tv_sec = tv->tv_sec;
+ ts.tv_nsec = tv->tv_usec * NSEC_PER_USEC;
+
+ /* Let clock_settime do the work */
+
+ return clock_settime(CLOCK_REALTIME, &ts);
+}
diff --git a/nuttx/libc/time/lib_time.c b/nuttx/libc/time/lib_time.c
index 8e596ef17..c7c1a6565 100644
--- a/nuttx/libc/time/lib_time.c
+++ b/nuttx/libc/time/lib_time.c
@@ -43,18 +43,6 @@
#include <time.h>
/****************************************************************************
- * Pre-processor Definitions
- ****************************************************************************/
-
-/****************************************************************************
- * Private Data
- ****************************************************************************/
-
-/****************************************************************************
- * Public Functions
- ****************************************************************************/
-
-/****************************************************************************
* Function: time
*
* Description:
@@ -62,13 +50,13 @@
* this value, and if the argument is not a null pointer, the value is also
* set to the object pointed by tloc.
*
- * Note that this function is just a thin wrapper around gettimeofday()
- * and is provided for compatibility. gettimeofday() is the preffered way
+ * Note that this function is just a thin wrapper around clock_gettime()
+ * and is provided for compatibility. clock_gettime() is the preferred way
* to obtain system time.
*
* Parameters:
* Pointer to an object of type time_t, where the time value is stored.
- * Alternativelly, this parameter can be a null pointer, in which case the
+ * Alternatively, this parameter can be a null pointer, in which case the
* parameter is not used, but a time_t object is still returned by the
* function.
*
@@ -84,22 +72,22 @@
time_t time(time_t *tloc)
{
- struct timeval tp;
+ struct timespec ts;
int ret;
/* Get the current time from the system */
- ret = gettimeofday(&tp, NULL);
+ ret = clock_gettime(CLOCK_REALTIME, &ts);
if (ret == OK)
{
/* Return the seconds since the epoch */
if (tloc)
{
- *tloc = tp.tv_sec;
+ *tloc = ts.tv_sec;
}
- return tp.tv_sec;
+ return ts.tv_sec;
}
return (time_t)ERROR;