summaryrefslogtreecommitdiff
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
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.
-rw-r--r--nuttx/include/nuttx/rtc.h21
-rw-r--r--nuttx/include/sys/syscall.h3
-rw-r--r--nuttx/include/sys/time.h63
-rw-r--r--nuttx/libc/time/Make.defs2
-rw-r--r--nuttx/libc/time/lib_gettimeofday.c (renamed from nuttx/sched/clock/clock_gettimeofday.c)60
-rw-r--r--nuttx/libc/time/lib_settimeofday.c92
-rw-r--r--nuttx/libc/time/lib_time.c26
-rw-r--r--nuttx/sched/clock/Make.defs2
-rw-r--r--nuttx/syscall/syscall.csv1
-rw-r--r--nuttx/syscall/syscall_lookup.h1
-rw-r--r--nuttx/syscall/syscall_stublookup.c1
11 files changed, 196 insertions, 76 deletions
diff --git a/nuttx/include/nuttx/rtc.h b/nuttx/include/nuttx/rtc.h
index 1b5658f16..b7801fd36 100644
--- a/nuttx/include/nuttx/rtc.h
+++ b/nuttx/include/nuttx/rtc.h
@@ -130,7 +130,8 @@ extern volatile bool g_rtc_enabled;
#undef EXTERN
#if defined(__cplusplus)
#define EXTERN extern "C"
-extern "C" {
+extern "C"
+{
#else
#define EXTERN extern
#endif
@@ -150,7 +151,7 @@ extern "C" {
*
************************************************************************************/
-EXTERN int up_rtcinitialize(void);
+int up_rtcinitialize(void);
/************************************************************************************
* Name: up_rtc_time
@@ -159,7 +160,7 @@ EXTERN int up_rtcinitialize(void);
* Get the current time in seconds. This is similar to the standard time()
* function. This interface is only required if the low-resolution RTC/counter
* hardware implementation selected. It is only used by the RTOS during
- * initializeation to set up the system time when CONFIG_RTC is set but neither
+ * initialization to set up the system time when CONFIG_RTC is set but neither
* CONFIG_RTC_HIRES nor CONFIG_RTC_DATETIME are set.
*
* Input Parameters:
@@ -171,7 +172,7 @@ EXTERN int up_rtcinitialize(void);
************************************************************************************/
#ifndef CONFIG_RTC_HIRES
-EXTERN time_t up_rtc_time(void);
+time_t up_rtc_time(void);
#endif
/************************************************************************************
@@ -191,7 +192,7 @@ EXTERN time_t up_rtc_time(void);
************************************************************************************/
#ifdef CONFIG_RTC_HIRES
-EXTERN int up_rtc_gettime(FAR struct timespec *tp);
+int up_rtc_gettime(FAR struct timespec *tp);
#endif
/************************************************************************************
@@ -201,7 +202,7 @@ EXTERN int up_rtc_gettime(FAR struct timespec *tp);
* Get the current date and time from the date/time RTC. This interface
* is only supported by the date/time RTC hardware implementation.
* It is used to replace the system timer. It is only used by the RTOS during
- * initializeation to set up the system time when CONFIG_RTC and CONFIG_RTC_DATETIME
+ * initialization to set up the system time when CONFIG_RTC and CONFIG_RTC_DATETIME
* are selected (and CONFIG_RTC_HIRES is not).
*
* NOTE: Some date/time RTC hardware is capability of sub-second accuracy. That
@@ -218,7 +219,7 @@ EXTERN int up_rtc_gettime(FAR struct timespec *tp);
************************************************************************************/
#ifdef CONFIG_RTC_DATETIME
-EXTERN int up_rtc_getdatetime(FAR struct tm *tp);
+int up_rtc_getdatetime(FAR struct tm *tp);
#endif
/************************************************************************************
@@ -236,7 +237,7 @@ EXTERN int up_rtc_getdatetime(FAR struct tm *tp);
*
************************************************************************************/
-EXTERN int up_rtc_settime(FAR const struct timespec *tp);
+int up_rtc_settime(FAR const struct timespec *tp);
/************************************************************************************
* Name: up_rtc_setalarm
@@ -254,7 +255,7 @@ EXTERN int up_rtc_settime(FAR const struct timespec *tp);
************************************************************************************/
#ifdef CONFIG_RTC_ALARM
-EXTERN int up_rtc_setalarm(FAR const struct timespec *tp, alarmcb_t callback);
+int up_rtc_setalarm(FAR const struct timespec *tp, alarmcb_t callback);
#endif
/************************************************************************************
@@ -272,7 +273,7 @@ EXTERN int up_rtc_setalarm(FAR const struct timespec *tp, alarmcb_t callback);
************************************************************************************/
#ifdef CONFIG_RTC_ALARM
-EXTERN int up_rtc_cancelalarm(void);
+int up_rtc_cancelalarm(void);
#endif
#undef EXTERN
diff --git a/nuttx/include/sys/syscall.h b/nuttx/include/sys/syscall.h
index c0d163452..79c8433b3 100644
--- a/nuttx/include/sys/syscall.h
+++ b/nuttx/include/sys/syscall.h
@@ -202,8 +202,7 @@
#define SYS_clock_getres (__SYS_clock+1)
#define SYS_clock_gettime (__SYS_clock+2)
#define SYS_clock_settime (__SYS_clock+3)
-#define SYS_gettimeofday (__SYS_clock+4)
-#define __SYS_timers (__SYS_clock+5)
+#define __SYS_timers (__SYS_clock+4)
/* The following are defined only if POSIX timers are supported */
diff --git a/nuttx/include/sys/time.h b/nuttx/include/sys/time.h
index 75dfd7280..e9bc3d6b3 100644
--- a/nuttx/include/sys/time.h
+++ b/nuttx/include/sys/time.h
@@ -1,7 +1,7 @@
/****************************************************************************
* include/sys/time.h
*
- * Copyright (C) 2009 Gregory Nutt. All rights reserved.
+ * 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
@@ -51,6 +51,17 @@
/****************************************************************************
* Public Type Definitions
****************************************************************************/
+/* struct timeval is defined in time.h */
+
+/* The use of the struct timezone is obsolete; the tz argument should
+ * normally be specified as NULL (and is ignored in any event).
+ */
+
+struct timezone
+{
+ int tz_minuteswest; /* Minutes west of Greenwich */
+ int tz_dsttime; /* Type of DST correction */
+};
/****************************************************************************
* Public Function Prototypes
@@ -59,12 +70,58 @@
#undef EXTERN
#if defined(__cplusplus)
#define EXTERN extern "C"
-extern "C" {
+extern "C"
+{
#else
#define EXTERN extern
#endif
-EXTERN int gettimeofday(struct timeval *tp, FAR void *tzp);
+/****************************************************************************
+ * 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);
+
+/****************************************************************************
+ * 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);
#undef EXTERN
#if defined(__cplusplus)
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/sched/clock/clock_gettimeofday.c b/nuttx/libc/time/lib_gettimeofday.c
index 22a58d052..e14d0af34 100644
--- a/nuttx/sched/clock/clock_gettimeofday.c
+++ b/nuttx/libc/time/lib_gettimeofday.c
@@ -1,7 +1,7 @@
/****************************************************************************
- * sched/clock/clock_gettimeofday.c
+ * libc/time/lib_gettimeofday.c
*
- * Copyright (C) 2009 Gregory Nutt. All rights reserved.
+ * 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
@@ -40,38 +40,10 @@
#include <nuttx/config.h>
#include <sys/time.h>
+#include <time.h>
#include <errno.h>
-#include <debug.h>
-#include "clock/clock.h"
-
-/****************************************************************************
- * Definitions
- ****************************************************************************/
-
-/****************************************************************************
- * Private Type Declarations
- ****************************************************************************/
-
-/****************************************************************************
- * Private Function Prototypes
- ****************************************************************************/
-
-/**************************************************************************
- * Public Constant Data
- **************************************************************************/
-
-/****************************************************************************
- * Public Variables
- ****************************************************************************/
-
-/**************************************************************************
- * Private Variables
- **************************************************************************/
-
-/****************************************************************************
- * Private Functions
- ****************************************************************************/
+#include <nuttx/clock.h>
/****************************************************************************
* Public Functions
@@ -81,17 +53,31 @@
* Name: gettimeofday
*
* Description:
- * Get the current time
+ * 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(struct timeval *tp, void *tzp)
+int gettimeofday(FAR struct timeval *tv, FAR struct timezone *tz)
{
struct timespec ts;
int ret;
#ifdef CONFIG_DEBUG
- if (!tp)
+ if (!tv)
{
set_errno(EINVAL);
return ERROR;
@@ -105,8 +91,8 @@ int gettimeofday(struct timeval *tp, void *tzp)
{
/* Convert the struct timespec to a struct timeval */
- tp->tv_sec = ts.tv_sec;
- tp->tv_usec = ts.tv_nsec / NSEC_PER_USEC;
+ 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;
diff --git a/nuttx/sched/clock/Make.defs b/nuttx/sched/clock/Make.defs
index 19ab8bae0..e52c73813 100644
--- a/nuttx/sched/clock/Make.defs
+++ b/nuttx/sched/clock/Make.defs
@@ -35,7 +35,7 @@
CSRCS += clock_initialize.c clock_settime.c clock_gettime.c clock_getres.c
CSRCS += clock_time2ticks.c clock_abstime2ticks.c clock_ticks2time.c
-CSRCS += clock_gettimeofday.c clock_systimer.c clock_systimespec.c
+CSRCS += clock_systimer.c clock_systimespec.c
# Include clock build support
diff --git a/nuttx/syscall/syscall.csv b/nuttx/syscall/syscall.csv
index 708a6aafb..1ad010d62 100644
--- a/nuttx/syscall/syscall.csv
+++ b/nuttx/syscall/syscall.csv
@@ -26,7 +26,6 @@
"getenv","stdlib.h","!defined(CONFIG_DISABLE_ENVIRON)","FAR char*","FAR const char*"
"getpid","unistd.h","","pid_t"
"getsockopt","sys/socket.h","CONFIG_NSOCKET_DESCRIPTORS > 0 && defined(CONFIG_NET)","int","int","int","int","FAR void*","FAR socklen_t*"
-"gettimeofday","sys/time.h","","int","struct timeval*","FAR void*"
"ioctl","sys/ioctl.h","!defined(CONFIG_LIBC_IOCTL_VARIADIC) && (CONFIG_NSOCKET_DESCRIPTORS > 0 || CONFIG_NFILE_DESCRIPTORS > 0)","int","int","int","unsigned long"
"kill","signal.h","!defined(CONFIG_DISABLE_SIGNALS)","int","pid_t","int"
"listen","sys/socket.h","CONFIG_NSOCKET_DESCRIPTORS > 0 && defined(CONFIG_NET)","int","int","int"
diff --git a/nuttx/syscall/syscall_lookup.h b/nuttx/syscall/syscall_lookup.h
index 11cdb92e1..e6c41a477 100644
--- a/nuttx/syscall/syscall_lookup.h
+++ b/nuttx/syscall/syscall_lookup.h
@@ -142,7 +142,6 @@ SYSCALL_LOOKUP(up_assert, 2, STUB_up_assert)
SYSCALL_LOOKUP(clock_getres, 2, STUB_clock_getres)
SYSCALL_LOOKUP(clock_gettime, 2, STUB_clock_gettime)
SYSCALL_LOOKUP(clock_settime, 2, STUB_clock_settime)
- SYSCALL_LOOKUP(gettimeofday, 2, STUB_gettimeofday)
/* The following are defined only if POSIX timers are supported */
diff --git a/nuttx/syscall/syscall_stublookup.c b/nuttx/syscall/syscall_stublookup.c
index 1a32ab687..63db0d773 100644
--- a/nuttx/syscall/syscall_stublookup.c
+++ b/nuttx/syscall/syscall_stublookup.c
@@ -144,7 +144,6 @@ uintptr_t STUB_clock_systimer(int nbr);
uintptr_t STUB_clock_getres(int nbr, uintptr_t parm1, uintptr_t parm2);
uintptr_t STUB_clock_gettime(int nbr, uintptr_t parm1, uintptr_t parm2);
uintptr_t STUB_clock_settime(int nbr, uintptr_t parm1, uintptr_t parm2);
-uintptr_t STUB_gettimeofday(int nbr, uintptr_t parm1, uintptr_t parm2);
/* The following are defined only if POSIX timers are supported */