summaryrefslogtreecommitdiff
diff options
context:
space:
mode:
authorGregory Nutt <gnutt@nuttx.org>2014-06-27 09:30:41 -0600
committerGregory Nutt <gnutt@nuttx.org>2014-06-27 09:30:41 -0600
commite8410ddb25e9f03d48928e1c9686a740303d9d45 (patch)
treee3e319d20ebb979203b04ed04f3593d91701ae75
parent4120657cd331cbfd29ac9d6b0f2b76cad7d72cd4 (diff)
downloadpx4-nuttx-e8410ddb25e9f03d48928e1c9686a740303d9d45.tar.gz
px4-nuttx-e8410ddb25e9f03d48928e1c9686a740303d9d45.tar.bz2
px4-nuttx-e8410ddb25e9f03d48928e1c9686a740303d9d45.zip
Add support for a network device IOCTL to access PHY registers. Ioctls only implemented for STM32. From Lazlo
-rw-r--r--apps/examples/Makefile1
-rw-r--r--apps/system/Kconfig4
-rw-r--r--apps/system/Make.defs4
-rw-r--r--apps/system/Makefile1
-rw-r--r--nuttx/arch/arm/src/stm32/stm32_eth.c63
-rw-r--r--nuttx/include/net/if.h27
-rw-r--r--nuttx/include/nuttx/net/ioctl.h6
-rw-r--r--nuttx/include/nuttx/net/netdev.h3
-rw-r--r--nuttx/net/Kconfig6
-rw-r--r--nuttx/net/netdev_ioctl.c15
10 files changed, 128 insertions, 2 deletions
diff --git a/apps/examples/Makefile b/apps/examples/Makefile
index 547e3004a..a4bca7dfe 100644
--- a/apps/examples/Makefile
+++ b/apps/examples/Makefile
@@ -86,4 +86,3 @@ clean: $(foreach SDIR, $(SUBDIRS), $(SDIR)_clean)
distclean: $(foreach SDIR, $(SUBDIRS), $(SDIR)_distclean)
-include Make.dep
-
diff --git a/apps/system/Kconfig b/apps/system/Kconfig
index 382ef3476..ed16af860 100644
--- a/apps/system/Kconfig
+++ b/apps/system/Kconfig
@@ -47,6 +47,10 @@ menu "P-Code Support"
source "$APPSDIR/system/prun/Kconfig"
endmenu
+menu "PHY Tool"
+source "$APPSDIR/system/mdio/Kconfig"
+endmenu
+
menu "Power Off"
source "$APPSDIR/system/poweroff/Kconfig"
endmenu
diff --git a/apps/system/Make.defs b/apps/system/Make.defs
index 44c584252..bdfde4503 100644
--- a/apps/system/Make.defs
+++ b/apps/system/Make.defs
@@ -74,6 +74,10 @@ ifeq ($(CONFIG_SYSTEM_PRUN),y)
CONFIGURED_APPS += system/prun
endif
+ifeq ($(CONFIG_SYSTEM_MDIO),y)
+CONFIGURED_APPS += system/mdio
+endif
+
ifeq ($(CONFIG_SYSTEM_RAMTEST),y)
CONFIGURED_APPS += system/ramtest
endif
diff --git a/apps/system/Makefile b/apps/system/Makefile
index c39cfae9f..ed7b64dff 100644
--- a/apps/system/Makefile
+++ b/apps/system/Makefile
@@ -40,6 +40,7 @@
SUBDIRS = cdcacm cle composite flash_eraseall free i2c hex2bin inifile
SUBDIRS += install nxplayer poweroff ramtest ramtron readline sdcard
SUBDIRS += stackmonitor sysinfo usbmonitor usbmsc vi zmodem
+SUBDIRS += mdio
# Create the list of installed runtime modules (INSTALLED_DIRS)
diff --git a/nuttx/arch/arm/src/stm32/stm32_eth.c b/nuttx/arch/arm/src/stm32/stm32_eth.c
index 2197665b3..0d86cd605 100644
--- a/nuttx/arch/arm/src/stm32/stm32_eth.c
+++ b/nuttx/arch/arm/src/stm32/stm32_eth.c
@@ -665,6 +665,9 @@ static void stm32_rxdescinit(FAR struct stm32_ethmac_s *priv);
/* PHY Initialization */
+#ifdef CONFIG_NETDEV_PHY_IOCTL
+static int stm32_ioctl(int cmd, struct mii_ioctl_data *req);
+#endif
static int stm32_phyread(uint16_t phydevaddr, uint16_t phyregaddr, uint16_t *value);
static int stm32_phywrite(uint16_t phydevaddr, uint16_t phyregaddr, uint16_t value);
#ifdef CONFIG_ETH0_PHY_DM9161
@@ -2476,6 +2479,63 @@ static void stm32_rxdescinit(FAR struct stm32_ethmac_s *priv)
}
/****************************************************************************
+ * Function: stm32_ioctl
+ *
+ * Description:
+ * Executes the SIOCxMIIxxx command and responds using the request struct
+ * that must be provided as its 2nd parameter.
+ *
+ * When called with SIOCGMIIPHY it will get the PHY address for the device
+ * and write it to the req->phy_id field of the request struct.
+ *
+ * When called with SIOCGMIIREG it will read a register of the PHY that is
+ * specified using the req->reg_no struct field and then write its output
+ * to the req->val_out field.
+ *
+ * When called with SIOCSMIIREG it will write to a register of the PHY that
+ * is specified using the req->reg_no struct field and use req->val_in as
+ * its input.
+ *
+ * Parameters:
+ * cmd - SIOCxMIIxxx command code
+ * req - request structure also used to return values
+ *
+ * Returned Value: Negated errno on failure.
+ *
+ * Assumptions:
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_NETDEV_PHY_IOCTL
+static int stm32_ioctl(int cmd, struct mii_ioctl_data *req)
+{
+ int ret = -ENOTTY;
+
+ switch (cmd)
+ {
+ case SIOCGMIIPHY: /* Get MII PHY address */
+ req->phy_id = CONFIG_STM32_PHYADDR;
+ ret = OK;
+ break;
+
+ case SIOCGMIIREG: /* Get register from MII PHY */
+ ret = stm32_phyread(req->phy_id, req->reg_num, &req->val_out);
+ break;
+
+ case SIOCSMIIREG: /* Set register in MII PHY */
+ ret = stm32_phywrite(req->phy_id, req->reg_num, req->val_in);
+ break;
+
+ default:
+ ret = -EINVAL;
+ break;
+ }
+
+ return ret;
+}
+#endif /* CONFIG_NETDEV_PHY_IOCTL */
+
+/****************************************************************************
* Function: stm32_phyread
*
* Description:
@@ -3461,6 +3521,9 @@ int stm32_ethinitialize(int intf)
priv->dev.d_addmac = stm32_addmac; /* Add multicast MAC address */
priv->dev.d_rmmac = stm32_rmmac; /* Remove multicast MAC address */
#endif
+#ifdef CONFIG_NETDEV_PHY_IOCTL
+ priv->dev.d_ioctl = stm32_ioctl; /* Support PHY ioctl() calls */
+#endif
priv->dev.d_private = (void*)g_stm32ethmac; /* Used to recover private state from dev */
/* Create a watchdog for timing polling for and timing of transmisstions */
diff --git a/nuttx/include/net/if.h b/nuttx/include/net/if.h
index eae6bcb3f..bad4a2124 100644
--- a/nuttx/include/net/if.h
+++ b/nuttx/include/net/if.h
@@ -57,11 +57,22 @@
#define IFF_RUNNING (1 << 2)
#define IFF_NOARP (1 << 7)
-
/*******************************************************************************************
* Public Type Definitions
*******************************************************************************************/
+/* Part of the I/F request used to read from or write to the MII/PHY management
+ * interface when SIOCxMIIREG ioctl was called.
+ */
+
+struct mii_ioctl_data
+{
+ uint16_t phy_id; /* PHY device address */
+ uint16_t reg_num; /* PHY register address */
+ uint16_t val_in; /* PHY input data */
+ uint16_t val_out; /* PHY output data */
+};
+
/* This is the newer form if the I/F request structure that can be used with both IPv4
* and IPv6.
*/
@@ -79,6 +90,7 @@ struct lifreq
int lifru_count; /* Number of devices */
int lifru_mtu; /* MTU size */
uint8_t lifru_flags; /* Interface flags */
+ struct mii_ioctl_data lifru_mii_data; /* MII request data */
} lifr_ifru;
};
@@ -90,6 +102,10 @@ struct lifreq
#define lifr_mtu lifr_ifru.lifru_mtu /* MTU */
#define lifr_count lifr_ifru.lifru_count /* Number of devices */
#define lifr_flags lifr_ifru.lifru_flags /* interface flags */
+#define lifr_mii_phy_id lifr_ifru.lifru_mii_data.phy_id /* PHY device address */
+#define lifr_mii_reg_num lifr_ifru.lifru_mii_data.reg_num /* PHY register address */
+#define lifr_mii_val_in lifr_ifru.lifru_mii_data.val_in /* PHY input data */
+#define lifr_mii_val_out lifr_ifru.lifru_mii_data.val_out /* PHY output data */
/* This is the older I/F request that should only be used with IPv4. However, since
* NuttX only supports IPv4 or 6 (not both), we can force the older structure to
@@ -110,6 +126,7 @@ struct ifreq
int ifru_count; /* Number of devices */
int ifru_mtu; /* MTU size */
uint8_t ifru_flags; /* Interface flags */
+ struct mii_ioctl_data ifru_mii_data; /* MII request data */
} ifr_ifru;
};
@@ -121,6 +138,10 @@ struct ifreq
#define ifr_mtu ifr_ifru.ifru_mtu /* MTU */
#define ifr_count ifr_ifru.ifru_count /* Number of devices */
#define ifr_flags ifr_ifru.ifru_flags /* interface flags */
+#define ifr_mii_phy_id ifr_ifru.ifru_mii_data.phy_id /* PHY device address */
+#define ifr_mii_reg_num ifr_ifru.ifru_mii_data.reg_num /* PHY register address */
+#define ifr_mii_val_in ifr_ifru.ifru_mii_data.val_in /* PHY input data */
+#define ifr_mii_val_out ifr_ifru.ifru_mii_data.val_out /* PHY output data */
#else /* CONFIG_NET_IPv6 */
@@ -134,6 +155,10 @@ struct ifreq
#define ifr_mtu lifr_ifru.lifru_mtu /* MTU */
#define ifr_count lifr_ifru.lifru_count /* Number of devices */
#define ifr_flags lifr_ifru.lifru_flags /* interface flags */
+#define ifr_mii_phy_id lifr_ifru.lifru_mii_data.phy_id /* PHY device address */
+#define ifr_mii_reg_num lifr_ifru.lifru_mii_data.reg_num /* PHY register address */
+#define ifr_mii_val_in lifr_ifru.lifru_mii_data.val_in /* PHY input data */
+#define ifr_mii_val_out lifr_ifru.lifru_mii_data.val_out /* PHY output data */
#endif /* CONFIG_NET_IPv6 */
diff --git a/nuttx/include/nuttx/net/ioctl.h b/nuttx/include/nuttx/net/ioctl.h
index 7fbcc3b20..7c2e1cb49 100644
--- a/nuttx/include/nuttx/net/ioctl.h
+++ b/nuttx/include/nuttx/net/ioctl.h
@@ -160,6 +160,12 @@
#define SIOCSIWPMKSA _SIOC(0x0041) /* PMKSA cache operation */
+/* MDIO/MCD *****************************************************************/
+
+#define SIOCGMIIPHY _SIOC(0x0042) /* Get address of MII PHY in use */
+#define SIOCGMIIREG _SIOC(0x0043) /* Get a MII register via MDIO */
+#define SIOCSMIIREG _SIOC(0x0044) /* Set a MII register via MDIO */
+
/****************************************************************************
* Type Definitions
****************************************************************************/
diff --git a/nuttx/include/nuttx/net/netdev.h b/nuttx/include/nuttx/net/netdev.h
index 053758738..cc781a77d 100644
--- a/nuttx/include/nuttx/net/netdev.h
+++ b/nuttx/include/nuttx/net/netdev.h
@@ -187,6 +187,9 @@ struct uip_driver_s
int (*d_addmac)(struct uip_driver_s *dev, FAR const uint8_t *mac);
int (*d_rmmac)(struct uip_driver_s *dev, FAR const uint8_t *mac);
#endif
+#ifdef CONFIG_NETDEV_PHY_IOCTL
+ int (*d_ioctl)(int cmd, struct mii_ioctl_data *req);
+#endif
/* Drivers may attached device-specific, private information */
diff --git a/nuttx/net/Kconfig b/nuttx/net/Kconfig
index 294ea523e..8440b4dc1 100644
--- a/nuttx/net/Kconfig
+++ b/nuttx/net/Kconfig
@@ -73,6 +73,12 @@ config NET_SOCKOPTS
---help---
Enable or disable support for socket options
+config NETDEV_PHY_IOCTL
+ bool "Enable PHY ioctl()"
+ default n
+ ---help---
+ Enable support for ioctl() commands to access PHY registers"
+
if NET_SOCKOPTS
config NET_SOLINGER
diff --git a/nuttx/net/netdev_ioctl.c b/nuttx/net/netdev_ioctl.c
index 1505e668f..ec216a1e4 100644
--- a/nuttx/net/netdev_ioctl.c
+++ b/nuttx/net/netdev_ioctl.c
@@ -422,6 +422,21 @@ static int netdev_ifrioctl(FAR struct socket *psock, int cmd,
# error "IOCTL Commands not implemented"
#endif
+#ifdef CONFIG_NETDEV_PHY_IOCTL
+ case SIOCGMIIPHY: /* Get address of MII PHY in use */
+ case SIOCGMIIREG: /* Get MII register via MDIO */
+ case SIOCSMIIREG: /* Set MII register via MDIO */
+ {
+ dev = netdev_ifrdev(req);
+ if (dev && dev->d_ioctl)
+ {
+ struct mii_ioctl_data *mii_data = &req->ifr_ifru.ifru_mii_data;
+ ret = dev->d_ioctl(cmd, mii_data);
+ }
+ }
+ break;
+#endif
+
default:
{
ret = -ENOTTY;