tivac_hardware_usb.h
Go to the documentation of this file.
00001 /*
00002  * Copyright (c) 2015, Robosavvy Ltd.
00003  * All rights reserved.
00004  * Author: Vitor Matos
00005  *
00006  * Redistribution and use in source and binary forms, with or without modification, are permitted provided that the
00007  * following conditions are met:
00008  *
00009  *   1. Redistributions of source code must retain the above copyright notice, this list of conditions and the
00010  * following disclaimer.
00011  *   2. Redistributions in binary form must reproduce the above copyright notice, this list of conditions and the
00012  * following disclaimer in the documentation and/or other materials provided with the distribution.
00013  *   3. Neither the name of the copyright holder nor the names of its contributors may be used to endorse or promote
00014  * products derived from this software without specific prior written permission.
00015  *
00016  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED
00017  * WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR
00018  * PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00019  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE
00020  * GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF
00021  * LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY
00022  * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
00023  */
00024 
00025 //*****************************************************************************
00026 //
00027 // Bare minimum hardware resources allocated for rosserials communication.
00028 // * 2 LEDs if desired
00029 // * One USB port
00030 // * Two USBBuffers of UART_BUFFER_SIZE
00031 // * Systick Interrupt handler
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       // Setup LEDs
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       // Enable time keeping
00108       g_ui32milliseconds = 0;
00109       // Set up timer such that it produces one tick for each millisecond
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       // Configure the required pins for USB operation.
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       // Initialize the transmit and receive buffers.
00127       USBBufferInit(&g_sTxBuffer);
00128       USBBufferInit(&g_sRxBuffer);
00129 
00130       // Set the USB stack mode to Device mode with VBUS monitoring.
00131       USBStackModeSet(0, eUSBModeForceDevice, 0);
00132 
00133       // Pass our device information to the USB library and place the device
00134       // on the bus.
00135       USBDCDCInit(0, &g_sCDCDevice);
00136 
00137       // Register USB interrupt handler
00138       USBIntRegister(USB0_BASE, USB0DeviceIntHandler);
00139 
00140       // Enable processor interrupts.
00141       MAP_IntMasterEnable();
00142     }
00143 
00144     // read a byte from the serial port. -1 = failure
00145     int read()
00146     {
00147       uint8_t ui8ReadData;
00148       if (USBBufferRead(&g_sRxBuffer, &ui8ReadData, 1) == 1)
00149       {
00150 #ifdef LED_COMM
00151         // Blink the LED to show a character transfer is occuring.
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     // write data to the connection to ROS
00161     void write(uint8_t* data, int length)
00162     {
00163 #ifdef LED_COMM
00164       // Blink the LED to show a character transfer is occuring.
00165       MAP_GPIOPinWrite(LED_PORT, LED2, MAP_GPIOPinRead(LED_PORT, LED2)^LED2);
00166 #endif
00167       // Let's assume for now all length is available for storage in the buffer.
00168       // Otherwise must use: USBBufferSpaceAvailable
00169       USBBufferWrite(&g_sTxBuffer, data, length);
00170     }
00171 
00172     // returns milliseconds since start of program
00173     uint32_t time()
00174     {
00175       return g_ui32milliseconds;
00176     }
00177 
00178     // Timing variables and System Tick interrupt handler.
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     // System frequency
00192     uint32_t ui32SysClkFreq;
00193     uint32_t getSysClkFreq(void)
00194     {
00195       return this->ui32SysClkFreq;
00196     }
00197 
00198     // Not really accurate ms delay. But good enough for our purposes.
00199     // For a more elaborate delay check out ``Energia/hardware/lm4f/cores/lm4f/wiring.c``
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


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