uart.h
Go to the documentation of this file.
00001 /*
00002 Copyright (c) 2011, Ascending Technologies GmbH
00003 Copyright (c) 2011, Markus Achtelik, ASL, ETH Zurich, Switzerland
00004 You can contact the author at <markus dot achtelik at mavt dot ethz dot ch>
00005 
00006 All rights reserved.
00007 
00008 Redistribution and use in source and binary forms, with or without
00009 modification, are permitted provided that the following conditions are met:
00010 * Redistributions of source code must retain the above copyright
00011 notice, this list of conditions and the following disclaimer.
00012 * Redistributions in binary form must reproduce the above copyright
00013 notice, this list of conditions and the following disclaimer in the
00014 documentation and/or other materials provided with the distribution.
00015 * Neither the name of ETHZ-ASL nor the
00016 names of its contributors may be used to endorse or promote products
00017 derived from this software without specific prior written permission.
00018 
00019 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
00020 ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
00021 WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
00022 DISCLAIMED. IN NO EVENT SHALL ETHZ-ASL BE LIABLE FOR ANY
00023 DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
00024 (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00025 LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
00026 ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
00027 (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
00028 SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
00029 
00030 */
00031 
00032 #ifndef __UART_H
00033 #define __UART_H
00034 
00035 #include <inttypes.h>
00036 
00037 extern void UARTInitialize(unsigned int);
00038 extern void UARTWriteChar(unsigned char);
00039 extern unsigned char UARTReadChar(void);
00040 extern void __putchar(int);
00041 extern void UART_send(char *, unsigned char);
00042 extern void UART_send_ringbuffer(void);
00043 extern int ringbuffer(unsigned char, unsigned char*, unsigned int);
00044 
00045 void startAutoBaud(void);
00046 volatile extern char autobaud_in_progress;
00047 
00048 int writePacket2Ringbuffer(uint8_t descriptor, void * data, uint8_t length);
00049 extern void uart0ISR(void);
00050 
00051 inline uint16_t crc16(void *, uint16_t count, uint16_t prev_crc);
00052 inline uint16_t crc_update(uint16_t, uint8_t);
00053 
00054 #define RBREAD 0
00055 #define RBWRITE 1
00056 #define RBFREE  2 
00057 #define RINGBUFFERSIZE  384
00058 
00059 int UART0_txEmpty(void);
00060 void UART0_rxFlush(void);
00061 void UART0_txFlush(void);
00062 uint8_t UART0_writeFifo(void * data, uint32_t length);
00063 
00064 // this has to be 2^n !!!
00065 #define UART0_RX_BUFFERSIZE 512
00066 #define UART0_TX_BUFFERSIZE 512
00067 
00068 // not more than 64 different packettypes
00069 #define PACKET_INFO_SIZE 64
00070 
00071 typedef struct
00072 {
00073   uint8_t descriptor;
00074   void * data;
00075   uint8_t updated;
00076 } PacketInfo;
00077 
00078 extern volatile unsigned int UART_rxPacketCount;
00079 extern volatile unsigned int UART_rxGoodPacketCount;
00080 
00081 typedef struct
00082 {
00083   volatile uint8_t *buffer;
00084   uint8_t inUse;
00085   uint32_t bufferSize;
00086   uint32_t readIdx;
00087   uint32_t writeIdx;
00088   uint32_t tmp;
00089   uint32_t mask;
00090 }volatile Fifo;
00091 
00092 extern volatile short uart0_min_tx_buffer;
00093 extern volatile short uart0_min_rx_buffer;
00094 
00095 void Fifo_initialize(Fifo * fifo, volatile uint8_t * buffer, uint32_t bufferSize);
00096 inline uint8_t Fifo_writeByte(Fifo * fifo, uint8_t byte);
00097 inline uint8_t Fifo_writeBlock(Fifo * fifo, void *data, uint32_t length);
00098 inline uint8_t Fifo_readByte(Fifo * fifo, uint8_t * byte);
00099 inline uint16_t Fifo_availableMemory(Fifo * fifo);
00100 inline void Fifo_reset(Fifo * fifo);
00101 
00102 void parseRxFifo(void);
00103 
00104 PacketInfo* registerPacket(uint8_t descriptor, void * data);
00105 
00106 #endif //__UART_H


asctec_hl_firmware
Author(s): Markus Achtelik, Michael Achtelik, Stephan Weiss, Laurent Kneip
autogenerated on Tue Dec 17 2013 11:39:27