Usb.h
Go to the documentation of this file.
00001 /*
00002  * Copyright 2009-2011 Oleg Mazurov, Circuits At Home, http://www.circuitsathome.com
00003  * MAX3421E USB host controller support
00004  *
00005  * Redistribution and use in source and binary forms, with or without
00006  * modification, are permitted provided that the following conditions
00007  * are met:
00008  * 1. Redistributions of source code must retain the above copyright
00009  *    notice, this list of conditions and the following disclaimer.
00010  * 2. Redistributions in binary form must reproduce the above copyright
00011  *    notice, this list of conditions and the following disclaimer in the
00012  *    documentation and/or other materials provided with the distribution.
00013  * 3. Neither the name of the authors nor the names of its contributors
00014  *    may be used to endorse or promote products derived from this software
00015  *    without specific prior written permission.
00016  *
00017  * THIS SOFTWARE IS PROVIDED BY THE REGENTS AND CONTRIBUTORS ``AS IS'' AND
00018  * ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00019  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00020  * ARE DISCLAIMED.  IN NO EVENT SHALL THE REGENTS OR CONTRIBUTORS BE LIABLE
00021  * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
00022  * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS
00023  * OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION)
00024  * HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00025  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY
00026  * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF
00027  * SUCH DAMAGE.
00028  */
00029 
00030 /* USB functions */
00031 #ifndef _usb_h_
00032 #define _usb_h_
00033 
00034 #include <Max3421e.h>
00035 #include "ch9.h"
00036 
00037 /* Common setup data constant combinations  */
00038 #define bmREQ_GET_DESCR     USB_SETUP_DEVICE_TO_HOST|USB_SETUP_TYPE_STANDARD|USB_SETUP_RECIPIENT_DEVICE     //get descriptor request type
00039 #define bmREQ_SET           USB_SETUP_HOST_TO_DEVICE|USB_SETUP_TYPE_STANDARD|USB_SETUP_RECIPIENT_DEVICE     //set request type for all but 'set feature' and 'set interface'
00040 #define bmREQ_CL_GET_INTF   USB_SETUP_DEVICE_TO_HOST|USB_SETUP_TYPE_CLASS|USB_SETUP_RECIPIENT_INTERFACE     //get interface request type
00041 /* HID requests */
00042 #define bmREQ_HIDOUT        USB_SETUP_HOST_TO_DEVICE|USB_SETUP_TYPE_CLASS|USB_SETUP_RECIPIENT_INTERFACE
00043 #define bmREQ_HIDIN         USB_SETUP_DEVICE_TO_HOST|USB_SETUP_TYPE_CLASS|USB_SETUP_RECIPIENT_INTERFACE 
00044 #define bmREQ_HIDREPORT     USB_SETUP_DEVICE_TO_HOST|USB_SETUP_TYPE_STANDARD|USB_SETUP_RECIPIENT_INTERFACE
00045 
00046 #define USB_XFER_TIMEOUT    5000    //USB transfer timeout in milliseconds, per section 9.2.6.1 of USB 2.0 spec
00047 #define USB_NAK_LIMIT       32000   //NAK limit for a transfer. o meand NAKs are not counted
00048 #define USB_RETRY_LIMIT     3       //retry limit for a transfer
00049 #define USB_SETTLE_DELAY    200     //settle delay in milliseconds
00050 #define USB_NAK_NOWAIT      1       //used in Richard's PS2/Wiimote code
00051 
00052 #define USB_NUMDEVICES  2           //number of USB devices
00053 
00054 /* USB state machine states */
00055 
00056 #define USB_STATE_MASK                                      0xf0
00057 
00058 #define USB_STATE_DETACHED                                  0x10
00059 #define USB_DETACHED_SUBSTATE_INITIALIZE                    0x11        
00060 #define USB_DETACHED_SUBSTATE_WAIT_FOR_DEVICE               0x12
00061 #define USB_DETACHED_SUBSTATE_ILLEGAL                       0x13
00062 #define USB_ATTACHED_SUBSTATE_SETTLE                        0x20
00063 #define USB_ATTACHED_SUBSTATE_RESET_DEVICE                  0x30    
00064 #define USB_ATTACHED_SUBSTATE_WAIT_RESET_COMPLETE           0x40
00065 #define USB_ATTACHED_SUBSTATE_WAIT_SOF                      0x50
00066 #define USB_ATTACHED_SUBSTATE_GET_DEVICE_DESCRIPTOR_SIZE    0x60
00067 #define USB_STATE_ADDRESSING                                0x70
00068 #define USB_STATE_CONFIGURING                               0x80
00069 #define USB_STATE_RUNNING                                   0x90
00070 #define USB_STATE_ERROR                                     0xa0
00071 
00072 // byte usb_task_state = USB_DETACHED_SUBSTATE_INITIALIZE
00073 
00074 /* USB Setup Packet Structure   */
00075 typedef struct {
00076     union {                          // offset   description
00077         byte bmRequestType;         //   0      Bit-map of request type
00078         struct {
00079             byte    recipient:  5;  //          Recipient of the request
00080             byte    type:       2;  //          Type of request
00081             byte    direction:  1;  //          Direction of data X-fer
00082         };
00083     }ReqType_u;
00084     byte    bRequest;               //   1      Request
00085     union {
00086         unsigned int    wValue;             //   2      Depends on bRequest
00087         struct {
00088         byte    wValueLo;
00089         byte    wValueHi;
00090         };
00091     }wVal_u;
00092     unsigned int    wIndex;                 //   4      Depends on bRequest
00093     unsigned int    wLength;                //   6      Depends on bRequest
00094 } SETUP_PKT, *PSETUP_PKT;
00095 
00096 /* Endpoint information structure               */
00097 /* bToggle of endpoint 0 initialized to 0xff    */
00098 /* during enumeration bToggle is set to 00      */
00099 typedef struct {        
00100     byte epAddr;        //copy from endpoint descriptor. Bit 7 indicates direction ( ignored for control endpoints )
00101     byte Attr;          // Endpoint transfer type.
00102     unsigned int MaxPktSize;    // Maximum packet size.
00103     byte Interval;      // Polling interval in frames.
00104     byte sndToggle;     //last toggle value, bitmask for HCTL toggle bits
00105     byte rcvToggle;     //last toggle value, bitmask for HCTL toggle bits
00106     /* not sure if both are necessary */
00107 } EP_RECORD;
00108 /* device record structure */
00109 typedef struct {
00110     EP_RECORD* epinfo;      //device endpoint information
00111     byte devclass;          //device class    
00112 } DEV_RECORD;
00113 
00114 
00115 
00116 class USB : public MAX3421E {
00117 //data structures    
00118 /* device table. Filled during enumeration              */
00119 /* index corresponds to device address                  */
00120 /* each entry contains pointer to endpoint structure    */
00121 /* and device class to use in various places            */             
00122 //DEV_RECORD devtable[ USB_NUMDEVICES + 1 ];
00123 //EP_RECORD dev0ep;         //Endpoint data structure used during enumeration for uninitialized device
00124 
00125 //byte usb_task_state;
00126 
00127     public:
00128         USB( void );
00129         byte getUsbTaskState( void );
00130         void setUsbTaskState( byte state );
00131         EP_RECORD* getDevTableEntry( byte addr, byte ep );
00132         void setDevTableEntry( byte addr, EP_RECORD* eprecord_ptr );
00133         byte ctrlReq( byte addr, byte ep, byte bmReqType, byte bRequest, byte wValLo, byte wValHi, unsigned int wInd, unsigned int nbytes, char* dataptr, unsigned int nak_limit = USB_NAK_LIMIT );
00134         /* Control requests */
00135         byte getDevDescr( byte addr, byte ep, unsigned int nbytes, char* dataptr, unsigned int nak_limit = USB_NAK_LIMIT );
00136         byte getConfDescr( byte addr, byte ep, unsigned int nbytes, byte conf, char* dataptr, unsigned int nak_limit = USB_NAK_LIMIT );
00137         byte getStrDescr( byte addr, byte ep, unsigned int nbytes, byte index, unsigned int langid, char* dataptr, unsigned int nak_limit = USB_NAK_LIMIT );
00138         byte setAddr( byte oldaddr, byte ep, byte newaddr, unsigned int nak_limit = USB_NAK_LIMIT );
00139         byte setConf( byte addr, byte ep, byte conf_value, unsigned int nak_limit = USB_NAK_LIMIT );
00140         
00141         byte setProto( byte addr, byte ep, byte interface, byte protocol, unsigned int nak_limit = USB_NAK_LIMIT );
00142         byte getProto( byte addr, byte ep, byte interface, char* dataptr, unsigned int nak_limit = USB_NAK_LIMIT );
00143         byte getReportDescr( byte addr, byte ep, unsigned int nbytes, char* dataptr, unsigned int nak_limit = USB_NAK_LIMIT );
00144         byte setReport( byte addr, byte ep, unsigned int nbytes, byte interface, byte report_type, byte report_id, char* dataptr, unsigned int nak_limit = USB_NAK_LIMIT );
00145               byte getReport( byte addr, byte ep, unsigned int nbytes, byte interface, byte report_type, byte report_id, char* dataptr, unsigned int nak_limit = USB_NAK_LIMIT );
00146         byte getIdle( byte addr, byte ep, byte interface, byte reportID, char* dataptr, unsigned int nak_limit = USB_NAK_LIMIT );
00147         byte setIdle( byte addr, byte ep, byte interface, byte reportID, byte duration, unsigned int nak_limit = USB_NAK_LIMIT );
00148         
00149         byte ctrlData( byte addr, byte ep, unsigned int nbytes, char* dataptr, boolean direction, unsigned int nak_limit = USB_NAK_LIMIT );
00150         byte ctrlStatus( byte ep, boolean direction, unsigned int nak_limit = USB_NAK_LIMIT );
00151         byte inTransfer( byte addr, byte ep, unsigned int nbytes, char* data, unsigned int nak_limit = USB_NAK_LIMIT );
00152                 int newInTransfer( byte addr, byte ep, unsigned int nbytes, char* data, unsigned int nak_limit  = USB_NAK_LIMIT);
00153         byte outTransfer( byte addr, byte ep, unsigned int nbytes, char* data, unsigned int nak_limit = USB_NAK_LIMIT );
00154         byte dispatchPkt( byte token, byte ep, unsigned int nak_limit = USB_NAK_LIMIT );
00155         void Task( void );
00156     private:
00157         void init();
00158 };
00159 
00160 //get device descriptor
00161 inline byte USB::getDevDescr( byte addr, byte ep, unsigned int nbytes, char* dataptr, unsigned int nak_limit ) {
00162     return( ctrlReq( addr, ep, bmREQ_GET_DESCR, USB_REQUEST_GET_DESCRIPTOR, 0x00, USB_DESCRIPTOR_DEVICE, 0x0000, nbytes, dataptr, nak_limit ));
00163 }
00164 //get configuration descriptor  
00165 inline byte USB::getConfDescr( byte addr, byte ep, unsigned int nbytes, byte conf, char* dataptr, unsigned int nak_limit ) {
00166         return( ctrlReq( addr, ep, bmREQ_GET_DESCR, USB_REQUEST_GET_DESCRIPTOR, conf, USB_DESCRIPTOR_CONFIGURATION, 0x0000, nbytes, dataptr, nak_limit ));
00167 }
00168 //get string descriptor
00169 inline byte USB::getStrDescr( byte addr, byte ep, unsigned int nbytes, byte index, unsigned int langid, char* dataptr, unsigned int nak_limit ) {
00170     return( ctrlReq( addr, ep, bmREQ_GET_DESCR, USB_REQUEST_GET_DESCRIPTOR, index, USB_DESCRIPTOR_STRING, langid, nbytes, dataptr, nak_limit ));
00171 }
00172 //set address 
00173 inline byte USB::setAddr( byte oldaddr, byte ep, byte newaddr, unsigned int nak_limit ) {
00174     return( ctrlReq( oldaddr, ep, bmREQ_SET, USB_REQUEST_SET_ADDRESS, newaddr, 0x00, 0x0000, 0x0000, NULL, nak_limit ));
00175 }
00176 //set configuration
00177 inline byte USB::setConf( byte addr, byte ep, byte conf_value, unsigned int nak_limit ) {
00178     return( ctrlReq( addr, ep, bmREQ_SET, USB_REQUEST_SET_CONFIGURATION, conf_value, 0x00, 0x0000, 0x0000, NULL, nak_limit ));         
00179 }
00180 //class requests
00181 inline byte USB::setProto( byte addr, byte ep, byte interface, byte protocol, unsigned int nak_limit ) {
00182         return( ctrlReq( addr, ep, bmREQ_HIDOUT, HID_REQUEST_SET_PROTOCOL, protocol, 0x00, interface, 0x0000, NULL, nak_limit ));
00183 }
00184 inline byte USB::getProto( byte addr, byte ep, byte interface, char* dataptr, unsigned int nak_limit ) {
00185         return( ctrlReq( addr, ep, bmREQ_HIDIN, HID_REQUEST_GET_PROTOCOL, 0x00, 0x00, interface, 0x0001, dataptr, nak_limit ));        
00186 }
00187 //get HID report descriptor 
00188 inline byte USB::getReportDescr( byte addr, byte ep, unsigned int nbytes, char* dataptr, unsigned int nak_limit ) {
00189         return( ctrlReq( addr, ep, bmREQ_HIDREPORT, USB_REQUEST_GET_DESCRIPTOR, 0x00, HID_DESCRIPTOR_REPORT, 0x0000, nbytes, dataptr, nak_limit ));
00190 }
00191 inline byte USB::setReport( byte addr, byte ep, unsigned int nbytes, byte interface, byte report_type, byte report_id, char* dataptr, unsigned int nak_limit ) {
00192     return( ctrlReq( addr, ep, bmREQ_HIDOUT, HID_REQUEST_SET_REPORT, report_id, report_type, interface, nbytes, dataptr, nak_limit ));
00193 }
00194 inline byte USB::getReport( byte addr, byte ep, unsigned int nbytes, byte interface, byte report_type, byte report_id, char* dataptr, unsigned int nak_limit ) { // ** RI 04/11/09
00195     return( ctrlReq( addr, ep, bmREQ_HIDIN, HID_REQUEST_GET_REPORT, report_id, report_type, interface, nbytes, dataptr, nak_limit ));
00196 }
00197 /* returns one byte of data in dataptr */
00198 inline byte USB::getIdle( byte addr, byte ep, byte interface, byte reportID, char* dataptr, unsigned int nak_limit ) {
00199         return( ctrlReq( addr, ep, bmREQ_HIDIN, HID_REQUEST_GET_IDLE, reportID, 0, interface, 0x0001, dataptr, nak_limit ));    
00200 }
00201 inline byte USB::setIdle( byte addr, byte ep, byte interface, byte reportID, byte duration, unsigned int nak_limit ) {
00202            return( ctrlReq( addr, ep, bmREQ_HIDOUT, HID_REQUEST_SET_IDLE, reportID, duration, interface, 0x0000, NULL, nak_limit ));
00203           }
00204 #endif //_usb_h_


rosserial_adk_demo
Author(s): Adam Stambler
autogenerated on Mon Dec 2 2013 12:02:02