From be3873f03972b44e95458345b5ab73b1b75e2eee Mon Sep 17 00:00:00 2001 From: patacongo Date: Wed, 31 Oct 2007 23:27:55 +0000 Subject: in progress update git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@360 42af7a65-404d-4744-a932-0658087f49c3 --- nuttx/arch/sim/src/up_internal.h | 1 + nuttx/arch/sim/src/up_tapdev.c | 110 +++++++++--- nuttx/arch/sim/src/up_uipdriver.c | 1 + nuttx/configs/c5471evm/Make.defs | 5 + nuttx/configs/m68332evb/Make.defs | 5 +- nuttx/configs/mcu123-lpc214x/Make.defs | 4 + nuttx/configs/ntosd-dm320/Make.defs | 4 + nuttx/configs/pjrc-8051/Make.defs | 5 + nuttx/configs/sim/Make.defs | 12 +- nuttx/configs/sim/defconfig | 9 + nuttx/configs/sim/netconfig | 287 ++++++++++++++++++++++++++++++ nuttx/examples/uip/main.c | 31 ++-- nuttx/include/net/uip/dhcpc.h | 8 +- nuttx/include/net/uip/resolv.h | 8 +- nuttx/include/net/uip/uip.h | 76 +------- nuttx/include/netinet/in.h | 22 ++- nuttx/net/connect.c | 291 +++++++++++++++++++++++++++--- nuttx/net/recvfrom.c | 24 ++- nuttx/net/uip/uip-arp.c | 302 ++++++++++++++++++-------------- nuttx/netutils/dhcpc/dhcpc.c | 34 ++-- nuttx/netutils/resolv/resolv.c | 40 +++-- nuttx/netutils/uiplib/uip-gethostaddr.c | 2 +- 22 files changed, 955 insertions(+), 326 deletions(-) create mode 100644 nuttx/configs/sim/netconfig (limited to 'nuttx') diff --git a/nuttx/arch/sim/src/up_internal.h b/nuttx/arch/sim/src/up_internal.h index 42b368d67..fbe5e5e44 100644 --- a/nuttx/arch/sim/src/up_internal.h +++ b/nuttx/arch/sim/src/up_internal.h @@ -112,6 +112,7 @@ extern char *up_deviceimage(void); #ifdef CONFIG_NET extern unsigned long up_getwalltime( void ); extern void tapdev_init(void); +extern int tapdev_getmacaddr(unsigned char *macaddr); extern unsigned int tapdev_read(unsigned char *buf, unsigned int buflen); extern void tapdev_send(unsigned char *buf, unsigned int buflen); #endif diff --git a/nuttx/arch/sim/src/up_tapdev.c b/nuttx/arch/sim/src/up_tapdev.c index 1961cfbae..3626809e3 100644 --- a/nuttx/arch/sim/src/up_tapdev.c +++ b/nuttx/arch/sim/src/up_tapdev.c @@ -1,3 +1,4 @@ + /**************************************************************************** * up_tapdev.c * @@ -59,6 +60,7 @@ #include #include +#include extern int lib_rawprintf(const char *format, ...); @@ -70,16 +72,24 @@ extern int lib_rawprintf(const char *format, ...); #define DEVTAP "/dev/net/tun" -#define UIP_DRIPADDR0 192 -#define UIP_DRIPADDR1 168 -#define UIP_DRIPADDR2 0 -#define UIP_DRIPADDR3 1 +#ifndef CONFIG_EXAMPLE_UIP_DHCPC +# define UIP_IPADDR0 192 +# define UIP_IPADDR1 168 +# define UIP_IPADDR2 0 +# define UIP_IPADDR3 128 +#else +# define UIP_IPADDR0 0 +# define UIP_IPADDR1 0 +# define UIP_IPADDR2 0 +# define UIP_IPADDR3 0 +#endif -#define READ 3 -#define WRITE 4 -#define OPEN 5 -#define IOCTL 54 -#define SELECT 82 +#define READ 3 +#define WRITE 4 +#define OPEN 5 +#define IOCTL 54 +#define SELECT 82 +#define SOCKETCALL 102 /**************************************************************************** * Private Types @@ -131,6 +141,27 @@ static inline int up_open(const char *filename, int flags, int mode) return (int)result; } +static inline int up_socketcall(int call, unsigned long *args) +{ + int result; + + __asm__ volatile ("int $0x80" \ + : "=a" (result) \ + : "0" (SOCKETCALL), "b" (call), "c" ((int)args) \ + : "memory"); + + return (int)result; +} + +static inline int up_socket(int domain, int type, int protocol) +{ + unsigned long args[3]; + args[0] = domain; + args[1] = type; + args[2] = protocol; + return up_socketcall(SYS_SOCKET, args); +} + static inline int up_read(int fd, void* buf, size_t count) { ssize_t result; @@ -209,9 +240,12 @@ unsigned long up_getwalltime( void ) void tapdev_init(void) { + struct ifreq ifr; char buf[1024]; int ret; + /* Open the tap device */ + gtapdevfd = up_open(DEVTAP, O_RDWR, 0644); if (gtapdevfd < 0) { @@ -219,25 +253,55 @@ void tapdev_init(void) return; } -#ifdef linux - { - struct ifreq ifr; - memset(&ifr, 0, sizeof(ifr)); - ifr.ifr_flags = IFF_TAP|IFF_NO_PI; - ret = up_ioctl(gtapdevfd, TUNSETIFF, (unsigned long) &ifr); - if (ret < 0) - { - lib_rawprintf("TAPDEV: ioctl failed: %d\n", -ret ); - return; - } - } -#endif /* Linux */ + /* Configure the tap device */ + + memset(&ifr, 0, sizeof(ifr)); + ifr.ifr_flags = IFF_TAP|IFF_NO_PI; + ret = up_ioctl(gtapdevfd, TUNSETIFF, (unsigned long) &ifr); + if (ret < 0) + { + lib_rawprintf("TAPDEV: ioctl failed: %d\n", -ret ); + return; + } + + /* Assign an IPv4 address to the tap device */ snprintf(buf, sizeof(buf), "ifconfig tap0 inet %d.%d.%d.%d\n", - UIP_DRIPADDR0, UIP_DRIPADDR1, UIP_DRIPADDR2, UIP_DRIPADDR3); + UIP_IPADDR0, UIP_IPADDR1, UIP_IPADDR2, UIP_IPADDR3); system(buf); } +int tapdev_getmacaddr(unsigned char *macaddr) +{ + int ret = -1; + if (macaddr) + { + /* Get a socket (only so that we get access to the INET subsystem) */ + + int sockfd = up_socket(PF_INET, SOCK_DGRAM, 0); + if (sockfd >= 0) + { + struct ifreq req; + memset (&req, 0, sizeof(struct ifreq)); + + /* Put the driver name into the request */ + + strncpy(req.ifr_name, "tap0", IFNAMSIZ); + + /* Perform the ioctl to get the MAC address */ + + ret = up_ioctl(sockfd, SIOCGIFHWADDR, (unsigned long)&req); + if (!ret) + { + /* Return the MAC address */ + + memcpy(macaddr, &req.ifr_hwaddr.sa_data, IFHWADDRLEN); + } + } + } + return ret; +} + unsigned int tapdev_read(unsigned char *buf, unsigned int buflen) { struct sel_arg_struct arg; diff --git a/nuttx/arch/sim/src/up_uipdriver.c b/nuttx/arch/sim/src/up_uipdriver.c index a3f641a36..6f465feca 100644 --- a/nuttx/arch/sim/src/up_uipdriver.c +++ b/nuttx/arch/sim/src/up_uipdriver.c @@ -235,6 +235,7 @@ int uipdriver_init(void) timer_set(&g_periodic_timer, 500); timer_set(&g_arp_timer, 10000 ); tapdev_init(); + (void)tapdev_getmacaddr(g_sim_dev.d_mac.addr); /* Register the device with the OS so that socket IOCTLs can be performed */ diff --git a/nuttx/configs/c5471evm/Make.defs b/nuttx/configs/c5471evm/Make.defs index 8baeb3f36..6a3dc119a 100644 --- a/nuttx/configs/c5471evm/Make.defs +++ b/nuttx/configs/c5471evm/Make.defs @@ -68,4 +68,9 @@ ifeq ("${CONFIG_DEBUG}","y") LDFLAGS += -g endif +HOSTCC = gcc +HOSTINCLUDES = -I. +HOSTCFLAGS = -Wall -wstrict-prototypes -Wshadow -g -pipe +HOSTLDFLAGS = + diff --git a/nuttx/configs/m68332evb/Make.defs b/nuttx/configs/m68332evb/Make.defs index 74f14b967..7d62fad82 100644 --- a/nuttx/configs/m68332evb/Make.defs +++ b/nuttx/configs/m68332evb/Make.defs @@ -68,4 +68,7 @@ ifeq ("${CONFIG_DEBUG}","y") LDFLAGS += -g endif - +HOSTCC = gcc +HOSTINCLUDES = -I. +HOSTCFLAGS = -Wall -wstrict-prototypes -Wshadow -g -pipe +HOSTLDFLAGS = diff --git a/nuttx/configs/mcu123-lpc214x/Make.defs b/nuttx/configs/mcu123-lpc214x/Make.defs index 8baeb3f36..ea6f051ae 100644 --- a/nuttx/configs/mcu123-lpc214x/Make.defs +++ b/nuttx/configs/mcu123-lpc214x/Make.defs @@ -68,4 +68,8 @@ ifeq ("${CONFIG_DEBUG}","y") LDFLAGS += -g endif +HOSTCC = gcc +HOSTINCLUDES = -I. +HOSTCFLAGS = -Wall -wstrict-prototypes -Wshadow -g -pipe +HOSTLDFLAGS = diff --git a/nuttx/configs/ntosd-dm320/Make.defs b/nuttx/configs/ntosd-dm320/Make.defs index 62302a2f4..95df8b31d 100644 --- a/nuttx/configs/ntosd-dm320/Make.defs +++ b/nuttx/configs/ntosd-dm320/Make.defs @@ -68,4 +68,8 @@ ifeq ("${CONFIG_DEBUG}","y") LDFLAGS += -g endif +HOSTCC = gcc +HOSTINCLUDES = -I. +HOSTCFLAGS = -Wall -wstrict-prototypes -Wshadow -g -pipe +HOSTLDFLAGS = diff --git a/nuttx/configs/pjrc-8051/Make.defs b/nuttx/configs/pjrc-8051/Make.defs index 5c4349fc2..e16f5b3ce 100644 --- a/nuttx/configs/pjrc-8051/Make.defs +++ b/nuttx/configs/pjrc-8051/Make.defs @@ -62,4 +62,9 @@ OBJEXT = .rel LIBEXT = .lib EXEEXT = .hex +HOSTCC = gcc +HOSTINCLUDES = -I. +HOSTCFLAGS = -Wall -wstrict-prototypes -Wshadow -g -pipe +HOSTLDFLAGS = + diff --git a/nuttx/configs/sim/Make.defs b/nuttx/configs/sim/Make.defs index 8f01a50f2..de9916e23 100644 --- a/nuttx/configs/sim/Make.defs +++ b/nuttx/configs/sim/Make.defs @@ -35,7 +35,7 @@ include ${TOPDIR}/.config -ifeq ("${CONFIG_DEBUG}","y") +ifneq ("${CONFIG_DEBUG}","y") ARCHOPTIMIZATION = -g else ARCHOPTIMIZATION = -O2 @@ -59,10 +59,6 @@ OBJDUMP = $(CROSSDEV)objdump CFLAGS = $(ARCHWARNINGS) $(ARCHOPTIMIZATION) \ $(ARCHCPUFLAGS) $(ARCHINCLUDES) $(ARCHDEFINES) -pipe -HOSTINCLUDES = -I. -HOSTCFLAGS = $(ARCHWARNINGS) $(ARCHOPTIMIZATION) \ - $(ARCHCPUFLAGS) $(HOSTINCLUDES) $(ARCHDEFINES) -pipe - OBJEXT = .o LIBEXT = .a EXEEXT = @@ -71,4 +67,8 @@ ifeq ("${CONFIG_DEBUG}","y") LDFLAGS += -g endif - +HOSTCC = gcc +HOSTINCLUDES = -I. +HOSTCFLAGS = $(ARCHWARNINGS) $(ARCHOPTIMIZATION) \ + $(ARCHCPUFLAGS) $(HOSTINCLUDES) $(ARCHDEFINES) -pipe +HOSTLDFLAGS = diff --git a/nuttx/configs/sim/defconfig b/nuttx/configs/sim/defconfig index fc62aa9e5..c1c78b670 100644 --- a/nuttx/configs/sim/defconfig +++ b/nuttx/configs/sim/defconfig @@ -255,6 +255,15 @@ CONFIG_NET_BROADCAST=n CONFIG_NET_DHCP_LIGHT=n CONFIG_NET_RESOLV_ENTRIES=4 +# +# Settings for examples/uip +#CONFIG_EXAMPLE_UIP_SMTP= +#CONFIG_EXAMPLE_UIP_TELNETD= +#CONFIG_EXAMPLE_UIP_WEBSERVER= +CONFIG_EXAMPLE_UIP_DHCPC=y +#CONFIG_EXAMPLE_UIP_RESOLV= +#CONFIG_EXAMPLE_UIP_WEBCLIENT= + # # Stack and heap information # diff --git a/nuttx/configs/sim/netconfig b/nuttx/configs/sim/netconfig new file mode 100644 index 000000000..22bdd8526 --- /dev/null +++ b/nuttx/configs/sim/netconfig @@ -0,0 +1,287 @@ +############################################################ +# defconfig +# +# Copyright (C) 2007 Gregory Nutt. All rights reserved. +# Author: Gregory Nutt +# +# 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 Gregory Nutt 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. +# +############################################################ +# +# architecture selection +# +# CONFIG_ARCH - identifies the arch subdirectory and, hence, the +# processor architecture. +# CONFIG_ARCH_name - for use in C code. This identifies the +# particular chip or SoC that the architecture is implemented +# in. +# CONFIG_ARCH_BOARD - identifies the configs subdirectory and, hence, +# the board that supports the particular chip or SoC. +# CONFIG_ARCH_BOARD_name - for use in C code +# CONFIG_ENDIAN_BIG - define if big endian (default is little endian) +# +CONFIG_ARCH=sim +CONFIG_ARCH_SIM=y +CONFIG_ARCH_BOARD=sim +CONFIG_ARCH_BOARD_SIM=y + +# +# General OS setup +# +# CONFIG_EXAMPLE - identifies the subdirectory in examples +# that will be used in the build +# CONFIG_DEBUG - enables built-in debug options +# CONFIG_DEBUG_VERBOSE - enables verbose debug output +# CONFIG_MM_REGIONS - If the architecture includes multiple +# regions of memory to allocate from, this specifies the +# number of memory regions that the memory manager must +# handle and enables the API mm_addregion(start, end); +# CONFIG_HAVE_LOWPUTC - architecture supports low-level, boot +# time console output +# CONFIG_TICKS_PER_MSEC - The default system timer is 100Hz +# or TICKS_PER_MSEC=10. This setting may be defined to +# inform NuttX that the processor hardware is providing +# system timer interrupts at some interrupt interval other +# than 10 msec. +# CONFIG_RR_INTERVAL - The round robin timeslice will be set +# this number of milliseconds; Round robin scheduling can +# be disabled by setting this value to zero. +# CONFIG_SCHED_INSTRUMENTATION - enables instrumentation in +# scheduler to monitor system performance +# CONFIG_TASK_NAME_SIZE - Spcifies that maximum size of a +# task name to save in the TCB. Useful if scheduler +# instrumentation is selected. Set to zero to disable. +# CONFIG_JULIAN_TIME - Enables Julian time conversions +# CONFIG_START_YEAR, CONFIG_START_MONTH, CONFIG_START_DAY - +# Used to initialize the internal time logic. +# CONFIG_DEV_CONSOLE - Set if architecture-specific logic +# provides /dev/console. Enables stdout, stderr, stdin. +# +#CONFIG_EXAMPLE=uip +CONFIG_EXAMPLE=nettest +CONFIG_DEBUG=n +CONFIG_DEBUG_VERBOSE=n +CONFIG_MM_REGIONS=1 +CONFIG_ARCH_LOWPUTC=y +CONFIG_RR_INTERVAL=0 +CONFIG_SCHED_INSTRUMENTATION=n +CONFIG_TASK_NAME_SIZE=32 +CONFIG_START_YEAR=2007 +CONFIG_START_MONTH=2 +CONFIG_START_DAY=27 +CONFIG_JULIAN_TIME=n +CONFIG_DEV_CONSOLE=y + +# +# The following can be used to disable categories of +# APIs supported by the OS. If the compiler supports +# weak functions, then it should not be necessary to +# disable functions unless you want to restrict usage +# of those APIs. +# +# There are certain dependency relationships in these +# features. +# +# o mq_notify logic depends on signals to awaken tasks +# waiting for queues to become full or empty. +# o pthread_condtimedwait() depends on signals to wake +# up waiting tasks. +# +CONFIG_DISABLE_CLOCK=n +CONFIG_DISABLE_POSIX_TIMERS=n +CONFIG_DISABLE_PTHREAD=n +CONFIG_DISABLE_SIGNALS=n +CONFIG_DISABLE_MQUEUE=n +CONFIG_DISABLE_MOUNTPOINT=n +CONFIG_DISABLE_ENVIRON=n + +# +# Misc libc settings +# +# CONFIG_NOPRINTF_FIELDWIDTH - sprintf-related logic is a +# little smaller if we do not support fieldwidthes +# +CONFIG_NOPRINTF_FIELDWIDTH=n + +# +# Allow for architecture optimized implementations +# +# The architecture can provide optimized versions of the +# following to improve sysem performance +# +CONFIG_ARCH_MEMCPY=n +CONFIG_ARCH_MEMCMP=n +CONFIG_ARCH_MEMMOVE=n +CONFIG_ARCH_MEMSET=n +CONFIG_ARCH_STRCMP=n +CONFIG_ARCH_STRCPY=n +CONFIG_ARCH_STRNCPY=n +CONFIG_ARCH_STRLEN=n +CONFIG_ARCH_BZERO=n +CONFIG_ARCH_KMALLOC=n +CONFIG_ARCH_KZMALLOC=n +CONFIG_ARCH_KFREE=n + +# +# General build options +# +# CONFIG_RRLOAD_BINARY - make the rrload binary format used with +# BSPs from www.ridgerun.com +# +CONFIG_RRLOAD_BINARY=n + +# +# Sizes of configurable things (0 disables) +# +# CONFIG_MAX_TASKS - The maximum number of simultaneously +# active tasks. This value must be a power of two. +# CONFIG_MAX_TASK_ARGS - This controls the maximum number of +# of parameters that a task may receive (i.e., maxmum value +# of 'argc') +# CONFIG_NPTHREAD_KEYS - The number of items of thread- +# specific data that can be retained +# CONFIG_NFILE_DESCRIPTORS - The maximum number of file +# descriptors (one for each open) +# CONFIG_NFILE_STREAMS - The maximum number of streams that +# can be fopen'ed +# CONFIG_NAME_MAX - The maximum size of a file name. +# CONFIG_STDIO_BUFFER_SIZE - Size of the buffer to allocate +# on fopen. (Only if CONFIG_NFILE_STREAMS > 0) +# CONFIG_NUNGET_CHARS - Number of characters that can be +# buffered by ungetc() (Only if CONFIG_NFILE_STREAMS > 0) +# CONFIG_PREALLOC_MQ_MSGS - The number of pre-allocated message +# structures. The system manages a pool of preallocated +# message structures to minimize dynamic allocations +# CONFIG_MQ_MAXMSGSIZE - Message structures are allocated with +# a fixed payload size given by this settin (does not include +# other message structure overhead. +# CONFIG_MAX_WDOGPARMS - Maximum number of parameters that +# can be passed to a watchdog handler +# CONFIG_PREALLOC_WDOGS - The number of pre-allocated watchdog +# structures. The system manages a pool of preallocated +# watchdog structures to minimize dynamic allocations +# CONFIG_PREALLOC_TIMERS - The number of pre-allocated POSIX +# timer structures. The system manages a pool of preallocated +# timer structures to minimize dynamic allocations. Set to +# zero for all dynamic allocations. +# +CONFIG_MAX_TASKS=64 +CONFIG_MAX_TASK_ARGS=4 +CONFIG_NPTHREAD_KEYS=4 +CONFIG_NFILE_DESCRIPTORS=32 +CONFIG_NFILE_STREAMS=16 +CONFIG_NAME_MAX=32 +CONFIG_STDIO_BUFFER_SIZE=1024 +CONFIG_NUNGET_CHARS=2 +CONFIG_PREALLOC_MQ_MSGS=32 +CONFIG_MQ_MAXMSGSIZE=32 +CONFIG_MAX_WDOGPARMS=4 +CONFIG_PREALLOC_WDOGS=32 +CONFIG_PREALLOC_TIMERS=8 + +# +# FAT filesystem configuration +# CONFIG_FS_FAT - Enable FAT filesystem support +# CONFIG_FAT_SECTORSIZE - Max supported sector size +CONFIG_FS_FAT=y + +# +# TCP/IP and UDP support via uIP +# 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 (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 +# CONFIG_NET_UDP_CHECKSUMS - UDP checksums on or off +# CONFIG_NET_UDP_CONNS - The maximum amount of concurrent UDP connections +# CONFIG_NET_STATISTICS - uIP statistics on or off +# CONFIG_NET_PINGADDRCONF - Use "ping" packet for setting IP address +# CONFIG_NET_RECEIVE_WINDOW - The size of the advertised receiver's window +# CONFIG_NET_ARPTAB_SIZE - The size of the ARP table +# CONFIG_NET_BROADCAST - Broadcast support +# CONFIG_NET_LLH_LEN - The link level header length +# CONFIG_NET_FWCACHE_SIZE - number of packets to remember when looking for duplicates +CONFIG_NET=y +CONFIG_NET_IPv6=n +CONFIG_NSOCKET_DESCRIPTORS=8 +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=y +CONFIG_NET_UDP_CHECKSUMS=y +#CONFIG_NET_UDP_CONNS=10 +CONFIG_NET_STATISTICS=y +#CONFIG_NET_PINGADDRCONF=0 +#CONFIG_NET_RECEIVE_WINDOW= +#CONFIG_NET_ARPTAB_SIZE=8 +CONFIG_NET_BROADCAST=n +#CONFIG_NET_LLH_LEN=14 +#CONFIG_NET_FWCACHE_SIZE=2 + +# +# UIP Network Utilities +# CONFIG_NET_DHCP_LIGHT - Reduces size of DHCP +# CONFIG_NET_RESOLV_ENTRIES - Number of resolver entries +CONFIG_NET_DHCP_LIGHT=n +CONFIG_NET_RESOLV_ENTRIES=4 + +# +# Settings for examples/uip +#CONFIG_EXAMPLE_UIP_SMTP= +#CONFIG_EXAMPLE_UIP_TELNETD= +#CONFIG_EXAMPLE_UIP_WEBSERVER= +CONFIG_EXAMPLE_UIP_DHCPC=y +#CONFIG_EXAMPLE_UIP_RESOLV= +#CONFIG_EXAMPLE_UIP_WEBCLIENT= + +# Stack and heap information +# +# CONFIG_BOOT_FROM_FLASH - Some configurations support XIP +# operation from FLASH. +# CONFIG_CUSTOM_STACK - The up_ implementation will handle +# all stack operations outside of the nuttx model. +# CONFIG_STACK_POINTER - The initial stack pointer +# CONFIG_PROC_STACK_SIZE - The size of the initial stack +# CONFIG_PTHREAD_STACK_MIN - Minimum pthread stack size +# CONFIG_PTHREAD_STACK_DEFAULT - Default pthread stack size +# CONFIG_HEAP_BASE - The beginning of the heap +# CONFIG_HEAP_SIZE - The size of the heap +# +CONFIG_BOOT_FROM_FLASH=n +CONFIG_CUSTOM_STACK=n +CONFIG_PROC_STACK_SIZE=0x00001000 +CONFIG_PTHREAD_STACK_MIN=256 +CONFIG_PTHREAD_STACK_DEFAULT=8192 +CONFIG_HEAP_BASE= +CONFIG_HEAP_SIZE= diff --git a/nuttx/examples/uip/main.c b/nuttx/examples/uip/main.c index f71a9a6dc..5d1406b6b 100644 --- a/nuttx/examples/uip/main.c +++ b/nuttx/examples/uip/main.c @@ -43,6 +43,7 @@ * Included Files ****************************************************************************/ +#include #include #include #include @@ -57,8 +58,6 @@ * our project as defined in the config//defconfig file */ -#define CONFIG_EXAMPLE_UIP_DHCPC 1 /* For now */ - #if defined(CONFIG_EXAMPLE_UIP_SMTP) # include #elif defined(CONFIG_EXAMPLE_UIP_TELNETD) @@ -66,10 +65,12 @@ #elif defined(CONFIG_EXAMPLE_UIP_WEBSERVER) # include #elif defined(CONFIG_EXAMPLE_UIP_DHCPC) +# include # include #elif defined(CONFIG_EXAMPLE_UIP_RESOLV) # include #elif defined(CONFIG_EXAMPLE_UIP_WEBCLIENT) +# include # include #else # error "No network application specified" @@ -110,17 +111,19 @@ void user_initialize(void) int user_start(int argc, char *argv[]) { +#if !defined(CONFIG_EXAMPLE_UIP_DHCPC) struct in_addr addr; -#if defined(CONFIG_EXAMPLE_UIP_DHCPC) || defined(CONFIG_ARCH_SIM) +#endif +#if defined(CONFIG_EXAMPLE_UIP_DHCPC) || !defined(CONFIG_ARCH_SIM) uint8 mac[IFHWADDRLEN]; #endif #if defined(CONFIG_EXAMPLE_UIP_DHCPC) || defined(CONFIG_EXAMPLE_UIP_SMTP) void *handle; #endif -#if defined(CONFIG_ARCH_SIM) - /* Give the simulated dirver a MAC address */ +/* Most embedded network interfaces must have a software assigned MAC */ +#if !defined(CONFIG_ARCH_SIM) mac[0] = 0x00; mac[1] = 0xe0; mac[2] = 0xb0; @@ -128,11 +131,6 @@ int user_start(int argc, char *argv[]) mac[4] = 0xba; mac[5] = 0xbe; uip_setmacaddr("eth0", mac); - -#elif defined(CONFIG_EXAMPLE_UIP_DHCPC) - /* Get the MAC address of the NIC */ - - uip_getmacaddr("eth0", mac); #endif #if !defined(CONFIG_EXAMPLE_UIP_DHCPC) @@ -158,8 +156,17 @@ int user_start(int argc, char *argv[]) #elif defined(CONFIG_EXAMPLE_UIP_TELNETD) telnetd_init(); #elif defined(CONFIG_EXAMPLE_UIP_DHCPC) + /* Get the MAC address of the NIC */ + + uip_getmacaddr("eth0", mac); + + /* Set up the resolver and DHCPC modules */ + resolv_init(); handle = dhcpc_open(&mac, IFHWADDRLEN); + + /* Get an IP address */ + if (handle) { struct dhcpc_state ds; @@ -167,7 +174,7 @@ int user_start(int argc, char *argv[]) uip_sethostaddr("eth0", &ds.ipaddr); uip_setnetmask("eth0", &ds.netmask); uip_setdraddr("eth0", &ds.default_router); - resolv_conf(ds.dnsaddr); + resolv_conf(&ds.dnsaddr); dhcpc_close(handle); } #elif defined(CONFIG_EXAMPLE_UIP_SMTP) @@ -184,7 +191,7 @@ int user_start(int argc, char *argv[]) webclient_init(); resolv_init(); uip_ipaddr(addr.s_addr, 195, 54, 122, 204); - resolv_conf(addr.s_addr); + resolv_conf(&addr); resolv_query("www.sics.se"); #endif diff --git a/nuttx/include/net/uip/dhcpc.h b/nuttx/include/net/uip/dhcpc.h index 13b717e43..12f3f0a9b 100644 --- a/nuttx/include/net/uip/dhcpc.h +++ b/nuttx/include/net/uip/dhcpc.h @@ -56,10 +56,10 @@ struct dhcpc_state { uint16 lease_time[2]; uint8 serverid[4]; - uint16 ipaddr[2]; - uint16 netmask[2]; - uint16 dnsaddr[2]; - uint16 default_router[2]; + struct in_addr ipaddr; + struct in_addr netmask; + struct in_addr dnsaddr; + struct in_addr default_router; }; /**************************************************************************** diff --git a/nuttx/include/net/uip/resolv.h b/nuttx/include/net/uip/resolv.h index c9547f13e..9d9f57f55 100644 --- a/nuttx/include/net/uip/resolv.h +++ b/nuttx/include/net/uip/resolv.h @@ -49,12 +49,12 @@ extern "C" { EXTERN int resolv_init(void); #ifdef CONFIG_NET_IPv6 -EXTERN void resolv_conf(const struct sockaddr_in6 *dnsserver); -EXTERN void resolv_getserver(const struct sockaddr_in6 *dnsserver); +EXTERN void resolv_conf(const struct in6_addr *dnsserver); +EXTERN void resolv_getserver(const struct in_addr *dnsserver); EXTERN int resolv_query(const char *name, struct sockaddr_in6 *addr); #else -EXTERN void resolv_conf(const struct sockaddr_in *dnsserver); -EXTERN void resolv_getserver(struct sockaddr_in *dnsserver); +EXTERN void resolv_conf(const struct in_addr *dnsserver); +EXTERN void resolv_getserver(struct in_addr *dnsserver); EXTERN int resolv_query(const char *name, struct sockaddr_in *addr); #endif diff --git a/nuttx/include/net/uip/uip.h b/nuttx/include/net/uip/uip.h index 3b2c90299..9f6a662d4 100644 --- a/nuttx/include/net/uip/uip.h +++ b/nuttx/include/net/uip/uip.h @@ -836,9 +836,9 @@ extern void uip_udpdisable(struct uip_udp_conn *conn); /* Convert an IPv4 address of the form uint16[2] to an in_addr_t */ #ifdef CONFIG_ENDIAN_BIG -# define uip_ip4addr_conv(addr) (((in_addr_t)((uint16*)addr)[1] << 16) | (in_addr_t)((uint16*)addr)[0]) -#else # define uip_ip4addr_conv(addr) (((in_addr_t)((uint16*)addr)[0] << 16) | (in_addr_t)((uint16*)addr)[1]) +#else +# define uip_ip4addr_conv(addr) (((in_addr_t)((uint16*)addr)[1] << 16) | (in_addr_t)((uint16*)addr)[0]) #endif /* Construct an IPv6 address from eight 16-bit words. @@ -922,7 +922,7 @@ extern void uip_udpdisable(struct uip_udp_conn *conn); * uip_ipaddr(&mask, 255,255,255,0); * uip_ipaddr(&ipaddr1, 192,16,1,2); * uip_ipaddr(&ipaddr2, 192,16,1,3); - * if(uip_ipaddr_maskcmp(&ipaddr1, &ipaddr2, &mask)) { + * if(uip_ipaddr_maskcmp(ipaddr1, ipaddr2, &mask)) { * printf("They are the same"); * } * @@ -933,7 +933,7 @@ extern void uip_udpdisable(struct uip_udp_conn *conn); #ifndef CONFIG_NET_IPv6 # define uip_ipaddr_maskcmp(addr1, addr2, mask) \ - ((uip_ip4addr_conv(addr1) & (in_addr_t)mask) == ((in_addr_t)addr2 & (in_addr_t)mask)) + (((in_addr_t)(addr1) & (in_addr_t)(mask)) == ((in_addr_t)(addr2) & (in_addr_t)(mask))) #else /* !CONFIG_NET_IPv6 */ #endif /* !CONFIG_NET_IPv6 */ @@ -963,74 +963,6 @@ extern void uip_udpdisable(struct uip_udp_conn *conn); (in_addr_t)(dest) = (in_addr_t)(src) & (in_addr_t)(mask); \ } while(0) -/* Pick the first octet of an IP address. - * - * Picks out the first octet of an IP address. - * - * Example: - * - * uip_ipaddr_t ipaddr; - * uint8 octet; - * - * uip_ipaddr(&ipaddr, 1,2,3,4); - * octet = uip_ipaddr1(&ipaddr); - * - * In the example above, the variable "octet" will contain the value 1. - */ - -#define uip_ipaddr1(addr) (htons(((uint16 *)(addr))[0]) >> 8) - -/* Pick the second octet of an IP address. - * - * Picks out the second octet of an IP address. - * - * Example: - * - * uip_ipaddr_t ipaddr; - * uint8 octet; - * - * uip_ipaddr(&ipaddr, 1,2,3,4); - * octet = uip_ipaddr2(&ipaddr); - * - * In the example above, the variable "octet" will contain the value 2. - */ - -#define uip_ipaddr2(addr) (htons(((uint16 *)(addr))[0]) & 0xff) - -/* Pick the third octet of an IP address. - * - * Picks out the third octet of an IP address. - * - * Example: - * - * uip_ipaddr_t ipaddr; - * uint8 octet; - * - * uip_ipaddr(&ipaddr, 1,2,3,4); - * octet = uip_ipaddr3(&ipaddr); - * - * In the example above, the variable "octet" will contain the value 3. - */ - -#define uip_ipaddr3(addr) (htons(((uint16 *)(addr))[1]) >> 8) - -/* Pick the fourth octet of an IP address. - * - * Picks out the fourth octet of an IP address. - * - * Example: - * - * uip_ipaddr_t ipaddr; - * uint8 octet; - * - * uip_ipaddr(&ipaddr, 1,2,3,4); - * octet = uip_ipaddr4(&ipaddr); - * - * In the example above, the variable "octet" will contain the value 4. - */ - -#define uip_ipaddr4(addr) (htons(((uint16 *)(addr))[1]) & 0xff) - /* Print out a uIP log message. * * This function must be implemented by the module that uses uIP, and diff --git a/nuttx/include/netinet/in.h b/nuttx/include/netinet/in.h index dd518388a..163e16ab1 100644 --- a/nuttx/include/netinet/in.h +++ b/nuttx/include/netinet/in.h @@ -48,22 +48,26 @@ /* Values for protocol argument to socket() */ -#define IPPROTO_TCP 1 -#define IPPROTO_UDP 2 +#define IPPROTO_TCP 1 +#define IPPROTO_UDP 2 /* Special values of in_addr_t */ -#define INADDR_ANY ((in_addr_t)0x00000000) /* Address to accept any incoming messages */ -#define INADDR_BROADCAST ((in_addr_t)0xffffffff) /* Address to send to all hosts */ -#define INADDR_NONE ((in_addr_t)0xffffffff) /* Address indicating an error return */ +#define INADDR_ANY ((in_addr_t)0x00000000) /* Address to accept any incoming messages */ +#define INADDR_BROADCAST ((in_addr_t)0xffffffff) /* Address to send to all hosts */ +#define INADDR_NONE ((in_addr_t)0xffffffff) /* Address indicating an error return */ +#define INADDR_LOOPBACK ((in_addr_t)0x7f000001) /* Inet 127.0.0.1. */ -#define IN6ADDR_ANY_INIT {{{0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0}}} +/* Special initializer for in6_addr_t */ + +#define IN6ADDR_ANY_INIT {{{0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0}}} +#define IN6ADDR_LOOPBACK_INIT {{{0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,1}}} /* struct in6_addr union selectors */ -#define s6_addr in6_u.u6_addr8 -#define s6_addr16 in6_u.u6_addr16 -#define s6_addr32 in6_u.u6_addr32 +#define s6_addr in6_u.u6_addr8 +#define s6_addr16 in6_u.u6_addr16 +#define s6_addr32 in6_u.u6_addr32 /**************************************************************************** * Public Type Definitions diff --git a/nuttx/net/connect.c b/nuttx/net/connect.c index 579972d99..35c3b9e0d 100644 --- a/nuttx/net/connect.c +++ b/nuttx/net/connect.c @@ -43,9 +43,36 @@ #include #include #include +#include #include "net-internal.h" +/**************************************************************************** + * Private Types + ****************************************************************************/ + +struct tcp_connect_s +{ + FAR struct uip_conn *tc_conn; /* Reference to TCP connection structure */ + sem_t tc_sem; /* Semaphore signals recv completion */ + int tc_result; /* OK on success, otherwise a negated errno. */ +}; + +/**************************************************************************** + * Private Function Prototypes + ****************************************************************************/ + +static void connection_event(void *private); +static inline void tcp_setup_callbacks(struct uip_conn *conn, FAR struct socket *psock, + FAR struct tcp_connect_s *pstate); +static inline void tcp_teardown_callbacks(struct uip_conn *conn, int status); +static void tcp_connect_interrupt(struct uip_driver_s *dev, void *private); +#ifdef CONFIG_NET_IPv6 +static inline int tcp_connect(FAR struct socket *psock, const struct sockaddr_in6 *inaddr); +#else +static inline int tcp_connect(FAR struct socket *psock, const struct sockaddr_in *inaddr); +#endif + /**************************************************************************** * Private Functions ****************************************************************************/ @@ -78,7 +105,7 @@ static void connection_event(void *private) */ if ((uip_flags & (UIP_CLOSE|UIP_ABORT|UIP_TIMEDOUT)) != 0) { - /* Indicate that the socet is no longer connected */ + /* Indicate that the socket is no longer connected */ psock->s_flags &= ~_SF_CONNECTED; } @@ -87,13 +114,244 @@ static void connection_event(void *private) else if ((uip_flags & UIP_CONNECTED) != 0) { - /* Indicate that the socet is no longer connected */ + /* Indicate that the socket is now connected */ psock->s_flags |= _SF_CONNECTED; } } } +/**************************************************************************** + * Function: tcp_setup_callbacks + ****************************************************************************/ + +static inline void tcp_setup_callbacks(struct uip_conn *conn, FAR struct socket *psock, + FAR struct tcp_connect_s *pstate) +{ + /* Set up the callbacks in the connection */ + + conn->data_private = (void*)pstate; + conn->data_event = tcp_connect_interrupt; + + /* Set up to receive callbacks on connection-related events */ + + conn->connection_private = (void*)psock; + conn->connection_event = connection_event; +} + +/**************************************************************************** + * Function: tcp_teardown_callbacks + ****************************************************************************/ + +static inline void tcp_teardown_callbacks(struct uip_conn *conn, int status) +{ + /* Make sure that no further interrupts are processed */ + + conn->data_private = NULL; + conn->data_event = NULL; + + /* If we successfully connected, we will continue to monitor the connection state + * via callbacks. + */ + + if (status < 0) + { + /* Failed to connect */ + + conn->connection_private = NULL; + conn->connection_event = NULL; + } +} + +/**************************************************************************** + * Function: tcp_connect_interrupt + * + * Description: + * This function is called from the interrupt level to perform the actual + * connection operation via by the uIP layer. + * + * Parameters: + * dev The sructure of the network driver that caused the interrupt + * private An instance of struct recvfrom_s cast to void* + * + * Returned Value: + * None + * + * Assumptions: + * Running at the interrupt level + * + ****************************************************************************/ + +static void tcp_connect_interrupt(struct uip_driver_s *dev, void *private) +{ + struct tcp_connect_s *pstate = (struct tcp_connect_s *)private; + + /* 'private' might be null in some race conditions (?) */ + + if (pstate) + { + /* The following errors should be detected here (someday) + * + * ECONNREFUSED + * No one listening on the remote address. + * ENETUNREACH + * Network is unreachable. + * ETIMEDOUT + * Timeout while attempting connection. The server may be too busy + * to accept new connections. + */ + + /* UIP_CLOSE: The remote host has closed the connection + * UIP_ABORT: The remote host has aborted the connection + */ + + if ((uip_flags & (UIP_CLOSE|UIP_ABORT)) != 0) + { + /* Indicate that remote host refused the connection */ + + pstate->tc_result = -ECONNREFUSED; + } + + /* UIP_TIMEDOUT: Connection aborted due to too many retransmissions. */ + + else if ((uip_flags & UIP_TIMEDOUT) != 0) + { + /* Indicate that the remote host is unreachable (or should this be timedout?) */ + + pstate->tc_result = -ECONNREFUSED; + } + + /* UIP_CONNECTED: The socket is successfully connected */ + + else if ((uip_flags & UIP_CONNECTED) != 0) + { + /* Indicate that the socket is no longer connected */ + + pstate->tc_result = OK; + } + + /* Otherwise, it is not an event of importance to us at the moment */ + + else + { + return; + } + + /* Stop further callbacks */ + + tcp_teardown_callbacks(pstate->tc_conn, pstate->tc_result); + + /* Wake up the waiting thread */ + + sem_post(&pstate->tc_sem); + } +} + +/**************************************************************************** + * Function: tcp_connect + * + * Description: + * Perform a TCP connection + * + * Parameters: + * psock A reference to the socket structure of the socket to be connected + * inaddr The address of the remote server to connect to + * + * Returned Value: + * None + * + * Assumptions: + * Running at the interrupt level + * + ****************************************************************************/ + +#ifdef CONFIG_NET_IPv6 +static inline int tcp_connect(FAR struct socket *psock, const struct sockaddr_in6 *inaddr) +#else +static inline int tcp_connect(FAR struct socket *psock, const struct sockaddr_in *inaddr) +#endif +{ + FAR struct uip_conn *conn; + struct tcp_connect_s state; + irqstate_t flags; + int ret = OK; + + /* Interrupts must be disabled through all of the following because + * we cannot allow the network callback to occur until we are completely + * setup. + */ + + flags = irqsave(); + + /* Get the connection reference from the socket */ + + conn = psock->s_conn; + if (!conn) /* Should always be non-NULL */ + { + ret = -EINVAL; + } + else + { + /* Perform the uIP connection operation */ + + ret = uip_tcpconnect(conn, inaddr); + } + + if (ret >= 0) + { + /* Initialize the TCP state structure */ + + (void)sem_init(&state.tc_sem, 0, 0); /* Doesn't really fail */ + state.tc_conn = conn; + state.tc_result = -EAGAIN; + + /* Set up the callbacks in the connection */ + + tcp_setup_callbacks(conn, psock, &state); + + /* Wait for either the connect to complete or for an error/timeout to occur. + * NOTES: (1) sem_wait will also terminate if a signal is received, (2) + * interrupts are disabled! They will be re-enabled while the task sleeps + * and automatically re-enabled when the task restarts. + */ + + ret = sem_wait(&state.tc_sem); + + /* Uninitialize the state structure */ + + (void)sem_destroy(&state.tc_sem); + + /* If sem_wait failed, recover the negated error (probably -EINTR) */ + + if (ret < 0) + { + int err = *get_errno_ptr(); + if (err >= 0) + { + err = ENOSYS; + } + ret = -err; + } + else + { + /* If the wait succeeded, then get the new error value from the state structure */ + + ret = state.tc_result; + } + + /* Make sure that no further interrupts are processed */ + tcp_teardown_callbacks(conn, ret); + + /* Mark the connection bound and connected */ + if (ret >= 0) + { + psock->s_flags |= (_SF_BOUND|_SF_CONNECTED); + } + } + irqrestore(flags); + return ret; +} + /**************************************************************************** * Public Functions ****************************************************************************/ @@ -204,38 +462,21 @@ int connect(int sockfd, const struct sockaddr *addr, socklen_t addrlen) { case SOCK_STREAM: { - struct uip_conn *conn; - /* Verify that the socket is not already connected */ if (_SS_ISCONNECTED(psock->s_flags)) { - err = -EISCONN; + err = EISCONN; goto errout; } - /* Get the connection reference from the socket */ + /* Its not ... connect it */ - conn = psock->s_conn; - if (conn) /* Should always be non-NULL */ + ret = tcp_connect(psock, inaddr); + if (ret < 0) { - /* Perform the uIP connection operation */ - - ret = uip_tcpconnect(psock->s_conn, inaddr); - if (ret < 0) - { - err = -ret; - goto errout; - } - - /* Mark the connection bound and connected */ - - psock->s_flags |= (_SF_BOUND|_SF_CONNECTED); - - /* Set up to receive callbacks on connection-related events */ - - conn->connection_private = (void*)psock; - conn->connection_event = connection_event; + err = -ret; + goto errout; } } break; diff --git a/nuttx/net/recvfrom.c b/nuttx/net/recvfrom.c index c13ada6e6..25dc1c4fb 100644 --- a/nuttx/net/recvfrom.c +++ b/nuttx/net/recvfrom.c @@ -64,13 +64,11 @@ struct recvfrom_s { #if defined(CONFIG_NET_SOCKOPTS) && !defined(CONFIG_DISABLE_CLOCK) FAR struct socket *rf_sock; /* The parent socket structure */ + uint32 rf_starttime; /* rcv start time for determining timeout */ #endif sem_t rf_sem; /* Semaphore signals recv completion */ size_t rf_buflen; /* Length of receive buffer */ char *rf_buffer; /* Pointer to receive buffer */ -#ifndef CONFIG_DISABLE_CLOCK - uint32 rf_starttime; /* rcv start time for determining timeout */ -#endif size_t rf_recvlen; /* The received length */ int rf_result; /* OK on success, otherwise a negated errno. */ }; @@ -101,16 +99,20 @@ struct recvfrom_s static void recvfrom_interrupt(struct uip_driver_s *dev, void *private) { struct recvfrom_s *pstate = (struct recvfrom_s *)private; +#if defined(CONFIG_NET_SOCKOPTS) && !defined(CONFIG_DISABLE_CLOCK) FAR struct socket *psock; +#endif size_t recvlen; /* 'private' might be null in some race conditions (?) */ if (pstate) { +#if defined(CONFIG_NET_SOCKOPTS) && !defined(CONFIG_DISABLE_CLOCK) /* Get the socket reference from the private data */ psock = pstate->rf_sock; +#endif /* If new data is available, then complete the read action. */ @@ -184,7 +186,7 @@ static void recvfrom_interrupt(struct uip_driver_s *dev, void *private) * the TCP receive. */ -#ifndef CONFIG_DISABLE_CLOCK +#if defined(CONFIG_NET_SOCKOPTS) && !defined(CONFIG_DISABLE_CLOCK) pstate->rf_starttime = g_system_timer; #endif } @@ -223,7 +225,7 @@ static void recvfrom_interrupt(struct uip_driver_s *dev, void *private) * poll -- check for a timeout. */ -#ifndef CONFIG_DISABLE_CLOCK +#if defined(CONFIG_NET_SOCKOPTS) && !defined(CONFIG_DISABLE_CLOCK) else { socktimeo_t timeo; @@ -240,16 +242,12 @@ static void recvfrom_interrupt(struct uip_driver_s *dev, void *private) } /* No.. check for a timeout configured via setsockopts(SO_RCVTIMEO). - * If non... we well let the read hang forever. + * If none... we well let the read hang forever. */ else { -#ifdef CONFIG_NET_SOCKOPTS timeo = psock->s_rcvtimeo; -#else - timeo = 0; -#endif } /* Is there an effective timeout? */ @@ -337,13 +335,13 @@ static void recvfrom_init(FAR struct socket *psock, FAR void *buf, size_t len, memset(pstate, 0, sizeof(struct recvfrom_s)); (void)sem_init(&pstate->rf_sem, 0, 0); /* Doesn't really fail */ - pstate->rf_sock = psock; pstate->rf_buflen = len; pstate->rf_buffer = buf; -#ifndef CONFIG_DISABLE_CLOCK +#if defined(CONFIG_NET_SOCKOPTS) && !defined(CONFIG_DISABLE_CLOCK) /* Set up the start time for the timeout */ + pstate->rf_sock = psock; pstate->rf_starttime = g_system_timer; #endif } @@ -542,7 +540,7 @@ static ssize_t tcp_recvfrom(FAR struct socket *psock, FAR void *buf, size_t len, * and automatically re-enabled when the task restarts. */ - ret = sem_wait(&state. rf_sem); + ret = sem_wait(&state.rf_sem); /* Make sure that no further interrupts are processed */ diff --git a/nuttx/net/uip/uip-arp.c b/nuttx/net/uip/uip-arp.c index 87e48a609..7b242156c 100644 --- a/nuttx/net/uip/uip-arp.c +++ b/nuttx/net/uip/uip-arp.c @@ -1,22 +1,20 @@ -/* uip-arp.c +/**************************************************************************** + * net/uip/uip-arp.c * Implementation of the ARP Address Resolution Protocol. - * Author: Adam Dunkels * - * The Address Resolution Protocol ARP is used for mapping between IP - * addresses and link level addresses such as the Ethernet MAC - * addresses. ARP uses broadcast queries to ask for the link level - * address of a known IP address and the host which is configured with - * the IP address for which the query was meant, will respond with its - * link level address. + * Copyright (C) 2007 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt * - * Note: This ARP implementation only supports Ethernet. + * Based on uIP which also has a BSD style license: * - * Copyright (c) 2001-2003, Adam Dunkels. - * All rights reserved. + * Author: Adam Dunkels + * Copyright (c) 2001-2003, Adam Dunkels. + * All rights reserved. * * 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 @@ -37,8 +35,23 @@ * 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. + * + ****************************************************************************/ + +/* The Address Resolution Protocol ARP is used for mapping between IP + * addresses and link level addresses such as the Ethernet MAC + * addresses. ARP uses broadcast queries to ask for the link level + * address of a known IP address and the host which is configured with + * the IP address for which the query was meant, will respond with its + * link level address. + * + * Note: This ARP implementation only supports Ethernet. */ +/**************************************************************************** + * Included Files + ****************************************************************************/ + #include #include #include @@ -46,99 +59,82 @@ #include #include +/**************************************************************************** + * Definitions + ****************************************************************************/ + +#define ARP_REQUEST 1 +#define ARP_REPLY 2 + +#define ARP_HWTYPE_ETH 1 + +#define BUF ((struct arp_hdr *)&dev->d_buf[0]) +#define IPBUF ((struct ethip_hdr *)&dev->d_buf[0]) + +/**************************************************************************** + * Private Types + ****************************************************************************/ + struct arp_hdr { - struct uip_eth_hdr ethhdr; - uint16 hwtype; - uint16 protocol; - uint8 hwlen; - uint8 protolen; - uint16 opcode; - struct uip_eth_addr shwaddr; - in_addr_t sipaddr; - struct uip_eth_addr dhwaddr; - in_addr_t dipaddr; + struct uip_eth_hdr ah_ethhdr; + uint16 ah_hwtype; + uint16 ah_protocol; + uint8 ah_hwlen; + uint8 ah_protolen; + uint16 ah_opcode; + struct uip_eth_addr ah_shwaddr; + uint16 ah_sipaddr[2]; + struct uip_eth_addr ah_dhwaddr; + uint16 ah_dipaddr[2]; }; struct ethip_hdr { - struct uip_eth_hdr ethhdr; + struct uip_eth_hdr eh_ethhdr; /* IP header. */ - uint8 vhl; - uint8 tos; - uint8 len[2]; - uint8 ipid[2]; - uint8 ipoffset[2]; - uint8 ttl; - uint8 proto; - uint16 ipchksum; - uint16 srcipaddr[2]; - uint16 destipaddr[2]; + uint8 eh_vhl; + uint8 eh_tos; + uint8 eh_len[2]; + uint8 eh_ipid[2]; + uint8 eh_ipoffset[2]; + uint8 eh_ttl; + uint8 eh_proto; + uint16 eh_ipchksum; + uint16 eh_srcipaddr[2]; + uint16 eh_destipaddr[2]; }; -#define ARP_REQUEST 1 -#define ARP_REPLY 2 - -#define ARP_HWTYPE_ETH 1 - struct arp_entry { - in_addr_t ipaddr; - struct uip_eth_addr ethaddr; - uint8 time; + in_addr_t at_ipaddr; + struct uip_eth_addr at_ethaddr; + uint8 at_time; }; +/**************************************************************************** + * Private Data + ****************************************************************************/ + static const struct uip_eth_addr broadcast_ethaddr = - {{0xff,0xff,0xff,0xff,0xff,0xff}}; -static const uint16 broadcast_ipaddr[2] = {0xffff,0xffff}; + {{0xff, 0xff, 0xff, 0xff, 0xff, 0xff}}; +static const uint16 broadcast_ipaddr[2] = {0xffff, 0xffff}; static struct arp_entry arp_table[UIP_ARPTAB_SIZE]; -static in_addr_t ipaddr; -static uint8 i, c; - -static uint8 arptime; -static uint8 tmpage; - -#define BUF ((struct arp_hdr *)&dev->d_buf[0]) -#define IPBUF ((struct ethip_hdr *)&dev->d_buf[0]) - -/* Initialize the ARP module. */ - -void uip_arp_init(void) -{ - for (i = 0; i < UIP_ARPTAB_SIZE; ++i) - { - memset(&arp_table[i].ipaddr, 0, sizeof(in_addr_t)); - } -} +static uint8 g_arptime; -/* Periodic ARP processing function. - * - * This function performs periodic timer processing in the ARP module - * and should be called at regular intervals. The recommended interval - * is 10 seconds between the calls. - */ -void uip_arp_timer(void) -{ - struct arp_entry *tabptr; - - ++arptime; - for (i = 0; i < UIP_ARPTAB_SIZE; ++i) - { - tabptr = &arp_table[i]; - if (tabptr->ipaddr != 0 && arptime - tabptr->time >= UIP_ARP_MAXAGE) - { - tabptr->ipaddr = 0; - } - } -} +/**************************************************************************** + * Private Functions + ****************************************************************************/ -static void uip_arp_update(in_addr_t pipaddr, struct uip_eth_addr *ethaddr) +static void uip_arp_update(uint16 *pipaddr, struct uip_eth_addr *ethaddr) { struct arp_entry *tabptr; + in_addr_t ipaddr = uip_ip4addr_conv(pipaddr); + int i; /* Walk through the ARP mapping table and try to find an entry to * update. If none is found, the IP -> MAC address mapping is @@ -151,17 +147,17 @@ static void uip_arp_update(in_addr_t pipaddr, struct uip_eth_addr *ethaddr) /* Only check those entries that are actually in use. */ - if (tabptr->ipaddr != 0) + if (tabptr->at_ipaddr != 0) { /* Check if the source IP address of the incoming packet matches * the IP address in this ARP table entry. */ - if (uip_ipaddr_cmp(pipaddr, tabptr->ipaddr)) + if (uip_ipaddr_cmp(ipaddr, tabptr->at_ipaddr)) { /* An old entry found, update this and return. */ - memcpy(tabptr->ethaddr.addr, ethaddr->addr, IFHWADDRLEN); - tabptr->time = arptime; + memcpy(tabptr->at_ethaddr.addr, ethaddr->addr, IFHWADDRLEN); + tabptr->at_time = g_arptime; return; } @@ -176,7 +172,7 @@ static void uip_arp_update(in_addr_t pipaddr, struct uip_eth_addr *ethaddr) for (i = 0; i < UIP_ARPTAB_SIZE; ++i) { tabptr = &arp_table[i]; - if (tabptr->ipaddr == 0) + if (tabptr->at_ipaddr == 0) { break; } @@ -188,18 +184,18 @@ static void uip_arp_update(in_addr_t pipaddr, struct uip_eth_addr *ethaddr) if (i == UIP_ARPTAB_SIZE) { - tmpage = 0; - c = 0; + uint8 tmpage = 0; + int j = 0; for (i = 0; i < UIP_ARPTAB_SIZE; ++i) { tabptr = &arp_table[i]; - if (arptime - tabptr->time > tmpage) + if (g_arptime - tabptr->at_time > tmpage) { - tmpage = arptime - tabptr->time; - c = i; + tmpage = g_arptime - tabptr->at_time; + j = i; } } - i = c; + i = j; tabptr = &arp_table[i]; } @@ -207,9 +203,47 @@ static void uip_arp_update(in_addr_t pipaddr, struct uip_eth_addr *ethaddr) * information. */ - tabptr->ipaddr = pipaddr; - memcpy(tabptr->ethaddr.addr, ethaddr->addr, IFHWADDRLEN); - tabptr->time = arptime; + tabptr->at_ipaddr = ipaddr; + memcpy(tabptr->at_ethaddr.addr, ethaddr->addr, IFHWADDRLEN); + tabptr->at_time = g_arptime; +} + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/* Initialize the ARP module. */ + +void uip_arp_init(void) +{ + int i; + for (i = 0; i < UIP_ARPTAB_SIZE; ++i) + { + memset(&arp_table[i].at_ipaddr, 0, sizeof(in_addr_t)); + } +} + +/* Periodic ARP processing function. + * + * This function performs periodic timer processing in the ARP module + * and should be called at regular intervals. The recommended interval + * is 10 seconds between the calls. + */ + +void uip_arp_timer(void) +{ + struct arp_entry *tabptr; + int i; + + ++g_arptime; + for (i = 0; i < UIP_ARPTAB_SIZE; ++i) + { + tabptr = &arp_table[i]; + if (tabptr->at_ipaddr != 0 && g_arptime - tabptr->at_time >= UIP_ARP_MAXAGE) + { + tabptr->at_ipaddr = 0; + } + } } /* ARP processing for incoming IP packets @@ -231,12 +265,12 @@ void uip_arp_ipin(void) /* Only insert/update an entry if the source IP address of the incoming IP packet comes from a host on the local network. */ - if ((IPBUF->srcipaddr & dev->d_netmask) != (dev->d_ipaddr & dev->d_netmask)) + if ((IPBUF->eh_srcipaddr & dev->d_netmask) != (dev->d_ipaddr & dev->d_netmask)) { return; } - uip_arp_update(IPBUF->srcipaddr, &(IPBUF->ethhdr.src)); + uip_arp_update(IPBUF->eh_srcipaddr, &(IPBUF->eh_ethhdr.src)); } #endif /* 0 */ @@ -263,6 +297,7 @@ void uip_arp_ipin(void) void uip_arp_arpin(struct uip_driver_s *dev) { + in_addr_t ipaddr; if (dev->d_len < sizeof(struct arp_hdr)) { dev->d_len = 0; @@ -270,33 +305,36 @@ void uip_arp_arpin(struct uip_driver_s *dev) } dev->d_len = 0; - switch(BUF->opcode) + ipaddr = uip_ip4addr_conv(BUF->ah_dipaddr); + switch(BUF->ah_opcode) { case HTONS(ARP_REQUEST): /* ARP request. If it asked for our address, we send out a reply. */ - if (uip_ipaddr_cmp(BUF->dipaddr, dev->d_ipaddr)) + if (uip_ipaddr_cmp(ipaddr, dev->d_ipaddr)) { /* First, we register the one who made the request in our ARP * table, since it is likely that we will do more communication * with this host in the future. */ - uip_arp_update(BUF->sipaddr, &BUF->shwaddr); + uip_arp_update(BUF->ah_sipaddr, &BUF->ah_shwaddr); /* The reply opcode is 2. */ - BUF->opcode = HTONS(2); + BUF->ah_opcode = HTONS(2); - memcpy(BUF->dhwaddr.addr, BUF->shwaddr.addr, IFHWADDRLEN); - memcpy(BUF->shwaddr.addr, dev->d_mac.addr, IFHWADDRLEN); - memcpy(BUF->ethhdr.src.addr, dev->d_mac.addr, IFHWADDRLEN); - memcpy(BUF->ethhdr.dest.addr, BUF->dhwaddr.addr, IFHWADDRLEN); + memcpy(BUF->ah_dhwaddr.addr, BUF->ah_shwaddr.addr, IFHWADDRLEN); + memcpy(BUF->ah_shwaddr.addr, dev->d_mac.addr, IFHWADDRLEN); + memcpy(BUF->ah_ethhdr.src.addr, dev->d_mac.addr, IFHWADDRLEN); + memcpy(BUF->ah_ethhdr.dest.addr, BUF->ah_dhwaddr.addr, IFHWADDRLEN); - BUF->dipaddr = BUF->sipaddr; - BUF->sipaddr = dev->d_ipaddr; + BUF->ah_dipaddr[0] = BUF->ah_sipaddr[0]; + BUF->ah_dipaddr[1] = BUF->ah_sipaddr[1]; + BUF->ah_sipaddr[0] = dev->d_ipaddr >> 16; + BUF->ah_sipaddr[1] = dev->d_ipaddr & 0xffff; - BUF->ethhdr.type = HTONS(UIP_ETHTYPE_ARP); + BUF->ah_ethhdr.type = HTONS(UIP_ETHTYPE_ARP); dev->d_len = sizeof(struct arp_hdr); } break; @@ -306,9 +344,9 @@ void uip_arp_arpin(struct uip_driver_s *dev) * for us. */ - if (uip_ipaddr_cmp(BUF->dipaddr, dev->d_ipaddr)) + if (uip_ipaddr_cmp(ipaddr, dev->d_ipaddr)) { - uip_arp_update(BUF->sipaddr, &BUF->shwaddr); + uip_arp_update(BUF->ah_sipaddr, &BUF->ah_shwaddr); } break; } @@ -342,6 +380,9 @@ void uip_arp_arpin(struct uip_driver_s *dev) void uip_arp_out(struct uip_driver_s *dev) { struct arp_entry *tabptr; + in_addr_t ipaddr; + in_addr_t destipaddr; + int i; /* Find the destination IP address in the ARP table and construct the Ethernet header. If the destination IP addres isn't on the @@ -352,15 +393,16 @@ void uip_arp_out(struct uip_driver_s *dev) /* First check if destination is a local broadcast. */ - if (uiphdr_ipaddr_cmp(IPBUF->destipaddr, broadcast_ipaddr)) + if (uiphdr_ipaddr_cmp(IPBUF->eh_destipaddr, broadcast_ipaddr)) { - memcpy(IPBUF->ethhdr.dest.addr, broadcast_ethaddr.addr, IFHWADDRLEN); + memcpy(IPBUF->eh_ethhdr.dest.addr, broadcast_ethaddr.addr, IFHWADDRLEN); } else { /* Check if the destination address is on the local network. */ - if (!uip_ipaddr_maskcmp(IPBUF->destipaddr, dev->d_ipaddr, dev->d_netmask)) + destipaddr = uip_ip4addr_conv(IPBUF->eh_destipaddr); + if (!uip_ipaddr_maskcmp(destipaddr, dev->d_ipaddr, dev->d_netmask)) { /* Destination address was not on the local network, so we need to * use the default router's IP address instead of the destination @@ -373,13 +415,13 @@ void uip_arp_out(struct uip_driver_s *dev) { /* Else, we use the destination IP address. */ - uip_ipaddr_copy(ipaddr, IPBUF->destipaddr); + uip_ipaddr_copy(ipaddr, destipaddr); } for (i = 0; i < UIP_ARPTAB_SIZE; ++i) { tabptr = &arp_table[i]; - if (uip_ipaddr_cmp(ipaddr, tabptr->ipaddr)) + if (uip_ipaddr_cmp(ipaddr, tabptr->at_ipaddr)) { break; } @@ -391,19 +433,19 @@ void uip_arp_out(struct uip_driver_s *dev) * overwrite the IP packet with an ARP request. */ - memset(BUF->ethhdr.dest.addr, 0xff, IFHWADDRLEN); - memset(BUF->dhwaddr.addr, 0x00, IFHWADDRLEN); - memcpy(BUF->ethhdr.src.addr, dev->d_mac.addr, IFHWADDRLEN); - memcpy(BUF->shwaddr.addr, dev->d_mac.addr, IFHWADDRLEN); + memset(BUF->ah_ethhdr.dest.addr, 0xff, IFHWADDRLEN); + memset(BUF->ah_dhwaddr.addr, 0x00, IFHWADDRLEN); + memcpy(BUF->ah_ethhdr.src.addr, dev->d_mac.addr, IFHWADDRLEN); + memcpy(BUF->ah_shwaddr.addr, dev->d_mac.addr, IFHWADDRLEN); - uip_ipaddr_copy(BUF->dipaddr, ipaddr); - uip_ipaddr_copy(BUF->sipaddr, dev->d_ipaddr); - BUF->opcode = HTONS(ARP_REQUEST); /* ARP request. */ - BUF->hwtype = HTONS(ARP_HWTYPE_ETH); - BUF->protocol = HTONS(UIP_ETHTYPE_IP); - BUF->hwlen = IFHWADDRLEN; - BUF->protolen = 4; - BUF->ethhdr.type = HTONS(UIP_ETHTYPE_ARP); + uiphdr_ipaddr_copy(BUF->ah_dipaddr, &ipaddr); + uiphdr_ipaddr_copy(BUF->ah_sipaddr, &dev->d_ipaddr); + BUF->ah_opcode = HTONS(ARP_REQUEST); /* ARP request. */ + BUF->ah_hwtype = HTONS(ARP_HWTYPE_ETH); + BUF->ah_protocol = HTONS(UIP_ETHTYPE_IP); + BUF->ah_hwlen = IFHWADDRLEN; + BUF->ah_protolen = 4; + BUF->ah_ethhdr.type = HTONS(UIP_ETHTYPE_ARP); dev->d_appdata = &dev->d_buf[UIP_TCPIP_HLEN + UIP_LLH_LEN]; @@ -413,11 +455,11 @@ void uip_arp_out(struct uip_driver_s *dev) /* Build an ethernet header. */ - memcpy(IPBUF->ethhdr.dest.addr, tabptr->ethaddr.addr, IFHWADDRLEN); + memcpy(IPBUF->eh_ethhdr.dest.addr, tabptr->at_ethaddr.addr, IFHWADDRLEN); } - memcpy(IPBUF->ethhdr.src.addr, dev->d_mac.addr, IFHWADDRLEN); + memcpy(IPBUF->eh_ethhdr.src.addr, dev->d_mac.addr, IFHWADDRLEN); - IPBUF->ethhdr.type = HTONS(UIP_ETHTYPE_IP); + IPBUF->eh_ethhdr.type = HTONS(UIP_ETHTYPE_IP); dev->d_len += sizeof(struct uip_eth_hdr); } diff --git a/nuttx/netutils/dhcpc/dhcpc.c b/nuttx/netutils/dhcpc/dhcpc.c index cff741794..a84728013 100644 --- a/nuttx/netutils/dhcpc/dhcpc.c +++ b/nuttx/netutils/dhcpc/dhcpc.c @@ -161,7 +161,7 @@ static uint8 *add_req_ipaddr(struct dhcpc_state *presult, uint8 *optptr) { *optptr++ = DHCP_OPTION_REQ_IPADDR; *optptr++ = 4; - memcpy(optptr, presult->ipaddr, 4); + memcpy(optptr, &presult->ipaddr.s_addr, 4); return optptr + 4; } @@ -262,13 +262,13 @@ static uint8 parse_options(struct dhcpc_state *presult, uint8 *optptr, int len) switch(*optptr) { case DHCP_OPTION_SUBNET_MASK: - memcpy(presult->netmask, optptr + 2, 4); + memcpy(&presult->netmask.s_addr, optptr + 2, 4); break; case DHCP_OPTION_ROUTER: - memcpy(presult->default_router, optptr + 2, 4); + memcpy(&presult->default_router.s_addr, optptr + 2, 4); break; case DHCP_OPTION_DNS_SERVER: - memcpy(presult->dnsaddr, optptr + 2, 4); + memcpy(&presult->dnsaddr.s_addr, optptr + 2, 4); break; case DHCP_OPTION_MSG_TYPE: type = *(optptr + 2); @@ -296,7 +296,7 @@ static uint8 parse_msg(struct dhcpc_state_internal *pdhcpc, int buflen, struct d memcmp(pbuffer->xid, xid, sizeof(xid)) == 0 && memcmp(pbuffer->chaddr, pdhcpc->mac_addr, pdhcpc->mac_len) == 0) { - memcpy(presult->ipaddr, pbuffer->yiaddr, 4); + memcpy(&presult->ipaddr.s_addr, pbuffer->yiaddr, 4); return parse_options(presult, &pbuffer->options[4], buflen); } return 0; @@ -440,17 +440,25 @@ int dhcpc_request(void *handle, struct dhcpc_state *presult) while(state != STATE_CONFIG_RECEIVED); dbg("Got IP address %d.%d.%d.%d\n", - uip_ipaddr1(presult->ipaddr), uip_ipaddr2(presult->ipaddr), - uip_ipaddr3(presult->ipaddr), uip_ipaddr4(presult->ipaddr)); + (presult->ipaddr.s_addr >> 24 ) & 0xff, + (presult->ipaddr.s_addr >> 16 ) & 0xff, + (presult->ipaddr.s_addr >> 8 ) & 0xff, + (presult->ipaddr.s_addr ) & 0xff); dbg("Got netmask %d.%d.%d.%d\n", - uip_ipaddr1(presult->netmask), uip_ipaddr2(presult->netmask), - uip_ipaddr3(presult->netmask), uip_ipaddr4(presult->netmask)); + (presult->netmask.s_addr >> 24 ) & 0xff, + (presult->netmask.s_addr >> 16 ) & 0xff, + (presult->netmask.s_addr >> 8 ) & 0xff, + (presult->netmask.s_addr ) & 0xff); dbg("Got DNS server %d.%d.%d.%d\n", - uip_ipaddr1(presult->dnsaddr), uip_ipaddr2(presult->dnsaddr), - uip_ipaddr3(presult->dnsaddr), uip_ipaddr4(presult->dnsaddr)); + (presult->dnsaddr.s_addr >> 24 ) & 0xff, + (presult->dnsaddr.s_addr >> 16 ) & 0xff, + (presult->dnsaddr.s_addr >> 8 ) & 0xff, + (presult->dnsaddr.s_addr ) & 0xff); dbg("Got default router %d.%d.%d.%d\n", - uip_ipaddr1(presult->default_router), uip_ipaddr2(presult->default_router), - uip_ipaddr3(presult->default_router), uip_ipaddr4(presult->default_router)); + (presult->default_router.s_addr >> 24 ) & 0xff, + (presult->default_router.s_addr >> 16 ) & 0xff, + (presult->default_router.s_addr >> 8 ) & 0xff, + (presult->default_router.s_addr ) & 0xff); dbg("Lease expires in %ld seconds\n", ntohs(presult->lease_time[0])*65536ul + ntohs(presult->lease_time[1])); return OK; diff --git a/nuttx/netutils/resolv/resolv.c b/nuttx/netutils/resolv/resolv.c index b318e551e..741116bb7 100644 --- a/nuttx/netutils/resolv/resolv.c +++ b/nuttx/netutils/resolv/resolv.c @@ -130,8 +130,9 @@ struct dns_answer uint16 ttl[2]; uint16 len; #ifdef CONFIG_NET_IPv6 + struct in6_addr ipaddr; #else - uint16 ipaddr[2]; + struct in_addr ipaddr; #endif }; @@ -144,8 +145,9 @@ struct namemap uint8 err; char name[32]; #ifdef CONFIG_NET_IPv6 + struct in6_addr ipaddr; #else - uint16 ipaddr[2]; + struct in_addr ipaddr; #endif }; @@ -200,7 +202,7 @@ static int send_query(const char *name, struct sockaddr_in *addr) char *nptr; const char *nameptr; uint8 seqno = g_seqno++; - static unsigned char endquery[] = {0,0,1,0,1}; + static unsigned char endquery[] = {0, 0, 1, 0, 1}; char buffer[SEND_BUFFER_SIZE]; int n; @@ -234,7 +236,7 @@ static int send_query(const char *name, struct sockaddr_in *addr) /* Called when new UDP data arrives */ #ifdef CONFIG_NET_IPv6 -#error "Not implemented +#error "Not implemented" #else int recv_response(struct sockaddr_in *addr) #endif @@ -314,14 +316,16 @@ int recv_response(struct sockaddr_in *addr) if (ans->type == HTONS(1) && ans->class == HTONS(1) && ans->len == HTONS(4)) { dbg("IP address %d.%d.%d.%d\n", - htons(ans->ipaddr[0]) >> 8, htons(ans->ipaddr[0]) & 0xff, - htons(ans->ipaddr[1]) >> 8, htons(ans->ipaddr[1]) & 0xff); + (ans->ipaddr.s_addr >> 24 ) & 0xff, + (ans->ipaddr.s_addr >> 16 ) & 0xff, + (ans->ipaddr.s_addr >> 8 ) & 0xff, + (ans->ipaddr.s_addr ) & 0xff); /* XXX: we should really check that this IP address is the one * we want. */ - addr->sin_addr.s_addr = ((uint32)ans->ipaddr[0] << 16) | (uint32)ans->ipaddr[1]; + addr->sin_addr.s_addr = ans->ipaddr.s_addr; return OK; } else @@ -374,23 +378,33 @@ int resolv_query(const char *name, struct sockaddr_in *addr) /* Obtain the currently configured DNS server. */ #ifdef CONFIG_NET_IPv6 -void resolv_getserver(struct sockaddr_in6 *dnsserver) +void resolv_getserver(struct in6_addr *dnsserver) #else -void resolv_getserver(struct sockaddr_in *dnsserver) +void resolv_getserver(struct in_addr *dnsserver) #endif { - memcpy(dnsserver, &g_dnsserver, ADDRLEN); +#ifdef CONFIG_NET_IPv6 + memcpy(dnsserver, &g_dnsserver.sin6_addr, ADDRLEN); +#else + dnsserver->s_addr = g_dnsserver.sin_addr.s_addr; +#endif } /* Configure which DNS server to use for queries */ #ifdef CONFIG_NET_IPv6 -void resolv_conf(const struct sockaddr_in6 *dnsserver) +void resolv_conf(const struct in6_addr *dnsserver) #else -void resolv_conf(const struct sockaddr_in *dnsserver) +void resolv_conf(const struct in_addr *dnsserver) #endif { - memcpy(&g_dnsserver, dnsserver, ADDRLEN); + g_dnsserver.sin_family = AF_INET; + g_dnsserver.sin_port = HTONS(53); +#ifdef CONFIG_NET_IPv6 + memcpy(&g_dnsserver.sin6_addr, dnsserver, ADDRLEN); +#else + g_dnsserver.sin_addr.s_addr = dnsserver->s_addr; +#endif } /* Initalize the resolver. */ diff --git a/nuttx/netutils/uiplib/uip-gethostaddr.c b/nuttx/netutils/uiplib/uip-gethostaddr.c index 64c5bb2ff..a8d36efac 100644 --- a/nuttx/netutils/uiplib/uip-gethostaddr.c +++ b/nuttx/netutils/uiplib/uip-gethostaddr.c @@ -86,7 +86,7 @@ int uip_gethostaddr(const char *ifname, struct in_addr *addr) { struct ifreq req; strncpy(req.ifr_name, ifname, IFNAMSIZ); - ret = ioctl(sockfd, SIOCSIFADDR, (unsigned long)&req); + ret = ioctl(sockfd, SIOCGIFADDR, (unsigned long)&req); if (!ret) { #ifdef CONFIG_NET_IPv6 -- cgit v1.2.3