mail archive of the barebox mailing list
 help / color / mirror / Atom feed
* [PATCH v2 0/8] Bitbang MDIO, miitool changes
@ 2016-02-01  3:10 Andrey Smirnov
  2016-02-01  3:10 ` [PATCH v2 1/8] include/linux/phy.h: Add MII_ADDR_C45 Andrey Smirnov
                   ` (7 more replies)
  0 siblings, 8 replies; 16+ messages in thread
From: Andrey Smirnov @ 2016-02-01  3:10 UTC (permalink / raw)
  To: barebox; +Cc: Andrey Smirnov

Hi everyone,

Here's the second verion of the MDIO-related patchset I recently sent:

http://lists.infradead.org/pipermail/barebox/2016-January/025936.html

The only change in v2 is that patch implementing mdio_write/mdio_read
commands has been dropped and instead a different patch augmenting
'miitool' with PHY registration capabilties was introduced.

Andrey Gusakov (2):
  include/linux/phy.h: Add MII_ADDR_C45
  net: Port bitbanged MDIO code from Linux kernel

Andrey Smirnov (6):
  miitool: Fix PHY argument handling
  mdio_bus: Change dev_info to dev_dbg
  mdio_bus: Add mdiobus_get_bus() function
  miitool: Don't print negative parent IDs
  mdio_bus: Change PHY's naming scheme
  miitool: Add code to register a PHY

 commands/miitool.c             | 117 ++++++++++++++++-----
 drivers/net/phy/Kconfig        |  15 +++
 drivers/net/phy/Makefile       |   2 +
 drivers/net/phy/mdio-bitbang.c | 228 ++++++++++++++++++++++++++++++++++++++++
 drivers/net/phy/mdio-gpio.c    | 231 +++++++++++++++++++++++++++++++++++++++++
 drivers/net/phy/mdio_bus.c     |  25 ++++-
 drivers/net/phy/phy.c          |   9 +-
 include/linux/mdio-bitbang.h   |  45 ++++++++
 include/linux/phy.h            |   7 ++
 9 files changed, 647 insertions(+), 32 deletions(-)
 create mode 100644 drivers/net/phy/mdio-bitbang.c
 create mode 100644 drivers/net/phy/mdio-gpio.c
 create mode 100644 include/linux/mdio-bitbang.h

-- 
2.5.0


_______________________________________________
barebox mailing list
barebox@lists.infradead.org
http://lists.infradead.org/mailman/listinfo/barebox

^ permalink raw reply	[flat|nested] 16+ messages in thread

* [PATCH v2 1/8] include/linux/phy.h: Add MII_ADDR_C45
  2016-02-01  3:10 [PATCH v2 0/8] Bitbang MDIO, miitool changes Andrey Smirnov
@ 2016-02-01  3:10 ` Andrey Smirnov
  2016-02-01  3:10 ` [PATCH v2 2/8] net: Port bitbanged MDIO code from Linux kernel Andrey Smirnov
                   ` (6 subsequent siblings)
  7 siblings, 0 replies; 16+ messages in thread
From: Andrey Smirnov @ 2016-02-01  3:10 UTC (permalink / raw)
  To: barebox; +Cc: Andrey Smirnov, Andrey Gusakov

From: Andrey Gusakov <andrey.gusakov@cogentembedded.com>

Add MII_ADDR_C45 used by bitbanged MDIO

Signed-off-by: Andrey Gusakov <andrey.gusakov@cogentembedded.com>
Signed-off-by: Andrey Smirnov <andrew.smirnov@gmail.com>
---
 include/linux/phy.h | 4 ++++
 1 file changed, 4 insertions(+)

diff --git a/include/linux/phy.h b/include/linux/phy.h
index a64b9b5..58e69da 100644
--- a/include/linux/phy.h
+++ b/include/linux/phy.h
@@ -69,6 +69,10 @@ typedef enum {
  */
 #define MII_BUS_ID_SIZE	(20 - 3)
 
+/* Or MII_ADDR_C45 into regnum for read/write on mii_bus to enable the 21 bit
+   IEEE 802.3ae clause 45 addressing mode used by 10GIGE phy chips. */
+#define MII_ADDR_C45 (1<<30)
+
 #define PHYLIB_FORCE_10		(1 << 0)
 #define PHYLIB_FORCE_100	(1 << 1)
 #define PHYLIB_FORCE_LINK	(1 << 2)
-- 
2.5.0


_______________________________________________
barebox mailing list
barebox@lists.infradead.org
http://lists.infradead.org/mailman/listinfo/barebox

^ permalink raw reply	[flat|nested] 16+ messages in thread

* [PATCH v2 2/8] net: Port bitbanged MDIO code from Linux kernel
  2016-02-01  3:10 [PATCH v2 0/8] Bitbang MDIO, miitool changes Andrey Smirnov
  2016-02-01  3:10 ` [PATCH v2 1/8] include/linux/phy.h: Add MII_ADDR_C45 Andrey Smirnov
@ 2016-02-01  3:10 ` Andrey Smirnov
  2016-02-01  3:10 ` [PATCH v2 3/8] miitool: Fix PHY argument handling Andrey Smirnov
                   ` (5 subsequent siblings)
  7 siblings, 0 replies; 16+ messages in thread
From: Andrey Smirnov @ 2016-02-01  3:10 UTC (permalink / raw)
  To: barebox; +Cc: Andrey Smirnov, Andrey Gusakov

From: Andrey Gusakov <andrey.gusakov@cogentembedded.com>

Port bitbanged MDIO framework and gpiolib MDIO bus driver that uses it
from Linux kernel.

Signed-off-by: Andrey Gusakov <andrey.gusakov@cogentembedded.com>
Signed-off-by: Andrey Smirnov <andrew.smirnov@gmail.com>
---
 drivers/net/phy/Kconfig        |  15 +++
 drivers/net/phy/Makefile       |   2 +
 drivers/net/phy/mdio-bitbang.c | 228 ++++++++++++++++++++++++++++++++++++++++
 drivers/net/phy/mdio-gpio.c    | 231 +++++++++++++++++++++++++++++++++++++++++
 include/linux/mdio-bitbang.h   |  45 ++++++++
 5 files changed, 521 insertions(+)
 create mode 100644 drivers/net/phy/mdio-bitbang.c
 create mode 100644 drivers/net/phy/mdio-gpio.c
 create mode 100644 include/linux/mdio-bitbang.h

diff --git a/drivers/net/phy/Kconfig b/drivers/net/phy/Kconfig
index d0a02c1..d30f65b 100644
--- a/drivers/net/phy/Kconfig
+++ b/drivers/net/phy/Kconfig
@@ -46,6 +46,21 @@ config MDIO_MVEBU
 	---help---
 	  Driver for the MDIO bus found on Marvell EBU SoCs.
 
+config MDIO_BITBANG
+        bool "Support for bitbanged MDIO buses"
+	---help---
+          This module implements the MDIO bus protocol in software,
+          for use by low level drivers that export the ability to
+          drive the relevant pins.
+
+          If in doubt, say N.
+
+config MDIO_GPIO
+	bool "Support for GPIO lib-based bitbanged MDIO buses"
+	depends on MDIO_BITBANG && GPIOLIB
+	---help---
+	  Supports GPIO lib-based MDIO busses.
+
 endif
 
 endmenu
diff --git a/drivers/net/phy/Makefile b/drivers/net/phy/Makefile
index 94b9be8..10732f8 100644
--- a/drivers/net/phy/Makefile
+++ b/drivers/net/phy/Makefile
@@ -7,3 +7,5 @@ obj-$(CONFIG_NATIONAL_PHY)	+= national.o
 obj-$(CONFIG_SMSC_PHY)		+= smsc.o
 
 obj-$(CONFIG_MDIO_MVEBU)	+= mdio-mvebu.o
+obj-$(CONFIG_MDIO_BITBANG)	+= mdio-bitbang.o
+obj-$(CONFIG_MDIO_GPIO)		+= mdio-gpio.o
diff --git a/drivers/net/phy/mdio-bitbang.c b/drivers/net/phy/mdio-bitbang.c
new file mode 100644
index 0000000..4f610e3
--- /dev/null
+++ b/drivers/net/phy/mdio-bitbang.c
@@ -0,0 +1,228 @@
+/*
+ * Bitbanged MDIO support.
+ *
+ * Author: Scott Wood <scottwood@freescale.com>
+ * Copyright (c) 2007 Freescale Semiconductor
+ *
+ * Based on CPM2 MDIO code which is:
+ *
+ * Copyright (c) 2003 Intracom S.A.
+ *  by Pantelis Antoniou <panto@intracom.gr>
+ *
+ * 2005 (c) MontaVista Software, Inc.
+ * Vitaly Bordug <vbordug@ru.mvista.com>
+ *
+ * This file is licensed under the terms of the GNU General Public License
+ * version 2. This program is licensed "as is" without any warranty of any
+ * kind, whether express or implied.
+ */
+
+#include <common.h>
+#include <driver.h>
+#include <linux/phy.h>
+#include <linux/mdio-bitbang.h>
+
+#define MDIO_READ 2
+#define MDIO_WRITE 1
+
+#define MDIO_C45 (1<<15)
+#define MDIO_C45_ADDR (MDIO_C45 | 0)
+#define MDIO_C45_READ (MDIO_C45 | 3)
+#define MDIO_C45_WRITE (MDIO_C45 | 1)
+
+#define MDIO_SETUP_TIME 10
+#define MDIO_HOLD_TIME 10
+
+/* Minimum MDC period is 400 ns, plus some margin for error.  MDIO_DELAY
+ * is done twice per period.
+ */
+#define MDIO_DELAY 250
+
+/* The PHY may take up to 300 ns to produce data, plus some margin
+ * for error.
+ */
+#define MDIO_READ_DELAY 350
+
+/* MDIO must already be configured as output. */
+static void mdiobb_send_bit(struct mdiobb_ctrl *ctrl, int val)
+{
+	const struct mdiobb_ops *ops = ctrl->ops;
+
+	ops->set_mdio_data(ctrl, val);
+	ndelay(MDIO_DELAY);
+	ops->set_mdc(ctrl, 1);
+	ndelay(MDIO_DELAY);
+	ops->set_mdc(ctrl, 0);
+}
+
+/* MDIO must already be configured as input. */
+static int mdiobb_get_bit(struct mdiobb_ctrl *ctrl)
+{
+	const struct mdiobb_ops *ops = ctrl->ops;
+
+	ndelay(MDIO_DELAY);
+	ops->set_mdc(ctrl, 1);
+	ndelay(MDIO_READ_DELAY);
+	ops->set_mdc(ctrl, 0);
+
+	return ops->get_mdio_data(ctrl);
+}
+
+/* MDIO must already be configured as output. */
+static void mdiobb_send_num(struct mdiobb_ctrl *ctrl, u16 val, int bits)
+{
+	int i;
+
+	for (i = bits - 1; i >= 0; i--)
+		mdiobb_send_bit(ctrl, (val >> i) & 1);
+}
+
+/* MDIO must already be configured as input. */
+static u16 mdiobb_get_num(struct mdiobb_ctrl *ctrl, int bits)
+{
+	int i;
+	u16 ret = 0;
+
+	for (i = bits - 1; i >= 0; i--) {
+		ret <<= 1;
+		ret |= mdiobb_get_bit(ctrl);
+	}
+
+	return ret;
+}
+
+/* Utility to send the preamble, address, and
+ * register (common to read and write).
+ */
+static void mdiobb_cmd(struct mdiobb_ctrl *ctrl, int op, u8 phy, u8 reg)
+{
+	const struct mdiobb_ops *ops = ctrl->ops;
+	int i;
+
+	ops->set_mdio_dir(ctrl, 1);
+
+	/*
+	 * Send a 32 bit preamble ('1's) with an extra '1' bit for good
+	 * measure.  The IEEE spec says this is a PHY optional
+	 * requirement.  The AMD 79C874 requires one after power up and
+	 * one after a MII communications error.  This means that we are
+	 * doing more preambles than we need, but it is safer and will be
+	 * much more robust.
+	 */
+
+	for (i = 0; i < 32; i++)
+		mdiobb_send_bit(ctrl, 1);
+
+	/* send the start bit (01) and the read opcode (10) or write (10).
+	   Clause 45 operation uses 00 for the start and 11, 10 for
+	   read/write */
+	mdiobb_send_bit(ctrl, 0);
+	if (op & MDIO_C45)
+		mdiobb_send_bit(ctrl, 0);
+	else
+		mdiobb_send_bit(ctrl, 1);
+	mdiobb_send_bit(ctrl, (op >> 1) & 1);
+	mdiobb_send_bit(ctrl, (op >> 0) & 1);
+
+	mdiobb_send_num(ctrl, phy, 5);
+	mdiobb_send_num(ctrl, reg, 5);
+}
+
+/* In clause 45 mode all commands are prefixed by MDIO_ADDR to specify the
+   lower 16 bits of the 21 bit address. This transfer is done identically to a
+   MDIO_WRITE except for a different code. To enable clause 45 mode or
+   MII_ADDR_C45 into the address. Theoretically clause 45 and normal devices
+   can exist on the same bus. Normal devices should ignore the MDIO_ADDR
+   phase. */
+static int mdiobb_cmd_addr(struct mdiobb_ctrl *ctrl, int phy, u32 addr)
+{
+	unsigned int dev_addr = (addr >> 16) & 0x1F;
+	unsigned int reg = addr & 0xFFFF;
+	mdiobb_cmd(ctrl, MDIO_C45_ADDR, phy, dev_addr);
+
+	/* send the turnaround (10) */
+	mdiobb_send_bit(ctrl, 1);
+	mdiobb_send_bit(ctrl, 0);
+
+	mdiobb_send_num(ctrl, reg, 16);
+
+	ctrl->ops->set_mdio_dir(ctrl, 0);
+	mdiobb_get_bit(ctrl);
+
+	return dev_addr;
+}
+
+static int mdiobb_read(struct mii_bus *bus, int phy, int reg)
+{
+	struct mdiobb_ctrl *ctrl = bus->priv;
+	int ret, i;
+
+	if (reg & MII_ADDR_C45) {
+		reg = mdiobb_cmd_addr(ctrl, phy, reg);
+		mdiobb_cmd(ctrl, MDIO_C45_READ, phy, reg);
+	} else
+		mdiobb_cmd(ctrl, MDIO_READ, phy, reg);
+
+	ctrl->ops->set_mdio_dir(ctrl, 0);
+
+	/* check the turnaround bit: the PHY should be driving it to zero, if this
+	 * PHY is listed in phy_ignore_ta_mask as having broken TA, skip that
+	 */
+	if (mdiobb_get_bit(ctrl) != 0) {
+		/* PHY didn't drive TA low -- flush any bits it
+		 * may be trying to send.
+		 */
+		for (i = 0; i < 32; i++)
+			mdiobb_get_bit(ctrl);
+
+		return 0xffff;
+	}
+
+	ret = mdiobb_get_num(ctrl, 16);
+	mdiobb_get_bit(ctrl);
+	return ret;
+}
+
+static int mdiobb_write(struct mii_bus *bus, int phy, int reg, u16 val)
+{
+	struct mdiobb_ctrl *ctrl = bus->priv;
+
+	if (reg & MII_ADDR_C45) {
+		reg = mdiobb_cmd_addr(ctrl, phy, reg);
+		mdiobb_cmd(ctrl, MDIO_C45_WRITE, phy, reg);
+	} else
+		mdiobb_cmd(ctrl, MDIO_WRITE, phy, reg);
+
+	/* send the turnaround (10) */
+	mdiobb_send_bit(ctrl, 1);
+	mdiobb_send_bit(ctrl, 0);
+
+	mdiobb_send_num(ctrl, val, 16);
+
+	ctrl->ops->set_mdio_dir(ctrl, 0);
+	mdiobb_get_bit(ctrl);
+	return 0;
+}
+
+static int mdiobb_reset(struct mii_bus *bus)
+{
+	struct mdiobb_ctrl *ctrl = bus->priv;
+	if (ctrl->reset)
+		ctrl->reset(bus);
+	return 0;
+}
+
+struct mii_bus *alloc_mdio_bitbang(struct mdiobb_ctrl *ctrl)
+{
+	struct mii_bus *bus;
+
+	bus = xzalloc(sizeof(*bus));
+
+	bus->read = mdiobb_read;
+	bus->write = mdiobb_write;
+	bus->reset = mdiobb_reset;
+	bus->priv = ctrl;
+
+	return bus;
+}
+EXPORT_SYMBOL(alloc_mdio_bitbang);
diff --git a/drivers/net/phy/mdio-gpio.c b/drivers/net/phy/mdio-gpio.c
new file mode 100644
index 0000000..a839f2d
--- /dev/null
+++ b/drivers/net/phy/mdio-gpio.c
@@ -0,0 +1,231 @@
+/*
+ * GPIO based MDIO bitbang driver.
+ * Supports OpenFirmware.
+ *
+ * (C) Copyright 2015
+ *  CogentEmbedded, Andrey Gusakov <andrey.gusakov@cogentembedded.com>
+ *
+ * based on mvmdio driver from Linux
+ *  Copyright (c) 2008 CSE Semaphore Belgium.
+ *   by Laurent Pinchart <laurentp@cse-semaphore.com>
+ *
+ * Copyright (C) 2008, Paulius Zaleckas <paulius.zaleckas@teltonika.lt>
+ *
+ * Based on earlier work by
+ *
+ * Copyright (c) 2003 Intracom S.A.
+ *  by Pantelis Antoniou <panto@intracom.gr>
+ *
+ * 2005 (c) MontaVista Software, Inc.
+ * Vitaly Bordug <vbordug@ru.mvista.com>
+ *
+ * This file is licensed under the terms of the GNU General Public License
+ * version 2. This program is licensed "as is" without any warranty of any
+ * kind, whether express or implied.
+ */
+
+#define DEBUG
+
+#include <common.h>
+#include <driver.h>
+#include <init.h>
+#include <io.h>
+#include <of.h>
+#include <of_gpio.h>
+#include <linux/phy.h>
+#include <gpio.h>
+#include <malloc.h>
+#include <xfuncs.h>
+
+#include <linux/mdio-bitbang.h>
+
+struct mdio_gpio_info {
+	struct mdiobb_ctrl ctrl;
+	int mdc, mdio, mdo;
+	int mdc_active_low, mdio_active_low, mdo_active_low;
+};
+
+struct mdio_gpio_info *mdio_gpio_of_get_info(struct device_d *dev)
+{
+	int ret;
+	enum of_gpio_flags flags;
+	struct mdio_gpio_info *info;
+
+	info = xzalloc(sizeof(*info));
+
+	ret = of_get_gpio_flags(dev->device_node, 0, &flags);
+	if (ret < 0) {
+		dev_dbg(dev, "failed to get MDC inforamtion from DT\n");
+		goto free_info;
+	}
+
+	info->mdc = ret;
+	info->mdc_active_low = flags & OF_GPIO_ACTIVE_LOW;
+
+	ret = of_get_gpio_flags(dev->device_node, 1, &flags);
+	if (ret < 0) {
+		dev_dbg(dev, "failed to get MDIO inforamtion from DT\n");
+		goto free_info;
+	}
+
+	info->mdio = ret;
+	info->mdio_active_low = flags & OF_GPIO_ACTIVE_LOW;
+
+	ret = of_get_gpio_flags(dev->device_node, 2, &flags);
+	if (ret > 0) {
+		dev_dbg(dev, "found MDO information in DT\n");
+		info->mdo = ret;
+		info->mdo_active_low = flags & OF_GPIO_ACTIVE_LOW;
+	}
+
+	return info;
+
+free_info:
+	free(info);
+	return ERR_PTR(ret);
+}
+
+static void mdio_dir(struct mdiobb_ctrl *ctrl, int dir)
+{
+	struct mdio_gpio_info *bitbang =
+		container_of(ctrl, struct mdio_gpio_info, ctrl);
+
+	if (bitbang->mdo) {
+		/* Separate output pin. Always set its value to high
+		 * when changing direction. If direction is input,
+		 * assume the pin serves as pull-up. If direction is
+		 * output, the default value is high.
+		 */
+		gpio_set_value(bitbang->mdo,
+				1 ^ bitbang->mdo_active_low);
+		return;
+	}
+
+	if (dir)
+		gpio_direction_output(bitbang->mdio,
+				      1 ^ bitbang->mdio_active_low);
+	else
+		gpio_direction_input(bitbang->mdio);
+}
+
+static int mdio_get(struct mdiobb_ctrl *ctrl)
+{
+	struct mdio_gpio_info *bitbang =
+		container_of(ctrl, struct mdio_gpio_info, ctrl);
+
+	return gpio_get_value(bitbang->mdio) ^
+		bitbang->mdio_active_low;
+}
+
+static void mdio_set(struct mdiobb_ctrl *ctrl, int what)
+{
+	struct mdio_gpio_info *bitbang =
+		container_of(ctrl, struct mdio_gpio_info, ctrl);
+
+	if (bitbang->mdo)
+		gpio_set_value(bitbang->mdo,
+				what ^ bitbang->mdo_active_low);
+	else
+		gpio_set_value(bitbang->mdio,
+				what ^ bitbang->mdio_active_low);
+}
+
+static void mdc_set(struct mdiobb_ctrl *ctrl, int what)
+{
+	struct mdio_gpio_info *bitbang =
+		container_of(ctrl, struct mdio_gpio_info, ctrl);
+
+	gpio_set_value(bitbang->mdc, what ^ bitbang->mdc_active_low);
+}
+
+static struct mdiobb_ops mdio_gpio_ops = {
+	.set_mdc = mdc_set,
+	.set_mdio_dir = mdio_dir,
+	.set_mdio_data = mdio_set,
+	.get_mdio_data = mdio_get,
+};
+
+static int mdio_gpio_probe(struct device_d *dev)
+{
+	int ret;
+	struct device_node *np = dev->device_node;
+	struct mdio_gpio_info *info;
+	struct mii_bus *bus;
+
+	info = mdio_gpio_of_get_info(dev);
+	if (IS_ERR(info))
+		return PTR_ERR(info);
+
+	info->ctrl.ops = &mdio_gpio_ops;
+
+	ret = gpio_request(info->mdc, "mdc");
+	if (ret < 0) {
+		dev_dbg(dev, "failed to request MDC\n");
+		goto free_info;
+	}
+
+	ret = gpio_request(info->mdio, "mdio");
+	if (ret < 0) {
+		dev_dbg(dev, "failed to request MDIO\n");
+		goto free_mdc;
+	}
+
+	if (info->mdo) {
+		ret = gpio_request(info->mdo, "mdo");
+		if (ret < 0) {
+			dev_dbg(dev, "failed to request MDO\n");
+			goto free_mdio;
+		}
+
+		ret = gpio_direction_output(info->mdo, 1);
+		if (ret < 0) {
+			dev_dbg(dev, "failed to set MDO as output\n");
+			goto free_mdo;
+		}
+
+		ret = gpio_direction_input(info->mdio);
+		if (ret < 0) {
+			dev_dbg(dev, "failed to set MDIO as input\n");
+			goto free_mdo;
+		}
+	}
+
+	ret = gpio_direction_output(info->mdc, 0);
+	if (ret < 0) {
+		dev_dbg(dev, "failed to set MDC as output\n");
+		goto free_mdo;
+	}
+
+	bus = alloc_mdio_bitbang(&info->ctrl);
+	bus->parent = dev;
+	bus->dev.device_node = np;
+
+	dev->priv = bus;
+
+	ret = mdiobus_register(bus);
+	if (!ret)
+		return 0;
+
+	free(bus);
+free_mdo:
+	gpio_free(info->mdo);
+free_mdc:
+	gpio_free(info->mdc);
+free_mdio:
+	gpio_free(info->mdio);
+free_info:
+	free(info);
+	return ret;
+}
+
+static const struct of_device_id gpio_mdio_dt_ids[] = {
+	{ .compatible = "virtual,mdio-gpio", },
+	{ /* sentinel */ }
+};
+
+static struct driver_d mdio_gpio_driver = {
+	.name = "mdio-gpio",
+	.probe = mdio_gpio_probe,
+	.of_compatible = DRV_OF_COMPAT(gpio_mdio_dt_ids),
+};
+device_platform_driver(mdio_gpio_driver);
diff --git a/include/linux/mdio-bitbang.h b/include/linux/mdio-bitbang.h
new file mode 100644
index 0000000..76f52bb
--- /dev/null
+++ b/include/linux/mdio-bitbang.h
@@ -0,0 +1,45 @@
+#ifndef __LINUX_MDIO_BITBANG_H
+#define __LINUX_MDIO_BITBANG_H
+
+#include <linux/phy.h>
+
+struct module;
+
+struct mdiobb_ctrl;
+
+struct mdiobb_ops {
+	struct module *owner;
+
+	/* Set the Management Data Clock high if level is one,
+	 * low if level is zero.
+	 */
+	void (*set_mdc)(struct mdiobb_ctrl *ctrl, int level);
+
+	/* Configure the Management Data I/O pin as an input if
+	 * "output" is zero, or an output if "output" is one.
+	 */
+	void (*set_mdio_dir)(struct mdiobb_ctrl *ctrl, int output);
+
+	/* Set the Management Data I/O pin high if value is one,
+	 * low if "value" is zero.  This may only be called
+	 * when the MDIO pin is configured as an output.
+	 */
+	void (*set_mdio_data)(struct mdiobb_ctrl *ctrl, int value);
+
+	/* Retrieve the state Management Data I/O pin. */
+	int (*get_mdio_data)(struct mdiobb_ctrl *ctrl);
+};
+
+struct mdiobb_ctrl {
+	const struct mdiobb_ops *ops;
+	/* reset callback */
+	int (*reset)(struct mii_bus *bus);
+};
+
+/* The returned bus is not yet registered with the phy layer. */
+struct mii_bus *alloc_mdio_bitbang(struct mdiobb_ctrl *ctrl);
+
+/* The bus must already have been unregistered. */
+void free_mdio_bitbang(struct mii_bus *bus);
+
+#endif
-- 
2.5.0


_______________________________________________
barebox mailing list
barebox@lists.infradead.org
http://lists.infradead.org/mailman/listinfo/barebox

^ permalink raw reply	[flat|nested] 16+ messages in thread

* [PATCH v2 3/8] miitool: Fix PHY argument handling
  2016-02-01  3:10 [PATCH v2 0/8] Bitbang MDIO, miitool changes Andrey Smirnov
  2016-02-01  3:10 ` [PATCH v2 1/8] include/linux/phy.h: Add MII_ADDR_C45 Andrey Smirnov
  2016-02-01  3:10 ` [PATCH v2 2/8] net: Port bitbanged MDIO code from Linux kernel Andrey Smirnov
@ 2016-02-01  3:10 ` Andrey Smirnov
  2016-02-01  3:10 ` [PATCH v2 4/8] mdio_bus: Change dev_info to dev_dbg Andrey Smirnov
                   ` (4 subsequent siblings)
  7 siblings, 0 replies; 16+ messages in thread
From: Andrey Smirnov @ 2016-02-01  3:10 UTC (permalink / raw)
  To: barebox; +Cc: Andrey Smirnov, Andrey Gusakov

Instead of displaying the status of PHY "PHY" the tool will print status
of all PHYs it encounters while searching for the one that was
requested. This commit fixes the logic such that only requested
information is printed.

Signed-off-by: Andrey Gusakov <andrey.gusakov@cogentembedded.com>
Signed-off-by: Andrey Smirnov <andrew.smirnov@gmail.com>
---
 commands/miitool.c | 25 +++++++++++++++++--------
 1 file changed, 17 insertions(+), 8 deletions(-)

diff --git a/commands/miitool.c b/commands/miitool.c
index c62e758..9ee3597 100644
--- a/commands/miitool.c
+++ b/commands/miitool.c
@@ -233,18 +233,27 @@ static void mdiobus_show(struct device_d *dev, char *phydevname, int verbose)
 		struct phy_device *phydev;
 
 		phydev = mdiobus_scan(mii, i);
-		if (IS_ERR(phydev))
+		if (IS_ERR(phydev) || !phydev->registered)
 			continue;
-		if (phydev->registered) {
 
-			show_basic_mii(mii, phydev, verbose);
+		/*
+		 * If we are looking for a secific phy, called
+		 * 'phydevname', but current phydev is not it, skip to
+		 * the next iteration
+		 */
+		if (phydevname &&
+		    strcmp(phydev->cdev.name, phydevname))
+			continue;
 
-			if (phydevname &&
-				!strcmp(phydev->cdev.name, phydevname)) {
-				return;
-			}
-		}
+		show_basic_mii(mii, phydev, verbose);
 
+		/*
+		 * We were looking for a specific device and at this
+		 * point we already shown the info about it so end the
+		 * loop and exit
+		 */
+		if (phydevname)
+			break;
 	}
 
 	return;
-- 
2.5.0


_______________________________________________
barebox mailing list
barebox@lists.infradead.org
http://lists.infradead.org/mailman/listinfo/barebox

^ permalink raw reply	[flat|nested] 16+ messages in thread

* [PATCH v2 4/8] mdio_bus: Change dev_info to dev_dbg
  2016-02-01  3:10 [PATCH v2 0/8] Bitbang MDIO, miitool changes Andrey Smirnov
                   ` (2 preceding siblings ...)
  2016-02-01  3:10 ` [PATCH v2 3/8] miitool: Fix PHY argument handling Andrey Smirnov
@ 2016-02-01  3:10 ` Andrey Smirnov
  2016-02-01  3:10 ` [PATCH v2 5/8] mdio_bus: Add mdiobus_get_bus() function Andrey Smirnov
                   ` (3 subsequent siblings)
  7 siblings, 0 replies; 16+ messages in thread
From: Andrey Smirnov @ 2016-02-01  3:10 UTC (permalink / raw)
  To: barebox; +Cc: Andrey Smirnov

Change dev_info to dev_dbg in mdiobus_detect for displaying phy's
registration status as it is in of_mdiobus_register_phy(). While that
information is useful for debugging, user doesn't really need to see
that information every time they call miitool for the first time.
---
 drivers/net/phy/mdio_bus.c | 2 +-
 1 file changed, 1 insertion(+), 1 deletion(-)

diff --git a/drivers/net/phy/mdio_bus.c b/drivers/net/phy/mdio_bus.c
index 0959c45..54d2f8f 100644
--- a/drivers/net/phy/mdio_bus.c
+++ b/drivers/net/phy/mdio_bus.c
@@ -43,7 +43,7 @@ int mdiobus_detect(struct device_d *dev)
 		ret = phy_register_device(phydev);
 		if (ret)
 			dev_err(dev, "failed to register phy: %s\n", strerror(-ret));
-		dev_info(dev, "registered phy as /dev/%s\n", phydev->cdev.name);
+		dev_dbg(dev, "registered phy as /dev/%s\n", phydev->cdev.name);
 	}
 
 	return 0;
-- 
2.5.0


_______________________________________________
barebox mailing list
barebox@lists.infradead.org
http://lists.infradead.org/mailman/listinfo/barebox

^ permalink raw reply	[flat|nested] 16+ messages in thread

* [PATCH v2 5/8] mdio_bus: Add mdiobus_get_bus() function
  2016-02-01  3:10 [PATCH v2 0/8] Bitbang MDIO, miitool changes Andrey Smirnov
                   ` (3 preceding siblings ...)
  2016-02-01  3:10 ` [PATCH v2 4/8] mdio_bus: Change dev_info to dev_dbg Andrey Smirnov
@ 2016-02-01  3:10 ` Andrey Smirnov
  2016-02-01  3:10 ` [PATCH v2 6/8] miitool: Don't print negative parent IDs Andrey Smirnov
                   ` (2 subsequent siblings)
  7 siblings, 0 replies; 16+ messages in thread
From: Andrey Smirnov @ 2016-02-01  3:10 UTC (permalink / raw)
  To: barebox; +Cc: Andrey Smirnov

Add mdiobus_get_bus() -- a function to get a MDIO bus by its number

Signed-off-by: Andrey Smirnov <andrew.smirnov@gmail.com>
---
 drivers/net/phy/mdio_bus.c | 19 +++++++++++++++++++
 include/linux/phy.h        |  2 ++
 2 files changed, 21 insertions(+)

diff --git a/drivers/net/phy/mdio_bus.c b/drivers/net/phy/mdio_bus.c
index 54d2f8f..b74b27e 100644
--- a/drivers/net/phy/mdio_bus.c
+++ b/drivers/net/phy/mdio_bus.c
@@ -187,6 +187,25 @@ struct phy_device *mdiobus_scan(struct mii_bus *bus, int addr)
 }
 EXPORT_SYMBOL(mdiobus_scan);
 
+
+/**
+ *
+ * mdio_get_bus - get a MDIO bus from its busnum
+ *
+ * @param	busnum	the desired bus number
+ *
+ */
+struct mii_bus *mdiobus_get_bus(int busnum)
+{
+	struct mii_bus *mii;
+
+	for_each_mii_bus(mii)
+		if (mii->dev.id == busnum)
+			return mii;
+
+	return NULL;
+}
+
 /**
  * mdio_bus_match - determine if given PHY driver supports the given PHY device
  * @dev: target PHY device
diff --git a/include/linux/phy.h b/include/linux/phy.h
index 58e69da..4e88936 100644
--- a/include/linux/phy.h
+++ b/include/linux/phy.h
@@ -114,6 +114,8 @@ int mdiobus_detect(struct device_d *dev);
 #define for_each_mii_bus(mii) \
 	list_for_each_entry(mii, &mii_bus_list, list)
 
+struct mii_bus *mdiobus_get_bus(int busnum);
+
 /**
  * mdiobus_read - Convenience function for reading a given MII mgmt register
  * @bus: the mii_bus struct
-- 
2.5.0


_______________________________________________
barebox mailing list
barebox@lists.infradead.org
http://lists.infradead.org/mailman/listinfo/barebox

^ permalink raw reply	[flat|nested] 16+ messages in thread

* [PATCH v2 6/8] miitool: Don't print negative parent IDs
  2016-02-01  3:10 [PATCH v2 0/8] Bitbang MDIO, miitool changes Andrey Smirnov
                   ` (4 preceding siblings ...)
  2016-02-01  3:10 ` [PATCH v2 5/8] mdio_bus: Add mdiobus_get_bus() function Andrey Smirnov
@ 2016-02-01  3:10 ` Andrey Smirnov
  2016-02-01  3:10 ` [PATCH v2 7/8] mdio_bus: Change PHY's naming scheme Andrey Smirnov
  2016-02-01  3:10 ` [PATCH v2 8/8] miitool: Add code to register a PHY Andrey Smirnov
  7 siblings, 0 replies; 16+ messages in thread
From: Andrey Smirnov @ 2016-02-01  3:10 UTC (permalink / raw)
  To: barebox; +Cc: Andrey Smirnov

Do not include ID of the parent to mii_bus if that ID is negative since
it produces a rather confusing string (e.g. "mdio.11-1", which is very
likely to be interpreted as "mdio.11<dash>1").

Signed-off-by: Andrey Smirnov <andrew.smirnov@gmail.com>
---
 commands/miitool.c | 5 +++--
 1 file changed, 3 insertions(+), 2 deletions(-)

diff --git a/commands/miitool.c b/commands/miitool.c
index 9ee3597..9ea5ab5 100644
--- a/commands/miitool.c
+++ b/commands/miitool.c
@@ -115,8 +115,9 @@ static int show_basic_mii(struct mii_bus *mii, struct phy_device *phydev,
 	for (i = 0; i < 32; i++)
 		mii_val[i] = mii->read(mii, phydev->addr, i);
 
-	printf("%s: %s%d: ", phydev->cdev.name,
-		mii->parent->name, mii->parent->id);
+	printf((mii->parent->id) < 0 ? "%s: %s:" : "%s: %s%d: ",
+	       phydev->cdev.name, mii->parent->name, mii->parent->id);
+
 
 	if (mii_val[MII_BMCR] == 0xffff || mii_val[MII_BMSR] == 0x0000) {
 		fprintf(stderr, "  No MII transceiver present!.\n");
-- 
2.5.0


_______________________________________________
barebox mailing list
barebox@lists.infradead.org
http://lists.infradead.org/mailman/listinfo/barebox

^ permalink raw reply	[flat|nested] 16+ messages in thread

* [PATCH v2 7/8] mdio_bus: Change PHY's naming scheme
  2016-02-01  3:10 [PATCH v2 0/8] Bitbang MDIO, miitool changes Andrey Smirnov
                   ` (5 preceding siblings ...)
  2016-02-01  3:10 ` [PATCH v2 6/8] miitool: Don't print negative parent IDs Andrey Smirnov
@ 2016-02-01  3:10 ` Andrey Smirnov
  2016-02-03  7:36   ` Sascha Hauer
  2016-02-01  3:10 ` [PATCH v2 8/8] miitool: Add code to register a PHY Andrey Smirnov
  7 siblings, 1 reply; 16+ messages in thread
From: Andrey Smirnov @ 2016-02-01  3:10 UTC (permalink / raw)
  To: barebox; +Cc: Andrey Smirnov

Change the way PHY devices are named upon creation. This commit replaces
sequentialy numbered "/dev/phy%d" with "/dev/mdio%d-phy%02x". This way
it is significanlty easier to identify which PHY in real-life (e.g. on a
schematic) corresponds to which device in /dev.

Also, replace asprintf with xasprintf to provide some form of memory
allocation failure checking.

Signed-off-by: Andrey Smirnov <andrew.smirnov@gmail.com>
---
 drivers/net/phy/mdio_bus.c | 4 +++-
 1 file changed, 3 insertions(+), 1 deletion(-)

diff --git a/drivers/net/phy/mdio_bus.c b/drivers/net/phy/mdio_bus.c
index b74b27e..41bf018 100644
--- a/drivers/net/phy/mdio_bus.c
+++ b/drivers/net/phy/mdio_bus.c
@@ -333,7 +333,9 @@ static int mdio_bus_probe(struct device_d *_dev)
 	dev_add_param_int_ro(&dev->dev, "phy_addr", dev->addr, "%d");
 	dev_add_param_int_ro(&dev->dev, "phy_id", dev->phy_id, "0x%08x");
 
-	dev->cdev.name = asprintf("phy%d", _dev->id);
+	dev->cdev.name = xasprintf("mdio%d-phy%02x",
+				   dev->bus->dev.id,
+				   dev->addr);
 	dev->cdev.size = 64;
 	dev->cdev.ops = &phydev_ops;
 	dev->cdev.priv = dev;
-- 
2.5.0


_______________________________________________
barebox mailing list
barebox@lists.infradead.org
http://lists.infradead.org/mailman/listinfo/barebox

^ permalink raw reply	[flat|nested] 16+ messages in thread

* [PATCH v2 8/8] miitool: Add code to register a PHY
  2016-02-01  3:10 [PATCH v2 0/8] Bitbang MDIO, miitool changes Andrey Smirnov
                   ` (6 preceding siblings ...)
  2016-02-01  3:10 ` [PATCH v2 7/8] mdio_bus: Change PHY's naming scheme Andrey Smirnov
@ 2016-02-01  3:10 ` Andrey Smirnov
  2016-02-01  9:35   ` Sascha Hauer
  7 siblings, 1 reply; 16+ messages in thread
From: Andrey Smirnov @ 2016-02-01  3:10 UTC (permalink / raw)
  To: barebox; +Cc: Andrey Smirnov

This commit changes the behaviour of the 'miitool'. Now in order to show
PHY's link information 'miitool' should be invoked as such:

miitool -s [PHY]

Also, implment code to allow to register a dummy PHY device in order to
be able to perform raw MDIO bus access.

Signed-off-by: Andrey Smirnov <andrew.smirnov@gmail.com>
---
 commands/miitool.c    | 87 ++++++++++++++++++++++++++++++++++++++++-----------
 drivers/net/phy/phy.c |  9 ++++--
 include/linux/phy.h   |  1 +
 3 files changed, 77 insertions(+), 20 deletions(-)

diff --git a/commands/miitool.c b/commands/miitool.c
index 9ea5ab5..b61113c 100644
--- a/commands/miitool.c
+++ b/commands/miitool.c
@@ -260,53 +260,104 @@ static void mdiobus_show(struct device_d *dev, char *phydevname, int verbose)
 	return;
 }
 
+enum miitool_operations {
+	MIITOOL_NOOP,
+	MIITOOL_SHOW,
+	MIITOOL_REGISTER,
+};
+
 static int do_miitool(int argc, char *argv[])
 {
-	char *phydevname;
+	char *phydevname = NULL;
 	struct mii_bus *mii;
-	int opt;
-	int argc_min;
-	int verbose;
+	int opt, ret;
+	int verbose = 0;
+	struct phy_device *phydev;
+	enum miitool_operations action = MIITOOL_NOOP;
+	int addr = -1, bus = -1;
 
-	verbose = 0;
-	while ((opt = getopt(argc, argv, "v")) > 0) {
+	while ((opt = getopt(argc, argv, "vs:rb:a:")) > 0) {
 		switch (opt) {
+		case 'a':
+			addr = simple_strtol(optarg, NULL, 0);
+			break;
+		case 'b':
+			bus = simple_strtoul(optarg, NULL, 0);
+			break;
+		case 's':
+			action = MIITOOL_SHOW;
+			phydevname = xstrdup(optarg);
+			break;
+		case 'r':
+			action = MIITOOL_REGISTER;
+			break;
 		case 'v':
 			verbose++;
 			break;
 		default:
-			return COMMAND_ERROR_USAGE;
+			ret = COMMAND_ERROR_USAGE;
+			goto free_phydevname;
 		}
 	}
 
-	argc_min = optind + 1;
+	switch (action) {
+	case MIITOOL_REGISTER:
+		if (addr < 0 || bus < 0) {
+			ret = COMMAND_ERROR_USAGE;
+			goto free_phydevname;
+		}
 
-	phydevname = NULL;
-	if (argc >= argc_min) {
-		phydevname = argv[optind];
-	}
+		mii = mdiobus_get_bus(bus);
+		if (!mii) {
+			printf("Can't find MDIO bus #%d\n", bus);
+			ret = COMMAND_ERROR;
+			goto free_phydevname;
+		}
+
+		phydev = phy_device_create(mii, addr, -1);
+		ret = phy_register_device(phydev);
+		if (ret) {
+			dev_err(&mii->dev, "failed to register phy: %s\n",
+				strerror(-ret));
+			goto free_phydevname;
+		}
 
-	for_each_mii_bus(mii) {
-		mdiobus_detect(&mii->dev);
-		mdiobus_show(&mii->dev, phydevname, verbose);
+		break;
+	default:
+	case MIITOOL_SHOW:
+		for_each_mii_bus(mii) {
+			mdiobus_detect(&mii->dev);
+			mdiobus_show(&mii->dev, phydevname, verbose);
+		}
+		break;
 	}
 
-	return COMMAND_SUCCESS;
+	ret = COMMAND_SUCCESS;
+
+free_phydevname:
+	free(phydevname);
+	return ret;
 }
 
 BAREBOX_CMD_HELP_START(miitool)
 BAREBOX_CMD_HELP_TEXT("This utility checks or sets the status of a network interface's")
-BAREBOX_CMD_HELP_TEXT("Media Independent Interface (MII) unit. Most fast ethernet")
+BAREBOX_CMD_HELP_TEXT("Media Independent Interface (MII) unit as well as allowing to")
+BAREBOX_CMD_HELP_TEXT"register dummy PHY devices for raw MDIO access. Most fast ethernet")
 BAREBOX_CMD_HELP_TEXT("adapters use an MII to autonegotiate link speed and duplex setting.")
 BAREBOX_CMD_HELP_TEXT("")
 BAREBOX_CMD_HELP_TEXT("Options:")
 BAREBOX_CMD_HELP_OPT("-v", "increase verbosity")
+BAREBOX_CMD_HELP_OPT("-s", "show PHY's status (not prioviding PHY prints status of all)")
+BAREBOX_CMD_HELP_OPT("-r", "register a dummy PHY")
+BAREBOX_CMD_HELP_OPT("-b", "dummy PHY's bus")
+BAREBOX_CMD_HELP_OPT("-a", "dummy PHY's address")
 BAREBOX_CMD_HELP_END
 
 BAREBOX_CMD_START(miitool)
 	.cmd		= do_miitool,
 	BAREBOX_CMD_DESC("view media-independent interface status")
-	BAREBOX_CMD_OPTS("[-v] PHY")
+	BAREBOX_CMD_OPTS("[-vs] PHY")
+	BAREBOX_CMD_OPTS("[-vrba]")
 	BAREBOX_CMD_GROUP(CMD_GRP_NET)
 	BAREBOX_CMD_HELP(cmd_miitool_help)
 BAREBOX_CMD_END
diff --git a/drivers/net/phy/phy.c b/drivers/net/phy/phy.c
index 25c999c..6ddf5d7 100644
--- a/drivers/net/phy/phy.c
+++ b/drivers/net/phy/phy.c
@@ -147,8 +147,13 @@ int phy_scan_fixups(struct phy_device *phydev)
 
 	return 0;
 }
-
-static struct phy_device *phy_device_create(struct mii_bus *bus, int addr, int phy_id)
+/**
+ * phy_device_create - creates a struct phy_device.
+ * @bus: the target MII bus
+ * @addr: PHY address on the MII bus
+ * @phy_id: PHY ID.
+ */
+struct phy_device *phy_device_create(struct mii_bus *bus, int addr, int phy_id)
 {
 	struct phy_device *phydev;
 
diff --git a/include/linux/phy.h b/include/linux/phy.h
index 4e88936..38b0670 100644
--- a/include/linux/phy.h
+++ b/include/linux/phy.h
@@ -271,6 +271,7 @@ struct phy_device *get_phy_device(struct mii_bus *bus, int addr);
 int phy_init(void);
 int phy_init_hw(struct phy_device *phydev);
 
+struct phy_device *phy_device_create(struct mii_bus *bus, int addr, int phy_id);
 int phy_register_device(struct phy_device* dev);
 void phy_unregister_device(struct phy_device *phydev);
 
-- 
2.5.0


_______________________________________________
barebox mailing list
barebox@lists.infradead.org
http://lists.infradead.org/mailman/listinfo/barebox

^ permalink raw reply	[flat|nested] 16+ messages in thread

* Re: [PATCH v2 8/8] miitool: Add code to register a PHY
  2016-02-01  3:10 ` [PATCH v2 8/8] miitool: Add code to register a PHY Andrey Smirnov
@ 2016-02-01  9:35   ` Sascha Hauer
  2016-02-03  0:41     ` Andrey Smirnov
  0 siblings, 1 reply; 16+ messages in thread
From: Sascha Hauer @ 2016-02-01  9:35 UTC (permalink / raw)
  To: Andrey Smirnov; +Cc: barebox

Hi Andrey,

On Sun, Jan 31, 2016 at 07:10:13PM -0800, Andrey Smirnov wrote:
> This commit changes the behaviour of the 'miitool'. Now in order to show
> PHY's link information 'miitool' should be invoked as such:
> 
> miitool -s [PHY]
> 
> Also, implment code to allow to register a dummy PHY device in order to
> be able to perform raw MDIO bus access.

These are not necessarily dummy phy devices, in fact if they were you
wouldn't be interested in them ;)

Do we need a way to register an individual phy? Wouldn't it be enough to
add a -f(orce) option to register all phys on all busses even if there's
nothing detected on them?

Sascha

-- 
Pengutronix e.K.                           |                             |
Industrial Linux Solutions                 | http://www.pengutronix.de/  |
Peiner Str. 6-8, 31137 Hildesheim, Germany | Phone: +49-5121-206917-0    |
Amtsgericht Hildesheim, HRA 2686           | Fax:   +49-5121-206917-5555 |

_______________________________________________
barebox mailing list
barebox@lists.infradead.org
http://lists.infradead.org/mailman/listinfo/barebox

^ permalink raw reply	[flat|nested] 16+ messages in thread

* Re: [PATCH v2 8/8] miitool: Add code to register a PHY
  2016-02-01  9:35   ` Sascha Hauer
@ 2016-02-03  0:41     ` Andrey Smirnov
  2016-02-03  7:34       ` Sascha Hauer
  0 siblings, 1 reply; 16+ messages in thread
From: Andrey Smirnov @ 2016-02-03  0:41 UTC (permalink / raw)
  To: Sascha Hauer; +Cc: barebox

On Mon, Feb 1, 2016 at 1:35 AM, Sascha Hauer <s.hauer@pengutronix.de> wrote:
> Hi Andrey,
>
> On Sun, Jan 31, 2016 at 07:10:13PM -0800, Andrey Smirnov wrote:
>> This commit changes the behaviour of the 'miitool'. Now in order to show
>> PHY's link information 'miitool' should be invoked as such:
>>
>> miitool -s [PHY]
>>
>> Also, implment code to allow to register a dummy PHY device in order to
>> be able to perform raw MDIO bus access.
>
> These are not necessarily dummy phy devices, in fact if they were you
> wouldn't be interested in them ;)

Poor choice of words, perhaps :-). Now that I think of it I think
"driver-less" would be a better description.

>
> Do we need a way to register an individual phy? Wouldn't it be enough to
> add a -f(orce) option to register all phys on all busses even if there's
> nothing detected on them?

If we go with "-f" we would still overwhelm the /dev with a lot of
devices (in my use-case 96 of them), it's just we won't do that on the
first run on "miitool".

Andrey

_______________________________________________
barebox mailing list
barebox@lists.infradead.org
http://lists.infradead.org/mailman/listinfo/barebox

^ permalink raw reply	[flat|nested] 16+ messages in thread

* Re: [PATCH v2 8/8] miitool: Add code to register a PHY
  2016-02-03  0:41     ` Andrey Smirnov
@ 2016-02-03  7:34       ` Sascha Hauer
  2016-02-03 19:20         ` Andrey Smirnov
  0 siblings, 1 reply; 16+ messages in thread
From: Sascha Hauer @ 2016-02-03  7:34 UTC (permalink / raw)
  To: Andrey Smirnov; +Cc: barebox

On Tue, Feb 02, 2016 at 04:41:46PM -0800, Andrey Smirnov wrote:
> On Mon, Feb 1, 2016 at 1:35 AM, Sascha Hauer <s.hauer@pengutronix.de> wrote:
> > Hi Andrey,
> >
> > On Sun, Jan 31, 2016 at 07:10:13PM -0800, Andrey Smirnov wrote:
> >> This commit changes the behaviour of the 'miitool'. Now in order to show
> >> PHY's link information 'miitool' should be invoked as such:
> >>
> >> miitool -s [PHY]
> >>
> >> Also, implment code to allow to register a dummy PHY device in order to
> >> be able to perform raw MDIO bus access.
> >
> > These are not necessarily dummy phy devices, in fact if they were you
> > wouldn't be interested in them ;)
> 
> Poor choice of words, perhaps :-). Now that I think of it I think
> "driver-less" would be a better description.
> 
> >
> > Do we need a way to register an individual phy? Wouldn't it be enough to
> > add a -f(orce) option to register all phys on all busses even if there's
> > nothing detected on them?
> 
> If we go with "-f" we would still overwhelm the /dev with a lot of
> devices (in my use-case 96 of them), it's just we won't do that on the
> first run on "miitool".

Ok, fine with me.

What I'd like to do though is the following change. It changes the way
how the mdio bus / phy address is specified. With separate options for
specifying the mdio bus and address it's not clear that the -a, -b and
-r options only make sense when given together, whereas the -a and -b
options are ignored when information is printed.
While at it I added a check for the maximum phy address and added a
<varname> to BAREBOX_CMD_HELP_OPT when an option requires an argument.

Sascha

--------------------------------------8<--------------------------

From d5dc3c3608311175d2250d951d0362a4241e1da0 Mon Sep 17 00:00:00 2001
From: Sascha Hauer <s.hauer@pengutronix.de>
Date: Wed, 3 Feb 2016 08:15:28 +0100
Subject: [PATCH] fixup! miitool: Add code to register a PHY

Signed-off-by: Sascha Hauer <s.hauer@pengutronix.de>
---
 commands/miitool.c | 35 +++++++++++++++++++++--------------
 1 file changed, 21 insertions(+), 14 deletions(-)

diff --git a/commands/miitool.c b/commands/miitool.c
index 9e86925..ba6e604 100644
--- a/commands/miitool.c
+++ b/commands/miitool.c
@@ -269,14 +269,16 @@ enum miitool_operations {
 static int do_miitool(int argc, char *argv[])
 {
 	char *phydevname = NULL;
+	char *regstr = NULL;
+	char *endp;
 	struct mii_bus *mii;
 	int opt, ret;
 	int verbose = 0;
 	struct phy_device *phydev;
 	enum miitool_operations action = MIITOOL_NOOP;
-	int addr = -1, bus = -1;
+	int addr, bus;
 
-	while ((opt = getopt(argc, argv, "vs:rb:a:")) > 0) {
+	while ((opt = getopt(argc, argv, "vs:r:")) > 0) {
 		switch (opt) {
 		case 'a':
 			addr = simple_strtol(optarg, NULL, 0);
@@ -290,6 +292,7 @@ static int do_miitool(int argc, char *argv[])
 			break;
 		case 'r':
 			action = MIITOOL_REGISTER;
+			regstr = optarg;
 			break;
 		case 'v':
 			verbose++;
@@ -302,10 +305,16 @@ static int do_miitool(int argc, char *argv[])
 
 	switch (action) {
 	case MIITOOL_REGISTER:
-		if (addr < 0 || bus < 0) {
-			ret = COMMAND_ERROR_USAGE;
-			goto free_phydevname;
+		bus = simple_strtoul(regstr, &endp, 0);
+		if (*endp != ':') {
+			printf("No colon between bus and address\n");
+			return COMMAND_ERROR_USAGE;
 		}
+		endp++;
+		addr = simple_strtoul(endp, NULL, 0);
+
+		if (addr >= PHY_MAX_ADDR)
+			printf("Address out of range (max %d)\n", PHY_MAX_ADDR - 1);
 
 		mii = mdiobus_get_bus(bus);
 		if (!mii) {
@@ -317,11 +326,12 @@ static int do_miitool(int argc, char *argv[])
 		phydev = phy_device_create(mii, addr, -1);
 		ret = phy_register_device(phydev);
 		if (ret) {
-			dev_err(&mii->dev, "failed to register phy: %s\n",
-				strerror(-ret));
+			printf("failed to register phy %s: %s\n",
+				dev_name(&phydev->dev), strerror(-ret));
 			goto free_phydevname;
+		} else {
+			printf("registered phy %s\n", dev_name(&phydev->dev));
 		}
-
 		break;
 	default:
 	case MIITOOL_SHOW:
@@ -347,17 +357,14 @@ BAREBOX_CMD_HELP_TEXT("adapters use an MII to autonegotiate link speed and duple
 BAREBOX_CMD_HELP_TEXT("")
 BAREBOX_CMD_HELP_TEXT("Options:")
 BAREBOX_CMD_HELP_OPT("-v", "increase verbosity")
-BAREBOX_CMD_HELP_OPT("-s", "show PHY's status (not prioviding PHY prints status of all)")
-BAREBOX_CMD_HELP_OPT("-r", "register a dummy PHY")
-BAREBOX_CMD_HELP_OPT("-b", "dummy PHY's bus")
-BAREBOX_CMD_HELP_OPT("-a", "dummy PHY's address")
+BAREBOX_CMD_HELP_OPT("-s <devname>", "show PHY status (not providing PHY prints status of all)")
+BAREBOX_CMD_HELP_OPT("-r <busno>:<adr>", "register a PHY")
 BAREBOX_CMD_HELP_END
 
 BAREBOX_CMD_START(miitool)
 	.cmd		= do_miitool,
 	BAREBOX_CMD_DESC("view media-independent interface status")
-	BAREBOX_CMD_OPTS("[-vs] PHY")
-	BAREBOX_CMD_OPTS("[-vrba]")
+	BAREBOX_CMD_OPTS("[-vsr]")
 	BAREBOX_CMD_GROUP(CMD_GRP_NET)
 	BAREBOX_CMD_HELP(cmd_miitool_help)
 BAREBOX_CMD_END
-- 
2.7.0.rc3


-- 
Pengutronix e.K.                           |                             |
Industrial Linux Solutions                 | http://www.pengutronix.de/  |
Peiner Str. 6-8, 31137 Hildesheim, Germany | Phone: +49-5121-206917-0    |
Amtsgericht Hildesheim, HRA 2686           | Fax:   +49-5121-206917-5555 |

_______________________________________________
barebox mailing list
barebox@lists.infradead.org
http://lists.infradead.org/mailman/listinfo/barebox

^ permalink raw reply	[flat|nested] 16+ messages in thread

* Re: [PATCH v2 7/8] mdio_bus: Change PHY's naming scheme
  2016-02-01  3:10 ` [PATCH v2 7/8] mdio_bus: Change PHY's naming scheme Andrey Smirnov
@ 2016-02-03  7:36   ` Sascha Hauer
  2016-02-03 19:23     ` Andrey Smirnov
  0 siblings, 1 reply; 16+ messages in thread
From: Sascha Hauer @ 2016-02-03  7:36 UTC (permalink / raw)
  To: Andrey Smirnov; +Cc: barebox

On Sun, Jan 31, 2016 at 07:10:12PM -0800, Andrey Smirnov wrote:
> Change the way PHY devices are named upon creation. This commit replaces
> sequentialy numbered "/dev/phy%d" with "/dev/mdio%d-phy%02x". This way
> it is significanlty easier to identify which PHY in real-life (e.g. on a
> schematic) corresponds to which device in /dev.
> 
> Also, replace asprintf with xasprintf to provide some form of memory
> allocation failure checking.
> 
> Signed-off-by: Andrey Smirnov <andrew.smirnov@gmail.com>
> ---
>  drivers/net/phy/mdio_bus.c | 4 +++-
>  1 file changed, 3 insertions(+), 1 deletion(-)
> 
> diff --git a/drivers/net/phy/mdio_bus.c b/drivers/net/phy/mdio_bus.c
> index b74b27e..41bf018 100644
> --- a/drivers/net/phy/mdio_bus.c
> +++ b/drivers/net/phy/mdio_bus.c
> @@ -333,7 +333,9 @@ static int mdio_bus_probe(struct device_d *_dev)
>  	dev_add_param_int_ro(&dev->dev, "phy_addr", dev->addr, "%d");
>  	dev_add_param_int_ro(&dev->dev, "phy_id", dev->phy_id, "0x%08x");
>  
> -	dev->cdev.name = asprintf("phy%d", _dev->id);
> +	dev->cdev.name = xasprintf("mdio%d-phy%02x",
> +				   dev->bus->dev.id,
> +				   dev->addr);

While at it we can change the phy device name in the same way to be
consistent:

------------------------------8<--------------------------


From 21eae26cbff053e42375edbe51f800f56173116a Mon Sep 17 00:00:00 2001
From: Sascha Hauer <s.hauer@pengutronix.de>
Date: Wed, 3 Feb 2016 08:14:22 +0100
Subject: [PATCH 1/2] fixup! mdio_bus: Change PHY's naming scheme

---
 drivers/net/phy/phy.c | 6 ++++--
 1 file changed, 4 insertions(+), 2 deletions(-)

diff --git a/drivers/net/phy/phy.c b/drivers/net/phy/phy.c
index 6ddf5d7..be2c68b 100644
--- a/drivers/net/phy/phy.c
+++ b/drivers/net/phy/phy.c
@@ -173,8 +173,10 @@ struct phy_device *phy_device_create(struct mii_bus *bus, int addr, int phy_id)
 	phydev->bus = bus;
 	phydev->dev.bus = &mdio_bus_type;
 
-	strcpy(phydev->dev.name, "phy");
-	phydev->dev.id = DEVICE_ID_DYNAMIC;
+	sprintf(phydev->dev.name, "mdio%d-phy%02x",
+				   phydev->bus->dev.id,
+				   phydev->addr);
+	phydev->dev.id = DEVICE_ID_SINGLE;
 
 	return phydev;
 }
-- 
2.7.0.rc3

-- 
Pengutronix e.K.                           |                             |
Industrial Linux Solutions                 | http://www.pengutronix.de/  |
Peiner Str. 6-8, 31137 Hildesheim, Germany | Phone: +49-5121-206917-0    |
Amtsgericht Hildesheim, HRA 2686           | Fax:   +49-5121-206917-5555 |

_______________________________________________
barebox mailing list
barebox@lists.infradead.org
http://lists.infradead.org/mailman/listinfo/barebox

^ permalink raw reply	[flat|nested] 16+ messages in thread

* Re: [PATCH v2 8/8] miitool: Add code to register a PHY
  2016-02-03  7:34       ` Sascha Hauer
@ 2016-02-03 19:20         ` Andrey Smirnov
  0 siblings, 0 replies; 16+ messages in thread
From: Andrey Smirnov @ 2016-02-03 19:20 UTC (permalink / raw)
  To: Sascha Hauer; +Cc: barebox

> What I'd like to do though is the following change. It changes the way
> how the mdio bus / phy address is specified. With separate options for
> specifying the mdio bus and address it's not clear that the -a, -b and
> -r options only make sense when given together, whereas the -a and -b
> options are ignored when information is printed.
> While at it I added a check for the maximum phy address and added a
> <varname> to BAREBOX_CMD_HELP_OPT when an option requires an argument.
>

Yeah, I agree, single "-r" option instead of what I originally had
makes much cleaner UI. Feel free to squash the fixup into my patch or
if it's easier I can make v3 of the patch set.

Thanks,
Andrey

_______________________________________________
barebox mailing list
barebox@lists.infradead.org
http://lists.infradead.org/mailman/listinfo/barebox

^ permalink raw reply	[flat|nested] 16+ messages in thread

* Re: [PATCH v2 7/8] mdio_bus: Change PHY's naming scheme
  2016-02-03  7:36   ` Sascha Hauer
@ 2016-02-03 19:23     ` Andrey Smirnov
  2016-02-04  7:47       ` Sascha Hauer
  0 siblings, 1 reply; 16+ messages in thread
From: Andrey Smirnov @ 2016-02-03 19:23 UTC (permalink / raw)
  To: Sascha Hauer; +Cc: barebox

On Tue, Feb 2, 2016 at 11:36 PM, Sascha Hauer <s.hauer@pengutronix.de> wrote:
> On Sun, Jan 31, 2016 at 07:10:12PM -0800, Andrey Smirnov wrote:
>> Change the way PHY devices are named upon creation. This commit replaces
>> sequentialy numbered "/dev/phy%d" with "/dev/mdio%d-phy%02x". This way
>> it is significanlty easier to identify which PHY in real-life (e.g. on a
>> schematic) corresponds to which device in /dev.
>>
>> Also, replace asprintf with xasprintf to provide some form of memory
>> allocation failure checking.
>>
>> Signed-off-by: Andrey Smirnov <andrew.smirnov@gmail.com>
>> ---
>>  drivers/net/phy/mdio_bus.c | 4 +++-
>>  1 file changed, 3 insertions(+), 1 deletion(-)
>>
>> diff --git a/drivers/net/phy/mdio_bus.c b/drivers/net/phy/mdio_bus.c
>> index b74b27e..41bf018 100644
>> --- a/drivers/net/phy/mdio_bus.c
>> +++ b/drivers/net/phy/mdio_bus.c
>> @@ -333,7 +333,9 @@ static int mdio_bus_probe(struct device_d *_dev)
>>       dev_add_param_int_ro(&dev->dev, "phy_addr", dev->addr, "%d");
>>       dev_add_param_int_ro(&dev->dev, "phy_id", dev->phy_id, "0x%08x");
>>
>> -     dev->cdev.name = asprintf("phy%d", _dev->id);
>> +     dev->cdev.name = xasprintf("mdio%d-phy%02x",
>> +                                dev->bus->dev.id,
>> +                                dev->addr);
>
> While at it we can change the phy device name in the same way to be
> consistent:

Yeah, I agree, let's do this. Let me know if I should do v3 patch set.

Thanks,
Andrey

_______________________________________________
barebox mailing list
barebox@lists.infradead.org
http://lists.infradead.org/mailman/listinfo/barebox

^ permalink raw reply	[flat|nested] 16+ messages in thread

* Re: [PATCH v2 7/8] mdio_bus: Change PHY's naming scheme
  2016-02-03 19:23     ` Andrey Smirnov
@ 2016-02-04  7:47       ` Sascha Hauer
  0 siblings, 0 replies; 16+ messages in thread
From: Sascha Hauer @ 2016-02-04  7:47 UTC (permalink / raw)
  To: Andrey Smirnov; +Cc: barebox

Hi Andrey,

On Wed, Feb 03, 2016 at 11:23:38AM -0800, Andrey Smirnov wrote:
> On Tue, Feb 2, 2016 at 11:36 PM, Sascha Hauer <s.hauer@pengutronix.de> wrote:
> > On Sun, Jan 31, 2016 at 07:10:12PM -0800, Andrey Smirnov wrote:
> >> Change the way PHY devices are named upon creation. This commit replaces
> >> sequentialy numbered "/dev/phy%d" with "/dev/mdio%d-phy%02x". This way
> >> it is significanlty easier to identify which PHY in real-life (e.g. on a
> >> schematic) corresponds to which device in /dev.
> >>
> >> Also, replace asprintf with xasprintf to provide some form of memory
> >> allocation failure checking.
> >>
> >> Signed-off-by: Andrey Smirnov <andrew.smirnov@gmail.com>
> >> ---
> >>  drivers/net/phy/mdio_bus.c | 4 +++-
> >>  1 file changed, 3 insertions(+), 1 deletion(-)
> >>
> >> diff --git a/drivers/net/phy/mdio_bus.c b/drivers/net/phy/mdio_bus.c
> >> index b74b27e..41bf018 100644
> >> --- a/drivers/net/phy/mdio_bus.c
> >> +++ b/drivers/net/phy/mdio_bus.c
> >> @@ -333,7 +333,9 @@ static int mdio_bus_probe(struct device_d *_dev)
> >>       dev_add_param_int_ro(&dev->dev, "phy_addr", dev->addr, "%d");
> >>       dev_add_param_int_ro(&dev->dev, "phy_id", dev->phy_id, "0x%08x");
> >>
> >> -     dev->cdev.name = asprintf("phy%d", _dev->id);
> >> +     dev->cdev.name = xasprintf("mdio%d-phy%02x",
> >> +                                dev->bus->dev.id,
> >> +                                dev->addr);
> >
> > While at it we can change the phy device name in the same way to be
> > consistent:
> 
> Yeah, I agree, let's do this. Let me know if I should do v3 patch set.

I'll squash that here as necessary.

Sascha

-- 
Pengutronix e.K.                           |                             |
Industrial Linux Solutions                 | http://www.pengutronix.de/  |
Peiner Str. 6-8, 31137 Hildesheim, Germany | Phone: +49-5121-206917-0    |
Amtsgericht Hildesheim, HRA 2686           | Fax:   +49-5121-206917-5555 |

_______________________________________________
barebox mailing list
barebox@lists.infradead.org
http://lists.infradead.org/mailman/listinfo/barebox

^ permalink raw reply	[flat|nested] 16+ messages in thread

end of thread, other threads:[~2016-02-04  7:47 UTC | newest]

Thread overview: 16+ messages (download: mbox.gz / follow: Atom feed)
-- links below jump to the message on this page --
2016-02-01  3:10 [PATCH v2 0/8] Bitbang MDIO, miitool changes Andrey Smirnov
2016-02-01  3:10 ` [PATCH v2 1/8] include/linux/phy.h: Add MII_ADDR_C45 Andrey Smirnov
2016-02-01  3:10 ` [PATCH v2 2/8] net: Port bitbanged MDIO code from Linux kernel Andrey Smirnov
2016-02-01  3:10 ` [PATCH v2 3/8] miitool: Fix PHY argument handling Andrey Smirnov
2016-02-01  3:10 ` [PATCH v2 4/8] mdio_bus: Change dev_info to dev_dbg Andrey Smirnov
2016-02-01  3:10 ` [PATCH v2 5/8] mdio_bus: Add mdiobus_get_bus() function Andrey Smirnov
2016-02-01  3:10 ` [PATCH v2 6/8] miitool: Don't print negative parent IDs Andrey Smirnov
2016-02-01  3:10 ` [PATCH v2 7/8] mdio_bus: Change PHY's naming scheme Andrey Smirnov
2016-02-03  7:36   ` Sascha Hauer
2016-02-03 19:23     ` Andrey Smirnov
2016-02-04  7:47       ` Sascha Hauer
2016-02-01  3:10 ` [PATCH v2 8/8] miitool: Add code to register a PHY Andrey Smirnov
2016-02-01  9:35   ` Sascha Hauer
2016-02-03  0:41     ` Andrey Smirnov
2016-02-03  7:34       ` Sascha Hauer
2016-02-03 19:20         ` Andrey Smirnov

This is a public inbox, see mirroring instructions
for how to clone and mirror all data and code used for this inbox