From 9d77db3c730780c8ef5ccd4b66403ff5675cfe4e Mon Sep 17 00:00:00 2001
From: hc <hc@nodka.com>
Date: Mon, 13 May 2024 10:30:14 +0000
Subject: [PATCH] modify sin led gpio

---
 kernel/drivers/usb/dwc2/gadget.c |  375 +++++++++++++++++++++++++++++++++++++++++------------
 1 files changed, 291 insertions(+), 84 deletions(-)

diff --git a/kernel/drivers/usb/dwc2/gadget.c b/kernel/drivers/usb/dwc2/gadget.c
index 9f3c751..2abbaf2 100644
--- a/kernel/drivers/usb/dwc2/gadget.c
+++ b/kernel/drivers/usb/dwc2/gadget.c
@@ -28,6 +28,8 @@
 #include <linux/usb/ch9.h>
 #include <linux/usb/gadget.h>
 #include <linux/usb/phy.h>
+#include <linux/usb/composite.h>
+
 
 #include "core.h"
 #include "hw.h"
@@ -148,6 +150,30 @@
 }
 
 /**
+ * dwc2_gadget_dec_frame_num_by_one - Decrements the targeted frame number
+ *                                    by one.
+ * @hs_ep: The endpoint.
+ *
+ * This function used in service interval based scheduling flow to calculate
+ * descriptor frame number filed value. For service interval mode frame
+ * number in descriptor should point to last (u)frame in the interval.
+ *
+ */
+static inline void dwc2_gadget_dec_frame_num_by_one(struct dwc2_hsotg_ep *hs_ep)
+{
+	struct dwc2_hsotg *hsotg = hs_ep->parent;
+	u16 limit = DSTS_SOFFN_LIMIT;
+
+	if (hsotg->gadget.speed != USB_SPEED_HIGH)
+		limit >>= 3;
+
+	if (hs_ep->target_frame)
+		hs_ep->target_frame -= 1;
+	else
+		hs_ep->target_frame = limit;
+}
+
+/**
  * dwc2_hsotg_en_gsint - enable one or more of the general interrupt
  * @hsotg: The device state
  * @ints: A bitmask of the interrupts to enable
@@ -250,6 +276,28 @@
 		return 0;
 
 	return tx_addr_max - addr;
+}
+
+/**
+ * dwc2_gadget_wkup_alert_handler - Handler for WKUP_ALERT interrupt
+ *
+ * @hsotg: Programming view of the DWC_otg controller
+ *
+ */
+static void dwc2_gadget_wkup_alert_handler(struct dwc2_hsotg *hsotg)
+{
+	u32 gintsts2;
+	u32 gintmsk2;
+
+	gintsts2 = dwc2_readl(hsotg, GINTSTS2);
+	gintmsk2 = dwc2_readl(hsotg, GINTMSK2);
+	gintsts2 &= gintmsk2;
+
+	if (gintsts2 & GINTSTS2_WKUP_ALERT_INT) {
+		dev_dbg(hsotg->dev, "%s: Wkup_Alert_Int\n", __func__);
+		dwc2_set_bit(hsotg, GINTSTS2, GINTSTS2_WKUP_ALERT_INT);
+		dwc2_set_bit(hsotg, DCTL, DCTL_RMTWKUPSIG);
+	}
 }
 
 /**
@@ -753,22 +801,13 @@
 	return desc_size;
 }
 
-/*
- * dwc2_gadget_config_nonisoc_xfer_ddma - prepare non ISOC DMA desc chain.
- * @hs_ep: The endpoint
- * @dma_buff: DMA address to use
- * @len: Length of the transfer
- *
- * This function will iterate over descriptor chain and fill its entries
- * with corresponding information based on transfer data.
- */
-static void dwc2_gadget_config_nonisoc_xfer_ddma(struct dwc2_hsotg_ep *hs_ep,
+static void dwc2_gadget_fill_nonisoc_xfer_ddma_one(struct dwc2_hsotg_ep *hs_ep,
+						 struct dwc2_dma_desc **desc,
 						 dma_addr_t dma_buff,
-						 unsigned int len)
+						 unsigned int len,
+						 bool true_last)
 {
-	struct dwc2_hsotg *hsotg = hs_ep->parent;
 	int dir_in = hs_ep->dir_in;
-	struct dwc2_dma_desc *desc = hs_ep->desc_list;
 	u32 mps = hs_ep->ep.maxpacket;
 	u32 maxsize = 0;
 	u32 offset = 0;
@@ -783,39 +822,80 @@
 		hs_ep->desc_count = 1;
 
 	for (i = 0; i < hs_ep->desc_count; ++i) {
-		desc->status = 0;
-		desc->status |= (DEV_DMA_BUFF_STS_HBUSY
+		(*desc)->status = 0;
+		(*desc)->status |= (DEV_DMA_BUFF_STS_HBUSY
 				 << DEV_DMA_BUFF_STS_SHIFT);
 
 		if (len > maxsize) {
 			if (!hs_ep->index && !dir_in)
-				desc->status |= (DEV_DMA_L | DEV_DMA_IOC);
+				(*desc)->status |= (DEV_DMA_L | DEV_DMA_IOC);
 
-			desc->status |= (maxsize <<
-						DEV_DMA_NBYTES_SHIFT & mask);
-			desc->buf = dma_buff + offset;
+			(*desc)->status |=
+				maxsize << DEV_DMA_NBYTES_SHIFT & mask;
+			(*desc)->buf = dma_buff + offset;
 
 			len -= maxsize;
 			offset += maxsize;
 		} else {
-			desc->status |= (DEV_DMA_L | DEV_DMA_IOC);
+			if (true_last)
+				(*desc)->status |= (DEV_DMA_L | DEV_DMA_IOC);
 
 			if (dir_in)
-				desc->status |= (len % mps) ? DEV_DMA_SHORT :
-					((hs_ep->send_zlp) ? DEV_DMA_SHORT : 0);
-			if (len > maxsize)
-				dev_err(hsotg->dev, "wrong len %d\n", len);
+				(*desc)->status |= (len % mps) ? DEV_DMA_SHORT :
+					((hs_ep->send_zlp && true_last) ?
+					DEV_DMA_SHORT : 0);
 
-			desc->status |=
+			(*desc)->status |=
 				len << DEV_DMA_NBYTES_SHIFT & mask;
-			desc->buf = dma_buff + offset;
+			(*desc)->buf = dma_buff + offset;
 		}
 
-		desc->status &= ~DEV_DMA_BUFF_STS_MASK;
-		desc->status |= (DEV_DMA_BUFF_STS_HREADY
+		(*desc)->status &= ~DEV_DMA_BUFF_STS_MASK;
+		(*desc)->status |= (DEV_DMA_BUFF_STS_HREADY
 				 << DEV_DMA_BUFF_STS_SHIFT);
-		desc++;
+		(*desc)++;
 	}
+}
+
+/*
+ * dwc2_gadget_config_nonisoc_xfer_ddma - prepare non ISOC DMA desc chain.
+ * @hs_ep: The endpoint
+ * @ureq: Request to transfer
+ * @offset: offset in bytes
+ * @len: Length of the transfer
+ *
+ * This function will iterate over descriptor chain and fill its entries
+ * with corresponding information based on transfer data.
+ */
+static void dwc2_gadget_config_nonisoc_xfer_ddma(struct dwc2_hsotg_ep *hs_ep,
+						 dma_addr_t dma_buff,
+						 unsigned int len)
+{
+	struct usb_request *ureq = NULL;
+	struct dwc2_dma_desc *desc = hs_ep->desc_list;
+	struct scatterlist *sg;
+	int i;
+	u8 desc_count = 0;
+
+	if (hs_ep->req)
+		ureq = &hs_ep->req->req;
+
+	/* non-DMA sg buffer */
+	if (!ureq || !ureq->num_sgs) {
+		dwc2_gadget_fill_nonisoc_xfer_ddma_one(hs_ep, &desc,
+			dma_buff, len, true);
+		return;
+	}
+
+	/* DMA sg buffer */
+	for_each_sg(ureq->sg, sg, ureq->num_sgs, i) {
+		dwc2_gadget_fill_nonisoc_xfer_ddma_one(hs_ep, &desc,
+			sg_dma_address(sg) + sg->offset, sg_dma_len(sg),
+			sg_is_last(sg));
+		desc_count += hs_ep->desc_count;
+	}
+
+	hs_ep->desc_count = desc_count;
 }
 
 /*
@@ -835,11 +915,10 @@
 	struct dwc2_dma_desc *desc;
 	struct dwc2_hsotg *hsotg = hs_ep->parent;
 	u32 index;
-	u32 maxsize = 0;
 	u32 mask = 0;
 	u8 pid = 0;
 
-	maxsize = dwc2_gadget_get_desc_params(hs_ep, &mask);
+	dwc2_gadget_get_desc_params(hs_ep, &mask);
 
 	index = hs_ep->next_desc;
 	desc = &hs_ep->desc_list[index];
@@ -929,7 +1008,13 @@
 
 	hs_ep->next_desc = 0;
 	list_for_each_entry_safe(hs_req, treq, &hs_ep->queue, queue) {
-		ret = dwc2_gadget_fill_isoc_desc(hs_ep, hs_req->req.dma,
+		dma_addr_t dma_addr = hs_req->req.dma;
+
+		if (hs_req->req.num_sgs) {
+			WARN_ON(hs_req->req.num_sgs > 1);
+			dma_addr = sg_dma_address(hs_req->req.sg);
+		}
+		ret = dwc2_gadget_fill_isoc_desc(hs_ep, dma_addr,
 						 hs_req->req.length);
 		if (ret)
 			break;
@@ -1400,11 +1485,22 @@
 	 */
 	if (using_desc_dma(hs) && hs_ep->isochronous) {
 		if (hs_ep->target_frame != TARGET_FRAME_INITIAL) {
-			dwc2_gadget_fill_isoc_desc(hs_ep, hs_req->req.dma,
+			dma_addr_t dma_addr = hs_req->req.dma;
+
+			if (hs_req->req.num_sgs) {
+				WARN_ON(hs_req->req.num_sgs > 1);
+				dma_addr = sg_dma_address(hs_req->req.sg);
+			}
+			dwc2_gadget_fill_isoc_desc(hs_ep, dma_addr,
 						   hs_req->req.length);
 		}
 		return 0;
 	}
+
+	/* Change EP direction if status phase request is after data out */
+	if (!hs_ep->index && !req->length && !hs_ep->dir_in &&
+	    hs->ep0_state == DWC2_EP0_DATA_OUT)
+		hs_ep->dir_in = 1;
 
 	if (first) {
 		if (!hs_ep->isochronous) {
@@ -1519,11 +1615,11 @@
 
 	dctl &= ~DCTL_TSTCTL_MASK;
 	switch (testmode) {
-	case TEST_J:
-	case TEST_K:
-	case TEST_SE0_NAK:
-	case TEST_PACKET:
-	case TEST_FORCE_EN:
+	case USB_TEST_J:
+	case USB_TEST_K:
+	case USB_TEST_SE0_NAK:
+	case USB_TEST_PACKET:
+	case USB_TEST_FORCE_ENABLE:
 		dctl |= testmode << DCTL_TSTCTL_SHIFT;
 		break;
 	default:
@@ -1604,7 +1700,8 @@
 
 	switch (ctrl->bRequestType & USB_RECIP_MASK) {
 	case USB_RECIP_DEVICE:
-		status = 1 << USB_DEVICE_SELF_POWERED;
+		status = hsotg->gadget.is_selfpowered <<
+			 USB_DEVICE_SELF_POWERED;
 		status |= hsotg->remote_wakeup_allowed <<
 			  USB_DEVICE_REMOTE_WAKEUP;
 		reply = cpu_to_le16(status);
@@ -1905,6 +2002,10 @@
 			dev_dbg(hsotg->dev, "driver->setup() ret %d\n", ret);
 	}
 
+	hsotg->delayed_status = false;
+	if (ret == USB_GADGET_DELAYED_STATUS)
+		hsotg->delayed_status = true;
+
 	/*
 	 * the request is either unhandlable, or is not formatted correctly
 	 * so respond with a STALL for the status stage to indicate failure.
@@ -2125,6 +2226,11 @@
 			 */
 			if (!hs_ep->dir_in && ureq->length & 0x3)
 				ureq->actual += 4 - (ureq->length & 0x3);
+
+			/* Set actual frame number for completed transfers */
+			ureq->frame_number =
+				(desc_sts & DEV_DMA_ISOC_FRNUM_MASK) >>
+				DEV_DMA_ISOC_FRNUM_SHIFT;
 		}
 
 		dwc2_hsotg_complete_request(hsotg, hs_ep, hs_req, 0);
@@ -2357,8 +2463,8 @@
 	if (!using_desc_dma(hsotg) && epnum == 0 &&
 	    hsotg->ep0_state == DWC2_EP0_DATA_OUT) {
 		/* Move to STATUS IN */
-		dwc2_hsotg_ep0_zlp(hsotg, true);
-		return;
+		if (!hsotg->delayed_status)
+			dwc2_hsotg_ep0_zlp(hsotg, true);
 	}
 
 	/* Set actual frame number for completed transfers */
@@ -2876,6 +2982,23 @@
 		if (using_desc_dma(hsotg)) {
 			hs_ep->target_frame = hsotg->frame_number;
 			dwc2_gadget_incr_frame_num(hs_ep);
+
+			/* In service interval mode target_frame must
+			 * be set to last (u)frame of the service interval.
+			 */
+			if (hsotg->params.service_interval) {
+				/* Set target_frame to the first (u)frame of
+				 * the service interval
+				 */
+				hs_ep->target_frame &= ~hs_ep->interval + 1;
+
+				/* Set target_frame to the last (u)frame of
+				 * the service interval
+				 */
+				dwc2_gadget_incr_frame_num(hs_ep);
+				dwc2_gadget_dec_frame_num_by_one(hs_ep);
+			}
+
 			dwc2_gadget_start_isoc_ddma(hs_ep);
 			return;
 		}
@@ -2952,10 +3075,8 @@
 	u32 epctl_reg = dir_in ? DIEPCTL(idx) : DOEPCTL(idx);
 	u32 epsiz_reg = dir_in ? DIEPTSIZ(idx) : DOEPTSIZ(idx);
 	u32 ints;
-	u32 ctrl;
 
 	ints = dwc2_gadget_read_ep_interrupts(hsotg, idx, dir_in);
-	ctrl = dwc2_readl(hsotg, epctl_reg);
 
 	/* Clear endpoint interrupts */
 	dwc2_writel(hsotg, ints, epint_reg);
@@ -3049,8 +3170,20 @@
 		/* Safety check EP0 state when STSPHSERCVD asserted */
 		if (hsotg->ep0_state == DWC2_EP0_DATA_OUT) {
 			/* Move to STATUS IN for DDMA */
-			if (using_desc_dma(hsotg))
-				dwc2_hsotg_ep0_zlp(hsotg, true);
+			if (using_desc_dma(hsotg)) {
+				if (!hsotg->delayed_status)
+					dwc2_hsotg_ep0_zlp(hsotg, true);
+				else
+				/* In case of 3 stage Control Write with delayed
+				 * status, when Status IN transfer started
+				 * before STSPHSERCVD asserted, NAKSTS bit not
+				 * cleared by CNAK in dwc2_hsotg_start_req()
+				 * function. Clear now NAKSTS to allow complete
+				 * transfer.
+				 */
+					dwc2_set_bit(hsotg, DIEPCTL(0),
+						     DXEPCTL_CNAK);
+			}
 		}
 
 	}
@@ -3185,14 +3318,15 @@
 			      struct dwc2_hsotg_ep *ep,
 			      int result)
 {
-	struct dwc2_hsotg_req *req, *treq;
 	unsigned int size;
 
 	ep->req = NULL;
 
-	list_for_each_entry_safe(req, treq, &ep->queue, queue)
-		dwc2_hsotg_complete_request(hsotg, ep, req,
-					    result);
+	while (!list_empty(&ep->queue)) {
+		struct dwc2_hsotg_req *req = get_ep_head(ep);
+
+		dwc2_hsotg_complete_request(hsotg, ep, req, result);
+	}
 
 	if (!hsotg->dedicated_fifos)
 		return;
@@ -3310,21 +3444,14 @@
 
 	/* keep other bits untouched (so e.g. forced modes are not lost) */
 	usbcfg = dwc2_readl(hsotg, GUSBCFG);
-	usbcfg &= ~(GUSBCFG_TOUTCAL_MASK | GUSBCFG_PHYIF16 | GUSBCFG_SRPCAP |
-		GUSBCFG_HNPCAP | GUSBCFG_USBTRDTIM_MASK);
+	usbcfg &= ~GUSBCFG_TOUTCAL_MASK;
+	usbcfg |= GUSBCFG_TOUTCAL(7);
 
-	if (hsotg->params.phy_type == DWC2_PHY_TYPE_PARAM_FS &&
-	    (hsotg->params.speed == DWC2_SPEED_PARAM_FULL ||
-	     hsotg->params.speed == DWC2_SPEED_PARAM_LOW)) {
-		/* FS/LS Dedicated Transceiver Interface */
-		usbcfg |= GUSBCFG_PHYSEL;
-	} else {
-		/* set the PLL on, remove the HNP/SRP and set the PHY */
-		val = (hsotg->phyif == GUSBCFG_PHYIF8) ? 9 : 5;
-		usbcfg |= hsotg->phyif | GUSBCFG_TOUTCAL(7) |
-			(val << GUSBCFG_USBTRDTIM_SHIFT);
-	}
-	dwc2_writel(hsotg, usbcfg, GUSBCFG);
+	/* remove the HNP/SRP and set the PHY */
+	usbcfg &= ~(GUSBCFG_SRPCAP | GUSBCFG_HNPCAP);
+        dwc2_writel(hsotg, usbcfg, GUSBCFG);
+
+	dwc2_phy_init(hsotg, true);
 
 	dwc2_hsotg_init_fifo(hsotg);
 
@@ -3416,6 +3543,10 @@
 		dwc2_set_bit(hsotg, DIEPMSK, DIEPMSK_BNAININTRMSK);
 	}
 
+	/* Enable Service Interval mode if supported */
+	if (using_desc_dma(hsotg) && hsotg->params.service_interval)
+		dwc2_set_bit(hsotg, DCTL, DCTL_SERVICE_INTERVAL_SUPPORTED);
+
 	dwc2_writel(hsotg, 0, DAINTMSK);
 
 	dev_dbg(hsotg->dev, "EP0: DIEPCTL0=0x%08x, DOEPCTL0=0x%08x\n",
@@ -3472,6 +3603,10 @@
 	/* configure the core to support LPM */
 	dwc2_gadget_init_lpm(hsotg);
 
+	/* program GREFCLK register if needed */
+	if (using_desc_dma(hsotg) && hsotg->params.service_interval)
+		dwc2_gadget_program_ref_clk(hsotg);
+
 	/* must be at-least 3ms to allow bus to see disconnect */
 	mdelay(3);
 
@@ -3484,7 +3619,7 @@
 		dwc2_readl(hsotg, DOEPCTL0));
 }
 
-static void dwc2_hsotg_core_disconnect(struct dwc2_hsotg *hsotg)
+void dwc2_hsotg_core_disconnect(struct dwc2_hsotg *hsotg)
 {
 	/* set the soft-disconnect bit */
 	dwc2_set_bit(hsotg, DCTL, DCTL_SFTDISCON);
@@ -3493,7 +3628,8 @@
 void dwc2_hsotg_core_connect(struct dwc2_hsotg *hsotg)
 {
 	/* remove the soft-disconnect and let's go */
-	dwc2_clear_bit(hsotg, DCTL, DCTL_SFTDISCON);
+	if (!hsotg->role_sw || (dwc2_readl(hsotg, GOTGCTL) & GOTGCTL_BSESVLD))
+		dwc2_clear_bit(hsotg, DCTL, DCTL_SFTDISCON);
 }
 
 /**
@@ -3743,14 +3879,25 @@
 		for (idx = 1; idx < hsotg->num_of_eps; idx++) {
 			hs_ep = hsotg->eps_out[idx];
 			/* Proceed only unmasked ISOC EPs */
-			if ((BIT(idx) & ~daintmsk) || !hs_ep->isochronous)
+			if (BIT(idx) & ~daintmsk)
 				continue;
 
 			epctrl = dwc2_readl(hsotg, DOEPCTL(idx));
 
-			if (epctrl & DXEPCTL_EPENA) {
+			//ISOC Ep's only
+			if ((epctrl & DXEPCTL_EPENA) && hs_ep->isochronous) {
 				epctrl |= DXEPCTL_SNAK;
 				epctrl |= DXEPCTL_EPDIS;
+				dwc2_writel(hsotg, epctrl, DOEPCTL(idx));
+				continue;
+			}
+
+			//Non-ISOC EP's
+			if (hs_ep->halted) {
+				if (!(epctrl & DXEPCTL_EPENA))
+					epctrl |= DXEPCTL_EPENA;
+				epctrl |= DXEPCTL_EPDIS;
+				epctrl |= DXEPCTL_STALL;
 				dwc2_writel(hsotg, epctrl, DOEPCTL(idx));
 			}
 		}
@@ -3779,6 +3926,10 @@
 
 	if (gintsts & IRQ_RETRY_MASK && --retry_count > 0)
 		goto irq_retry;
+
+	/* Check WKUP_ALERT interrupt*/
+	if (hsotg->params.service_interval)
+		dwc2_gadget_wkup_alert_handler(hsotg);
 
 	spin_unlock(&hsotg->lock);
 
@@ -3818,8 +3969,26 @@
 					 __func__);
 		}
 	} else {
+		/* Mask GINTSTS_GOUTNAKEFF interrupt */
+		dwc2_hsotg_disable_gsint(hsotg, GINTSTS_GOUTNAKEFF);
+
 		if (!(dwc2_readl(hsotg, GINTSTS) & GINTSTS_GOUTNAKEFF))
 			dwc2_set_bit(hsotg, DCTL, DCTL_SGOUTNAK);
+
+		if (!using_dma(hsotg)) {
+			/* Wait for GINTSTS_RXFLVL interrupt */
+			if (dwc2_hsotg_wait_bit_set(hsotg, GINTSTS,
+						    GINTSTS_RXFLVL, 100)) {
+				dev_warn(hsotg->dev, "%s: timeout GINTSTS.RXFLVL\n",
+					 __func__);
+			} else {
+				/*
+				 * Pop GLOBAL OUT NAK status packet from RxFIFO
+				 * to assert GOUTNAKEFF interrupt
+				 */
+				dwc2_readl(hsotg, GRXSTSP);
+			}
+		}
 
 		/* Wait for global nak to take effect */
 		if (dwc2_hsotg_wait_bit_set(hsotg, GINTSTS,
@@ -4036,6 +4205,7 @@
 			ret = -ENOMEM;
 			goto error1;
 		}
+		epctrl &= ~(DXEPCTL_TXFNUM_LIMIT << DXEPCTL_TXFNUM_SHIFT);
 		hsotg->fifo_map |= 1 << fifo_index;
 		epctrl |= DXEPCTL_TXFNUM(fifo_index);
 		hs_ep->fifo_index = fifo_index;
@@ -4266,19 +4436,23 @@
 		epctl = dwc2_readl(hs, epreg);
 
 		if (value) {
-			epctl |= DXEPCTL_STALL;
+			/* Unmask GOUTNAKEFF interrupt */
+			dwc2_hsotg_en_gsint(hs, GINTSTS_GOUTNAKEFF);
+
+			if (!(dwc2_readl(hs, GINTSTS) & GINTSTS_GOUTNAKEFF))
+				dwc2_set_bit(hs, DCTL, DCTL_SGOUTNAK);
+			// STALL bit will be set in GOUTNAKEFF interrupt handler
 		} else {
 			epctl &= ~DXEPCTL_STALL;
 			xfertype = epctl & DXEPCTL_EPTYPE_MASK;
 			if (xfertype == DXEPCTL_EPTYPE_BULK ||
 			    xfertype == DXEPCTL_EPTYPE_INTERRUPT)
 				epctl |= DXEPCTL_SETD0PID;
+			dwc2_writel(hs, epctl, epreg);
 		}
-		dwc2_writel(hs, epctl, epreg);
 	}
 
 	hs_ep->halted = value;
-
 	return 0;
 }
 
@@ -4318,8 +4492,6 @@
  */
 static void dwc2_hsotg_init(struct dwc2_hsotg *hsotg)
 {
-	u32 trdtim;
-	u32 usbcfg;
 	/* unmask subset of endpoint interrupts */
 
 	dwc2_writel(hsotg, DIEPMSK_TIMEOUTMSK | DIEPMSK_AHBERRMSK |
@@ -4342,17 +4514,6 @@
 		dwc2_readl(hsotg, GNPTXFSIZ));
 
 	dwc2_hsotg_init_fifo(hsotg);
-
-	/* keep other bits untouched (so e.g. forced modes are not lost) */
-	usbcfg = dwc2_readl(hsotg, GUSBCFG);
-	usbcfg &= ~(GUSBCFG_TOUTCAL_MASK | GUSBCFG_PHYIF16 | GUSBCFG_SRPCAP |
-		GUSBCFG_HNPCAP | GUSBCFG_USBTRDTIM_MASK);
-
-	/* set the PLL on, remove the HNP/SRP and set the PHY */
-	trdtim = (hsotg->phyif == GUSBCFG_PHYIF8) ? 9 : 5;
-	usbcfg |= hsotg->phyif | GUSBCFG_TOUTCAL(7) |
-		(trdtim << GUSBCFG_USBTRDTIM_SHIFT);
-	dwc2_writel(hsotg, usbcfg, GUSBCFG);
 
 	if (using_dma(hsotg))
 		dwc2_set_bit(hsotg, GAHBCFG, GAHBCFG_DMA_EN);
@@ -4393,7 +4554,6 @@
 
 	WARN_ON(hsotg->driver);
 
-	driver->driver.bus = NULL;
 	hsotg->driver = driver;
 	hsotg->gadget.dev.of_node = hsotg->dev->of_node;
 	hsotg->gadget.speed = USB_SPEED_UNKNOWN;
@@ -4424,6 +4584,7 @@
 	hsotg->enabled = 0;
 	spin_unlock_irqrestore(&hsotg->lock, flags);
 
+	gadget->sg_supported = using_desc_dma(hsotg);
 	dev_info(hsotg->dev, "bound driver %s\n", driver->driver.name);
 
 	return 0;
@@ -4487,6 +4648,26 @@
 static int dwc2_hsotg_gadget_getframe(struct usb_gadget *gadget)
 {
 	return dwc2_hsotg_read_frameno(to_hsotg(gadget));
+}
+
+/**
+ * dwc2_hsotg_set_selfpowered - set if device is self/bus powered
+ * @gadget: The usb gadget state
+ * @is_selfpowered: Whether the device is self-powered
+ *
+ * Set if the device is self or bus powered.
+ */
+static int dwc2_hsotg_set_selfpowered(struct usb_gadget *gadget,
+				      int is_selfpowered)
+{
+	struct dwc2_hsotg *hsotg = to_hsotg(gadget);
+	unsigned long flags;
+
+	spin_lock_irqsave(&hsotg->lock, flags);
+	gadget->is_selfpowered = !!is_selfpowered;
+	spin_unlock_irqrestore(&hsotg->lock, flags);
+
+	return 0;
 }
 
 /**
@@ -4580,6 +4761,7 @@
 
 static const struct usb_gadget_ops dwc2_hsotg_gadget_ops = {
 	.get_frame	= dwc2_hsotg_gadget_getframe,
+	.set_selfpowered	= dwc2_hsotg_set_selfpowered,
 	.udc_start		= dwc2_hsotg_udc_start,
 	.udc_stop		= dwc2_hsotg_udc_stop,
 	.pullup                 = dwc2_hsotg_pullup,
@@ -5069,8 +5251,33 @@
 	val |= hsotg->params.lpm_clock_gating ? GLPMCFG_ENBLSLPM : 0;
 	val |= hsotg->params.hird_threshold << GLPMCFG_HIRD_THRES_SHIFT;
 	val |= hsotg->params.besl ? GLPMCFG_ENBESL : 0;
+	val |= GLPMCFG_LPM_REJECT_CTRL_CONTROL;
+	val |= GLPMCFG_LPM_ACCEPT_CTRL_ISOC;
 	dwc2_writel(hsotg, val, GLPMCFG);
 	dev_dbg(hsotg->dev, "GLPMCFG=0x%08x\n", dwc2_readl(hsotg, GLPMCFG));
+
+	/* Unmask WKUP_ALERT Interrupt */
+	if (hsotg->params.service_interval)
+		dwc2_set_bit(hsotg, GINTMSK2, GINTMSK2_WKUP_ALERT_INT_MSK);
+}
+
+/**
+ * dwc2_gadget_program_ref_clk - Program GREFCLK register in device mode
+ *
+ * @hsotg: Programming view of DWC_otg controller
+ *
+ */
+void dwc2_gadget_program_ref_clk(struct dwc2_hsotg *hsotg)
+{
+	u32 val = 0;
+
+	val |= GREFCLK_REF_CLK_MODE;
+	val |= hsotg->params.ref_clk_per << GREFCLK_REFCLKPER_SHIFT;
+	val |= hsotg->params.sof_cnt_wkup_alert <<
+	       GREFCLK_SOF_CNT_WKUP_ALERT_SHIFT;
+
+	dwc2_writel(hsotg, val, GREFCLK);
+	dev_dbg(hsotg->dev, "GREFCLK=0x%08x\n", dwc2_readl(hsotg, GREFCLK));
 }
 
 /**

--
Gitblit v1.6.2