Max3421e.cpp
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 /* MAX3421E USB host controller support */
00031 
00032 #include "Max3421e.h"
00033 // #include "Max3421e_constants.h"
00034 
00035 static byte vbusState;
00036 
00037 /* Functions    */
00038 
00039 #define INT             PE6
00040 #define INT_PORT        PORTE
00041 #define INT_DDR         DDRE
00042 #define INT_PIN         PINE
00043 
00044 #define RST             PJ2
00045 #define RST_PORT        PORTJ
00046 #define RST_DDR         DDRJ
00047 #define RST_PIN         PINJ
00048 
00049 #define GPX             PJ3
00050 #define GPX_PORT        PORTJ
00051 #define GPX_DDR         DDRJ
00052 #define GPX_PIN         PINJ
00053 
00054 
00055 void MAX3421E::setRST(uint8_t val)
00056 {
00057         if (val == LOW)
00058                 RST_PORT &= ~_BV(RST);
00059         else
00060                 RST_PORT |= _BV(RST);
00061 }
00062 
00063 uint8_t MAX3421E::readINT(void)
00064 {
00065         return INT_PIN & _BV(INT) ? HIGH : LOW;
00066 }
00067 
00068 uint8_t MAX3421E::readGPX(void)
00069 {
00070         // return GPX_PIN & _BV(GPX) ? HIGH : LOW;
00071         return LOW;
00072 }
00073 
00074 
00075 void MAX3421E::pinInit(void)
00076 {
00077         INT_DDR &= ~_BV(INT);
00078         RST_DDR |= _BV(RST);
00079         digitalWrite(MAX_SS,HIGH);   
00080         setRST(HIGH);
00081 }
00082 
00083 
00084 /* Constructor */
00085 MAX3421E::MAX3421E()
00086 {
00087     spi_init();  
00088         pinInit();
00089 }
00090 
00091 byte MAX3421E::getVbusState( void )
00092 { 
00093     return( vbusState );
00094 }
00095 /* initialization */
00096 //void MAX3421E::init()
00097 //{
00098 //    /* setup pins */
00099 //    pinMode( MAX_INT, INPUT);
00100 //    pinMode( MAX_GPX, INPUT );
00101 //    pinMode( MAX_SS, OUTPUT );
00102 //    //pinMode( BPNT_0, OUTPUT );
00103 //    //pinMode( BPNT_1, OUTPUT );
00104 //    //digitalWrite( BPNT_0, LOW );
00105 //    //digitalWrite( BPNT_1, LOW );
00106 //    Deselect_MAX3421E;              
00107 //    pinMode( MAX_RESET, OUTPUT );
00108 //    digitalWrite( MAX_RESET, HIGH );  //release MAX3421E from reset
00109 //}
00110 //byte MAX3421E::getVbusState( void )
00111 //{
00112 //    return( vbusState );
00113 //}
00114 //void MAX3421E::toggle( byte pin )
00115 //{
00116 //    digitalWrite( pin, HIGH );
00117 //    digitalWrite( pin, LOW );
00118 //}
00119 /* Single host register write   */
00120 void MAX3421E::regWr( byte reg, byte val)
00121 {
00122       digitalWrite(MAX_SS,LOW);
00123       SPDR = ( reg | 0x02 );
00124       while(!( SPSR & ( 1 << SPIF )));
00125       SPDR = val;
00126       while(!( SPSR & ( 1 << SPIF )));
00127       digitalWrite(MAX_SS,HIGH);
00128       return;
00129 }
00130 /* multiple-byte write */
00131 /* returns a pointer to a memory position after last written */
00132 char * MAX3421E::bytesWr( byte reg, byte nbytes, char * data )
00133 {
00134     digitalWrite(MAX_SS,LOW);
00135     SPDR = ( reg | 0x02 );
00136     while( nbytes-- ) {
00137       while(!( SPSR & ( 1 << SPIF )));  //check if previous byte was sent
00138       SPDR = ( *data );               // send next data byte
00139       data++;                         // advance data pointer
00140     }
00141     while(!( SPSR & ( 1 << SPIF )));
00142     digitalWrite(MAX_SS,HIGH);
00143     return( data );
00144 }
00145 /* GPIO write. GPIO byte is split between 2 registers, so two writes are needed to write one byte */
00146 /* GPOUT bits are in the low nibble. 0-3 in IOPINS1, 4-7 in IOPINS2 */
00147 /* upper 4 bits of IOPINS1, IOPINS2 are read-only, so no masking is necessary */
00148 void MAX3421E::gpioWr( byte val )
00149 {
00150     regWr( rIOPINS1, val );
00151     val = val >>4;
00152     regWr( rIOPINS2, val );
00153     
00154     return;     
00155 }
00156 /* Single host register read        */
00157 byte MAX3421E::regRd( byte reg )    
00158 {
00159   byte tmp;
00160     digitalWrite(MAX_SS,LOW);
00161     SPDR = reg;
00162     while(!( SPSR & ( 1 << SPIF )));
00163     SPDR = 0; //send empty byte
00164     while(!( SPSR & ( 1 << SPIF )));
00165     digitalWrite(MAX_SS,HIGH); 
00166     return( SPDR );
00167 }
00168 /* multiple-bytes register read                             */
00169 /* returns a pointer to a memory position after last read   */
00170 char * MAX3421E::bytesRd ( byte reg, byte nbytes, char  * data )
00171 {
00172     digitalWrite(MAX_SS,LOW);
00173     SPDR = reg;      
00174     while(!( SPSR & ( 1 << SPIF )));    //wait
00175     while( nbytes ) {
00176       SPDR = 0; //send empty byte
00177       nbytes--;
00178       while(!( SPSR & ( 1 << SPIF )));
00179       *data = SPDR;
00180       data++;
00181     }
00182     digitalWrite(MAX_SS,HIGH);
00183     return( data );   
00184 }
00185 /* GPIO read. See gpioWr for explanation */
00186 /* GPIN pins are in high nibbles of IOPINS1, IOPINS2    */
00187 byte MAX3421E::gpioRd( void )
00188 {
00189  byte tmpbyte = 0;
00190     tmpbyte = regRd( rIOPINS2 );            //pins 4-7
00191     tmpbyte &= 0xf0;                        //clean lower nibble
00192     tmpbyte |= ( regRd( rIOPINS1 ) >>4 ) ;  //shift low bits and OR with upper from previous operation. Upper nibble zeroes during shift, at least with this compiler
00193     return( tmpbyte );
00194 }
00195 /* reset MAX3421E using chip reset bit. SPI configuration is not affected   */
00196 boolean MAX3421E::reset()
00197 {
00198   byte tmp = 0;
00199     regWr( rUSBCTL, bmCHIPRES );                        //Chip reset. This stops the oscillator
00200     regWr( rUSBCTL, 0x00 );                             //Remove the reset
00201     while(!(regRd( rUSBIRQ ) & bmOSCOKIRQ )) {          //wait until the PLL is stable
00202         tmp++;                                          //timeout after 256 attempts
00203         if( tmp == 0 ) {
00204             return( false );
00205         }
00206     }
00207     return( true );
00208 }
00209 /* turn USB power on/off                                                */
00210 /* does nothing, returns TRUE. Left for compatibility with old sketches               */
00211 /* will be deleted eventually                                           */
00215 boolean MAX3421E::vbusPwr ( boolean action )
00216 {
00217 //  byte tmp;
00218 //    tmp = regRd( rIOPINS2 );                //copy of IOPINS2
00219 //    if( action ) {                          //turn on by setting GPOUT7
00220 //        tmp |= bmGPOUT7;
00221 //    }
00222 //    else {                                  //turn off by clearing GPOUT7
00223 //        tmp &= ~bmGPOUT7;
00224 //    }
00225 //    regWr( rIOPINS2, tmp );                 //send GPOUT7
00226 //    if( action ) {
00227 //        delay( 60 );
00228 //    }
00229 //    if (( regRd( rIOPINS2 ) & bmGPIN7 ) == 0 ) {     // check if overload is present. MAX4793 /FLAG ( pin 4 ) goes low if overload
00230 //        return( false );
00231 //    }                      
00232     return( true );                                             // power on/off successful                       
00233 }
00234 /* probe bus to determine device presense and speed and switch host to this speed */
00235 void MAX3421E::busprobe( void )
00236 {
00237  byte bus_sample;
00238     bus_sample = regRd( rHRSL );            //Get J,K status
00239     bus_sample &= ( bmJSTATUS|bmKSTATUS );      //zero the rest of the byte
00240     switch( bus_sample ) {                          //start full-speed or low-speed host 
00241         case( bmJSTATUS ):
00242             if(( regRd( rMODE ) & bmLOWSPEED ) == 0 ) {
00243                 regWr( rMODE, MODE_FS_HOST );       //start full-speed host
00244                 vbusState = FSHOST;
00245             }
00246             else {
00247                 regWr( rMODE, MODE_LS_HOST);        //start low-speed host
00248                 vbusState = LSHOST;
00249             }
00250             break;
00251         case( bmKSTATUS ):
00252             if(( regRd( rMODE ) & bmLOWSPEED ) == 0 ) {
00253                 regWr( rMODE, MODE_LS_HOST );       //start low-speed host
00254                 vbusState = LSHOST;
00255             }
00256             else {
00257                 regWr( rMODE, MODE_FS_HOST );       //start full-speed host
00258                 vbusState = FSHOST;
00259             }
00260             break;
00261         case( bmSE1 ):              //illegal state
00262             vbusState = SE1;
00263             break;
00264         case( bmSE0 ):              //disconnected state
00265                 regWr( rMODE, bmDPPULLDN|bmDMPULLDN|bmHOST|bmSEPIRQ);
00266             vbusState = SE0;
00267             break;
00268         }//end switch( bus_sample )
00269 }
00270 /* MAX3421E initialization after power-on   */
00271 void MAX3421E::powerOn()
00272 {
00273     /* Configure full-duplex SPI, interrupt pulse   */
00274     regWr( rPINCTL,( bmFDUPSPI + bmINTLEVEL + bmGPXB ));    //Full-duplex SPI, level interrupt, GPX
00275     if( reset() == false ) {                                //stop/start the oscillator
00276         Serial.println("Error: OSCOKIRQ failed to assert");
00277     }
00278 
00279     /* configure host operation */
00280     regWr( rMODE, bmDPPULLDN|bmDMPULLDN|bmHOST|bmSEPIRQ );      // set pull-downs, Host, Separate GPIN IRQ on GPX
00281     regWr( rHIEN, bmCONDETIE|bmFRAMEIE );                                             //connection detection
00282     /* check if device is connected */
00283     regWr( rHCTL,bmSAMPLEBUS );                                             // sample USB bus
00284     while(!(regRd( rHCTL ) & bmSAMPLEBUS ));                                //wait for sample operation to finish
00285     busprobe();                                                             //check if anything is connected
00286     regWr( rHIRQ, bmCONDETIRQ );                                            //clear connection detect interrupt                 
00287     regWr( rCPUCTL, 0x01 );                                                 //enable interrupt pin
00288 }
00289 /* MAX3421 state change task and interrupt handler */
00290 byte MAX3421E::Task( void )
00291 {
00292  byte rcode = 0;
00293  byte pinvalue;
00294     //Serial.print("Vbus state: ");
00295     //Serial.println( vbusState, HEX );
00296  pinvalue = readINT();
00297  if( pinvalue  == LOW ) {
00298         rcode = IntHandler();
00299     }
00300     pinvalue = readGPX();
00301     if( pinvalue == LOW ) {
00302         GpxHandler();
00303     }
00304 //    usbSM();                                //USB state machine                            
00305     return( rcode );   
00306 }   
00307 byte MAX3421E::IntHandler()
00308 {
00309  byte HIRQ;
00310  byte HIRQ_sendback = 0x00;
00311     HIRQ = regRd( rHIRQ );                  //determine interrupt source
00312     //if( HIRQ & bmFRAMEIRQ ) {               //->1ms SOF interrupt handler
00313     //    HIRQ_sendback |= bmFRAMEIRQ;
00314     //}//end FRAMEIRQ handling
00315     if( HIRQ & bmCONDETIRQ ) {
00316         busprobe();
00317         HIRQ_sendback |= bmCONDETIRQ;
00318     }
00319     /* End HIRQ interrupts handling, clear serviced IRQs    */
00320     regWr( rHIRQ, HIRQ_sendback );
00321     return( HIRQ_sendback );
00322 }
00323 byte MAX3421E::GpxHandler()
00324 {
00325  byte GPINIRQ = regRd( rGPINIRQ );          //read GPIN IRQ register
00326 //    if( GPINIRQ & bmGPINIRQ7 ) {            //vbus overload
00327 //        vbusPwr( OFF );                     //attempt powercycle
00328 //        delay( 1000 );
00329 //        vbusPwr( ON );
00330 //        regWr( rGPINIRQ, bmGPINIRQ7 );
00331 //    }       
00332     return( GPINIRQ );
00333 }
00334 
00335 //void MAX3421E::usbSM( void )                //USB state machine
00336 //{
00337 //    
00338 //
00339 //}


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