tivac_hardware.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 UART port, interrupt driven transfers
30 // * Two RingBuffers of TX_BUFFER_SIZE and RX_BUFFER_SIZE
31 // * Systick Interrupt handler
32 //
33 //*****************************************************************************
34 
35 #ifndef ROS_LIB_TIVAC_HARDWARE_H
36 #define ROS_LIB_TIVAC_HARDWARE_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/uart.h>
52  #include <utils/ringbuf.h>
53 }
54 
55 #define SYSTICKHZ 1000UL
56 
57 #ifdef TM4C123GXL
58 #define LED1 GPIO_PIN_3 // Green LED
59 #define LED2 GPIO_PIN_2 // Blue LED
60 #define LED_PORT GPIO_PORTF_BASE
61 #define LED_PERIPH SYSCTL_PERIPH_GPIOF
62 #endif
63 
64 #ifdef TM4C1294XL
65 #define LED1 GPIO_PIN_1 // D1 LED
66 #define LED2 GPIO_PIN_0 // D2 LED
67 #define LED_PORT GPIO_PORTN_BASE
68 #define LED_PERIPH SYSCTL_PERIPH_GPION
69 #ifndef TM4C129FREQ
70 #error "Must define system clock frequency on: TM4C129FREQ"
71 #endif
72 #endif
73 
74 #ifndef ROSSERIAL_BAUDRATE
75 #define ROSSERIAL_BAUDRATE 57600
76 #endif
77 
78 extern tRingBufObject rxBuffer;
79 extern tRingBufObject txBuffer;
80 extern volatile uint32_t g_ui32milliseconds;
81 extern volatile uint32_t g_ui32heartbeat;
82 
84 {
85  public:
87 
88  void init()
89  {
90 #ifdef TM4C123GXL
91  this->ui32SysClkFreq = MAP_SysCtlClockGet();
92 #endif
93 #ifdef TM4C1294XL
94  this->ui32SysClkFreq = TM4C129FREQ;
95 #endif
96 
97  // Setup LEDs
98 #if defined(LED_HEARTBEAT) || defined(LED_COMM)
99  MAP_SysCtlPeripheralEnable(LED_PERIPH);
100 #endif
101 #ifdef LED_HEARTBEAT
102  MAP_GPIOPinTypeGPIOOutput(LED_PORT, LED1);
103 #endif
104 #ifdef LED_COMM
105  MAP_GPIOPinTypeGPIOOutput(LED_PORT, LED2);
106 #endif
107 
108  // Enable time keeping
109  g_ui32milliseconds = 0;
110  // Set up timer such that it produces one tick for each millisecond
111  SysTickIntRegister(TivaCHardware::SystickIntHandler);
112  MAP_SysTickPeriodSet(this->ui32SysClkFreq/SYSTICKHZ);
113  MAP_SysTickEnable();
114  MAP_SysTickIntEnable();
115 
116  // Enable the peripherals for UART0
117  MAP_SysCtlPeripheralEnable(SYSCTL_PERIPH_UART0);
118  MAP_SysCtlPeripheralEnable(SYSCTL_PERIPH_GPIOA);
119  // Set GPIO A0 and A1 as UART pins.
120  MAP_GPIOPinConfigure(GPIO_PA0_U0RX);
121  MAP_GPIOPinConfigure(GPIO_PA1_U0TX);
122  MAP_GPIOPinTypeUART(GPIO_PORTA_BASE, GPIO_PIN_0 | GPIO_PIN_1);
123  // Configure UART0
124  MAP_UARTConfigSetExpClk(UART0_BASE, this->ui32SysClkFreq, ROSSERIAL_BAUDRATE,
125  (UART_CONFIG_WLEN_8 | UART_CONFIG_STOP_ONE | UART_CONFIG_PAR_NONE));
126  // Supposedely MCU resets with FIFO 1 byte depth. Just making sure.
127  MAP_UARTFIFODisable(UART0_BASE);
128  // UART buffers to transmit and receive
129  RingBufInit(&rxBuffer, this->ui8rxBufferData, RX_BUFFER_SIZE);
130  RingBufInit(&txBuffer, this->ui8txBufferData, TX_BUFFER_SIZE);
131 
132  // Enable RX and TX interrupt
133  UARTIntRegister(UART0_BASE, TivaCHardware::UARTIntHandler);
134  MAP_IntEnable(INT_UART0);
135  MAP_UARTTxIntModeSet(UART0_BASE, UART_TXINT_MODE_EOT);
136  MAP_UARTIntEnable(UART0_BASE, UART_INT_RX | UART_INT_TX);
137 
138  // Enable processor interrupts.
139  MAP_IntMasterEnable();
140  }
141 
142  // read a byte from the serial port. -1 = failure
143  int read()
144  {
145  if (!RingBufEmpty(&rxBuffer))
146  return RingBufReadOne(&rxBuffer);
147  else
148  return -1;
149  }
150 
151  // write data to the connection to ROS
152  void write(uint8_t* data, int length)
153  {
154  // Trigger sending buffer, if not already sending
155  if (RingBufEmpty(&txBuffer))
156  {
157  RingBufWrite(&txBuffer, data, length);
158  MAP_UARTCharPutNonBlocking(UART0_BASE, RingBufReadOne(&txBuffer));
159  }
160  else
161  {
162  RingBufWrite(&txBuffer, data, length);
163  }
164  }
165 
166  // returns milliseconds since start of program
167  uint32_t time()
168  {
169  return g_ui32milliseconds;
170  }
171 
172  // UART buffer structures
173  uint8_t ui8rxBufferData[RX_BUFFER_SIZE];
174  uint8_t ui8txBufferData[TX_BUFFER_SIZE];
175 
176  // UARD interrupt handler
177  // For each received byte, pushes it into the buffer.
178  // For each transmitted byte, read the next available from the buffer.
179  static void UARTIntHandler()
180  {
181  uint32_t ui32Status;
182  // Get the interrrupt status.
183  ui32Status = MAP_UARTIntStatus(UART0_BASE, true);
184  // Clear the asserted interrupts.
185  MAP_UARTIntClear(UART0_BASE, ui32Status);
186 
187  // Since we are using no RX, or TX FIFO, only one char at a time for each interrupt call
188  // RX the next character from the UART and put it on RingBuffer.
189  // We should verify if buffer is not full. Let's assume not, for faster interrupt routine.
190  if (ui32Status & UART_INT_RX)
191  RingBufWriteOne(&rxBuffer, MAP_UARTCharGetNonBlocking(UART0_BASE));
192 
193  // TX the next available char on the buffer
194  if (ui32Status & UART_INT_TX)
195  if (!RingBufEmpty(&txBuffer))
196  MAP_UARTCharPutNonBlocking(UART0_BASE, RingBufReadOne(&txBuffer));
197 
198 #ifdef LED_COMM
199  // Blink the LED to show a character transfer is occuring.
200  MAP_GPIOPinWrite(LED_PORT, LED2, MAP_GPIOPinRead(LED_PORT, LED2)^LED2);
201 #endif
202  }
203 
204  // Timing variables and System Tick interrupt handler.
205  static void SystickIntHandler()
206  {
208 #ifdef LED_HEARTBEAT
209  if (++g_ui32heartbeat >= SYSTICKHZ)
210  {
211  MAP_GPIOPinWrite(LED_PORT, LED1, MAP_GPIOPinRead(LED_PORT, LED1)^LED1);
212  g_ui32heartbeat = 0;
213  }
214 #endif
215  }
216 
217  // System frequency
218  uint32_t ui32SysClkFreq;
219  uint32_t getSysClkFreq(void)
220  {
221  return this->ui32SysClkFreq;
222  }
223 
224  // Not really accurate ms delay. But good enough for our purposes.
225  // For a more elaborate delay check out ``Energia/hardware/lm4f/cores/lm4f/wiring.c``
226  void delay(uint32_t ms)
227  {
228  while (ms > 500)
229  {
230  MAP_SysCtlDelay(this->ui32SysClkFreq/3/SYSTICKHZ * 500);
231  ms -= 500;
232  }
233  MAP_SysCtlDelay(this->ui32SysClkFreq/3/SYSTICKHZ * ms);
234  }
235 };
236 #endif // ROS_LIB_TIVAC_HARDWARE_H
uint8_t ui8rxBufferData[RX_BUFFER_SIZE]
void write(uint8_t *data, int length)
static void SystickIntHandler()
static void UARTIntHandler()
uint32_t getSysClkFreq(void)
#define ROSSERIAL_BAUDRATE
uint32_t ui32SysClkFreq
uint32_t time()
volatile uint32_t g_ui32heartbeat
#define SYSTICKHZ
uint8_t ui8txBufferData[TX_BUFFER_SIZE]
tRingBufObject txBuffer
tRingBufObject rxBuffer
void delay(uint32_t ms)
volatile uint32_t g_ui32milliseconds


rosserial_tivac
Author(s): Vitor Matos, Vitor Matos
autogenerated on Fri Jun 7 2019 22:03:04