Subversion Repositories Projects

Compare Revisions

Ignore whitespace Rev 1931 → Rev 1932

/Transportables_Koptertool/branch/PKT/branch/GPL_PKT_V3_6_7f_FC090b/uart/.directory
0,0 → 1,3
[Dolphin]
Timestamp=2013,2,17,15,38,3
ViewMode=1
/Transportables_Koptertool/branch/PKT/branch/GPL_PKT_V3_6_7f_FC090b/uart/uart1.c
0,0 → 1,371
/*************************************************************************
Title: Interrupt UART library with receive/transmit circular buffers
Author: Peter Fleury <pfleury@gmx.ch> http://jump.to/fleury
File: $Id: uart.c,v 1.6.2.2 2009/11/29 08:56:12 Peter Exp $
Software: AVR-GCC 4.1, AVR Libc 1.4.6 or higher
Hardware: any AVR with built-in UART,
License: GNU General Public License
 
DESCRIPTION:
An interrupt is generated when the UART has finished transmitting or
receiving a byte. The interrupt handling routines use circular buffers
for buffering received and transmitted data.
 
The UART_RX_BUFFER_SIZE and UART_TX_BUFFER_SIZE variables define
the buffer size in bytes. Note that these variables must be a
power of 2.
 
USAGE:
Refere to the header file uart.h for a description of the routines.
See also example test_uart.c.
 
NOTES:
Based on Atmel Application Note AVR306
 
LICENSE:
Copyright (C) 2006 Peter Fleury
 
This program is free software; you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation; either version 2 of the License, or
any later version.
 
This program is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
 
*************************************************************************/
 
#include <avr/io.h>
#include <avr/interrupt.h>
#include <avr/pgmspace.h>
#include <string.h>
#include <stdbool.h>
#include "uart1.h"
#include "../main.h"
#include "../bluetooth/bluetooth.h"
#include "../tracking/tracking.h"
//
// constants and macros
//
#if defined HWVERSION1_3W || defined HWVERSION3_9
 
// size of RX/TX buffers
#define UART_RX_BUFFER_MASK ( UART_RX_BUFFER_SIZE - 1)
#define UART_TX_BUFFER_MASK ( UART_TX_BUFFER_SIZE - 1)
 
#if ( UART_RX_BUFFER_SIZE & UART_RX_BUFFER_MASK )
#error RX buffer size is not a power of 2
#endif
 
#if ( UART_TX_BUFFER_SIZE & UART_TX_BUFFER_MASK )
#error TX buffer size is not a power of 2
#endif
 
 
// ATmega with two USART
 
#define ATMEGA_USART1
 
#define UART1_STATUS UCSR1A
#define UART1_CONTROL UCSR1B
#define UART1_DATA UDR1
#define UART1_UDRIE UDRIE1
 
 
 
//
// module global variables
//
 
uint8_t receiveNMEA = false;
 
 
#if defined( ATMEGA_USART1 )
static volatile unsigned char UART1_TxBuf[UART_TX_BUFFER_SIZE];
static volatile unsigned char UART1_RxBuf[UART_RX_BUFFER_SIZE];
static volatile unsigned char UART1_TxHead;
static volatile unsigned char UART1_TxTail;
static volatile unsigned char UART1_RxHead;
static volatile unsigned char UART1_RxTail;
static volatile unsigned char UART1_LastRxError;
volatile uint16_t UART1_RxError;
#endif
 
 
void SetBaudUart1(uint8_t Baudrate)
{
switch (Baudrate)
{
case Baud_2400: uart1_init( UART_BAUD_SELECT(2400,F_CPU) ); break;
case Baud_4800: uart1_init( UART_BAUD_SELECT(4800,F_CPU) ); break;
// case Baud_9600: uart1_init( UART_BAUD_SELECT(9600,F_CPU) ); break;
case Baud_9600: uart1_init( 129); break;
case Baud_19200: uart1_init( UART_BAUD_SELECT(19200,F_CPU) ); break;
case Baud_38400: uart1_init( UART_BAUD_SELECT(38400,F_CPU) ); break;
case Baud_57600: uart1_init( UART_BAUD_SELECT(57600,F_CPU) ); break;
// case Baud_57600: uart1_init( 21); break;
// case Baud_115200: uart1_init( UART_BAUD_SELECT(115200,F_CPU) ); break;
case Baud_115200: uart1_init( 10 ); break;
}
}
 
//
// these functions are only for ATmegas with two USART
//
 
 
#if defined( ATMEGA_USART1 )
 
//--------------------------------------------------------------
// Function: UART1 Receive Complete interrupt
// Purpose: called when the UART1 has received a character
//--------------------------------------------------------------
ISR(USART1_RX_vect)
{
unsigned char tmphead;
unsigned char data;
unsigned char usr;
unsigned char lastRxError;
 
 
// read UART status register and UART data register
usr = UART1_STATUS;
data = UART1_DATA;
 
lastRxError = (usr & (_BV(FE1)|_BV(DOR1)) );
 
// calculate buffer index
tmphead = ( UART1_RxHead + 1) & UART_RX_BUFFER_MASK;
 
if ( tmphead == UART1_RxTail )
{
// error: receive buffer overflow
lastRxError = UART_BUFFER_OVERFLOW >> 8;
UART1_RxError++;
}
else
{
// store new index
UART1_RxHead = tmphead;
// store received data in buffer
UART1_RxBuf[tmphead] = data;
}
UART1_LastRxError = lastRxError;
 
 
 
// if (receiveNMEA==true)
// {
// if (bt_receiveNMEA()) Tracking_NMEA();
// else receiveNMEA = false;
//
// }
 
}
 
 
//--------------------------------------------------------------
// Function: UART1 Data Register Empty interrupt
// Purpose: called when the UART1 is ready to transmit the next byte
//--------------------------------------------------------------
ISR(USART1_UDRE_vect)
{
unsigned char tmptail;
 
 
if ( UART1_TxHead != UART1_TxTail)
{
// calculate and store new buffer index
tmptail = (UART1_TxTail + 1) & UART_TX_BUFFER_MASK;
UART1_TxTail = tmptail;
// get one byte from buffer and write it to UART
UART1_DATA = UART1_TxBuf[tmptail]; // start transmission
}
else
{
// tx buffer empty, disable UDRE interrupt
UART1_CONTROL &= ~_BV(UART1_UDRIE);
}
}
 
 
//--------------------------------------------------------------
// Function: uart1_init()
// Purpose: initialize UART1 and set baudrate
// Input: baudrate using macro UART_BAUD_SELECT()
// Returns: none
//--------------------------------------------------------------
void uart1_init(unsigned int baudrate)
{
UART1_TxHead = 0;
UART1_TxTail = 0;
UART1_RxHead = 0;
UART1_RxTail = 0;
UART1_RxError = 0;
 
// Set baud rate
if ( baudrate & 0x8000 )
{
UART1_STATUS = (1<<U2X1); //Enable 2x speed
baudrate &= ~0x8000;
}
UBRR1H = (unsigned char)(baudrate>>8);
UBRR1L = (unsigned char) baudrate;
 
// Enable USART receiver and transmitter and receive complete interrupt
UART1_CONTROL = _BV(RXCIE1)|(1<<RXEN1)|(1<<TXEN1);
 
// Set frame format: asynchronous, 8data, no parity, 1stop bit
#ifdef URSEL1
UCSR1C = (1<<URSEL1)|(3<<UCSZ10);
#else
UCSR1C = (3<<UCSZ10);
// UCSR1C = (1<<UCSZ11) | (1<<UCSZ10); // 8data Bit
#endif
 
 
 
}
 
 
//--------------------------------------------------------------
// Function: uart1_getc()
// Purpose: return byte from ringbuffer
// Returns: lower byte: received byte from ringbuffer
// higher byte: last receive error
//--------------------------------------------------------------
unsigned int uart1_getc(void)
{
unsigned char tmptail;
unsigned char data;
 
 
if ( UART1_RxHead == UART1_RxTail )
{
return UART_NO_DATA; // no data available
}
 
// calculate /store buffer index
tmptail = (UART1_RxTail + 1) & UART_RX_BUFFER_MASK;
UART1_RxTail = tmptail;
 
// get data from receive buffer
data = UART1_RxBuf[tmptail];
 
return (UART1_LastRxError << 8) + data;
 
}/* uart1_getc */
 
 
//--------------------------------------------------------------
// Function: uart1_putc()
// Purpose: write byte to ringbuffer for transmitting via UART
// Input: byte to be transmitted
// Returns: 1 on succes, 0 if remote not ready
//--------------------------------------------------------------
int uart1_putc(unsigned char data)
{
unsigned char tmphead;
 
 
tmphead = (UART1_TxHead + 1) & UART_TX_BUFFER_MASK;
 
while ( tmphead == UART1_TxTail )
{;} // wait for free space in buffer
 
UART1_TxBuf[tmphead] = data;
UART1_TxHead = tmphead;
 
// enable UDRE interrupt
UART1_CONTROL |= _BV(UART1_UDRIE);
return (UART1_LastRxError << 8) + data;
}
 
 
//--------------------------------------------------------------
// Function: uart1_puts()
// Purpose: transmit string to UART1
// Input: string to be transmitted
// Returns: none
//--------------------------------------------------------------
void uart1_puts(const char *s )
{
while (*s)
uart1_putc(*s++);
}
 
 
//--------------------------------------------------------------
// Function: uart1_puts_p()
// Purpose: transmit string from program memory to UART1
// Input: program memory string to be transmitted
// Returns: none
//--------------------------------------------------------------
void uart1_puts_p(const char *progmem_s )
{
register char c;
while ( (c = pgm_read_byte(progmem_s++)) )
uart1_putc(c);
}
 
 
//--------------------------------------------------------------
// Function: uart1_available()
// Purpose: Determine the number of bytes waiting in the receive buffer
// Input: None
// Returns: Integer number of bytes in the receive buffer
//--------------------------------------------------------------
uint16_t uart1_available(void)
{
return (UART_RX_BUFFER_MASK + UART1_RxHead - UART1_RxTail) % UART_RX_BUFFER_MASK;
}
 
 
 
//--------------------------------------------------------------
// Function: uart1_flush()
// Purpose: Flush bytes waiting the receive buffer. Acutally ignores them.
// Input: None
// Returns: None
//--------------------------------------------------------------
void uart1_flush(void)
{
UART1_RxHead = UART1_RxTail;
}
 
 
/*************************************************************************
Function: utoa()
Purpose: convert unsigned integer to ascii
Input: string_buffer, string_buffer_size, unsigned integer value
Returns: first ascii character
**************************************************************************/
char *utoa1(char* buffer, const unsigned int size, unsigned int value)
{
char *p;
 
// p points to last char
p = buffer+size-1;
 
// Set terminating Zero
*p='\0';
 
do
{
*--p = value%10 + '0';
value = value/10;
} while (value!=0 && p>buffer);
 
return p;
}/* utoa */
 
 
 
 
 
 
#endif
#endif
 
Property changes:
Added: svn:mime-type
+text/plain
\ No newline at end of property
/Transportables_Koptertool/branch/PKT/branch/GPL_PKT_V3_6_7f_FC090b/uart/uart1.h
0,0 → 1,175
/************************************************************************
Title: Interrupt UART library with receive/transmit circular buffers
Author: Peter Fleury <pfleury@gmx.ch> http://jump.to/fleury
File: $Id: uart.h,v 1.8.2.1 2007/07/01 11:14:38 peter Exp $
Software: AVR-GCC 4.1, AVR Libc 1.4
Hardware: any AVR with built-in UART, tested on AT90S8515 & ATmega8 at 4 Mhz
License: GNU General Public License
Usage: see Doxygen manual
 
LICENSE:
Copyright (C) 2006 Peter Fleury
 
This program is free software; you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation; either version 2 of the License, or
any later version.
 
This program is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
 
************************************************************************/
 
//
// @defgroup pfleury_uart UART Library
// @code #include <uart.h> @endcode
//
// @brief Interrupt UART library using the built-in UART with transmit and receive circular buffers.
//
// This library can be used to transmit and receive data through the built in UART.
//
// An interrupt is generated when the UART has finished transmitting or
// receiving a byte. The interrupt handling routines use circular buffers
// for buffering received and transmitted data.
//
// The UART_RX_BUFFER_SIZE and UART_TX_BUFFER_SIZE constants define
// the size of the circular buffers in bytes. Note that these constants must be a power of 2.
// You may need to adapt this constants to your target and your application by adding
// CDEFS += -DUART_RX_BUFFER_SIZE=nn -DUART_RX_BUFFER_SIZE=nn to your Makefile.
//
// @note Based on Atmel Application Note AVR306
// @author Peter Fleury pfleury@gmx.ch http://jump.to/fleury
//
 
#ifndef UART_H
#define UART_H
 
#if (__GNUC__ * 100 + __GNUC_MINOR__) < 304
#error "This library requires AVR-GCC 3.4 or later, update to newer AVR-GCC compiler !"
#endif
 
 
// constants and macros
 
 
// @brief UART Baudrate Expression
// @param xtalcpu system clock in Mhz, e.g. 4000000L for 4Mhz
// @param baudrate baudrate in bps, e.g. 1200, 2400, 9600
//
#define UART_BAUD_SELECT(baudRate,xtalCpu) ((xtalCpu)/((baudRate)*16l)-1)
 
// @brief UART Baudrate Expression for ATmega double speed mode
// @param xtalcpu system clock in Mhz, e.g. 4000000L for 4Mhz
// @param baudrate baudrate in bps, e.g. 1200, 2400, 9600
//
#define UART_BAUD_SELECT_DOUBLE_SPEED(baudRate,xtalCpu) (((xtalCpu)/((baudRate)*8l)-1)|0x8000)
 
 
// Size of the circular receive buffer, must be power of 2
#ifndef UART_RX_BUFFER_SIZE
#define UART_RX_BUFFER_SIZE 1024
#endif
 
// Size of the circular transmit buffer, must be power of 2
#ifndef UART_TX_BUFFER_SIZE
#define UART_TX_BUFFER_SIZE 64
#endif
 
// test if the size of the circular buffers fits into SRAM
#if ( (UART_RX_BUFFER_SIZE+UART_TX_BUFFER_SIZE) >= (RAMEND-0x60 ) )
#error "size of UART_RX_BUFFER_SIZE + UART_TX_BUFFER_SIZE larger than size of SRAM"
#endif
 
//global variable
extern uint8_t receiveNMEA;
extern volatile uint16_t UART1_RxError;
 
 
// high byte error return code of uart_getc()
 
#define UART_FRAME_ERROR 0x0800 // Framing Error by UART
#define UART_OVERRUN_ERROR 0x0400 // Overrun condition by UART
#define UART_BUFFER_OVERFLOW 0x0200 // receive ringbuffer overflow
#define UART_NO_DATA 0x0100 // no receive data available
 
#define TRACKING_RSSI 1
#define TRACKING_GPS 2
#define TRACKING_MKCOCKPIT 3
#define TRACKING_NMEA 4
//
// function prototypes
//
 
//
// @brief Initialize UART and set baudrate
// @param baudrate Specify baudrate using macro UART_BAUD_SELECT()
// @return none
//
extern void uart_init(unsigned int baudrate);
 
 
//
// @brief Get received byte from ringbuffer
//
// Returns in the lower byte the received character and in the
// higher byte the last receive error.
// UART_NO_DATA is returned when no data is available.
//
// @param void
// @return lower byte: received byte from ringbuffer
// @return higher byte: last receive status
// - \b 0 successfully received data from UART
// - \b UART_NO_DATA
// <br>no receive data available
// - \b UART_BUFFER_OVERFLOW
// <br>Receive ringbuffer overflow.
// We are not reading the receive buffer fast enough,
// one or more received character have been dropped
// - \b UART_OVERRUN_ERROR
// <br>Overrun condition by UART.
// A character already present in the UART UDR register was
// not read by the interrupt handler before the next character arrived,
// one or more received characters have been dropped.
// - \b UART_FRAME_ERROR
// <br>Framing Error by UART
//
extern unsigned int uart_getc(void);
 
 
//
// @brief Put byte to ringbuffer for transmitting via UART
// @param data byte to be transmitted
// @return none
//
 
// @brief Set Baudrate USART1
extern void SetBaudUart1(uint8_t Baudrate);
 
// @brief Initialize USART1 (only available on selected ATmegas) @see uart_init
extern void uart1_init(unsigned int baudrate);
 
// @brief Get received byte of USART1 from ringbuffer. (only available on selected ATmega) @see uart_getc
extern unsigned int uart1_getc(void);
 
// @brief Put byte to ringbuffer for transmitting via USART1 (only available on selected ATmega) @see uart_putc
//extern void uart1_putc(unsigned char data);
extern int uart1_putc(unsigned char data);
 
// @brief Put string to ringbuffer for transmitting via USART1 (only available on selected ATmega) @see uart_puts
extern void uart1_puts(const char *s );
 
// @brief Put string from program memory to ringbuffer for transmitting via USART1 (only available on selected ATmega) @see uart_puts_p
extern void uart1_puts_p(const char *s );
 
// @brief Macro to automatically put a string constant into program memory
#define uart1_puts_P(__s) uart1_puts_p(PSTR(__s))
 
extern char *utoa1(char* buffer, const unsigned int size, unsigned int value);
 
extern uint16_t uart1_available(void);
 
#endif // UART_H
 
 
Property changes:
Added: svn:mime-type
+text/plain
\ No newline at end of property
/Transportables_Koptertool/branch/PKT/branch/GPL_PKT_V3_6_7f_FC090b/uart/usart.c
0,0 → 1,688
/*****************************************************************************
* Copyright (C) 2008 Thomas Kaiser, thomas@ft-fanpage.de *
* Copyright (C) 2009 Peter "woggle" Mack, mac@denich.net *
* Copyright (C) 2011 Christian "Cebra" Brandtner, brandtner@brandtner.net *
* Copyright (C) 2011 Harald Bongartz *
* *
* This program is free software; you can redistribute it and/or modify *
* it under the terms of the GNU General Public License as published by *
* the Free Software Foundation; either version 2 of the License. *
* *
* This program is distributed in the hope that it will be useful, *
* but WITHOUT ANY WARRANTY; without even the implied warranty of *
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the *
* GNU General Public License for more details. *
* *
* You should have received a copy of the GNU General Public License *
* along with this program; if not, write to the *
* Free Software Foundation, Inc., *
* 59 Temple Place - Suite 330, Boston, MA 02111-1307, USA. *
* *
* *
* Credits to: *
* Holger Buss & Ingo Busker from mikrokopter.de for the MK project + SVN *
* http://www.mikrokopter.de *
* Gregor "killagreg" Stobrawa for his version of the MK code *
* Thomas Kaiser "thkais" for the original project. See *
* http://www.ft-fanpage.de/mikrokopter/ *
* http://forum.mikrokopter.de/topic-4061-1.html *
* Claas Anders "CaScAdE" Rathje for providing the font and his C-OSD code *
* http://www.mylifesucks.de/oss/c-osd/ *
* Harald Bongartz "HaraldB" for providing his Ideas and Code for usibility*
*****************************************************************************/
 
 
#include <avr/io.h>
#include <avr/interrupt.h>
#include <avr/pgmspace.h>
#include <avr/wdt.h>
#include "../cpu.h"
#include <util/delay.h>
#include <stdarg.h>
 
#include "../main.h"
#include "usart.h"
#include "../lcd/lcd.h"
#include "../timer/timer.h"
#include "uart1.h"
#include "../eeprom/eeprom.h"
#include "../osd/osd.h"
 
 
uint8_t buffer[30];
 
volatile uint8_t txd_buffer[TXD_BUFFER_LEN];
volatile uint8_t txd_complete = TRUE;
 
volatile uint8_t rxd_buffer[RXD_BUFFER_LEN];
volatile uint8_t rxd_buffer_locked = FALSE;
volatile uint8_t ReceivedBytes = 0;
volatile uint8_t *pRxData = 0;
volatile uint8_t RxDataLen = 0;
 
volatile uint16_t stat_crc_error = 0;
volatile uint16_t stat_overflow_error = 0;
 
volatile uint8_t rx_byte;
volatile uint8_t rxFlag = 0;
 
 
#define UART_RXBUFSIZE 64
#define UART_NO_DATA 0x0100 /* no receive data available */
 
volatile static uint8_t rxbuf[UART_RXBUFSIZE];
volatile static uint8_t *volatile rxhead, *volatile rxtail;
 
 
/*
 
//-----------------------------------------------------------------------------
// USART1 transmitter ISR
ISR (USART1_TX_vect)
{
static uint16_t ptr_txd1_buffer = 0;
uint8_t tmp_tx1;
 
if(!txd1_complete) // transmission not completed
{
ptr_txd1_buffer++; // [0] was already sent
tmp_tx1 = txd1_buffer[ptr_txd1_buffer];
// if terminating character or end of txd buffer was reached
if((tmp_tx1 == '\r') || (ptr_txd1_buffer == TXD_BUFFER_LEN))
{
ptr_txd1_buffer = 0; // reset txd pointer
txd1_complete = TRUE; // stop transmission
}
UDR1 = tmp_tx1; // send current byte will trigger this ISR again
}
// transmission completed
else ptr_txd1_buffer = 0;
}
 
*/
 
 
#ifdef USART_INT
//-----------------------------------------------------------------------------
// USART0 transmitter ISR
ISR (USART_TX_vect)
{
static uint16_t ptr_txd_buffer = 0;
uint8_t tmp_tx;
 
if(!txd_complete) // transmission not completed
{
ptr_txd_buffer++; // [0] was already sent
tmp_tx = txd_buffer[ptr_txd_buffer];
// if terminating character or end of txd buffer was reached
if((tmp_tx == '\r') || (ptr_txd_buffer == TXD_BUFFER_LEN))
{
ptr_txd_buffer = 0; // reset txd pointer
txd_complete = TRUE; // stop transmission
}
UDR = tmp_tx; // send current byte will trigger this ISR again
}
// transmission completed
else ptr_txd_buffer = 0;
}
#endif
 
 
void SetBaudUart0(uint8_t Baudrate)
{
switch (Baudrate)
{
case Baud_2400: USART_Init( UART_BAUD_SELECT(2400,F_CPU) ); break;
case Baud_4800: USART_Init( UART_BAUD_SELECT(4800,F_CPU) ); break;
case Baud_9600: USART_Init( UART_BAUD_SELECT(9600,F_CPU) ); break;
case Baud_19200: USART_Init( UART_BAUD_SELECT(19200,F_CPU) ); break;
case Baud_38400: USART_Init( UART_BAUD_SELECT(38400,F_CPU) ); break;
case Baud_57600: USART_Init( UART_BAUD_SELECT(57600,F_CPU) ); break;
// case Baud_115200: USART_Init( UART_BAUD_SELECT(115200,F_CPU) ); break;
// Macro erechnet falschen Wert (9,85 = 9) für 115200 Baud mit 20Mhz Quarz, zu grosse Abweichung
 
//#warning "Baurate prüfen wenn kein 20 Mhz Quarz verwendet wird"
 
case Baud_115200: USART_Init( 10 ); break;
}
}
 
 
//-----------------------------------------------------------------------------
//
 
//
//uint8_t uart_getc_nb(uint8_t *c)
//{
// if (rxhead==rxtail) return 0;
// *c = *rxtail;
// if (++rxtail == (rxbuf + UART_RXBUFSIZE)) rxtail = rxbuf;
// return 1;
//}
 
 
 
 
ISR (USART0_RX_vect)
{
static uint16_t crc;
static uint8_t ptr_rxd_buffer = 0;
uint8_t crc1, crc2;
uint8_t c;
// IdleTimer = 0;
if (current_hardware == Wi232)
{
// rx_byte = c;
// rxFlag = 1;
int diff;
uint8_t c;
c=UDR;
diff = rxhead - rxtail;
if (diff < 0) diff += UART_RXBUFSIZE;
if (diff < UART_RXBUFSIZE -1)
{
*rxhead = c;
++rxhead;
if (rxhead == (rxbuf + UART_RXBUFSIZE)) rxhead = rxbuf;
};
// USART_putc (c);
return;
}
 
 
if (current_hardware == MKGPS)
{
// rx_byte = c;
// rxFlag = 1;
int diff;
uint8_t c;
c=UDR;
diff = rxhead - rxtail;
if (diff < 0) diff += UART_RXBUFSIZE;
if (diff < UART_RXBUFSIZE -1)
{
*rxhead = c;
++rxhead;
if (rxhead == (rxbuf + UART_RXBUFSIZE)) rxhead = rxbuf;
};
 
return;
}
 
c = UDR; // catch the received byte
if (OSD_active && Config.OSD_SendOSD) // Daten an SV2 senden
uart1_putc(c);
 
 
if (rxd_buffer_locked)
return; // if rxd buffer is locked immediately return
 
// the rxd buffer is unlocked
if ((ptr_rxd_buffer == 0) && (c == '#')) // if rxd buffer is empty and syncronisation character is received
{
rxd_buffer[ptr_rxd_buffer++] = c; // copy 1st byte to buffer
crc = c; // init crc
}
else if (ptr_rxd_buffer < RXD_BUFFER_LEN) // collect incomming bytes
{
if(c != '\r') // no termination character
{
rxd_buffer[ptr_rxd_buffer++] = c; // copy byte to rxd buffer
crc += c; // update crc
}
else // termination character was received
{
// the last 2 bytes are no subject for checksum calculation
// they are the checksum itself
crc -= rxd_buffer[ptr_rxd_buffer-2];
crc -= rxd_buffer[ptr_rxd_buffer-1];
// calculate checksum from transmitted data
crc %= 4096;
crc1 = '=' + crc / 64;
crc2 = '=' + crc % 64;
// compare checksum to transmitted checksum bytes
if((crc1 == rxd_buffer[ptr_rxd_buffer-2]) && (crc2 == rxd_buffer[ptr_rxd_buffer-1]))
{ // checksum valid
rxd_buffer[ptr_rxd_buffer] = '\r'; // set termination character
ReceivedBytes = ptr_rxd_buffer + 1;// store number of received bytes
if (mode == rxd_buffer[2])
{
rxd_buffer_locked = TRUE; // lock the rxd buffer
// if 2nd byte is an 'R' enable watchdog that will result in an reset
if(rxd_buffer[2] == 'R') {wdt_enable(WDTO_250MS);} // Reset-Commando
}
}
else
{ // checksum invalid
stat_crc_error++;
rxd_buffer_locked = FALSE; // unlock rxd buffer
}
ptr_rxd_buffer = 0; // reset rxd buffer pointer
}
}
else // rxd buffer overrun
{
stat_overflow_error++;
ptr_rxd_buffer = 0; // reset rxd buffer
rxd_buffer_locked = FALSE; // unlock rxd buffer
}
}
 
 
//-----------------------------------------------------------------------------
// Function: uart0_getc()
// Purpose: return byte from ringbuffer
// Returns: lower byte: received byte from ringbuffer
// higher byte: last receive error
//-----------------------------------------------------------------------------
char USART_getc(void)
{
char val;
 
// while(rxhead==rxtail) ;
if (rxhead==rxtail)
return val=0;
// IdleTimer = 0;
val = *rxtail;
if (++rxtail == (rxbuf + UART_RXBUFSIZE))
rxtail = rxbuf;
 
return val;
}
 
 
uint8_t uart_getc_nb(uint8_t *c)
{
if (rxhead==rxtail)
return 0;
// IdleTimer = 0;
*c = *rxtail;
if (++rxtail == (rxbuf + UART_RXBUFSIZE))
rxtail = rxbuf;
return 1;
}
//-----------------------------------------------------------------------------
//
 
 
 
 
 
//-----------------------------------------------------------------------------
//
void USART_Init (unsigned int baudrate)
{
// set clock divider
// #undef BAUD
// #define BAUD baudrate
// #include <util/setbaud.h>
// UBRRH = UBRRH_VALUE;
// UBRRL = UBRRL_VALUE;
 
//#ifndef F_CPU
///* In neueren Version der WinAVR/Mfile Makefile-Vorlage kann
// F_CPU im Makefile definiert werden, eine nochmalige Definition
// hier wuerde zu einer Compilerwarnung fuehren. Daher "Schutz" durch
// #ifndef/#endif
//
// Dieser "Schutz" kann zu Debugsessions führen, wenn AVRStudio
// verwendet wird und dort eine andere, nicht zur Hardware passende
// Taktrate eingestellt ist: Dann wird die folgende Definition
// nicht verwendet, sondern stattdessen der Defaultwert (8 MHz?)
// von AVRStudio - daher Ausgabe einer Warnung falls F_CPU
// noch nicht definiert: */
//#warning "F_CPU war noch nicht definiert, wird nun nachgeholt mit 4000000"
//#define F_CPU 18432000UL // Systemtakt in Hz - Definition als unsigned long beachten
// Ohne ergeben sich unten Fehler in der Berechnung
//#endif
//#define BAUD 115200UL // Baudrate
//
//// Berechnungen
//#define UBRR_VAL ((F_CPU+BAUD*8)/(BAUD*16)-1) // clever runden
//#define BAUD_REAL (F_CPU/(16*(UBRR_VAL+1))) // Reale Baudrate
//#define BAUD_ERROR ((BAUD_REAL*1000)/BAUD) // Fehler in Promille, 1000 = kein Fehler.
//
//
//#if ((BAUD_ERROR<990) || (BAUD_ERROR>1010))
// #error "Systematischer Fehler der Baudrate grösser 1% und damit zu hoch!"
//#endif
 
 
UBRRH = (unsigned char)(baudrate>>8);
UBRRL = (unsigned char) baudrate;
// UBRRH = (unsigned char)(BAUD_REAL>>8);
// UBRRL = (unsigned char) BAUD_REAL;
 
#if USE_2X
UCSRA |= (1 << U2X); // enable double speed operation
#else
UCSRA &= ~(1 << U2X); // disable double speed operation
#endif
 
// set 8N1
#if defined (__AVR_ATmega8__) || defined (__AVR_ATmega32__)
UCSRC = (1 << URSEL) | (1 << UCSZ1) | (1 << UCSZ0);
#else
UCSRC = (1 << UCSZ1) | (1 << UCSZ0);
#endif
UCSRB &= ~(1 << UCSZ2);
 
// flush receive buffer
while ( UCSRA & (1 << RXC) ) UDR;
 
UCSRB |= (1 << RXEN) | (1 << TXEN);
#ifdef USART_INT
UCSRB |= (1 << RXCIE) | (1 << TXCIE);
#else
UCSRB |= (1 << RXCIE);
#endif
 
rxhead = rxtail = rxbuf;
 
}
 
 
 
 
 
//-----------------------------------------------------------------------------
// disable the txd pin of usart
void USART_DisableTXD (void)
{
#ifdef USART_INT
UCSRB &= ~(1 << TXCIE); // disable TX-Interrupt
#endif
UCSRB &= ~(1 << TXEN); // disable TX in USART
DDRB &= ~(1 << DDB3); // set TXD pin as input
PORTB &= ~(1 << PORTB3); // disable pullup on TXD pin
}
 
//-----------------------------------------------------------------------------
// enable the txd pin of usart
void USART_EnableTXD (void)
{
DDRB |= (1 << DDB3); // set TXD pin as output
PORTB &= ~(1 << PORTB3); // disable pullup on TXD pin
UCSRB |= (1 << TXEN); // enable TX in USART
#ifdef USART_INT
UCSRB |= (1 << TXCIE); // enable TX-Interrupt
#endif
}
 
//-----------------------------------------------------------------------------
// short script to directly send a request thorugh usart including en- and disabling it
// where <address> is the address of the receipient, <label> is which data set to request
// and <ms> represents the milliseconds delay between data
void USART_request_mk_data (uint8_t cmd, uint8_t addr, uint8_t ms)
{
USART_EnableTXD (); // re-enable TXD pin
 
unsigned char mstenth = ms/10;
SendOutData(cmd, addr, 1, &mstenth, 1);
// wait until command transmitted
while (txd_complete == FALSE);
 
USART_DisableTXD (); // disable TXD pin again
}
 
//-----------------------------------------------------------------------------
//
void USART_putc (char c)
{
#ifdef USART_INT
#else
loop_until_bit_is_set(UCSRA, UDRE);
UDR = c;
#endif
}
 
 
 
//-----------------------------------------------------------------------------
//
void USART_puts (char *s)
{
#ifdef USART_INT
#else
while (*s)
{
USART_putc (*s);
s++;
}
#endif
}
 
//-----------------------------------------------------------------------------
//
void USART_puts_p (const char *s)
{
#ifdef USART_INT
#else
while (pgm_read_byte(s))
{
USART_putc (pgm_read_byte(s));
s++;
}
#endif
}
 
//-----------------------------------------------------------------------------
//
void SendOutData(uint8_t cmd, uint8_t addr, uint8_t numofbuffers, ...) // uint8_t *pdata, uint8_t len, ...
{
va_list ap;
uint16_t pt = 0;
uint8_t a,b,c;
uint8_t ptr = 0;
uint16_t tmpCRC = 0;
 
uint8_t *pdata = 0;
int len = 0;
 
txd_buffer[pt++] = '#'; // Start character
txd_buffer[pt++] = 'a' + addr; // Address (a=0; b=1,...)
txd_buffer[pt++] = cmd; // Command
 
va_start(ap, numofbuffers);
if(numofbuffers)
{
pdata = va_arg (ap, uint8_t*);
len = va_arg (ap, int);
ptr = 0;
numofbuffers--;
}
 
while(len)
{
if(len)
{
a = pdata[ptr++];
len--;
if((!len) && numofbuffers)
{
pdata = va_arg(ap, uint8_t*);
len = va_arg(ap, int);
ptr = 0;
numofbuffers--;
}
}
else
a = 0;
 
if(len)
{
b = pdata[ptr++];
len--;
if((!len) && numofbuffers)
{
pdata = va_arg(ap, uint8_t*);
len = va_arg(ap, int);
ptr = 0;
numofbuffers--;
}
}
else
b = 0;
 
if(len)
{
c = pdata[ptr++];
len--;
if((!len) && numofbuffers)
{
pdata = va_arg(ap, uint8_t*);
len = va_arg(ap, int);
ptr = 0;
numofbuffers--;
}
}
else
c = 0;
 
txd_buffer[pt++] = '=' + (a >> 2);
txd_buffer[pt++] = '=' + (((a & 0x03) << 4) | ((b & 0xf0) >> 4));
txd_buffer[pt++] = '=' + (((b & 0x0f) << 2) | ((c & 0xc0) >> 6));
txd_buffer[pt++] = '=' + ( c & 0x3f);
}
va_end(ap);
 
for(a = 0; a < pt; a++)
{
tmpCRC += txd_buffer[a];
}
tmpCRC %= 4096;
txd_buffer[pt++] = '=' + tmpCRC / 64;
txd_buffer[pt++] = '=' + tmpCRC % 64;
txd_buffer[pt++] = '\r';
 
txd_complete = FALSE;
#ifdef USART_INT
UDR = txd_buffer[0]; // initiates the transmittion (continued in the TXD ISR)
#else
for(a = 0; a < pt; a++)
{
loop_until_bit_is_set(UCSRA, UDRE);
UDR = txd_buffer[a];
}
txd_complete = TRUE;
#endif
}
 
//-----------------------------------------------------------------------------
//
void Decode64 (void)
{
uint8_t a,b,c,d;
uint8_t ptrIn = 3;
uint8_t ptrOut = 3;
uint8_t len = ReceivedBytes - 6;
 
while (len)
{
a = rxd_buffer[ptrIn++] - '=';
b = rxd_buffer[ptrIn++] - '=';
c = rxd_buffer[ptrIn++] - '=';
d = rxd_buffer[ptrIn++] - '=';
//if(ptrIn > ReceivedBytes - 3) break;
 
if (len--)
rxd_buffer[ptrOut++] = (a << 2) | (b >> 4);
else
break;
 
if (len--)
rxd_buffer[ptrOut++] = ((b & 0x0f) << 4) | (c >> 2);
else
break;
 
if (len--)
rxd_buffer[ptrOut++] = ((c & 0x03) << 6) | d;
else
break;
}
pRxData = &rxd_buffer[3];
RxDataLen = ptrOut - 3;
}
 
 
//-----------------------------------------------------------------------------
//
void SwitchToNC (void)
{
 
if(hardware == NC)
{
// switch to NC
USART_putc (0x1b);
USART_putc (0x1b);
USART_putc (0x55);
USART_putc (0xaa);
USART_putc (0x00);
current_hardware = NC;
_delay_ms (50);
}
}
 
//-----------------------------------------------------------------------------
//
 
 
//-----------------------------------------------------------------------------
//
void SwitchToWi232 (void)
{
 
// if(hardware == NC)
{
// switch to Wi232
current_hardware = Wi232;
_delay_ms (50);
}
}
 
//-----------------------------------------------------------------------------
//
void SwitchToFC (void)
{
uint8_t cmd;
 
if (current_hardware == NC)
{
// switch to FC
cmd = 0x00; // 0 = FC, 1 = MK3MAG, 2 = MKGPS
SendOutData('u', ADDRESS_NC, 1, &cmd, 1);
current_hardware = FC;
_delay_ms (50);
}
}
 
//-----------------------------------------------------------------------------
//
void SwitchToMAG (void)
{
uint8_t cmd;
 
if (current_hardware == NC)
{
// switch to MK3MAG
cmd = 0x01; // 0 = FC, 1 = MK3MAG, 2 = MKGPS
SendOutData('u', ADDRESS_NC, 1, &cmd, 1);
current_hardware = MK3MAG;
_delay_ms (50);
}
}
 
//-----------------------------------------------------------------------------
//
void SwitchToGPS (void)
{
uint8_t cmd;
if (current_hardware == NC)
{
// switch to MKGPS
cmd = 0x02; // 0 = FC, 1 = MK3MAG, 2 = MKGPS
SendOutData('u', ADDRESS_NC, 1, &cmd, 1);
current_hardware = MKGPS;
_delay_ms (50);
}
}
Property changes:
Added: svn:mime-type
+text/plain
\ No newline at end of property
/Transportables_Koptertool/branch/PKT/branch/GPL_PKT_V3_6_7f_FC090b/uart/usart.h
0,0 → 1,150
/*****************************************************************************
* Copyright (C) 2008 Thomas Kaiser, thomas@ft-fanpage.de *
* Copyright (C) 2009 Peter "woggle" Mack, mac@denich.net *
* Copyright (C) 2011 Christian "Cebra" Brandtner, brandtner@brandtner.net *
* Copyright (C) 2011 Harald Bongartz *
* *
* This program is free software; you can redistribute it and/or modify *
* it under the terms of the GNU General Public License as published by *
* the Free Software Foundation; either version 2 of the License. *
* *
* This program is distributed in the hope that it will be useful, *
* but WITHOUT ANY WARRANTY; without even the implied warranty of *
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the *
* GNU General Public License for more details. *
* *
* You should have received a copy of the GNU General Public License *
* along with this program; if not, write to the *
* Free Software Foundation, Inc., *
* 59 Temple Place - Suite 330, Boston, MA 02111-1307, USA. *
* *
* *
* Credits to: *
* Holger Buss & Ingo Busker from mikrokopter.de for the MK project + SVN *
* http://www.mikrokopter.de *
* Gregor "killagreg" Stobrawa for his version of the MK code *
* Thomas Kaiser "thkais" for the original project. See *
* http://www.ft-fanpage.de/mikrokopter/ *
* http://forum.mikrokopter.de/topic-4061-1.html *
* Claas Anders "CaScAdE" Rathje for providing the font and his C-OSD code *
* http://www.mylifesucks.de/oss/c-osd/ *
* Harald Bongartz "HaraldB" for providing his Ideas and Code for usibility*
*****************************************************************************/
 
 
#ifndef _USART_H
#define _USART_H
 
//--------------------------------------------------------------
//
#ifndef FALSE
#define FALSE 0
#endif
#ifndef TRUE
#define TRUE 1
#endif
 
// addresses
#define ADDRESS_ANY 0
#define ADDRESS_FC 1
#define ADDRESS_NC 2
#define ADDRESS_MAG 3
 
// must be at least 4('#'+Addr+'CmdID'+'\r')+ (80 * 4)/3 = 111 bytes
#define TXD_BUFFER_LEN 180
#define RXD_BUFFER_LEN 180
 
// Baud rate of the USART
#define USART_BAUD 57600
//#define USART_BAUD 125000
 
//--------------------------------------------------------------
//
extern uint8_t buffer[30];
 
extern volatile uint8_t txd_buffer[TXD_BUFFER_LEN];
extern volatile uint8_t txd_complete;
extern volatile uint8_t txd1_buffer[TXD_BUFFER_LEN];
extern volatile uint8_t txd1_complete;
extern volatile uint8_t rxd_buffer[RXD_BUFFER_LEN];
extern volatile uint8_t rxd_buffer_locked;
extern volatile uint8_t ReceivedBytes;
extern volatile uint8_t *pRxData;
extern volatile uint8_t RxDataLen;
 
extern volatile uint16_t stat_crc_error;
extern volatile uint16_t stat_overflow_error;
 
extern volatile uint8_t rxFlag;
extern volatile uint8_t rx_byte;
 
//--------------------------------------------------------------
//
void SetBaudUart0(uint8_t Baudrate);
void USART_Init (unsigned int baudrate);
void USART_DisableTXD (void);
void USART_EnableTXD (void);
void USART_request_mk_data (uint8_t cmd, uint8_t addr, uint8_t ms);
 
void USART_putc (char c);
void USART_puts (char *s);
void USART_puts_p (const char *s);
 
 
extern char USART_getc(void);
void SendOutData (uint8_t cmd, uint8_t addr, uint8_t numofbuffers, ...); // uint8_t *pdata, uint8_t len, ...
//void SendOutData(uint8_t cmd, uint8_t addr, uint8_t numofbuffers, uint8_t *pdata, uint8_t len); // uint8_t *pdata, uint8_t len, ...
void Decode64 (void);
 
void SwitchToNC (void);
void SwitchToFC (void);
void SwitchToMAG (void);
void SwitchToGPS (void);
void SwitchToWi232 (void);
void debug1(void);
 
uint8_t uart_getc_nb(uint8_t*);
 
//--------------------------------------------------------------
//Anpassen der seriellen Schnittstellen Register
#define USART_RXC_vect USART0_RX_vect
//--------------------------------------------------------------
#define UCSRA UCSR0A
#define UCSRB UCSR0B
#define UCSRC UCSR0C
#define UDR UDR0
#define UBRRL UBRR0L
#define UBRRH UBRR0H
 
// UCSRA
#define RXC RXC0
#define TXC TXC0
#define UDRE UDRE0
#define FE FE0
#define UPE UPE0
#define U2X U2X0
#define MPCM MPCM0
 
// UCSRB
#define RXCIE RXCIE0
#define TXCIE TXCIE0
#define UDRIE UDRIE0
#define TXEN TXEN0
#define RXEN RXEN0
#define UCSZ2 UCSZ02
#define RXB8 RXB80
#define TXB8 TXB80
 
// UCSRC
#define UMSEL1 UMSEL01
#define UMSEL0 UMSEL00
#define UPM1 UPM01
#define UPM0 UPM00
#define USBS USBS0
#define UCSZ1 UCSZ01
#define UCSZ0 UCSZ00
#define UCPOL UCPOL0
 
 
#endif
 
Property changes:
Added: svn:mime-type
+text/plain
\ No newline at end of property