summaryrefslogtreecommitdiff
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2011-03-06 13:55:20 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2011-03-06 13:55:20 +0000
commit517ae43b4f1c1eaf64137a5a6d0d79f3e26608af (patch)
tree5a063aa82942faca48e26c8c35b6e65ef8c0b89c
parent84beafe48b5fdb3bf8dfc80bf84ce922eb7dba31 (diff)
downloadpx4-nuttx-517ae43b4f1c1eaf64137a5a6d0d79f3e26608af.tar.gz
px4-nuttx-517ae43b4f1c1eaf64137a5a6d0d79f3e26608af.tar.bz2
px4-nuttx-517ae43b4f1c1eaf64137a5a6d0d79f3e26608af.zip
RTL driver update (still in progress)
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@3346 42af7a65-404d-4744-a932-0658087f49c3
-rw-r--r--nuttx/arch/x86/src/qemu/qemu_lowputc.c36
-rwxr-xr-xnuttx/arch/x86/src/qemu/qemu_vectors.S10
-rwxr-xr-xnuttx/configs/detron/wlan/defconfig19
-rwxr-xr-xnuttx/configs/olimex-lpc1766stk/wlan/defconfig47
-rw-r--r--nuttx/configs/qemu-i486/README.txt47
-rwxr-xr-xnuttx/configs/qemu-i486/ostest/ld.script1
-rw-r--r--nuttx/drivers/net/skeleton.c6
-rwxr-xr-xnuttx/drivers/usbhost/usbhost_rtl8187.c671
8 files changed, 788 insertions, 49 deletions
diff --git a/nuttx/arch/x86/src/qemu/qemu_lowputc.c b/nuttx/arch/x86/src/qemu/qemu_lowputc.c
index 4e3471e60..1fa4aa6c5 100644
--- a/nuttx/arch/x86/src/qemu/qemu_lowputc.c
+++ b/nuttx/arch/x86/src/qemu/qemu_lowputc.c
@@ -45,6 +45,32 @@
* Pre-processor Definitions
****************************************************************************/
+ /* COM1 port addresses */
+
+#define COM1_PORT 0x3f8 /* COM1: I/O port 0x3f8, IRQ 4 */
+#define COM2_PORT 0x2f8 /* COM2: I/O port 0x2f8, IRQ 3 */
+#define COM3_PORT 0x3e8 /* COM3: I/O port 0x3e8, IRQ 4 */
+#define COM4_PORT 0x2e8 /* COM4: I/O port 0x2e8, IRQ 3 */
+
+/* 16650 register offsets */
+
+#define COM_RBR 0 /* DLAB=0, Receiver Buffer (read) */
+#define COM_THR 0 /* DLAB=0, Transmitter Holding Register (write) */
+#define COM_DLL 0 /* DLAB=1, Divisor Latch (least significant byte) */
+#define COM_IER 1 /* DLAB=0, Interrupt Enable */
+#define COM_DLM 1 /* DLAB=1, Divisor Latch(most significant byte) */
+#define COM_IIR 2 /* Interrupt Identification (read) */
+#define COM_FCR 2 /* FIFO Control (write) */
+#define COM_LCR 3 /* Line Control */
+#define COM_MCR 4 /* MODEM Control */
+#define COM_LSR 5 /* Line Status */
+#define COM_MSR 6 /* MODEM Status */
+#define COM_SCR 7 /* Scratch */
+
+/* 16650 register bit definitions */
+
+#define LSR_THRE (1 << 5) /* Bit 5: Transmitter Holding Register Empty */
+
/****************************************************************************
* Private Data
****************************************************************************/
@@ -67,14 +93,12 @@
void up_lowputc(char ch)
{
- /* Wait until the BIOS can accept another character (so that the OS will
- * continue to run.
- */
+ /* Wait until the Transmitter Holding Register (THR) is empty. */
- while ((inb(0x3f8+5) & (1 << 5)) == 0);
+ while ((inb(COM1_PORT+COM_LSR) & LSR_THRE) == 0);
- /* Then output the character */
+ /* Then output the character to the THR*/
- outb(ch, 0x3f8);
+ outb(ch, COM1_PORT+COM_THR);
}
diff --git a/nuttx/arch/x86/src/qemu/qemu_vectors.S b/nuttx/arch/x86/src/qemu/qemu_vectors.S
index 810904538..6795203e2 100755
--- a/nuttx/arch/x86/src/qemu/qemu_vectors.S
+++ b/nuttx/arch/x86/src/qemu/qemu_vectors.S
@@ -296,14 +296,10 @@ irq_common:
/* Trace macros, use like trace 'i' to print char to serial port. */
- .macro io_outb, addr, data
- mov dx, $\addr
- mov al, $\data
- out dx, al
- .endm
-
.macro trace, ch
- io_outb 0x3f8, \ch
+ mov $0x3f8, %dx
+ mov $\ch, %al
+ out %al, %dx
.endm
/* This macro creates a stub for an ISR which does NOT pass it's own
diff --git a/nuttx/configs/detron/wlan/defconfig b/nuttx/configs/detron/wlan/defconfig
index d173298ca..3e6f60177 100755
--- a/nuttx/configs/detron/wlan/defconfig
+++ b/nuttx/configs/detron/wlan/defconfig
@@ -53,7 +53,7 @@
# CONFIG_DRAM_SIZE - Describes the installed DRAM.
# CONFIG_DRAM_START - The start address of DRAM (physical)
# CONFIG_DRAM_END - Last address+1 of installed RAM
-# CONFIG_ARCH_IRQPRIO - The ST32F103Z supports interrupt prioritization
+# CONFIG_ARCH_IRQPRIO - The LPC17xx supports interrupt prioritization
# CONFIG_ARCH_INTERRUPTSTACK - This architecture supports an interrupt
# stack. If defined, this symbol is the size of the interrupt
# stack in bytes. If not defined, the user task stacks will be
@@ -208,6 +208,7 @@ CONFIG_PHY_KS8721=y
CONFIG_PHY_AUTONEG=y
CONFIG_PHY_SPEED100=n
CONFIG_PHY_FDUPLEX=y
+CONFIG_NET_REGDEBUG=n
#
# General build options
@@ -333,9 +334,9 @@ CONFIG_ARCH_LOWPUTC=y
CONFIG_RR_INTERVAL=200
CONFIG_SCHED_INSTRUMENTATION=n
CONFIG_TASK_NAME_SIZE=0
-CONFIG_START_YEAR=2010
-CONFIG_START_MONTH=12
-CONFIG_START_DAY=22
+CONFIG_START_YEAR=2011
+CONFIG_START_MONTH=3
+CONFIG_START_DAY=6
CONFIG_GREGORIAN_TIME=n
CONFIG_JULIAN_TIME=n
CONFIG_DEV_CONSOLE=y
@@ -530,16 +531,17 @@ CONFIG_MMCSD_HAVECARDDETECT=n
# 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_WLAN - Enable or disable WLAN network interface
#
-CONFIG_NET=n
+CONFIG_NET=y
CONFIG_NET_IPv6=n
-CONFIG_NSOCKET_DESCRIPTORS=0
+CONFIG_NSOCKET_DESCRIPTORS=2
CONFIG_NET_SOCKOPTS=y
CONFIG_NET_BUFSIZE=420
-CONFIG_NET_TCP=n
+CONFIG_NET_TCP=y
CONFIG_NET_TCP_CONNS=40
CONFIG_NET_MAX_LISTENPORTS=40
-CONFIG_NET_UDP=n
+CONFIG_NET_UDP=y
CONFIG_NET_UDP_CHECKSUMS=y
#CONFIG_NET_UDP_CONNS=10
CONFIG_NET_ICMP=n
@@ -551,6 +553,7 @@ CONFIG_NET_STATISTICS=y
CONFIG_NET_BROADCAST=n
#CONFIG_NET_LLH_LEN=14
#CONFIG_NET_FWCACHE_SIZE=2
+CONFIG_NET_WLAN=y
#
# UIP Network Utilities
diff --git a/nuttx/configs/olimex-lpc1766stk/wlan/defconfig b/nuttx/configs/olimex-lpc1766stk/wlan/defconfig
index 33d869bf1..e676a66ca 100755
--- a/nuttx/configs/olimex-lpc1766stk/wlan/defconfig
+++ b/nuttx/configs/olimex-lpc1766stk/wlan/defconfig
@@ -207,9 +207,6 @@ CONFIG_PHY_KS8721=y
CONFIG_PHY_AUTONEG=y
CONFIG_PHY_SPEED100=n
CONFIG_PHY_FDUPLEX=y
-CONFIG_NET_EMACRAM_SIZE=8192
-CONFIG_NET_NTXDESC=7
-CONFIG_NET_NRXDESC=7
CONFIG_NET_REGDEBUG=n
#
@@ -336,9 +333,9 @@ CONFIG_ARCH_LOWPUTC=y
CONFIG_RR_INTERVAL=200
CONFIG_SCHED_INSTRUMENTATION=n
CONFIG_TASK_NAME_SIZE=0
-CONFIG_START_YEAR=2010
-CONFIG_START_MONTH=11
-CONFIG_START_DAY=10
+CONFIG_START_YEAR=2011
+CONFIG_START_MONTH=3
+CONFIG_START_DAY=6
CONFIG_GREGORIAN_TIME=n
CONFIG_JULIAN_TIME=n
CONFIG_DEV_CONSOLE=y
@@ -533,22 +530,21 @@ CONFIG_MMCSD_HAVECARDDETECT=n
# 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_WLAN - Enable or disable WLAN network interface
#
-CONFIG_NET=n
+CONFIG_NET=y
CONFIG_NET_IPv6=n
-CONFIG_NSOCKET_DESCRIPTORS=8
+CONFIG_NSOCKET_DESCRIPTORS=2
CONFIG_NET_SOCKOPTS=y
-CONFIG_NET_BUFSIZE=562
+CONFIG_NET_BUFSIZE=420
CONFIG_NET_TCP=y
-CONFIG_NET_TCP_CONNS=8
-CONFIG_NET_NTCP_READAHEAD_BUFFERS=16
-CONFIG_NET_TCPBACKLOG=n
-CONFIG_NET_MAX_LISTENPORTS=8
+CONFIG_NET_TCP_CONNS=40
+CONFIG_NET_MAX_LISTENPORTS=40
CONFIG_NET_UDP=y
CONFIG_NET_UDP_CHECKSUMS=y
-#CONFIG_NET_UDP_CONNS=8
-CONFIG_NET_ICMP=y
-CONFIG_NET_ICMP_PING=y
+#CONFIG_NET_UDP_CONNS=10
+CONFIG_NET_ICMP=n
+CONFIG_NET_ICMP_PING=n
#CONFIG_NET_PINGADDRCONF=0
CONFIG_NET_STATISTICS=y
#CONFIG_NET_RECEIVE_WINDOW=
@@ -556,6 +552,7 @@ CONFIG_NET_STATISTICS=y
CONFIG_NET_BROADCAST=n
#CONFIG_NET_LLH_LEN=14
#CONFIG_NET_FWCACHE_SIZE=2
+CONFIG_NET_WLAN=y
#
# UIP Network Utilities
@@ -657,7 +654,7 @@ CONFIG_LPC17_USBDEV_DMAINTMASK=0
#
CONFIG_USBHOST_OHCIRAM_SIZE=1536
CONFIG_USBHOST_NEDS=2
-CONFIG_USBHOST_NTDS=3
+CONFIG_USBHOST_NTDS=2
CONFIG_USBHOST_TDBUFFERS=3
CONFIG_USBHOST_TDBUFSIZE=128
CONFIG_USBHOST_IOBUFSIZE=512
@@ -761,11 +758,11 @@ CONFIG_EXAMPLE_UIP_DHCPC=n
#
CONFIG_EXAMPLE_NETTEST_SERVER=n
CONFIG_EXAMPLE_NETTEST_PERFORMANCE=n
-CONFIG_EXAMPLE_NETTEST_NOMAC=y
-CONFIG_EXAMPLE_NETTEST_IPADDR=(10L<<24|0L<<16|0L<<8|2L)
-CONFIG_EXAMPLE_NETTEST_DRIPADDR=(10L<<24|0L<<16|0L<<8|1L)
-CONFIG_EXAMPLE_NETTEST_NETMASK=(255L<<24|255L<<16|255L<<8|0L)
-CONFIG_EXAMPLE_NETTEST_CLIENTIP=(10L<<24|0L<<16|0L<<8|1L)
+CONFIG_EXAMPLE_NETTEST_NOMAC=n
+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)
#
# Settings for examples/ostest
@@ -817,11 +814,11 @@ CONFIG_EXAMPLES_NSH_DISABLESCRIPT=n
CONFIG_EXAMPLES_NSH_DISABLEBG=n
CONFIG_EXAMPLES_NSH_ROMFSETC=n
CONFIG_EXAMPLES_NSH_CONSOLE=y
-CONFIG_EXAMPLES_NSH_TELNET=y
+CONFIG_EXAMPLES_NSH_TELNET=n
CONFIG_EXAMPLES_NSH_ARCHINIT=y
CONFIG_EXAMPLES_NSH_IOBUFFER_SIZE=512
CONFIG_EXAMPLES_NSH_DHCPC=n
-CONFIG_EXAMPLES_NSH_NOMAC=y
+CONFIG_EXAMPLES_NSH_NOMAC=n
CONFIG_EXAMPLES_NSH_IPADDR=(10<<24|0<<16|0<<8|2)
CONFIG_EXAMPLES_NSH_DRIPADDR=(10<<24|0<<16|0<<8|1)
CONFIG_EXAMPLES_NSH_NETMASK=(255<<24|255<<16|255<<8|0)
@@ -837,7 +834,7 @@ CONFIG_EXAMPLES_NSH_FATMOUNTPT=/tmp
#
# Architecture-specific NSH options
#
-CONFIG_EXAMPLES_NSH_MMCSDSPIPORTNO=1
+CONFIG_EXAMPLES_NSH_MMCSDSPIPORTNO=0
CONFIG_EXAMPLES_NSH_MMCSDSLOTNO=0
CONFIG_EXAMPLES_NSH_MMCSDMINOR=0
diff --git a/nuttx/configs/qemu-i486/README.txt b/nuttx/configs/qemu-i486/README.txt
index d4c418ed8..32cbfa76f 100644
--- a/nuttx/configs/qemu-i486/README.txt
+++ b/nuttx/configs/qemu-i486/README.txt
@@ -4,6 +4,53 @@ README
This README file describes the contents of the build configurations available
for the NuttX QEMU i486 port.
+Contents
+^^^^^^^^
+
+ * QEMU
+ * Configurations
+
+QEMU
+^^^^
+
+QEMU is a generic and open source machine emulator and virtualizer. Here are
+some links (which are mostly outdated by the time your read this):
+
+ Home Page: http://wiki.qemu.org/Main_Page
+ Downloads: http://wiki.qemu.org/Download
+ Documentation: http://wiki.qemu.org/Manual
+ Usage: qemu -nographic -kernel nuttx.elf
+
+Building QEMU:
+
+ tar zxf qemu-0.14.0.tar.gz
+ cd qemu-0.14.0
+ ./configure
+ make
+ make install
+
+Cygwin build problems:
+
+ Error:
+
+ "gcc: The -mno-cygwin flag has been removed; use a mingw-targeted cross-compiler."
+
+ Workaround:
+
+ None known. It does not seem possible to build QEMU using the Cygwin gcc.
+ I tried editing configure. Removing the following line will allow QEMU to
+ configure:
+
+ QEMU_CFLAGS="-mno-cygwin $QEMU_CFLAGS"
+
+ However, it then fails later during the compilation phase.
+
+ Recommendation:
+
+ 1. Google for "qemu windows download" and download some pre-built QEMU
+ binaries. I found 0.14.0 here: http://dietpc.org/windows/qemu/, or
+ 2. Try building QEMU with MingGW
+
Configurations
^^^^^^^^^^^^^^
diff --git a/nuttx/configs/qemu-i486/ostest/ld.script b/nuttx/configs/qemu-i486/ostest/ld.script
index 209a0089a..cf4e40cb0 100755
--- a/nuttx/configs/qemu-i486/ostest/ld.script
+++ b/nuttx/configs/qemu-i486/ostest/ld.script
@@ -48,6 +48,7 @@ SECTIONS
.text ALIGN (0x1000) : {
_srodata = ABSOLUTE(.);
*(.rodata .rodata.*)
+ *(.rdata .rdata.*)
*(.fixup)
*(.gnu.warning)
*(.glue_7)
diff --git a/nuttx/drivers/net/skeleton.c b/nuttx/drivers/net/skeleton.c
index c286886b9..16aab6d87 100644
--- a/nuttx/drivers/net/skeleton.c
+++ b/nuttx/drivers/net/skeleton.c
@@ -642,12 +642,12 @@ static int skel_rmmac(struct uip_driver_s *dev, FAR const uint8_t *mac)
int skel_initialize(int intf)
{
- struct lpc17_driver_s *priv;
+ struct skel_driver_s *priv;
/* Get the interface structure associated with this interface number. */
- DEBUGASSERT(inf < ONFIG_skeleton_NINTERFACES);
- priv = &g_ethdrvr[intf];
+ DEBUGASSERT(inf < CONFIG_skeleton_NINTERFACES);
+ priv = &g_skel[intf];
/* Check if a Ethernet chip is recognized at its I/O base */
diff --git a/nuttx/drivers/usbhost/usbhost_rtl8187.c b/nuttx/drivers/usbhost/usbhost_rtl8187.c
index fa849ce12..81944df17 100755
--- a/nuttx/drivers/usbhost/usbhost_rtl8187.c
+++ b/nuttx/drivers/usbhost/usbhost_rtl8187.c
@@ -34,6 +34,9 @@
*
****************************************************************************/
+/* @TODO TEMPORARILY. REMOVE LATER!!! */
+#define CONFIG_WLAN_IRQ 1
+
/****************************************************************************
* Included Files
****************************************************************************/
@@ -55,6 +58,25 @@
#include <nuttx/usb/usb.h>
#include <nuttx/usb/usbhost.h>
+#if defined(CONFIG_NET) && defined(CONFIG_NET_WLAN)
+
+#include <stdint.h>
+#include <stdbool.h>
+#include <time.h>
+#include <string.h>
+#include <debug.h>
+#include <wdog.h>
+#include <errno.h>
+
+#include <nuttx/irq.h>
+#include <nuttx/arch.h>
+
+#include <net/uip/uip.h>
+#include <net/uip/uip-arp.h>
+#include <net/uip/uip-arch.h>
+
+#endif /* CONFIG_NET && CONFIG_NET_WLAN */
+
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/
@@ -83,6 +105,30 @@
#define USBHOST_MAX_CREFS 0x7fff
+#if defined(CONFIG_NET) && defined(CONFIG_NET_WLAN)
+/* CONFIG_WLAN_NINTERFACES determines the number of physical interfaces
+ * that will be supported.
+ */
+
+#ifndef CONFIG_WLAN_NINTERFACES
+# define CONFIG_WLAN_NINTERFACES 1
+#endif
+
+/* TX poll delay = 1 seconds. CLK_TCK is the number of clock ticks per second */
+
+#define WLAN_WDDELAY (1*CLK_TCK)
+#define WLAN_POLLHSEC (1*2)
+
+/* TX timeout = 1 minute */
+
+#define WLAN_TXTIMEOUT (60*CLK_TCK)
+
+/* This is a helper pointer for accessing the contents of the WLAN header */
+
+#define BUF ((struct uip_eth_hdr *)wlan->wl_dev.d_buf)
+
+#endif /* CONFIG_NET && CONFIG_NET_WLAN */
+
/****************************************************************************
* Private Types
****************************************************************************/
@@ -115,6 +161,25 @@ struct usbhost_state_s
usbhost_ep_t epout; /* OUT endpoint */
};
+#if defined(CONFIG_NET) && defined(CONFIG_NET_WLAN)
+
+ /* The wlan_driver_s encapsulates all state information for a single hardware
+ * interface
+ */
+
+ struct wlan_driver_s
+ {
+ bool wl_bifup; /* true:ifup false:ifdown */
+ WDOG_ID wl_txpoll; /* TX poll timer */
+ WDOG_ID wl_txtimeout; /* TX timeout timer */
+
+ /* This holds the information visible to uIP/NuttX */
+
+ struct uip_driver_s wl_dev; /* Interface understood by uIP */
+ };
+
+#endif /* CONFIG_NET && CONFIG_NET_WLAN */
+
/****************************************************************************
* Private Function Prototypes
****************************************************************************/
@@ -172,6 +237,36 @@ static int usbhost_disconnected(FAR struct usbhost_class_s *class);
/* Driver methods -- depend upon the type of NuttX driver interface exported */
+#if defined(CONFIG_NET) && defined(CONFIG_NET_WLAN)
+
+/* Common TX logic */
+
+static int wlan_transmit(FAR struct wlan_driver_s *wlan);
+static int wlan_uiptxpoll(struct uip_driver_s *dev);
+
+/* Interrupt handling */
+
+static void wlan_receive(FAR struct wlan_driver_s *wlan);
+static void wlan_txdone(FAR struct wlan_driver_s *wlan);
+static int wlan_interrupt(int irq, FAR void *context);
+
+/* Watchdog timer expirations */
+
+static void wlan_polltimer(int argc, uint32_t arg, ...);
+static void wlan_txtimeout(int argc, uint32_t arg, ...);
+
+/* NuttX callback functions */
+
+static int wlan_ifup(struct uip_driver_s *dev);
+static int wlan_ifdown(struct uip_driver_s *dev);
+static int wlan_txavail(struct uip_driver_s *dev);
+#ifdef CONFIG_NET_IGMP
+static int wlan_addmac(struct uip_driver_s *dev, FAR const uint8_t *mac);
+static int wlan_rmmac(struct uip_driver_s *dev, FAR const uint8_t *mac);
+#endif
+
+#endif /* CONFIG_NET && CONFIG_NET_WLAN */
+
/****************************************************************************
* Private Data
****************************************************************************/
@@ -203,6 +298,12 @@ static struct usbhost_registry_s g_wlan =
static uint32_t g_devinuse;
+#if defined(CONFIG_NET) && defined(CONFIG_NET_WLAN)
+
+static struct wlan_driver_s g_wlan1[CONFIG_WLAN_NINTERFACES];
+
+#endif /* CONFIG_NET && CONFIG_NET_WLAN */
+
/****************************************************************************
* Private Functions
****************************************************************************/
@@ -1034,6 +1135,490 @@ static int usbhost_disconnected(struct usbhost_class_s *class)
return OK;
}
+#if defined(CONFIG_NET) && defined(CONFIG_NET_WLAN)
+
+/****************************************************************************
+ * Function: wlan_transmit
+ *
+ * Description:
+ * Start hardware transmission. Called either from the txdone interrupt
+ * handling or from watchdog based polling.
+ *
+ * Parameters:
+ * wlan - Reference to the driver state structure
+ *
+ * Returned Value:
+ * OK on success; a negated errno on failure
+ *
+ * Assumptions:
+ * May or may not be called from an interrupt handler. In either case,
+ * global interrupts are disabled, either explicitly or indirectly through
+ * interrupt handling logic.
+ *
+ ****************************************************************************/
+
+static int wlan_transmit(FAR struct wlan_driver_s *wlan)
+{
+ /* Verify that the hardware is ready to send another packet. If we get
+ * here, then we are committed to sending a packet; Higher level logic
+ * must have assured that there is not transmission in progress.
+ */
+
+ /* Increment statistics */
+
+ /* Send the packet: address=wlan->wl_dev.d_buf, length=wlan->wl_dev.d_len */
+
+ /* Enable Tx interrupts */
+
+ /* Setup the TX timeout watchdog (perhaps restarting the timer) */
+
+ (void)wd_start(wlan->wl_txtimeout, WLAN_TXTIMEOUT, wlan_txtimeout, 1, (uint32_t)wlan);
+ return OK;
+}
+
+/****************************************************************************
+ * Function: wlan_uiptxpoll
+ *
+ * Description:
+ * The transmitter is available, check if uIP has any outgoing packets ready
+ * to send. This is a callback from uip_poll(). uip_poll() may be called:
+ *
+ * 1. When the preceding TX packet send is complete,
+ * 2. When the preceding TX packet send timesout and the interface is reset
+ * 3. During normal TX polling
+ *
+ * Parameters:
+ * dev - Reference to the NuttX driver state structure
+ *
+ * Returned Value:
+ * OK on success; a negated errno on failure
+ *
+ * Assumptions:
+ * May or may not be called from an interrupt handler. In either case,
+ * global interrupts are disabled, either explicitly or indirectly through
+ * interrupt handling logic.
+ *
+ ****************************************************************************/
+
+static int wlan_uiptxpoll(struct uip_driver_s *dev)
+{
+ FAR struct wlan_driver_s *wlan = (FAR struct wlan_driver_s *)dev->d_private;
+
+ /* If the polling resulted in data that should be sent out on the network,
+ * the field d_len is set to a value > 0.
+ */
+
+ if (wlan->wl_dev.d_len > 0)
+ {
+ uip_arp_out(&wlan->wl_dev);
+ wlan_transmit(wlan);
+
+ /* Check if there is room in the device to hold another packet. If not,
+ * return a non-zero value to terminate the poll.
+ */
+ }
+
+ /* If zero is returned, the polling will continue until all connections have
+ * been examined.
+ */
+
+ return 0;
+}
+
+/****************************************************************************
+ * Function: wlan_receive
+ *
+ * Description:
+ * An interrupt was received indicating the availability of a new RX packet
+ *
+ * Parameters:
+ * wlan - Reference to the driver state structure
+ *
+ * Returned Value:
+ * None
+ *
+ * Assumptions:
+ * Global interrupts are disabled by interrupt handling logic.
+ *
+ ****************************************************************************/
+
+static void wlan_receive(FAR struct wlan_driver_s *wlan)
+{
+ do
+ {
+ /* Check for errors and update statistics */
+
+ /* Check if the packet is a valid size for the uIP buffer configuration */
+
+ /* Copy the data data from the hardware to wlan->wl_dev.d_buf. Set
+ * amount of data in wlan->wl_dev.d_len
+ */
+
+ /* We only accept IP packets of the configured type and ARP packets */
+
+#ifdef CONFIG_NET_IPv6
+ if (BUF->type == HTONS(UIP_ETHTYPE_IP6))
+#else
+ if (BUF->type == HTONS(UIP_ETHTYPE_IP))
+#endif
+ {
+ uip_arp_ipin(&wlan->wl_dev);
+ uip_input(&wlan->wl_dev);
+
+ /* If the above function invocation resulted in data that should be
+ * sent out on the network, the field d_len will set to a value > 0.
+ */
+
+ if (wlan->wl_dev.d_len > 0)
+ {
+ uip_arp_out(&wlan->wl_dev);
+ wlan_transmit(wlan);
+ }
+ }
+ else if (BUF->type == htons(UIP_ETHTYPE_ARP))
+ {
+ uip_arp_arpin(&wlan->wl_dev);
+
+ /* If the above function invocation resulted in data that should be
+ * sent out on the network, the field d_len will set to a value > 0.
+ */
+
+ if (wlan->wl_dev.d_len > 0)
+ {
+ wlan_transmit(wlan);
+ }
+ }
+ }
+ while (0); /* While there are more packets to be processed */
+}
+
+/****************************************************************************
+ * Function: wlan_txdone
+ *
+ * Description:
+ * An interrupt was received indicating that the last TX packet(s) is done
+ *
+ * Parameters:
+ * wlan - Reference to the driver state structure
+ *
+ * Returned Value:
+ * None
+ *
+ * Assumptions:
+ * Global interrupts are disabled by the watchdog logic.
+ *
+ ****************************************************************************/
+
+static void wlan_txdone(FAR struct wlan_driver_s *wlan)
+{
+ /* Check for errors and update statistics */
+
+ /* If no further xmits are pending, then cancel the TX timeout and
+ * disable further Tx interrupts.
+ */
+
+ wd_cancel(wlan->wl_txtimeout);
+
+ /* Then poll uIP for new XMIT data */
+
+ (void)uip_poll(&wlan->wl_dev, wlan_uiptxpoll);
+}
+
+/****************************************************************************
+ * Function: wlan_interrupt
+ *
+ * Description:
+ * Hardware interrupt handler
+ *
+ * Parameters:
+ * irq - Number of the IRQ that generated the interrupt
+ * context - Interrupt register state save info (architecture-specific)
+ *
+ * Returned Value:
+ * OK on success
+ *
+ * Assumptions:
+ *
+ ****************************************************************************/
+
+static int wlan_interrupt(int irq, FAR void *context)
+{
+ register FAR struct wlan_driver_s *wlan = &g_wlan1[0];
+
+ /* Get and clear interrupt status bits */
+
+ /* Handle interrupts according to status bit settings */
+
+ /* Check if we received an incoming packet, if so, call wlan_receive() */
+
+ wlan_receive(wlan);
+
+ /* Check is a packet transmission just completed. If so, call wlan_txdone.
+ * This may disable further Tx interrupts if there are no pending
+ * tansmissions.
+ */
+
+ wlan_txdone(wlan);
+
+ return OK;
+}
+
+/****************************************************************************
+ * Function: wlan_txtimeout
+ *
+ * Description:
+ * Our TX watchdog timed out. Called from the timer interrupt handler.
+ * The last TX never completed. Reset the hardware and start again.
+ *
+ * Parameters:
+ * argc - The number of available arguments
+ * arg - The first argument
+ *
+ * Returned Value:
+ * None
+ *
+ * Assumptions:
+ * Global interrupts are disabled by the watchdog logic.
+ *
+ ****************************************************************************/
+
+static void wlan_txtimeout(int argc, uint32_t arg, ...)
+{
+ FAR struct wlan_driver_s *wlan = (FAR struct wlan_driver_s *)arg;
+
+ /* Increment statistics and dump debug info */
+
+ /* Then reset the hardware */
+
+ /* Then poll uIP for new XMIT data */
+
+ (void)uip_poll(&wlan->wl_dev, wlan_uiptxpoll);
+}
+
+/****************************************************************************
+ * Function: wlan_polltimer
+ *
+ * Description:
+ * Periodic timer handler. Called from the timer interrupt handler.
+ *
+ * Parameters:
+ * argc - The number of available arguments
+ * arg - The first argument
+ *
+ * Returned Value:
+ * None
+ *
+ * Assumptions:
+ * Global interrupts are disabled by the watchdog logic.
+ *
+ ****************************************************************************/
+
+static void wlan_polltimer(int argc, uint32_t arg, ...)
+{
+ FAR struct wlan_driver_s *wlan = (FAR struct wlan_driver_s *)arg;
+
+ /* Check if there is room in the send another TX packet. We cannot perform
+ * the TX poll if he are unable to accept another packet for transmission.
+ */
+
+ /* If so, update TCP timing states and poll uIP for new XMIT data. Hmmm..
+ * might be bug here. Does this mean if there is a transmit in progress,
+ * we will missing TCP time state updates?
+ */
+
+ (void)uip_timer(&wlan->wl_dev, wlan_uiptxpoll, WLAN_POLLHSEC);
+
+ /* Setup the watchdog poll timer again */
+
+ (void)wd_start(wlan->wl_txpoll, WLAN_WDDELAY, wlan_polltimer, 1, arg);
+}
+
+/****************************************************************************
+ * Function: wlan_ifup
+ *
+ * Description:
+ * NuttX Callback: Bring up the WLAN interface when an IP address is
+ * provided
+ *
+ * Parameters:
+ * dev - Reference to the NuttX driver state structure
+ *
+ * Returned Value:
+ * None
+ *
+ * Assumptions:
+ *
+ ****************************************************************************/
+
+static int wlan_ifup(struct uip_driver_s *dev)
+{
+ FAR struct wlan_driver_s *wlan = (FAR struct wlan_driver_s *)dev->d_private;
+
+ ndbg("Bringing up: %d.%d.%d.%d\n",
+ dev->d_ipaddr & 0xff, (dev->d_ipaddr >> 8) & 0xff,
+ (dev->d_ipaddr >> 16) & 0xff, dev->d_ipaddr >> 24 );
+
+ /* Initialize PHYs, the WLAN interface, and setup up WLAN interrupts */
+
+ /* Set and activate a timer process */
+
+ (void)wd_start(wlan->wl_txpoll, WLAN_WDDELAY, wlan_polltimer, 1, (uint32_t)wlan);
+
+ /* Enable the WLAN interrupt */
+
+ wlan->wl_bifup = true;
+ up_enable_irq(CONFIG_WLAN_IRQ);
+ return OK;
+}
+
+/****************************************************************************
+ * Function: wlan_ifdown
+ *
+ * Description:
+ * NuttX Callback: Stop the interface.
+ *
+ * Parameters:
+ * dev - Reference to the NuttX driver state structure
+ *
+ * Returned Value:
+ * None
+ *
+ * Assumptions:
+ *
+ ****************************************************************************/
+
+static int wlan_ifdown(struct uip_driver_s *dev)
+{
+ FAR struct wlan_driver_s *wlan = (FAR struct wlan_driver_s *)dev->d_private;
+ irqstate_t flags;
+
+ /* Disable the WLAN interrupt */
+
+ flags = irqsave();
+ up_disable_irq(CONFIG_WLAN_IRQ);
+
+ /* Cancel the TX poll timer and TX timeout timers */
+
+ wd_cancel(wlan->wl_txpoll);
+ wd_cancel(wlan->wl_txtimeout);
+
+ /* Put the the EMAC is its reset, non-operational state. This should be
+ * a known configuration that will guarantee the wlan_ifup() always
+ * successfully brings the interface back up.
+ */
+
+ /* Mark the device "down" */
+
+ wlan->wl_bifup = false;
+ irqrestore(flags);
+ return OK;
+}
+
+/****************************************************************************
+ * Function: wlan_txavail
+ *
+ * Description:
+ * Driver callback invoked when new TX data is available. This is a
+ * stimulus perform an out-of-cycle poll and, thereby, reduce the TX
+ * latency.
+ *
+ * Parameters:
+ * dev - Reference to the NuttX driver state structure
+ *
+ * Returned Value:
+ * None
+ *
+ * Assumptions:
+ * Called in normal user mode
+ *
+ ****************************************************************************/
+
+static int wlan_txavail(struct uip_driver_s *dev)
+{
+ FAR struct wlan_driver_s *wlan = (FAR struct wlan_driver_s *)dev->d_private;
+ irqstate_t flags;
+
+ /* Disable interrupts because this function may be called from interrupt
+ * level processing.
+ */
+
+ flags = irqsave();
+
+ /* Ignore the notification if the interface is not yet up */
+
+ if (wlan->wl_bifup)
+ {
+ /* Check if there is room in the hardware to hold another outgoing packet. */
+
+ /* If so, then poll uIP for new XMIT data */
+
+ (void)uip_poll(&wlan->wl_dev, wlan_uiptxpoll);
+ }
+
+ irqrestore(flags);
+ return OK;
+}
+
+/****************************************************************************
+ * Function: wlan_addmac
+ *
+ * Description:
+ * NuttX Callback: Add the specified MAC address to the hardware multicast
+ * address filtering
+ *
+ * Parameters:
+ * dev - Reference to the NuttX driver state structure
+ * mac - The MAC address to be added
+ *
+ * Returned Value:
+ * None
+ *
+ * Assumptions:
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_NET_IGMP
+static int wlan_addmac(struct uip_driver_s *dev, FAR const uint8_t *mac)
+{
+ FAR struct wlan_driver_s *wlan = (FAR struct wlan_driver_s *)dev->d_private;
+
+ /* Add the MAC address to the hardware multicast routing table */
+
+ return OK;
+}
+#endif
+
+/****************************************************************************
+ * Function: wlan_rmmac
+ *
+ * Description:
+ * NuttX Callback: Remove the specified MAC address from the hardware multicast
+ * address filtering
+ *
+ * Parameters:
+ * dev - Reference to the NuttX driver state structure
+ * mac - The MAC address to be removed
+ *
+ * Returned Value:
+ * None
+ *
+ * Assumptions:
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_NET_IGMP
+static int wlan_rmmac(struct uip_driver_s *dev, FAR const uint8_t *mac)
+{
+ FAR struct wlan_driver_s *wlan = (FAR struct wlan_driver_s *)dev->d_private;
+
+ /* Add the MAC address to the hardware multicast routing table */
+
+ return OK;
+}
+#endif
+
+#endif /* CONFIG_NET && CONFIG_NET_WLAN */
+
/****************************************************************************
* Public Functions
****************************************************************************/
@@ -1063,3 +1648,89 @@ int usbhost_wlaninit(void)
return usbhost_registerclass(&g_wlan);
}
+
+#if defined(CONFIG_NET) && defined(CONFIG_NET_WLAN)
+
+/****************************************************************************
+ * Function: wlan_initialize
+ *
+ * Description:
+ * Initialize the WLAN controller and driver
+ *
+ * Parameters:
+ * intf - In the case where there are multiple EMACs, this value
+ * identifies which EMAC is to be initialized.
+ *
+ * Returned Value:
+ * OK on success; Negated errno on failure.
+ *
+ * Assumptions:
+ *
+ ****************************************************************************/
+
+int wlan_initialize(int intf)
+{
+ struct wlan_driver_s *priv;
+
+ /* Get the interface structure associated with this interface number. */
+
+ DEBUGASSERT(inf < CONFIG_WLAN_NINTERFACES);
+ priv = &g_wlan1[intf];
+
+ /* Check if a WLAN chip is recognized at its I/O base */
+
+ /* Attach the IRQ to the driver */
+
+ if (irq_attach(CONFIG_WLAN_IRQ, wlan_interrupt))
+ {
+ /* We could not attach the ISR to the the interrupt */
+
+ return -EAGAIN;
+ }
+
+ /* Initialize the driver structure */
+
+ memset(priv, 0, sizeof(struct wlan_driver_s));
+ priv->wl_dev.d_ifup = wlan_ifup; /* I/F down callback */
+ priv->wl_dev.d_ifdown = wlan_ifdown; /* I/F up (new IP address) callback */
+ priv->wl_dev.d_txavail = wlan_txavail; /* New TX data callback */
+#ifdef CONFIG_NET_IGMP
+ priv->wl_dev.d_addmac = wlan_addmac; /* Add multicast MAC address */
+ priv->wl_dev.d_rmmac = wlan_rmmac; /* Remove multicast MAC address */
+#endif
+ priv->wl_dev.d_private = (void*)g_wlan1; /* Used to recover private state from dev */
+
+ /* Create a watchdog for timing polling for and timing of transmisstions */
+
+ priv->wl_txpoll = wd_create(); /* Create periodic poll timer */
+ priv->wl_txtimeout = wd_create(); /* Create TX timeout timer */
+
+ /* Put the interface in the down state. This usually amounts to resetting
+ * the device and/or calling wlan_ifdown().
+ */
+
+ /* Read the MAC address from the hardware into priv->wl_dev.d_mac.ether_addr_octet */
+
+ /* Register the device with the OS so that socket IOCTLs can be performed */
+
+ (void)netdev_register(&priv->wl_dev);
+ return OK;
+}
+
+/****************************************************************************
+ * Name: up_netinitialize
+ *
+ * Description:
+ * Initialize the first network interface. If there are more than one
+ * interface in the device, then device-specific logic will have to provide
+ * this function to determine which, if any, WLAN controllers should
+ * be initialized.
+ *
+ ****************************************************************************/
+
+void up_netinitialize(void)
+{
+ (void)wlan_initialize(0);
+}
+#endif /* CONFIG_NET && CONFIG_NET_WLAN */
+