From 7a21220ebd5cef442fb059c90e18ff90232d8dc9 Mon Sep 17 00:00:00 2001 From: patacongo Date: Tue, 6 Nov 2007 19:58:14 +0000 Subject: Verified basic client-side network functionality git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@373 42af7a65-404d-4744-a932-0658087f49c3 --- nuttx/ChangeLog | 5 +- nuttx/Documentation/NuttX.html | 62 ++++-- nuttx/ReleaseNotes | 23 ++- nuttx/TODO | 49 +++-- nuttx/arch/arm/src/common/up_udelay.c | 52 +++-- nuttx/arch/sim/src/up_uipdriver.c | 2 +- nuttx/configs/ntosd-dm320/README.txt | 11 ++ nuttx/configs/ntosd-dm320/netconfig | 338 ++++++++++++++++++++++++++++++++ nuttx/configs/sim/README.txt | 9 + nuttx/drivers/net/dm90x0.c | 6 +- nuttx/examples/nettest/nettest-server.c | 39 +++- nuttx/examples/nettest/nettest.h | 20 ++ nuttx/include/net/uip/uip-arch.h | 34 ++-- nuttx/net/send.c | 2 +- nuttx/net/uip/uip-poll.c | 8 +- nuttx/net/uip/uip.c | 26 +-- 16 files changed, 581 insertions(+), 105 deletions(-) create mode 100644 nuttx/configs/ntosd-dm320/README.txt create mode 100644 nuttx/configs/ntosd-dm320/netconfig create mode 100644 nuttx/configs/sim/README.txt (limited to 'nuttx') diff --git a/nuttx/ChangeLog b/nuttx/ChangeLog index bb6b359ae..ebe9cbdc4 100644 --- a/nuttx/ChangeLog +++ b/nuttx/ChangeLog @@ -199,7 +199,7 @@ * examples/nsh/: Add cp, rm, rmdir, set, unset commands. echo will now print environment variables. -0.3.0 2007-xx-xx Gregory Nutt +0.3.0 2007-11-06 Gregory Nutt * Imported uIP into the tree (see http://www.sics.se/~adam/uip/index.php/Main_Page) @@ -215,4 +215,7 @@ * Added listen() and accept() * Added DM90x0 ethernet driver * ARP timer is now built into the network layer + * Basic client functionality verified: socket(), bind(), connect(), recv(), send(). + +0.3.1 2007-xx-xx Gregory Nutt diff --git a/nuttx/Documentation/NuttX.html b/nuttx/Documentation/NuttX.html index 0e0535bb0..9be4a5dba 100644 --- a/nuttx/Documentation/NuttX.html +++ b/nuttx/Documentation/NuttX.html @@ -8,7 +8,7 @@

NuttX RTOS

-

Last Updated: September 8, 2007

+

Last Updated: November 6, 2007

@@ -183,13 +183,28 @@

- The 11th release of NuttX (nuttx-0.2.8) is available for download + The 12th release of NuttX (nuttx-0.3.0) is available for download from the SourceForge website. The change log associated with the release is available here. Unreleased changes after this release are avalable in CVS. These unreleased changes are listed here.

+

+ NuttX 30.3.0 includes the initial integration of a network subsystem and + a TCP/IP stack based on uIP. + Also included is a device driver for the Davicom DM90x0 ethernet controller. +

+

+ This integration is very preliminary. Only a small portion of the + network functionality has been integrated and there are a number of + open issues. The network subsystem is pre-alpha this point in time. + I expect that it will stabilize and mature over the next few releases. +

+

+ The baseline functionality of NuttX continues to mature and remains at + post-beta (as long as the network is not used). +

@@ -251,14 +266,14 @@

STATUS: - This port is in progress and should be available in the nuttx-0.2.7 release. + Initial coding of this port code complete but has not yet been verified.

@@ -273,7 +288,7 @@

STATUS: - This port is code complete but totally untested due to hardware issues with my OSD. + This port is complete and verified.

@@ -329,7 +344,7 @@ is available that be used to build a NuttX-compatible arm-elf toolchain.
    -

    C5471 (Arm7) +

    C5471 (ARM7) The build for this ARM7 target that includes most of the OS features and a broad range of OS tests. The size of this executable as given by the Linux size command is (3/9/07): @@ -338,6 +353,14 @@ is available that be used to build a NuttX-compatible arm-elf toolchain. +

    DM320 (ARM9) + This build for the ARM9 target includes a signficant subset of OS + features, ethernet driver and full TCP/IP stack (via uIP). +

    +
    +   text    data     bss     dec     hex filename
    +  51368     296    6072   57736    e188 nuttx
    +

    87C52 A reduced functionality OS test for the 8052 target requires only about 18-19Kb: @@ -589,17 +612,7 @@ Other memory: __FILE__and __LINE__ (not tested) * examples/ostest/barrier.c: Don't call usleep() when signals are disabled. -

-
- ARM9EJS. + ARM926EJS.
- - - -
- ChangeLog for Current Release -
- -
    0.2.8 2007-07-02 Gregory Nutt * tools/Makefile.mkconfig: Under Cygwin, executable has a different name * tools/mkdeps.sh & arch/arm/src/Makefile: Corrected a problem makeing dependencies @@ -626,13 +639,13 @@ Other memory:
    - Unreleased Changes + ChangeLog for Current Release
      -0.3.0 2007-xx-xx Gregory Nutt +0.3.0 2007-11-06 Gregory Nutt * Imported uIP into the tree (see http://www.sics.se/~adam/uip/index.php/Main_Page) @@ -648,6 +661,19 @@ Other memory: * Added listen() and accept() * Added DM90x0 ethernet driver * ARP timer is now built into the network layer + * Basic client functionality verified: socket(), bind(), connect(), recv(), send(). +
+ + + + + +
+ Unreleased Changes +
+ +
    +0.3.1 2007-xx-xx Gregory Nutt
diff --git a/nuttx/ReleaseNotes b/nuttx/ReleaseNotes index 8f9a01a24..be7b984fa 100644 --- a/nuttx/ReleaseNotes +++ b/nuttx/ReleaseNotes @@ -1,12 +1,23 @@ -nuttx-0.2.8 +nuttx-0.3.0 ^^^^^^^^^^^ -This is the 11th release of NuttX. This release (1) corrects important bugs -in opendir and realloc, (2) adds support for environment variables, (3) adds -several new C library interfaces, and (4) extends several example programs. +This is the 12th release of NuttX. This release includes the initial +integration of a network subsystem and the uIP TCP/IP stack into NuttX +(see http://www.sics.se/~adam/uip/index.php/Main_Page). Also included +is a device driver for the Davicom DM90x0 ethernet controller. + +This integration is very preliminary. Only a small portion of the +network functionality has been integrated and there are a number of +open issues (see the TODO file). The network subsystem is pre-alpha +at this point in time. I expect that it will stabilize and mature +over the next few releases. + +The baseline functionality of NuttX continues to mature and remains at +post-beta (as long as the network is not used). See the ChangeLog for a complete list of changes. -This release has been verified only on the Linux user-mode platform. +This release has been verified only on the Neuros OSD (DM320 ARM9) +platform using the DM90x0 driver. -This tarball contains a complete CVS snapshot from July 2, 2007. +This tarball contains a complete CVS snapshot from November 6, 2007. diff --git a/nuttx/TODO b/nuttx/TODO index 9a2890417..dddf2ecaa 100644 --- a/nuttx/TODO +++ b/nuttx/TODO @@ -28,38 +28,53 @@ o pthreads o C++ Support - Need to call static constructors -o Network -- Finish integratin of uIP - -o USB -- Implement USB device support -- Implement USB bulk device - -o Libraries -- sscanf() and lib_vsprintf() do not support floating point values. -- The definition of environ in stdlib.h is bogus and will not work as it should. This - is because the underlying representation of the environment is not an arry of pointers. - -o File system -- Add chmod(), truncate(). -- FAT32: long file names - o Network - Did not implement send() and sendto() timeouts. Option is setable via setsockopt, but is not implemented. - netutils/webserver netutils/telnetd (and maybe others) are seriously broken. + Need to be re-written to use listen() and accept() - Should implement SOCK_RAW +- listen() and accept() are untested. +- accept() and recvfrom() need to return connection address - Performance Improvements (uIP is not very fast): - +- Improve performance by queing TX operations Add simple buffer management. CONFIG_NET_BUFFERS (1) On write, queue buffer for output get a new buffer for the socket (waiting if nececcesary (2) Copy buffer structure into uip_driver_structure when driver requests write data +- Improve performance by stimulating the driver to accept new TX data before the + next polling interval. Add a txail callback into driver to eliminate send delays. Since we want to support multiple network devices, this means we will have to add some infrastructure to map to device. +- Break uip_interrupt() (in uip.c) into several functions. +- uIP polling issues: + (1) uIP expects a single driver to poll at a 500ms interval (dm90x0 currently + polls a 5sec). + (2) Current logic will not support multiple ethernet drivers. Each driver should + poll on TCP connections connect on the network supported by the driver; UDP + polling should respond with TX data only if the UDP packet is intended for the + the network supported by the driver. + (3) If there were multiple drivers, polling would occur at double the rate. +- TCP Bug: + When TCP data is received with no read in place, it appears that uIP ACKs the data + even though it was not taken accepted. We must either (1) buffer incoming data, or + (2) not ACK it so that it will be re-sent. + +o USB +- Implement USB device support +- Implement USB bulk device + +o Libraries +- sscanf() and lib_vsprintf() do not support floating point values. +- The definition of environ in stdlib.h is bogus and will not work as it should. This + is because the underlying representation of the environment is not an arry of pointers. + +o File system +- Add chmod(), truncate(). +- FAT32: long file names o Documentation - Document fs/ & driver/ logic diff --git a/nuttx/arch/arm/src/common/up_udelay.c b/nuttx/arch/arm/src/common/up_udelay.c index f7d10e459..40ec3ba75 100644 --- a/nuttx/arch/arm/src/common/up_udelay.c +++ b/nuttx/arch/arm/src/common/up_udelay.c @@ -44,8 +44,9 @@ * Definitions ****************************************************************************/ -#define CONFIG_BOARD_LOOPSPERUSEC ((CONFIG_BOARD_LOOPSPERMSEC+500)/1000) -#define CONFIG_BOARD_LOOPSPER10USEC ((CONFIG_BOARD_LOOPSPERMSEC+50)/100) +#define CONFIG_BOARD_LOOPSPER100USEC ((CONFIG_BOARD_LOOPSPERMSEC+5)/10) +#define CONFIG_BOARD_LOOPSPER10USEC ((CONFIG_BOARD_LOOPSPERMSEC+50)/100) +#define CONFIG_BOARD_LOOPSPERUSEC ((CONFIG_BOARD_LOOPSPERMSEC+500)/1000) /**************************************************************************** * Private Types @@ -85,48 +86,43 @@ void up_udelay(unsigned int microseconds) { - volatile int i; - volatile int j; - register uint32 loops; + volatile int i; - /* The value of microseconds should be less than 1000. If not, then we - * will perform millescond delays until it is. + /* We'll do this a little at a time because we expect that the + * CONFIG_BOARD_LOOPSPERUSEC is very inaccurate during to truncation in + * the divisions of its calculation. We'll use the largest values that + * we can in order to prevent significant error buildup in the loops. */ while (microseconds > 1000) { - for (j = 0; j < CONFIG_BOARD_LOOPSPERMSEC; j++) + for (i = 0; i < CONFIG_BOARD_LOOPSPERMSEC; i++) { } microseconds -= 1000; } - /* The numerator of the 'loops' below will overflow if CONFIG_BOARD_LOOPSPERMSEC - * is larger than (4*1024*1024*1024 - 500)/999 = 4,299,266.06 - */ - -#if CONFIG_BOARD_LOOPSPERMSEC >= 4299266 - while (microseconds > 500) + while (microseconds > 100) { - for (j = 0; j < ((CONFIG_BOARD_LOOPSPERMSEC+1)/2); j++) + for (i = 0; i < CONFIG_BOARD_LOOPSPER100USEC; i++) { } - microseconds -= 500; + microseconds -= 100; } -#endif - - /* The overflow could still occur if CONFIG_BOARD_LOOPSPERMSEC is larger than - * (4*1024*1024*1024 - 500)/499 = 8,607,147.89 - */ - -#if CONFIG_BOARD_LOOPSPERMSEC >= 8607147 -# warning "Overflow in loops calculation is possible" -#endif - /* Caculate the number of loops need to produce the required usec delay */ + while (microseconds > 10) + { + for (i = 0; i < CONFIG_BOARD_LOOPSPER10USEC; i++) + { + } + microseconds -= 10; + } - loops = (CONFIG_BOARD_LOOPSPERMSEC * microseconds + 500) / 1000; - for (j = 0; j < loops; j++) + while (microseconds > 0) { + for (i = 0; i < CONFIG_BOARD_LOOPSPERUSEC; i++) + { + } + microseconds--; } } diff --git a/nuttx/arch/sim/src/up_uipdriver.c b/nuttx/arch/sim/src/up_uipdriver.c index 3bd08c0b5..82e740bc0 100644 --- a/nuttx/arch/sim/src/up_uipdriver.c +++ b/nuttx/arch/sim/src/up_uipdriver.c @@ -201,7 +201,7 @@ void uipdriver_loop(void) else if (timer_expired(&g_periodic_timer)) { timer_reset(&g_periodic_timer); - uip_poll(&g_sim_dev, sim_uiptxpoll, UIP_TIMER); + uip_poll(&g_sim_dev, sim_uiptxpoll, UIP_DRV_TIMER); } sched_unlock(); } diff --git a/nuttx/configs/ntosd-dm320/README.txt b/nuttx/configs/ntosd-dm320/README.txt new file mode 100644 index 000000000..58e2563d6 --- /dev/null +++ b/nuttx/configs/ntosd-dm320/README.txt @@ -0,0 +1,11 @@ +README +^^^^^^ + +The configuration netconfig may be used instead of the +default configuration (defconfig). This configuration +enables networking using the OSDs DM9000A ethernet +interface. + +Disclaimer: The NuttX network subsystem is a "work in +progress" at this time and minimal network functionality +should be expected. diff --git a/nuttx/configs/ntosd-dm320/netconfig b/nuttx/configs/ntosd-dm320/netconfig new file mode 100644 index 000000000..10cca587f --- /dev/null +++ b/nuttx/configs/ntosd-dm320/netconfig @@ -0,0 +1,338 @@ +############################################################ +# 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_CHIP - Identifies the arch/*/chip subdirectory +# CONFIG_ARCH_CHIP_name - For use in C code +# 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_BOARD_LOOPSPERMSEC - for delay loops +# CONFIG_DRAM_SIZE - Describes the installed DRAM. +# CONFIG_DRAM_START - The start address of DRAM (physical) +# CONFIG_DRAM_VSTART - The startaddress of DRAM (virtual) +# CONFIG_ARCH_STACKDUMP - Do stack dumps after assertions +# +CONFIG_ARCH=arm +CONFIG_ARCH_ARM=y +CONFIG_ARCH_CHIP=dm320 +CONFIG_ARCH_CHIP_DM320=y +CONFIG_ARCH_BOARD=ntosd-dm320 +CONFIG_ARCH_BOARD_NTOSD_DM320=y +CONFIG_BOARD_LOOPSPERMSEC=16945 +CONFIG_DRAM_SIZE=0x01000000 +CONFIG_DRAM_START=0x01000000 +CONFIG_DRAM_VSTART=0x00000000 +CONFIG_DRAM_NUTTXENTRY=0x01008000 +CONFIG_ARCH_STACKDUMP=y + +# +# DM320 specific device driver settings +# +# CONFIG_UARTn_SERIAL_CONSOLE - selects the UARTn for the +# console and ttys0 (default is the UART0). +# CONFIG_UARTn_RXBUFSIZE - Characters are buffered as received. +# This specific the size of the receive buffer +# CONFIG_UARTn_TXBUFSIZE - Characters are buffered before +# being sent. This specific the size of the transmit buffer +# CONFIG_UARTn_BAUD - The configure BAUD of the UART. Must be +# CONFIG_UARTn_BITS - The number of bits. Must be either 7 or 8. +# CONFIG_UARTn_PARTIY - 0=no parity, 1=odd parity, 2=even parity +# CONFIG_UARTn_2STOP - Two stop bits +# +CONFIG_UART0_SERIAL_CONSOLE=y +CONFIG_UART1_SERIAL_CONSOLE=n +CONFIG_UART0_TXBUFSIZE=256 +CONFIG_UART1_TXBUFSIZE=256 +CONFIG_UART0_RXBUFSIZE=256 +CONFIG_UART1_RXBUFSIZE=256 +CONFIG_UART0_BAUD=115200 +CONFIG_UART1_BAUD=115200 +CONFIG_UART0_BITS=8 +CONFIG_UART1_BITS=8 +CONFIG_UART0_PARITY=0 +CONFIG_UART1_PARITY=0 +CONFIG_UART0_2STOP=0 +CONFIG_UART1_2STOP=0 + +# +# 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_START_YEAR, CONFIG_START_MONTH, CONFIG_START_DAY - +# Used to initialize the internal time logic. +# CONFIG_JULIAN_TIME - Enables Julian time conversions +# 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=200 +CONFIG_SCHED_INSTRUMENTATION=n +CONFIG_TASK_NAME_SIZE=0 +CONFIG_START_YEAR=2007 +CONFIG_START_MONTH=2 +CONFIG_START_DAY=13 +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=y +CONFIG_DISABLE_ENVIRON=y + +# +# 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 + +# +# 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/nettest +CONFIG_EXAMPLE_NETTEST_IPADDR=(10<<24|0<<16|0<<8|2) +CONFIG_EXAMPLE_NETTEST_DRIPADDR=(10<<24|0<<16|0<<8|1) +CONFIG_EXAMPLE_NETTEST_NETMASK=(255<<24|255<<16|255<<8|0) +CONFIG_EXAMPLE_NETTEST_CLIENTIP=(10<<24|0<<16|0<<8|1) + +# +# DM90x0 Driver Settings +CONFIG_NET_DM90x0=y +CONFIG_DM9X_NINTERFACES=1 +CONFIG_DM9X_STATS=1 +CONFIG_DM9X_BASE=0xd0000300 +CONFIG_DM9X_IRQ=27 +CONFIG_DM9X_BUSWIDTH8=n +CONFIG_DM9X_BUSWIDTH16=y +CONFIG_DM9X_BUSWIDTH32=n +CONFIG_DM9X_CHECKSUM=n +CONFIG_DM9X_ETRANS=n + +# +# 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 (arm7tdmi only) +# 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_STACK_POINTER= +CONFIG_PROC_STACK_SIZE=4096 +CONFIG_PTHREAD_STACK_MIN=256 +CONFIG_PTHREAD_STACK_DEFAULT=4096 +CONFIG_HEAP_BASE= +CONFIG_HEAP_SIZE= diff --git a/nuttx/configs/sim/README.txt b/nuttx/configs/sim/README.txt new file mode 100644 index 000000000..4f50ca032 --- /dev/null +++ b/nuttx/configs/sim/README.txt @@ -0,0 +1,9 @@ +README +^^^^^^ + +The configuration netconfig may be used instead of the +default configuration (defconfig). This configuration +enables networking using the network TAP device. + +The NuttX network is not, however, functional on the TAP +device yet. diff --git a/nuttx/drivers/net/dm90x0.c b/nuttx/drivers/net/dm90x0.c index 9a36ed51b..7f49fda4c 100644 --- a/nuttx/drivers/net/dm90x0.c +++ b/nuttx/drivers/net/dm90x0.c @@ -1074,7 +1074,7 @@ static void dm9x_txdone(struct dm9x_driver_s *dm9x) /* Then poll uIP for new XMIT data */ - (void)uip_poll(&dm9x->dm_dev, dm9x_uiptxpoll, UIP_POLL); + (void)uip_poll(&dm9x->dm_dev, dm9x_uiptxpoll, UIP_DRV_POLL); } /**************************************************************************** @@ -1231,7 +1231,7 @@ static void dm9x_txtimeout(int argc, uint32 arg, ...) /* Then poll uIP for new XMIT data */ - (void)uip_poll(&dm9x->dm_dev, dm9x_uiptxpoll, UIP_POLL); + (void)uip_poll(&dm9x->dm_dev, dm9x_uiptxpoll, UIP_DRV_POLL); } /**************************************************************************** @@ -1275,7 +1275,7 @@ static void dm9x_polltimer(int argc, uint32 arg, ...) { /* If so, poll uIP for new XMIT data */ - (void)uip_poll(&dm9x->dm_dev, dm9x_uiptxpoll, UIP_TIMER); + (void)uip_poll(&dm9x->dm_dev, dm9x_uiptxpoll, UIP_DRV_TIMER); } /* Setup the watchdog poll timer again */ diff --git a/nuttx/examples/nettest/nettest-server.c b/nuttx/examples/nettest/nettest-server.c index 2f398583a..98b1cc98f 100644 --- a/nuttx/examples/nettest/nettest-server.c +++ b/nuttx/examples/nettest/nettest-server.c @@ -55,6 +55,9 @@ void recv_server(void) { struct sockaddr_in myaddr; +#ifdef NETTEST_HAVE_SOLINGER + struct linger ling; +#endif char buffer[1024]; int listensd; int acceptsd; @@ -82,11 +85,11 @@ void recv_server(void) optval = 1; if (setsockopt(listensd, SOL_SOCKET, SO_REUSEADDR, (void*)&optval, sizeof(int)) < 0) { - message("server: setsockopt failure: %d\n", errno); + message("server: setsockopt SO_REUSEADDR failure: %d\n", errno); exit(1); } - /* Bind the TCP socket to a local address */ + /* Bind the socket to a local address */ myaddr.sin_family = AF_INET; myaddr.sin_port = HTONS(PORTNO); @@ -118,6 +121,18 @@ void recv_server(void) } message("server: Connection accepted -- receiving\n"); + /* Configure to "linger" until all data is sent when the socket is closed */ + +#ifdef NETTEST_HAVE_SOLINGER + ling.l_onoff = 1; + ling.l_linger = 30; /* timeout is seconds */ + if (setsockopt(acceptsd, SOL_SOCKET, SO_LINGER, &ling, sizeof(struct linger)) < 0) + { + message("server: setsockopt SO_LINGER failure: %d\n", errno); + exit(1); + } +#endif + #ifdef CONFIG_NETTEST_PERFORMANCE /* Then receive data forever */ @@ -179,6 +194,17 @@ void recv_server(void) } } +#ifdef CONFIG_NETTEST_HOST + /* At present, data received by the target before it is completed the + * the write opertion and started the read operation results in a failure + * (the data is not received, but it is ACKed). This will have to be + * fixed. + */ + +# warning "FIXME: This should not be necessary" + sleep(10); +#endif + /* Then send the same data back to the client */ nbytessent = send(acceptsd, buffer, totalbytesread, 0); @@ -191,6 +217,15 @@ void recv_server(void) } message("server: Sent %d bytes\n", nbytessent); + /* If this platform only does abortive disconnects, then wait a bit to get the + * client side a change to receive the data. + */ + +#if 1 /* Do it for all platforms */ + message("server: Wait before closing\n"); + sleep(60); +#endif + close(listensd); close(acceptsd); #endif diff --git a/nuttx/examples/nettest/nettest.h b/nuttx/examples/nettest/nettest.h index b868ec90d..9fe735911 100644 --- a/nuttx/examples/nettest/nettest.h +++ b/nuttx/examples/nettest/nettest.h @@ -54,14 +54,34 @@ # define HTONS(a) htons(a) # define HTONL(a) htonl(a) + + /* Used printf for debug output */ + # define message(...) printf(__VA_ARGS__) + + /* Have SO_LINGER */ + +# define NETTEST_HAVE_SOLINGER 1 + #else + + /* Get errno using a pointer */ + # define errno *get_errno_ptr() + + /* If debug is enabled, use the synchronous lib_lowprintf so that the + * program output does not get disassociated in the debug output. + */ + # ifdef CONFIG_DEBUG # define message(...) lib_lowprintf(__VA_ARGS__) # else # define message(...) printf(__VA_ARGS__) # endif + + /* At present, uIP does only abortive disconnects */ + +# undef NETTEST_HAVE_SOLINGER #endif #define PORTNO 5471 diff --git a/nuttx/include/net/uip/uip-arch.h b/nuttx/include/net/uip/uip-arch.h index 91b80f521..c93cd614c 100644 --- a/nuttx/include/net/uip/uip-arch.h +++ b/nuttx/include/net/uip/uip-arch.h @@ -63,15 +63,25 @@ * incoming data that should be processed, or because the periodic * timer has fired. These values are never used directly, but only in * the macrose defined in this file. + * + * UIP_DRV_RECEIVE - There is new incoming data from the driver in the d_buf + * field of the uip_driver_s structure. The length of the + * new data is provided in the d_len field of the + * uip_driver_s structure. + * UIP_DRV_TIMER - Called periodically from driver to service timeout- + * related activities to and to get timeout-related + * responses (e.g., reset) + * UIP_DRV_POLL - Poll TCP for data to be transmitted + * UIP_DRV_UDPPOLL - Poll for UDP data to be transmitted. This value is used + * internally by the uip_poll logic. */ -#define UIP_DATA 1 /* There is incoming data in the d_buf buffer. The - * length of the data is stored in the field d_len. */ -#define UIP_TIMER 2 /* TCP periodic timer has fired */ -#define UIP_POLL_REQUEST 3 /* Poll TCP connection */ +#define UIP_DRV_RECEIVE 1 +#define UIP_DRV_TIMER 2 +#define UIP_DRV_POLL 3 #ifdef CONFIG_NET_UDP -# define UIP_UDP_POLL 4 /* Poll UDP connection */ -#endif /* CONFIG_NET_UDP */ +# define UIP_DRV_UDPPOLL 4 +#endif /**************************************************************************** * Public Types @@ -236,7 +246,7 @@ struct uip_driver_s * } */ -#define uip_input(dev) uip_interrupt(dev,UIP_DATA) +#define uip_input(dev) uip_interrupt(dev, UIP_DRV_RECEIVE) /* Polling of connections. * @@ -248,9 +258,9 @@ struct uip_driver_s * suplied function returns a non-zero value (which is would do only if * it cannot accept further write data). * - * This function should be called periodically with event == UIP_TIMER for - * periodic processing. This function may also be called with UIP_POLL to - * perform necessary periodic processing of TCP connections. + * This function should be called periodically with event == UIP_DRV_TIMER + * to perform TCP. This function may also be called with UIP_DRV_POLL to + * obtain pending TX data. * * This function is called from the CAN device driver and may be called from * the timer interrupt/watchdog handle level. @@ -272,7 +282,7 @@ struct uip_driver_s * } * * ... - * uip_poll(dev, driver_callback, UIP_TIMER); + * uip_poll(dev, driver_callback, UIP_DRV_TIMER); * * Note: If you are writing a uIP device driver that needs ARP (Address * Resolution Protocol), e.g., when running uIP over Ethernet, you will @@ -296,7 +306,7 @@ extern int uip_poll(struct uip_driver_s *dev, uip_poll_callback_t callback, int /* uip_poll helper functions */ -#define uip_periodic(dev,cb) uip_poll(dev,db,UIP_TIMER); +#define uip_periodic(dev,cb) uip_poll(dev, db, UIP_DRV_TIMER); /* Architecure support * diff --git a/nuttx/net/send.c b/nuttx/net/send.c index 1827a86e5..cfb56f1ca 100644 --- a/nuttx/net/send.c +++ b/nuttx/net/send.c @@ -128,7 +128,7 @@ static void send_interrupt(struct uip_driver_s *dev, void *private) else if (pstate->snd_state == STATE_DATA_SENT && uip_ack_event()) { - /* Yes.. the data has been sent AND acknowledge */ + /* Yes.. the data has been sent AND acknowledged */ if (pstate->snd_buflen > uip_mss()) { diff --git a/nuttx/net/uip/uip-poll.c b/nuttx/net/uip/uip-poll.c index b61eb32aa..22a641ce1 100644 --- a/nuttx/net/uip/uip-poll.c +++ b/nuttx/net/uip/uip-poll.c @@ -95,9 +95,9 @@ static inline void uip_udppoll(struct uip_driver_s *dev, unsigned int conn) * suplied function returns a non-zero value (which is would do only if * it cannot accept further write data). * - * This function should be called periodically with event == UIP_TIMER for - * periodic processing. This function may also be called with UIP_POLL to - * perform necessary periodic processing of TCP connections. + * This function should be called periodically with event == UIP_DRV_TIMER + * to perform period TCP processing. This function may also be called + * with UIP_DRV_POLL obtain queue TX data. * * When the callback function is called, there may be an outbound packet * waiting for service in the uIP packet buffer, and if so the d_len field @@ -144,7 +144,7 @@ int uip_poll(struct uip_driver_s *dev, uip_poll_callback_t callback, int event) while ((udp_conn = uip_nextudpconn(udp_conn))) { uip_udp_conn = udp_conn; - uip_interrupt(dev, UIP_UDP_POLL); + uip_interrupt(dev, UIP_DRV_UDPPOLL); if (callback(dev)) { irqrestore(flags); diff --git a/nuttx/net/uip/uip.c b/nuttx/net/uip/uip.c index 3a8e4fb8e..bbe287d6c 100644 --- a/nuttx/net/uip/uip.c +++ b/nuttx/net/uip/uip.c @@ -591,11 +591,11 @@ void uip_interrupt(struct uip_driver_s *dev, uint8 event) dev->d_snddata = dev->d_appdata = &dev->d_buf[UIP_IPTCPH_LEN + UIP_LLH_LEN]; - /* Check if we were invoked because of a poll request for a - * particular connection. + /* Check if we were invoked because of a TX poll request for a + * particular TCP connection. */ - if (event == UIP_POLL_REQUEST) + if (event == UIP_DRV_POLL) { if ((uip_connr->tcpstateflags & UIP_TS_MASK) == UIP_ESTABLISHED && !uip_outstanding(uip_connr)) @@ -609,7 +609,7 @@ void uip_interrupt(struct uip_driver_s *dev, uint8 event) /* Check if we were invoked because of the perodic timer firing. */ - else if (event == UIP_TIMER) + else if (event == UIP_DRV_TIMER) { #if UIP_REASSEMBLY if (uip_reasstmr != 0) @@ -740,7 +740,7 @@ void uip_interrupt(struct uip_driver_s *dev, uint8 event) } #ifdef CONFIG_NET_UDP - else if (event == UIP_POLL) + else if (event == UIP_DRV_UDPPOLL) { if (uip_udp_conn->lport != 0) { @@ -937,7 +937,7 @@ void uip_interrupt(struct uip_driver_s *dev, uint8 event) #if UIP_PINGADDRCONF icmp_input: -#endif /* UIP_PINGADDRCONF */ +#endif UIP_STAT(++uip_stat.icmp.recv); /* ICMP echo (i.e., ping) processing. This is simple, we only change @@ -1375,8 +1375,8 @@ tcp_send_syn: BUF->optdata[1] = TCP_OPT_MSS_LEN; BUF->optdata[2] = (UIP_TCP_MSS) / 256; BUF->optdata[3] = (UIP_TCP_MSS) & 255; - dev->d_len = UIP_IPTCPH_LEN + TCP_OPT_MSS_LEN; - BUF->tcpoffset = ((UIP_TCPH_LEN + TCP_OPT_MSS_LEN) / 4) << 4; + dev->d_len = UIP_IPTCPH_LEN + TCP_OPT_MSS_LEN; + BUF->tcpoffset = ((UIP_TCPH_LEN + TCP_OPT_MSS_LEN) / 4) << 4; goto tcp_send; /* This label will be jumped to if we found an active connection. */ @@ -1426,9 +1426,9 @@ found: { if ((dev->d_len > 0 || ((BUF->flags & (TCP_SYN | TCP_FIN)) != 0)) && (BUF->seqno[0] != uip_connr->rcv_nxt[0] || - BUF->seqno[1] != uip_connr->rcv_nxt[1] || - BUF->seqno[2] != uip_connr->rcv_nxt[2] || - BUF->seqno[3] != uip_connr->rcv_nxt[3])) + BUF->seqno[1] != uip_connr->rcv_nxt[1] || + BUF->seqno[2] != uip_connr->rcv_nxt[2] || + BUF->seqno[3] != uip_connr->rcv_nxt[3])) { goto tcp_send_ack; } @@ -1959,7 +1959,9 @@ tcp_send_ack: tcp_send_nodata: dev->d_len = UIP_IPTCPH_LEN; - tcp_send_noopts: + +tcp_send_noopts: + BUF->tcpoffset = (UIP_TCPH_LEN / 4) << 4; tcp_send: -- cgit v1.2.3