usb_serial_structs.c
Go to the documentation of this file.
00001 //*****************************************************************************
00002 //
00003 // usb_serial_structs.c - Data structures defining this CDC USB device.
00004 //
00005 // Copyright (c) 2012-2014 Texas Instruments Incorporated.  All rights reserved.
00006 // Software License Agreement
00007 // 
00008 // Texas Instruments (TI) is supplying this software for use solely and
00009 // exclusively on TI's microcontroller products. The software is owned by
00010 // TI and/or its suppliers, and is protected under applicable copyright
00011 // laws. You may not combine this software with "viral" open-source
00012 // software in order to form a larger program.
00013 // 
00014 // THIS SOFTWARE IS PROVIDED "AS IS" AND WITH ALL FAULTS.
00015 // NO WARRANTIES, WHETHER EXPRESS, IMPLIED OR STATUTORY, INCLUDING, BUT
00016 // NOT LIMITED TO, IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR
00017 // A PARTICULAR PURPOSE APPLY TO THIS SOFTWARE. TI SHALL NOT, UNDER ANY
00018 // CIRCUMSTANCES, BE LIABLE FOR SPECIAL, INCIDENTAL, OR CONSEQUENTIAL
00019 // DAMAGES, FOR ANY REASON WHATSOEVER.
00020 // 
00021 // This is part of revision 2.1.0.12573 of the EK-TM4C123GXL Firmware Package.
00022 //
00023 //*****************************************************************************
00024 
00025 #include <stdint.h>
00026 #include <stdbool.h>
00027 #include "inc/hw_types.h"
00028 #include "driverlib/rom.h"
00029 #include "driverlib/rom_map.h"
00030 #include "driverlib/usb.h"
00031 #include "usblib/usblib.h"
00032 #include "usblib/usbcdc.h"
00033 #include "usblib/usb-ids.h"
00034 #include "usblib/device/usbdevice.h"
00035 #include "usblib/device/usbdcdc.h"
00036 #include "usb_serial_structs.h"
00037 
00038 
00039 //*****************************************************************************
00040 //
00041 // Flag indicating whether or not we are currently sending a Break condition.
00042 //
00043 //*****************************************************************************
00044 static volatile bool g_bUSBConfigured = false;
00045 
00046 //*****************************************************************************
00047 //
00048 // Flags used to pass commands from interrupt context to the main loop.
00049 //
00050 //*****************************************************************************
00051 //#define COMMAND_PACKET_RECEIVED 0x00000001
00052 //#define COMMAND_STATUS_UPDATE   0x00000002
00053 //volatile uint32_t g_ui32Flags = 0;
00054 //char *g_pcStatus;
00055 
00056 
00057 //*****************************************************************************
00058 //
00059 // The languages supported by this device.
00060 //
00061 //*****************************************************************************
00062 const uint8_t g_pui8LangDescriptor[] =
00063 {
00064     4,
00065     USB_DTYPE_STRING,
00066     USBShort(USB_LANG_EN_US)
00067 };
00068 
00069 //*****************************************************************************
00070 //
00071 // The manufacturer string.
00072 //
00073 //*****************************************************************************
00074 const uint8_t g_pui8ManufacturerString[] =
00075 {
00076     (17 + 1) * 2,
00077     USB_DTYPE_STRING,
00078     'T', 0, 'e', 0, 'x', 0, 'a', 0, 's', 0, ' ', 0, 'I', 0, 'n', 0, 's', 0,
00079     't', 0, 'r', 0, 'u', 0, 'm', 0, 'e', 0, 'n', 0, 't', 0, 's', 0,
00080 };
00081 
00082 //*****************************************************************************
00083 //
00084 // The product string.
00085 //
00086 //*****************************************************************************
00087 const uint8_t g_pui8ProductString[] =
00088 {
00089     2 + (16 * 2),
00090     USB_DTYPE_STRING,
00091     'V', 0, 'i', 0, 'r', 0, 't', 0, 'u', 0, 'a', 0, 'l', 0, ' ', 0,
00092     'C', 0, 'O', 0, 'M', 0, ' ', 0, 'P', 0, 'o', 0, 'r', 0, 't', 0
00093 };
00094 
00095 //*****************************************************************************
00096 //
00097 // The serial number string.
00098 //
00099 //*****************************************************************************
00100 const uint8_t g_pui8SerialNumberString[] =
00101 {
00102     2 + (8 * 2),
00103     USB_DTYPE_STRING,
00104     '1', 0, '2', 0, '3', 0, '4', 0, '5', 0, '6', 0, '7', 0, '8', 0
00105 };
00106 
00107 //*****************************************************************************
00108 //
00109 // The control interface description string.
00110 //
00111 //*****************************************************************************
00112 const uint8_t g_pui8ControlInterfaceString[] =
00113 {
00114     2 + (21 * 2),
00115     USB_DTYPE_STRING,
00116     'A', 0, 'C', 0, 'M', 0, ' ', 0, 'C', 0, 'o', 0, 'n', 0, 't', 0,
00117     'r', 0, 'o', 0, 'l', 0, ' ', 0, 'I', 0, 'n', 0, 't', 0, 'e', 0,
00118     'r', 0, 'f', 0, 'a', 0, 'c', 0, 'e', 0
00119 };
00120 
00121 //*****************************************************************************
00122 //
00123 // The configuration description string.
00124 //
00125 //*****************************************************************************
00126 const uint8_t g_pui8ConfigString[] =
00127 {
00128     2 + (26 * 2),
00129     USB_DTYPE_STRING,
00130     'S', 0, 'e', 0, 'l', 0, 'f', 0, ' ', 0, 'P', 0, 'o', 0, 'w', 0,
00131     'e', 0, 'r', 0, 'e', 0, 'd', 0, ' ', 0, 'C', 0, 'o', 0, 'n', 0,
00132     'f', 0, 'i', 0, 'g', 0, 'u', 0, 'r', 0, 'a', 0, 't', 0, 'i', 0,
00133     'o', 0, 'n', 0
00134 };
00135 
00136 //*****************************************************************************
00137 //
00138 // The descriptor string table.
00139 //
00140 //*****************************************************************************
00141 const uint8_t * const g_ppui8StringDescriptors[] =
00142 {
00143     g_pui8LangDescriptor,
00144     g_pui8ManufacturerString,
00145     g_pui8ProductString,
00146     g_pui8SerialNumberString,
00147     g_pui8ControlInterfaceString,
00148     g_pui8ConfigString
00149 };
00150 
00151 #define NUM_STRING_DESCRIPTORS (sizeof(g_ppui8StringDescriptors) /            \
00152                                 sizeof(uint8_t *))
00153 
00154 
00155 //*****************************************************************************
00156 //
00157 // The CDC device initialization and customization structures. In this case,
00158 // we are using USBBuffers between the CDC device class driver and the
00159 // application code. The function pointers and callback data values are set
00160 // to insert a buffer in each of the data channels, transmit and receive.
00161 //
00162 // With the buffer in place, the CDC channel callback is set to the relevant
00163 // channel function and the callback data is set to point to the channel
00164 // instance data. The buffer, in turn, has its callback set to the application
00165 // function and the callback data set to our CDC instance structure.
00166 //
00167 //*****************************************************************************
00168 tUSBDCDCDevice g_sCDCDevice =
00169 {
00170     USB_VID_TI_1CBE,
00171     USB_PID_SERIAL,
00172     0,
00173     USB_CONF_ATTR_SELF_PWR,
00174     ControlHandler,
00175     (void *)&g_sCDCDevice,
00176     USBBufferEventCallback,
00177     (void *)&g_sRxBuffer,
00178     USBBufferEventCallback,
00179     (void *)&g_sTxBuffer,
00180     g_ppui8StringDescriptors,
00181     NUM_STRING_DESCRIPTORS
00182 };
00183 
00184 //*****************************************************************************
00185 //
00186 // Receive buffer (from the USB perspective).
00187 //
00188 //*****************************************************************************
00189 uint8_t g_pui8USBRxBuffer[UART_BUFFER_SIZE];
00190 tUSBBuffer g_sRxBuffer =
00191 {
00192     false,                          // This is a receive buffer.
00193     RxHandler,                      // pfnCallback
00194     (void *)&g_sCDCDevice,          // Callback data is our device pointer.
00195     USBDCDCPacketRead,              // pfnTransfer
00196     USBDCDCRxPacketAvailable,       // pfnAvailable
00197     (void *)&g_sCDCDevice,          // pvHandle
00198     g_pui8USBRxBuffer,              // pui8Buffer
00199     UART_BUFFER_SIZE,               // ui32BufferSize
00200 };
00201 
00202 //*****************************************************************************
00203 //
00204 // Transmit buffer (from the USB perspective).
00205 //
00206 //*****************************************************************************
00207 uint8_t g_pui8USBTxBuffer[UART_BUFFER_SIZE];
00208 tUSBBuffer g_sTxBuffer =
00209 {
00210     true,                           // This is a transmit buffer.
00211     TxHandler,                      // pfnCallback
00212     (void *)&g_sCDCDevice,          // Callback data is our device pointer.
00213     USBDCDCPacketWrite,             // pfnTransfer
00214     USBDCDCTxPacketAvailable,       // pfnAvailable
00215     (void *)&g_sCDCDevice,          // pvHandle
00216     g_pui8USBTxBuffer,              // pui8Buffer
00217     UART_BUFFER_SIZE,               // ui32BufferSize
00218 };
00219 
00220 
00221 //*****************************************************************************
00222 //
00223 // Handles CDC driver notifications related to the transmit channel (data to
00224 // the USB host).
00225 //
00226 // \param ui32CBData is the client-supplied callback pointer for this channel.
00227 // \param ui32Event identifies the event we are being notified about.
00228 // \param ui32MsgValue is an event-specific value.
00229 // \param pvMsgData is an event-specific pointer.
00230 //
00231 // This function is called by the CDC driver to notify us of any events
00232 // related to operation of the transmit data channel (the IN channel carrying
00233 // data to the USB host).
00234 //
00235 // \return The return value is event-specific.
00236 //
00237 //*****************************************************************************
00238 uint32_t
00239 TxHandler(void *pvCBData, uint32_t ui32Event, uint32_t ui32MsgValue,
00240           void *pvMsgData)
00241 {
00242     //
00243     // Which event have we been sent?
00244     //
00245     switch(ui32Event)
00246     {
00247         case USB_EVENT_TX_COMPLETE:
00248             //
00249             // Since we are using the USBBuffer, we don't need to do anything
00250             // here.
00251             //
00252             break;
00253 
00254         //
00255         // We don't expect to receive any other events.  Ignore any that show
00256         // up in a release build or hang in a debug build.
00257         //
00258         default:
00259 #ifdef DEBUG
00260             while(1);
00261 #else
00262             break;
00263 #endif
00264 
00265     }
00266     return(0);
00267 }
00268 
00269 //*****************************************************************************
00270 //
00271 // Handles CDC driver notifications related to the receive channel (data from
00272 // the USB host).
00273 //
00274 // \param ui32CBData is the client-supplied callback data value for this channel.
00275 // \param ui32Event identifies the event we are being notified about.
00276 // \param ui32MsgValue is an event-specific value.
00277 // \param pvMsgData is an event-specific pointer.
00278 //
00279 // This function is called by the CDC driver to notify us of any events
00280 // related to operation of the receive data channel (the OUT channel carrying
00281 // data from the USB host).
00282 //
00283 // \return The return value is event-specific.
00284 //
00285 //*****************************************************************************
00286 uint32_t
00287 RxHandler(void *pvCBData, uint32_t ui32Event, uint32_t ui32MsgValue,
00288           void *pvMsgData)
00289 {
00290     uint32_t ui32Count;
00291 
00292     //
00293     // Which event are we being sent?
00294     //
00295     switch(ui32Event)
00296     {
00297         //
00298         // A new packet has been received.
00299         //
00300         case USB_EVENT_RX_AVAILABLE:
00301         {
00302             //
00303             // Notify a new packet has beed received
00304             //
00305             break;
00306         }
00307 
00308         //
00309         // We are being asked how much unprocessed data we have still to
00310         // process. We return 0 if the UART is currently idle or 1 if it is
00311         // in the process of transmitting something. The actual number of
00312         // bytes in the UART FIFO is not important here, merely whether or
00313         // not everything previously sent to us has been transmitted.
00314         //
00315         case USB_EVENT_DATA_REMAINING:
00316         {
00317             //
00318             // Get the number of bytes in the buffer
00319             //
00320             ui32Count = USBBufferDataAvailable(&g_sRxBuffer);
00321 
00322             return(ui32Count);
00323         }
00324 
00325         //
00326         // We are being asked to provide a buffer into which the next packet
00327         // can be read. We do not support this mode of receiving data so let
00328         // the driver know by returning 0. The CDC driver should not be sending
00329         // this message but this is included just for illustration and
00330         // completeness.
00331         //
00332         case USB_EVENT_REQUEST_BUFFER:
00333         {
00334             return(0);
00335         }
00336 
00337         //
00338         // We don't expect to receive any other events.  Ignore any that show
00339         // up in a release build or hang in a debug build.
00340         //
00341         default:
00342 #ifdef DEBUG
00343             while(1);
00344 #else
00345             break;
00346 #endif
00347     }
00348 
00349     return(0);
00350 }
00351 
00352 //*****************************************************************************
00353 //
00354 // Handles CDC driver notifications related to control and setup of the device.
00355 //
00356 // \param pvCBData is the client-supplied callback pointer for this channel.
00357 // \param ui32Event identifies the event we are being notified about.
00358 // \param ui32MsgValue is an event-specific value.
00359 // \param pvMsgData is an event-specific pointer.
00360 //
00361 // This function is called by the CDC driver to perform control-related
00362 // operations on behalf of the USB host.  These functions include setting
00363 // and querying the serial communication parameters, setting handshake line
00364 // states and sending break conditions.
00365 //
00366 // \return The return value is event-specific.
00367 //
00368 //*****************************************************************************
00369 uint32_t
00370 ControlHandler(void *pvCBData, uint32_t ui32Event,
00371                uint32_t ui32MsgValue, void *pvMsgData)
00372 {
00373     // uint32_t ui32IntsOff;
00374 
00375     //
00376     // Which event are we being asked to process?
00377     //
00378     switch(ui32Event)
00379     {
00380         //
00381         // We are connected to a host and communication is now possible.
00382         //
00383         case USB_EVENT_CONNECTED:
00384             g_bUSBConfigured = true;
00385 
00386             //
00387             // Flush our buffers.
00388             //
00389             USBBufferFlush(&g_sTxBuffer);
00390             USBBufferFlush(&g_sRxBuffer);
00391 
00392             //
00393             // Tell the main loop to update the display.
00394             //
00395             //ui32IntsOff = ROM_IntMasterDisable();
00396             //g_pcStatus = "Connected";
00397             //g_ui32Flags |= COMMAND_STATUS_UPDATE;
00398             //if(!ui32IntsOff)
00399             //{
00400                 //ROM_IntMasterEnable();
00401             //}
00402             break;
00403 
00404         //
00405         // The host has disconnected.
00406         //
00407         case USB_EVENT_DISCONNECTED:
00408             g_bUSBConfigured = false;
00409             //ui32IntsOff = ROM_IntMasterDisable();
00410             //g_pcStatus = "Disconnected";
00411             //g_ui32Flags |= COMMAND_STATUS_UPDATE;
00412             //if(!ui32IntsOff)
00413             //{
00414                 //ROM_IntMasterEnable();
00415             //}
00416             break;
00417 
00418         //
00419         // Return the current serial communication parameters.
00420         //
00421         case USBD_CDC_EVENT_GET_LINE_CODING:
00422             break;
00423 
00424         //
00425         // Set the current serial communication parameters.
00426         //
00427         case USBD_CDC_EVENT_SET_LINE_CODING:
00428             break;
00429 
00430         //
00431         // Set the current serial communication parameters.
00432         //
00433         case USBD_CDC_EVENT_SET_CONTROL_LINE_STATE:
00434             break;
00435 
00436         //
00437         // Send a break condition on the serial line.
00438         //
00439         case USBD_CDC_EVENT_SEND_BREAK:
00440             break;
00441 
00442         //
00443         // Clear the break condition on the serial line.
00444         //
00445         case USBD_CDC_EVENT_CLEAR_BREAK:
00446             break;
00447 
00448         //
00449         // Ignore SUSPEND and RESUME for now.
00450         //
00451         case USB_EVENT_SUSPEND:
00452         case USB_EVENT_RESUME:
00453             break;
00454 
00455         //
00456         // We don't expect to receive any other events.  Ignore any that show
00457         // up in a release build or hang in a debug build.
00458         //
00459         default:
00460 #ifdef DEBUG
00461             while(1);
00462 #else
00463             break;
00464 #endif
00465 
00466     }
00467 
00468     return(0);
00469 }


rosserial_tivac
Author(s): Vitor Matos, Vitor Matos
autogenerated on Sat Oct 7 2017 03:08:58