summaryrefslogtreecommitdiff
path: root/nuttx/arch/arm
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2011-12-08 22:14:48 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2011-12-08 22:14:48 +0000
commit3e02e3c3b0b44da40a0fabca761d251c8846a065 (patch)
treea72d271c6bc54f842d780161f6658cb5af8a9750 /nuttx/arch/arm
parent63f6daa6c3b6988e24bacfcb5145995ed20f2994 (diff)
downloadpx4-nuttx-3e02e3c3b0b44da40a0fabca761d251c8846a065.tar.gz
px4-nuttx-3e02e3c3b0b44da40a0fabca761d251c8846a065.tar.bz2
px4-nuttx-3e02e3c3b0b44da40a0fabca761d251c8846a065.zip
Add Ethernet pin/clock configuration logic
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@4148 42af7a65-404d-4744-a932-0658087f49c3
Diffstat (limited to 'nuttx/arch/arm')
-rw-r--r--nuttx/arch/arm/src/stm32/chip/stm32f40xxx_pinmap.h86
-rw-r--r--nuttx/arch/arm/src/stm32/chip/stm32f40xxx_rcc.h10
-rw-r--r--nuttx/arch/arm/src/stm32/stm32.h4
-rwxr-xr-xnuttx/arch/arm/src/stm32/stm32_eth.c190
-rw-r--r--nuttx/arch/arm/src/stm32/stm32_rcc.h103
-rw-r--r--nuttx/arch/arm/src/stm32/stm32_syscfg.h104
6 files changed, 428 insertions, 69 deletions
diff --git a/nuttx/arch/arm/src/stm32/chip/stm32f40xxx_pinmap.h b/nuttx/arch/arm/src/stm32/chip/stm32f40xxx_pinmap.h
index b6b21072a..cd0dbd196 100644
--- a/nuttx/arch/arm/src/stm32/chip/stm32f40xxx_pinmap.h
+++ b/nuttx/arch/arm/src/stm32/chip/stm32f40xxx_pinmap.h
@@ -126,50 +126,52 @@
#define GPIO_DCMI_VSYNC_1 (GPIO_ALT|GPIO_AF13|GPIO_PORTB|GPIO_PIN7)
#define GPIO_DCMI_VSYNC_2 (GPIO_ALT|GPIO_AF13|GPIO_PORTI|GPIO_PIN5)
+/* Clocks outputs */
+
+#define GPIO_MCO1 (GPIO_ALT|GPIO_AF0|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTA|GPIO_PIN8)
+#define GPIO_MCO2 (GPIO_ALT|GPIO_AF0|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTC|GPIO_PIN9)
+
/* Ethernet MAC */
-#define GPIO_MCO1 (GPIO_ALT|GPIO_AF0|GPIO_PORTA|GPIO_PIN8)
-#define GPIO_MCO2 (GPIO_ALT|GPIO_AF0|GPIO_PORTC|GPIO_PIN9)
-
-#define GPIO_ETH_MDC (GPIO_ALT|GPIO_AF11|GPIO_PORTC|GPIO_PIN1)
-#define GPIO_ETH_MDIO (GPIO_ALT|GPIO_AF11|GPIO_PORTA|GPIO_PIN2)
-#define GPIO_ETH_MII_COL_1 (GPIO_ALT|GPIO_AF11|GPIO_PORTA|GPIO_PIN3)
-#define GPIO_ETH_MII_COL_2 (GPIO_ALT|GPIO_AF11|GPIO_PORTH|GPIO_PIN3)
-#define GPIO_ETH_MII_CRS_1 (GPIO_ALT|GPIO_AF11|GPIO_PORTA|GPIO_PIN0)
-#define GPIO_ETH_MII_CRS_2 (GPIO_ALT|GPIO_AF11|GPIO_PORTH|GPIO_PIN2)
-#define GPIO_ETH_MII_RXD0 (GPIO_ALT|GPIO_AF11|GPIO_PORTC|GPIO_PIN4)
-#define GPIO_ETH_MII_RXD1 (GPIO_ALT|GPIO_AF11|GPIO_PORTC|GPIO_PIN5)
-#define GPIO_ETH_MII_RXD2_1 (GPIO_ALT|GPIO_AF11|GPIO_PORTB|GPIO_PIN0)
-#define GPIO_ETH_MII_RXD2_2 (GPIO_ALT|GPIO_AF11|GPIO_PORTH|GPIO_PIN6)
-#define GPIO_ETH_MII_RXD3_1 (GPIO_ALT|GPIO_AF11|GPIO_PORTB|GPIO_PIN1)
-#define GPIO_ETH_MII_RXD3_2 (GPIO_ALT|GPIO_AF11|GPIO_PORTH|GPIO_PIN7)
-#define GPIO_ETH_MII_RX_CLK (GPIO_ALT|GPIO_AF11|GPIO_PORTA|GPIO_PIN1)
-#define GPIO_ETH_MII_RX_DV (GPIO_ALT|GPIO_AF11|GPIO_PORTA|GPIO_PIN7)
-#define GPIO_ETH_MII_RX_ER_1 (GPIO_ALT|GPIO_AF11|GPIO_PORTB|GPIO_PIN10)
-#define GPIO_ETH_MII_RX_ER_2 (GPIO_ALT|GPIO_AF11|GPIO_PORTI|GPIO_PIN10)
-#define GPIO_ETH_MII_TXD0_1 (GPIO_ALT|GPIO_AF11|GPIO_PORTB|GPIO_PIN12)
-#define GPIO_ETH_MII_TXD0_2 (GPIO_ALT|GPIO_AF11|GPIO_PORTG|GPIO_PIN13)
-#define GPIO_ETH_MII_TXD1_1 (GPIO_ALT|GPIO_AF11|GPIO_PORTB|GPIO_PIN13)
-#define GPIO_ETH_MII_TXD1_2 (GPIO_ALT|GPIO_AF11|GPIO_PORTG|GPIO_PIN14)
-#define GPIO_ETH_MII_TXD2 (GPIO_ALT|GPIO_AF11|GPIO_PORTC|GPIO_PIN2)
-#define GPIO_ETH_MII_TXD3_1 (GPIO_ALT|GPIO_AF11|GPIO_PORTB|GPIO_PIN8)
-#define GPIO_ETH_MII_TXD3_2 (GPIO_ALT|GPIO_AF11|GPIO_PORTE|GPIO_PIN2)
-#define GPIO_ETH_MII_TX_CLK (GPIO_ALT|GPIO_AF11|GPIO_PORTC|GPIO_PIN3)
-#define GPIO_ETH_MII_TX_EN_1 (GPIO_ALT|GPIO_AF11|GPIO_PORTB|GPIO_PIN11)
-#define GPIO_ETH_MII_TX_EN_2 (GPIO_ALT|GPIO_AF11|GPIO_PORTG|GPIO_PIN11)
-#define GPIO_ETH_PPS_OUT_1 (GPIO_ALT|GPIO_AF11|GPIO_PORTB|GPIO_PIN5)
-#define GPIO_ETH_PPS_OUT_2 (GPIO_ALT|GPIO_AF11|GPIO_PORTG|GPIO_PIN8)
-#define GPIO_ETH_RMII_CRS_DV (GPIO_ALT|GPIO_AF11|GPIO_PORTA|GPIO_PIN7)
-#define GPIO_ETH_RMII_REF_CLK (GPIO_ALT|GPIO_AF11|GPIO_PORTA|GPIO_PIN1)
-#define GPIO_ETH_RMII_RXD0 (GPIO_ALT|GPIO_AF11|GPIO_PORTC|GPIO_PIN4)
-#define GPIO_ETH_RMII_RXD1 (GPIO_ALT|GPIO_AF11|GPIO_PORTC|GPIO_PIN5)
-#define GPIO_ETH_RMII_TXD0_1 (GPIO_ALT|GPIO_AF11|GPIO_PORTB|GPIO_PIN12)
-#define GPIO_ETH_RMII_TXD0_2 (GPIO_ALT|GPIO_AF11|GPIO_PORTG|GPIO_PIN13)
-#define GPIO_ETH_RMII_TXD1_1 (GPIO_ALT|GPIO_AF11|GPIO_PORTB|GPIO_PIN13)
-#define GPIO_ETH_RMII_TXD1_2 (GPIO_ALT|GPIO_AF11|GPIO_PORTG|GPIO_PIN14)
-#define GPIO_ETH_RMII_TX_CLK (GPIO_ALT|GPIO_AF11|GPIO_PORTC|GPIO_PIN3)
-#define GPIO_ETH_RMII_TX_EN_1 (GPIO_ALT|GPIO_AF11|GPIO_PORTB|GPIO_PIN11)
-#define GPIO_ETH_RMII_TX_EN_2 (GPIO_ALT|GPIO_AF11|GPIO_PORTG|GPIO_PIN11)
+#define GPIO_ETH_MDC (GPIO_ALT|GPIO_AF11|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTC|GPIO_PIN1)
+#define GPIO_ETH_MDIO (GPIO_ALT|GPIO_AF11|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTA|GPIO_PIN2)
+#define GPIO_ETH_MII_COL_1 (GPIO_ALT|GPIO_AF11|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTA|GPIO_PIN3)
+#define GPIO_ETH_MII_COL_2 (GPIO_ALT|GPIO_AF11|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTH|GPIO_PIN3)
+#define GPIO_ETH_MII_CRS_1 (GPIO_ALT|GPIO_AF11|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTA|GPIO_PIN0)
+#define GPIO_ETH_MII_CRS_2 (GPIO_ALT|GPIO_AF11|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTH|GPIO_PIN2)
+#define GPIO_ETH_MII_RXD0 (GPIO_ALT|GPIO_AF11|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTC|GPIO_PIN4)
+#define GPIO_ETH_MII_RXD1 (GPIO_ALT|GPIO_AF11|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTC|GPIO_PIN5)
+#define GPIO_ETH_MII_RXD2_1 (GPIO_ALT|GPIO_AF11|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTB|GPIO_PIN0)
+#define GPIO_ETH_MII_RXD2_2 (GPIO_ALT|GPIO_AF11|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTH|GPIO_PIN6)
+#define GPIO_ETH_MII_RXD3_1 (GPIO_ALT|GPIO_AF11|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTB|GPIO_PIN1)
+#define GPIO_ETH_MII_RXD3_2 (GPIO_ALT|GPIO_AF11|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTH|GPIO_PIN7)
+#define GPIO_ETH_MII_RX_CLK (GPIO_ALT|GPIO_AF11|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTA|GPIO_PIN1)
+#define GPIO_ETH_MII_RX_DV (GPIO_ALT|GPIO_AF11|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTA|GPIO_PIN7)
+#define GPIO_ETH_MII_RX_ER_1 (GPIO_ALT|GPIO_AF11|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTB|GPIO_PIN10)
+#define GPIO_ETH_MII_RX_ER_2 (GPIO_ALT|GPIO_AF11|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTI|GPIO_PIN10)
+#define GPIO_ETH_MII_TXD0_1 (GPIO_ALT|GPIO_AF11|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTB|GPIO_PIN12)
+#define GPIO_ETH_MII_TXD0_2 (GPIO_ALT|GPIO_AF11|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTG|GPIO_PIN13)
+#define GPIO_ETH_MII_TXD1_1 (GPIO_ALT|GPIO_AF11|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTB|GPIO_PIN13)
+#define GPIO_ETH_MII_TXD1_2 (GPIO_ALT|GPIO_AF11|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTG|GPIO_PIN14)
+#define GPIO_ETH_MII_TXD2 (GPIO_ALT|GPIO_AF11|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTC|GPIO_PIN2)
+#define GPIO_ETH_MII_TXD3_1 (GPIO_ALT|GPIO_AF11|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTB|GPIO_PIN8)
+#define GPIO_ETH_MII_TXD3_2 (GPIO_ALT|GPIO_AF11|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTE|GPIO_PIN2)
+#define GPIO_ETH_MII_TX_CLK (GPIO_ALT|GPIO_AF11|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTC|GPIO_PIN3)
+#define GPIO_ETH_MII_TX_EN_1 (GPIO_ALT|GPIO_AF11|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTB|GPIO_PIN11)
+#define GPIO_ETH_MII_TX_EN_2 (GPIO_ALT|GPIO_AF11|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTG|GPIO_PIN11)
+#define GPIO_ETH_PPS_OUT_1 (GPIO_ALT|GPIO_AF11|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTB|GPIO_PIN5)
+#define GPIO_ETH_PPS_OUT_2 (GPIO_ALT|GPIO_AF11|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTG|GPIO_PIN8)
+#define GPIO_ETH_RMII_CRS_DV (GPIO_ALT|GPIO_AF11|GPIO_SPEED_100MHz|GPIO_PUSHPULLGPIO_PORTA|GPIO_PIN7)
+#define GPIO_ETH_RMII_REF_CLK (GPIO_ALT|GPIO_AF11|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTA|GPIO_PIN1)
+#define GPIO_ETH_RMII_RXD0 (GPIO_ALT|GPIO_AF11|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTC|GPIO_PIN4)
+#define GPIO_ETH_RMII_RXD1 (GPIO_ALT|GPIO_AF11|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTC|GPIO_PIN5)
+#define GPIO_ETH_RMII_TXD0_1 (GPIO_ALT|GPIO_AF11|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTB|GPIO_PIN12)
+#define GPIO_ETH_RMII_TXD0_2 (GPIO_ALT|GPIO_AF11|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTG|GPIO_PIN13)
+#define GPIO_ETH_RMII_TXD1_1 (GPIO_ALT|GPIO_AF11|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTB|GPIO_PIN13)
+#define GPIO_ETH_RMII_TXD1_2 (GPIO_ALT|GPIO_AF11|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTG|GPIO_PIN14)
+#define GPIO_ETH_RMII_TX_CLK (GPIO_ALT|GPIO_AF11|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTC|GPIO_PIN3)
+#define GPIO_ETH_RMII_TX_EN_1 (GPIO_ALT|GPIO_AF11|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTB|GPIO_PIN11)
+#define GPIO_ETH_RMII_TX_EN_2 (GPIO_ALT|GPIO_AF11|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTG|GPIO_PIN11)
/* Flexible Static Memory Controller (FSMC) */
diff --git a/nuttx/arch/arm/src/stm32/chip/stm32f40xxx_rcc.h b/nuttx/arch/arm/src/stm32/chip/stm32f40xxx_rcc.h
index b1e292437..4a305249b 100644
--- a/nuttx/arch/arm/src/stm32/chip/stm32f40xxx_rcc.h
+++ b/nuttx/arch/arm/src/stm32/chip/stm32f40xxx_rcc.h
@@ -179,11 +179,11 @@
#define RCC_CFGR_RTCPRE_MASK (31 << RCC_CFGR_RTCPRE)
# define RCC_CFGR_RTCPRE(n) ((n) << RCC_CFGR_RTCPRE) /* HSE/n, n=1..31 */
#define RCC_CFGR_MCO1_SHIFT (21) /* Bits 21-22: Microcontroller Clock Output */
-#define RCC_CFGR_MCO1_MASK (3 << RCC_CFGR_MCO_SHIFT)
-# define RCC_CFGR_MCO1_HSI (0 << RCC_CFGR_MCO_SHIFT) /* 00: HSI clock selected */
-# define RCC_CFGR_MCO1_LSE (1 << RCC_CFGR_MCO_SHIFT) /* 01: LSE oscillator selected */
-# define RCC_CFGR_MCO1_HSE (2 << RCC_CFGR_MCO_SHIFT) /* 10: HSE oscillator clock selected */
-# define RCC_CFGR_MCO1_PLL (3 << RCC_CFGR_MCO_SHIFT) /* 11: PLL clock selected */
+#define RCC_CFGR_MCO1_MASK (3 << RCC_CFGR_MCO1_SHIFT)
+# define RCC_CFGR_MCO1_HSI (0 << RCC_CFGR_MCO1_SHIFT) /* 00: HSI clock selected */
+# define RCC_CFGR_MCO1_LSE (1 << RCC_CFGR_MCO1_SHIFT) /* 01: LSE oscillator selected */
+# define RCC_CFGR_MCO1_HSE (2 << RCC_CFGR_MCO1_SHIFT) /* 10: HSE oscillator clock selected */
+# define RCC_CFGR_MCO1_PLL (3 << RCC_CFGR_MCO1_SHIFT) /* 11: PLL clock selected */
#define TCC_CFGR_I2SSRC (1 << 23) /* Bit 23: I2S clock selection */
#define RCC_CFGR_MCO1PRE_SHIFT (24) /* Bits 24-26: MCO1 prescaler */
#define RCC_CFGR_MCO1PRE_MASK (7 << RCC_CFGR_MCO1PRE_SHIFT)
diff --git a/nuttx/arch/arm/src/stm32/stm32.h b/nuttx/arch/arm/src/stm32/stm32.h
index 34718f5ba..1337f737b 100644
--- a/nuttx/arch/arm/src/stm32/stm32.h
+++ b/nuttx/arch/arm/src/stm32/stm32.h
@@ -2,7 +2,9 @@
* arch/arm/src/stm32/stm32.h
*
* Copyright (C) 2011 Uros Platise. All rights reserved.
- * Author: Uros Platise <uros.platise@isotel.eu>
+ * Copyright (C) 2011 Gregory Nutt. All rights reserved.
+ * Authors: Uros Platise <uros.platise@isotel.eu>
+ * Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
diff --git a/nuttx/arch/arm/src/stm32/stm32_eth.c b/nuttx/arch/arm/src/stm32/stm32_eth.c
index e432ce82b..eb372262c 100755
--- a/nuttx/arch/arm/src/stm32/stm32_eth.c
+++ b/nuttx/arch/arm/src/stm32/stm32_eth.c
@@ -55,10 +55,15 @@
#include <net/uip/uip-arp.h>
#include <net/uip/uip-arch.h>
+#include "up_internal.h"
+
#include "chip.h"
+#include "stm32_gpio.h"
+#include "stm32_rcc.h"
+#include "stm32_syscfg.h"
#include "stm32_eth.h"
-#include "up_internal.h"
+#include <arch/board/board.h>
/* STM32_NETHERNET determines the number of physical interfaces
* that will be supported.
@@ -69,8 +74,33 @@
/****************************************************************************
* Definitions
****************************************************************************/
+/* Configuration ************************************************************/
+
+#ifndef CONFIG_STM32_SYSCFG
+# error "CONFIG_STM32_SYSCFG must be defined in the NuttX configuration"
+#endif
+
+#if !defined(CONFIG_STM32_MII) && !defined(CONFIG_STM32_RMII)
+# warning "Neither CONFIG_STM32_MII nor CONFIG_STM32_RMII defined"
+#endif
+
+#if defined(CONFIG_STM32_MII) && defined(CONFIG_STM32_RMII)
+# error "Both CONFIG_STM32_MII and CONFIG_STM32_RMII defined"
+#endif
+
+#ifdef CONFIG_STM32_MII
+# if !defined(CONFIG_STM32_MII_MCO1) && !defined(CONFIG_STM32_MII_MCO2)
+# warning "Neither CONFIG_STM32_MII_MCO1 nor CONFIG_STM32_MII_MCO2 defined"
+# endif
+# if defined(CONFIG_STM32_MII_MCO1) && defined(CONFIG_STM32_MII_MCO2)
+# warning "Both CONFIG_STM32_MII_MCO1 and CONFIG_STM32_MII_MCO2 defined"
+# endif
+#endif
-/* TX poll delay = 1 seconds. CLK_TCK is the number of clock ticks per second */
+/* Timing *******************************************************************/
+/* TX poll delay = 1 seconds. CLK_TCK is the number of clock ticks per
+ * second
+ */
#define STM32_WDDELAY (1*CLK_TCK)
#define STM32_POLLHSEC (1*2)
@@ -79,7 +109,10 @@
#define STM32_TXTIMEOUT (60*CLK_TCK)
-/* This is a helper pointer for accessing the contents of the Ethernet header */
+/* Helpers ******************************************************************/
+/* This is a helper pointer for accessing the contents of the Ethernet
+ * header
+ */
#define BUF ((struct uip_eth_hdr *)priv->dev.d_buf)
@@ -138,6 +171,10 @@ static int stm32_addmac(struct uip_driver_s *dev, FAR const uint8_t *mac);
static int stm32_rmmac(struct uip_driver_s *dev, FAR const uint8_t *mac);
#endif
+/* Initialization */
+
+static inline void stm32_ethgpioconfig(FAR struct stm32_ethmac_s *priv);
+
/****************************************************************************
* Private Functions
****************************************************************************/
@@ -623,6 +660,127 @@ static int stm32_rmmac(struct uip_driver_s *dev, FAR const uint8_t *mac)
#endif
/****************************************************************************
+ * Function: stm32_ethgpioconfig
+ *
+ * Description:
+ * Configure GPIOs for the Ethernet interface.
+ *
+ * Parameters:
+ * priv - A reference to the private driver state structure
+ *
+ * Returned Value:
+ * OK on success; Negated errno on failure.
+ *
+ * Assumptions:
+ *
+ ****************************************************************************/
+
+#if STM32_NETHERNET == 1
+static inline void stm32_ethgpioconfig(FAR struct stm32_ethmac_s *priv)
+{
+ /* Configure GPIO pins to support Ethernet */
+
+#if defined(CONFIG_STM32_MII) || defined(CONFIG_STM32_RMII)
+
+ /* MDC and MDIO are common to both modes */
+
+ stm32_configgpio(GPIO_ETH_MDC);
+ stm32_configgpio(GPIO_ETH_MDIO);
+
+ /* Set up the MII interface */
+
+#if defined(CONFIG_STM32_MII)
+
+ /* Select the MII interface */
+
+ stm32_selectmii();
+
+ /* Provide clocking via MCO1 or MCO2:
+ *
+ * "MCO1 (microcontroller clock output), used to output HSI, LSE, HSE or PLL
+ * clock (through a configurable prescaler) on PA8 pin."
+ *
+ * "MCO2 (microcontroller clock output), used to output HSE, PLL, SYSCLK or
+ * PLLI2S clock (through a configurable prescaler) on PC9 pin."
+ */
+
+# warning "REVISIT: This is very board-specific"
+# if defined(CONFIG_STM32_MII_MCO1)
+ /* Configure MC01 to drive the PHY */
+
+ stm32_configgpio(GPIO_MCO1);
+
+ /* Output HSE clock (25MHz) on MCO pin (PA8) to clock the PHY */
+
+ stm32_mco1config(RCC_CFGR_MCO1_HSE, RCC_CFGR_MCO1PRE_NONE);
+
+# elif defined(CONFIG_STM32_MII_MCO2)
+ /* Configure MC02 to drive the PHY */
+
+ stm32_configgpio(GPIO_MCO2);
+
+ /* Output HSE clock (25MHz) on MCO pin (PA8) to clock the PHY */
+
+ stm32_mco2config(RCC_CFGR_MCO2_HSE, RCC_CFGR_MCO2PRE_NONE);
+# endif
+
+ /* MII interface pins (17):
+ *
+ * MII_TX_CLK, MII_TXD[3:0], MII_TX_EN, MII_RX_CLK, MII_RXD[3:0], MII_RX_ER,
+ * MII_RX_DV, MII_CRS, MII_COL, MDC, MDIO
+ */
+
+ stm32_configgpio(GPIO_ETH_MII_COL);
+ stm32_configgpio(GPIO_ETH_MII_CRS);
+ stm32_configgpio(GPIO_ETH_MII_RXD0);
+ stm32_configgpio(GPIO_ETH_MII_RXD1);
+ stm32_configgpio(GPIO_ETH_MII_RXD2);
+ stm32_configgpio(GPIO_ETH_MII_RXD3);
+ stm32_configgpio(GPIO_ETH_MII_RX_CLK);
+ stm32_configgpio(GPIO_ETH_MII_RX_DV);
+ stm32_configgpio(GPIO_ETH_MII_RX_ER);
+ stm32_configgpio(GPIO_ETH_MII_TXD0);
+ stm32_configgpio(GPIO_ETH_MII_TXD1);
+ stm32_configgpio(GPIO_ETH_MII_TXD2);
+ stm32_configgpio(GPIO_ETH_MII_TXD3);
+ stm32_configgpio(GPIO_ETH_MII_TX_CLK);
+ stm32_configgpio(GPIO_ETH_MII_TX_EN);
+
+ /* Set up the RMII interface. */
+
+#elif defined(CONFIG_STM32_RMII)
+
+ /* Select the RMII interface */
+
+ stm32_selectrmii();
+
+ /* RMII interface pins (7):
+ *
+ * RMII_TXD[1:0], RMII_TX_EN, RMII_RXD[1:0], RMII_CRS_DV, MDC, MDIO,
+ * RMII_REF_CLK
+ */
+
+ stm32_configgpio(GPIO_ETH_RMII_CRS_DV);
+ stm32_configgpio(GPIO_ETH_RMII_REF_CLK);
+ stm32_configgpio(GPIO_ETH_RMII_RXD0);
+ stm32_configgpio(GPIO_ETH_RMII_RXD1);
+ stm32_configgpio(GPIO_ETH_RMII_TXD0);
+ stm32_configgpio(GPIO_ETH_RMII_TXD1);
+ stm32_configgpio(GPIO_ETH_RMII_TX_CLK);
+ stm32_configgpio(GPIO_ETH_RMII_TX_EN);
+
+#endif
+#endif
+
+ /* Enable pulse-per-second (PPS) output signal */
+
+ stm32_configgpio(GPIO_ETH_PPS_OUT);
+}
+#else
+# warning "This would need to be re-designed to support multiple interfaces"
+#endif
+
+/****************************************************************************
* Public Functions
****************************************************************************/
@@ -659,17 +817,6 @@ int stm32_ethinitialize(int intf)
DEBUGASSERT(inf < STM32_NETHERNET);
priv = &g_stm32ethmac[intf];
- /* Check if a Ethernet chip is recognized at its I/O base */
-
- /* Attach the IRQ to the driver */
-
- if (irq_attach(STM32_IRQ_ETH, stm32_interrupt))
- {
- /* We could not attach the ISR to the interrupt */
-
- return -EAGAIN;
- }
-
/* Initialize the driver structure */
memset(priv, 0, sizeof(struct stm32_ethmac_s));
@@ -687,6 +834,21 @@ int stm32_ethinitialize(int intf)
priv->txpoll = wd_create(); /* Create periodic poll timer */
priv->txtimeout = wd_create(); /* Create TX timeout timer */
+ /* Configure GPIO pins to support Ethernet */
+
+ stm32_ethgpioconfig(priv);
+
+ /* Check if a Ethernet chip is recognized at its I/O base */
+
+ /* Attach the IRQ to the driver */
+
+ if (irq_attach(STM32_IRQ_ETH, stm32_interrupt))
+ {
+ /* We could not attach the ISR to the interrupt */
+
+ return -EAGAIN;
+ }
+
/* Put the interface in the down state. This usually amounts to resetting
* the device and/or calling stm32_ifdown().
*/
diff --git a/nuttx/arch/arm/src/stm32/stm32_rcc.h b/nuttx/arch/arm/src/stm32/stm32_rcc.h
index ac7a80ec9..b4a1500b7 100644
--- a/nuttx/arch/arm/src/stm32/stm32_rcc.h
+++ b/nuttx/arch/arm/src/stm32/stm32_rcc.h
@@ -42,6 +42,7 @@
#include <nuttx/config.h>
+#include "up_arch.h"
#include "chip.h"
#if defined(CONFIG_STM32_STM32F10XX)
@@ -75,21 +76,109 @@ extern "C" {
* and we will need to set the NVIC vector location to this alternative location.
*/
-extern uint32_t stm32_vectors[]; /* See stm32_vectors.S */
+extern uint32_t stm32_vectors[]; /* See stm32_vectors.S */
+
+/************************************************************************************
+ * Inline Functions
+ ************************************************************************************/
+
+/************************************************************************************
+ * Name: stm32_mco1config
+ *
+ * Description:
+ * Selects the clock source to output on MCO1 pin (PA8). PA8 should be configured in
+ * alternate function mode.
+ *
+ * Input Parameters:
+ * source - One of the definitions for the RCC_CFGR_MCO1 definitions from
+ * chip/stm32f40xxx_rcc.h {RCC_CFGR_MCO1_HSI, RCC_CFGR_MCO1_LSE,
+ * RCC_CFGR_MCO1_HSE, RCC_CFGR_MCO1_PLL}
+ * div - One of the definitions for the RCC_CFGR_MCO1PRE definitions from
+ * chip/stm32f40xxx_rcc.h {RCC_CFGR_MCO1PRE_NONE, RCC_CFGR_MCO1PRE_DIV2,
+ * RCC_CFGR_MCO1PRE_DIV3, RCC_CFGR_MCO1PRE_DIV4, RCC_CFGR_MCO1PRE_DIV5}
+ *
+ * Returned Value:
+ * None
+ *
+ ************************************************************************************/
+
+#if defined(CONFIG_STM32_STM32F40XX)
+static inline void stm32_mco1config(uint32_t source, uint32_t div)
+{
+ uint32_t regval;
+
+ regval = getreg32(STM32_RCC_CFGR);
+ regval &= ~(RCC_CFGR_MCO1_MASK|RCC_CFGR_MCO1PRE_MASK);
+ regval |= (source | div);
+ putreg32(regval, STM32_RCC_CFGR);
+}
+#endif
+
+/************************************************************************************
+ * Name: stm32_mco2config
+ *
+ * Description:
+ * Selects the clock source to output on MCO2 pin (PC9). PC9 should be configured in
+ * alternate function mode.
+ *
+ * Input Parameters:
+ * source - One of the definitions for the RCC_CFGR_MCO2 definitions from
+ * chip/stm32f40xxx_rcc.h {RCC_CFGR_MCO2_SYSCLK, RCC_CFGR_MCO2_PLLI2S,
+ * RCC_CFGR_MCO2_HSE, RCC_CFGR_MCO2_PLL}
+ * div - One of the definitions for the RCC_CFGR_MCO2PRE definitions from
+ * chip/stm32f40xxx_rcc.h {RCC_CFGR_MCO2PRE_NONE, RCC_CFGR_MCO2PRE_DIV2,
+ * RCC_CFGR_MCO2PRE_DIV3, RCC_CFGR_MCO2PRE_DIV4, RCC_CFGR_MCO2PRE_DIV5}
+ *
+ * Returned Value:
+ * None
+ *
+ ************************************************************************************/
+
+#if defined(CONFIG_STM32_STM32F40XX)
+static inline void stm32_mco2config(uint32_t source, uint32_t div)
+{
+ uint32_t regval;
+
+ regval = getreg32(STM32_RCC_CFGR);
+ regval &= ~(RCC_CFGR_MCO2_MASK|RCC_CFGR_MCO2PRE_MASK);
+ regval |= (source | div);
+ putreg32(regval, STM32_RCC_CFGR);
+}
+#endif
/************************************************************************************
* Public Function Prototypes
************************************************************************************/
-/* Called to change to new clock based on settings in board.h
- *
- * NOTE: This logic needs to be extended so that we can selected low-power
- * clocking modes as well!
- */
+/************************************************************************************
+ * Name: stm32_clockconfig
+ *
+ * Description:
+ * Called to change to new clock based on settings in board.h
+ *
+ * Input Parameters:
+ * None
+ *
+ * Returned Value:
+ * None
+ *
+ ************************************************************************************/
EXTERN void stm32_clockconfig(void);
-/* Enable LSE Clock */
+/************************************************************************************
+ * Name: stm32_rcc_enablelse
+ *
+ * Description:
+ * Enable LSE Clock
+ *
+ * Input Parameters:
+ * None
+ *
+ * Returned Value:
+ * None
+ *
+ ************************************************************************************/
EXTERN void stm32_rcc_enablelse(void);
diff --git a/nuttx/arch/arm/src/stm32/stm32_syscfg.h b/nuttx/arch/arm/src/stm32/stm32_syscfg.h
new file mode 100644
index 000000000..0d2688eb9
--- /dev/null
+++ b/nuttx/arch/arm/src/stm32/stm32_syscfg.h
@@ -0,0 +1,104 @@
+/****************************************************************************************************
+ * arch/arm/src/stm32/stm32_syscfg.h
+ *
+ * Copyright (C) 2011 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.
+ *
+ ****************************************************************************************************/
+
+#ifndef __ARCH_ARM_SRC_STM32_STM32_SYSCFG_H
+#define __ARCH_ARM_SRC_STM32_STM32_SYSCFG_H
+
+/****************************************************************************************************
+ * Included Files
+ ****************************************************************************************************/
+
+#include <nuttx/config.h>
+#include "chip.h"
+
+#ifdef CONFIG_STM32_STM32F40XX
+# include "chip/stm32_syscfg.h"
+
+/****************************************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************************************/
+
+/****************************************************************************************************
+ * Inline Functions
+ ****************************************************************************************************/
+
+/************************************************************************************
+ * Name: stm32_selectmii
+ *
+ * Description:
+ * Selects the MII inteface.
+ *
+ * Input Parameters:
+ * None
+ *
+ * Returned Value:
+ * None
+ *
+ ************************************************************************************/
+
+static inline void stm32_selectmii(void)
+{
+ uint32_t regval;
+
+ regval = getreg32(STM32_SYSCFG_PMC);
+ regval &= ~SYSCFG_PMC_MII_RMII_SEL;
+ putreg32(regval, STM32_SYSCFG_PMC);
+}
+
+/************************************************************************************
+ * Name: stm32_selectrmii
+ *
+ * Description:
+ * Selects the RMII inteface.
+ *
+ * Input Parameters:
+ * None
+ *
+ * Returned Value:
+ * None
+ *
+ ************************************************************************************/
+
+static inline void stm32_selectrmii(void)
+{
+ uint32_t regval;
+
+ regval = getreg32(STM32_SYSCFG_PMC);
+ regval |= SYSCFG_PMC_MII_RMII_SEL;
+ putreg32(regval, STM32_SYSCFG_PMC);
+}
+
+#endif /* CONFIG_STM32_STM32F40XX */
+#endif /* __ARCH_ARM_SRC_STM32_STM32_SYSCFG_H */