summaryrefslogtreecommitdiff
path: root/nuttx/configs
diff options
context:
space:
mode:
authorGregory Nutt <gnutt@nuttx.org>2014-10-24 12:28:57 -0600
committerGregory Nutt <gnutt@nuttx.org>2014-10-24 12:28:57 -0600
commit96fcf48a5a892b575eb7ad059d12fb38bd3e1a38 (patch)
tree3d8843a43aa69d345d077c196a87756b03076da3 /nuttx/configs
parentffee5206c96f0f5bcaf4d8fc180ddb5f051f22f3 (diff)
downloadpx4-nuttx-96fcf48a5a892b575eb7ad059d12fb38bd3e1a38.tar.gz
px4-nuttx-96fcf48a5a892b575eb7ad059d12fb38bd3e1a38.tar.bz2
px4-nuttx-96fcf48a5a892b575eb7ad059d12fb38bd3e1a38.zip
SAM4E-EK: Add support for PHY insterrupt
Diffstat (limited to 'nuttx/configs')
-rw-r--r--nuttx/configs/sam4e-ek/include/board.h1
-rw-r--r--nuttx/configs/sam4e-ek/src/Makefile4
-rw-r--r--nuttx/configs/sam4e-ek/src/sam4e-ek.h23
-rw-r--r--nuttx/configs/sam4e-ek/src/sam_boot.c12
-rw-r--r--nuttx/configs/sam4e-ek/src/sam_ethernet.c271
5 files changed, 309 insertions, 2 deletions
diff --git a/nuttx/configs/sam4e-ek/include/board.h b/nuttx/configs/sam4e-ek/include/board.h
index cf16d045b..68e74a3f5 100644
--- a/nuttx/configs/sam4e-ek/include/board.h
+++ b/nuttx/configs/sam4e-ek/include/board.h
@@ -44,6 +44,7 @@
#ifndef __ASSEMBLY__
# include <stdint.h>
+# include <stdbool.h>
# ifdef CONFIG_SAM34_GPIO_IRQ
# include <arch/irq.h>
# endif
diff --git a/nuttx/configs/sam4e-ek/src/Makefile b/nuttx/configs/sam4e-ek/src/Makefile
index aee81f4d9..8c28707f6 100644
--- a/nuttx/configs/sam4e-ek/src/Makefile
+++ b/nuttx/configs/sam4e-ek/src/Makefile
@@ -64,6 +64,10 @@ endif
endif
endif
+ifeq ($(CONFIG_SAM34_EMAC),y)
+CSRCS += sam_ethernet.c
+endif
+
ifeq ($(CONFIG_INPUT_ADS7843E),y)
CSRCS += sam_ads7843e.c
endif
diff --git a/nuttx/configs/sam4e-ek/src/sam4e-ek.h b/nuttx/configs/sam4e-ek/src/sam4e-ek.h
index a5430ec5d..25184e589 100644
--- a/nuttx/configs/sam4e-ek/src/sam4e-ek.h
+++ b/nuttx/configs/sam4e-ek/src/sam4e-ek.h
@@ -59,6 +59,7 @@
#define HAVE_AT25 1
#define HAVE_USBDEV 1
#define HAVE_USBMONITOR 1
+#define HAVE_NETWORK 1
/* HSMCI */
/* Can't support MMC/SD if the card interface is not enabled */
@@ -133,6 +134,12 @@
# undef HAVE_USBMONITOR
#endif
+/* Networking */
+
+#if !defined(CONFIG_NET) || !defined(CONFIG_SAM34_EMAC)
+# undef HAVE_NETWORK
+#endif
+
/* SAM4E-EK GPIO Pin Definitions ****************************************************/
/* LCD:
@@ -243,8 +250,8 @@
/* Ethernet MAC. The PHY interrupt is available on pin PD28 */
-#define GPIO_PHY_IRQ (GPIO_INPUT | GPIO_CFG_PULLUP | GPIO_INT_BOTHEDGES | \
- GPIO_PORT_PIOD | GPIO_PIN28)
+#define GPIO_PHY_IRQ (GPIO_INPUT | GPIO_CFG_PULLUP | GPIO_CFG_DEGLITCH | \
+ GPIO_INT_FALLING | GPIO_PORT_PIOD | GPIO_PIN28)
#define SAM_PHY_IRQ SAM_IRQ_PD28
/* LEDs
@@ -398,6 +405,18 @@ int sam_hsmci_initialize(int minor);
#endif
/************************************************************************************
+ * Name: sam_netinitialize
+ *
+ * Description:
+ * Configure board resources to support networking.
+ *
+ ************************************************************************************/
+
+#ifdef HAVE_NETWORK
+void weak_function sam_netinitialize(void);
+#endif
+
+/************************************************************************************
* Name: sam_cardinserted
*
* Description:
diff --git a/nuttx/configs/sam4e-ek/src/sam_boot.c b/nuttx/configs/sam4e-ek/src/sam_boot.c
index ac7562f18..9145cf9e9 100644
--- a/nuttx/configs/sam4e-ek/src/sam_boot.c
+++ b/nuttx/configs/sam4e-ek/src/sam_boot.c
@@ -110,6 +110,18 @@ void sam_boardinitialize(void)
}
#endif
+ /* Configure board resources to support networkingif the 1) networking is enabled,
+ * 2) the EMAC module is enabled, and 2) the weak function sam_netinitialize()
+ * has been brought into the build.
+ */
+
+#ifdef HAVE_NETWORK
+ if (sam_netinitialize)
+ {
+ sam_netinitialize();
+ }
+#endif
+
/* Configure on-board LEDs if LED support has been selected. */
#ifdef CONFIG_ARCH_LEDS
diff --git a/nuttx/configs/sam4e-ek/src/sam_ethernet.c b/nuttx/configs/sam4e-ek/src/sam_ethernet.c
new file mode 100644
index 000000000..ea50d6296
--- /dev/null
+++ b/nuttx/configs/sam4e-ek/src/sam_ethernet.c
@@ -0,0 +1,271 @@
+/************************************************************************************
+ * configs/sam4e-ek/src/sam_ethernet.c
+ *
+ * Copyright (C) 2014 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * 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 NuttX 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.
+ *
+ ************************************************************************************/
+
+/************************************************************************************
+ * Included Files
+ ************************************************************************************/
+
+#include <nuttx/config.h>
+
+/* Force verbose debug on in this file only to support unit-level testing. */
+
+#ifdef CONFIG_NETDEV_PHY_DEBUG
+# undef CONFIG_DEBUG_VERBOSE
+# define CONFIG_DEBUG_VERBOSE 1
+# undef CONFIG_DEBUG_NET
+# define CONFIG_DEBUG_NET 1
+#endif
+
+#include <string.h>
+#include <assert.h>
+#include <debug.h>
+
+#include <nuttx/irq.h>
+#include <nuttx/arch.h>
+
+#include "sam_gpio.h"
+#include "sam_emac.h"
+
+#include "sam4e-ek.h"
+
+#ifdef HAVE_NETWORK
+
+/************************************************************************************
+ * Pre-processor Definitions
+ ************************************************************************************/
+
+#define SAM34_EMAC_DEVNAME "eth0"
+
+/* Debug ********************************************************************/
+/* Extra, in-depth debug output that is only available if
+ * CONFIG_NETDEV_PHY_DEBUG us defined.
+ */
+
+#ifdef CONFIG_NETDEV_PHY_DEBUG
+# define phydbg dbg
+# define phylldbg lldbg
+#else
+# define phydbg(x...)
+# define phylldbg(x...)
+#endif
+
+/************************************************************************************
+ * Private Data
+ ************************************************************************************/
+
+#ifdef CONFIG_SAM34_GPIOD_IRQ
+static xcpt_t g_emac_handler;
+#endif
+
+/************************************************************************************
+ * Private Functions
+ ************************************************************************************/
+
+/************************************************************************************
+ * Name: sam_emac_phy_enable and sam_gmac_enable
+ ************************************************************************************/
+
+#ifdef CONFIG_SAM34_GPIOD_IRQ
+static void sam_emac_phy_enable(bool enable)
+{
+ phydbg("IRQ%d: enable=%d\n", SAM_PHY_IRQ, enable);
+ if (enable)
+ {
+ sam_gpioirqenable(SAM_PHY_IRQ);
+ }
+ else
+ {
+ sam_gpioirqdisable(SAM_PHY_IRQ);
+ }
+}
+#endif
+
+/************************************************************************************
+ * Public Functions
+ ************************************************************************************/
+
+/************************************************************************************
+ * Name: sam_netinitialize
+ *
+ * Description:
+ * Configure board resources to support networking.
+ *
+ ************************************************************************************/
+
+void weak_function sam_netinitialize(void)
+{
+ phydbg("Configuring %08x\n", GPIO_PHY_IRQ);
+ sam_configgpio(GPIO_PHY_IRQ);
+}
+
+/****************************************************************************
+ * Name: arch_phy_irq
+ *
+ * Description:
+ * This function may be called to register an interrupt handler that will
+ * be called when a PHY interrupt occurs. This function both attaches
+ * the interrupt handler and enables the interrupt if 'handler' is non-
+ * NULL. If handler is NULL, then the interrupt is detached and disabled
+ * instead.
+ *
+ * The PHY interrupt is always disabled upon return. The caller must
+ * call back through the enable function point to control the state of
+ * the interrupt.
+ *
+ * This interrupt may or may not be available on a given platform depending
+ * on how the network hardware architecture is implemented. In a typical
+ * case, the PHY interrupt is provided to board-level logic as a GPIO
+ * interrupt (in which case this is a board-specific interface and really
+ * should be called board_phy_irq()); In other cases, the PHY interrupt
+ * may be cause by the chip's MAC logic (in which case arch_phy_irq()) is
+ * an appropriate name. Other other boards, there may be no PHY interrupts
+ * available at all. If client attachable PHY interrupts are available
+ * from the board or from the chip, then CONFIG_ARCH_PHY_INTERRUPT should
+ * be defined to indicate that fact.
+ *
+ * Typical usage:
+ * a. OS service logic (not application logic*) attaches to the PHY
+ * PHY interrupt and enables the PHY interrupt.
+ * b. When the PHY interrupt occurs: (1) the interrupt should be
+ * disabled and () work should be scheduled on the worker thread (or
+ * perhaps a dedicated application thread).
+ * c. That worker thread should use the SIOCGMIIPHY, SIOCGMIIREG,
+ * and SIOCSMIIREG ioctl calls** to communicate with the PHY,
+ * determine what network event took place (Link Up/Down?), and
+ * take the appropriate actions.
+ * d. It should then interact the the PHY to clear any pending
+ * interrupts, then re-enable the PHY interrupt.
+ *
+ * * This is an OS internal interface and should not be used from
+ * application space. Rather applications should use the SIOCMIISIG
+ * ioctl to receive a signal when a PHY event occurs.
+ * ** This interrupt is really of no use if the Ethernet MAC driver
+ * does not support these ioctl calls.
+ *
+ * Input Parameters:
+ * intf - Identifies the network interface. For example "eth0". Only
+ * useful on platforms that support multiple Ethernet interfaces
+ * and, hence, multiple PHYs and PHY interrupts.
+ * handler - The client interrupt handler to be invoked when the PHY
+ * asserts an interrupt. Must reside in OS space, but can
+ * signal tasks in user space. A value of NULL can be passed
+ * in order to detach and disable the PHY interrupt.
+ * enable - A function pointer that be unsed to enable or disable the
+ * PHY interrupt.
+ *
+ * Returned Value:
+ * The previous PHY interrupt handler address is returned. This allows you
+ * to temporarily replace an interrupt handler, then restore the original
+ * interrupt handler. NULL is returned if there is was not handler in
+ * place when the call was made.
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_SAM34_GPIOD_IRQ
+xcpt_t arch_phy_irq(FAR const char *intf, xcpt_t handler, phy_enable_t *enable)
+{
+ irqstate_t flags;
+ xcpt_t *phandler;
+ xcpt_t oldhandler;
+ gpio_pinset_t pinset;
+ phy_enable_t enabler;
+ int irq;
+
+ DEBUGASSERT(intf);
+
+ nvdbg("%s: handler=%p\n", intf, handler);
+ phydbg("EMAC: devname=%s\n", SAM34_EMAC_DEVNAME);
+
+ if (strcmp(intf, SAM34_EMAC_DEVNAME) == 0)
+ {
+ phydbg("Select EMAC\n");
+ phandler = &g_emac_handler;
+ pinset = GPIO_PHY_IRQ;
+ irq = SAM_PHY_IRQ;
+ enabler = sam_emac_phy_enable;
+ }
+ else
+ {
+ ndbg("Unsupported interface: %s\n", intf);
+ return NULL;
+ }
+
+ /* Disable interrupts until we are done. This guarantees that the
+ * following operations are atomic.
+ */
+
+ flags = irqsave();
+
+ /* Get the old interrupt handler and save the new one */
+
+ oldhandler = *phandler;
+ *phandler = handler;
+
+ /* Configure the interrupt */
+
+ if (handler)
+ {
+ phydbg("Configure pin: %08x\n", pinset);
+ sam_gpioirq(pinset);
+
+ phydbg("Attach IRQ%d\n", irq);
+ (void)irq_attach(irq, handler);
+ }
+ else
+ {
+ phydbg("Detach IRQ%d\n", irq);
+ (void)irq_detach(irq);
+ enabler = NULL;
+ }
+
+ /* Return with the interrupt disabled in either case */
+
+ sam_gpioirqdisable(irq);
+
+ /* Return the enabling function pointer */
+
+ if (enable)
+ {
+ *enable = enabler;
+ }
+
+ /* Return the old handler (so that it can be restored) */
+
+ irqrestore(flags);
+ return oldhandler;
+}
+#endif /* CONFIG_SAM34_GPIOD_IRQ */
+
+#endif /* HAVE_NETWORK */