summaryrefslogtreecommitdiff
diff options
context:
space:
mode:
-rw-r--r--nuttx/Documentation/NuttxPortingGuide.html7
-rw-r--r--nuttx/configs/README.txt6
-rw-r--r--nuttx/configs/c5471evm/defconfig6
-rw-r--r--nuttx/configs/m68332evb/defconfig6
-rw-r--r--nuttx/configs/mcu123-lpc214x/defconfig6
-rw-r--r--nuttx/configs/ntosd-dm320/defconfig6
-rw-r--r--nuttx/configs/pjrc-8051/defconfig6
-rw-r--r--nuttx/configs/sim/defconfig6
-rw-r--r--nuttx/include/nuttx/net.h21
-rw-r--r--nuttx/include/nuttx/os_external.h79
-rw-r--r--nuttx/include/sys/socket.h19
-rw-r--r--nuttx/net/Makefile10
-rw-r--r--nuttx/net/getsockopt.c139
-rw-r--r--nuttx/net/net-dsec2timeval.c79
-rw-r--r--nuttx/net/net-timeo.c80
-rw-r--r--nuttx/net/net-timeval2dsec.c75
-rw-r--r--nuttx/net/net_internal.h79
-rw-r--r--nuttx/net/setsockopt.c145
-rw-r--r--nuttx/sched/clock_internal.h32
19 files changed, 691 insertions, 116 deletions
diff --git a/nuttx/Documentation/NuttxPortingGuide.html b/nuttx/Documentation/NuttxPortingGuide.html
index 5b8335232..4e8c0beca 100644
--- a/nuttx/Documentation/NuttxPortingGuide.html
+++ b/nuttx/Documentation/NuttxPortingGuide.html
@@ -1350,10 +1350,13 @@ The system can be re-made subsequently by just typing <code>make</code>.
<code>CONFIG_NSOCKET_DESCRIPTORS</code>: Maximum number of socket descriptors per task/thread.
</li>
<li>
- <code>CONFIG_NET_MAX_CONNECTIONS</code>: Maximum number of TCP connections
+ <code>CONFIG_NET_MAX_CONNECTIONS</code>: Maximum number of TCP connections (all tasks).
</li>
<li>
- <code>CONFIG_NET_MAX_LISTENPORTS</code>: Maximum number of listening TCP ports
+ <code>CONFIG_NET_MAX_LISTENPORTS</code>: Maximum number of listening TCP ports (all tasks).
+ </li>
+ <li>
+ <code>CONFIG_NET_SOCKOPTS</code>: Enable or disable support for socket options.
</li>
<li>
<code>CONFIG_NET_BUFFER_SIZE</code>: uIP buffer size
diff --git a/nuttx/configs/README.txt b/nuttx/configs/README.txt
index ffba46227..a3ea2ec3e 100644
--- a/nuttx/configs/README.txt
+++ b/nuttx/configs/README.txt
@@ -212,8 +212,10 @@ defconfig -- This is a configuration file similar to the Linux
CONFIG_NET - Enable or disable all network features
CONFIG_NET_IPv6 - Build in support for IPv6
CONFIG_NSOCKET_DESCRIPTORS - Maximum number of socket descriptors per task/thread.
- CONFIG_NET_MAX_CONNECTIONS - Maximum number of TCP connections
- CONFIG_NET_MAX_LISTENPORTS - Maximum number of listening TCP ports
+ CONFIG_NET_MAX_CONNECTIONS - Maximum number of TCP connections (all tasks)
+ CONFIG_NET_MAX_LISTENPORTS - Maximum number of listening TCP ports (all tasks)
+ CONFIG_NET_SOCKOPTS - Enable or disable support for socket options
+
CONFIG_NET_BUFFER_SIZE - uIP buffer size
CONFIG_NET_LOGGING - Logging on or off
CONFIG_NET_UDP - UDP support on or off
diff --git a/nuttx/configs/c5471evm/defconfig b/nuttx/configs/c5471evm/defconfig
index cad404821..c14905848 100644
--- a/nuttx/configs/c5471evm/defconfig
+++ b/nuttx/configs/c5471evm/defconfig
@@ -254,8 +254,9 @@ CONFIG_PREALLOC_TIMERS=8
# CONFIG_NET - Enable or disable all network features
# CONFIG_NET_IPv6 - Build in support for IPv6
# CONFIG_NSOCKET_DESCRIPTORS - Maximum number of socket descriptors per task/thread.
-# CONFIG_NET_MAX_CONNECTIONS - Maximum number of TCP connections
-# CONFIG_NET_MAX_LISTENPORTS - Maximum number of listening TCP ports
+# CONFIG_NET_MAX_CONNECTIONS - Maximum number of TCP connections (all tasks)
+# CONFIG_NET_MAX_LISTENPORTS - Maximum number of listening TCP ports (all tasks)
+# CONFIG_NET_SOCKOPTS - Enable or disable support for socket options
# CONFIG_NET_BUFFER_SIZE - uIP buffer size
# CONFIG_NET_LOGGING - Logging on or off
# CONFIG_NET_UDP - UDP support on or off
@@ -274,6 +275,7 @@ CONFIG_NET_IPv6=n
CONFIG_NSOCKET_DESCRIPTORS=0
CONFIG_NET_MAX_CONNECTIONS=40
CONFIG_NET_MAX_LISTENPORTS=40
+CONFIG_NET_SOCKOPTS=y
CONFIG_NET_BUFFER_SIZE=420
CONFIG_NET_LOGGING=y
CONFIG_NET_UDP=n
diff --git a/nuttx/configs/m68332evb/defconfig b/nuttx/configs/m68332evb/defconfig
index 15ba43500..0279e73be 100644
--- a/nuttx/configs/m68332evb/defconfig
+++ b/nuttx/configs/m68332evb/defconfig
@@ -243,8 +243,9 @@ CONFIG_PREALLOC_TIMERS=8
# CONFIG_NET - Enable or disable all network features
# CONFIG_NET_IPv6 - Build in support for IPv6
# CONFIG_NSOCKET_DESCRIPTORS - Maximum number of socket descriptors per task/thread.
-# CONFIG_NET_MAX_CONNECTIONS - Maximum number of TCP connections
-# CONFIG_NET_MAX_LISTENPORTS - Maximum number of listening TCP ports
+# CONFIG_NET_MAX_CONNECTIONS - Maximum number of TCP connections (all tasks)
+# CONFIG_NET_MAX_LISTENPORTS - Maximum number of listening TCP ports (all tasks)
+# CONFIG_NET_SOCKOPTS - Enable or disable support for socket options
# CONFIG_NET_BUFFER_SIZE - uIP buffer size
# CONFIG_NET_LOGGING - Logging on or off
# CONFIG_NET_UDP - UDP support on or off
@@ -263,6 +264,7 @@ CONFIG_NET_IPv6=n
CONFIG_NSOCKET_DESCRIPTORS=0
CONFIG_NET_MAX_CONNECTIONS=40
CONFIG_NET_MAX_LISTENPORTS=40
+CONFIG_NET_SOCKOPTS=y
CONFIG_NET_BUFFER_SIZE=420
CONFIG_NET_LOGGING=y
CONFIG_NET_UDP=n
diff --git a/nuttx/configs/mcu123-lpc214x/defconfig b/nuttx/configs/mcu123-lpc214x/defconfig
index f8874256a..e594174f7 100644
--- a/nuttx/configs/mcu123-lpc214x/defconfig
+++ b/nuttx/configs/mcu123-lpc214x/defconfig
@@ -267,8 +267,9 @@ CONFIG_PREALLOC_TIMERS=8
# CONFIG_NET - Enable or disable all network features
# CONFIG_NET_IPv6 - Build in support for IPv6
# CONFIG_NSOCKET_DESCRIPTORS - Maximum number of socket descriptors per task/thread.
-# CONFIG_NET_MAX_CONNECTIONS - Maximum number of TCP connections
-# CONFIG_NET_MAX_LISTENPORTS - Maximum number of listening TCP ports
+# CONFIG_NET_MAX_CONNECTIONS - Maximum number of TCP connections (all tasks)
+# CONFIG_NET_MAX_LISTENPORTS - Maximum number of listening TCP ports (all tasks)
+# CONFIG_NET_SOCKOPTS - Enable or disable support for socket options
# CONFIG_NET_BUFFER_SIZE - uIP buffer size
# CONFIG_NET_LOGGING - Logging on or off
# CONFIG_NET_UDP - UDP support on or off
@@ -287,6 +288,7 @@ CONFIG_NET_IPv6=n
CONFIG_NSOCKET_DESCRIPTORS=0
CONFIG_NET_MAX_CONNECTIONS=40
CONFIG_NET_MAX_LISTENPORTS=40
+CONFIG_NET_SOCKOPTS=y
CONFIG_NET_BUFFER_SIZE=420
CONFIG_NET_LOGGING=y
CONFIG_NET_UDP=n
diff --git a/nuttx/configs/ntosd-dm320/defconfig b/nuttx/configs/ntosd-dm320/defconfig
index 7e1d182f1..36a3b8f46 100644
--- a/nuttx/configs/ntosd-dm320/defconfig
+++ b/nuttx/configs/ntosd-dm320/defconfig
@@ -252,8 +252,9 @@ CONFIG_PREALLOC_TIMERS=8
# CONFIG_NET - Enable or disable all network features
# CONFIG_NET_IPv6 - Build in support for IPv6
# CONFIG_NSOCKET_DESCRIPTORS - Maximum number of socket descriptors per task/thread.
-# CONFIG_NET_MAX_CONNECTIONS - Maximum number of TCP connections
-# CONFIG_NET_MAX_LISTENPORTS - Maximum number of listening TCP ports
+# CONFIG_NET_MAX_CONNECTIONS - Maximum number of TCP connections (all tasks)
+# CONFIG_NET_MAX_LISTENPORTS - Maximum number of listening TCP ports (all tasks)
+# CONFIG_NET_SOCKOPTS - Enable or disable support for socket options
# CONFIG_NET_BUFFER_SIZE - uIP buffer size
# CONFIG_NET_LOGGING - Logging on or off
# CONFIG_NET_UDP - UDP support on or off
@@ -272,6 +273,7 @@ CONFIG_NET_IPv6=n
CONFIG_NSOCKET_DESCRIPTORS=0
CONFIG_NET_MAX_CONNECTIONS=40
CONFIG_NET_MAX_LISTENPORTS=40
+CONFIG_NET_SOCKOPTS=y
CONFIG_NET_BUFFER_SIZE=420
CONFIG_NET_LOGGING=y
CONFIG_NET_UDP=n
diff --git a/nuttx/configs/pjrc-8051/defconfig b/nuttx/configs/pjrc-8051/defconfig
index 1af793bd4..513ce74e0 100644
--- a/nuttx/configs/pjrc-8051/defconfig
+++ b/nuttx/configs/pjrc-8051/defconfig
@@ -240,8 +240,9 @@ CONFIG_PREALLOC_TIMERS=0
# CONFIG_NET - Enable or disable all network features
# CONFIG_NET_IPv6 - Build in support for IPv6
# CONFIG_NSOCKET_DESCRIPTORS - Maximum number of socket descriptors per task/thread.
-# CONFIG_NET_MAX_CONNECTIONS - Maximum number of TCP connections
-# CONFIG_NET_MAX_LISTENPORTS - Maximum number of listening TCP ports
+# CONFIG_NET_MAX_CONNECTIONS - Maximum number of TCP connections (all tasks)
+# CONFIG_NET_MAX_LISTENPORTS - Maximum number of listening TCP ports (all tasks)
+# CONFIG_NET_SOCKOPTS - Enable or disable support for socket options
# CONFIG_NET_BUFFER_SIZE - uIP buffer size
# CONFIG_NET_LOGGING - Logging on or off
# CONFIG_NET_UDP - UDP support on or off
@@ -260,6 +261,7 @@ CONFIG_NET_IPv6=n
CONFIG_NSOCKET_DESCRIPTORS=0
CONFIG_NET_MAX_CONNECTIONS=40
CONFIG_NET_MAX_LISTENPORTS=40
+CONFIG_NET_SOCKOPTS=y
CONFIG_NET_BUFFER_SIZE=420
CONFIG_NET_LOGGING=y
CONFIG_NET_UDP=n
diff --git a/nuttx/configs/sim/defconfig b/nuttx/configs/sim/defconfig
index 3d363786f..fb5f60a1a 100644
--- a/nuttx/configs/sim/defconfig
+++ b/nuttx/configs/sim/defconfig
@@ -214,8 +214,9 @@ CONFIG_FS_FAT=y
# CONFIG_NET - Enable or disable all network features
# CONFIG_NET_IPv6 - Build in support for IPv6
# CONFIG_NSOCKET_DESCRIPTORS - Maximum number of socket descriptors per task/thread.
-# CONFIG_NET_MAX_CONNECTIONS - Maximum number of TCP connections
-# CONFIG_NET_MAX_LISTENPORTS - Maximum number of listening TCP ports
+# CONFIG_NET_MAX_CONNECTIONS - Maximum number of TCP connections (all tasks)
+# CONFIG_NET_MAX_LISTENPORTS - Maximum number of listening TCP ports (all tasks)
+# CONFIG_NET_SOCKOPTS - Enable or disable support for socket options
# CONFIG_NET_BUFFER_SIZE - uIP buffer size
# CONFIG_NET_LOGGING - Logging on or off
# CONFIG_NET_UDP - UDP support on or off
@@ -234,6 +235,7 @@ CONFIG_NET_IPv6=n
CONFIG_NSOCKET_DESCRIPTORS=0
CONFIG_NET_MAX_CONNECTIONS=40
CONFIG_NET_MAX_LISTENPORTS=40
+CONFIG_NET_SOCKOPTS=y
CONFIG_NET_BUFFER_SIZE=420
CONFIG_NET_LOGGING=y
CONFIG_NET_UDP=n
diff --git a/nuttx/include/nuttx/net.h b/nuttx/include/nuttx/net.h
index ce21f4984..39596b76a 100644
--- a/nuttx/include/nuttx/net.h
+++ b/nuttx/include/nuttx/net.h
@@ -45,6 +45,7 @@
#include <semaphore.h>
+#include <nuttx/os_external.h>
#include <net/uip/uip.h>
#include <net/uip/psock.h>
@@ -71,18 +72,30 @@
typedef uint16 sockopt_t;
+/* This defines the storage size of a timeout value. This effects only
+ * range of supported timeout values. With an LSB in seciseconds, the
+ * 16-bit maximum of 65535 corresponds to 1 hr 49 min 13.5 sec at decisecond
+ * resolution.
+ */
+
+typedef uint16 socktimeo_t;
+
/* This is the internal representation of a socket reference by a file
* descriptor.
*/
struct socket
{
- int s_crefs; /* Reference count on the socket */
- uint8 s_type; /* Protocol type: Only SOCK_STREAM or SOCK_DGRAM */
+ int s_crefs; /* Reference count on the socket */
+ uint8 s_type; /* Protocol type: Only SOCK_STREAM or SOCK_DGRAM */
#ifdef CONFIG_NET_SOCKOPTS
- sockopt_t s_options; /* Selected socket options */
+ sockopt_t s_options; /* Selected socket options */
+#ifndef CONFIG_DISABLE_CLOCK
+ socktimeo_t s_rcvtimeo; /* Receive timeout value (in deciseconds) */
+ socktimeo_t s_sndtimeo; /* Send timeout value (in deciseconds) */
+#endif
#endif
- void *s_conn; /* Connection: struct uip_conn * or uip_udp_conn * */
+ void *s_conn; /* Connection: struct uip_conn or uip_udp_conn */
};
/* This defines a list of sockets indexed by the socket descriptor */
diff --git a/nuttx/include/nuttx/os_external.h b/nuttx/include/nuttx/os_external.h
index 6c81b9874..d144fb9c6 100644
--- a/nuttx/include/nuttx/os_external.h
+++ b/nuttx/include/nuttx/os_external.h
@@ -1,4 +1,4 @@
-/************************************************************
+/****************************************************************************
* os_external.h
*
* Copyright (C) 2007 Gregory Nutt. All rights reserved.
@@ -31,31 +31,82 @@
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
- ************************************************************/
+ ****************************************************************************/
#ifndef __OS_EXTERNAL_H
#define __OS_EXTERNAL_H
-/************************************************************
+/****************************************************************************
* Included Files
- ************************************************************/
+ ****************************************************************************/
#include <nuttx/config.h>
#include <pthread.h>
-#include <sched.h>
#include <nuttx/compiler.h>
-/************************************************************
+/****************************************************************************
* Definitions
- ************************************************************/
+ ****************************************************************************/
+
+/* Timing constants */
+
+#define NSEC_PER_SEC 1000000000
+#define USEC_PER_SEC 1000000
+#define MSEC_PER_SEC 1000
+#define DSEC_PER_SEC 10
+#define NSEC_PER_DSEC 100000000
+#define USEC_PER_DSEC 100000
+#define MSEC_PER_DSEC 100
+#define NSEC_PER_MSEC 1000000
+#define USEC_PER_MSEC 1000
+#define NSEC_PER_USEC 1000
+
+/* The interrupt interval of the system timer is given by MSEC_PER_TICK.
+ * This is the expected number of milliseconds between calls from the
+ * processor-specific logic to sched_process_timer(). The default value
+ * of MSEC_PER_TICK is 10 milliseconds (100KHz). However, this default
+ * setting can be overridden by defining the interval in milliseconds as
+ * CONFIG_MSEC_PER_TICK in the board configuration file.
+ *
+ * The following calculations are only accurate when (1) there is no
+ * truncation involved and (2) the underlying system timer is an even
+ * multiple of milliseconds. If (2) is not true, you will probably want
+ * to redefine all of the following.
+ */
+
+#ifdef CONFIG_MSEC_PER_TICK
+# define MSEC_PER_TICK (CONFIG_MSEC_PER_TICK)
+#else
+# define MSEC_PER_TICK (10)
+#endif
+
+#define TICK_PER_SEC (MSEC_PER_SEC / MSEC_PER_TICK) /* Truncates! */
+#define NSEC_PER_TICK (MSEC_PER_TICK * NSEC_PER_MSEC) /* Exact */
+#define USEC_PER_TICK (MSEC_PER_TICK * USEC_PER_MSEC) /* Exact */
+
+#define NSEC2TICK(nsec) (((nsec)+(NSEC_PER_TICK/2))/NSEC_PER_TICK) /* Rounds */
+#define USEC2TICK(usec) (((usec)+(USEC_PER_TICK/2))/USEC_PER_TICK) /* Rounds */
+#define MSEC2TICK(msec) (((msec)+(MSEC_PER_TICK/2))/MSEC_PER_TICK) /* Rounds */
+#define DSEC2TICK(dsec) MSEC2TICK((dsec)*DSEC_PER_MSEC)
+#define SEC2TICK(sec) MSEC2TICK((sec)*SEC_PER_MSEC)
+
+/****************************************************************************
+ * Global Data
+ ****************************************************************************/
+
+/* Access to raw system clock ***********************************************/
+
+#ifndef CONFIG_DISABLE_CLOCK
+extern volatile uint32 g_system_timer;
+#endif
-/************************************************************
+/****************************************************************************
* Global Function Prototypes
- ************************************************************/
+ ****************************************************************************/
-/************************************************************
+/****************************************************************************
* Global Function Prototypes
- ************************************************************/
+ ****************************************************************************/
#ifdef __cplusplus
#define EXTERN extern "C"
@@ -69,16 +120,16 @@ extern "C" {
EXTERN void weak_function user_initialize(void);
EXTERN int user_start(int argc, char *argv[]);
-/* Functions contained in os_task.c *************************/
+/* Functions contained in os_task.c *****************************************/
EXTERN void os_start(void); /* OS entry point called by boot logic */
-/* Functions contained in mm_initialize.c *******************/
+/* Functions contained in mm_initialize.c ***********************************/
EXTERN void mm_initialize(FAR void *heap_start, size_t heap_size);
EXTERN void mm_addregion(FAR void *heapstart, size_t heapsize);
-/* Functions contained in mm_sem.c **************************/
+/* Functions contained in mm_sem.c ******************************************/
EXTERN int mm_trysemaphore(void);
EXTERN void mm_givesemaphore(void);
diff --git a/nuttx/include/sys/socket.h b/nuttx/include/sys/socket.h
index 1de251129..15afd9662 100644
--- a/nuttx/include/sys/socket.h
+++ b/nuttx/include/sys/socket.h
@@ -118,26 +118,27 @@
/* Socket options */
#define SO_DEBUG 0 /* Enables recording of debugging information (get/set).
- * arg: integer contain boolean value */
+ * arg: pointer to integer containing a boolean value */
#define SO_ACCEPTCONN 1 /* Reports whether socket listening is enabled (get only).
- * arg: returns integer contain boolean value */
+ * arg: pointer to integer containing a boolean value */
#define SO_BROADCAST 2 /* Permits sending of broadcast messages (get/set).
- * arg: integer contain boolean value */
+ * arg: pointer to integer containing a boolean value */
#define SO_REUSEADDR 3 /* Allow reuse of local addresses (get/set)
- * arg: integer contain boolean value */
+ * arg: pointer to integer containing a boolean value */
#define SO_KEEPALIVE 4 /* Keeps connections active by enabling the periodic transmission
- * of messages (get/set). arg: int */
+ * of messages (get/set).
+ * arg: pointer to integer containing a boolean value */
#define SO_LINGER 5 /* Lingers on a close() if data is present (get/set)
* arg: struct linger */
#define SO_OOBINLINE 6 /* Leaves received out-of-band data (data marked urgent) inline
- * (get/set) arg: integer contain boolean value */
+ * (get/set) arg: pointer to integer containing a boolean value */
#define SO_SNDBUF 7 /* Sets send buffer size. arg: integer value (get/set). */
#define SO_RCVBUF 8 /* Sets receive buffer size. arg: integer value (get/set). */
-#define SO_ERROR 9 /* Reports and clears error statust (get only). arg: returns
+#define SO_ERROR 9 /* Reports and clears error status (get only). arg: returns
* an integer value
#define SO_TYPE 10 /* Reports the socket type (get only). return: int */
-#define SO_DONTROUTE 11 /* equests that outgoing messages bypass standard routing (get/set)
- * arg: integer contain boolean value */
+#define SO_DONTROUTE 11 /* Requests that outgoing messages bypass standard routing (get/set)
+ * arg: pointer to integer containing a boolean value */
#define SO_RCVLOWAT 12 /* Sets the minimum number of bytes to process for socket input
* (get/set). arg: integer value */
#define SO_RCVTIMEO 13 /* Sets the timeout value that specifies the maximum amount of time
diff --git a/nuttx/net/Makefile b/nuttx/net/Makefile
index 2b514fe5e..6fd922649 100644
--- a/nuttx/net/Makefile
+++ b/nuttx/net/Makefile
@@ -41,7 +41,15 @@ MKDEP = $(TOPDIR)/tools/mkdeps.sh
ifeq ($(CONFIG_NET),y)
STD_ASRCS =
STD_CSRCS = socket.c bind.c connect.c send.c sendto.c recv.c recvfrom.c \
- setsockopt.c getsockopt.c net_sockets.c net-close.c
+ net_sockets.c net-close.c
+
+ifeq ($(CONFIG_NET_SOCKOPTS),y)
+STD_CSRCS += setsockopt.c getsockopt.c
+ifneq ($(CONFIG_DISABLE_CLOCK),y)
+STD_CSRCS += net_timeout.c net_dsec2timeval.c net_timeval2dsec.c
+endif
+endif
+
include uip/Make.defs
endif
diff --git a/nuttx/net/getsockopt.c b/nuttx/net/getsockopt.c
index 369c9201d..cc183b52f 100644
--- a/nuttx/net/getsockopt.c
+++ b/nuttx/net/getsockopt.c
@@ -38,7 +38,7 @@
****************************************************************************/
#include <nuttx/config.h>
-#ifdef CONFIG_NET
+#if defined(CONFIG_NET) && defined(CONFIG_NET_SOCKOPTS)
#include <sys/types.h>
#include <sys/socket.h>
@@ -95,8 +95,141 @@
int getsockopt(int sockfd, int level, int option, void *value, socklen_t *value_len)
{
- *get_errno_ptr() = ENOPROTOOPT;
+ FAR struct socket *psock;
+ int err;
+
+ /* Get the underlying socket structure */
+ /* Verify that the sockfd corresponds to valid, allocated socket */
+
+ psock = sockfd_socket(sockfd);
+ if (!psock || psock->s_crefs <= 0)
+ {
+ err = EBADF;
+ goto errout;
+ }
+
+ /* Verify that the socket option if valid (but might not be supported ) */
+
+ if (!_SO_GETVALID(option) || !value)
+ {
+ err = EINVAL;
+ goto errout;
+ }
+
+ /* Process the option */
+ switch (option)
+ {
+ /* The following options take a point to an integer boolean value.
+ * We will blindly report the bit here although the implementation
+ * is outside of the scope of getsockopt.
+ */
+
+ case SO_DEBUG: /* Enables recording of debugging information */
+ case SO_BROADCAST: /* Permits sending of broadcast messages */
+ case SO_REUSEADDR: /* Allow reuse of local addresses */
+ case SO_KEEPALIVE: /* Keeps connections active by enabling the
+ * periodic transmission */
+ case SO_OOBINLINE: /* Leaves received out-of-band data inline */
+ case SO_DONTROUTE: /* Requests outgoing messages bypass standard routing */
+ {
+ sockopt_t optionset;
+
+ /* Verify that option is the size of an 'int'. Should also check
+ * that 'value' is properly aligned for an 'int'
+ */
+
+ if (value_len != sizeof(int))
+ {
+ err = EINVAL;
+ goto errout;
+ }
+
+ /* Sample the current options. This is atomic operation and so
+ * should not require any special steps for thread safety. We
+ * this outside of the macro because you can never be sure what
+ * a macro will do.
+ */
+
+ optionset = psock->options;
+ *(int*)value = _SO_GETOPT(optionset, option);
+ }
+ break;
+
+ case SO_TYPE: /* Reports the socket type */
+ {
+ /* Verify that option is the size of an 'int'. Should also check
+ * that 'value' is properly aligned for an 'int'
+ */
+
+ if (value_len != sizeof(int))
+ {
+ err = EINVAL;
+ goto errout;
+ }
+
+ /* Return the socket type */
+
+ *(int*)value = psock->s_type;
+ }
+ break;
+
+ /* The following are valid only if the OS CLOCK feature is enabled */
+
+ case SO_RCVTIMEO:
+ case SO_SNDTIMEO:
+#ifndef CONFIG_DISABLE_CLOCK
+ {
+ socktimeo_t timeo;
+
+ /* Verify that option is the size of an 'int'. Should also check
+ * that 'value' is properly aligned for an 'int'
+ */
+
+ if (value_len != sizeof(struct timeval))
+ {
+ err = EINVAL;
+ goto errout;
+ }
+
+ /* Get the timeout value. This is a atomic operation and should
+ * require no special operation.
+ */
+
+ if (option == SO_RCVTIMEO)
+ {
+ timeo = psock->s_rcvtimeo;
+ }
+ else
+ {
+ timeo = psock->s_sndtimeo;
+ }
+
+ /* Then return the timeout value to the caller */
+
+ net_dsec2timeval(timeo, (struct timeval *)value);
+ }
+ break;
+#endif
+
+ /* The following are not yet implemented */
+
+ case SO_ACCEPTCONN: /* Reports whether socket listening is enabled */
+ case SO_LINGER:
+ case SO_SNDBUF: /* Sets send buffer size */
+ case SO_RCVBUF: /* Sets receive buffer size */
+ case SO_ERROR: /* Reports and clears error status. */
+ case SO_RCVLOWAT: /* Sets the minimum number of bytes to input */
+ case SO_SNDLOWAT: /* Sets the minimum number of bytes to output */
+
+ default:
+ err = ENOPROTOOPT;
+ goto errout;
+ }
+ return OK;
+
+errout:
+ *get_errno_ptr() = err;
return ERROR;
}
-#endif /* CONFIG_NET */
+#endif /* CONFIG_NET && CONFIG_NET_SOCKOPTS */
diff --git a/nuttx/net/net-dsec2timeval.c b/nuttx/net/net-dsec2timeval.c
new file mode 100644
index 000000000..7621acd28
--- /dev/null
+++ b/nuttx/net/net-dsec2timeval.c
@@ -0,0 +1,79 @@
+/****************************************************************************
+ * net/net-dsec2timeval.c
+ *
+ * Copyright (C) 2007 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * 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>
+#if defined(CONFIG_NET) && defined(CONFIG_NET_SOCKOPTS) && !defined(CONFIG_DISABLE_CLOCK)
+
+#include <sys/types.h>
+#include <sys/socket.h>
+#include <errno.h>
+
+#include "net_internal.h"
+
+/****************************************************************************
+ * Global Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Function: net_dsec2timeval
+ *
+ * Description:
+ * Convert a decisecond timeout value to a struct timeval. Needed by
+ * getsockopt() to report timeout values.
+ *
+ * Parameters:
+ * dsec The decisecond value to convert
+ * tv The struct timeval to receive the converted value
+ *
+ * Returned Value:
+ * None
+ *
+ * Assumptions:
+ *
+ ****************************************************************************/
+
+void net_dsec2timeval(uint16 dsec, struct timeval *tv)
+{
+ uint16 remainder;
+ tv->tv_sec = dsec / DSEC_PER_SEC;
+ remainder = dsec - tv->tv_sec * DSEC_PER_SEC;
+ tv->tv_usec = remainder * USEC_PER_DSEC;
+}
+
+#endif /* CONFIG_NET && CONFIG_NET_SOCKOPTS && !CONFIG_DISABLE_CLOCK */
diff --git a/nuttx/net/net-timeo.c b/nuttx/net/net-timeo.c
new file mode 100644
index 000000000..144dfef45
--- /dev/null
+++ b/nuttx/net/net-timeo.c
@@ -0,0 +1,80 @@
+/****************************************************************************
+ * net/net-timeo.c
+ *
+ * Copyright (C) 2007 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * 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>
+#if defined(CONFIG_NET) && defined(CONFIG_NET_SOCKOPTS) && !defined(CONFIG_DISABLE_CLOCK)
+
+#include <sys/types.h>
+#include <nuttx/os_external.h>
+#include "net_internal.h"
+
+/****************************************************************************
+ * Global Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Function: net_timeo
+ *
+ * Description:
+ * Check if a timeout has elapsed. This can be called from a socket poll
+ * function to determine if a timeout has occurred.
+ *
+ * Parameters:
+ * start_time Timeout start time in system clock ticks
+ * timeout Timeout value in deciseconds.
+ *
+ * Returned Value:
+ * 0 (FALSE) if not timeout; 1 (TRUE) if timeout
+ *
+ * Assumptions:
+ *
+ ****************************************************************************/
+
+int net_timeo(uint32 start_time, socktimeo_t timeo)
+{
+ uint32 timeo_ticks = DSEC2TICK(timeo);
+ uint32 elapsed = g_system_timer - start_time;
+ if (elapsed >= timeo_ticks)
+ {
+ return TRUE;
+ }
+ return FALSE;
+}
+
+#endif /* CONFIG_NET && CONFIG_NET_SOCKOPTS && !CONFIG_DISABLE_CLOCK */
diff --git a/nuttx/net/net-timeval2dsec.c b/nuttx/net/net-timeval2dsec.c
new file mode 100644
index 000000000..212bdb854
--- /dev/null
+++ b/nuttx/net/net-timeval2dsec.c
@@ -0,0 +1,75 @@
+/****************************************************************************
+ * net/net-timeval2dsec.c
+ *
+ * Copyright (C) 2007 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * 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>
+#if defined(CONFIG_NET) && defined(CONFIG_NET_SOCKOPTS) && !defined(CONFIG_DISABLE_CLOCK)
+
+#include <sys/types.h>
+#include <sys/socket.h>
+#include <errno.h>
+
+#include "net_internal.h"
+
+/****************************************************************************
+ * Global Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Function: net_timeval2dsec
+ *
+ * Description:
+ * Convert a struct timeval to deciseconds. Needed by setsockopt() to
+ * save new timeout values.
+ *
+ * Parameters:
+ * tv The struct timeval to convert
+ *
+ * Returned Value:
+ * the converted value
+ *
+ * Assumptions:
+ *
+ ****************************************************************************/
+
+socktimeo_t net_timeval2dsec(struct timeval *tv)
+{
+ return (uint16)(tv->tv_sec* DSEC_PER_SEC + tv->tv_usec / USEC_PER_DSEC);
+}
+
+#endif /* CONFIG_NET && CONFIG_NET_SOCKOPTS && !CONFIG_DISABLE_CLOCK */
diff --git a/nuttx/net/net_internal.h b/nuttx/net/net_internal.h
index 584c49c76..7da918bb4 100644
--- a/nuttx/net/net_internal.h
+++ b/nuttx/net/net_internal.h
@@ -51,46 +51,47 @@
* Definitions
****************************************************************************/
-/* These define bit positions for each socket option (see sys/socket.h) */
+/* This macro converts a socket option value into a bit setting */
-#define _SO_DEBUG (1 << SO_DEBUG)
-#define _SO_ACCEPTCONN (1 << SO_ACCEPTCONN)
-#define _SO_BROADCAST (1 << SO_BROADCAST)
-#define _SO_REUSEADDR (1 << SO_REUSEADDR)
-#define _SO_KEEPALIVE (1 << SO_KEEPALIVE)
-#define _SO_LINGER (1 << SO_LINGER)
-#define _SO_OOBINLINE (1 << SO_OOBINLINE)
-#define _SO_SNDBUF (1 << SO_SNDBUF)
-#define _SO_RCVBUF (1 << SO_RCVBUF)
-#define _SO_ERROR (1 << SO_ERROR)
-#define _SO_TYPE (1 << SO_TYPE)
-#define _SO_DONTROUTE (1 << SO_DONTROUTE)
-#define _SO_RCVLOWAT (1 << SO_RCVLOWAT)
-#define _SO_RCVTIMEO (1 << SO_RCVTIMEO)
-#define _SO_SNDLOWAT (1 << SO_SNDLOWAT)
-#define _SO_SNDTIMEO (1 << SO_SNDTIMEO)
-
-/* This idenfies the options that have been implemented. Someday this
- * should be 0xffff
- */
+#define _SO_BIT(o) (1 << (o))
-#define _SO_IMPLEMENTED 0x0000
+/* These define bit positions for each socket option (see sys/socket.h) */
-/* The set of all valid options is a subset of those that are implemented
- * and those that can be supported within the kernel OS configuration.
+#define _SO_DEBUG _SO_BIT(SO_DEBUG)
+#define _SO_ACCEPTCONN _SO_BIT(SO_ACCEPTCONN)
+#define _SO_BROADCAST _SO_BIT(SO_BROADCAST)
+#define _SO_REUSEADDR _SO_BIT(SO_REUSEADDR)
+#define _SO_KEEPALIVE _SO_BIT(SO_KEEPALIVE)
+#define _SO_LINGER _SO_BIT(SO_LINGER)
+#define _SO_OOBINLINE _SO_BIT(SO_OOBINLINE)
+#define _SO_SNDBUF _SO_BIT(SO_SNDBUF)
+#define _SO_RCVBUF _SO_BIT(SO_RCVBUF)
+#define _SO_ERROR _SO_BIT(SO_ERROR)
+#define _SO_TYPE _SO_BIT(SO_TYPE)
+#define _SO_DONTROUTE _SO_BIT(SO_DONTROUTE)
+#define _SO_RCVLOWAT _SO_BIT(SO_RCVLOWAT)
+#define _SO_RCVTIMEO _SO_BIT(SO_RCVTIMEO)
+#define _SO_SNDLOWAT _SO_BIT(SO_SNDLOWAT)
+#define _SO_SNDTIMEO _SO_BIT(SO_SNDTIMEO)
+
+/* This is the larget option value */
+
+#define _SO_MAXOPT (15)
+
+/* Macros to set, test, clear options */
+
+#define _SO_SETOPT(s,o) ((s) |= _SO_BIT(o))
+#define _SO_CLROPT(s,o) ((s) &= ~_SO_BIT(o))
+#define _SO_GETOPT(s,o) (((s) & _SO_BIT(o)) != 0)
+
+/* These are macros that can be used to determine if socket option code is
+ * valid (in range) and supported by API.
*/
-#ifdef CONFIG_DISABLE_CLOCK
-# define _SO_ALLOPTIONS (_SO_IMPLEMENTED & ~(_SO_RCVTIMEO|_SO_SNDTIMEO)
-#else
-# define _SO_ALLOPTIONS (_SO_IMPLEMENTED)
-#endif
-
-/* This is the set of options valid for getsockopt and setsockopt */
-
-#define _SO_GETONLY (_SO_ACCEPTCONN|_SO_ERROR|_SO_TYPE)
-#define _SO_SETOPTS (_SO_ALLOPTIONS & ~_SO_GETONLY)
-#define _SO_GETOTPS _SO_ALLOPTIONS
+#define _SO_GETONLYSET (_SO_ACCEPTCONN|_SO_ERROR|_SO_TYPE)
+#define _SO_GETONLY(o) ((_SO_BIT(o) & _SO_GETONLYSET) != 0)
+#define _SO_GETVALID(o) (((unsigned int)(o)) <= _SO_MAXOPT)
+#define _SO_SETVALID(o) ((((unsigned int)(o)) <= _SO_MAXOPT) && !_SO_GETONLY(o))
/****************************************************************************
* Public Types
@@ -119,6 +120,14 @@ EXTERN int sockfd_allocate(void);
EXTERN void sockfd_release(int sockfd);
EXTERN FAR struct socket *sockfd_socket(int sockfd);
+/* sockopt support ***********************************************************/
+
+#if defined(CONFIG_NET_SOCKOPTS) && !defined(CONFIG_DISABLE_CLOCK)
+EXTERN int net_timeo(uint32 start_time, socktimeo_t timeo);
+EXTERN socktimeo_t socktimeo_t net_timeval2dsec(struct timeval *tv);
+EXTERN void net_dsec2timeval(uint16 dsec, struct timeval *tv);
+#endif
+
#undef EXTERN
#if defined(__cplusplus)
}
diff --git a/nuttx/net/setsockopt.c b/nuttx/net/setsockopt.c
index 786b4da19..95f535ce1 100644
--- a/nuttx/net/setsockopt.c
+++ b/nuttx/net/setsockopt.c
@@ -38,7 +38,7 @@
****************************************************************************/
#include <nuttx/config.h>
-#ifdef CONFIG_NET
+#if defined(CONFIG_NET) && defined(CONFIG_NET_SOCKOPTS)
#include <sys/types.h>
#include <sys/socket.h>
@@ -101,8 +101,147 @@
int setsockopt(int sockfd, int level, int option, const void *value, socklen_t value_len)
{
- *get_errno_ptr() = ENOPROTOOPT;
+ FAR struct socket *psock;
+ irqstate_t flags;
+ int err;
+
+ /* Get the underlying socket structure */
+ /* Verify that the sockfd corresponds to valid, allocated socket */
+
+ psock = sockfd_socket(sockfd);
+ if (!psock || psock->s_crefs <= 0)
+ {
+ err = EBADF;
+ goto errout;
+ }
+
+ /* Verify that the socket option if valid (but might not be supported ) */
+
+ if (!_SO_SETVALID(option) || !value)
+ {
+ err = EINVAL;
+ goto errout;
+ }
+
+ /* Process the option */
+ switch (option)
+ {
+ /* The following options take a point to an integer boolean value.
+ * We will blindly set the bit here although the implementation
+ * is outside of the scope of setsockopt.
+ */
+
+ case SO_DEBUG: /* Enables recording of debugging information */
+ case SO_BROADCAST: /* Permits sending of broadcast messages */
+ case SO_REUSEADDR: /* Allow reuse of local addresses */
+ case SO_KEEPALIVE: /* Keeps connections active by enabling the
+ * periodic transmission */
+ case SO_OOBINLINE: /* Leaves received out-of-band data inline */
+ case SO_DONTROUTE: /* Requests outgoing messages bypass standard routing */
+ {
+ int setting;
+
+ /* Verify that option is the size of an 'int'. Should also check
+ * that 'value' is properly aligned for an 'int'
+ */
+
+ if (value_len != sizeof(int))
+ {
+ err = EINVAL;
+ goto errout;
+ }
+
+ /* Get the value. Is the option being set or cleared? */
+
+ setting = *(int*)value;
+
+ /* Disable interrupts so that there is no conflict with interrupt
+ * level access to options.
+ */
+
+ flags = irqsave();
+
+ /* Set or clear the option bit */
+
+ if (setting)
+ {
+ _SO_SETOPT(psock->s_options, option);
+ }
+ else
+ {
+ _SO_CLROPT(psock->s_options, option);
+ }
+ }
+ break;
+
+ /* The following are valid only if the OS CLOCK feature is enabled */
+
+ case SO_RCVTIMEO:
+ case SO_SNDTIMEO:
+#ifndef CONFIG_DISABLE_CLOCK
+ {
+ socktimeo_t timeo;
+
+ /* Verify that option is the size of an 'struct timeval'. */
+
+ if (value_len != sizeof(struct timeval))
+ {
+ err = EINVAL;
+ goto errout;
+ }
+
+ /* Get the timeout value */
+
+ timeo = net_timeval2dsec((struct timeval *)value);
+
+ /* Save the timeout value */
+
+ if (option == SO_RCVTIMEO)
+ {
+ psock->s_rcvtimeo = timeo;
+ }
+ else
+ {
+ psock->s_sndtimeo = timeo;
+ }
+
+ /* Set/clear the corresponding enable/disable bit */
+
+ if (timeo)
+ {
+ _SO_CLROPT(psock->s_options, option);
+ }
+ else
+ {
+ _SO_SETOPT(psock->s_options, option);
+ }
+ }
+ break;
+#endif
+
+ /* The following are not yet implemented */
+
+ case SO_LINGER:
+ case SO_SNDBUF: /* Sets send buffer size */
+ case SO_RCVBUF: /* Sets receive buffer size */
+ case SO_RCVLOWAT: /* Sets the minimum number of bytes to input */
+ case SO_SNDLOWAT: /* Sets the minimum number of bytes to output */
+
+ /* There options are only valid when used with getopt */
+
+ case SO_ACCEPTCONN: /* Reports whether socket listening is enabled */
+ case SO_ERROR: /* Reports and clears error status. */
+ case SO_TYPE: /* Reports the socket type */
+
+ default:
+ err = ENOPROTOOPT;
+ goto errout;
+ }
+ return OK;
+
+errout:
+ *get_errno_ptr() = err;
return ERROR;
}
-#endif /* CONFIG_NET */
+#endif /* CONFIG_NET && CONFIG_NET_SOCKOPTS */
diff --git a/nuttx/sched/clock_internal.h b/nuttx/sched/clock_internal.h
index 2f7a9c783..2b1346880 100644
--- a/nuttx/sched/clock_internal.h
+++ b/nuttx/sched/clock_internal.h
@@ -42,42 +42,13 @@
#include <nuttx/config.h>
#include <sys/types.h>
+#include <nuttx/os_external.h>
#include <nuttx/compiler.h>
/********************************************************************************
* Definitions
********************************************************************************/
-/* Timing constants */
-
-#define NSEC_PER_SEC 1000000000
-#define USEC_PER_SEC 1000000
-#define MSEC_PER_SEC 1000
-#define NSEC_PER_MSEC 1000000
-#define USEC_PER_MSEC 1000
-#define NSEC_PER_USEC 1000
-
-/* The interrupt interval of the system timer is given by MSEC_PER_TICK. This
- * is the expected number of milliseconds between calls from the processor-
- * specific logic to sched_process_timer(). The default value of MSEC_PER_TICK
- * is 10 milliseconds (100KHz). However, this default setting can be overridden
- * by defining the interval in milliseconds as CONFIG_MSEC_PER_TICK in the board
- * configuration file.
- */
-
-#ifdef CONFIG_MSEC_PER_TICK
-# define MSEC_PER_TICK (CONFIG_MSEC_PER_TICK)
-#else
-# define MSEC_PER_TICK (10)
-#endif
-
-#define USEC_PER_TICK (MSEC_PER_TICK * USEC_PER_MSEC)
-#define NSEC_PER_TICK (MSEC_PER_TICK * NSEC_PER_MSEC)
-#define TICK_PER_SEC (MSEC_PER_SEC / MSEC_PER_TICK)
-
-#define MSEC2TICK(msec) (((msec)+(MSEC_PER_TICK/2))/MSEC_PER_TICK)
-#define USEC2TICK(usec) (((usec)+(USEC_PER_TICK/2))/USEC_PER_TICK)
-
#define JD_OF_EPOCH 2440588 /* Julian Date of noon, J1970 */
#ifdef CONFIG_JULIAN_TIME
@@ -97,7 +68,6 @@
* Global Variables
********************************************************************************/
-extern volatile uint32 g_system_timer;
extern struct timespec g_basetime;
extern uint32 g_tickbias;