2023-05-08 18:50:32

by Florian Fainelli

[permalink] [raw]
Subject: [PATCH net-next 0/3] Support for Wake-on-LAN for Broadcom PHYs

This patch series adds support for Wake-on-LAN to the Broadcom PHY
driver. Specifically the BCM54210E/B50212E are capable of supporting
Wake-on-LAN using an external pin typically wired up to a system's GPIO.

These PHY operate a programmable Ethernet MAC destination address
comparator which will fire up an interrupt whenever a match is received.
Because of that, it was necessary to introduce patch #1 which allows the
PHY driver's ->suspend() routine to be called unconditionally. This is
necessary in our case because we need a hook point into the device
suspend/resume flow to enable the wake-up interrupt as late as possible.

Patch #2 adds support for the Broadcom PHY library and driver for
Wake-on-LAN proper with the WAKE_UCAST, WAKE_MCAST, WAKE_BCAST,
WAKE_MAGIC and WAKE_MAGICSECURE. Note that WAKE_FILTER is supportable,
however this will require further discussions and be submitted as a RFC
series later on.

Patch #3 updates the GENET driver to defer to the PHY for Wake-on-LAN if
the PHY supports it, thus allowing the MAC to be powered down to
conserve power.

Florian Fainelli (3):
net: phy: Let drivers check Wake-on-LAN status
net: phy: broadcom: Add support for Wake-on-LAN
net: bcmgenet: Add support for PHY-based Wake-on-LAN

.../ethernet/broadcom/genet/bcmgenet_wol.c | 14 ++
drivers/net/phy/aquantia_main.c | 3 +
drivers/net/phy/at803x.c | 10 +
drivers/net/phy/bcm-phy-lib.c | 212 ++++++++++++++++++
drivers/net/phy/bcm-phy-lib.h | 5 +
drivers/net/phy/bcm7xxx.c | 3 +
drivers/net/phy/broadcom.c | 128 ++++++++++-
drivers/net/phy/dp83822.c | 2 +-
drivers/net/phy/dp83867.c | 3 +
drivers/net/phy/dp83tc811.c | 2 +-
drivers/net/phy/marvell-88x2222.c | 3 +
drivers/net/phy/marvell.c | 3 +
drivers/net/phy/marvell10g.c | 3 +
drivers/net/phy/micrel.c | 3 +
drivers/net/phy/microchip.c | 4 +-
drivers/net/phy/motorcomm.c | 2 +-
drivers/net/phy/phy-c45.c | 3 +
drivers/net/phy/phy_device.c | 7 +-
drivers/net/phy/realtek.c | 3 +
include/linux/brcmphy.h | 55 +++++
include/linux/phy.h | 3 +
21 files changed, 460 insertions(+), 11 deletions(-)

--
2.34.1


2023-05-08 18:50:49

by Florian Fainelli

[permalink] [raw]
Subject: [PATCH net-next 2/3] net: phy: broadcom: Add support for Wake-on-LAN

Add support for WAKE_UCAST, WAKE_MCAST, WAKE_BCAST, WAKE_MAGIC and
WAKE_MAGICSECURE. This is only supported with the BCM54210E and
compatible Ethernet PHYs. Using the in-band interrupt or an out of band
GPIO interrupts are supported.

Broadcom PHYs will generate a Wake-on-LAN level low interrupt on LED4 as
soon as one of the supported patterns is being matched. That includes
generating such an interrupt even if the PHY is operated during normal
modes. If WAKE_UCAST is selected, this could lead to the LED4 interrupt
firing up for every packet being received which is absolutely
undesirable from a performance point of view.

Because the Wake-on-LAN configuration can be set long before the system
is actually put to sleep, we cannot have an interrupt service routine to
clear on read the interrupt status register and ensure that new packet
matches will be detected.

It is desirable to enable the Wake-on-LAN interrupt as late as possible
during the system suspend process such that we limit the number of
interrupts to be handled by the system, but also conversely feed into
the Linux's system suspend way of dealing with interrupts in and around
the points of no return.

Signed-off-by: Florian Fainelli <[email protected]>
---
drivers/net/phy/bcm-phy-lib.c | 212 ++++++++++++++++++++++++++++++++++
drivers/net/phy/bcm-phy-lib.h | 5 +
drivers/net/phy/broadcom.c | 124 +++++++++++++++++++-
include/linux/brcmphy.h | 55 +++++++++
4 files changed, 392 insertions(+), 4 deletions(-)

diff --git a/drivers/net/phy/bcm-phy-lib.c b/drivers/net/phy/bcm-phy-lib.c
index b2c0baa51f39..27c57f6ab211 100644
--- a/drivers/net/phy/bcm-phy-lib.c
+++ b/drivers/net/phy/bcm-phy-lib.c
@@ -6,12 +6,14 @@
#include "bcm-phy-lib.h"
#include <linux/bitfield.h>
#include <linux/brcmphy.h>
+#include <linux/etherdevice.h>
#include <linux/export.h>
#include <linux/mdio.h>
#include <linux/module.h>
#include <linux/phy.h>
#include <linux/ethtool.h>
#include <linux/ethtool_netlink.h>
+#include <linux/netdevice.h>

#define MII_BCM_CHANNEL_WIDTH 0x2000
#define BCM_CL45VEN_EEE_ADV 0x3c
@@ -816,6 +818,216 @@ int bcm_phy_cable_test_get_status_rdb(struct phy_device *phydev,
}
EXPORT_SYMBOL_GPL(bcm_phy_cable_test_get_status_rdb);

+#define BCM54XX_WOL_SUPPORTED_MASK (WAKE_UCAST | \
+ WAKE_MCAST | \
+ WAKE_BCAST | \
+ WAKE_MAGIC | \
+ WAKE_MAGICSECURE)
+
+int bcm_phy_set_wol(struct phy_device *phydev, struct ethtool_wolinfo *wol)
+{
+ struct net_device *ndev = phydev->attached_dev;
+ u8 da[ETH_ALEN], mask[ETH_ALEN];
+ unsigned int i;
+ u16 ctl;
+ int ret;
+
+ /* Allow a MAC driver to play through its own Wake-on-LAN
+ * implementation
+ */
+ if (wol->wolopts & ~BCM54XX_WOL_SUPPORTED_MASK)
+ return -EOPNOTSUPP;
+
+ /* The PHY supports passwords of 4, 6 and 8 bytes in size, but Linux's
+ * ethtool only supports 6, for now.
+ */
+ BUILD_BUG_ON(sizeof(wol->sopass) != ETH_ALEN);
+
+ /* Clear previous interrupts */
+ ret = bcm_phy_read_exp(phydev, BCM54XX_WOL_INT_STATUS);
+ if (ret < 0)
+ return ret;
+
+ ret = bcm_phy_read_exp(phydev, BCM54XX_WOL_MAIN_CTL);
+ if (ret < 0)
+ return ret;
+
+ ctl = ret;
+
+ if (!wol->wolopts) {
+ if (phy_interrupt_is_valid(phydev))
+ disable_irq_wake(phydev->irq);
+
+ /* Leave all interrupts disabled */
+ ret = bcm_phy_write_exp(phydev, BCM54XX_WOL_INT_MASK,
+ BCM54XX_WOL_ALL_INTRS);
+ if (ret < 0)
+ return ret;
+
+ /* Disable the global Wake-on-LAN enable bit */
+ ctl &= ~BCM54XX_WOL_EN;
+
+ return bcm_phy_write_exp(phydev, BCM54XX_WOL_MAIN_CTL, ctl);
+ }
+
+ /* Clear the previously configured mode and mask mode for Wake-on-LAN */
+ ctl &= ~(BCM54XX_WOL_MODE_MASK << BCM54XX_WOL_MODE_SHIFT);
+ ctl &= ~(BCM54XX_WOL_MASK_MODE_MASK << BCM54XX_WOL_MASK_MODE_SHIFT);
+ ctl &= ~BCM54XX_WOL_DIR_PKT_EN;
+ ctl &= ~(BCM54XX_WOL_SECKEY_OPT_MASK << BCM54XX_WOL_SECKEY_OPT_SHIFT);
+
+ /* When using WAKE_MAGIC, we program the magic pattern filter to match
+ * the device's MAC address and we accept any MAC DA in the Ethernet
+ * frame.
+ *
+ * When using WAKE_UCAST, WAKE_BCAST or WAKE_MCAST, we program the
+ * following:
+ * - WAKE_UCAST -> MAC DA is the device's MAC with a perfect match
+ * - WAKE_MCAST -> MAC DA is X1:XX:XX:XX:XX:XX where XX is don't care
+ * - WAKE_BCAST -> MAC DA is FF:FF:FF:FF:FF:FF with a perfect match
+ *
+ * Note that the Broadcast MAC DA is inherently going to match the
+ * multicast pattern being matched.
+ */
+ memset(mask, 0, sizeof(mask));
+
+ if (wol->wolopts & WAKE_MCAST) {
+ memset(da, 0, sizeof(da));
+ memset(mask, 0xff, sizeof(mask));
+ da[0] = 0x01;
+ mask[0] = ~da[0];
+ } else {
+ if (wol->wolopts & WAKE_UCAST) {
+ ether_addr_copy(da, ndev->dev_addr);
+ } else if (wol->wolopts & WAKE_BCAST) {
+ eth_broadcast_addr(da);
+ } else if (wol->wolopts & WAKE_MAGICSECURE) {
+ ether_addr_copy(da, wol->sopass);
+ } else if (wol->wolopts & WAKE_MAGIC) {
+ memset(da, 0, sizeof(da));
+ memset(mask, 0xff, sizeof(mask));
+ }
+ }
+
+ for (i = 0; i < ETH_ALEN / 2; i++) {
+ if (wol->wolopts & (WAKE_MAGIC | WAKE_MAGICSECURE)) {
+ ret = bcm_phy_write_exp(phydev,
+ BCM54XX_WOL_MPD_DATA1(2 - i),
+ ndev->dev_addr[i * 2] << 8 |
+ ndev->dev_addr[i * 2 + 1]);
+ if (ret < 0)
+ return ret;
+ }
+
+ ret = bcm_phy_write_exp(phydev, BCM54XX_WOL_MPD_DATA2(2 - i),
+ da[i * 2] << 8 | da[i * 2 + 1]);
+ if (ret < 0)
+ return ret;
+
+ ret = bcm_phy_write_exp(phydev, BCM54XX_WOL_MASK(2 - i),
+ mask[i * 2] << 8 | mask[i * 2 + 1]);
+ if (ret)
+ return ret;
+ }
+
+ if (wol->wolopts & WAKE_MAGICSECURE) {
+ ctl |= BCM54XX_WOL_SECKEY_OPT_6B <<
+ BCM54XX_WOL_SECKEY_OPT_SHIFT;
+ ctl |= BCM54XX_WOL_MODE_SINGLE_MPDSEC << BCM54XX_WOL_MODE_SHIFT;
+ ctl |= BCM54XX_WOL_MASK_MODE_DA_FF <<
+ BCM54XX_WOL_MASK_MODE_SHIFT;
+ } else {
+ if (wol->wolopts & WAKE_MAGIC)
+ ctl |= BCM54XX_WOL_MODE_SINGLE_MPD;
+ else
+ ctl |= BCM54XX_WOL_DIR_PKT_EN;
+ ctl |= BCM54XX_WOL_MASK_MODE_DA_ONLY <<
+ BCM54XX_WOL_MASK_MODE_SHIFT;
+ }
+
+ /* Globally enable Wake-on-LAN */
+ ctl |= BCM54XX_WOL_EN | BCM54XX_WOL_CRC_CHK;
+
+ ret = bcm_phy_write_exp(phydev, BCM54XX_WOL_MAIN_CTL, ctl);
+ if (ret < 0)
+ return ret;
+
+ /* Enable WOL interrupt on LED4 */
+ ret = bcm_phy_read_exp(phydev, BCM54XX_TOP_MISC_LED_CTL);
+ if (ret < 0)
+ return ret;
+
+ ret |= BCM54XX_LED4_SEL_INTR;
+ ret = bcm_phy_write_exp(phydev, BCM54XX_TOP_MISC_LED_CTL, ret);
+ if (ret < 0)
+ return ret;
+
+ /* Enable all Wake-on-LAN interrupt sources */
+ ret = bcm_phy_write_exp(phydev, BCM54XX_WOL_INT_MASK, 0);
+ if (ret < 0)
+ return ret;
+
+ if (phy_interrupt_is_valid(phydev))
+ enable_irq_wake(phydev->irq);
+
+ return 0;
+}
+EXPORT_SYMBOL_GPL(bcm_phy_set_wol);
+
+void bcm_phy_get_wol(struct phy_device *phydev, struct ethtool_wolinfo *wol)
+{
+ struct net_device *ndev = phydev->attached_dev;
+ u8 da[ETH_ALEN];
+ unsigned int i;
+ int ret;
+ u16 ctl;
+
+ wol->supported = BCM54XX_WOL_SUPPORTED_MASK;
+ wol->wolopts = 0;
+
+ ret = bcm_phy_read_exp(phydev, BCM54XX_WOL_MAIN_CTL);
+ if (ret < 0)
+ return;
+
+ ctl = ret;
+
+ if (!(ctl & BCM54XX_WOL_EN))
+ return;
+
+ for (i = 0; i < sizeof(da) / 2; i++) {
+ ret = bcm_phy_read_exp(phydev,
+ BCM54XX_WOL_MPD_DATA2(2 - i));
+ if (ret < 0)
+ return;
+
+ da[i * 2] = ret >> 8;
+ da[i * 2 + 1] = ret & 0xff;
+ }
+
+ if (ctl & BCM54XX_WOL_DIR_PKT_EN) {
+ if (is_broadcast_ether_addr(da))
+ wol->wolopts |= WAKE_BCAST;
+ else if (is_multicast_ether_addr(da))
+ wol->wolopts |= WAKE_MCAST;
+ else if (ether_addr_equal(da, ndev->dev_addr))
+ wol->wolopts |= WAKE_UCAST;
+ } else {
+ ctl = (ctl >> BCM54XX_WOL_MODE_SHIFT) & BCM54XX_WOL_MODE_MASK;
+ switch (ctl) {
+ case BCM54XX_WOL_MODE_SINGLE_MPD:
+ wol->wolopts |= WAKE_MAGIC;
+ break;
+ case BCM54XX_WOL_MODE_SINGLE_MPDSEC:
+ wol->wolopts |= WAKE_MAGICSECURE;
+ memcpy(wol->sopass, da, sizeof(da));
+ break;
+ default:
+ break;
+ }
+ }
+}
+EXPORT_SYMBOL_GPL(bcm_phy_get_wol);
+
MODULE_DESCRIPTION("Broadcom PHY Library");
MODULE_LICENSE("GPL v2");
MODULE_AUTHOR("Broadcom Corporation");
diff --git a/drivers/net/phy/bcm-phy-lib.h b/drivers/net/phy/bcm-phy-lib.h
index 9902fb182099..4337e4a5cade 100644
--- a/drivers/net/phy/bcm-phy-lib.h
+++ b/drivers/net/phy/bcm-phy-lib.h
@@ -9,6 +9,8 @@
#include <linux/brcmphy.h>
#include <linux/phy.h>

+struct ethtool_wolinfo;
+
/* 28nm only register definitions */
#define MISC_ADDR(base, channel) base, channel

@@ -106,4 +108,7 @@ static inline void bcm_ptp_stop(struct bcm_ptp_private *priv)
}
#endif

+int bcm_phy_set_wol(struct phy_device *phydev, struct ethtool_wolinfo *wol);
+void bcm_phy_get_wol(struct phy_device *phydev, struct ethtool_wolinfo *wol);
+
#endif /* _LINUX_BCM_PHY_LIB_H */
diff --git a/drivers/net/phy/broadcom.c b/drivers/net/phy/broadcom.c
index 3f142dc266a9..a9dfa230495b 100644
--- a/drivers/net/phy/broadcom.c
+++ b/drivers/net/phy/broadcom.c
@@ -14,8 +14,12 @@
#include <linux/delay.h>
#include <linux/module.h>
#include <linux/phy.h>
+#include <linux/pm_wakeup.h>
#include <linux/brcmphy.h>
#include <linux/of.h>
+#include <linux/interrupt.h>
+#include <linux/irq.h>
+#include <linux/gpio/consumer.h>

#define BRCM_PHY_MODEL(phydev) \
((phydev)->drv->phy_id & (phydev)->drv->phy_id_mask)
@@ -30,8 +34,17 @@ MODULE_LICENSE("GPL");
struct bcm54xx_phy_priv {
u64 *stats;
struct bcm_ptp_private *ptp;
+ int wake_irq;
+ bool wake_irq_enabled;
};

+static bool bcm54xx_phy_can_wakeup(struct phy_device *phydev)
+{
+ struct bcm54xx_phy_priv *priv = phydev->priv;
+
+ return phy_interrupt_is_valid(phydev) || priv->wake_irq >= 0;
+}
+
static int bcm54xx_config_clock_delay(struct phy_device *phydev)
{
int rc, val;
@@ -413,6 +426,16 @@ static int bcm54xx_config_init(struct phy_device *phydev)

bcm54xx_ptp_config_init(phydev);

+ /* Acknowledge any left over interrupt and charge the device for
+ * wake-up.
+ */
+ err = bcm_phy_read_exp(phydev, BCM54XX_WOL_INT_STATUS);
+ if (err < 0)
+ return err;
+
+ if (err)
+ pm_wakeup_event(&phydev->mdio.dev, 0);
+
return 0;
}

@@ -437,14 +460,38 @@ static int bcm54xx_iddq_set(struct phy_device *phydev, bool enable)
return ret;
}

-static int bcm54xx_suspend(struct phy_device *phydev)
+static int bcm54xx_set_wakeup_irq(struct phy_device *phydev, bool state)
{
+ struct bcm54xx_phy_priv *priv = phydev->priv;
int ret;

+ if (!bcm54xx_phy_can_wakeup(phydev))
+ return 0;
+
+ if (priv->wake_irq_enabled != state) {
+ if (state)
+ ret = enable_irq_wake(priv->wake_irq);
+ else
+ ret = disable_irq_wake(priv->wake_irq);
+ priv->wake_irq_enabled = state;
+ }
+
+ return ret;
+}
+
+static int bcm54xx_suspend(struct phy_device *phydev)
+{
+ int ret = 0;
+
bcm54xx_ptp_stop(phydev);

+ /* Acknowledge any Wake-on-LAN interrupt prior to suspend */
+ ret = bcm_phy_read_exp(phydev, BCM54XX_WOL_INT_STATUS);
+ if (ret < 0)
+ return ret;
+
if (phydev->wol_enabled)
- return 0;
+ return bcm54xx_set_wakeup_irq(phydev, true);

/* We cannot use a read/modify/write here otherwise the PHY gets into
* a bad state where its LEDs keep flashing, thus defeating the purpose
@@ -459,7 +506,13 @@ static int bcm54xx_suspend(struct phy_device *phydev)

static int bcm54xx_resume(struct phy_device *phydev)
{
- int ret;
+ int ret = 0;
+
+ if (phydev->wol_enabled) {
+ ret = bcm54xx_set_wakeup_irq(phydev, false);
+ if (ret)
+ return ret;
+ }

ret = bcm54xx_iddq_set(phydev, false);
if (ret < 0)
@@ -807,14 +860,54 @@ static int brcm_fet_suspend(struct phy_device *phydev)
return err;
}

+static void bcm54xx_phy_get_wol(struct phy_device *phydev,
+ struct ethtool_wolinfo *wol)
+{
+ /* We cannot wake-up if we do not have a dedicated PHY interrupt line
+ * or an out of band GPIO descriptor for wake-up. Zeroing
+ * wol->supported allows the caller (MAC driver) to play through and
+ * offer its own Wake-on-LAN scheme if available.
+ */
+ if (!bcm54xx_phy_can_wakeup(phydev)) {
+ wol->supported = 0;
+ return;
+ }
+
+ bcm_phy_get_wol(phydev, wol);
+}
+
+static int bcm54xx_phy_set_wol(struct phy_device *phydev,
+ struct ethtool_wolinfo *wol)
+{
+ int ret;
+
+ /* We cannot wake-up if we do not have a dedicated PHY interrupt line
+ * or an out of band GPIO descriptor for wake-up. Returning -EOPNOTSUPP
+ * allows the caller (MAC driver) to play through and offer its own
+ * Wake-on-LAN scheme if available.
+ */
+ if (!bcm54xx_phy_can_wakeup(phydev))
+ return -EOPNOTSUPP;
+
+ ret = bcm_phy_set_wol(phydev, wol);
+ if (ret < 0)
+ return ret;
+
+ return 0;
+}
+
static int bcm54xx_phy_probe(struct phy_device *phydev)
{
struct bcm54xx_phy_priv *priv;
+ struct gpio_desc *wakeup_gpio;
+ int ret = 0;

priv = devm_kzalloc(&phydev->mdio.dev, sizeof(*priv), GFP_KERNEL);
if (!priv)
return -ENOMEM;

+ priv->wake_irq = -ENXIO;
+
phydev->priv = priv;

priv->stats = devm_kcalloc(&phydev->mdio.dev,
@@ -827,7 +920,28 @@ static int bcm54xx_phy_probe(struct phy_device *phydev)
if (IS_ERR(priv->ptp))
return PTR_ERR(priv->ptp);

- return 0;
+ /* We cannot utilize the _optional variant here since we want to know
+ * whether the GPIO descriptor exists or not to advertise Wake-on-LAN
+ * support or not.
+ */
+ wakeup_gpio = devm_gpiod_get(&phydev->mdio.dev, "wakeup", GPIOD_IN);
+ if (PTR_ERR(wakeup_gpio) == -EPROBE_DEFER)
+ return PTR_ERR(wakeup_gpio);
+
+ if (!IS_ERR(wakeup_gpio)) {
+ priv->wake_irq = gpiod_to_irq(wakeup_gpio);
+ ret = irq_set_irq_type(priv->wake_irq, IRQ_TYPE_LEVEL_LOW);
+ if (ret)
+ return ret;
+ }
+
+ /* If we do not have a main interrupt or a side-band wake-up interrupt,
+ * then the device cannot be marked as wake-up capable.
+ */
+ if (!bcm54xx_phy_can_wakeup(phydev))
+ return ret;
+
+ return device_init_wakeup(&phydev->mdio.dev, true);
}

static void bcm54xx_get_stats(struct phy_device *phydev,
@@ -910,6 +1024,8 @@ static struct phy_driver broadcom_drivers[] = {
.link_change_notify = bcm54xx_link_change_notify,
.suspend = bcm54xx_suspend,
.resume = bcm54xx_resume,
+ .get_wol = bcm54xx_phy_get_wol,
+ .set_wol = bcm54xx_phy_set_wol,
}, {
.phy_id = PHY_ID_BCM5461,
.phy_id_mask = 0xfffffff0,
diff --git a/include/linux/brcmphy.h b/include/linux/brcmphy.h
index 9e77165f3ef6..e9afbfb6d7a5 100644
--- a/include/linux/brcmphy.h
+++ b/include/linux/brcmphy.h
@@ -89,6 +89,7 @@
#define MII_BCM54XX_EXP_SEL 0x17 /* Expansion register select */
#define MII_BCM54XX_EXP_SEL_TOP 0x0d00 /* TOP_MISC expansion register select */
#define MII_BCM54XX_EXP_SEL_SSD 0x0e00 /* Secondary SerDes select */
+#define MII_BCM54XX_EXP_SEL_WOL 0x0e00 /* Wake-on-LAN expansion select register */
#define MII_BCM54XX_EXP_SEL_ER 0x0f00 /* Expansion register select */
#define MII_BCM54XX_EXP_SEL_ETC 0x0d00 /* Expansion register spare + 2k mem */

@@ -253,6 +254,9 @@
#define BCM54XX_TOP_MISC_IDDQ_SD (1 << 2)
#define BCM54XX_TOP_MISC_IDDQ_SR (1 << 3)

+#define BCM54XX_TOP_MISC_LED_CTL (MII_BCM54XX_EXP_SEL_TOP + 0x0C)
+#define BCM54XX_LED4_SEL_INTR BIT(1)
+
/*
* BCM5482: Secondary SerDes registers
*/
@@ -272,6 +276,57 @@
#define BCM54612E_EXP_SPARE0 (MII_BCM54XX_EXP_SEL_ETC + 0x34)
#define BCM54612E_LED4_CLK125OUT_EN (1 << 1)

+
+/* Wake-on-LAN registers */
+#define BCM54XX_WOL_MAIN_CTL (MII_BCM54XX_EXP_SEL_WOL + 0x80)
+#define BCM54XX_WOL_EN BIT(0)
+#define BCM54XX_WOL_MODE_SINGLE_MPD 0
+#define BCM54XX_WOL_MODE_SINGLE_MPDSEC 1
+#define BCM54XX_WOL_MODE_DUAL 2
+#define BCM54XX_WOL_MODE_SHIFT 1
+#define BCM54XX_WOL_MODE_MASK 0x3
+#define BCM54XX_WOL_MP_MSB_FF_EN BIT(3)
+#define BCM54XX_WOL_SECKEY_OPT_4B 0
+#define BCM54XX_WOL_SECKEY_OPT_6B 1
+#define BCM54XX_WOL_SECKEY_OPT_8B 2
+#define BCM54XX_WOL_SECKEY_OPT_SHIFT 4
+#define BCM54XX_WOL_SECKEY_OPT_MASK 0x3
+#define BCM54XX_WOL_L2_TYPE_CHK BIT(6)
+#define BCM54XX_WOL_L4IPV4UDP_CHK BIT(7)
+#define BCM54XX_WOL_L4IPV6UDP_CHK BIT(8)
+#define BCM54XX_WOL_UDPPORT_CHK BIT(9)
+#define BCM54XX_WOL_CRC_CHK BIT(10)
+#define BCM54XX_WOL_SECKEY_MODE BIT(11)
+#define BCM54XX_WOL_RST BIT(12)
+#define BCM54XX_WOL_DIR_PKT_EN BIT(13)
+#define BCM54XX_WOL_MASK_MODE_DA_FF 0
+#define BCM54XX_WOL_MASK_MODE_DA_MPD 1
+#define BCM54XX_WOL_MASK_MODE_DA_ONLY 2
+#define BCM54XX_WOL_MASK_MODE_MPD 3
+#define BCM54XX_WOL_MASK_MODE_SHIFT 14
+#define BCM54XX_WOL_MASK_MODE_MASK 0x3
+
+#define BCM54XX_WOL_INNER_PROTO (MII_BCM54XX_EXP_SEL_WOL + 0x81)
+#define BCM54XX_WOL_OUTER_PROTO (MII_BCM54XX_EXP_SEL_WOL + 0x82)
+#define BCM54XX_WOL_OUTER_PROTO2 (MII_BCM54XX_EXP_SEL_WOL + 0x83)
+
+#define BCM54XX_WOL_MPD_DATA1(x) (MII_BCM54XX_EXP_SEL_WOL + 0x84 + (x))
+#define BCM54XX_WOL_MPD_DATA2(x) (MII_BCM54XX_EXP_SEL_WOL + 0x87 + (x))
+#define BCM54XX_WOL_SEC_KEY_8B (MII_BCM54XX_EXP_SEL_WOL + 0x8A)
+#define BCM54XX_WOL_MASK(x) (MII_BCM54XX_EXP_SEL_WOL + 0x8B + (x))
+#define BCM54XX_SEC_KEY_STORE(x) (MII_BCM54XX_EXP_SEL_WOL + 0x8E)
+#define BCM54XX_WOL_SHARED_CNT (MII_BCM54XX_EXP_SEL_WOL + 0x92)
+
+#define BCM54XX_WOL_INT_MASK (MII_BCM54XX_EXP_SEL_WOL + 0x93)
+#define BCM54XX_WOL_PKT1 BIT(0)
+#define BCM54XX_WOL_PKT2 BIT(1)
+#define BCM54XX_WOL_DIR BIT(2)
+#define BCM54XX_WOL_ALL_INTRS (BCM54XX_WOL_PKT1 | \
+ BCM54XX_WOL_PKT2 | \
+ BCM54XX_WOL_DIR)
+
+#define BCM54XX_WOL_INT_STATUS (MII_BCM54XX_EXP_SEL_WOL + 0x94)
+
/*****************************************************************************/
/* Fast Ethernet Transceiver definitions. */
/*****************************************************************************/
--
2.34.1

2023-05-08 19:00:13

by Florian Fainelli

[permalink] [raw]
Subject: [PATCH net-next 1/3] net: phy: Let drivers check Wake-on-LAN status

A few PHY drivers are currently attempting to not suspend the PHY when
Wake-on-LAN is enabled, however that code is not currently executing at
all due to an early check in phy_suspend().

This prevents PHY drivers from making an appropriate decisions and put
the hardware into a low power state if desired.

In order to allow the PHY framework to always call into the PHY driver's
->suspend routine whether Wake-on-LAN is enabled or not, provide a
phydev::wol_enabled boolean that tracks whether the PHY or the attached
MAC has Wake-on-LAN enabled.

If phydev::wol_enabled then the PHY shall not prevent its own
Wake-on-LAN detection logic from working and shall not prevent the
Ethernet MAC from receiving packets for matching.

The check for -EBUSY is also removed since it would have prevented a PHY
being in an always on power domain and thus retaining its Wake-on-LAN
configuration from allowing the system to suspend.

Signed-off-by: Florian Fainelli <[email protected]>
---
drivers/net/phy/aquantia_main.c | 3 +++
drivers/net/phy/at803x.c | 10 ++++++++++
drivers/net/phy/bcm7xxx.c | 3 +++
drivers/net/phy/broadcom.c | 6 ++++++
drivers/net/phy/dp83822.c | 2 +-
drivers/net/phy/dp83867.c | 3 +++
drivers/net/phy/dp83tc811.c | 2 +-
drivers/net/phy/marvell-88x2222.c | 3 +++
drivers/net/phy/marvell.c | 3 +++
drivers/net/phy/marvell10g.c | 3 +++
drivers/net/phy/micrel.c | 3 +++
drivers/net/phy/microchip.c | 4 +---
drivers/net/phy/motorcomm.c | 2 +-
drivers/net/phy/phy-c45.c | 3 +++
drivers/net/phy/phy_device.c | 7 +++++--
drivers/net/phy/realtek.c | 3 +++
include/linux/phy.h | 3 +++
17 files changed, 55 insertions(+), 8 deletions(-)

diff --git a/drivers/net/phy/aquantia_main.c b/drivers/net/phy/aquantia_main.c
index 334a6904ca5a..ffe4e8f16c07 100644
--- a/drivers/net/phy/aquantia_main.c
+++ b/drivers/net/phy/aquantia_main.c
@@ -691,6 +691,9 @@ static int aqr107_suspend(struct phy_device *phydev)
{
int err;

+ if (phydev->wol_enabled)
+ return 0;
+
err = phy_set_bits_mmd(phydev, MDIO_MMD_VEND1, MDIO_CTRL1,
MDIO_CTRL1_LPOWER);
if (err)
diff --git a/drivers/net/phy/at803x.c b/drivers/net/phy/at803x.c
index 656136628ffd..acd941beeb8e 100644
--- a/drivers/net/phy/at803x.c
+++ b/drivers/net/phy/at803x.c
@@ -569,6 +569,13 @@ static int at803x_suspend(struct phy_device *phydev)
int value;
int wol_enabled;

+ /* We cannot isolate if the attached network device has
+ * Wake-on-LAN enabled since we would not be passing
+ * packets through it.
+ */
+ if (phydev->attached_dev->wol_enabled)
+ return 0;
+
value = phy_read(phydev, AT803X_INTR_ENABLE);
wol_enabled = value & AT803X_INTR_ENABLE_WOL;

@@ -1701,6 +1708,9 @@ static int qca83xx_suspend(struct phy_device *phydev)
{
u16 mask = 0;

+ if (phydev->wol_enabled)
+ return 0;
+
/* Only QCA8337 support actual suspend.
* QCA8327 cause port unreliability when phy suspend
* is set.
diff --git a/drivers/net/phy/bcm7xxx.c b/drivers/net/phy/bcm7xxx.c
index 06be71ecd2f8..f060a5783694 100644
--- a/drivers/net/phy/bcm7xxx.c
+++ b/drivers/net/phy/bcm7xxx.c
@@ -747,6 +747,9 @@ static int bcm7xxx_suspend(struct phy_device *phydev)
};
unsigned int i;

+ if (phydev->wol_enabled)
+ return 0;
+
for (i = 0; i < ARRAY_SIZE(bcm7xxx_suspend_cfg); i++) {
ret = phy_write(phydev,
bcm7xxx_suspend_cfg[i].reg,
diff --git a/drivers/net/phy/broadcom.c b/drivers/net/phy/broadcom.c
index ad71c88c87e7..3f142dc266a9 100644
--- a/drivers/net/phy/broadcom.c
+++ b/drivers/net/phy/broadcom.c
@@ -443,6 +443,9 @@ static int bcm54xx_suspend(struct phy_device *phydev)

bcm54xx_ptp_stop(phydev);

+ if (phydev->wol_enabled)
+ return 0;
+
/* We cannot use a read/modify/write here otherwise the PHY gets into
* a bad state where its LEDs keep flashing, thus defeating the purpose
* of low power mode.
@@ -770,6 +773,9 @@ static int brcm_fet_suspend(struct phy_device *phydev)
{
int reg, err, err2, brcmtest;

+ if (phydev->wol_enabled)
+ return 0;
+
/* We cannot use a read/modify/write here otherwise the PHY continues
* to drive LEDs which defeats the purpose of low power mode.
*/
diff --git a/drivers/net/phy/dp83822.c b/drivers/net/phy/dp83822.c
index b7cb71817780..2ab0cbd1a60f 100644
--- a/drivers/net/phy/dp83822.c
+++ b/drivers/net/phy/dp83822.c
@@ -573,7 +573,7 @@ static int dp83822_suspend(struct phy_device *phydev)

value = phy_read_mmd(phydev, DP83822_DEVADDR, MII_DP83822_WOL_CFG);

- if (!(value & DP83822_WOL_EN))
+ if (!(value & DP83822_WOL_EN) && !phydev->wol_enabled)
genphy_suspend(phydev);

return 0;
diff --git a/drivers/net/phy/dp83867.c b/drivers/net/phy/dp83867.c
index d75f526a20a4..8f2b19e57f90 100644
--- a/drivers/net/phy/dp83867.c
+++ b/drivers/net/phy/dp83867.c
@@ -708,6 +708,9 @@ static int dp83867_suspend(struct phy_device *phydev)
dp83867_config_intr(phydev);
}

+ if (phydev->wol_enabled)
+ return 0;
+
return genphy_suspend(phydev);
}

diff --git a/drivers/net/phy/dp83tc811.c b/drivers/net/phy/dp83tc811.c
index 7ea32fb77190..2106f9ea15f5 100644
--- a/drivers/net/phy/dp83tc811.c
+++ b/drivers/net/phy/dp83tc811.c
@@ -368,7 +368,7 @@ static int dp83811_suspend(struct phy_device *phydev)

value = phy_read_mmd(phydev, DP83811_DEVADDR, MII_DP83811_WOL_CFG);

- if (!(value & DP83811_WOL_EN))
+ if (!(value & DP83811_WOL_EN) && !phydev->wol_enabled)
genphy_suspend(phydev);

return 0;
diff --git a/drivers/net/phy/marvell-88x2222.c b/drivers/net/phy/marvell-88x2222.c
index f83cae64585d..9c13e4dd1807 100644
--- a/drivers/net/phy/marvell-88x2222.c
+++ b/drivers/net/phy/marvell-88x2222.c
@@ -458,6 +458,9 @@ static int mv2222_resume(struct phy_device *phydev)

static int mv2222_suspend(struct phy_device *phydev)
{
+ /* No need to check for phydev->wol_enabled since we only disable the
+ * transmitter
+ */
return mv2222_tx_disable(phydev);
}

diff --git a/drivers/net/phy/marvell.c b/drivers/net/phy/marvell.c
index 43b6cb725551..c08ad1c3f4c3 100644
--- a/drivers/net/phy/marvell.c
+++ b/drivers/net/phy/marvell.c
@@ -1741,6 +1741,9 @@ static int marvell_suspend(struct phy_device *phydev)
{
int err;

+ if (phydev->wol_enabled)
+ return 0;
+
/* Suspend the fiber mode first */
if (linkmode_test_bit(ETHTOOL_LINK_MODE_FIBRE_BIT,
phydev->supported)) {
diff --git a/drivers/net/phy/marvell10g.c b/drivers/net/phy/marvell10g.c
index 55d9d7acc32e..6d45a94e5bea 100644
--- a/drivers/net/phy/marvell10g.c
+++ b/drivers/net/phy/marvell10g.c
@@ -559,6 +559,9 @@ static void mv3310_remove(struct phy_device *phydev)

static int mv3310_suspend(struct phy_device *phydev)
{
+ if (phydev->wol_enabled)
+ return 0;
+
return mv3310_power_down(phydev);
}

diff --git a/drivers/net/phy/micrel.c b/drivers/net/phy/micrel.c
index 3f81bb8dac44..fe71ab8926fc 100644
--- a/drivers/net/phy/micrel.c
+++ b/drivers/net/phy/micrel.c
@@ -1826,6 +1826,9 @@ static int kszphy_suspend(struct phy_device *phydev)
phydev->drv->config_intr(phydev);
}

+ if (phydev->wol_enabled)
+ return 0;
+
return genphy_suspend(phydev);
}

diff --git a/drivers/net/phy/microchip.c b/drivers/net/phy/microchip.c
index 0b88635f4fbc..5290fd684c93 100644
--- a/drivers/net/phy/microchip.c
+++ b/drivers/net/phy/microchip.c
@@ -74,10 +74,8 @@ static irqreturn_t lan88xx_handle_interrupt(struct phy_device *phydev)

static int lan88xx_suspend(struct phy_device *phydev)
{
- struct lan88xx_priv *priv = phydev->priv;
-
/* do not power down PHY when WOL is enabled */
- if (!priv->wolopts)
+ if (!phydev->wol_enabled)
genphy_suspend(phydev);

return 0;
diff --git a/drivers/net/phy/motorcomm.c b/drivers/net/phy/motorcomm.c
index 2fa5a90e073b..50472708c15e 100644
--- a/drivers/net/phy/motorcomm.c
+++ b/drivers/net/phy/motorcomm.c
@@ -1414,7 +1414,7 @@ static int yt8521_suspend(struct phy_device *phydev)
return wol_config;

/* if wol enable, do nothing */
- if (wol_config & YTPHY_WCR_ENABLE)
+ if ((wol_config & YTPHY_WCR_ENABLE) || phydev->wol_enabled)
return 0;

return yt8521_modify_utp_fiber_bmcr(phydev, 0, BMCR_PDOWN);
diff --git a/drivers/net/phy/phy-c45.c b/drivers/net/phy/phy-c45.c
index fee514b96ab1..355e78c441a8 100644
--- a/drivers/net/phy/phy-c45.c
+++ b/drivers/net/phy/phy-c45.c
@@ -64,6 +64,9 @@ EXPORT_SYMBOL_GPL(genphy_c45_pma_resume);
*/
int genphy_c45_pma_suspend(struct phy_device *phydev)
{
+ if (phydev->wol_enabled)
+ return 0;
+
if (!genphy_c45_pma_can_sleep(phydev))
return -EOPNOTSUPP;

diff --git a/drivers/net/phy/phy_device.c b/drivers/net/phy/phy_device.c
index 17d0d0555a79..ae86e169a578 100644
--- a/drivers/net/phy/phy_device.c
+++ b/drivers/net/phy/phy_device.c
@@ -1862,8 +1862,8 @@ int phy_suspend(struct phy_device *phydev)

/* If the device has WOL enabled, we cannot suspend the PHY */
phy_ethtool_get_wol(phydev, &wol);
- if (wol.wolopts || (netdev && netdev->wol_enabled))
- return -EBUSY;
+ phydev->wol_enabled = !!(wol.wolopts || (netdev &&
+ netdev->wol_enabled));

if (!phydrv || !phydrv->suspend)
return 0;
@@ -2687,6 +2687,9 @@ EXPORT_SYMBOL(genphy_write_mmd_unsupported);

int genphy_suspend(struct phy_device *phydev)
{
+ if (phydev->wol_enabled)
+ return 0;
+
return phy_set_bits(phydev, MII_BMCR, BMCR_PDOWN);
}
EXPORT_SYMBOL(genphy_suspend);
diff --git a/drivers/net/phy/realtek.c b/drivers/net/phy/realtek.c
index 3d99fd6664d7..316f9e868d84 100644
--- a/drivers/net/phy/realtek.c
+++ b/drivers/net/phy/realtek.c
@@ -482,6 +482,9 @@ static int rtl8211e_config_init(struct phy_device *phydev)

static int rtl8211b_suspend(struct phy_device *phydev)
{
+ if (phydev->wol_enabled)
+ return 0;
+
phy_write(phydev, MII_MMD_DATA, BIT(9));

return genphy_suspend(phydev);
diff --git a/include/linux/phy.h b/include/linux/phy.h
index c5a0dc829714..e36dfc8236b4 100644
--- a/include/linux/phy.h
+++ b/include/linux/phy.h
@@ -548,6 +548,8 @@ struct macsec_ops;
* @downshifted_rate: Set true if link speed has been downshifted.
* @is_on_sfp_module: Set true if PHY is located on an SFP module.
* @mac_managed_pm: Set true if MAC driver takes of suspending/resuming PHY
+ * @wol_enabled: Set to true if the PHY or the attached MAC have Wake-on-LAN
+ * enabled.
* @state: State of the PHY for management purposes
* @dev_flags: Device-specific flags used by the PHY driver.
*
@@ -644,6 +646,7 @@ struct phy_device {
unsigned downshifted_rate:1;
unsigned is_on_sfp_module:1;
unsigned mac_managed_pm:1;
+ unsigned wol_enabled:1;

unsigned autoneg:1;
/* The most recently read link state */
--
2.34.1

2023-05-08 19:00:18

by Florian Fainelli

[permalink] [raw]
Subject: [PATCH net-next 3/3] net: bcmgenet: Add support for PHY-based Wake-on-LAN

If available, interrogate the PHY to find out whether we can use it for
Wake-on-LAN. This can be a more power efficient way of implementing
that feature, especially when the MAC is powered off in low power
states.

Signed-off-by: Florian Fainelli <[email protected]>
---
drivers/net/ethernet/broadcom/genet/bcmgenet_wol.c | 14 ++++++++++++++
1 file changed, 14 insertions(+)

diff --git a/drivers/net/ethernet/broadcom/genet/bcmgenet_wol.c b/drivers/net/ethernet/broadcom/genet/bcmgenet_wol.c
index 3a4b6cb7b7b9..7a41cad5788f 100644
--- a/drivers/net/ethernet/broadcom/genet/bcmgenet_wol.c
+++ b/drivers/net/ethernet/broadcom/genet/bcmgenet_wol.c
@@ -42,6 +42,12 @@ void bcmgenet_get_wol(struct net_device *dev, struct ethtool_wolinfo *wol)
struct bcmgenet_priv *priv = netdev_priv(dev);
struct device *kdev = &priv->pdev->dev;

+ if (dev->phydev) {
+ phy_ethtool_get_wol(dev->phydev, wol);
+ if (wol->supported)
+ return;
+ }
+
if (!device_can_wakeup(kdev)) {
wol->supported = 0;
wol->wolopts = 0;
@@ -63,6 +69,14 @@ int bcmgenet_set_wol(struct net_device *dev, struct ethtool_wolinfo *wol)
{
struct bcmgenet_priv *priv = netdev_priv(dev);
struct device *kdev = &priv->pdev->dev;
+ int ret;
+
+ /* Try Wake-on-LAN from the PHY first */
+ if (dev->phydev) {
+ ret = phy_ethtool_set_wol(dev->phydev, wol);
+ if (ret != -EOPNOTSUPP)
+ return ret;
+ }

if (!device_can_wakeup(kdev))
return -ENOTSUPP;
--
2.34.1

2023-05-08 19:19:58

by Andrew Lunn

[permalink] [raw]
Subject: Re: [PATCH net-next 1/3] net: phy: Let drivers check Wake-on-LAN status

On Mon, May 08, 2023 at 11:43:07AM -0700, Florian Fainelli wrote:
> A few PHY drivers are currently attempting to not suspend the PHY when
> Wake-on-LAN is enabled, however that code is not currently executing at
> all due to an early check in phy_suspend().
>
> This prevents PHY drivers from making an appropriate decisions and put
> the hardware into a low power state if desired.
>
> In order to allow the PHY framework to always call into the PHY driver's
> ->suspend routine whether Wake-on-LAN is enabled or not, provide a
> phydev::wol_enabled boolean that tracks whether the PHY or the attached
> MAC has Wake-on-LAN enabled.
>
> If phydev::wol_enabled then the PHY shall not prevent its own
> Wake-on-LAN detection logic from working and shall not prevent the
> Ethernet MAC from receiving packets for matching.

Hi Florian

Did you look at using late_suspend for this? Then there would not be
any need to change all these drivers which are happy as they are.

It actually looks like late_suspend is what you want anyway, when you
say you want to turn the matching hardware on as late as possible.

Andrew

2023-05-08 19:24:22

by Florian Fainelli

[permalink] [raw]
Subject: Re: [PATCH net-next 1/3] net: phy: Let drivers check Wake-on-LAN status

On 5/8/23 12:17, Florian Fainelli wrote:
> On 5/8/23 12:02, Andrew Lunn wrote:
>> On Mon, May 08, 2023 at 11:43:07AM -0700, Florian Fainelli wrote:
>>> A few PHY drivers are currently attempting to not suspend the PHY when
>>> Wake-on-LAN is enabled, however that code is not currently executing at
>>> all due to an early check in phy_suspend().
>>>
>>> This prevents PHY drivers from making an appropriate decisions and put
>>> the hardware into a low power state if desired.
>>>
>>> In order to allow the PHY framework to always call into the PHY driver's
>>> ->suspend routine whether Wake-on-LAN is enabled or not, provide a
>>> phydev::wol_enabled boolean that tracks whether the PHY or the attached
>>> MAC has Wake-on-LAN enabled.
>>>
>>> If phydev::wol_enabled then the PHY shall not prevent its own
>>> Wake-on-LAN detection logic from working and shall not prevent the
>>> Ethernet MAC from receiving packets for matching.
>>
>> Hi Florian
>>
>> Did you look at using late_suspend for this? Then there would not be
>> any need to change all these drivers which are happy as they are.
>
> I did not know its existence until you mentioned it, this would require
> plumbing all the way from the MDIO bus driver down to the PHY driver
> level, which could be done, but for a single driver? The way Linux
> suspends devices currently, and the fact that the interrupt is driven
> level low, it does not give much room if at all for missing the
> interrupt AFAICT.

I suppose that a middle ground could be to introduce a specific callback
or flag that says: please call my suspend routine and I will do what's
necessary.

>
> phy_suspend() is called both from the system suspend path, but also
> whenever the PHY is unused, and this is a nice property because we do
> not really need to differentiate these paths usually, that includes
> Wake-on-LAN.
>
> Besides there are drivers like drivers/net/phy/at803x.c that wish to
> isolate the PHY if WoL is enabled and which are currently not doing it
> because this never gets called.

--
Florian

2023-05-08 19:28:05

by Simon Horman

[permalink] [raw]
Subject: Re: [PATCH net-next 2/3] net: phy: broadcom: Add support for Wake-on-LAN

On Mon, May 08, 2023 at 11:43:08AM -0700, Florian Fainelli wrote:
> Add support for WAKE_UCAST, WAKE_MCAST, WAKE_BCAST, WAKE_MAGIC and
> WAKE_MAGICSECURE. This is only supported with the BCM54210E and
> compatible Ethernet PHYs. Using the in-band interrupt or an out of band
> GPIO interrupts are supported.
>
> Broadcom PHYs will generate a Wake-on-LAN level low interrupt on LED4 as
> soon as one of the supported patterns is being matched. That includes
> generating such an interrupt even if the PHY is operated during normal
> modes. If WAKE_UCAST is selected, this could lead to the LED4 interrupt
> firing up for every packet being received which is absolutely
> undesirable from a performance point of view.
>
> Because the Wake-on-LAN configuration can be set long before the system
> is actually put to sleep, we cannot have an interrupt service routine to
> clear on read the interrupt status register and ensure that new packet
> matches will be detected.
>
> It is desirable to enable the Wake-on-LAN interrupt as late as possible
> during the system suspend process such that we limit the number of
> interrupts to be handled by the system, but also conversely feed into
> the Linux's system suspend way of dealing with interrupts in and around
> the points of no return.
>
> Signed-off-by: Florian Fainelli <[email protected]>

...

> @@ -437,14 +460,38 @@ static int bcm54xx_iddq_set(struct phy_device *phydev, bool enable)
> return ret;
> }
>
> -static int bcm54xx_suspend(struct phy_device *phydev)
> +static int bcm54xx_set_wakeup_irq(struct phy_device *phydev, bool state)
> {
> + struct bcm54xx_phy_priv *priv = phydev->priv;
> int ret;
>
> + if (!bcm54xx_phy_can_wakeup(phydev))
> + return 0;
> +
> + if (priv->wake_irq_enabled != state) {
> + if (state)
> + ret = enable_irq_wake(priv->wake_irq);
> + else
> + ret = disable_irq_wake(priv->wake_irq);
> + priv->wake_irq_enabled = state;
> + }

Hi Florian,

If priv->wake_irq_enabled == state the ret is uninitialised here.

> +
> + return ret;
> +}

...

2023-05-08 19:41:32

by Florian Fainelli

[permalink] [raw]
Subject: Re: [PATCH net-next 1/3] net: phy: Let drivers check Wake-on-LAN status

On 5/8/23 12:02, Andrew Lunn wrote:
> On Mon, May 08, 2023 at 11:43:07AM -0700, Florian Fainelli wrote:
>> A few PHY drivers are currently attempting to not suspend the PHY when
>> Wake-on-LAN is enabled, however that code is not currently executing at
>> all due to an early check in phy_suspend().
>>
>> This prevents PHY drivers from making an appropriate decisions and put
>> the hardware into a low power state if desired.
>>
>> In order to allow the PHY framework to always call into the PHY driver's
>> ->suspend routine whether Wake-on-LAN is enabled or not, provide a
>> phydev::wol_enabled boolean that tracks whether the PHY or the attached
>> MAC has Wake-on-LAN enabled.
>>
>> If phydev::wol_enabled then the PHY shall not prevent its own
>> Wake-on-LAN detection logic from working and shall not prevent the
>> Ethernet MAC from receiving packets for matching.
>
> Hi Florian
>
> Did you look at using late_suspend for this? Then there would not be
> any need to change all these drivers which are happy as they are.

I did not know its existence until you mentioned it, this would require
plumbing all the way from the MDIO bus driver down to the PHY driver
level, which could be done, but for a single driver? The way Linux
suspends devices currently, and the fact that the interrupt is driven
level low, it does not give much room if at all for missing the
interrupt AFAICT.

phy_suspend() is called both from the system suspend path, but also
whenever the PHY is unused, and this is a nice property because we do
not really need to differentiate these paths usually, that includes
Wake-on-LAN.

Besides there are drivers like drivers/net/phy/at803x.c that wish to
isolate the PHY if WoL is enabled and which are currently not doing it
because this never gets called.
--
Florian


Attachments:
smime.p7s (4.12 kB)
S/MIME Cryptographic Signature

2023-05-08 19:41:46

by Florian Fainelli

[permalink] [raw]
Subject: Re: [PATCH net-next 2/3] net: phy: broadcom: Add support for Wake-on-LAN

On 5/8/23 12:09, Andrew Lunn wrote:
>> Because the Wake-on-LAN configuration can be set long before the system
>> is actually put to sleep, we cannot have an interrupt service routine to
>> clear on read the interrupt status register and ensure that new packet
>> matches will be detected.
>
> Hi Florian
>
> I assume the interrupt is active low, not an edge. And it will remain
> active until it is cleared? So on resume, don't you need to clear it?
> Otherwise it is already active when entering the next suspend/resume
> cycle.

The interrupt is indeed a level low driven interrupt. The interrupt is
acknowledged by reading the WOL_INT_STATUS during bcm54xx_config_init()
which executes during ->probe() and ->resume() and which is a clear on
read register, this is also necessary to charge the device with the
wake-up event.
--
Florian

2023-05-08 19:43:58

by Andrew Lunn

[permalink] [raw]
Subject: Re: [PATCH net-next 2/3] net: phy: broadcom: Add support for Wake-on-LAN

> Because the Wake-on-LAN configuration can be set long before the system
> is actually put to sleep, we cannot have an interrupt service routine to
> clear on read the interrupt status register and ensure that new packet
> matches will be detected.

Hi Florian

I assume the interrupt is active low, not an edge. And it will remain
active until it is cleared? So on resume, don't you need to clear it?
Otherwise it is already active when entering the next suspend/resume
cycle.

Andrew

2023-05-09 09:37:01

by kernel test robot

[permalink] [raw]
Subject: Re: [PATCH net-next 2/3] net: phy: broadcom: Add support for Wake-on-LAN

Hi Florian,

kernel test robot noticed the following build warnings:

[auto build test WARNING on net-next/main]

url: https://github.com/intel-lab-lkp/linux/commits/Florian-Fainelli/net-phy-Let-drivers-check-Wake-on-LAN-status/20230509-024405
base: net-next/main
patch link: https://lore.kernel.org/r/20230508184309.1628108-3-f.fainelli%40gmail.com
patch subject: [PATCH net-next 2/3] net: phy: broadcom: Add support for Wake-on-LAN
config: s390-randconfig-r036-20230508 (https://download.01.org/0day-ci/archive/20230509/[email protected]/config)
compiler: clang version 17.0.0 (https://github.com/llvm/llvm-project b0fb98227c90adf2536c9ad644a74d5e92961111)
reproduce (this is a W=1 build):
wget https://raw.githubusercontent.com/intel/lkp-tests/master/sbin/make.cross -O ~/bin/make.cross
chmod +x ~/bin/make.cross
# install s390 cross compiling tool for clang build
# apt-get install binutils-s390x-linux-gnu
# https://github.com/intel-lab-lkp/linux/commit/9bc5e73961748471e3dae79cb94f329382a6d490
git remote add linux-review https://github.com/intel-lab-lkp/linux
git fetch --no-tags linux-review Florian-Fainelli/net-phy-Let-drivers-check-Wake-on-LAN-status/20230509-024405
git checkout 9bc5e73961748471e3dae79cb94f329382a6d490
# save the config file
mkdir build_dir && cp config build_dir/.config
COMPILER_INSTALL_PATH=$HOME/0day COMPILER=clang make.cross W=1 O=build_dir ARCH=s390 olddefconfig
COMPILER_INSTALL_PATH=$HOME/0day COMPILER=clang make.cross W=1 O=build_dir ARCH=s390 SHELL=/bin/bash drivers/net/phy/ kernel/

If you fix the issue, kindly add following tag where applicable
| Reported-by: kernel test robot <[email protected]>
| Link: https://lore.kernel.org/oe-kbuild-all/[email protected]/

All warnings (new ones prefixed by >>):

In file included from drivers/net/phy/broadcom.c:13:
In file included from drivers/net/phy/bcm-phy-lib.h:9:
In file included from include/linux/brcmphy.h:5:
In file included from include/linux/phy.h:16:
In file included from include/linux/ethtool.h:18:
In file included from include/linux/if_ether.h:19:
In file included from include/linux/skbuff.h:28:
In file included from include/linux/dma-mapping.h:10:
In file included from include/linux/scatterlist.h:9:
In file included from arch/s390/include/asm/io.h:75:
include/asm-generic/io.h:547:31: warning: performing pointer arithmetic on a null pointer has undefined behavior [-Wnull-pointer-arithmetic]
val = __raw_readb(PCI_IOBASE + addr);
~~~~~~~~~~ ^
include/asm-generic/io.h:560:61: warning: performing pointer arithmetic on a null pointer has undefined behavior [-Wnull-pointer-arithmetic]
val = __le16_to_cpu((__le16 __force)__raw_readw(PCI_IOBASE + addr));
~~~~~~~~~~ ^
include/uapi/linux/byteorder/big_endian.h:37:59: note: expanded from macro '__le16_to_cpu'
#define __le16_to_cpu(x) __swab16((__force __u16)(__le16)(x))
^
include/uapi/linux/swab.h:102:54: note: expanded from macro '__swab16'
#define __swab16(x) (__u16)__builtin_bswap16((__u16)(x))
^
In file included from drivers/net/phy/broadcom.c:13:
In file included from drivers/net/phy/bcm-phy-lib.h:9:
In file included from include/linux/brcmphy.h:5:
In file included from include/linux/phy.h:16:
In file included from include/linux/ethtool.h:18:
In file included from include/linux/if_ether.h:19:
In file included from include/linux/skbuff.h:28:
In file included from include/linux/dma-mapping.h:10:
In file included from include/linux/scatterlist.h:9:
In file included from arch/s390/include/asm/io.h:75:
include/asm-generic/io.h:573:61: warning: performing pointer arithmetic on a null pointer has undefined behavior [-Wnull-pointer-arithmetic]
val = __le32_to_cpu((__le32 __force)__raw_readl(PCI_IOBASE + addr));
~~~~~~~~~~ ^
include/uapi/linux/byteorder/big_endian.h:35:59: note: expanded from macro '__le32_to_cpu'
#define __le32_to_cpu(x) __swab32((__force __u32)(__le32)(x))
^
include/uapi/linux/swab.h:115:54: note: expanded from macro '__swab32'
#define __swab32(x) (__u32)__builtin_bswap32((__u32)(x))
^
In file included from drivers/net/phy/broadcom.c:13:
In file included from drivers/net/phy/bcm-phy-lib.h:9:
In file included from include/linux/brcmphy.h:5:
In file included from include/linux/phy.h:16:
In file included from include/linux/ethtool.h:18:
In file included from include/linux/if_ether.h:19:
In file included from include/linux/skbuff.h:28:
In file included from include/linux/dma-mapping.h:10:
In file included from include/linux/scatterlist.h:9:
In file included from arch/s390/include/asm/io.h:75:
include/asm-generic/io.h:584:33: warning: performing pointer arithmetic on a null pointer has undefined behavior [-Wnull-pointer-arithmetic]
__raw_writeb(value, PCI_IOBASE + addr);
~~~~~~~~~~ ^
include/asm-generic/io.h:594:59: warning: performing pointer arithmetic on a null pointer has undefined behavior [-Wnull-pointer-arithmetic]
__raw_writew((u16 __force)cpu_to_le16(value), PCI_IOBASE + addr);
~~~~~~~~~~ ^
include/asm-generic/io.h:604:59: warning: performing pointer arithmetic on a null pointer has undefined behavior [-Wnull-pointer-arithmetic]
__raw_writel((u32 __force)cpu_to_le32(value), PCI_IOBASE + addr);
~~~~~~~~~~ ^
include/asm-generic/io.h:692:20: warning: performing pointer arithmetic on a null pointer has undefined behavior [-Wnull-pointer-arithmetic]
readsb(PCI_IOBASE + addr, buffer, count);
~~~~~~~~~~ ^
include/asm-generic/io.h:700:20: warning: performing pointer arithmetic on a null pointer has undefined behavior [-Wnull-pointer-arithmetic]
readsw(PCI_IOBASE + addr, buffer, count);
~~~~~~~~~~ ^
include/asm-generic/io.h:708:20: warning: performing pointer arithmetic on a null pointer has undefined behavior [-Wnull-pointer-arithmetic]
readsl(PCI_IOBASE + addr, buffer, count);
~~~~~~~~~~ ^
include/asm-generic/io.h:717:21: warning: performing pointer arithmetic on a null pointer has undefined behavior [-Wnull-pointer-arithmetic]
writesb(PCI_IOBASE + addr, buffer, count);
~~~~~~~~~~ ^
include/asm-generic/io.h:726:21: warning: performing pointer arithmetic on a null pointer has undefined behavior [-Wnull-pointer-arithmetic]
writesw(PCI_IOBASE + addr, buffer, count);
~~~~~~~~~~ ^
include/asm-generic/io.h:735:21: warning: performing pointer arithmetic on a null pointer has undefined behavior [-Wnull-pointer-arithmetic]
writesl(PCI_IOBASE + addr, buffer, count);
~~~~~~~~~~ ^
>> drivers/net/phy/broadcom.c:471:6: warning: variable 'ret' is used uninitialized whenever 'if' condition is false [-Wsometimes-uninitialized]
if (priv->wake_irq_enabled != state) {
^~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
drivers/net/phy/broadcom.c:479:9: note: uninitialized use occurs here
return ret;
^~~
drivers/net/phy/broadcom.c:471:2: note: remove the 'if' if its condition is always true
if (priv->wake_irq_enabled != state) {
^~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
drivers/net/phy/broadcom.c:466:9: note: initialize the variable 'ret' to silence this warning
int ret;
^
= 0
13 warnings generated.


vim +471 drivers/net/phy/broadcom.c

462
463 static int bcm54xx_set_wakeup_irq(struct phy_device *phydev, bool state)
464 {
465 struct bcm54xx_phy_priv *priv = phydev->priv;
466 int ret;
467
468 if (!bcm54xx_phy_can_wakeup(phydev))
469 return 0;
470
> 471 if (priv->wake_irq_enabled != state) {
472 if (state)
473 ret = enable_irq_wake(priv->wake_irq);
474 else
475 ret = disable_irq_wake(priv->wake_irq);
476 priv->wake_irq_enabled = state;
477 }
478
479 return ret;
480 }
481

--
0-DAY CI Kernel Test Service
https://github.com/intel/lkp-tests