2022-11-21 16:17:33

by Arun Ramadoss

[permalink] [raw]
Subject: [RFC Patch net-next v2 0/8] net: dsa: microchip: add PTP support for KSZ9x and LAN937x

The LAN937x switch has capable for supporting IEEE 1588 PTP protocol. This
patch series add PTP support and tested using the ptp4l application.
LAN937x has the same PTP register set similar to KSZ9563, hence the
implementation has been made common for the ksz switches.
KSZ9563 does not support two step timestamping but LAN937x supports both.
Tested the 1step & 2step p2p timestamping in LAN937x and p2p1step
timestamping in KSZ9563.

RFC v1 -> v2
- Added the p2p1step timestamping and conditional execution of 2 step for
LAN937x only.
- Added the periodic output support

Arun Ramadoss (7):
net: dsa: microchip: adding the posix clock support
net: dsa: microchip: Initial hardware time stamping support
net: dsa: microchip: Manipulating absolute time using ptp hw clock
net: dsa: microchip: enable the ptp interrupt for timestamping
net: dsa: microchip: Adding the ptp packet reception logic
net: dsa: microchip: add the transmission tstamp logic
net: dsa: microchip: ptp: add periodic output signal

Christian Eggers (1):
net: ptp: add helper for one-step P2P clocks

drivers/net/dsa/microchip/Kconfig | 12 +
drivers/net/dsa/microchip/Makefile | 5 +
drivers/net/dsa/microchip/ksz_common.c | 44 +-
drivers/net/dsa/microchip/ksz_common.h | 48 +
drivers/net/dsa/microchip/ksz_ptp.c | 1117 +++++++++++++++++++++++
drivers/net/dsa/microchip/ksz_ptp.h | 96 ++
drivers/net/dsa/microchip/ksz_ptp_reg.h | 136 +++
include/linux/dsa/ksz_common.h | 55 ++
include/linux/ptp_classify.h | 73 ++
net/dsa/tag_ksz.c | 288 +++++-
10 files changed, 1859 insertions(+), 15 deletions(-)
create mode 100644 drivers/net/dsa/microchip/ksz_ptp.c
create mode 100644 drivers/net/dsa/microchip/ksz_ptp.h
create mode 100644 drivers/net/dsa/microchip/ksz_ptp_reg.h
create mode 100644 include/linux/dsa/ksz_common.h

--
2.36.1



2022-11-21 16:18:20

by Arun Ramadoss

[permalink] [raw]
Subject: [RFC Patch net-next v2 2/8] net: dsa: microchip: adding the posix clock support

This patch implement routines (adjfine, adjtime, gettime and settime)
for manipulating the chip's PTP clock. It registers the ptp caps
to posix clock register.

Signed-off-by: Christian Eggers <[email protected]>
Signed-off-by: Arun Ramadoss <[email protected]>
---
drivers/net/dsa/microchip/Kconfig | 12 ++
drivers/net/dsa/microchip/Makefile | 5 +
drivers/net/dsa/microchip/ksz_common.c | 14 +-
drivers/net/dsa/microchip/ksz_common.h | 17 ++
drivers/net/dsa/microchip/ksz_ptp.c | 270 ++++++++++++++++++++++++
drivers/net/dsa/microchip/ksz_ptp.h | 43 ++++
drivers/net/dsa/microchip/ksz_ptp_reg.h | 52 +++++
7 files changed, 412 insertions(+), 1 deletion(-)
create mode 100644 drivers/net/dsa/microchip/ksz_ptp.c
create mode 100644 drivers/net/dsa/microchip/ksz_ptp.h
create mode 100644 drivers/net/dsa/microchip/ksz_ptp_reg.h

diff --git a/drivers/net/dsa/microchip/Kconfig b/drivers/net/dsa/microchip/Kconfig
index 06b1efdb5e7d..a1a3a04d0ea2 100644
--- a/drivers/net/dsa/microchip/Kconfig
+++ b/drivers/net/dsa/microchip/Kconfig
@@ -10,6 +10,7 @@ menuconfig NET_DSA_MICROCHIP_KSZ_COMMON
config NET_DSA_MICROCHIP_KSZ9477_I2C
tristate "KSZ series I2C connected switch driver"
depends on NET_DSA_MICROCHIP_KSZ_COMMON && I2C
+ depends on PTP_1588_CLOCK_OPTIONAL
select REGMAP_I2C
help
Select to enable support for registering switches configured through I2C.
@@ -17,10 +18,21 @@ config NET_DSA_MICROCHIP_KSZ9477_I2C
config NET_DSA_MICROCHIP_KSZ_SPI
tristate "KSZ series SPI connected switch driver"
depends on NET_DSA_MICROCHIP_KSZ_COMMON && SPI
+ depends on PTP_1588_CLOCK_OPTIONAL
select REGMAP_SPI
help
Select to enable support for registering switches configured through SPI.

+config NET_DSA_MICROCHIP_KSZ_PTP
+ bool "Support for the PTP clock on the KSZ9563/LAN937x Ethernet Switch"
+ depends on NET_DSA_MICROCHIP_KSZ_COMMON && PTP_1588_CLOCK
+ help
+ This enables support for timestamping & PTP clock manipulation
+ in the KSZ9563/LAN937x Ethernet switch
+
+ Select to enable support for PTP feature for KSZ9563/lan937x series
+ of switch.
+
config NET_DSA_MICROCHIP_KSZ8863_SMI
tristate "KSZ series SMI connected switch driver"
depends on NET_DSA_MICROCHIP_KSZ_COMMON
diff --git a/drivers/net/dsa/microchip/Makefile b/drivers/net/dsa/microchip/Makefile
index 28873559efc2..48360cc9fc68 100644
--- a/drivers/net/dsa/microchip/Makefile
+++ b/drivers/net/dsa/microchip/Makefile
@@ -4,6 +4,11 @@ ksz_switch-objs := ksz_common.o
ksz_switch-objs += ksz9477.o
ksz_switch-objs += ksz8795.o
ksz_switch-objs += lan937x_main.o
+
+ifdef CONFIG_NET_DSA_MICROCHIP_KSZ_PTP
+ksz_switch-objs += ksz_ptp.o
+endif
+
obj-$(CONFIG_NET_DSA_MICROCHIP_KSZ9477_I2C) += ksz9477_i2c.o
obj-$(CONFIG_NET_DSA_MICROCHIP_KSZ_SPI) += ksz_spi.o
obj-$(CONFIG_NET_DSA_MICROCHIP_KSZ8863_SMI) += ksz8863_smi.o
diff --git a/drivers/net/dsa/microchip/ksz_common.c b/drivers/net/dsa/microchip/ksz_common.c
index 8c8db315317d..eb77eca0dcb2 100644
--- a/drivers/net/dsa/microchip/ksz_common.c
+++ b/drivers/net/dsa/microchip/ksz_common.c
@@ -27,6 +27,7 @@
#include "ksz8.h"
#include "ksz9477.h"
#include "lan937x.h"
+#include "ksz_ptp.h"

#define MIB_COUNTER_NUM 0x20

@@ -2016,10 +2017,16 @@ static int ksz_setup(struct dsa_switch *ds)
}
}

+ ret = ksz_ptp_clock_register(ds);
+ if (ret) {
+ dev_err(dev->dev, "Failed to register PTP clock: %d\n", ret);
+ goto out_pirq;
+ }
+
ret = ksz_mdio_register(dev);
if (ret < 0) {
dev_err(dev->dev, "failed to register the mdio");
- goto out_pirq;
+ goto out_ptp_clock_unregister;
}

/* start switch */
@@ -2028,6 +2035,8 @@ static int ksz_setup(struct dsa_switch *ds)

return 0;

+out_ptp_clock_unregister:
+ ksz_ptp_clock_unregister(ds);
out_pirq:
if (dev->irq > 0)
dsa_switch_for_each_user_port(dp, dev->ds)
@@ -2044,6 +2053,8 @@ static void ksz_teardown(struct dsa_switch *ds)
struct ksz_device *dev = ds->priv;
struct dsa_port *dp;

+ ksz_ptp_clock_unregister(ds);
+
if (dev->irq > 0) {
dsa_switch_for_each_user_port(dp, dev->ds)
ksz_irq_free(&dev->ports[dp->index].pirq);
@@ -2861,6 +2872,7 @@ static const struct dsa_switch_ops ksz_switch_ops = {
.get_pause_stats = ksz_get_pause_stats,
.port_change_mtu = ksz_change_mtu,
.port_max_mtu = ksz_max_mtu,
+ .get_ts_info = ksz_get_ts_info,
};

struct ksz_device *ksz_switch_alloc(struct device *base, void *priv)
diff --git a/drivers/net/dsa/microchip/ksz_common.h b/drivers/net/dsa/microchip/ksz_common.h
index c6726cbd5465..767f17d2c75d 100644
--- a/drivers/net/dsa/microchip/ksz_common.h
+++ b/drivers/net/dsa/microchip/ksz_common.h
@@ -14,6 +14,9 @@
#include <linux/regmap.h>
#include <net/dsa.h>
#include <linux/irq.h>
+#include <linux/ptp_clock_kernel.h>
+
+#include "ksz_ptp.h"

#define KSZ_MAX_NUM_PORTS 8

@@ -141,6 +144,7 @@ struct ksz_device {
u16 port_mask;
struct mutex lock_irq; /* IRQ Access */
struct ksz_irq girq;
+ struct ksz_ptp_data ptp_data;
};

/* List of supported models */
@@ -444,6 +448,19 @@ static inline int ksz_write32(struct ksz_device *dev, u32 reg, u32 value)
return ret;
}

+static inline int ksz_rmw16(struct ksz_device *dev, u32 reg, u16 mask,
+ u16 value)
+{
+ int ret;
+
+ ret = regmap_update_bits(dev->regmap[1], reg, mask, value);
+ if (ret)
+ dev_err(dev->dev, "can't rmw 16bit reg: 0x%x %pe\n", reg,
+ ERR_PTR(ret));
+
+ return ret;
+}
+
static inline int ksz_write64(struct ksz_device *dev, u32 reg, u64 value)
{
u32 val[2];
diff --git a/drivers/net/dsa/microchip/ksz_ptp.c b/drivers/net/dsa/microchip/ksz_ptp.c
new file mode 100644
index 000000000000..cad0c6087419
--- /dev/null
+++ b/drivers/net/dsa/microchip/ksz_ptp.c
@@ -0,0 +1,270 @@
+// SPDX-License-Identifier: GPL-2.0
+/* Microchip LAN937X PTP Implementation
+ * Copyright (C) 2021-2022 Microchip Technology Inc.
+ */
+
+#include <linux/kernel.h>
+#include <linux/ptp_classify.h>
+#include <linux/ptp_clock_kernel.h>
+
+#include "ksz_common.h"
+#include "ksz_ptp.h"
+#include "ksz_ptp_reg.h"
+
+#define ptp_caps_to_data(d) \
+ container_of((d), struct ksz_ptp_data, caps)
+#define ptp_data_to_ksz_dev(d) \
+ container_of((d), struct ksz_device, ptp_data)
+
+#define MAX_DRIFT_CORR 6250000
+
+#define KSZ_PTP_INC_NS 40 /* HW clock is incremented every 40 ns (by 40) */
+#define KSZ_PTP_SUBNS_BITS 32 /* Number of bits in sub-nanoseconds counter */
+
+/* The function is return back the capability of timestamping feature when
+ * requested through ethtool -T <interface> utility
+ */
+int ksz_get_ts_info(struct dsa_switch *ds, int port, struct ethtool_ts_info *ts)
+{
+ struct ksz_device *dev = ds->priv;
+ struct ksz_ptp_data *ptp_data = &dev->ptp_data;
+
+ ts->so_timestamping = SOF_TIMESTAMPING_TX_HARDWARE |
+ SOF_TIMESTAMPING_RX_HARDWARE |
+ SOF_TIMESTAMPING_RAW_HARDWARE;
+
+ ts->tx_types = (1 << HWTSTAMP_TX_OFF);
+
+ ts->rx_filters = (1 << HWTSTAMP_FILTER_NONE);
+
+ ts->phc_index = ptp_clock_index(ptp_data->clock);
+
+ return 0;
+}
+
+/* These are function related to the ptp clock info */
+static int _ksz_ptp_gettime(struct ksz_device *dev, struct timespec64 *ts)
+{
+ u32 nanoseconds;
+ u32 seconds;
+ u8 phase;
+ int ret;
+
+ /* Copy current PTP clock into shadow registers */
+ ret = ksz_rmw16(dev, REG_PTP_CLK_CTRL, PTP_READ_TIME, PTP_READ_TIME);
+ if (ret)
+ return ret;
+
+ /* Read from shadow registers */
+ ret = ksz_read8(dev, REG_PTP_RTC_SUB_NANOSEC__2, &phase);
+ if (ret)
+ return ret;
+
+ ret = ksz_read32(dev, REG_PTP_RTC_NANOSEC, &nanoseconds);
+ if (ret)
+ return ret;
+
+ ret = ksz_read32(dev, REG_PTP_RTC_SEC, &seconds);
+ if (ret)
+ return ret;
+
+ ts->tv_sec = seconds;
+ ts->tv_nsec = nanoseconds + phase * 8;
+
+ return 0;
+}
+
+static int ksz_ptp_gettime(struct ptp_clock_info *ptp, struct timespec64 *ts)
+{
+ struct ksz_ptp_data *ptp_data = ptp_caps_to_data(ptp);
+ struct ksz_device *dev = ptp_data_to_ksz_dev(ptp_data);
+ int ret;
+
+ mutex_lock(&ptp_data->lock);
+ ret = _ksz_ptp_gettime(dev, ts);
+ mutex_unlock(&ptp_data->lock);
+
+ return ret;
+}
+
+static int ksz_ptp_settime(struct ptp_clock_info *ptp,
+ const struct timespec64 *ts)
+{
+ struct ksz_ptp_data *ptp_data = ptp_caps_to_data(ptp);
+ struct ksz_device *dev = ptp_data_to_ksz_dev(ptp_data);
+ int ret;
+
+ mutex_lock(&ptp_data->lock);
+
+ /* Write to shadow registers */
+
+ /* Write 0 to clock phase */
+ ret = ksz_write16(dev, REG_PTP_RTC_SUB_NANOSEC__2, PTP_RTC_0NS);
+ if (ret)
+ goto error_return;
+
+ /* nanoseconds */
+ ret = ksz_write32(dev, REG_PTP_RTC_NANOSEC, ts->tv_nsec);
+ if (ret)
+ goto error_return;
+
+ /* seconds */
+ ret = ksz_write32(dev, REG_PTP_RTC_SEC, ts->tv_sec);
+ if (ret)
+ goto error_return;
+
+ /* Load PTP clock from shadow registers */
+ ret = ksz_rmw16(dev, REG_PTP_CLK_CTRL, PTP_LOAD_TIME, PTP_LOAD_TIME);
+
+error_return:
+ mutex_unlock(&ptp_data->lock);
+
+ return ret;
+}
+
+static int ksz_ptp_adjfine(struct ptp_clock_info *ptp, long scaled_ppm)
+{
+ struct ksz_ptp_data *ptp_data = ptp_caps_to_data(ptp);
+ struct ksz_device *dev = ptp_data_to_ksz_dev(ptp_data);
+ int ret;
+
+ mutex_lock(&ptp_data->lock);
+
+ if (scaled_ppm) {
+ s64 ppb, adj;
+ u32 data32;
+
+ /* see scaled_ppm_to_ppb() in ptp_clock.c for details */
+ ppb = 1 + scaled_ppm;
+ ppb *= 125;
+ ppb *= KSZ_PTP_INC_NS;
+ ppb <<= KSZ_PTP_SUBNS_BITS - 13;
+ adj = div_s64(ppb, NSEC_PER_SEC);
+
+ data32 = abs(adj);
+ data32 &= PTP_SUBNANOSEC_M;
+ if (adj >= 0)
+ data32 |= PTP_RATE_DIR;
+
+ ret = ksz_write32(dev, REG_PTP_SUBNANOSEC_RATE, data32);
+ if (ret)
+ goto error_return;
+
+ ret = ksz_rmw16(dev, REG_PTP_CLK_CTRL, PTP_CLK_ADJ_ENABLE,
+ PTP_CLK_ADJ_ENABLE);
+ if (ret)
+ goto error_return;
+ } else {
+ ret = ksz_rmw16(dev, REG_PTP_CLK_CTRL, PTP_CLK_ADJ_ENABLE, 0);
+ if (ret)
+ goto error_return;
+ }
+
+error_return:
+ mutex_unlock(&ptp_data->lock);
+ return ret;
+}
+
+static int ksz_ptp_adjtime(struct ptp_clock_info *ptp, s64 delta)
+{
+ struct ksz_ptp_data *ptp_data = ptp_caps_to_data(ptp);
+ struct ksz_device *dev = ptp_data_to_ksz_dev(ptp_data);
+ s32 sec, nsec;
+ u16 data16;
+ int ret;
+
+ mutex_lock(&ptp_data->lock);
+
+ /* do not use ns_to_timespec64(),
+ * both sec and nsec are subtracted by hw
+ */
+ sec = div_s64_rem(delta, NSEC_PER_SEC, &nsec);
+
+ ret = ksz_write32(dev, REG_PTP_RTC_NANOSEC, abs(nsec));
+ if (ret)
+ goto error_return;
+
+ ret = ksz_write32(dev, REG_PTP_RTC_SEC, abs(sec));
+ if (ret)
+ goto error_return;
+
+ ret = ksz_read16(dev, REG_PTP_CLK_CTRL, &data16);
+ if (ret)
+ goto error_return;
+
+ data16 |= PTP_STEP_ADJ;
+
+ /*PTP_STEP_DIR -- 0: subtract, 1: add */
+ if (delta < 0)
+ data16 &= ~PTP_STEP_DIR;
+ else
+ data16 |= PTP_STEP_DIR;
+
+ ret = ksz_write16(dev, REG_PTP_CLK_CTRL, data16);
+
+error_return:
+ mutex_unlock(&ptp_data->lock);
+ return ret;
+}
+
+static int ksz_ptp_start_clock(struct ksz_device *dev)
+{
+ return ksz_rmw16(dev, REG_PTP_CLK_CTRL, PTP_CLK_ENABLE, PTP_CLK_ENABLE);
+}
+
+static const struct ptp_clock_info ksz_ptp_caps = {
+ .owner = THIS_MODULE,
+ .name = "Microchip Clock",
+ .max_adj = MAX_DRIFT_CORR,
+ .gettime64 = ksz_ptp_gettime,
+ .settime64 = ksz_ptp_settime,
+ .adjfine = ksz_ptp_adjfine,
+ .adjtime = ksz_ptp_adjtime,
+};
+
+int ksz_ptp_clock_register(struct dsa_switch *ds)
+{
+ struct ksz_device *dev = ds->priv;
+ struct ksz_ptp_data *ptp_data = &dev->ptp_data;
+ int ret;
+
+ mutex_init(&ptp_data->lock);
+
+ ptp_data->caps = ksz_ptp_caps;
+
+ /* Start hardware counter */
+ ret = ksz_ptp_start_clock(dev);
+ if (ret)
+ return ret;
+
+ /* Register the PTP Clock */
+ ptp_data->clock = ptp_clock_register(&ptp_data->caps, dev->dev);
+ if (IS_ERR_OR_NULL(ptp_data->clock))
+ return PTR_ERR(ptp_data->clock);
+
+ ret = ksz_rmw16(dev, REG_PTP_MSG_CONF1, PTP_802_1AS, PTP_802_1AS);
+ if (ret)
+ goto error_unregister_clock;
+
+ return 0;
+
+error_unregister_clock:
+ ptp_clock_unregister(ptp_data->clock);
+ return ret;
+}
+
+void ksz_ptp_clock_unregister(struct dsa_switch *ds)
+{
+ struct ksz_device *dev = ds->priv;
+ struct ksz_ptp_data *ptp_data = &dev->ptp_data;
+
+ if (IS_ERR_OR_NULL(ptp_data->clock))
+ return;
+
+ ptp_clock_unregister(ptp_data->clock);
+}
+
+MODULE_AUTHOR("Christian Eggers <[email protected]>");
+MODULE_AUTHOR("Arun Ramadoss <[email protected]>");
+MODULE_DESCRIPTION("PTP support for KSZ switch");
+MODULE_LICENSE("GPL");
diff --git a/drivers/net/dsa/microchip/ksz_ptp.h b/drivers/net/dsa/microchip/ksz_ptp.h
new file mode 100644
index 000000000000..ac53b0df2733
--- /dev/null
+++ b/drivers/net/dsa/microchip/ksz_ptp.h
@@ -0,0 +1,43 @@
+/* SPDX-License-Identifier: GPL-2.0 */
+/* Microchip LAN937X PTP Implementation
+ * Copyright (C) 2020-2021 Microchip Technology Inc.
+ */
+
+#ifndef _NET_DSA_DRIVERS_KSZ_PTP_H
+#define _NET_DSA_DRIVERS_KSZ_PTP_H
+
+#if IS_ENABLED(CONFIG_NET_DSA_MICROCHIP_KSZ_PTP)
+
+struct ksz_ptp_data {
+ struct ptp_clock_info caps;
+ struct ptp_clock *clock;
+ /* Serializes all operations on the PTP hardware clock */
+ struct mutex lock;
+};
+
+int ksz_ptp_clock_register(struct dsa_switch *ds);
+
+void ksz_ptp_clock_unregister(struct dsa_switch *ds);
+
+int ksz_get_ts_info(struct dsa_switch *ds, int port,
+ struct ethtool_ts_info *ts);
+
+#else
+
+struct ksz_ptp_data {
+ /* Serializes all operations on the PTP hardware clock */
+ struct mutex lock;
+};
+
+static inline int ksz_ptp_clock_register(struct dsa_switch *ds)
+{
+ return 0;
+}
+
+static inline void ksz_ptp_clock_unregister(struct dsa_switch *ds) { }
+
+#define ksz_get_ts_info NULL
+
+#endif /* End of CONFIG_NET_DSA_MICROCHIOP_KSZ_PTP */
+
+#endif
diff --git a/drivers/net/dsa/microchip/ksz_ptp_reg.h b/drivers/net/dsa/microchip/ksz_ptp_reg.h
new file mode 100644
index 000000000000..2bf8395475b9
--- /dev/null
+++ b/drivers/net/dsa/microchip/ksz_ptp_reg.h
@@ -0,0 +1,52 @@
+/* SPDX-License-Identifier: GPL-2.0 */
+/* Microchip KSZ PTP register definitions
+ * Copyright (C) 2019-2021 Microchip Technology Inc.
+ */
+
+/* 5 - PTP Clock */
+#define REG_PTP_CLK_CTRL 0x0500
+
+#define PTP_STEP_ADJ BIT(6)
+#define PTP_STEP_DIR BIT(5)
+#define PTP_READ_TIME BIT(4)
+#define PTP_LOAD_TIME BIT(3)
+#define PTP_CLK_ADJ_ENABLE BIT(2)
+#define PTP_CLK_ENABLE BIT(1)
+#define PTP_CLK_RESET BIT(0)
+
+#define REG_PTP_RTC_SUB_NANOSEC__2 0x0502
+
+#define PTP_RTC_SUB_NANOSEC_M 0x0007
+#define PTP_RTC_0NS 0x00
+
+#define REG_PTP_RTC_NANOSEC 0x0504
+#define REG_PTP_RTC_NANOSEC_H 0x0504
+#define REG_PTP_RTC_NANOSEC_L 0x0506
+
+#define REG_PTP_RTC_SEC 0x0508
+#define REG_PTP_RTC_SEC_H 0x0508
+#define REG_PTP_RTC_SEC_L 0x050A
+
+#define REG_PTP_SUBNANOSEC_RATE 0x050C
+#define REG_PTP_SUBNANOSEC_RATE_H 0x050C
+#define PTP_SUBNANOSEC_M 0x3FFFFFFF
+
+#define PTP_RATE_DIR BIT(31)
+#define PTP_TMP_RATE_ENABLE BIT(30)
+
+#define REG_PTP_SUBNANOSEC_RATE_L 0x050E
+
+#define REG_PTP_RATE_DURATION 0x0510
+#define REG_PTP_RATE_DURATION_H 0x0510
+#define REG_PTP_RATE_DURATION_L 0x0512
+
+#define REG_PTP_MSG_CONF1 0x0514
+
+#define PTP_802_1AS BIT(7)
+#define PTP_ENABLE BIT(6)
+#define PTP_ETH_ENABLE BIT(5)
+#define PTP_IPV4_UDP_ENABLE BIT(4)
+#define PTP_IPV6_UDP_ENABLE BIT(3)
+#define PTP_TC_P2P BIT(2)
+#define PTP_MASTER BIT(1)
+#define PTP_1STEP BIT(0)
--
2.36.1


2022-11-21 16:20:25

by Arun Ramadoss

[permalink] [raw]
Subject: [RFC Patch net-next v2 1/8] net: ptp: add helper for one-step P2P clocks

From: Christian Eggers <[email protected]>

For P2P delay measurement, the ingress time stamp of the PDelay_Req is
required for the correction field of the PDelay_Resp. The application
echoes back the correction field of the PDelay_Req when sending the
PDelay_Resp.

Some hardware (like the ZHAW InES PTP time stamping IP core) subtracts
the ingress timestamp autonomously from the correction field, so that
the hardware only needs to add the egress timestamp on tx. Other
hardware (like the Microchip KSZ9563) reports the ingress time stamp via
an interrupt and requires that the software provides this time stamp via
tail-tag on tx.

In order to avoid introducing a further application interface for this,
the driver can simply emulate the behavior of the InES device and
subtract the ingress time stamp in software from the correction field.

On egress, the correction field can either be kept as it is (and the
time stamp field in the tail-tag is set to zero) or move the value from
the correction field back to the tail-tag.

Changing the correction field requires updating the UDP checksum (if UDP
is used as transport).

Signed-off-by: Christian Eggers <[email protected]>
---
include/linux/ptp_classify.h | 73 ++++++++++++++++++++++++++++++++++++
1 file changed, 73 insertions(+)

diff --git a/include/linux/ptp_classify.h b/include/linux/ptp_classify.h
index 2b6ea36ad162..e32efe3c4d66 100644
--- a/include/linux/ptp_classify.h
+++ b/include/linux/ptp_classify.h
@@ -10,8 +10,12 @@
#ifndef _PTP_CLASSIFY_H_
#define _PTP_CLASSIFY_H_

+#include <asm/unaligned.h>
#include <linux/ip.h>
+#include <linux/ktime.h>
#include <linux/skbuff.h>
+#include <linux/udp.h>
+#include <net/checksum.h>

#define PTP_CLASS_NONE 0x00 /* not a PTP event message */
#define PTP_CLASS_V1 0x01 /* protocol version 1 */
@@ -129,6 +133,67 @@ static inline u8 ptp_get_msgtype(const struct ptp_header *hdr,
return msgtype;
}

+/**
+ * ptp_check_diff8 - Computes new checksum (when altering a 64-bit field)
+ * @old: old field value
+ * @new: new field value
+ * @oldsum: previous checksum
+ *
+ * This function can be used to calculate a new checksum when only a single
+ * field is changed. Similar as ip_vs_check_diff*() in ip_vs.h.
+ *
+ * Return: Updated checksum
+ */
+static inline __wsum ptp_check_diff8(__be64 old, __be64 new, __wsum oldsum)
+{
+ __be64 diff[2] = { ~old, new };
+
+ return csum_partial(diff, sizeof(diff), oldsum);
+}
+
+/**
+ * ptp_header_update_correction - Update PTP header's correction field
+ * @skb: packet buffer
+ * @type: type of the packet (see ptp_classify_raw())
+ * @hdr: ptp header
+ * @correction: new correction value
+ *
+ * This updates the correction field of a PTP header and updates the UDP
+ * checksum (if UDP is used as transport). It is needed for hardware capable of
+ * one-step P2P that does not already modify the correction field of Pdelay_Req
+ * event messages on ingress.
+ */
+static inline
+void ptp_header_update_correction(struct sk_buff *skb, unsigned int type,
+ struct ptp_header *hdr, s64 correction)
+{
+ __be64 correction_old;
+ struct udphdr *uhdr;
+
+ /* previous correction value is required for checksum update. */
+ memcpy(&correction_old, &hdr->correction, sizeof(correction_old));
+
+ /* write new correction value */
+ put_unaligned_be64((u64)correction, &hdr->correction);
+
+ switch (type & PTP_CLASS_PMASK) {
+ case PTP_CLASS_IPV4:
+ case PTP_CLASS_IPV6:
+ /* locate udp header */
+ uhdr = (struct udphdr *)((char *)hdr - sizeof(struct udphdr));
+ break;
+ default:
+ return;
+ }
+
+ /* update checksum */
+ uhdr->check = csum_fold(ptp_check_diff8(correction_old,
+ hdr->correction,
+ ~csum_unfold(uhdr->check)));
+ if (!uhdr->check)
+ uhdr->check = CSUM_MANGLED_0;
+}
+
/**
* ptp_msg_is_sync - Evaluates whether the given skb is a PTP Sync message
* @skb: packet buffer
@@ -166,5 +231,13 @@ static inline bool ptp_msg_is_sync(struct sk_buff *skb, unsigned int type)
{
return false;
}
+
+static inline
+void ptp_onestep_p2p_move_t2_to_correction(struct sk_buff *skb,
+ unsigned int type,
+ struct ptp_header *hdr,
+ ktime_t t2)
+{
+}
#endif
#endif /* _PTP_CLASSIFY_H_ */
--
2.36.1


2022-11-21 21:39:46

by Vladimir Oltean

[permalink] [raw]
Subject: Re: [RFC Patch net-next v2 0/8] net: dsa: microchip: add PTP support for KSZ9x and LAN937x

Hi Arun,

On Mon, Nov 21, 2022 at 09:11:42PM +0530, Arun Ramadoss wrote:
> The LAN937x switch has capable for supporting IEEE 1588 PTP protocol. This
> patch series add PTP support and tested using the ptp4l application.
> LAN937x has the same PTP register set similar to KSZ9563, hence the
> implementation has been made common for the ksz switches.
> KSZ9563 does not support two step timestamping but LAN937x supports both.
> Tested the 1step & 2step p2p timestamping in LAN937x and p2p1step
> timestamping in KSZ9563.

A process-related pattern I noticed in your patches. The Author: is in
general the same as the first Signed-off-by:. I don't know of cases
where that's not true.

There can be more subsequent Signed-off-by: tags, and those are people
through the hands of whom those patches have passed, and who might have
made changes to them.

When you use Christian's patches (verbatim or with non-radical rework,
like fixes here and there, styling rework, commit message rewrite),
you need Christian to appear in the Author: and first Signed-off-by:
field, and you in the second. When patches are more or less a complete
rework (such that it no longer resembles Christian's original intentions
and it would be misleading to put his sign off on something which he did
not write), you can put yourself as author and first sign off, and use
Co-developed-by: + Signed-off-by for Christian's work (the sign off
still seems to be required for some reason). You need to use your
judgement here, you can't always put your name on others' work.
You can also say "based on a previous patch posted on the mailing lists
which was heavily reworked" and provide a Link: tag with a
lore.kernel.org or patchwork.kernel.org link. Under the "---" sign in
the patch you can also clarify the changes you've made, if you decide to
keep Christian's authorship but make significant but not radical changes.
These annotations will always be visible in patchwork even if not in
git. At least that's what I would do.

2022-11-21 21:42:41

by Vladimir Oltean

[permalink] [raw]
Subject: Re: [RFC Patch net-next v2 2/8] net: dsa: microchip: adding the posix clock support

On Mon, Nov 21, 2022 at 09:11:44PM +0530, Arun Ramadoss wrote:
> +int ksz_ptp_clock_register(struct dsa_switch *ds)
> +{
> + /* Register the PTP Clock */
> + ptp_data->clock = ptp_clock_register(&ptp_data->caps, dev->dev);
> + if (IS_ERR_OR_NULL(ptp_data->clock))
> + return PTR_ERR(ptp_data->clock);
> +}
> +
> +void ksz_ptp_clock_unregister(struct dsa_switch *ds)
> +{
> + struct ksz_device *dev = ds->priv;
> + struct ksz_ptp_data *ptp_data = &dev->ptp_data;
> +
> + if (IS_ERR_OR_NULL(ptp_data->clock))
> + return;
> +
> + ptp_clock_unregister(ptp_data->clock);
> +}

API usage seems to be incorrect here (probably copied from sja1105 which
is written by me and also incorrect, yay).

The intention with IS_ERR_OR_NULL() is for the caller to return 0
(success) when ptp_clock_register() returns NULL (when PTP support
is compiled out), and this will not make the driver fail to probe.

There isn't a reason to use IS_ERR_OR_NULL() in the normal unregister
code path, because the code won't get there in the IS_ERR() case.
So a simple "if (ptp_data->clock) ptp_clock_unregister(ptp_data->clock)"
would do.

2022-11-21 22:31:06

by Vladimir Oltean

[permalink] [raw]
Subject: Re: [RFC Patch net-next v2 2/8] net: dsa: microchip: adding the posix clock support

On Mon, Nov 21, 2022 at 09:11:44PM +0530, Arun Ramadoss wrote:
> @@ -17,10 +18,21 @@ config NET_DSA_MICROCHIP_KSZ9477_I2C
> config NET_DSA_MICROCHIP_KSZ_SPI
> tristate "KSZ series SPI connected switch driver"
> depends on NET_DSA_MICROCHIP_KSZ_COMMON && SPI
> + depends on PTP_1588_CLOCK_OPTIONAL
> select REGMAP_SPI
> help
> Select to enable support for registering switches configured through SPI.
>
> +config NET_DSA_MICROCHIP_KSZ_PTP
> + bool "Support for the PTP clock on the KSZ9563/LAN937x Ethernet Switch"
> + depends on NET_DSA_MICROCHIP_KSZ_COMMON && PTP_1588_CLOCK
> + help
> + This enables support for timestamping & PTP clock manipulation

Please use "and" instead of "&".

> + in the KSZ9563/LAN937x Ethernet switch
> +
> + Select to enable support for PTP feature for KSZ9563/lan937x series

Please capitalize both KSZ9563 and LAN937X. This help text is the
business card of the feature, you need it to look nice and shiny.

Also, "for PTP feature for ..."? How about "enable PTP hardware
timestamping and clock manipulation support for ..."?

> + of switch.

switches

> +
> config NET_DSA_MICROCHIP_KSZ8863_SMI
> tristate "KSZ series SMI connected switch driver"
> depends on NET_DSA_MICROCHIP_KSZ_COMMON
> diff --git a/drivers/net/dsa/microchip/ksz_ptp.c b/drivers/net/dsa/microchip/ksz_ptp.c
> new file mode 100644
> index 000000000000..cad0c6087419
> --- /dev/null
> +++ b/drivers/net/dsa/microchip/ksz_ptp.c
> @@ -0,0 +1,270 @@
> +// SPDX-License-Identifier: GPL-2.0
> +/* Microchip LAN937X PTP Implementation
> + * Copyright (C) 2021-2022 Microchip Technology Inc.
> + */
> +
> +#include <linux/kernel.h>
> +#include <linux/ptp_classify.h>
> +#include <linux/ptp_clock_kernel.h>
> +
> +#include "ksz_common.h"
> +#include "ksz_ptp.h"
> +#include "ksz_ptp_reg.h"
> +
> +#define ptp_caps_to_data(d) \
> + container_of((d), struct ksz_ptp_data, caps)
> +#define ptp_data_to_ksz_dev(d) \
> + container_of((d), struct ksz_device, ptp_data)
> +
> +#define MAX_DRIFT_CORR 6250000

KSZ_MAX_DRIFT_CORR maybe? Also maybe a small comment about the
assumptions that were made when it was calculated?

> +
> +#define KSZ_PTP_INC_NS 40 /* HW clock is incremented every 40 ns (by 40) */
> +#define KSZ_PTP_SUBNS_BITS 32 /* Number of bits in sub-nanoseconds counter */
> +
> +/* The function is return back the capability of timestamping feature when
> + * requested through ethtool -T <interface> utility
> + */
> +int ksz_get_ts_info(struct dsa_switch *ds, int port, struct ethtool_ts_info *ts)
> +{
> + struct ksz_device *dev = ds->priv;
> + struct ksz_ptp_data *ptp_data = &dev->ptp_data;
> +
> + ts->so_timestamping = SOF_TIMESTAMPING_TX_HARDWARE |
> + SOF_TIMESTAMPING_RX_HARDWARE |
> + SOF_TIMESTAMPING_RAW_HARDWARE;
> +
> + ts->tx_types = (1 << HWTSTAMP_TX_OFF);
> +
> + ts->rx_filters = (1 << HWTSTAMP_FILTER_NONE);
> +
> + ts->phc_index = ptp_clock_index(ptp_data->clock);

Ah, but I don't think the optionality of ptp_data->clock is dealt with
very well here. ptp_data->clock can be NULL, and ethtool -T can still be
run on the interface. That will dereference a NULL pointer in ptp_clock_index().

int ptp_clock_index(struct ptp_clock *ptp)
{
return ptp->index;
}
EXPORT_SYMBOL(ptp_clock_index);

> +
> + return 0;
> +}
> +
> +int ksz_ptp_clock_register(struct dsa_switch *ds)
> +{
> + struct ksz_device *dev = ds->priv;
> + struct ksz_ptp_data *ptp_data = &dev->ptp_data;
> + int ret;
> +
> + mutex_init(&ptp_data->lock);
> +
> + ptp_data->caps = ksz_ptp_caps;
> +
> + /* Start hardware counter */
> + ret = ksz_ptp_start_clock(dev);
> + if (ret)
> + return ret;
> +
> + /* Register the PTP Clock */
> + ptp_data->clock = ptp_clock_register(&ptp_data->caps, dev->dev);
> + if (IS_ERR_OR_NULL(ptp_data->clock))
> + return PTR_ERR(ptp_data->clock);
> +
> + ret = ksz_rmw16(dev, REG_PTP_MSG_CONF1, PTP_802_1AS, PTP_802_1AS);

A small comment as to what this does? I see in other places you're
generous with comments, like "Register the PTP clock" above the
ptp_clock_register() call.

> + if (ret)
> + goto error_unregister_clock;
> +
> + return 0;
> +
> +error_unregister_clock:
> + ptp_clock_unregister(ptp_data->clock);
> + return ret;
> +}
> +
> +MODULE_AUTHOR("Christian Eggers <[email protected]>");
> +MODULE_AUTHOR("Arun Ramadoss <[email protected]>");
> +MODULE_DESCRIPTION("PTP support for KSZ switch");
> +MODULE_LICENSE("GPL");
> diff --git a/drivers/net/dsa/microchip/ksz_ptp.h b/drivers/net/dsa/microchip/ksz_ptp.h
> new file mode 100644
> index 000000000000..ac53b0df2733
> --- /dev/null
> +++ b/drivers/net/dsa/microchip/ksz_ptp.h
> @@ -0,0 +1,43 @@
> +/* SPDX-License-Identifier: GPL-2.0 */
> +/* Microchip LAN937X PTP Implementation
> + * Copyright (C) 2020-2021 Microchip Technology Inc.
> + */
> +
> +#ifndef _NET_DSA_DRIVERS_KSZ_PTP_H
> +#define _NET_DSA_DRIVERS_KSZ_PTP_H
> +
> +#if IS_ENABLED(CONFIG_NET_DSA_MICROCHIP_KSZ_PTP)
> +
> +#endif /* End of CONFIG_NET_DSA_MICROCHIOP_KSZ_PTP */

MICROCHIP not MICROCHIOP

> +
> +#endif

2022-11-22 15:14:13

by Richard Cochran

[permalink] [raw]
Subject: Re: [RFC Patch net-next v2 1/8] net: ptp: add helper for one-step P2P clocks

On Mon, Nov 21, 2022 at 09:11:43PM +0530, Arun Ramadoss wrote:
> +/**
> + * ptp_header_update_correction - Update PTP header's correction field
> + * @skb: packet buffer
> + * @type: type of the packet (see ptp_classify_raw())
> + * @hdr: ptp header
> + * @correction: new correction value
> + *
> + * This updates the correction field of a PTP header and updates the UDP
> + * checksum (if UDP is used as transport). It is needed for hardware capable of
> + * one-step P2P that does not already modify the correction field of Pdelay_Req
> + * event messages on ingress.
> + */

Does this really belong in the common PTP header?

Seems more like a driver/hardware specific workaround to me.

Thanks,
Richard

2022-11-23 07:32:44

by Arun Ramadoss

[permalink] [raw]
Subject: Re: [RFC Patch net-next v2 1/8] net: ptp: add helper for one-step P2P clocks

Hi Richard,
Thanks for the comment.

On Tue, 2022-11-22 at 06:34 -0800, Richard Cochran wrote:
> [Some people who received this message don't often get email from
> [email protected]. Learn why this is important at
> https://aka.ms/LearnAboutSenderIdentification ]
>
> EXTERNAL EMAIL: Do not click links or open attachments unless you
> know the content is safe
>
> On Mon, Nov 21, 2022 at 09:11:43PM +0530, Arun Ramadoss wrote:
> > +/**
> > + * ptp_header_update_correction - Update PTP header's correction
> > field
> > + * @skb: packet buffer
> > + * @type: type of the packet (see ptp_classify_raw())
> > + * @hdr: ptp header
> > + * @correction: new correction value
> > + *
> > + * This updates the correction field of a PTP header and updates
> > the UDP
> > + * checksum (if UDP is used as transport). It is needed for
> > hardware capable of
> > + * one-step P2P that does not already modify the correction field
> > of Pdelay_Req
> > + * event messages on ingress.
> > + */
>
> Does this really belong in the common PTP header?
>
> Seems more like a driver/hardware specific workaround to me.

This patch series is extension of PTP support for KSZ9563 patch series
submitted two years back which is not mainlined.
In that patch review feedback, it was suggested to make this function
generic and so it was moved from ksz_common.h to ptp_classify.h

Link:
https://lore.kernel.org/netdev/20201022113243.4shddtywgvpcqq6c@skbuf/


https://lore.kernel.org/netdev/[email protected]/

>
> Thanks,
> Richard

2022-11-24 15:53:07

by Richard Cochran

[permalink] [raw]
Subject: Re: [RFC Patch net-next v2 1/8] net: ptp: add helper for one-step P2P clocks

On Wed, Nov 23, 2022 at 07:10:58AM +0000, [email protected] wrote:
> This patch series is extension of PTP support for KSZ9563 patch series
> submitted two years back which is not mainlined.
> In that patch review feedback, it was suggested to make this function
> generic and so it was moved from ksz_common.h to ptp_classify.h
>
> Link:
> https://lore.kernel.org/netdev/20201022113243.4shddtywgvpcqq6c@skbuf/
>
>
> https://lore.kernel.org/netdev/[email protected]/

okay

Thanks,
Richard