tivac_hardware_usb.h
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2015, Robosavvy Ltd.
3  * All rights reserved.
4  * Author: Vitor Matos
5  *
6  * Redistribution and use in source and binary forms, with or without modification, are permitted provided that the
7  * following conditions are met:
8  *
9  * 1. Redistributions of source code must retain the above copyright notice, this list of conditions and the
10  * following disclaimer.
11  * 2. Redistributions in binary form must reproduce the above copyright notice, this list of conditions and the
12  * following disclaimer in the documentation and/or other materials provided with the distribution.
13  * 3. Neither the name of the copyright holder nor the names of its contributors may be used to endorse or promote
14  * products derived from this software without specific prior written permission.
15  *
16  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED
17  * WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR
18  * PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
19  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE
20  * GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF
21  * LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY
22  * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
23  */
24 
25 //*****************************************************************************
26 //
27 // Bare minimum hardware resources allocated for rosserials communication.
28 // * 2 LEDs if desired
29 // * One USB port
30 // * Two USBBuffers of UART_BUFFER_SIZE
31 // * Systick Interrupt handler
32 //
33 //*****************************************************************************
34 
35 #ifndef ROS_LIB_TIVAC_HARDWARE_USB_H
36 #define ROS_LIB_TIVAC_HARDWARE_USB_H
37 
38 #include <stdbool.h>
39 #include <stdint.h>
40 extern "C"
41 {
42  #include <inc/hw_types.h>
43  #include <inc/hw_memmap.h>
44  #include <inc/hw_ints.h>
45  #include <driverlib/sysctl.h>
46  #include <driverlib/gpio.h>
47  #include <driverlib/rom.h>
48  #include <driverlib/rom_map.h>
49  #include <driverlib/systick.h>
50  #include <driverlib/pin_map.h>
51  #include <driverlib/usb.h>
52  #include <usblib/usblib.h>
53  #include <usblib/usbcdc.h>
54  #include <usblib/usb-ids.h>
55  #include <usblib/device/usbdevice.h>
56  #include <usblib/device/usbdcdc.h>
57  #include "usb_serial_structs.h"
58 }
59 
60 #define SYSTICKHZ 1000UL
61 
62 #ifdef TM4C123GXL
63 #define LED1 GPIO_PIN_3 // Green LED
64 #define LED2 GPIO_PIN_2 // Blue LED
65 #define LED_PORT GPIO_PORTF_BASE
66 #define LED_PERIPH SYSCTL_PERIPH_GPIOF
67 #endif
68 
69 #ifdef TM4C1294XL
70 #define LED1 GPIO_PIN_1 // D1 LED
71 #define LED2 GPIO_PIN_0 // D2 LED
72 #define LED_PORT GPIO_PORTN_BASE
73 #define LED_PERIPH SYSCTL_PERIPH_GPION
74 #ifndef TM4C129FREQ
75 #error "Must define system clock frequency on: TM4C129FREQ"
76 #endif
77 #endif
78 
79 extern volatile uint32_t g_ui32milliseconds;
80 extern volatile uint32_t g_ui32heartbeat;
81 
82 class TivaCHardware
83 {
84  public:
86 
87  void init()
88  {
89 #ifdef TM4C123GXL
90  this->ui32SysClkFreq = MAP_SysCtlClockGet();
91 #endif
92 #ifdef TM4C1294XL
93  this->ui32SysClkFreq = TM4C129FREQ;
94 #endif
95 
96  // Setup LEDs
97 #if defined(LED_HEARTBEAT) || defined(LED_COMM)
98  MAP_SysCtlPeripheralEnable(LED_PERIPH);
99 #endif
100 #ifdef LED_HEARTBEAT
101  MAP_GPIOPinTypeGPIOOutput(LED_PORT, LED1);
102 #endif
103 #ifdef LED_COMM
104  MAP_GPIOPinTypeGPIOOutput(LED_PORT, LED2);
105 #endif
106 
107  // Enable time keeping
108  g_ui32milliseconds = 0;
109  // Set up timer such that it produces one tick for each millisecond
110  SysTickIntRegister(TivaCHardware::SystickIntHandler);
111  MAP_SysTickPeriodSet(this->ui32SysClkFreq/SYSTICKHZ);
112  MAP_SysTickEnable();
113  MAP_SysTickIntEnable();
114 
115  MAP_SysCtlPeripheralEnable(SYSCTL_PERIPH_USB0);
116 #ifdef TM4C123GXL
117  // Configure the required pins for USB operation.
118  MAP_SysCtlPeripheralEnable(SYSCTL_PERIPH_GPIOD);
119  MAP_GPIOPinTypeUSBAnalog(GPIO_PORTD_BASE, GPIO_PIN_5 | GPIO_PIN_4);
120 #endif
121 #ifdef TM4C1294XL
122  MAP_SysCtlPeripheralEnable(SYSCTL_PERIPH_GPIOL);
123  MAP_GPIOPinTypeUSBAnalog(GPIO_PORTL_BASE, GPIO_PIN_6 | GPIO_PIN_7);
124 #endif
125 
126  // Initialize the transmit and receive buffers.
127  USBBufferInit(&g_sTxBuffer);
128  USBBufferInit(&g_sRxBuffer);
129 
130  // Set the USB stack mode to Device mode with VBUS monitoring.
131  USBStackModeSet(0, eUSBModeForceDevice, 0);
132 
133  // Pass our device information to the USB library and place the device
134  // on the bus.
135  USBDCDCInit(0, &g_sCDCDevice);
136 
137  // Register USB interrupt handler
138  USBIntRegister(USB0_BASE, USB0DeviceIntHandler);
139 
140  // Enable processor interrupts.
141  MAP_IntMasterEnable();
142  }
143 
144  // read a byte from the serial port. -1 = failure
145  int read()
146  {
147  uint8_t ui8ReadData;
148  if (USBBufferRead(&g_sRxBuffer, &ui8ReadData, 1) == 1)
149  {
150 #ifdef LED_COMM
151  // Blink the LED to show a character transfer is occuring.
152  MAP_GPIOPinWrite(LED_PORT, LED2, MAP_GPIOPinRead(LED_PORT, LED2)^LED2);
153 #endif
154  return ui8ReadData;
155  }
156  else
157  return -1;
158  }
159 
160  // write data to the connection to ROS
161  void write(uint8_t* data, int length)
162  {
163 #ifdef LED_COMM
164  // Blink the LED to show a character transfer is occuring.
165  MAP_GPIOPinWrite(LED_PORT, LED2, MAP_GPIOPinRead(LED_PORT, LED2)^LED2);
166 #endif
167  // Let's assume for now all length is available for storage in the buffer.
168  // Otherwise must use: USBBufferSpaceAvailable
169  USBBufferWrite(&g_sTxBuffer, data, length);
170  }
171 
172  // returns milliseconds since start of program
173  uint32_t time()
174  {
175  return g_ui32milliseconds;
176  }
177 
178  // Timing variables and System Tick interrupt handler.
179  static void SystickIntHandler()
180  {
182 #ifdef LED_HEARTBEAT
183  if (++g_ui32heartbeat >= SYSTICKHZ)
184  {
185  MAP_GPIOPinWrite(LED_PORT, LED1, MAP_GPIOPinRead(LED_PORT, LED1)^LED1);
186  g_ui32heartbeat = 0;
187  }
188 #endif
189  }
190 
191  // System frequency
192  uint32_t ui32SysClkFreq;
193  uint32_t getSysClkFreq(void)
194  {
195  return this->ui32SysClkFreq;
196  }
197 
198  // Not really accurate ms delay. But good enough for our purposes.
199  // For a more elaborate delay check out ``Energia/hardware/lm4f/cores/lm4f/wiring.c``
200  void delay(uint32_t ms)
201  {
202  while (ms > 500)
203  {
204  MAP_SysCtlDelay(this->ui32SysClkFreq/3/SYSTICKHZ * 500);
205  ms -= 500;
206  }
207  MAP_SysCtlDelay(this->ui32SysClkFreq/3/SYSTICKHZ * ms);
208  }
209 };
210 #endif // ROS_LIB_TIVAC_HARDWARE_USB_H
void write(uint8_t *data, int length)
static void SystickIntHandler()
uint32_t getSysClkFreq(void)
#define SYSTICKHZ
tUSBBuffer g_sTxBuffer
uint32_t ui32SysClkFreq
tUSBBuffer g_sRxBuffer
volatile uint32_t g_ui32milliseconds
volatile uint32_t g_ui32heartbeat
tUSBDCDCDevice g_sCDCDevice
void delay(uint32_t ms)


rosserial_tivac
Author(s): Vitor Matos, Vitor Matos
autogenerated on Mon Jun 10 2019 14:53:43