summaryrefslogtreecommitdiff
diff options
context:
space:
mode:
authorGregory Nutt <gnutt@nuttx.org>2013-09-14 08:19:36 -0600
committerGregory Nutt <gnutt@nuttx.org>2013-09-14 08:19:36 -0600
commit06bf997730c96a77095d8beb789577a376856c4e (patch)
treeb7b9dfa0ca260bba9f623f9b3c767ac2de19cb97
parent7581dba539fa936ae5ebc9c91e34553118b8a51a (diff)
downloadpx4-nuttx-06bf997730c96a77095d8beb789577a376856c4e.tar.gz
px4-nuttx-06bf997730c96a77095d8beb789577a376856c4e.tar.bz2
px4-nuttx-06bf997730c96a77095d8beb789577a376856c4e.zip
SAMA5: Update Ethernet initalization logic to handle both EMAC and GMAC
-rw-r--r--nuttx/arch/arm/src/sama5/sam_emac.c54
-rw-r--r--nuttx/arch/arm/src/sama5/sam_emac.h51
-rw-r--r--nuttx/arch/arm/src/sama5/sam_eth.c116
3 files changed, 167 insertions, 54 deletions
diff --git a/nuttx/arch/arm/src/sama5/sam_emac.c b/nuttx/arch/arm/src/sama5/sam_emac.c
index 5fd112285..25a24056b 100644
--- a/nuttx/arch/arm/src/sama5/sam_emac.c
+++ b/nuttx/arch/arm/src/sama5/sam_emac.c
@@ -1,5 +1,5 @@
/****************************************************************************
- * arch/arm/src/sama5/sam_eth.c
+ * arch/arm/src/sama5/sam_emac.c
*
* Copyright (C) 2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
@@ -2102,7 +2102,7 @@ static int sam_phyinit(FAR struct sam_emac_s *priv)
/* Perform any necessary, board-specific PHY initialization */
#ifdef CONFIG_SAMA5_PHYINIT
- ret = sam_phy_boardinitialize(0);
+ ret = sam_phy_boardinitialize(EMAC_INTF);
if (ret < 0)
{
ndbg("Failed to initialize the PHY: %d\n", ret);
@@ -2674,34 +2674,32 @@ static int sam_ethconfig(FAR struct sam_emac_s *priv)
}
/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
* Function: sam_emac_initialize
*
* Description:
- * Initialize the Ethernet driver for one interface. If the SAMA5 chip
- * supports multiple Ethernet controllers, then board specific logic
- * must implement up_netinitialize() and call this function to initialize
- * the desired interfaces.
+ * Initialize the EMAC driver.
*
- * Parameters:
- * intf - In the case where there are multiple EMACs, this value
- * identifies which EMAC is to be initialized.
+ * Input Parameters:
+ * None
*
* Returned Value:
* OK on success; Negated errno on failure.
*
* Assumptions:
+ * Called very early in the initialization sequence.
*
****************************************************************************/
-static inline int sam_emac_initialize(int intf)
+int sam_emac_initialize(void)
{
struct sam_emac_s *priv;
- nvdbg("intf: %d\n", intf);
-
/* Get the interface structure associated with this interface number. */
- DEBUGASSERT(intf == 0);
priv = &g_emac;
/* Initialize the driver structure */
@@ -2743,33 +2741,3 @@ static inline int sam_emac_initialize(int intf)
(void)netdev_register(&priv->dev);
return OK;
}
-
-/****************************************************************************
- * Public Functions
- ****************************************************************************/
-
-/****************************************************************************
- * Function: up_netinitialize
- *
- * Description:
- * This is the "standard" network initialization logic called from the
- * low-level initialization logic in up_initialize.c. If both the EMAC
- * and GMAC are enabled, then this single entry point must initialize
- * both.
- *
- * Parameters:
- * None.
- *
- * Returned Value:
- * None.
- *
- * Assumptions:
- *
- ****************************************************************************/
-
-void up_netinitialize(void)
-{
- (void)sam_emac_initialize();
-}
-
-#endif /* CONFIG_NET && CONFIG_SAMA5_EMAC */
diff --git a/nuttx/arch/arm/src/sama5/sam_emac.h b/nuttx/arch/arm/src/sama5/sam_emac.h
index df71da4b8..31b73ee25 100644
--- a/nuttx/arch/arm/src/sama5/sam_emac.h
+++ b/nuttx/arch/arm/src/sama5/sam_emac.h
@@ -45,12 +45,20 @@
#include "chip.h"
#include "chip/sam_emac.h"
-#ifndef __ASSEMBLY__
+/************************************************************************************
+ * Pre-processor Definitions
+ ************************************************************************************/
+/* Definitions for use with sam_phy_boardinitialize */
+
+#define GMAC_INTF 0
+#define EMAC_INTF 1
/************************************************************************************
* Public Functions
************************************************************************************/
+#ifndef __ASSEMBLY__
+
#undef EXTERN
#if defined(__cplusplus)
#define EXTERN extern "C"
@@ -59,26 +67,47 @@ extern "C" {
#define EXTERN extern
#endif
-/************************************************************************************
- * Function: sam_ethinitialize
+/****************************************************************************
+ * Function: sam_gmac_initialize
*
* Description:
- * Initialize the Ethernet driver for one interface. If the STM32 chip supports
- * multiple Ethernet controllers, then board specific logic must implement
- * up_netinitialize() and call this function to initialize the desired interfaces.
+ * Initialize the GMAC driver.
*
- * Parameters:
- * intf - In the case where there are multiple EMACs, this value identifies which
- * EMAC is to be initialized.
+ * Input Parameters:
+ * None
*
* Returned Value:
* OK on success; Negated errno on failure.
*
* Assumptions:
+ * Called very early in the initialization sequence.
*
- ************************************************************************************/
+ ****************************************************************************/
+
+#ifdef CONFIG_SAMA5_GMAC
+int sam_gmac_initialize(void);
+#endif
-int sam_ethinitialize(int intf);
+/****************************************************************************
+ * Function: sam_emac_initialize
+ *
+ * Description:
+ * Initialize the EMAC driver.
+ *
+ * Input Parameters:
+ * None
+ *
+ * Returned Value:
+ * OK on success; Negated errno on failure.
+ *
+ * Assumptions:
+ * Called very early in the initialization sequence.
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_SAMA5_EMAC
+int sam_emac_initialize(void);
+#endif
/************************************************************************************
* Function: sam_phy_boardinitialize
diff --git a/nuttx/arch/arm/src/sama5/sam_eth.c b/nuttx/arch/arm/src/sama5/sam_eth.c
new file mode 100644
index 000000000..6db12bd93
--- /dev/null
+++ b/nuttx/arch/arm/src/sama5/sam_eth.c
@@ -0,0 +1,116 @@
+/****************************************************************************
+ * arch/arm/src/sama5/sam_eth.c
+ *
+ * Copyright (C) 2013 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>
+#include <debug.h>
+#include "sam_emac.h"
+
+#ifdef CONFIG_NET
+
+/****************************************************************************
+ * Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Types
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Function Prototypes
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Function: up_netinitialize
+ *
+ * Description:
+ * This is the "standard" network initialization logic called from the
+ * low-level initialization logic in up_initialize.c. If both the EMAC
+ * and GMAC are enabled, then this single entry point must initialize
+ * both.
+ *
+ * Parameters:
+ * None.
+ *
+ * Returned Value:
+ * None.
+ *
+ * Assumptions:
+ *
+ ****************************************************************************/
+
+void up_netinitialize(void)
+{
+ /* Initialize the GMAC driver */
+
+#ifdef CONFIG_SAMA5_GMAC
+ ret = sam_gmac_initialize();
+ if (ret < 0)
+ {
+ nlldbg("ERROR: sam_gmac_initialize failed: %d\n", ret);
+ return ret;
+ }
+#endif
+
+/* Initialize the EMAC driver */
+
+#ifdef CONFIG_SAMA5_EMAC
+ ret = sam_emac_initialize();
+ if (ret < 0)
+ {
+ nlldbg("ERROR: sam_gmac_initialize failed: %d\n", ret);
+ return ret;
+ }
+#endif
+
+ return OK;
+}
+
+#endif /* CONFIG_NET && CONFIG_SAMA5_EMAC */