summaryrefslogtreecommitdiff
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2010-04-26 12:46:08 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2010-04-26 12:46:08 +0000
commitc4781fbb89f25eb857444208f1a55744db5e94d8 (patch)
tree304beed701d858193fb3f36a467918e48df1744c
parent6ea7df6026967e9da744c3f9018de5dbb6d724f4 (diff)
downloadpx4-nuttx-c4781fbb89f25eb857444208f1a55744db5e94d8.tar.gz
px4-nuttx-c4781fbb89f25eb857444208f1a55744db5e94d8.tar.bz2
px4-nuttx-c4781fbb89f25eb857444208f1a55744db5e94d8.zip
Add ENC28J60 work queue logic
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@2632 42af7a65-404d-4744-a932-0658087f49c3
-rwxr-xr-xnuttx/drivers/net/enc28j60.c107
-rw-r--r--nuttx/drivers/net/skeleton.c4
2 files changed, 90 insertions, 21 deletions
diff --git a/nuttx/drivers/net/enc28j60.c b/nuttx/drivers/net/enc28j60.c
index ad828c43b..1ff4846da 100755
--- a/nuttx/drivers/net/enc28j60.c
+++ b/nuttx/drivers/net/enc28j60.c
@@ -56,6 +56,7 @@
#include <nuttx/irq.h>
#include <nuttx/arch.h>
#include <nuttx/spi.h>
+#include <nuttx/wqueue.h>
#include <net/uip/uip.h>
#include <net/uip/uip-arp.h>
@@ -73,7 +74,8 @@
* defaults will be provided.
*
* CONFIG_ENC28J60_OWNBUS - Set if the ENC28J60 is the only active device on
- * the SPI bus.
+ * the SPI bus. No locking or SPI configuration will be performed. All
+ * transfers will be performed from the ENC2J60 interrupt handler.
* CONFIG_ENC28J60_SPIMODE - Controls the SPI mode
* CONFIG_ENC28J60_FREQUENCY - Define to use a different bus frequency
* CONFIG_ENC28J60_NINTERFACES - Specifies the number of physical ENC28J60
@@ -92,6 +94,12 @@
# define CONFIG_ENC28J60_NINTERFACES 1
#endif
+/* We need to have the work queue to handle SPI interrupts */
+
+#if !defined(CONFIG_SCHED_WORKQUEUE) && !defined(CONFIG_ENC28J60_OWNBUS)
+# error "Worker thread support is required (CONFIG_SCHED_WORKQUEUE)"
+#endif
+
/* Timing *******************************************************************/
/* TX poll deley = 1 seconds. CLK_TCK is the number of clock ticks per second */
@@ -128,11 +136,25 @@
struct enc28j60_driver_s
{
- bool bifup; /* true:ifup false:ifdown */
- uint8_t bank; /* Currently selected bank */
- uint16_t nextpkt; /* Next packet address */
- WDOG_ID txpoll; /* TX poll timer */
- WDOG_ID txtimeout; /* TX timeout timer */
+ /* Device control */
+
+ bool bifup; /* true:ifup false:ifdown */
+ uint8_t bank; /* Currently selected bank */
+ uint16_t nextpkt; /* Next packet address */
+ int irq; /* GPIO IRQ configured for the ENC28J60 */
+
+ /* Timing */
+
+ WDOG_ID txpoll; /* TX poll timer */
+ WDOG_ID txtimeout; /* TX timeout timer */
+
+ /* We we don't own the SPI bus, then we cannot do SPI accesses from the
+ * interrupt handler.
+ */
+
+#ifndef CONFIG_ENC28J60_OWNBUS
+ struct work_s work; /* Work queue support */
+#endif
/* This is the contained SPI driver intstance */
@@ -140,7 +162,7 @@ struct enc28j60_driver_s
/* This holds the information visible to uIP/NuttX */
- struct uip_driver_s dev; /* Interface understood by uIP */
+ struct uip_driver_s dev; /* Interface understood by uIP */
};
/****************************************************************************
@@ -192,6 +214,7 @@ static int enc28j60_uiptxpoll(struct uip_driver_s *dev);
static void enc28j60_receive(FAR struct enc28j60_driver_s *priv);
static void enc28j60_txdone(FAR struct enc28j60_driver_s *priv);
+static void enc28j60_worker(FAR void *arg);
static int enc28j60_interrupt(int irq, FAR void *context);
/* Watchdog timer expirations */
@@ -750,25 +773,27 @@ static void enc28j60_txdone(FAR struct enc28j60_driver_s *priv)
}
/****************************************************************************
- * Function: enc28j60_interrupt
+ * Function: enc28j60_worker
*
* Description:
- * Hardware interrupt handler
+ * Perform interrupt handling logic outside of the interrupt handler (on
+ * the work queue thread).
*
* Parameters:
- * irq - Number of the IRQ that generated the interrupt
- * context - Interrupt register state save info (architecture-specific)
+ * arg - The reference to the driver structure (case to void*)
*
* Returned Value:
- * OK on success
+ * None
*
* Assumptions:
*
****************************************************************************/
-static int enc28j60_interrupt(int irq, FAR void *context)
+static void enc28j60_worker(FAR void *arg)
{
- register FAR struct enc28j60_driver_s *priv = &g_enc28j60[0];
+ FAR struct enc28j60_driver_s *priv = (FAR struct enc28j60_driver_s *)arg;
+
+ DEBUGASSERT(priv);
/* Disable Ethernet interrupts */
@@ -787,8 +812,49 @@ static int enc28j60_interrupt(int irq, FAR void *context)
/* Enable Ethernet interrupts (perhaps excluding the TX done interrupt if
* there are no pending transmissions.
*/
+}
+/****************************************************************************
+ * Function: enc28j60_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 enc28j60_interrupt(int irq, FAR void *context)
+{
+ register FAR struct enc28j60_driver_s *priv = &g_enc28j60[0];
+
+ DEBUGASSERT(priv->irq == irq);
+
+#ifdef CONFIG_ENC28J60_OWNBUS
+ /* In very simple environments, we own the SPI and can do data transfers
+ * from the interrupt handler. That is actually a very bad idea in any
+ * case because it keeps interrupts disabled for a long time.
+ */
+
+ enc28j60_worker((FAR void*)priv);
return OK;
+#else
+ /* In complex environments, we cannot do SPI transfers from the interrupt
+ * handler because semaphores are probably used to lock the SPI bus. In
+ * this case, we will defer processing to the worker thread. This is also
+ * much kinder in the use of system resources and is, therefore, probably
+ * a good thing to do in any event.
+ */
+
+ return work_queue(&priv->work, enc28j60_worker, (FAR void *)priv, 0);
+#endif
}
/****************************************************************************
@@ -888,7 +954,7 @@ static int enc28j60_ifup(struct uip_driver_s *dev)
/* Enable the Ethernet interrupt */
priv->bifup = true;
- up_enable_irq(CONFIG_ENC28J60_IRQ);
+ up_enable_irq(priv->irq);
return OK;
}
@@ -916,7 +982,7 @@ static int enc28j60_ifdown(struct uip_driver_s *dev)
/* Disable the Ethernet interrupt */
flags = irqsave();
- up_disable_irq(CONFIG_ENC28J60_IRQ);
+ up_disable_irq(priv->irq);
/* Cancel the TX poll timer and TX timeout timers */
@@ -983,7 +1049,9 @@ static int enc28j60_txavail(struct uip_driver_s *dev)
* Initialize the Ethernet driver
*
* Parameters:
- * None
+ * spi - A reference to the platform's SPI driver for the ENC28J60
+ * irq - The fully configured GPIO IRQ that ENC28J60 interrupts will be
+ * asserted on. This driver will attach and entable this IRQ.
*
* Returned Value:
* OK on success; Negated errno on failure.
@@ -994,7 +1062,7 @@ static int enc28j60_txavail(struct uip_driver_s *dev)
/* Initialize the Ethernet controller and driver */
-int enc28j60_initialize(FAR struct spi_dev_s *spi)
+int enc28j60_initialize(FAR struct spi_dev_s *spi, int irq)
{
/* Initialize and configure the ENC28J60 */
@@ -1011,10 +1079,11 @@ int enc28j60_initialize(FAR struct spi_dev_s *spi)
g_enc28j60[0].txpoll = wd_create(); /* Create periodic poll timer */
g_enc28j60[0].txtimeout = wd_create(); /* Create TX timeout timer */
g_enc28j60[0].spi = spi; /* Save the SPI instance */
+ g_enc28j60[0].irq = irq; /* Save the IRQ number */
/* Attach the IRQ to the driver */
- if (irq_attach(CONFIG_ENC28J60_IRQ, enc28j60_interrupt))
+ if (irq_attach(irq, enc28j60_interrupt))
{
/* We could not attach the ISR to the interrupt */
diff --git a/nuttx/drivers/net/skeleton.c b/nuttx/drivers/net/skeleton.c
index a9621edd8..00ec39334 100644
--- a/nuttx/drivers/net/skeleton.c
+++ b/nuttx/drivers/net/skeleton.c
@@ -38,7 +38,7 @@
****************************************************************************/
#include <nuttx/config.h>
-#if defined(CONFIG_NET) && defined(CONFIG_skeleton_NET)
+#if defined(CONFIG_NET) && defined(CONFIG_NET_skeleton)
#include <stdint.h>
#include <stdbool.h>
@@ -590,4 +590,4 @@ int skel_initialize(void)
return OK;
}
-#endif /* CONFIG_NET && CONFIG_skeleton_NET */
+#endif /* CONFIG_NET && CONFIG_NET_skeleton */