From a3170f4c8e9d06966bb5d3b0c29cddd03d93cdcb Mon Sep 17 00:00:00 2001 From: patacongo Date: Thu, 9 Oct 2008 15:15:00 +0000 Subject: Last option in configure; ep address in ep struct git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@1011 42af7a65-404d-4744-a932-0658087f49c3 --- nuttx/arch/arm/src/dm320/dm320_usbdev.c | 72 ++++++++++++++-------- nuttx/arch/arm/src/lpc214x/lpc214x_usbdev.c | 96 +++++++++++++++++++++-------- 2 files changed, 117 insertions(+), 51 deletions(-) diff --git a/nuttx/arch/arm/src/dm320/dm320_usbdev.c b/nuttx/arch/arm/src/dm320/dm320_usbdev.c index a4e57a9ed..1411a4412 100644 --- a/nuttx/arch/arm/src/dm320/dm320_usbdev.c +++ b/nuttx/arch/arm/src/dm320/dm320_usbdev.c @@ -110,13 +110,14 @@ #define DM320_TRACEERR_NOTCONFIGURED 0x000b #define DM320_TRACEERR_NULLPACKET 0x000c #define DM320_TRACEERR_NULLREQUEST 0x000d -#define DM320_TRACEERR_STALLEDCLRFEATURE 0x000e -#define DM320_TRACEERR_STALLEDISPATCH 0x000f -#define DM320_TRACEERR_STALLEDGETST 0x0010 -#define DM320_TRACEERR_STALLEDGETSTEP 0x0011 -#define DM320_TRACEERR_STALLEDGETSTRECIP 0x0012 -#define DM320_TRACEERR_STALLEDREQUEST 0x0013 -#define DM320_TRACEERR_STALLEDSETFEATURE 0x0014 +#define DM320_TRACEERR_REQABORTED 0x000e +#define DM320_TRACEERR_STALLEDCLRFEATURE 0x000f +#define DM320_TRACEERR_STALLEDISPATCH 0x0010 +#define DM320_TRACEERR_STALLEDGETST 0x0011 +#define DM320_TRACEERR_STALLEDGETSTEP 0x0012 +#define DM320_TRACEERR_STALLEDGETSTRECIP 0x0013 +#define DM320_TRACEERR_STALLEDREQUEST 0x0014 +#define DM320_TRACEERR_STALLEDSETFEATURE 0x0015 /* Trace interrupt codes */ @@ -208,7 +209,6 @@ struct dm320_ep_s struct dm320_req_s *head; /* Request list for this endpoint */ struct dm320_req_s *tail; ubyte epphy; /* Physical EP address/index */ - ubyte eplog; /* Logical, configured EP address */ ubyte stalled:1; /* Endpoint is halted */ ubyte in:1; /* Endpoint is IN only */ ubyte halted:1; /* Endpoint feature halted */ @@ -291,7 +291,7 @@ static int dm320_ep0write(ubyte *buf, uint16 nbytes); static int dm320_epwrite(ubyte epphy, ubyte *buf, uint16 nbytes); static int dm320_epread(ubyte epphy, ubyte *buf, uint16 nbytes); static inline void dm320_abortrequest(struct dm320_ep_s *privep, - struct dm320_req_s *privreq, sint16 result) + struct dm320_req_s *privreq, sint16 result); static void dm320_reqcomplete(struct dm320_ep_s *privep, sint16 result); static int dm320_wrrequest(struct dm320_ep_s *privep); static int dm320_rdrequest(struct dm320_ep_s *privep); @@ -317,7 +317,7 @@ static void dm320_ctrlinitialize(struct dm320_usbdev_s *priv); /* Endpoint methods */ static int dm320_epconfigure(FAR struct usbdev_ep_s *ep, - const struct usb_epdesc_s *desc); + const struct usb_epdesc_s *desc, boolean last); static int dm320_epdisable(FAR struct usbdev_ep_s *ep); static FAR struct usbdev_req_s *dm320_epallocreq(FAR struct usbdev_ep_s *ep); static void dm320_epfreereq(FAR struct usbdev_ep_s *ep, FAR struct usbdev_req_s *req); @@ -861,7 +861,7 @@ static inline void dm320_abortrequest(struct dm320_ep_s *privep, struct dm320_req_s *privreq, sint16 result) { - usbtrace(TRACE_DEVERROR(LPC214X_TRACEERR_REQABORTED), (uint16)privep->epphy); + usbtrace(TRACE_DEVERROR(DM320_TRACEERR_REQABORTED), (uint16)privep->epphy); /* Save the result in the request structure */ @@ -1114,7 +1114,7 @@ static struct dm320_ep_s *dm320_epfindbyaddr(struct dm320_usbdev_s *priv, /* Same logical endpoint number? (includes direction bit) */ - if (eplog == privep->eplog) + if (eplog == privep->ep.eplog) { /* Return endpoint found */ @@ -1857,16 +1857,25 @@ static void dm320_ctrlinitialize(FAR struct dm320_usbdev_s *priv) * Description: * Configure endpoint, making it usable * + * Input Parameters: + * ep - the struct usbdev_ep_s instance obtained from allocep() + * desc - A struct usb_epdesc_s instance describing the endpoint + * last - TRUE if this this last endpoint to be configured. Some hardware + * needs to take special action when all of the endpoints have been + * configured. + * *******************************************************************************/ -static int dm320_epconfigure(FAR struct usbdev_ep_s *ep, FAR const struct usb_epdesc_s *desc) +static int dm320_epconfigure(FAR struct usbdev_ep_s *ep, + FAR const struct usb_epdesc_s *desc, + boolean last) { - struct dm320_ep_s *privep = (struct dm320_ep_s *)ep; + FAR struct dm320_ep_s *privep = (FAR struct dm320_ep_s *)ep; /* Retain what we need from the descriptor */ usbtrace(TRACE_EPCONFIGURE, privep->epphy); - privep->eplog = desc->addr; + DEBUGASSERT(desc->addr == ep->eplog); return OK; } @@ -2031,14 +2040,14 @@ static int dm320_epsubmit(FAR struct usbdev_ep_s *ep, FAR struct usbdev_req_s *r { usbtrace(TRACE_DEVERROR(DM320_TRACEERR_NULLPACKET), 0); dm320_putreg8(dm320_getreg8(DM320_USB_PERTXCSR1) | USB_TXCSR1_TXPKTRDY, DM320_USB_PERTXCSR1); - dm320_abortcomplete(privep, OK); + dm320_abortrequest(privep, req, OK); } /* If we are stalled, then drop all requests on the floor */ else if (privep->stalled) { - lpc214x_abortrequest(privep, privreq, -EBUSY); + dm320_abortrequest(privep, privreq, -EBUSY); ret = -EBUSY; } @@ -2049,7 +2058,7 @@ static int dm320_epsubmit(FAR struct usbdev_ep_s *ep, FAR struct usbdev_req_s *r /* Nothing to transfer -- exit success, with zero bytes transferred */ usbtrace(TRACE_COMPLETE(privep->epphy), privreq->req.xfrd); - dm320_abortcomplete(privep, OK); + dm320_abortrequest(privep, req, OK); } /* Handle IN (device-to-host) requests */ @@ -2127,15 +2136,16 @@ static int dm320_epcancel(struct usbdev_ep_s *ep, FAR struct usbdev_req_s *req) * Allocate an endpoint matching the parameters * * Input Parameters: - * epphy - 7-bit physical endpoint number (without diretion bit). Zero means - * that any endpoint matching the other requirements will suffice. + * eplog - 7-bit logical endpoint number (direction bit ignored). Zero means + * that any endpoint matching the other requirements will suffice. The + * assigned endpoint can be found in the eplog field. * in - TRUE: IN (device-to-host) endpoint requested * eptype - Endpoint type. One of {USB_EP_ATTR_XFER_ISOC, USB_EP_ATTR_XFER_BULK, * USB_EP_ATTR_XFER_INT} * *******************************************************************************/ -static FAR struct usbdev_ep_s *dm320_allocep(FAR struct usbdev_s *dev, ubyte epphy, +static FAR struct usbdev_ep_s *dm320_allocep(FAR struct usbdev_s *dev, ubyte eplog, boolean in, ubyte eptype) { FAR struct dm320_usbdev_s *priv = (FAR struct dm320_usbdev_s *)dev; @@ -2143,13 +2153,17 @@ static FAR struct usbdev_ep_s *dm320_allocep(FAR struct usbdev_s *dev, ubyte epp usbtrace(TRACE_DEVALLOCEP, 0); + /* Ignore any direction bits in the logical address */ + + eplog = USB_EPNO(eplog); + /* Check all endpoints (except EP0) */ for (ndx = 1; ndx < DM320_NENDPOINTS; ndx++) { /* Does this match the endpoint number (if one was provided?) */ - if (epphy != 0 && epphy != priv->eplist[ndx].epphy) + if (eplog != 0 && eplog != USB_EPNO(priv->eplist[ndx].ep.eplog)) { continue; } @@ -2387,11 +2401,17 @@ void up_usbinitialize(void) { /* Set up the standard stuff */ - privep = &priv->eplist[i]; + privep = &priv->eplist[i]; memset(privep, 0, sizeof(struct dm320_ep_s)); - privep->ep.ops = &g_epops; - privep->dev = priv; - privep->epphy = i; + privep->ep.ops = &g_epops; + privep->dev = priv; + + /* The index, i, is the physical endpoint address; Map this + * to a logical endpoint address usable by the class driver. + */ + + privep->epphy = i; + privep->ep.eplog = g_epinfo[i].addr; /* Setup the endpoint-specific stuff */ diff --git a/nuttx/arch/arm/src/lpc214x/lpc214x_usbdev.c b/nuttx/arch/arm/src/lpc214x/lpc214x_usbdev.c index 8edd83651..0db5437a4 100644 --- a/nuttx/arch/arm/src/lpc214x/lpc214x_usbdev.c +++ b/nuttx/arch/arm/src/lpc214x/lpc214x_usbdev.c @@ -241,6 +241,9 @@ #define LPC214X_EPPHYIN(epphy) (((epphy)&1)!=0) #define LPC214X_EPPHYOUT(epphy) (((epphy)&1)==0) +#define LPC214X_EPPHYIN2LOG(epphy) (((ubyte)(epphy)>>1)|USB_DIR_IN) +#define LPC214X_EPPHYOUT2LOG(epphy) (((ubyte)(epphy)>>1)|USB_DIR_OUT) + /* Each endpoint has somewhat different characteristics */ #define LPC214X_EPALLSET (0xffffffff) /* All endpoints */ @@ -304,7 +307,6 @@ struct lpc214x_ep_s struct lpc214x_req_s *head; /* Request list for this endpoint */ struct lpc214x_req_s *tail; ubyte epphy; /* Physical EP address */ - ubyte eplog; /* Configured logical EP address */ ubyte stalled:1; /* Endpoint is halted */ ubyte halted:1; /* Endpoint feature halted */ ubyte txnullpkt:1; /* Null packet needed at end of transfer */ @@ -433,7 +435,7 @@ static void lpc214x_dmadisable(ubyte epphy); /* Endpoint operations *********************************************************/ static int lpc214x_epconfigure(FAR struct usbdev_ep_s *ep, - const struct usb_epdesc_s *desc); + const struct usb_epdesc_s *desc, boolean last); static int lpc214x_epdisable(FAR struct usbdev_ep_s *ep); static FAR struct usbdev_req_s *lpc214x_epallocreq(FAR struct usbdev_ep_s *ep); static void lpc214x_epfreereq(FAR struct usbdev_ep_s *ep, @@ -1202,7 +1204,7 @@ static struct lpc214x_ep_s *lpc214x_epfindbyaddr(struct lpc214x_usbdev_s *priv, /* Same logical endpoint number? (includes direction bit) */ - if (eplog == privep->eplog) + if (eplog == privep->ep.eplog) { /* Return endpoint found */ @@ -2447,19 +2449,24 @@ static void lpc214x_dmadisable(ubyte epphy) * Description: * Configure endpoint, making it usable * + * Input Parameters: + * ep - the struct usbdev_ep_s instance obtained from allocep() + * desc - A struct usb_epdesc_s instance describing the endpoint + * last - TRUE if this this last endpoint to be configured. Some hardware + * needs to take special action when all of the endpoints have been + * configured. + * *******************************************************************************/ static int lpc214x_epconfigure(FAR struct usbdev_ep_s *ep, - FAR const struct usb_epdesc_s *desc) + FAR const struct usb_epdesc_s *desc, + boolean last) { FAR struct lpc214x_ep_s *privep = (FAR struct lpc214x_ep_s *)ep; uint32 inten; usbtrace(TRACE_EPCONFIGURE, privep->epphy); - - /* Save the logical EP number (so that we can map logical to physical later) */ - - privep->eplog = desc->addr; + DEBUGASSERT(desc->addr == ep->eplog); /* Realize the endpoint */ @@ -2477,10 +2484,19 @@ static int lpc214x_epconfigure(FAR struct usbdev_ep_s *ep, #else /* Enable Ep interrupt (R/W) */ - inten = lpc214x_getreg(LPC214X_USBDEV_EPINTEN); - inten |= (1 << privep->epphy); - lpc214x_putreg(inten, LPC214X_USBDEV_EPINTEN); + inten = lpc214x_getreg(LPC214X_USBDEV_EPINTEN); + inten |= (1 << privep->epphy); + lpc214x_putreg(inten, LPC214X_USBDEV_EPINTEN); #endif + + /* If all of the endpoints have been configured, then tell the USB controller + * to enabled normal activity on all realized endpoints. + */ + + if (last) + { + lpc214x_usbcmd(CMD_USB_DEV_CONFIG, 1); + } return OK; } @@ -2776,35 +2792,52 @@ static int lpc214x_epstall(FAR struct usbdev_ep_s *ep, boolean resume) * Allocate an endpoint matching the parameters. * * Input Parameters: - * epphy - 7-bit physical endpoint number (without direction bit). Zero means - * that any endpoint matching the other requirements will suffice. + * eplog - 7-bit logical endpoint number (direction bit ignored). Zero means + * that any endpoint matching the other requirements will suffice. The + * assigned endpoint can be found in the eplog field. * in - TRUE: IN (device-to-host) endpoint requested * eptype - Endpoint type. One of {USB_EP_ATTR_XFER_ISOC, USB_EP_ATTR_XFER_BULK, * USB_EP_ATTR_XFER_INT} * *******************************************************************************/ -static FAR struct usbdev_ep_s *lcp214x_allocep(FAR struct usbdev_s *dev, ubyte epphy, +static FAR struct usbdev_ep_s *lcp214x_allocep(FAR struct usbdev_s *dev, ubyte eplog, boolean in, ubyte eptype) { FAR struct lpc214x_usbdev_s *priv = (FAR struct lpc214x_usbdev_s *)dev; - uint32 epset = LPC214X_EPALLSET; + uint32 epset = LPC214X_EPALLSET & ~LPC214X_EPCTRLSET; irqstate_t flags; int epndx = 0; - usbtrace(TRACE_DEVALLOCEP, (uint16)epphy); + usbtrace(TRACE_DEVALLOCEP, (uint16)eplog); + + /* Ignore any direction bits in the logical address */ - /* epphy=0 means that any endpoint will do */ + eplog = USB_EPNO(eplog); - if (epphy > 0) + /* A logical address of 0 means that any endpoint will do */ + + if (eplog > 0) { - if (epphy >= LPC214X_NLOGENDPOINTS) + /* Otherwise, we will return the endpoint structure only for the requested + * 'logical' endpoint. All of the other checks will still be performed. + * + * First, verify that the logical endpoint is in the range supported by + * by the hardware. + */ + + if (eplog >= LPC214X_NLOGENDPOINTS) { - usbtrace(TRACE_DEVERROR(LPC214X_TRACEERR_BADEPNO), (uint16)epphy); - return NULL; + usbtrace(TRACE_DEVERROR(LPC214X_TRACEERR_BADEPNO), (uint16)eplog); + return NULL; } - epset &= 3 << epphy; + /* Convert the logical address to a physical OUT endpoint address and + * remove all of the candidate endpoints from the bitset except for the + * the IN/OUT pair for this logical address. + */ + + epset &= 3 << (eplog << 1); } /* Get the subset matching the requested direction */ @@ -2857,9 +2890,9 @@ static FAR struct usbdev_ep_s *lcp214x_allocep(FAR struct usbdev_s *dev, ubyte e uint32 bit = 1 << epndx; if ((epset & bit) != 0) { - /* Mark the endpoint no longer available */ + /* Mark the IN/OUT endpoint no longer available */ - priv->epavail &= ~bit; + priv->epavail &= ~(3 << (bit & ~1)); irqrestore(flags); /* And return the pointer to the standard endpoint structure */ @@ -2872,7 +2905,7 @@ static FAR struct usbdev_ep_s *lcp214x_allocep(FAR struct usbdev_s *dev, ubyte e irqrestore(flags); } - usbtrace(TRACE_DEVERROR(LPC214X_TRACEERR_NOEP), (uint16)epphy); + usbtrace(TRACE_DEVERROR(LPC214X_TRACEERR_NOEP), (uint16)eplog); return NULL; } @@ -3050,7 +3083,20 @@ void up_usbinitialize(void) */ priv->eplist[i].ep.ops = &g_epops; priv->eplist[i].dev = priv; + + /* The index, i, is the physical endpoint address; Map this + * to a logical endpoint address usable by the class driver. + */ + priv->eplist[i].epphy = i; + if (LPC214X_EPPHYIN(i)) + { + priv->eplist[i].ep.eplog = LPC214X_EPPHYIN2LOG(i); + } + else + { + priv->eplist[i].ep.eplog = LPC214X_EPPHYOUT2LOG(i); + } /* The maximum packet size may depend on the type of endpoint */ -- cgit v1.2.3