tivac_hardware.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 UART port, interrupt driven transfers
00030 // * Two RingBuffers of TX_BUFFER_SIZE and RX_BUFFER_SIZE
00031 // * Systick Interrupt handler
00032 //
00033 //*****************************************************************************
00034 
00035 #ifndef ROS_LIB_TIVAC_HARDWARE_H
00036 #define ROS_LIB_TIVAC_HARDWARE_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/uart.h>
00052   #include <utils/ringbuf.h>
00053 }
00054 
00055 #define SYSTICKHZ  1000UL
00056 
00057 #ifdef TM4C123GXL
00058 #define LED1        GPIO_PIN_3  // Green LED
00059 #define LED2        GPIO_PIN_2  // Blue LED
00060 #define LED_PORT    GPIO_PORTF_BASE
00061 #define LED_PERIPH  SYSCTL_PERIPH_GPIOF
00062 #endif
00063 
00064 #ifdef TM4C1294XL
00065 #define LED1        GPIO_PIN_1  // D1 LED
00066 #define LED2        GPIO_PIN_0  // D2 LED
00067 #define LED_PORT    GPIO_PORTN_BASE
00068 #define LED_PERIPH  SYSCTL_PERIPH_GPION
00069 #ifndef TM4C129FREQ
00070 #error "Must define system clock frequency on: TM4C129FREQ"
00071 #endif
00072 #endif
00073 
00074 #ifndef ROSSERIAL_BAUDRATE
00075 #define ROSSERIAL_BAUDRATE 57600
00076 #endif
00077 
00078 extern tRingBufObject rxBuffer;
00079 extern tRingBufObject txBuffer;
00080 extern volatile uint32_t g_ui32milliseconds;
00081 extern volatile uint32_t g_ui32heartbeat;
00082 
00083 class TivaCHardware
00084 {
00085   public:
00086     TivaCHardware() {}
00087 
00088     void init()
00089     {
00090 #ifdef TM4C123GXL
00091       this->ui32SysClkFreq = MAP_SysCtlClockGet();
00092 #endif
00093 #ifdef TM4C1294XL
00094       this->ui32SysClkFreq = TM4C129FREQ;
00095 #endif
00096 
00097       // Setup LEDs
00098 #if defined(LED_HEARTBEAT) || defined(LED_COMM)
00099       MAP_SysCtlPeripheralEnable(LED_PERIPH);
00100 #endif
00101 #ifdef LED_HEARTBEAT
00102       MAP_GPIOPinTypeGPIOOutput(LED_PORT, LED1);
00103 #endif
00104 #ifdef LED_COMM
00105       MAP_GPIOPinTypeGPIOOutput(LED_PORT, LED2);
00106 #endif
00107 
00108       // Enable time keeping
00109       g_ui32milliseconds = 0;
00110       // Set up timer such that it produces one tick for each millisecond
00111       SysTickIntRegister(TivaCHardware::SystickIntHandler);
00112       MAP_SysTickPeriodSet(this->ui32SysClkFreq/SYSTICKHZ);
00113       MAP_SysTickEnable();
00114       MAP_SysTickIntEnable();
00115 
00116       // Enable the peripherals for UART0
00117       MAP_SysCtlPeripheralEnable(SYSCTL_PERIPH_UART0);
00118       MAP_SysCtlPeripheralEnable(SYSCTL_PERIPH_GPIOA);
00119       // Set GPIO A0 and A1 as UART pins.
00120       MAP_GPIOPinConfigure(GPIO_PA0_U0RX);
00121       MAP_GPIOPinConfigure(GPIO_PA1_U0TX);
00122       MAP_GPIOPinTypeUART(GPIO_PORTA_BASE, GPIO_PIN_0 | GPIO_PIN_1);
00123       // Configure UART0
00124       MAP_UARTConfigSetExpClk(UART0_BASE, this->ui32SysClkFreq, ROSSERIAL_BAUDRATE,
00125           (UART_CONFIG_WLEN_8 | UART_CONFIG_STOP_ONE | UART_CONFIG_PAR_NONE));
00126       // Supposedely MCU resets with FIFO 1 byte depth. Just making sure.
00127       MAP_UARTFIFODisable(UART0_BASE);
00128       // UART buffers to transmit and receive
00129       RingBufInit(&rxBuffer, this->ui8rxBufferData, RX_BUFFER_SIZE);
00130       RingBufInit(&txBuffer, this->ui8txBufferData, TX_BUFFER_SIZE);
00131 
00132       // Enable RX and TX interrupt
00133       UARTIntRegister(UART0_BASE, TivaCHardware::UARTIntHandler);
00134       MAP_IntEnable(INT_UART0);
00135       MAP_UARTTxIntModeSet(UART0_BASE, UART_TXINT_MODE_EOT);
00136       MAP_UARTIntEnable(UART0_BASE, UART_INT_RX | UART_INT_TX);
00137 
00138       // Enable processor interrupts.
00139       MAP_IntMasterEnable();
00140     }
00141 
00142     // read a byte from the serial port. -1 = failure
00143     int read()
00144     {
00145       if (!RingBufEmpty(&rxBuffer))
00146         return RingBufReadOne(&rxBuffer);
00147       else
00148         return -1;
00149     }
00150 
00151     // write data to the connection to ROS
00152     void write(uint8_t* data, int length)
00153     {
00154       // Trigger sending buffer, if not already sending
00155       if (RingBufEmpty(&txBuffer))
00156       {
00157         RingBufWrite(&txBuffer, data, length);
00158         MAP_UARTCharPutNonBlocking(UART0_BASE, RingBufReadOne(&txBuffer));
00159       }
00160       else
00161       {
00162         RingBufWrite(&txBuffer, data, length);
00163       }        
00164     }
00165 
00166     // returns milliseconds since start of program
00167     uint32_t time()
00168     {
00169       return g_ui32milliseconds;
00170     }
00171 
00172     // UART buffer structures
00173     uint8_t ui8rxBufferData[RX_BUFFER_SIZE];
00174     uint8_t ui8txBufferData[TX_BUFFER_SIZE];
00175 
00176     // UARD interrupt handler
00177     // For each received byte, pushes it into the buffer.
00178     // For each transmitted byte, read the next available from the buffer.
00179     static void UARTIntHandler()
00180     {
00181       uint32_t ui32Status;
00182       // Get the interrrupt status.
00183       ui32Status = MAP_UARTIntStatus(UART0_BASE, true);
00184       // Clear the asserted interrupts.
00185       MAP_UARTIntClear(UART0_BASE, ui32Status);
00186 
00187       // Since we are using no RX, or TX FIFO, only one char at a time for each interrupt call
00188       // RX the next character from the UART and put it on RingBuffer.
00189       // We should verify if buffer is not full. Let's assume not, for faster interrupt routine.
00190       if (ui32Status & UART_INT_RX)
00191         RingBufWriteOne(&rxBuffer, MAP_UARTCharGetNonBlocking(UART0_BASE));
00192 
00193       // TX the next available char on the buffer
00194       if (ui32Status & UART_INT_TX)
00195         if (!RingBufEmpty(&txBuffer))
00196           MAP_UARTCharPutNonBlocking(UART0_BASE, RingBufReadOne(&txBuffer));
00197 
00198 #ifdef LED_COMM
00199       // Blink the LED to show a character transfer is occuring.
00200       MAP_GPIOPinWrite(LED_PORT, LED2, MAP_GPIOPinRead(LED_PORT, LED2)^LED2);
00201 #endif
00202     }
00203 
00204     // Timing variables and System Tick interrupt handler.
00205     static void SystickIntHandler()
00206     {
00207       ++g_ui32milliseconds;
00208 #ifdef LED_HEARTBEAT
00209       if (++g_ui32heartbeat >= SYSTICKHZ)
00210       {
00211         MAP_GPIOPinWrite(LED_PORT, LED1, MAP_GPIOPinRead(LED_PORT, LED1)^LED1);
00212         g_ui32heartbeat = 0;
00213       }
00214 #endif
00215     }
00216 
00217     // System frequency
00218     uint32_t ui32SysClkFreq;
00219     uint32_t getSysClkFreq(void)
00220     {
00221       return this->ui32SysClkFreq;
00222     }
00223 
00224     // Not really accurate ms delay. But good enough for our purposes.
00225     // For a more elaborate delay check out ``Energia/hardware/lm4f/cores/lm4f/wiring.c``
00226     void delay(uint32_t ms)
00227     {
00228       while (ms > 500)
00229       {
00230         MAP_SysCtlDelay(this->ui32SysClkFreq/3/SYSTICKHZ * 500);
00231         ms -= 500;
00232       }
00233       MAP_SysCtlDelay(this->ui32SysClkFreq/3/SYSTICKHZ * ms);
00234     }
00235 };
00236 #endif  // ROS_LIB_TIVAC_HARDWARE_H


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