summaryrefslogtreecommitdiff
path: root/nuttx/net
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2007-11-02 20:20:34 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2007-11-02 20:20:34 +0000
commit8ccf68ba63bb82c099b549548b8f47d40a92acd3 (patch)
tree5951645d8a83a70d730fdf4b8a8866eb3b7e597e /nuttx/net
parent9863a1c37c3bf98152fefced591d4338df5bf501 (diff)
downloadpx4-nuttx-8ccf68ba63bb82c099b549548b8f47d40a92acd3.tar.gz
px4-nuttx-8ccf68ba63bb82c099b549548b8f47d40a92acd3.tar.bz2
px4-nuttx-8ccf68ba63bb82c099b549548b8f47d40a92acd3.zip
Add DM90x0 driver
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@362 42af7a65-404d-4744-a932-0658087f49c3
Diffstat (limited to 'nuttx/net')
-rw-r--r--nuttx/net/Makefile2
-rw-r--r--nuttx/net/connect.c1
-rw-r--r--nuttx/net/net-arptimer.c130
-rw-r--r--nuttx/net/net-internal.h4
-rw-r--r--nuttx/net/net-sockets.c4
-rw-r--r--nuttx/net/netdev-ioctl.c36
6 files changed, 166 insertions, 11 deletions
diff --git a/nuttx/net/Makefile b/nuttx/net/Makefile
index fa0175409..cf6f35081 100644
--- a/nuttx/net/Makefile
+++ b/nuttx/net/Makefile
@@ -46,7 +46,7 @@ SOCK_CSRCS = socket.c bind.c connect.c listen.c accept.c send.c sendto.c \
ifeq ($(CONFIG_NET_SOCKOPTS),y)
SOCK_CSRCS += setsockopt.c getsockopt.c
ifneq ($(CONFIG_DISABLE_CLOCK),y)
-SOCK_CSRCS += net-timeo.c net-dsec2timeval.c net-timeval2dsec.c
+SOCK_CSRCS += net-timeo.c net-dsec2timeval.c net-timeval2dsec.c net-arptimer.c
endif
endif
diff --git a/nuttx/net/connect.c b/nuttx/net/connect.c
index 35c3b9e0d..c520aaac8 100644
--- a/nuttx/net/connect.c
+++ b/nuttx/net/connect.c
@@ -355,7 +355,6 @@ static inline int tcp_connect(FAR struct socket *psock, const struct sockaddr_in
/****************************************************************************
* Public Functions
****************************************************************************/
-
/****************************************************************************
* Function: connect
*
diff --git a/nuttx/net/net-arptimer.c b/nuttx/net/net-arptimer.c
new file mode 100644
index 000000000..69d8aebb0
--- /dev/null
+++ b/nuttx/net/net-arptimer.c
@@ -0,0 +1,130 @@
+/****************************************************************************
+ * net/net-arptimer.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>
+#ifdef CONFIG_NET
+
+#include <time.h>
+#include <wdog.h>
+
+#include <net/uip/uip-arp.h>
+
+#include "net-internal.h"
+
+/****************************************************************************
+ * Definitions
+ ****************************************************************************/
+
+/* ARP timer interval = 10 seconds. CLK_TCK is the number of clock ticks
+ * per second
+ */
+
+#define ARPTIMER_WDINTERVAL (10*CLK_TCK)
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+static WDOG_ID g_arptimer; /* ARP timer */
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Function: arptimer_poll
+ *
+ * Description:
+ * Periodic timer handler. Called from the timer interrupt handler.
+ *
+ * Parameters:
+ * argc - The number of available arguments
+ * arg - The first argument
+ *
+ * Returned Value:
+ * None
+ *
+ * Assumptions:
+ *
+ ****************************************************************************/
+
+static void arptimer_poll(int argc, uint32 arg, ...)
+{
+ dbg("ARP timer expiration\n");
+
+ /* Call the ARP timer function every 10 seconds. */
+
+ uip_arp_timer();
+
+ /* Setup the watchdog timer again */
+
+ (void)wd_start(g_arptimer, ARPTIMER_WDINTERVAL, arptimer_poll, 0);
+}
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Function: arptimer_init
+ *
+ * Description:
+ * Initialized the 10 second timer that is need by uIP to age ARP
+ * associations
+ *
+ * Parameters:
+ * None
+ *
+ * Returned Value:
+ * None
+ *
+ * Assumptions:
+ * Called once at system initialization time
+ *
+ ****************************************************************************/
+
+void arptimer_init(void)
+{
+ /* Create and start the ARP timer */
+
+ g_arptimer = wd_create();
+ (void)wd_start(g_arptimer, ARPTIMER_WDINTERVAL, arptimer_poll, 0);
+}
+
+#endif /* CONFIG_NET */
diff --git a/nuttx/net/net-internal.h b/nuttx/net/net-internal.h
index af587d970..2354e54c1 100644
--- a/nuttx/net/net-internal.h
+++ b/nuttx/net/net-internal.h
@@ -176,6 +176,10 @@ EXTERN FAR struct uip_driver_s *netdev_find(const char *ifname);
EXTERN int netdev_count(void);
#endif
+/* net-arptimer.c ************************************************************/
+
+EXTERN void arptimer_init(void);
+
#undef EXTERN
#if defined(__cplusplus)
}
diff --git a/nuttx/net/net-sockets.c b/nuttx/net/net-sockets.c
index 71641a8fa..34a20a05a 100644
--- a/nuttx/net/net-sockets.c
+++ b/nuttx/net/net-sockets.c
@@ -107,6 +107,10 @@ void net_initialize(void)
#if CONFIG_NSOCKET_DESCRIPTORS > 0
sem_init(&g_netdev_sem, 0, 1);
#endif
+
+ /* Initialize the periodic ARP timer */
+
+ arptimer_init();
}
#if CONFIG_NSOCKET_DESCRIPTORS > 0
diff --git a/nuttx/net/netdev-ioctl.c b/nuttx/net/netdev-ioctl.c
index 1abc84105..5c7b767fd 100644
--- a/nuttx/net/netdev-ioctl.c
+++ b/nuttx/net/netdev-ioctl.c
@@ -67,14 +67,14 @@
****************************************************************************/
/****************************************************************************
- * Name: _get_ipaddr / _set_ipaddr
+ * Name: ioctl_getipaddr / ioctl_setipaddr
*
* Description:
* Copy IP addresses into and out of device structure
*
****************************************************************************/
-static void _get_ipaddr(struct sockaddr *outaddr, uip_ipaddr_t *inaddr)
+static void ioctl_getipaddr(struct sockaddr *outaddr, uip_ipaddr_t *inaddr)
{
#ifdef CONFIG_NET_IPv6
#error " big enough for IPv6 address"
@@ -90,7 +90,7 @@ static void _get_ipaddr(struct sockaddr *outaddr, uip_ipaddr_t *inaddr)
#endif
}
-static void _set_ipaddr(uip_ipaddr_t *outaddr, struct sockaddr *inaddr)
+static void ioctl_setipaddr(uip_ipaddr_t *outaddr, struct sockaddr *inaddr)
{
#ifdef CONFIG_NET_IPv6
struct sockaddr_in6 *src = (struct sockaddr_in6 *)inaddr;
@@ -101,6 +101,22 @@ static void _set_ipaddr(uip_ipaddr_t *outaddr, struct sockaddr *inaddr)
#endif
}
+static void ioctl_ifup(FAR struct uip_driver_s *dev)
+{
+ if (dev->ifup)
+ {
+ dev->ifup(dev);
+ }
+}
+
+static void ioctl_ifdown(FAR struct uip_driver_s *dev)
+{
+ if (dev->ifdown)
+ {
+ dev->ifdown(dev);
+ }
+}
+
/****************************************************************************
* Global Functions
****************************************************************************/
@@ -170,27 +186,29 @@ int netdev_ioctl(int sockfd, int cmd, struct ifreq *req)
switch (cmd)
{
case SIOCGIFADDR: /* Get IP address */
- _get_ipaddr(&req->ifr_addr, &dev->d_ipaddr);
+ ioctl_getipaddr(&req->ifr_addr, &dev->d_ipaddr);
break;
case SIOCSIFADDR: /* Set IP address */
- _set_ipaddr(&dev->d_ipaddr, &req->ifr_addr);
+ ioctl_ifdown(dev);
+ ioctl_setipaddr(&dev->d_ipaddr, &req->ifr_addr);
+ ioctl_ifup(dev);
break;
case SIOCGIFDSTADDR: /* Get P-to-P address */
- _get_ipaddr(&req->ifr_dstaddr, &dev->d_draddr);
+ ioctl_getipaddr(&req->ifr_dstaddr, &dev->d_draddr);
break;
case SIOCSIFDSTADDR: /* Set P-to-P address */
- _set_ipaddr(&dev->d_draddr, &req->ifr_dstaddr);
+ ioctl_setipaddr(&dev->d_draddr, &req->ifr_dstaddr);
break;
case SIOCGIFNETMASK: /* Get network mask */
- _get_ipaddr(&req->ifr_addr, &dev->d_netmask);
+ ioctl_getipaddr(&req->ifr_addr, &dev->d_netmask);
break;
case SIOCSIFNETMASK: /* Set network mask */
- _set_ipaddr(&dev->d_netmask, &req->ifr_addr);
+ ioctl_setipaddr(&dev->d_netmask, &req->ifr_addr);
break;
case SIOCGIFMTU: /* Get MTU size */