lists.openwall.net   lists  /  announce  owl-users  owl-dev  john-users  john-dev  passwdqc-users  yescrypt  popa3d-users  /  oss-security  kernel-hardening  musl  sabotage  tlsify  passwords  /  crypt-dev  xvendor  /  Bugtraq  Full-Disclosure  linux-kernel  linux-netdev  linux-ext4  linux-hardening  linux-cve-announce  PHC 
Open Source and information security mailing list archives
 
Hash Suite: Windows password security audit tool. GUI, reports in PDF.
[<prev] [next>] [<thread-prev] [thread-next>] [day] [month] [year] [list]
Date:   Thu, 12 Jul 2018 15:05:06 -0400
From:   Bryan Whitehead <Bryan.Whitehead@...rochip.com>
To:     <davem@...emloft.net>
CC:     <netdev@...r.kernel.org>, <UNGLinuxDriver@...rochip.com>,
        <richardcochran@...il.com>
Subject: [PATCH v2 net-next 9/9] lan743x: Add PTP support

PTP support includes:
    Ingress, and egress timestamping.
    PTP clock support
    Pulse per second output on GPIO

Signed-off-by: Bryan Whitehead <Bryan.Whitehead@...rochip.com>
---
 drivers/net/ethernet/microchip/Makefile          |    2 +-
 drivers/net/ethernet/microchip/lan743x_ethtool.c |   28 +
 drivers/net/ethernet/microchip/lan743x_main.c    |   81 +-
 drivers/net/ethernet/microchip/lan743x_main.h    |   96 +-
 drivers/net/ethernet/microchip/lan743x_ptp.c     | 1194 ++++++++++++++++++++++
 drivers/net/ethernet/microchip/lan743x_ptp.h     |   78 ++
 6 files changed, 1474 insertions(+), 5 deletions(-)
 create mode 100644 drivers/net/ethernet/microchip/lan743x_ptp.c
 create mode 100644 drivers/net/ethernet/microchip/lan743x_ptp.h

diff --git a/drivers/net/ethernet/microchip/Makefile b/drivers/net/ethernet/microchip/Makefile
index 43f47cb..538926d 100644
--- a/drivers/net/ethernet/microchip/Makefile
+++ b/drivers/net/ethernet/microchip/Makefile
@@ -6,4 +6,4 @@ obj-$(CONFIG_ENC28J60) += enc28j60.o
 obj-$(CONFIG_ENCX24J600) += encx24j600.o encx24j600-regmap.o
 obj-$(CONFIG_LAN743X) += lan743x.o
 
-lan743x-objs := lan743x_main.o lan743x_ethtool.o
+lan743x-objs := lan743x_main.o lan743x_ethtool.o lan743x_ptp.o
diff --git a/drivers/net/ethernet/microchip/lan743x_ethtool.c b/drivers/net/ethernet/microchip/lan743x_ethtool.c
index 33d6c2d..8800716 100644
--- a/drivers/net/ethernet/microchip/lan743x_ethtool.c
+++ b/drivers/net/ethernet/microchip/lan743x_ethtool.c
@@ -4,6 +4,7 @@
 #include <linux/netdevice.h>
 #include "lan743x_main.h"
 #include "lan743x_ethtool.h"
+#include <linux/net_tstamp.h>
 #include <linux/pci.h>
 #include <linux/phy.h>
 
@@ -542,6 +543,32 @@ static int lan743x_ethtool_set_rxfh(struct net_device *netdev,
 	return 0;
 }
 
+static int lan743x_ethtool_get_ts_info(struct net_device *netdev,
+				       struct ethtool_ts_info *ts_info)
+{
+	struct lan743x_adapter *adapter = netdev_priv(netdev);
+
+	ts_info->so_timestamping = SOF_TIMESTAMPING_TX_SOFTWARE |
+				   SOF_TIMESTAMPING_RX_SOFTWARE |
+				   SOF_TIMESTAMPING_SOFTWARE |
+				   SOF_TIMESTAMPING_TX_HARDWARE |
+				   SOF_TIMESTAMPING_RX_HARDWARE |
+				   SOF_TIMESTAMPING_RAW_HARDWARE;
+#ifdef CONFIG_PTP_1588_CLOCK
+	if (adapter->ptp.ptp_clock)
+		ts_info->phc_index = ptp_clock_index(adapter->ptp.ptp_clock);
+	else
+		ts_info->phc_index = -1;
+#else
+	ts_info->phc_index = -1;
+#endif
+	ts_info->tx_types = BIT(HWTSTAMP_TX_OFF) |
+			    BIT(HWTSTAMP_TX_ON);
+	ts_info->rx_filters = BIT(HWTSTAMP_FILTER_NONE) |
+			      BIT(HWTSTAMP_FILTER_ALL);
+	return 0;
+}
+
 static int lan743x_ethtool_get_eee(struct net_device *netdev,
 				   struct ethtool_eee *eee)
 {
@@ -690,6 +717,7 @@ const struct ethtool_ops lan743x_ethtool_ops = {
 	.get_rxfh_indir_size = lan743x_ethtool_get_rxfh_indir_size,
 	.get_rxfh = lan743x_ethtool_get_rxfh,
 	.set_rxfh = lan743x_ethtool_set_rxfh,
+	.get_ts_info = lan743x_ethtool_get_ts_info,
 	.get_eee = lan743x_ethtool_get_eee,
 	.set_eee = lan743x_ethtool_set_eee,
 	.get_link_ksettings = phy_ethtool_get_link_ksettings,
diff --git a/drivers/net/ethernet/microchip/lan743x_main.c b/drivers/net/ethernet/microchip/lan743x_main.c
index 953b581..ca9ae49 100644
--- a/drivers/net/ethernet/microchip/lan743x_main.c
+++ b/drivers/net/ethernet/microchip/lan743x_main.c
@@ -267,6 +267,10 @@ static void lan743x_intr_shared_isr(void *context, u32 int_sts, u32 flags)
 			lan743x_intr_software_isr(adapter);
 			int_sts &= ~INT_BIT_SW_GP_;
 		}
+		if (int_sts & INT_BIT_1588_) {
+			lan743x_ptp_isr(adapter);
+			int_sts &= ~INT_BIT_1588_;
+		}
 	}
 	if (int_sts)
 		lan743x_csr_write(adapter, INT_EN_CLR, int_sts);
@@ -976,6 +980,7 @@ static void lan743x_phy_link_status_change(struct net_device *netdev)
 					       ksettings.base.duplex,
 					       local_advertisement,
 					       remote_advertisement);
+		lan743x_ptp_update_latency(adapter, ksettings.base.speed);
 	}
 }
 
@@ -1256,11 +1261,29 @@ static void lan743x_tx_release_desc(struct lan743x_tx *tx,
 		buffer_info->dma_ptr = 0;
 		buffer_info->buffer_length = 0;
 	}
-	if (buffer_info->skb) {
+	if (!buffer_info->skb)
+		goto clear_active;
+
+	if (!(buffer_info->flags &
+		TX_BUFFER_INFO_FLAG_TIMESTAMP_REQUESTED)) {
 		dev_kfree_skb(buffer_info->skb);
-		buffer_info->skb = NULL;
+		goto clear_skb;
 	}
 
+	if (cleanup) {
+		lan743x_ptp_unrequest_tx_timestamp(tx->adapter);
+		dev_kfree_skb(buffer_info->skb);
+	} else {
+		lan743x_ptp_tx_timestamp_skb(tx->adapter,
+					     buffer_info->skb,
+					     (buffer_info->flags &
+					     TX_BUFFER_INFO_FLAG_IGNORE_SYNC)
+					     != 0);
+	}
+
+clear_skb:
+	buffer_info->skb = NULL;
+
 clear_active:
 	buffer_info->flags &= ~TX_BUFFER_INFO_FLAG_ACTIVE;
 
@@ -1321,10 +1344,25 @@ static int lan743x_tx_get_avail_desc(struct lan743x_tx *tx)
 		return last_head - last_tail - 1;
 }
 
+void lan743x_tx_set_timestamping_mode(struct lan743x_tx *tx,
+				      bool enable_timestamping,
+				      bool enable_onestep_sync)
+{
+	if (enable_timestamping)
+		tx->ts_flags |= TX_TS_FLAG_TIMESTAMPING_ENABLED;
+	else
+		tx->ts_flags &= ~TX_TS_FLAG_TIMESTAMPING_ENABLED;
+	if (enable_onestep_sync)
+		tx->ts_flags |= TX_TS_FLAG_ONE_STEP_SYNC;
+	else
+		tx->ts_flags &= ~TX_TS_FLAG_ONE_STEP_SYNC;
+}
+
 static int lan743x_tx_frame_start(struct lan743x_tx *tx,
 				  unsigned char *first_buffer,
 				  unsigned int first_buffer_length,
 				  unsigned int frame_length,
+				  bool time_stamp,
 				  bool check_sum)
 {
 	/* called only from within lan743x_tx_xmit_frame.
@@ -1362,6 +1400,8 @@ static int lan743x_tx_frame_start(struct lan743x_tx *tx,
 		TX_DESC_DATA0_DTYPE_DATA_ |
 		TX_DESC_DATA0_FS_ |
 		TX_DESC_DATA0_FCS_;
+	if (time_stamp)
+		tx->frame_data0 |= TX_DESC_DATA0_TSE_;
 
 	if (check_sum)
 		tx->frame_data0 |= TX_DESC_DATA0_ICE_ |
@@ -1475,6 +1515,7 @@ static int lan743x_tx_frame_add_fragment(struct lan743x_tx *tx,
 
 static void lan743x_tx_frame_end(struct lan743x_tx *tx,
 				 struct sk_buff *skb,
+				 bool time_stamp,
 				 bool ignore_sync)
 {
 	/* called only from within lan743x_tx_xmit_frame
@@ -1492,6 +1533,8 @@ static void lan743x_tx_frame_end(struct lan743x_tx *tx,
 	tx_descriptor = &tx->ring_cpu_ptr[tx->frame_tail];
 	buffer_info = &tx->buffer_info[tx->frame_tail];
 	buffer_info->skb = skb;
+	if (time_stamp)
+		buffer_info->flags |= TX_BUFFER_INFO_FLAG_TIMESTAMP_REQUESTED;
 	if (ignore_sync)
 		buffer_info->flags |= TX_BUFFER_INFO_FLAG_IGNORE_SYNC;
 
@@ -1520,6 +1563,7 @@ static netdev_tx_t lan743x_tx_xmit_frame(struct lan743x_tx *tx,
 	unsigned int frame_length = 0;
 	unsigned int head_length = 0;
 	unsigned long irq_flags = 0;
+	bool do_timestamp = false;
 	bool ignore_sync = false;
 	int nr_frags = 0;
 	bool gso = false;
@@ -1541,6 +1585,16 @@ static netdev_tx_t lan743x_tx_xmit_frame(struct lan743x_tx *tx,
 	}
 
 	/* space available, transmit skb  */
+	if (skb_shinfo(skb)->tx_flags & SKBTX_HW_TSTAMP) {
+		if (tx->ts_flags & TX_TS_FLAG_TIMESTAMPING_ENABLED) {
+			if (lan743x_ptp_request_tx_timestamp(tx->adapter)) {
+				skb_shinfo(skb)->tx_flags |= SKBTX_IN_PROGRESS;
+				do_timestamp = true;
+				if (tx->ts_flags & TX_TS_FLAG_ONE_STEP_SYNC)
+					ignore_sync = true;
+			}
+		}
+	}
 	head_length = skb_headlen(skb);
 	frame_length = skb_pagelen(skb);
 	nr_frags = skb_shinfo(skb)->nr_frags;
@@ -1554,6 +1608,7 @@ static netdev_tx_t lan743x_tx_xmit_frame(struct lan743x_tx *tx,
 	if (lan743x_tx_frame_start(tx,
 				   skb->data, head_length,
 				   start_frame_length,
+				   do_timestamp,
 				   skb->ip_summed == CHECKSUM_PARTIAL)) {
 		dev_kfree_skb(skb);
 		goto unlock;
@@ -1581,7 +1636,7 @@ static netdev_tx_t lan743x_tx_xmit_frame(struct lan743x_tx *tx,
 	}
 
 finish:
-	lan743x_tx_frame_end(tx, skb, ignore_sync);
+	lan743x_tx_frame_end(tx, skb, do_timestamp, ignore_sync);
 
 unlock:
 	spin_unlock_irqrestore(&tx->ring_lock, irq_flags);
@@ -2410,6 +2465,8 @@ static int lan743x_netdev_close(struct net_device *netdev)
 	for (index = 0; index < LAN743X_USED_RX_CHANNELS; index++)
 		lan743x_rx_close(&adapter->rx[index]);
 
+	lan743x_ptp_close(adapter);
+
 	lan743x_phy_close(adapter);
 
 	lan743x_mac_close(adapter);
@@ -2437,6 +2494,10 @@ static int lan743x_netdev_open(struct net_device *netdev)
 	if (ret)
 		goto close_mac;
 
+	ret = lan743x_ptp_open(adapter);
+	if (ret)
+		goto close_phy;
+
 	lan743x_rfe_open(adapter);
 
 	for (index = 0; index < LAN743X_USED_RX_CHANNELS; index++) {
@@ -2456,6 +2517,9 @@ static int lan743x_netdev_open(struct net_device *netdev)
 		if (adapter->rx[index].ring_cpu_ptr)
 			lan743x_rx_close(&adapter->rx[index]);
 	}
+	lan743x_ptp_close(adapter);
+
+close_phy:
 	lan743x_phy_close(adapter);
 
 close_mac:
@@ -2483,6 +2547,8 @@ static int lan743x_netdev_ioctl(struct net_device *netdev,
 {
 	if (!netif_running(netdev))
 		return -EINVAL;
+	if (cmd == SIOCSHWTSTAMP)
+		return lan743x_ptp_ioctl(netdev, ifr, cmd);
 	return phy_mii_ioctl(netdev->phydev, ifr, cmd);
 }
 
@@ -2607,6 +2673,11 @@ static int lan743x_hardware_init(struct lan743x_adapter *adapter,
 	adapter->intr.irq = adapter->pdev->irq;
 	lan743x_csr_write(adapter, INT_EN_CLR, 0xFFFFFFFF);
 	mutex_init(&adapter->dp_lock);
+
+	ret = lan743x_gpio_init(adapter);
+	if (ret)
+		return ret;
+
 	ret = lan743x_mac_init(adapter);
 	if (ret)
 		return ret;
@@ -2615,6 +2686,10 @@ static int lan743x_hardware_init(struct lan743x_adapter *adapter,
 	if (ret)
 		return ret;
 
+	ret = lan743x_ptp_init(adapter);
+	if (ret)
+		return ret;
+
 	lan743x_rfe_update_mac_address(adapter);
 
 	ret = lan743x_dmac_init(adapter);
diff --git a/drivers/net/ethernet/microchip/lan743x_main.h b/drivers/net/ethernet/microchip/lan743x_main.h
index 4fa7a5e..578a618 100644
--- a/drivers/net/ethernet/microchip/lan743x_main.h
+++ b/drivers/net/ethernet/microchip/lan743x_main.h
@@ -4,12 +4,17 @@
 #ifndef _LAN743X_H
 #define _LAN743X_H
 
+#include "lan743x_ptp.h"
+
 #define DRIVER_AUTHOR   "Bryan Whitehead <Bryan.Whitehead@...rochip.com>"
 #define DRIVER_DESC "LAN743x PCIe Gigabit Ethernet Driver"
 #define DRIVER_NAME "lan743x"
 
 /* Register Definitions */
 #define ID_REV				(0x00)
+#define ID_REV_ID_MASK_			(0xFFFF0000)
+#define ID_REV_ID_LAN7430_		(0x74300000)
+#define ID_REV_ID_LAN7431_		(0x74310000)
 #define ID_REV_IS_VALID_CHIP_ID_(id_rev)	\
 	(((id_rev) & 0xFFF00000) == 0x74300000)
 #define ID_REV_CHIP_REV_MASK_		(0x0000FFFF)
@@ -62,6 +67,21 @@
 
 #define E2P_DATA			(0x044)
 
+#define GPIO_CFG0			(0x050)
+#define GPIO_CFG0_GPIO_DIR_BIT_(bit)	BIT(16 + (bit))
+#define GPIO_CFG0_GPIO_DATA_BIT_(bit)	BIT(0 + (bit))
+
+#define GPIO_CFG1			(0x054)
+#define GPIO_CFG1_GPIOEN_BIT_(bit)	BIT(16 + (bit))
+#define GPIO_CFG1_GPIOBUF_BIT_(bit)	BIT(0 + (bit))
+
+#define GPIO_CFG2			(0x058)
+#define GPIO_CFG2_1588_POL_BIT_(bit)	BIT(0 + (bit))
+
+#define GPIO_CFG3			(0x05C)
+#define GPIO_CFG3_1588_CH_SEL_BIT_(bit)	BIT(16 + (bit))
+#define GPIO_CFG3_1588_OE_BIT_(bit)	BIT(0 + (bit))
+
 #define FCT_RX_CTL			(0xAC)
 #define FCT_RX_CTL_EN_(channel)		BIT(28 + (channel))
 #define FCT_RX_CTL_DIS_(channel)	BIT(24 + (channel))
@@ -193,7 +213,8 @@
 #define INT_BIT_DMA_TX_(channel)	BIT(16 + (channel))
 #define INT_BIT_ALL_TX_			(0x000F0000)
 #define INT_BIT_SW_GP_			BIT(9)
-#define INT_BIT_ALL_OTHER_		(0x00000280)
+#define INT_BIT_1588_			BIT(7)
+#define INT_BIT_ALL_OTHER_		(INT_BIT_SW_GP_ | INT_BIT_1588_)
 #define INT_BIT_MAS_			BIT(0)
 
 #define INT_SET				(0x784)
@@ -234,6 +255,66 @@
 #define INT_MOD_CFG6			(0x7D8)
 #define INT_MOD_CFG7			(0x7DC)
 
+#define PTP_CMD_CTL					(0x0A00)
+#define PTP_CMD_CTL_PTP_CLK_STP_NSEC_			BIT(6)
+#define PTP_CMD_CTL_PTP_CLOCK_STEP_SEC_			BIT(5)
+#define PTP_CMD_CTL_PTP_CLOCK_LOAD_			BIT(4)
+#define PTP_CMD_CTL_PTP_CLOCK_READ_			BIT(3)
+#define PTP_CMD_CTL_PTP_ENABLE_				BIT(2)
+#define PTP_CMD_CTL_PTP_DISABLE_			BIT(1)
+#define PTP_CMD_CTL_PTP_RESET_				BIT(0)
+#define PTP_GENERAL_CONFIG				(0x0A04)
+#define PTP_GENERAL_CONFIG_CLOCK_EVENT_X_MASK_(channel) \
+	(0x7 << (1 + ((channel) << 2)))
+#define PTP_GENERAL_CONFIG_CLOCK_EVENT_100US_	(2)
+#define PTP_GENERAL_CONFIG_CLOCK_EVENT_X_SET_(channel, value) \
+	(((value) & 0x7) << (1 + ((channel) << 2)))
+#define PTP_GENERAL_CONFIG_RELOAD_ADD_X_(channel)	(BIT((channel) << 2))
+
+#define PTP_INT_STS				(0x0A08)
+#define PTP_INT_EN_SET				(0x0A0C)
+#define PTP_INT_EN_CLR				(0x0A10)
+#define PTP_INT_BIT_TX_SWTS_ERR_		BIT(13)
+#define PTP_INT_BIT_TX_TS_			BIT(12)
+#define PTP_INT_BIT_TIMER_B_			BIT(1)
+#define PTP_INT_BIT_TIMER_A_			BIT(0)
+
+#define PTP_CLOCK_SEC				(0x0A14)
+#define PTP_CLOCK_NS				(0x0A18)
+#define PTP_CLOCK_SUBNS				(0x0A1C)
+#define PTP_CLOCK_RATE_ADJ			(0x0A20)
+#define PTP_CLOCK_RATE_ADJ_DIR_			BIT(31)
+#define PTP_CLOCK_STEP_ADJ			(0x0A2C)
+#define PTP_CLOCK_STEP_ADJ_DIR_			BIT(31)
+#define PTP_CLOCK_STEP_ADJ_VALUE_MASK_		(0x3FFFFFFF)
+#define PTP_CLOCK_TARGET_SEC_X(channel)		(0x0A30 + ((channel) << 4))
+#define PTP_CLOCK_TARGET_NS_X(channel)		(0x0A34 + ((channel) << 4))
+#define PTP_CLOCK_TARGET_RELOAD_SEC_X(channel)	(0x0A38 + ((channel) << 4))
+#define PTP_CLOCK_TARGET_RELOAD_NS_X(channel)	(0x0A3C + ((channel) << 4))
+#define PTP_LATENCY				(0x0A5C)
+#define PTP_LATENCY_TX_SET_(tx_latency)		(((u32)(tx_latency)) << 16)
+#define PTP_LATENCY_RX_SET_(rx_latency)		\
+	(((u32)(rx_latency)) & 0x0000FFFF)
+#define PTP_CAP_INFO				(0x0A60)
+#define PTP_CAP_INFO_TX_TS_CNT_GET_(reg_val)	((reg_val & 0x00000070) >> 4)
+
+#define PTP_TX_MOD				(0x0AA4)
+#define PTP_TX_MOD_TX_PTP_SYNC_TS_INSERT_	(0x10000000)
+
+#define PTP_TX_MOD2				(0x0AA8)
+#define PTP_TX_MOD2_TX_PTP_CLR_UDPV4_CHKSUM_	(0x00000001)
+
+#define PTP_TX_EGRESS_SEC			(0x0AAC)
+#define PTP_TX_EGRESS_NS			(0x0AB0)
+#define PTP_TX_EGRESS_NS_CAPTURE_CAUSE_MASK_	(0xC0000000)
+#define PTP_TX_EGRESS_NS_CAPTURE_CAUSE_AUTO_	(0x00000000)
+#define PTP_TX_EGRESS_NS_CAPTURE_CAUSE_SW_	(0x40000000)
+#define PTP_TX_EGRESS_NS_TS_NS_MASK_		(0x3FFFFFFF)
+
+#define PTP_TX_MSG_HEADER			(0x0AB4)
+#define PTP_TX_MSG_HEADER_MSG_TYPE_		(0x000F0000)
+#define PTP_TX_MSG_HEADER_MSG_TYPE_SYNC_	(0x00000000)
+
 #define DMAC_CFG				(0xC00)
 #define DMAC_CFG_COAL_EN_			BIT(16)
 #define DMAC_CFG_CH_ARB_SEL_RX_HIGH_		(0x00000000)
@@ -542,8 +623,12 @@ struct lan743x_tx_buffer_info;
 
 #define TX_FRAME_FLAG_IN_PROGRESS	BIT(0)
 
+#define TX_TS_FLAG_TIMESTAMPING_ENABLED	BIT(0)
+#define TX_TS_FLAG_ONE_STEP_SYNC	BIT(1)
+
 struct lan743x_tx {
 	struct lan743x_adapter *adapter;
+	u32	ts_flags;
 	u32	vector_flags;
 	int	channel_number;
 
@@ -570,6 +655,10 @@ struct lan743x_tx {
 	struct sk_buff *overflow_skb;
 };
 
+void lan743x_tx_set_timestamping_mode(struct lan743x_tx *tx,
+				      bool enable_timestamping,
+				      bool enable_onestep_sync);
+
 /* RX */
 struct lan743x_rx_descriptor;
 struct lan743x_rx_buffer_info;
@@ -610,6 +699,9 @@ struct lan743x_adapter {
 	/* lock, used to prevent concurrent access to data port */
 	struct mutex		dp_lock;
 
+	struct lan743x_gpio	gpio;
+	struct lan743x_ptp	ptp;
+
 	u8			mac_address[ETH_ALEN];
 
 	struct lan743x_phy      phy;
@@ -660,6 +752,7 @@ struct lan743x_adapter {
 #define TX_DESC_DATA0_IPE_			(0x00200000)
 #define TX_DESC_DATA0_TPE_			(0x00100000)
 #define TX_DESC_DATA0_FCS_			(0x00020000)
+#define TX_DESC_DATA0_TSE_			(0x00010000)
 #define TX_DESC_DATA0_BUF_LENGTH_MASK_		(0x0000FFFF)
 #define TX_DESC_DATA0_EXT_LSO_			(0x00200000)
 #define TX_DESC_DATA0_EXT_PAY_LENGTH_MASK_	(0x000FFFFF)
@@ -673,6 +766,7 @@ struct lan743x_tx_descriptor {
 } __aligned(DEFAULT_DMA_DESCRIPTOR_SPACING);
 
 #define TX_BUFFER_INFO_FLAG_ACTIVE		BIT(0)
+#define TX_BUFFER_INFO_FLAG_TIMESTAMP_REQUESTED	BIT(1)
 #define TX_BUFFER_INFO_FLAG_IGNORE_SYNC		BIT(2)
 #define TX_BUFFER_INFO_FLAG_SKB_FRAGMENT	BIT(3)
 struct lan743x_tx_buffer_info {
diff --git a/drivers/net/ethernet/microchip/lan743x_ptp.c b/drivers/net/ethernet/microchip/lan743x_ptp.c
new file mode 100644
index 0000000..f14565b
--- /dev/null
+++ b/drivers/net/ethernet/microchip/lan743x_ptp.c
@@ -0,0 +1,1194 @@
+/* SPDX-License-Identifier: GPL-2.0+ */
+/* Copyright (C) 2018 Microchip Technology Inc. */
+
+#include <linux/netdevice.h>
+#include "lan743x_main.h"
+
+#include <linux/module.h>
+#include <linux/pci.h>
+#include <linux/netdevice.h>
+#include <linux/net_tstamp.h>
+
+#include "lan743x_ptp.h"
+
+/* GPIO */
+#define LAN743X_NUMBER_OF_GPIO          (12)
+
+int lan743x_gpio_init(struct lan743x_adapter *adapter)
+{
+	struct lan743x_gpio *gpio = &adapter->gpio;
+
+	spin_lock_init(&gpio->gpio_lock);
+
+	gpio->gpio_cfg0 = 0; /* set all direction to input, data = 0 */
+	gpio->gpio_cfg1 = 0x0FFF0000;/* disable all gpio, set to open drain */
+	gpio->gpio_cfg2 = 0;/* set all to 1588 low polarity level */
+	gpio->gpio_cfg3 = 0;/* disable all 1588 output */
+	lan743x_csr_write(adapter, GPIO_CFG0, gpio->gpio_cfg0);
+	lan743x_csr_write(adapter, GPIO_CFG1, gpio->gpio_cfg1);
+	lan743x_csr_write(adapter, GPIO_CFG2, gpio->gpio_cfg2);
+	lan743x_csr_write(adapter, GPIO_CFG3, gpio->gpio_cfg3);
+
+	return 0;
+}
+
+#ifdef CONFIG_PTP_1588_CLOCK
+static int lan743x_gpio_reserve_ptp_output(struct lan743x_adapter *adapter,
+					   int bit, int ptp_channel)
+{
+	struct lan743x_gpio *gpio = &adapter->gpio;
+	unsigned long irq_flags = 0;
+	int bit_mask = BIT(bit);
+	int ret = -EBUSY;
+
+	spin_lock_irqsave(&gpio->gpio_lock, irq_flags);
+
+	if (!(gpio->used_bits & bit_mask)) {
+		gpio->used_bits |= bit_mask;
+		gpio->output_bits |= bit_mask;
+		gpio->ptp_bits |= bit_mask;
+
+		/* set as output, and zero initial value */
+		gpio->gpio_cfg0 |= GPIO_CFG0_GPIO_DIR_BIT_(bit);
+		gpio->gpio_cfg0 &= ~GPIO_CFG0_GPIO_DATA_BIT_(bit);
+		lan743x_csr_write(adapter, GPIO_CFG0, gpio->gpio_cfg0);
+
+		/* enable gpio , and set buffer type to push pull */
+		gpio->gpio_cfg1 &= ~GPIO_CFG1_GPIOEN_BIT_(bit);
+		gpio->gpio_cfg1 |= GPIO_CFG1_GPIOBUF_BIT_(bit);
+		lan743x_csr_write(adapter, GPIO_CFG1, gpio->gpio_cfg1);
+
+		/* set 1588 polarity to high */
+		gpio->gpio_cfg2 |= GPIO_CFG2_1588_POL_BIT_(bit);
+		lan743x_csr_write(adapter, GPIO_CFG2, gpio->gpio_cfg2);
+
+		if (!ptp_channel) {
+			/* use channel A */
+			gpio->gpio_cfg3 &= ~GPIO_CFG3_1588_CH_SEL_BIT_(bit);
+		} else {
+			/* use channel B */
+			gpio->gpio_cfg3 |= GPIO_CFG3_1588_CH_SEL_BIT_(bit);
+		}
+		gpio->gpio_cfg3 |= GPIO_CFG3_1588_OE_BIT_(bit);
+		lan743x_csr_write(adapter, GPIO_CFG3, gpio->gpio_cfg3);
+
+		ret = bit;
+	}
+	spin_unlock_irqrestore(&gpio->gpio_lock, irq_flags);
+	return ret;
+}
+#endif /* CONFIG_PTP_1588_CLOCK */
+
+#ifdef CONFIG_PTP_1588_CLOCK
+static void lan743x_gpio_release(struct lan743x_adapter *adapter, int bit)
+{
+	struct lan743x_gpio *gpio = &adapter->gpio;
+	unsigned long irq_flags = 0;
+	int bit_mask = BIT(bit);
+
+	spin_lock_irqsave(&gpio->gpio_lock, irq_flags);
+	if (gpio->used_bits & bit_mask) {
+		gpio->used_bits &= ~bit_mask;
+		if (gpio->output_bits & bit_mask) {
+			gpio->output_bits &= ~bit_mask;
+
+			if (gpio->ptp_bits & bit_mask) {
+				gpio->ptp_bits &= ~bit_mask;
+				/* disable ptp output */
+				gpio->gpio_cfg3 &= ~GPIO_CFG3_1588_OE_BIT_(bit);
+				lan743x_csr_write(adapter, GPIO_CFG3,
+						  gpio->gpio_cfg3);
+			}
+			/* release gpio output */
+
+			/* disable gpio */
+			gpio->gpio_cfg1 |= GPIO_CFG1_GPIOEN_BIT_(bit);
+			gpio->gpio_cfg1 &= ~GPIO_CFG1_GPIOBUF_BIT_(bit);
+			lan743x_csr_write(adapter, GPIO_CFG1, gpio->gpio_cfg1);
+
+			/* reset back to input */
+			gpio->gpio_cfg0 &= ~GPIO_CFG0_GPIO_DIR_BIT_(bit);
+			gpio->gpio_cfg0 &= ~GPIO_CFG0_GPIO_DATA_BIT_(bit);
+			lan743x_csr_write(adapter, GPIO_CFG0, gpio->gpio_cfg0);
+		}
+	}
+	spin_unlock_irqrestore(&gpio->gpio_lock, irq_flags);
+}
+#endif /* CONFIG_PTP_1588_CLOCK */
+
+/* PTP */
+#define LAN743X_PTP_MAX_FREQ_ADJ_IN_PPB (31249999)
+
+#ifdef CONFIG_PTP_1588_CLOCK
+static int lan743x_ptp_reserve_event_ch(struct lan743x_adapter *adapter);
+static void lan743x_ptp_release_event_ch(struct lan743x_adapter *adapter,
+					 int event_channel);
+#endif
+
+static bool lan743x_ptp_is_enabled(struct lan743x_adapter *adapter);
+static void lan743x_ptp_enable(struct lan743x_adapter *adapter);
+static void lan743x_ptp_disable(struct lan743x_adapter *adapter);
+static void lan743x_ptp_reset(struct lan743x_adapter *adapter);
+
+#ifdef CONFIG_PTP_1588_CLOCK
+static void lan743x_ptp_clock_get(struct lan743x_adapter *adapter,
+				  u32 *seconds, u32 *nano_seconds,
+				  u32 *sub_nano_seconds);
+static int lan743x_ptp_enable_pps(struct lan743x_adapter *adapter);
+static void lan743x_ptp_disable_pps(struct lan743x_adapter *adapter);
+#endif /* CONFIG_PTP_1588_CLOCK */
+
+#ifdef CONFIG_PTP_1588_CLOCK
+static void lan743x_ptp_clock_step(struct lan743x_adapter *adapter,
+				   s64 time_step_ns);
+#endif /* CONFIG_PTP_1588_CLOCK */
+
+static void lan743x_ptp_clock_set(struct lan743x_adapter *adapter,
+				  u32 seconds, u32 nano_seconds,
+				  u32 sub_nano_seconds);
+
+#ifdef CONFIG_PTP_1588_CLOCK
+static int lan743x_ptpci_adjfreq(struct ptp_clock_info *ptpci, s32 delta_ppb)
+{
+	struct lan743x_ptp *ptp = container_of(ptpci, struct lan743x_ptp,
+					       ptp_clock_info);
+	struct lan743x_adapter *adapter = container_of(ptp,
+						       struct lan743x_adapter,
+						       ptp);
+	u32 lan743x_rate_adj = 0;
+	bool positive = true;
+	u32 u32_delta = 0;
+	u64 u64_delta = 0;
+
+	if ((delta_ppb < (-LAN743X_PTP_MAX_FREQ_ADJ_IN_PPB)) ||
+	    delta_ppb > LAN743X_PTP_MAX_FREQ_ADJ_IN_PPB) {
+		return -EINVAL;
+	}
+	if (delta_ppb > 0) {
+		u32_delta = (u32)delta_ppb;
+		positive = true;
+	} else {
+		u32_delta = (u32)(-delta_ppb);
+		positive = false;
+	}
+	u64_delta = (((u64)u32_delta) * 0x800000000ULL);
+	lan743x_rate_adj = (u32)(u64_delta / 1000000000);
+
+	if (positive)
+		lan743x_rate_adj |= PTP_CLOCK_RATE_ADJ_DIR_;
+
+	lan743x_csr_write(adapter, PTP_CLOCK_RATE_ADJ,
+			  lan743x_rate_adj);
+
+	netif_info(adapter, drv, adapter->netdev,
+		   "adjfreq, delta_ppb = %d, lan743x_rate_adj = 0x%08X\n",
+		   delta_ppb, lan743x_rate_adj);
+	return 0;
+}
+#endif /*CONFIG_PTP_1588_CLOCK */
+
+#ifdef CONFIG_PTP_1588_CLOCK
+static int lan743x_ptpci_adjtime(struct ptp_clock_info *ptpci, s64 delta)
+{
+	struct lan743x_ptp *ptp = container_of(ptpci, struct lan743x_ptp,
+					       ptp_clock_info);
+	struct lan743x_adapter *adapter = container_of(ptp,
+						       struct lan743x_adapter,
+						       ptp);
+	bool enable_pps = false;
+
+	if (ptp->pps_event_ch >= 0) {
+		lan743x_ptp_disable_pps(adapter);
+		enable_pps = true;
+	}
+
+	lan743x_ptp_clock_step(adapter, delta);
+	netif_info(adapter, drv, adapter->netdev,
+		   "adjtime, delta = %lld\n", delta);
+
+	if (enable_pps)
+		lan743x_ptp_enable_pps(adapter);
+
+	return 0;
+}
+#endif /*CONFIG_PTP_1588_CLOCK */
+
+#ifdef CONFIG_PTP_1588_CLOCK
+static int lan743x_ptpci_gettime64(struct ptp_clock_info *ptpci,
+				   struct timespec64 *ts)
+{
+	struct lan743x_ptp *ptp = container_of(ptpci, struct lan743x_ptp,
+					       ptp_clock_info);
+	struct lan743x_adapter *adapter = container_of(ptp,
+						       struct lan743x_adapter,
+						       ptp);
+
+	if (ts) {
+		u32 seconds = 0;
+		u32 nano_seconds = 0;
+
+		lan743x_ptp_clock_get(adapter, &seconds, &nano_seconds, NULL);
+		ts->tv_sec = seconds;
+		ts->tv_nsec = nano_seconds;
+		netif_info(adapter, drv, adapter->netdev,
+			   "gettime = %u.%09u\n", seconds, nano_seconds);
+	} else {
+		netif_warn(adapter, drv, adapter->netdev, "ts == NULL\n");
+		return -EINVAL;
+	}
+	return 0;
+}
+#endif /*CONFIG_PTP_1588_CLOCK */
+
+#ifdef CONFIG_PTP_1588_CLOCK
+static int lan743x_ptpci_settime64(struct ptp_clock_info *ptpci,
+				   const struct timespec64 *ts)
+{
+	struct lan743x_ptp *ptp = container_of(ptpci, struct lan743x_ptp,
+					       ptp_clock_info);
+	struct lan743x_adapter *adapter = container_of(ptp,
+						       struct lan743x_adapter,
+						       ptp);
+	bool enable_pps = false;
+
+	if (ptp->pps_event_ch >= 0) {
+		lan743x_ptp_disable_pps(adapter);
+		enable_pps = true;
+	}
+
+	if (ts) {
+		u32 seconds = 0;
+		u32 nano_seconds = 0;
+
+		if (ts->tv_sec > 0xFFFFFFFFLL ||
+		    ts->tv_sec < 0) {
+			netif_warn(adapter, drv, adapter->netdev,
+				   "ts->tv_sec out of range, %lld\n",
+				   ts->tv_sec);
+			return -EINVAL;
+		}
+		if (ts->tv_nsec >= 1000000000L ||
+		    ts->tv_nsec < 0) {
+			netif_warn(adapter, drv, adapter->netdev,
+				   "ts->tv_nsec out of range, %ld\n",
+				   ts->tv_nsec);
+			return -EINVAL;
+		}
+		seconds = ts->tv_sec;
+		nano_seconds = ts->tv_nsec;
+		netif_info(adapter, drv, adapter->netdev,
+			   "settime = %u.%09u\n", seconds, nano_seconds);
+		lan743x_ptp_clock_set(adapter, seconds, nano_seconds, 0);
+	} else {
+		netif_warn(adapter, drv, adapter->netdev, "ts == NULL\n");
+		return -EINVAL;
+	}
+
+	if (enable_pps)
+		lan743x_ptp_enable_pps(adapter);
+
+	return 0;
+}
+#endif /*CONFIG_PTP_1588_CLOCK */
+
+#ifdef CONFIG_PTP_1588_CLOCK
+static int lan743x_ptp_enable_pps(struct lan743x_adapter *adapter)
+{
+	struct lan743x_ptp *ptp = &adapter->ptp;
+	u32 current_seconds = 0;
+	u32 target_seconds = 0;
+	u32 general_config = 0;
+	int result = -ENODEV;
+	int pps_bit = 0;
+
+	if (ptp->pps_event_ch >= 0) {
+		result = 0;
+		goto done;
+	}
+
+	ptp->pps_event_ch = lan743x_ptp_reserve_event_ch(adapter);
+	if (ptp->pps_event_ch < 0) {
+		netif_warn(adapter, drv, adapter->netdev,
+			   "Failed to reserve event channel for PPS\n");
+		goto done;
+	}
+
+	switch(adapter->csr.id_rev & ID_REV_ID_MASK_) {
+	case ID_REV_ID_LAN7430_:
+		pps_bit = 2;/* GPIO 2 is preferred on EVB LAN7430 */
+		break;
+	case ID_REV_ID_LAN7431_:
+		pps_bit = 4;/* GPIO 4 is preferred on EVB LAN7431 */
+		break;
+	}
+
+	ptp->pps_gpio_bit = lan743x_gpio_reserve_ptp_output(adapter, pps_bit,
+							    ptp->pps_event_ch);
+
+	if (ptp->pps_gpio_bit < 0) {
+		netif_warn(adapter, drv, adapter->netdev,
+			   "Failed to reserve gpio 0 for PPS\n");
+		goto done;
+	}
+
+	lan743x_ptp_clock_get(adapter, &current_seconds, NULL, NULL);
+
+	/* set the first target ahead by 2 seconds
+	 *	to make sure its not missed
+	 */
+	target_seconds = current_seconds + 2;
+
+	/* set the new target */
+	lan743x_csr_write(adapter,
+			  PTP_CLOCK_TARGET_SEC_X(ptp->pps_event_ch),
+			  0xFFFF0000);
+	lan743x_csr_write(adapter,
+			  PTP_CLOCK_TARGET_NS_X(ptp->pps_event_ch), 0);
+
+	general_config = lan743x_csr_read(adapter, PTP_GENERAL_CONFIG);
+
+	general_config &= ~(PTP_GENERAL_CONFIG_CLOCK_EVENT_X_MASK_
+			  (ptp->pps_event_ch));
+	general_config |= PTP_GENERAL_CONFIG_CLOCK_EVENT_X_SET_
+			  (ptp->pps_event_ch,
+			   PTP_GENERAL_CONFIG_CLOCK_EVENT_100US_);
+	general_config &= ~PTP_GENERAL_CONFIG_RELOAD_ADD_X_
+			  (ptp->pps_event_ch);
+	lan743x_csr_write(adapter, PTP_GENERAL_CONFIG, general_config);
+
+	/* set the reload to one second steps */
+	lan743x_csr_write(adapter,
+			  PTP_CLOCK_TARGET_RELOAD_SEC_X(ptp->pps_event_ch),
+			  1);
+	lan743x_csr_write(adapter,
+			  PTP_CLOCK_TARGET_RELOAD_NS_X(ptp->pps_event_ch),
+			  0);
+
+	/* set the new target */
+	lan743x_csr_write(adapter,
+			  PTP_CLOCK_TARGET_SEC_X(ptp->pps_event_ch),
+			  target_seconds);
+	lan743x_csr_write(adapter,
+			  PTP_CLOCK_TARGET_NS_X(ptp->pps_event_ch),
+			  0);
+	return 0;
+
+done:
+	if (ptp->pps_gpio_bit >= 0) {
+		lan743x_gpio_release(adapter, ptp->pps_gpio_bit);
+		ptp->pps_gpio_bit = -1;
+	}
+	if (ptp->pps_event_ch >= 0) {
+		lan743x_ptp_release_event_ch(adapter,
+					     ptp->pps_event_ch);
+		ptp->pps_event_ch = -1;
+	}
+	return result;
+}
+#endif /* CONFIG_PTP_1588_CLOCK */
+
+#ifdef CONFIG_PTP_1588_CLOCK
+static void lan743x_ptp_disable_pps(struct lan743x_adapter *adapter)
+{
+	struct lan743x_ptp *ptp = &adapter->ptp;
+
+	if (ptp->pps_gpio_bit >= 0) {
+		lan743x_gpio_release(adapter, ptp->pps_gpio_bit);
+		ptp->pps_gpio_bit = -1;
+	}
+
+	if (ptp->pps_event_ch >= 0) {
+		u32 general_config = 0;
+
+		/* set target to far in the future, effectively disabling it */
+		lan743x_csr_write(adapter,
+				  PTP_CLOCK_TARGET_SEC_X(ptp->pps_event_ch),
+				  0xFFFF0000);
+		lan743x_csr_write(adapter,
+				  PTP_CLOCK_TARGET_NS_X(ptp->pps_event_ch), 0);
+
+		general_config = lan743x_csr_read(adapter, PTP_GENERAL_CONFIG);
+		general_config |= PTP_GENERAL_CONFIG_RELOAD_ADD_X_
+				  (ptp->pps_event_ch);
+		lan743x_csr_write(adapter, PTP_GENERAL_CONFIG, general_config);
+		lan743x_ptp_release_event_ch(adapter, ptp->pps_event_ch);
+		ptp->pps_event_ch = -1;
+	}
+}
+#endif /* CONFIG_PTP_1588_CLOCK */
+
+#ifdef CONFIG_PTP_1588_CLOCK
+static int lan743x_ptpci_enable(struct ptp_clock_info *ptpci,
+				struct ptp_clock_request *request, int on)
+{
+	struct lan743x_ptp *ptp = container_of(ptpci, struct lan743x_ptp,
+					       ptp_clock_info);
+	struct lan743x_adapter *adapter = container_of(ptp,
+						       struct lan743x_adapter,
+						       ptp);
+
+	if (request) {
+		switch (request->type) {
+		case PTP_CLK_REQ_EXTTS:
+			return -EINVAL;
+		case PTP_CLK_REQ_PEROUT:
+			return -EINVAL;
+		case PTP_CLK_REQ_PPS:
+			if (on) {
+				if (lan743x_ptp_enable_pps(adapter) >= 0)
+					netif_info(adapter, drv,
+						   adapter->netdev,
+						   "PPS is ON\n");
+				else
+					netif_warn(adapter, drv,
+						   adapter->netdev,
+						   "Error starting PPS\n");
+			} else {
+				lan743x_ptp_disable_pps(adapter);
+				netif_info(adapter, drv, adapter->netdev,
+					   "PPS is OFF\n");
+			}
+			break;
+		default:
+			netif_err(adapter, drv, adapter->netdev,
+				  "request->type == %d, Unknown\n",
+				  request->type);
+			break;
+		}
+	} else {
+		netif_err(adapter, drv, adapter->netdev, "request == NULL\n");
+	}
+	return 0;
+}
+#endif /* CONFIG_PTP_1588_CLOCK */
+
+void lan743x_ptp_isr(void *context)
+{
+	struct lan743x_adapter *adapter = (struct lan743x_adapter *)context;
+	struct lan743x_ptp *ptp = NULL;
+	int enable_flag = 1;
+	u32 ptp_int_sts = 0;
+
+	ptp = &adapter->ptp;
+
+	lan743x_csr_write(adapter, INT_EN_CLR, INT_BIT_1588_);
+
+	ptp_int_sts = lan743x_csr_read(adapter, PTP_INT_STS);
+	ptp_int_sts &= lan743x_csr_read(adapter, PTP_INT_EN_SET);
+
+	if (ptp_int_sts & PTP_INT_BIT_TX_TS_) {
+		tasklet_schedule(&ptp->ptp_isr_bottom_half);
+		enable_flag = 0;/* tasklet will re-enable later */
+	}
+	if (ptp_int_sts & PTP_INT_BIT_TX_SWTS_ERR_) {
+		netif_err(adapter, drv, adapter->netdev,
+			  "PTP TX Software Timestamp Error\n");
+		/* clear int status bit */
+		lan743x_csr_write(adapter, PTP_INT_STS,
+				  PTP_INT_BIT_TX_SWTS_ERR_);
+	}
+	if (ptp_int_sts & PTP_INT_BIT_TIMER_B_) {
+		netif_info(adapter, drv, adapter->netdev,
+			   "PTP TIMER B Interrupt\n");
+		/* clear int status bit */
+		lan743x_csr_write(adapter, PTP_INT_STS,
+				  PTP_INT_BIT_TIMER_B_);
+	}
+	if (ptp_int_sts & PTP_INT_BIT_TIMER_A_) {
+		netif_info(adapter, drv, adapter->netdev,
+			   "PTP TIMER A Interrupt\n");
+		/* clear int status bit */
+		lan743x_csr_write(adapter, PTP_INT_STS,
+				  PTP_INT_BIT_TIMER_A_);
+	}
+
+	if (enable_flag) {
+		/* re-enable isr */
+		lan743x_csr_write(adapter, INT_EN_SET, INT_BIT_1588_);
+	}
+}
+
+static void lan743x_ptp_tx_ts_complete(struct lan743x_adapter *adapter)
+{
+	struct lan743x_ptp *ptp = &adapter->ptp;
+	int i;
+	int c;
+
+	spin_lock_bh(&ptp->tx_ts_lock);
+	c = ptp->tx_ts_skb_queue_size;
+
+	if (c > ptp->tx_ts_queue_size)
+		c = ptp->tx_ts_queue_size;
+	if (c <= 0)
+		goto done;
+
+	for (i = 0; i < c; i++) {
+		bool ignore_sync = ((ptp->tx_ts_ignore_sync_queue &
+				    BIT(i)) != 0);
+		struct sk_buff *skb = ptp->tx_ts_skb_queue[i];
+		u32 nseconds = ptp->tx_ts_nseconds_queue[i];
+		u32 seconds = ptp->tx_ts_seconds_queue[i];
+		u32 header = ptp->tx_ts_header_queue[i];
+		struct skb_shared_hwtstamps tstamps;
+
+		memset(&tstamps, 0, sizeof(tstamps));
+		tstamps.hwtstamp = ktime_set(seconds, nseconds);
+		if (!ignore_sync ||
+		    ((header & PTP_TX_MSG_HEADER_MSG_TYPE_) !=
+		    PTP_TX_MSG_HEADER_MSG_TYPE_SYNC_))
+			skb_tstamp_tx(skb, &tstamps);
+
+		dev_kfree_skb(skb);
+
+		ptp->tx_ts_skb_queue[i] = NULL;
+		ptp->tx_ts_seconds_queue[i] = 0;
+		ptp->tx_ts_nseconds_queue[i] = 0;
+		ptp->tx_ts_header_queue[i] = 0;
+	}
+
+	/* shift queue */
+	ptp->tx_ts_ignore_sync_queue >>= c;
+	for (i = c; i < LAN743X_PTP_NUMBER_OF_TX_TIMESTAMPS; i++) {
+		ptp->tx_ts_skb_queue[i - c] = ptp->tx_ts_skb_queue[i];
+		ptp->tx_ts_seconds_queue[i - c] = ptp->tx_ts_seconds_queue[i];
+		ptp->tx_ts_nseconds_queue[i - c] = ptp->tx_ts_nseconds_queue[i];
+		ptp->tx_ts_header_queue[i - c] = ptp->tx_ts_header_queue[i];
+
+		ptp->tx_ts_skb_queue[i] = NULL;
+		ptp->tx_ts_seconds_queue[i] = 0;
+		ptp->tx_ts_nseconds_queue[i] = 0;
+		ptp->tx_ts_header_queue[i] = 0;
+	}
+	ptp->tx_ts_skb_queue_size -= c;
+	ptp->tx_ts_queue_size -= c;
+done:
+	ptp->pending_tx_timestamps -= c;
+	spin_unlock_bh(&ptp->tx_ts_lock);
+}
+
+static void lan743x_ptp_tx_ts_enqueue_skb(struct lan743x_adapter *adapter,
+					  struct sk_buff *skb, bool ignore_sync)
+{
+	struct lan743x_ptp *ptp = &adapter->ptp;
+
+	spin_lock_bh(&ptp->tx_ts_lock);
+	if (ptp->tx_ts_skb_queue_size < LAN743X_PTP_NUMBER_OF_TX_TIMESTAMPS) {
+		ptp->tx_ts_skb_queue[ptp->tx_ts_skb_queue_size] = skb;
+		if (ignore_sync)
+			ptp->tx_ts_ignore_sync_queue |=
+				BIT(ptp->tx_ts_skb_queue_size);
+		ptp->tx_ts_skb_queue_size++;
+	} else {
+		/* this should never happen, so long as the tx channel
+		 * calls and honors the result from
+		 * lan743x_ptp_request_tx_timestamp
+		 */
+		netif_err(adapter, drv, adapter->netdev,
+			  "tx ts skb queue overflow\n");
+		dev_kfree_skb(skb);
+	}
+	spin_unlock_bh(&ptp->tx_ts_lock);
+}
+
+static void lan743x_ptp_tx_ts_enqueue_ts(struct lan743x_adapter *adapter,
+					 u32 seconds, u32 nano_seconds,
+					 u32 header)
+{
+	struct lan743x_ptp *ptp = &adapter->ptp;
+
+	spin_lock_bh(&ptp->tx_ts_lock);
+	if (ptp->tx_ts_queue_size < LAN743X_PTP_NUMBER_OF_TX_TIMESTAMPS) {
+		ptp->tx_ts_seconds_queue[ptp->tx_ts_queue_size] = seconds;
+		ptp->tx_ts_nseconds_queue[ptp->tx_ts_queue_size] = nano_seconds;
+		ptp->tx_ts_header_queue[ptp->tx_ts_queue_size] = header;
+		ptp->tx_ts_queue_size++;
+	} else {
+		netif_err(adapter, drv, adapter->netdev,
+			  "tx ts queue overflow\n");
+	}
+	spin_unlock_bh(&ptp->tx_ts_lock);
+}
+
+static void lan743x_ptp_isr_bottom_half(unsigned long param)
+{
+	struct lan743x_adapter *adapter = (struct lan743x_adapter *)param;
+	bool new_timestamp_available = false;
+
+	while (lan743x_csr_read(adapter, PTP_INT_STS) & PTP_INT_BIT_TX_TS_) {
+		u32 cap_info = lan743x_csr_read(adapter, PTP_CAP_INFO);
+
+		if (PTP_CAP_INFO_TX_TS_CNT_GET_(cap_info) > 0) {
+			u32 seconds = lan743x_csr_read(adapter,
+				PTP_TX_EGRESS_SEC);
+			u32 nsec = lan743x_csr_read(adapter, PTP_TX_EGRESS_NS);
+			u32 cause = (nsec &
+				     PTP_TX_EGRESS_NS_CAPTURE_CAUSE_MASK_);
+			u32 header = lan743x_csr_read(adapter,
+						      PTP_TX_MSG_HEADER);
+
+			if (cause == PTP_TX_EGRESS_NS_CAPTURE_CAUSE_SW_) {
+				nsec &= PTP_TX_EGRESS_NS_TS_NS_MASK_;
+				lan743x_ptp_tx_ts_enqueue_ts(adapter,
+							     seconds, nsec,
+							     header);
+				new_timestamp_available = true;
+			} else if (cause ==
+				PTP_TX_EGRESS_NS_CAPTURE_CAUSE_AUTO_) {
+				netif_err(adapter, drv, adapter->netdev,
+					  "Auto capture cause not supported\n");
+			} else {
+				netif_warn(adapter, drv, adapter->netdev,
+					   "unknown tx timestamp capture cause\n");
+			}
+		} else {
+			netif_warn(adapter, drv, adapter->netdev,
+				   "TX TS INT but no TX TS CNT\n");
+		}
+		lan743x_csr_write(adapter, PTP_INT_STS, PTP_INT_BIT_TX_TS_);
+	}
+
+	if (new_timestamp_available)
+		lan743x_ptp_tx_ts_complete(adapter);
+
+	lan743x_csr_write(adapter, INT_EN_SET, INT_BIT_1588_);
+}
+
+static void lan743x_ptp_sync_to_system_clock(struct lan743x_adapter *adapter)
+{
+	struct timeval tv;
+
+	memset(&tv, 0, sizeof(tv));
+	do_gettimeofday(&tv);
+	lan743x_ptp_clock_set(adapter, tv.tv_sec, tv.tv_usec * 1000, 0);
+}
+
+void lan743x_ptp_update_latency(struct lan743x_adapter *adapter,
+				u32 link_speed)
+{
+	switch (link_speed) {
+	case 10:
+		lan743x_csr_write(adapter, PTP_LATENCY,
+				  PTP_LATENCY_TX_SET_(0) |
+				  PTP_LATENCY_RX_SET_(0));
+		break;
+	case 100:
+		lan743x_csr_write(adapter, PTP_LATENCY,
+				  PTP_LATENCY_TX_SET_(181) |
+				  PTP_LATENCY_RX_SET_(594));
+		break;
+	case 1000:
+		lan743x_csr_write(adapter, PTP_LATENCY,
+				  PTP_LATENCY_TX_SET_(30) |
+				  PTP_LATENCY_RX_SET_(525));
+		break;
+	}
+}
+
+int lan743x_ptp_init(struct lan743x_adapter *adapter)
+{
+	struct lan743x_ptp *ptp = &adapter->ptp;
+
+	mutex_init(&ptp->command_lock);
+	spin_lock_init(&ptp->tx_ts_lock);
+	tasklet_init(&ptp->ptp_isr_bottom_half,
+		     lan743x_ptp_isr_bottom_half, (unsigned long)adapter);
+	tasklet_disable(&ptp->ptp_isr_bottom_half);
+	ptp->used_event_ch = 0;
+	ptp->pps_event_ch = -1;
+	ptp->pps_gpio_bit = -1;
+	return 0;
+}
+
+int lan743x_ptp_open(struct lan743x_adapter *adapter)
+{
+	struct lan743x_ptp *ptp = &adapter->ptp;
+	int ret = -ENODEV;
+	u32 temp;
+
+	lan743x_ptp_reset(adapter);
+	lan743x_ptp_sync_to_system_clock(adapter);
+	temp = lan743x_csr_read(adapter, PTP_TX_MOD2);
+	temp |= PTP_TX_MOD2_TX_PTP_CLR_UDPV4_CHKSUM_;
+	lan743x_csr_write(adapter, PTP_TX_MOD2, temp);
+	lan743x_ptp_enable(adapter);
+	tasklet_enable(&ptp->ptp_isr_bottom_half);
+	lan743x_csr_write(adapter, INT_EN_SET, INT_BIT_1588_);
+	lan743x_csr_write(adapter, PTP_INT_EN_SET,
+			  PTP_INT_BIT_TX_SWTS_ERR_ | PTP_INT_BIT_TX_TS_);
+	ptp->flags |= PTP_FLAG_ISR_ENABLED;
+
+#ifdef CONFIG_PTP_1588_CLOCK
+	snprintf(ptp->pin_config[0].name, 32, "lan743x_ptp_pin_0");
+	ptp->pin_config[0].index = 0;
+	ptp->pin_config[0].func = PTP_PF_PEROUT;
+	ptp->pin_config[0].chan = 0;
+
+	ptp->ptp_clock_info.owner = THIS_MODULE;
+	snprintf(ptp->ptp_clock_info.name, 16, "%pm",
+		 adapter->netdev->dev_addr);
+	ptp->ptp_clock_info.max_adj = LAN743X_PTP_MAX_FREQ_ADJ_IN_PPB;
+	ptp->ptp_clock_info.n_alarm = 0;
+	ptp->ptp_clock_info.n_ext_ts = 0;
+	ptp->ptp_clock_info.n_per_out = 0;
+	ptp->ptp_clock_info.n_pins = 0;
+	ptp->ptp_clock_info.pps = 1;
+	ptp->ptp_clock_info.pin_config = NULL;
+	ptp->ptp_clock_info.adjfreq = lan743x_ptpci_adjfreq;
+	ptp->ptp_clock_info.adjtime = lan743x_ptpci_adjtime;
+	ptp->ptp_clock_info.gettime64 = lan743x_ptpci_gettime64;
+	ptp->ptp_clock_info.getcrosststamp = NULL;
+	ptp->ptp_clock_info.settime64 = lan743x_ptpci_settime64;
+	ptp->ptp_clock_info.enable = lan743x_ptpci_enable;
+	ptp->ptp_clock_info.verify = NULL;
+
+	ptp->ptp_clock = ptp_clock_register(&ptp->ptp_clock_info,
+					    &adapter->pdev->dev);
+
+	if (IS_ERR(ptp->ptp_clock)) {
+		netif_err(adapter, ifup, adapter->netdev,
+			  "ptp_clock_register failed\n");
+		goto done;
+	}
+	ptp->flags |= PTP_FLAG_PTP_CLOCK_REGISTERED;
+	netif_info(adapter, ifup, adapter->netdev,
+		   "successfully registered ptp clock\n");
+#endif
+
+	return 0;
+
+#ifdef CONFIG_PTP_1588_CLOCK
+done:
+	lan743x_ptp_close(adapter);
+	return ret;
+#endif
+}
+
+void lan743x_ptp_close(struct lan743x_adapter *adapter)
+{
+	struct lan743x_ptp *ptp = &adapter->ptp;
+	int index;
+
+#ifdef CONFIG_PTP_1588_CLOCK
+	if (ptp->flags & PTP_FLAG_PTP_CLOCK_REGISTERED) {
+		ptp_clock_unregister(ptp->ptp_clock);
+		ptp->ptp_clock = NULL;
+		ptp->flags &= ~PTP_FLAG_PTP_CLOCK_REGISTERED;
+		netif_info(adapter, drv, adapter->netdev,
+			   "ptp clock unregister\n");
+	}
+#endif
+
+	if (ptp->flags & PTP_FLAG_ISR_ENABLED) {
+		lan743x_csr_write(adapter, PTP_INT_EN_CLR,
+				  PTP_INT_BIT_TX_SWTS_ERR_ |
+				  PTP_INT_BIT_TX_TS_);
+		lan743x_csr_write(adapter, INT_EN_CLR, INT_BIT_1588_);
+		tasklet_disable(&ptp->ptp_isr_bottom_half);
+		ptp->flags &= ~PTP_FLAG_ISR_ENABLED;
+	}
+
+	/* clean up pending timestamp requests */
+	lan743x_ptp_tx_ts_complete(adapter);
+	spin_lock_bh(&ptp->tx_ts_lock);
+	for (index = 0;
+		index < LAN743X_PTP_NUMBER_OF_TX_TIMESTAMPS;
+		index++) {
+		struct sk_buff *skb = ptp->tx_ts_skb_queue[index];
+
+		if (skb)
+			dev_kfree_skb(skb);
+		ptp->tx_ts_skb_queue[index] = NULL;
+		ptp->tx_ts_seconds_queue[index] = 0;
+		ptp->tx_ts_nseconds_queue[index] = 0;
+	}
+	ptp->tx_ts_skb_queue_size = 0;
+	ptp->tx_ts_queue_size = 0;
+	ptp->pending_tx_timestamps = 0;
+	spin_unlock_bh(&ptp->tx_ts_lock);
+
+	lan743x_ptp_disable(adapter);
+}
+
+void lan743x_ptp_set_sync_ts_insert(struct lan743x_adapter *adapter,
+				    bool ts_insert_enable)
+{
+	u32 ptp_tx_mod = lan743x_csr_read(adapter, PTP_TX_MOD);
+
+	if (ts_insert_enable)
+		ptp_tx_mod |= PTP_TX_MOD_TX_PTP_SYNC_TS_INSERT_;
+	else
+		ptp_tx_mod &= ~PTP_TX_MOD_TX_PTP_SYNC_TS_INSERT_;
+
+	lan743x_csr_write(adapter, PTP_TX_MOD, ptp_tx_mod);
+}
+
+static bool lan743x_ptp_is_enabled(struct lan743x_adapter *adapter)
+{
+	if (lan743x_csr_read(adapter, PTP_CMD_CTL) & PTP_CMD_CTL_PTP_ENABLE_)
+		return true;
+	return false;
+}
+
+static void lan743x_ptp_wait_till_cmd_done(struct lan743x_adapter *adapter,
+					   u32 bit_mask)
+{
+	int timeout = 1000;
+	u32 data = 0;
+
+	while (timeout &&
+	       (data = (lan743x_csr_read(adapter, PTP_CMD_CTL) &
+	       bit_mask))) {
+		usleep_range(1000, 20000);
+		timeout--;
+	}
+	if (data) {
+		netif_err(adapter, drv, adapter->netdev,
+			  "timeout waiting for cmd to be done, cmd = 0x%08X\n",
+			  bit_mask);
+	}
+}
+
+static void lan743x_ptp_enable(struct lan743x_adapter *adapter)
+{
+	struct lan743x_ptp *ptp = &adapter->ptp;
+
+	mutex_lock(&ptp->command_lock);
+
+	if (lan743x_ptp_is_enabled(adapter)) {
+		netif_warn(adapter, drv, adapter->netdev,
+			   "PTP already enabled\n");
+		goto done;
+	}
+	lan743x_csr_write(adapter, PTP_CMD_CTL, PTP_CMD_CTL_PTP_ENABLE_);
+done:
+	mutex_unlock(&ptp->command_lock);
+}
+
+static void lan743x_ptp_disable(struct lan743x_adapter *adapter)
+{
+	struct lan743x_ptp *ptp = &adapter->ptp;
+
+	mutex_lock(&ptp->command_lock);
+	if (!lan743x_ptp_is_enabled(adapter)) {
+		netif_warn(adapter, drv, adapter->netdev,
+			   "PTP already disabled\n");
+		goto done;
+	}
+	lan743x_csr_write(adapter, PTP_CMD_CTL, PTP_CMD_CTL_PTP_DISABLE_);
+	lan743x_ptp_wait_till_cmd_done(adapter, PTP_CMD_CTL_PTP_ENABLE_);
+done:
+	mutex_unlock(&ptp->command_lock);
+}
+
+static void lan743x_ptp_reset(struct lan743x_adapter *adapter)
+{
+	struct lan743x_ptp *ptp = &adapter->ptp;
+
+	mutex_lock(&ptp->command_lock);
+
+	if (lan743x_ptp_is_enabled(adapter)) {
+		netif_err(adapter, drv, adapter->netdev,
+			  "Attempting reset while enabled\n");
+		goto done;
+	}
+
+	lan743x_csr_write(adapter, PTP_CMD_CTL, PTP_CMD_CTL_PTP_RESET_);
+	lan743x_ptp_wait_till_cmd_done(adapter, PTP_CMD_CTL_PTP_RESET_);
+done:
+	mutex_unlock(&ptp->command_lock);
+}
+
+#ifdef CONFIG_PTP_1588_CLOCK
+static int lan743x_ptp_reserve_event_ch(struct lan743x_adapter *adapter)
+{
+	struct lan743x_ptp *ptp = &adapter->ptp;
+	int result = -ENODEV;
+	int index = 0;
+
+	mutex_lock(&ptp->command_lock);
+	for (index = 0; index < LAN743X_PTP_NUMBER_OF_EVENT_CHANNELS; index++) {
+		if (!(test_bit(index, &ptp->used_event_ch))) {
+			ptp->used_event_ch |= BIT(index);
+			result = index;
+			break;
+		}
+	}
+	mutex_unlock(&ptp->command_lock);
+	return result;
+}
+#endif /* CONFIG_PTP_1588_CLOCK */
+
+#ifdef CONFIG_PTP_1588_CLOCK
+static void lan743x_ptp_release_event_ch(struct lan743x_adapter *adapter,
+					 int event_channel)
+{
+	struct lan743x_ptp *ptp = &adapter->ptp;
+
+	mutex_lock(&ptp->command_lock);
+	if (test_bit(event_channel, &ptp->used_event_ch)) {
+		ptp->used_event_ch &= ~BIT(event_channel);
+	} else {
+		netif_warn(adapter, drv, adapter->netdev,
+			   "attempted release on a not used event_channel = %d\n",
+			   event_channel);
+	}
+	mutex_unlock(&ptp->command_lock);
+}
+#endif /* CONFIG_PTP_1588_CLOCK */
+
+#ifdef CONFIG_PTP_1588_CLOCK
+static void lan743x_ptp_clock_get(struct lan743x_adapter *adapter,
+				  u32 *seconds, u32 *nano_seconds,
+				  u32 *sub_nano_seconds)
+{
+	struct lan743x_ptp *ptp = &adapter->ptp;
+
+	mutex_lock(&ptp->command_lock);
+
+	lan743x_csr_write(adapter, PTP_CMD_CTL, PTP_CMD_CTL_PTP_CLOCK_READ_);
+	lan743x_ptp_wait_till_cmd_done(adapter, PTP_CMD_CTL_PTP_CLOCK_READ_);
+
+	if (seconds)
+		(*seconds) = lan743x_csr_read(adapter, PTP_CLOCK_SEC);
+
+	if (nano_seconds)
+		(*nano_seconds) = lan743x_csr_read(adapter, PTP_CLOCK_NS);
+
+	if (sub_nano_seconds)
+		(*sub_nano_seconds) =
+		lan743x_csr_read(adapter, PTP_CLOCK_SUBNS);
+
+	mutex_unlock(&ptp->command_lock);
+}
+#endif /* CONFIG_PTP_1588_CLOCK */
+
+static void lan743x_ptp_clock_set(struct lan743x_adapter *adapter,
+				  u32 seconds, u32 nano_seconds,
+				  u32 sub_nano_seconds)
+{
+	struct lan743x_ptp *ptp = &adapter->ptp;
+
+	mutex_lock(&ptp->command_lock);
+
+	lan743x_csr_write(adapter, PTP_CLOCK_SEC, seconds);
+	lan743x_csr_write(adapter, PTP_CLOCK_NS, nano_seconds);
+	lan743x_csr_write(adapter, PTP_CLOCK_SUBNS, sub_nano_seconds);
+
+	lan743x_csr_write(adapter, PTP_CMD_CTL, PTP_CMD_CTL_PTP_CLOCK_LOAD_);
+	lan743x_ptp_wait_till_cmd_done(adapter, PTP_CMD_CTL_PTP_CLOCK_LOAD_);
+	mutex_unlock(&ptp->command_lock);
+}
+
+#ifdef CONFIG_PTP_1588_CLOCK
+static void lan743x_ptp_clock_step(struct lan743x_adapter *adapter,
+				   s64 time_step_ns)
+{
+	struct lan743x_ptp *ptp = &adapter->ptp;
+	u64 abs_time_step_ns = 0;
+	u32 nano_seconds = 0;
+	s32 seconds = 0;
+
+	if (time_step_ns >  15000000000LL) {
+		/* convert to clock set */
+		u32 nano_seconds = 0;
+		u32 seconds = 0;
+
+		lan743x_ptp_clock_get(adapter, &seconds, &nano_seconds, NULL);
+		seconds += (time_step_ns / 1000000000LL);
+		nano_seconds += (time_step_ns % 1000000000LL);
+		if (nano_seconds >= 1000000000) {
+			seconds++;
+			nano_seconds -= 1000000000;
+		}
+		lan743x_ptp_clock_set(adapter, seconds, nano_seconds, 0);
+		return;
+	} else if (time_step_ns < -15000000000LL) {
+		/* convert to clock set */
+		u32 nano_seconds_step = 0;
+		u32 nano_seconds = 0;
+		u32 seconds = 0;
+
+		time_step_ns = -time_step_ns;
+
+		lan743x_ptp_clock_get(adapter, &seconds, &nano_seconds, NULL);
+		seconds -= (time_step_ns / 1000000000LL);
+		nano_seconds_step = (time_step_ns % 1000000000LL);
+		if (nano_seconds < nano_seconds_step) {
+			seconds--;
+			nano_seconds += 1000000000;
+		}
+		nano_seconds -= nano_seconds_step;
+		lan743x_ptp_clock_set(adapter, seconds, nano_seconds, 0);
+		return;
+	}
+
+	/* do clock step */
+
+	if (time_step_ns >= 0) {
+		abs_time_step_ns = (u64)(time_step_ns);
+		seconds = (s32)(abs_time_step_ns / 1000000000);
+		nano_seconds = (u32)(abs_time_step_ns % 1000000000);
+	} else {
+		abs_time_step_ns = (u64)(-time_step_ns);
+		seconds = -((s32)(abs_time_step_ns / 1000000000));
+		nano_seconds = (u32)(abs_time_step_ns % 1000000000);
+		if (nano_seconds > 0) {
+			/* subtracting nano seconds is not allowed
+			 * convert to subtracting from seconds,
+			 * and adding to nanoseconds
+			 */
+			seconds--;
+			nano_seconds = (1000000000 - nano_seconds);
+		}
+	}
+
+	if (nano_seconds > 0) {
+		/* add 8 ns to cover the likely normal increment */
+		nano_seconds += 8;
+	}
+
+	if (nano_seconds >= 1000000000) {
+		/* carry into seconds */
+		seconds++;
+		nano_seconds -= 1000000000;
+	}
+
+	while (seconds) {
+		mutex_lock(&ptp->command_lock);
+		if (seconds > 0) {
+			u32 adjustment_value = (u32)seconds;
+
+			if (adjustment_value > 0xF)
+				adjustment_value = 0xF;
+			lan743x_csr_write(adapter, PTP_CLOCK_STEP_ADJ,
+					  PTP_CLOCK_STEP_ADJ_DIR_ |
+					  adjustment_value);
+			seconds -= ((s32)adjustment_value);
+		} else {
+			u32 adjustment_value = (u32)(-seconds);
+
+			if (adjustment_value > 0xF)
+				adjustment_value = 0xF;
+			lan743x_csr_write(adapter, PTP_CLOCK_STEP_ADJ,
+					  adjustment_value);
+			seconds += ((s32)adjustment_value);
+		}
+		lan743x_csr_write(adapter, PTP_CMD_CTL,
+				  PTP_CMD_CTL_PTP_CLOCK_STEP_SEC_);
+		lan743x_ptp_wait_till_cmd_done(adapter,
+					       PTP_CMD_CTL_PTP_CLOCK_STEP_SEC_);
+		mutex_unlock(&ptp->command_lock);
+	}
+	if (nano_seconds) {
+		mutex_lock(&ptp->command_lock);
+		lan743x_csr_write(adapter, PTP_CLOCK_STEP_ADJ,
+				  PTP_CLOCK_STEP_ADJ_DIR_ |
+				  (nano_seconds &
+				  PTP_CLOCK_STEP_ADJ_VALUE_MASK_));
+		lan743x_csr_write(adapter, PTP_CMD_CTL,
+				  PTP_CMD_CTL_PTP_CLK_STP_NSEC_);
+		lan743x_ptp_wait_till_cmd_done(adapter,
+					       PTP_CMD_CTL_PTP_CLK_STP_NSEC_);
+		mutex_unlock(&ptp->command_lock);
+	}
+}
+#endif /* CONFIG_PTP_1588_CLOCK */
+
+bool lan743x_ptp_request_tx_timestamp(struct lan743x_adapter *adapter)
+{
+	struct lan743x_ptp *ptp = &adapter->ptp;
+	bool result = false;
+
+	spin_lock_bh(&ptp->tx_ts_lock);
+	if (ptp->pending_tx_timestamps < LAN743X_PTP_NUMBER_OF_TX_TIMESTAMPS) {
+		ptp->pending_tx_timestamps++;
+		result = true;/* request granted */
+	}
+	spin_unlock_bh(&ptp->tx_ts_lock);
+	return result;
+}
+
+void lan743x_ptp_unrequest_tx_timestamp(struct lan743x_adapter *adapter)
+{
+	struct lan743x_ptp *ptp = &adapter->ptp;
+
+	spin_lock_bh(&ptp->tx_ts_lock);
+	if (ptp->pending_tx_timestamps > 0)
+		ptp->pending_tx_timestamps--;
+	else
+		netif_err(adapter, drv, adapter->netdev,
+			  "unrequest failed, pending_tx_timestamps==0\n");
+	spin_unlock_bh(&ptp->tx_ts_lock);
+}
+
+void lan743x_ptp_tx_timestamp_skb(struct lan743x_adapter *adapter,
+				  struct sk_buff *skb, bool ignore_sync)
+{
+	lan743x_ptp_tx_ts_enqueue_skb(adapter, skb, ignore_sync);
+
+	lan743x_ptp_tx_ts_complete(adapter);
+}
+
+int lan743x_ptp_ioctl(struct net_device *netdev, struct ifreq *ifr, int cmd)
+{
+	struct lan743x_adapter *adapter = netdev_priv(netdev);
+	struct hwtstamp_config config;
+	int ret = 0;
+	int index;
+
+	if (!ifr) {
+		netif_err(adapter, drv, adapter->netdev,
+			  "SIOCSHWTSTAMP, ifr == NULL\n");
+		return -EINVAL;
+	}
+
+	if (copy_from_user(&config, ifr->ifr_data, sizeof(config)))
+		return -EFAULT;
+
+	if (config.flags) {
+		netif_warn(adapter, drv, adapter->netdev,
+			   "ignoring hwtstamp_config.flags == 0x%08X, expected 0\n",
+			   config.flags);
+	}
+
+	switch (config.tx_type) {
+	case HWTSTAMP_TX_OFF:
+		for (index = 0; index < LAN743X_MAX_TX_CHANNELS;
+			index++)
+			lan743x_tx_set_timestamping_mode(&adapter->tx[index],
+							 false, false);
+		lan743x_ptp_set_sync_ts_insert(adapter, false);
+		netif_info(adapter, drv, adapter->netdev,
+			   "  tx_type = HWTSTAMP_TX_OFF\n");
+		break;
+	case HWTSTAMP_TX_ON:
+		for (index = 0; index < LAN743X_MAX_TX_CHANNELS;
+			index++)
+			lan743x_tx_set_timestamping_mode(&adapter->tx[index],
+							 true, false);
+		lan743x_ptp_set_sync_ts_insert(adapter, false);
+		netif_info(adapter, drv, adapter->netdev,
+			   "  tx_type = HWTSTAMP_TX_ON\n");
+		break;
+	case HWTSTAMP_TX_ONESTEP_SYNC:
+		for (index = 0; index < LAN743X_MAX_TX_CHANNELS;
+			index++)
+			lan743x_tx_set_timestamping_mode(&adapter->tx[index],
+							 true, true);
+
+		lan743x_ptp_set_sync_ts_insert(adapter, true);
+		netif_info(adapter, drv, adapter->netdev,
+			   "  tx_type = HWTSTAMP_TX_ONESTEP_SYNC\n");
+		break;
+	default:
+		netif_info(adapter, drv, adapter->netdev,
+			   "  tx_type = %d, UNKNOWN\n", config.tx_type);
+		ret = -EINVAL;
+		break;
+	}
+
+	if (!ret)
+		return copy_to_user(ifr->ifr_data, &config,
+			sizeof(config)) ? -EFAULT : 0;
+	return ret;
+}
diff --git a/drivers/net/ethernet/microchip/lan743x_ptp.h b/drivers/net/ethernet/microchip/lan743x_ptp.h
new file mode 100644
index 0000000..979ffce
--- /dev/null
+++ b/drivers/net/ethernet/microchip/lan743x_ptp.h
@@ -0,0 +1,78 @@
+/* SPDX-License-Identifier: GPL-2.0+ */
+/* Copyright (C) 2018 Microchip Technology Inc. */
+
+#ifndef _LAN743X_PTP_H
+#define _LAN743X_PTP_H
+
+#include "linux/ptp_clock_kernel.h"
+#include "linux/netdevice.h"
+
+struct lan743x_adapter;
+
+/* GPIO */
+struct lan743x_gpio {
+	/* gpio_lock: used to prevent concurrent access to gpio settings */
+	spinlock_t gpio_lock;
+
+	int used_bits;
+	int output_bits;
+	int ptp_bits;
+	u32 gpio_cfg0;
+	u32 gpio_cfg1;
+	u32 gpio_cfg2;
+	u32 gpio_cfg3;
+};
+
+int lan743x_gpio_init(struct lan743x_adapter *adapter);
+
+void lan743x_ptp_isr(void *context);
+bool lan743x_ptp_request_tx_timestamp(struct lan743x_adapter *adapter);
+void lan743x_ptp_unrequest_tx_timestamp(struct lan743x_adapter *adapter);
+void lan743x_ptp_tx_timestamp_skb(struct lan743x_adapter *adapter,
+				  struct sk_buff *skb, bool ignore_sync);
+int lan743x_ptp_init(struct lan743x_adapter *adapter);
+int lan743x_ptp_open(struct lan743x_adapter *adapter);
+void lan743x_ptp_close(struct lan743x_adapter *adapter);
+void lan743x_ptp_update_latency(struct lan743x_adapter *adapter,
+				u32 link_speed);
+
+int lan743x_ptp_ioctl(struct net_device *netdev, struct ifreq *ifr, int cmd);
+
+#define LAN743X_PTP_NUMBER_OF_TX_TIMESTAMPS (4)
+
+#define PTP_FLAG_PTP_CLOCK_REGISTERED	BIT(1)
+#define PTP_FLAG_ISR_ENABLED			BIT(2)
+
+struct lan743x_ptp {
+	int flags;
+
+	/* command_lock: used to prevent concurrent ptp commands */
+	struct mutex	command_lock;
+
+#ifdef CONFIG_PTP_1588_CLOCK
+	struct ptp_clock *ptp_clock;
+	struct ptp_clock_info ptp_clock_info;
+	struct ptp_pin_desc pin_config[1];
+#endif /* CONFIG_PTP_1588_CLOCK */
+
+	struct tasklet_struct	ptp_isr_bottom_half;
+
+#define LAN743X_PTP_NUMBER_OF_EVENT_CHANNELS (2)
+	unsigned long used_event_ch;
+
+	int pps_event_ch;
+	int pps_gpio_bit;
+
+	/* tx_ts_lock: used to prevent concurrent access to timestamp arrays */
+	spinlock_t	tx_ts_lock;
+	int pending_tx_timestamps;
+	struct sk_buff *tx_ts_skb_queue[LAN743X_PTP_NUMBER_OF_TX_TIMESTAMPS];
+	unsigned int	tx_ts_ignore_sync_queue;
+	int tx_ts_skb_queue_size;
+	u32 tx_ts_seconds_queue[LAN743X_PTP_NUMBER_OF_TX_TIMESTAMPS];
+	u32 tx_ts_nseconds_queue[LAN743X_PTP_NUMBER_OF_TX_TIMESTAMPS];
+	u32 tx_ts_header_queue[LAN743X_PTP_NUMBER_OF_TX_TIMESTAMPS];
+	int tx_ts_queue_size;
+};
+
+#endif /* _LAN743X_PTP_H */
-- 
2.7.4

Powered by blists - more mailing lists

Powered by Openwall GNU/*/Linux Powered by OpenVZ