Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035 #ifndef ROS_LIB_TIVAC_HARDWARE_USB_H
00036 #define ROS_LIB_TIVAC_HARDWARE_USB_H
00037
00038 #include <stdbool.h>
00039 #include <stdint.h>
00040 extern "C"
00041 {
00042 #include <inc/hw_types.h>
00043 #include <inc/hw_memmap.h>
00044 #include <inc/hw_ints.h>
00045 #include <driverlib/sysctl.h>
00046 #include <driverlib/gpio.h>
00047 #include <driverlib/rom.h>
00048 #include <driverlib/rom_map.h>
00049 #include <driverlib/systick.h>
00050 #include <driverlib/pin_map.h>
00051 #include <driverlib/usb.h>
00052 #include <usblib/usblib.h>
00053 #include <usblib/usbcdc.h>
00054 #include <usblib/usb-ids.h>
00055 #include <usblib/device/usbdevice.h>
00056 #include <usblib/device/usbdcdc.h>
00057 #include "usb_serial_structs.h"
00058 }
00059
00060 #define SYSTICKHZ 1000UL
00061
00062 #ifdef TM4C123GXL
00063 #define LED1 GPIO_PIN_3 // Green LED
00064 #define LED2 GPIO_PIN_2 // Blue LED
00065 #define LED_PORT GPIO_PORTF_BASE
00066 #define LED_PERIPH SYSCTL_PERIPH_GPIOF
00067 #endif
00068
00069 #ifdef TM4C1294XL
00070 #define LED1 GPIO_PIN_1 // D1 LED
00071 #define LED2 GPIO_PIN_0 // D2 LED
00072 #define LED_PORT GPIO_PORTN_BASE
00073 #define LED_PERIPH SYSCTL_PERIPH_GPION
00074 #ifndef TM4C129FREQ
00075 #error "Must define system clock frequency on: TM4C129FREQ"
00076 #endif
00077 #endif
00078
00079 extern volatile uint32_t g_ui32milliseconds;
00080 extern volatile uint32_t g_ui32heartbeat;
00081
00082 class TivaCHardware
00083 {
00084 public:
00085 TivaCHardware() {}
00086
00087 void init()
00088 {
00089 #ifdef TM4C123GXL
00090 this->ui32SysClkFreq = MAP_SysCtlClockGet();
00091 #endif
00092 #ifdef TM4C1294XL
00093 this->ui32SysClkFreq = TM4C129FREQ;
00094 #endif
00095
00096
00097 #if defined(LED_HEARTBEAT) || defined(LED_COMM)
00098 MAP_SysCtlPeripheralEnable(LED_PERIPH);
00099 #endif
00100 #ifdef LED_HEARTBEAT
00101 MAP_GPIOPinTypeGPIOOutput(LED_PORT, LED1);
00102 #endif
00103 #ifdef LED_COMM
00104 MAP_GPIOPinTypeGPIOOutput(LED_PORT, LED2);
00105 #endif
00106
00107
00108 g_ui32milliseconds = 0;
00109
00110 SysTickIntRegister(TivaCHardware::SystickIntHandler);
00111 MAP_SysTickPeriodSet(this->ui32SysClkFreq/SYSTICKHZ);
00112 MAP_SysTickEnable();
00113 MAP_SysTickIntEnable();
00114
00115 MAP_SysCtlPeripheralEnable(SYSCTL_PERIPH_USB0);
00116 #ifdef TM4C123GXL
00117
00118 MAP_SysCtlPeripheralEnable(SYSCTL_PERIPH_GPIOD);
00119 MAP_GPIOPinTypeUSBAnalog(GPIO_PORTD_BASE, GPIO_PIN_5 | GPIO_PIN_4);
00120 #endif
00121 #ifdef TM4C1294XL
00122 MAP_SysCtlPeripheralEnable(SYSCTL_PERIPH_GPIOL);
00123 MAP_GPIOPinTypeUSBAnalog(GPIO_PORTL_BASE, GPIO_PIN_6 | GPIO_PIN_7);
00124 #endif
00125
00126
00127 USBBufferInit(&g_sTxBuffer);
00128 USBBufferInit(&g_sRxBuffer);
00129
00130
00131 USBStackModeSet(0, eUSBModeForceDevice, 0);
00132
00133
00134
00135 USBDCDCInit(0, &g_sCDCDevice);
00136
00137
00138 USBIntRegister(USB0_BASE, USB0DeviceIntHandler);
00139
00140
00141 MAP_IntMasterEnable();
00142 }
00143
00144
00145 int read()
00146 {
00147 uint8_t ui8ReadData;
00148 if (USBBufferRead(&g_sRxBuffer, &ui8ReadData, 1) == 1)
00149 {
00150 #ifdef LED_COMM
00151
00152 MAP_GPIOPinWrite(LED_PORT, LED2, MAP_GPIOPinRead(LED_PORT, LED2)^LED2);
00153 #endif
00154 return ui8ReadData;
00155 }
00156 else
00157 return -1;
00158 }
00159
00160
00161 void write(uint8_t* data, int length)
00162 {
00163 #ifdef LED_COMM
00164
00165 MAP_GPIOPinWrite(LED_PORT, LED2, MAP_GPIOPinRead(LED_PORT, LED2)^LED2);
00166 #endif
00167
00168
00169 USBBufferWrite(&g_sTxBuffer, data, length);
00170 }
00171
00172
00173 uint32_t time()
00174 {
00175 return g_ui32milliseconds;
00176 }
00177
00178
00179 static void SystickIntHandler()
00180 {
00181 ++g_ui32milliseconds;
00182 #ifdef LED_HEARTBEAT
00183 if (++g_ui32heartbeat >= SYSTICKHZ)
00184 {
00185 MAP_GPIOPinWrite(LED_PORT, LED1, MAP_GPIOPinRead(LED_PORT, LED1)^LED1);
00186 g_ui32heartbeat = 0;
00187 }
00188 #endif
00189 }
00190
00191
00192 uint32_t ui32SysClkFreq;
00193 uint32_t getSysClkFreq(void)
00194 {
00195 return this->ui32SysClkFreq;
00196 }
00197
00198
00199
00200 void delay(uint32_t ms)
00201 {
00202 while (ms > 500)
00203 {
00204 MAP_SysCtlDelay(this->ui32SysClkFreq/3/SYSTICKHZ * 500);
00205 ms -= 500;
00206 }
00207 MAP_SysCtlDelay(this->ui32SysClkFreq/3/SYSTICKHZ * ms);
00208 }
00209 };
00210 #endif // ROS_LIB_TIVAC_HARDWARE_USB_H