summaryrefslogtreecommitdiff
path: root/nuttx/arch/sim/src/up_uipdriver.c
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2007-08-28 00:18:50 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2007-08-28 00:18:50 +0000
commit2c857524a54906a5aaa42bdf803dddd6b3b110de (patch)
tree712c76744f67704338718640504615643ac0b08c /nuttx/arch/sim/src/up_uipdriver.c
parentdf850961888239e142c03f386945f41238364344 (diff)
downloadpx4-nuttx-2c857524a54906a5aaa42bdf803dddd6b3b110de.tar.gz
px4-nuttx-2c857524a54906a5aaa42bdf803dddd6b3b110de.tar.bz2
px4-nuttx-2c857524a54906a5aaa42bdf803dddd6b3b110de.zip
Corrects UIP driver build
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@314 42af7a65-404d-4744-a932-0658087f49c3
Diffstat (limited to 'nuttx/arch/sim/src/up_uipdriver.c')
-rw-r--r--nuttx/arch/sim/src/up_uipdriver.c149
1 files changed, 9 insertions, 140 deletions
diff --git a/nuttx/arch/sim/src/up_uipdriver.c b/nuttx/arch/sim/src/up_uipdriver.c
index e68c4fccd..883207ab4 100644
--- a/nuttx/arch/sim/src/up_uipdriver.c
+++ b/nuttx/arch/sim/src/up_uipdriver.c
@@ -44,35 +44,11 @@
#include <nuttx/config.h>
#include <sys/types.h>
-#include <sys/ioctl.h>
-#include <sys/socket.h>
-#include <sys/time.h>
-#include <sys/uio.h>
-#include <sys/socket.h>
-
-#include <stdlib.h>
-#include <stdio.h>
-#include <unistd.h>
-#include <string.h>
-#include <fcntl.h>
-#include <string.h>
-#include <time.h>
-#include <errno.h>
-#include <debug.h>
#include <net/uip/uip.h>
#include <net/uip/uip-arch.h>
#include <net/uip/uip-arp.h>
-#ifdef linux
-# include <sys/ioctl.h>
-# include <linux/if.h>
-# include <linux/if_tun.h>
-# define DEVTAP "/dev/net/tun"
-#else /* linux */
-# define DEVTAP "/dev/tap0"
-#endif /* linux */
-
#include "up_internal.h"
/****************************************************************************
@@ -81,11 +57,6 @@
#define BUF ((struct uip_eth_hdr *)&uip_buf[0])
-#define UIP_DRIPADDR0 192
-#define UIP_DRIPADDR1 168
-#define UIP_DRIPADDR2 0
-#define UIP_DRIPADDR3 1
-
/****************************************************************************
* Private Types
****************************************************************************/
@@ -104,10 +75,6 @@ struct timer
* Private Data
****************************************************************************/
-#ifdef CONFIG_DEBUG
-static int drop = 0;
-#endif
-static int fd;
static struct timer periodic_timer;
static struct timer arp_timer;
@@ -115,22 +82,15 @@ static struct timer arp_timer;
* Private Functions
****************************************************************************/
-static uint32 gettime( void )
-{
- struct timespec tm;
- (void)clock_gettime(CLOCK_REALTIME, &tm);
- return tm.tv_sec*1000 + tm.tv_nsec/1000000;
-}
-
static void timer_set( struct timer *t, unsigned int interval )
{
t->interval = interval;
- t->start = gettime();
+ t->start = up_getwalltime();
}
static boolean timer_expired( struct timer *t )
{
- return (gettime() - t->start) >= t->interval;
+ return (up_getwalltime() - t->start) >= t->interval;
}
void timer_reset(struct timer *t)
@@ -138,97 +98,6 @@ void timer_reset(struct timer *t)
t->start += t->interval;
}
-static void tapdev_init(void)
-{
- char buf[1024];
-
- fd = open(DEVTAP, O_RDWR);
- if(fd == -1)
- {
- lib_rawprintf("tapdev: tapdev_init: open");
- return;
- }
-
-#ifdef linux
- {
- struct ifreq ifr;
- memset(&ifr, 0, sizeof(ifr));
- ifr.ifr_flags = IFF_TAP|IFF_NO_PI;
- if (ioctl(fd, TUNSETIFF, (void *) &ifr) < 0)
- {
- lib_rawprintf(buf);
- return;
- }
- }
-#endif /* Linux */
-
- snprintf(buf, sizeof(buf), "ifconfig tap0 inet %d.%d.%d.%d",
- UIP_DRIPADDR0, UIP_DRIPADDR1, UIP_DRIPADDR2, UIP_DRIPADDR3);
- system(buf);
-}
-
-static unsigned int tapdev_read(void)
-{
- fd_set fdset;
- struct timeval tv;
- int ret;
-
- tv.tv_sec = 0;
- tv.tv_usec = 1000;
-
- FD_ZERO(&fdset);
- FD_SET(fd, &fdset);
-
- ret = select(fd + 1, &fdset, NULL, NULL, &tv);
- if(ret == 0)
- {
- return 0;
- }
- ret = read(fd, uip_buf, UIP_BUFSIZE);
- if(ret == -1)
- {
- lib_rawprintf("tap_dev: tapdev_read: read");
- }
-
- dbg("tap_dev: tapdev_read: read %d bytes\n", ret);
- {
- int i;
- for(i = 0; i < 20; i++)
- {
- vdbg("%x ", uip_buf[i]);
- }
- vdbg("\n");
- }
-
-#ifdef CONFIG_DEBUG
- check_checksum(uip_buf, ret);
-#endif
- return ret;
-}
-
-static void tapdev_send(void)
-{
- int ret;
-#ifdef CONFIG_DEBUG
- dbg("tapdev_send: sending %d bytes\n", uip_len);
- check_checksum(uip_buf, uip_len);
-
- drop++;
- if(drop % 8 == 7)
- {
- dbg("Dropped a packet!\n");
- return;
- }
-#endif
-
- ret = write(fd, uip_buf, uip_len);
- if(ret == -1)
- {
- perror("tap_dev: tapdev_send: writev");
- exit(1);
- }
-}
-
/****************************************************************************
* Public Functions
****************************************************************************/
@@ -237,7 +106,7 @@ void uipdriver_loop(void)
{
int i;
- uip_len = tapdev_read();
+ uip_len = tapdev_read(uip_buf, UIP_BUFSIZE);
if (uip_len > 0)
{
if (BUF->type == htons(UIP_ETHTYPE_IP))
@@ -253,7 +122,7 @@ void uipdriver_loop(void)
if (uip_len > 0)
{
uip_arp_out();
- tapdev_send();
+ tapdev_send(uip_buf, uip_len);
}
}
else if (BUF->type == htons(UIP_ETHTYPE_ARP))
@@ -267,7 +136,7 @@ void uipdriver_loop(void)
if (uip_len > 0)
{
- tapdev_send();
+ tapdev_send(uip_buf, uip_len);
}
}
}
@@ -286,7 +155,7 @@ void uipdriver_loop(void)
if (uip_len > 0)
{
uip_arp_out();
- tapdev_send();
+ tapdev_send(uip_buf, uip_len);
}
}
@@ -303,7 +172,7 @@ void uipdriver_loop(void)
if (uip_len > 0)
{
uip_arp_out();
- tapdev_send();
+ tapdev_send(uip_buf, uip_len);
}
}
#endif /* UIP_UDP */
@@ -320,8 +189,8 @@ void uipdriver_loop(void)
int uipdriver_init(void)
{
- timer_set(&periodic_timer, CLK_TCK / 2);
- timer_set(&arp_timer, CLK_TCK * 10);
+ timer_set(&periodic_timer, 500);
+ timer_set(&arp_timer, 10000 );
tapdev_init();
uip_init();