Subversion Repositories FlightCtrl

Compare Revisions

Ignore whitespace Rev 885 → Rev 886

/branches/V0.69k Code Redesign killagreg/uart.c
1,4 → 1,4
// ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
// ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
// + Copyright (c) 04.2007 Holger Buss
// + only for non-profit use
// + www.MikroKopter.com
5,60 → 5,88
// + see the File "License.txt" for further Informations
// ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
 
#include <avr/io.h>
#include <avr/interrupt.h>
#include <avr/wdt.h>
 
#include "eeprom.h"
#include "main.h"
#include "menu.h"
#include "timer0.h"
#include "uart.h"
#include "fc.h"
#include "_Settings.h"
#include "rc.h"
#ifdef USE_KILLAGREG
#include "ubx.h"
#endif
#if !defined(USE_KILLAGREG) && !defined (USE_NAVICTRL)
#include "mk3mag.h"
#endif
 
unsigned char DebugGetAnforderung = 0,DebugDisplayAnforderung = 0,DebugDataAnforderung = 0,GetVersionAnforderung = 0;
unsigned volatile char SioTmp = 0;
unsigned volatile char SendeBuffer[MAX_SENDE_BUFF];
unsigned volatile char RxdBuffer[MAX_EMPFANGS_BUFF];
unsigned volatile char NMEABuffer[MAX_EMPFANGS_BUFF];
unsigned volatile char NeuerDatensatzEmpfangen = 0;
unsigned volatile char NeueKoordinateEmpfangen = 0;
unsigned volatile char UebertragungAbgeschlossen = 1;
unsigned volatile char CntCrcError = 0;
unsigned volatile char AnzahlEmpfangsBytes = 0;
unsigned volatile char PC_DebugTimeout = 0;
unsigned char RemotePollDisplayLine = 0;
unsigned char NurKanalAnforderung = 0;
unsigned char DebugTextAnforderung = 255;
unsigned char PcZugriff = 100;
unsigned char MotorTest[4] = {0,0,0,0};
unsigned char DubWiseKeys[4] = {0,0,0,0};
unsigned char MeineSlaveAdresse;
unsigned char ConfirmFrame;
struct str_DebugOut DebugOut;
struct str_ExternControl ExternControl;
struct str_VersionInfo VersionInfo;
struct str_WinkelOut WinkelOut;
 
int Debug_Timer,Kompass_Timer;
 
const unsigned char ANALOG_TEXT[32][16] =
#define FALSE 0
#define TRUE 1
 
//int8_t test __attribute__ ((section (".noinit")));
uint8_t RequestVerInfo = FALSE;
uint8_t RequestExternalControl = FALSE;
uint8_t RequestDisplay = FALSE;
uint8_t RequestDebugData = FALSE;
uint8_t RequestDebugLabel = 255;
uint8_t RequestChannelOnly = FALSE;
uint8_t RemotePollDisplayLine = 0;
 
volatile uint8_t txd_buffer[TXD_BUFFER_LEN];
volatile uint8_t rxd_buffer_locked = FALSE;
volatile uint8_t rxd_buffer[RXD_BUFFER_LEN];
volatile uint8_t txd_complete = TRUE;
volatile uint8_t ReceivedBytes = 0;
 
 
uint8_t PcAccess = 100;
uint8_t MotorTest[4] = {0,0,0,0};
uint8_t DubWiseKeys[4] = {0,0,0,0};
uint8_t MySlaveAddr = 0;
uint8_t ConfirmFrame;
 
DebugOut_t DebugOut;
ExternControl_t ExternControl;
VersionInfo_t VersionInfo;
 
int16_t Debug_Timer;
 
#if !defined (USE_KILLAGREG) && !defined (USE_NAVICTRL)
int16_t Compass_Timer;
#endif
 
 
const uint8_t ANALOG_LABEL[32][16] =
{
//1234567890123456
"IntegralNick ", //0
//1234567890123456
"IntegralPitch ", //0
"IntegralRoll ",
"AccNick ",
"AccPitch ",
"AccRoll ",
"GyroGier ",
"HoehenWert ", //5
"GyroYaw ",
"ReadingHeight ", //5
"AccZ ",
"Gas ",
"KompassValue ",
"Spannung ",
"Empfang ", //10
"Ersatzkompass ",
"Motor_Vorne ",
"Motor_Hinten ",
"Motor_Links ",
"Motor_Rechts ", //15
"Thrust ",
"CompassHeading ",
"Voltage ",
"Receiver Level ", //10
"YawGyroHeading ",
"Motor_Front ",
"Motor_Rear ",
"Motor_Right ",
"Motor_Left ", //15
"Acc_Z ",
"Distance ",
"OsdBar ",
"MK3Mag CalState ",
"SPI Error ",
"SPI Ok ",
" ",
"Servo ", //20
"Nick ",
"Pitch ",
"Roll ",
" ",
" ",
67,355 → 95,422
" ",
" ",
" ",
"GPS_Nick ", //30
"GPS_Pitch ", //30
"GPS_Roll "
};
 
 
 
//+++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
//++ Sende-Part der Datenübertragung
//+++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
SIGNAL(INT_VEC_TX)
/****************************************************************/
/* Initialization of the USART0 */
/****************************************************************/
void USART0_Init (void)
{
static unsigned int ptr = 0;
unsigned char tmp_tx;
if(!UebertragungAbgeschlossen)
{
ptr++; // die [0] wurde schon gesendet
tmp_tx = SendeBuffer[ptr];
if((tmp_tx == '\r') || (ptr == MAX_SENDE_BUFF))
{
ptr = 0;
UebertragungAbgeschlossen = 1;
}
UDR = tmp_tx;
}
else ptr = 0;
uint8_t sreg = SREG;
uint16_t ubrr = (uint16_t) ((uint32_t) SYSCLK/(8 * USART0_BAUD) - 1);
 
// disable all interrupts before configuration
cli();
 
// disable RX-Interrupt
UCSR0B &= ~(1 << RXCIE0);
// disable TX-Interrupt
UCSR0B &= ~(1 << TXCIE0);
 
// set direction of RXD0 and TXD0 pins
// set RXD0 (PD0) as an input pin
PORTD |= (1 << PORTD0);
DDRD &= ~(1 << DDD0);
// set TXD0 (PD1) as an output pin
PORTD |= (1 << PORTD1);
DDRD |= (1 << DDD1);
 
// USART0 Baud Rate Register
// set clock divider
UBRR0H = (uint8_t)(ubrr >> 8);
UBRR0L = (uint8_t)ubrr;
 
// USART0 Control and Status Register A, B, C
 
// enable double speed operation in
UCSR0A |= (1 << U2X0);
// enable receiver and transmitter in
UCSR0B = (1 << TXEN0) | (1 << RXEN0);
// set asynchronous mode
UCSR0C &= ~(1 << UMSEL01);
UCSR0C &= ~(1 << UMSEL00);
// no parity
UCSR0C &= ~(1 << UPM01);
UCSR0C &= ~(1 << UPM00);
// 1 stop bit
UCSR0C &= ~(1 << USBS0);
// 8-bit
UCSR0B &= ~(1 << UCSZ02);
UCSR0C |= (1 << UCSZ01);
UCSR0C |= (1 << UCSZ00);
 
// flush receive buffer
while ( UCSR0A & (1<<RXC0) ) UDR0;
 
// enable interrupts at the end
// enable RX-Interrupt
UCSR0B |= (1 << RXCIE0);
// enable TX-Interrupt
UCSR0B |= (1 << TXCIE0);
 
rxd_buffer_locked = FALSE;
txd_complete = TRUE;
 
Debug_Timer = SetDelay(200);
 
#if !defined (USE_KILLAGREG) && !defined (USE_NAVICTRL)
Compass_Timer = SetDelay(220);
#endif
 
// restore global interrupt flags
SREG = sreg;
}
 
//+++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
//++ Empfangs-Part der Datenübertragung, incl. CRC-Auswertung
//+++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
SIGNAL(INT_VEC_RX)
/****************************************************************/
/* USART0 transmitter ISR */
/****************************************************************/
ISR(USART0_TX_vect)
{
static unsigned int crc;
static unsigned char crc1,crc2,buf_ptr;
static unsigned char UartState = 0;
unsigned char CrcOkay = 0;
static uint16_t ptr_txd_buffer = 0;
uint8_t tmp_tx;
if(!txd_complete) // transmission not completed
{
ptr_txd_buffer++; // die [0] wurde schon gesendet
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 = 1; // stop transmission
}
UDR0 = tmp_tx; // send current byte will trigger this ISR again
}
// transmission completed
else ptr_txd_buffer = 0;
}
 
SioTmp = UDR;
if(buf_ptr >= MAX_EMPFANGS_BUFF) UartState = 0;
if(SioTmp == '\r' && UartState == 2)
{
UartState = 0;
crc -= RxdBuffer[buf_ptr-2];
crc -= RxdBuffer[buf_ptr-1];
crc %= 4096;
crc1 = '=' + crc / 64;
crc2 = '=' + crc % 64;
CrcOkay = 0;
if((crc1 == RxdBuffer[buf_ptr-2]) && (crc2 == RxdBuffer[buf_ptr-1])) CrcOkay = 1; else { CrcOkay = 0; CntCrcError++;};
if(!NeuerDatensatzEmpfangen && CrcOkay) // Datensatz schon verarbeitet
{
NeuerDatensatzEmpfangen = 1;
AnzahlEmpfangsBytes = buf_ptr;
RxdBuffer[buf_ptr] = '\r';
if(RxdBuffer[2] == 'R') wdt_enable(WDTO_250MS); // Reset-Commando
}
}
else
switch(UartState)
{
case 0:
if(SioTmp == '#' && !NeuerDatensatzEmpfangen) UartState = 1; // Startzeichen und Daten schon verarbeitet
buf_ptr = 0;
RxdBuffer[buf_ptr++] = SioTmp;
crc = SioTmp;
break;
case 1: // Adresse auswerten
UartState++;
RxdBuffer[buf_ptr++] = SioTmp;
crc += SioTmp;
break;
case 2: // Eingangsdaten sammeln
RxdBuffer[buf_ptr] = SioTmp;
if(buf_ptr < MAX_EMPFANGS_BUFF) buf_ptr++;
else UartState = 0;
crc += SioTmp;
break;
default:
UartState = 0;
break;
}
/****************************************************************/
/* USART0 receiver ISR */
/****************************************************************/
ISR(USART0_RX_vect)
{
static uint16_t crc;
static uint8_t ptr_rxd_buffer = 0;
uint8_t crc1, crc2;
uint8_t c;
 
c = UDR0; // catch the received byte
 
#ifdef USE_KILLAGREG
// If the FC 1.0 cpu is used the ublox module should be conneced to rxd of the 1st uart.
// The FC 1.1 /1.2 has the ATMEGA644p cpu with a 2nd uart to which the ublox should be connected.
#if defined (__AVR_ATmega644P__)
if(BoardRelease == 10) ubx_parser(c);
#else
ubx_parser(c);
#endif
#endif // USE_KILLAGREG
 
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
}
#if 0
else if (ptr_rxd_buffer == 1) // handle address
{
rxd_buffer[ptr_rxd_buffer++] = c; // copy byte to rxd buffer
crc += c; // update crc
}
#endif
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_locked = TRUE; // lock the rxd buffer
ReceivedBytes = ptr_rxd_buffer; // store number of received bytes
rxd_buffer[ptr_rxd_buffer] = '\r'; // set termination character
// 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
rxd_buffer_locked = FALSE; // unlock rxd buffer
}
ptr_rxd_buffer = 0; // reset rxd buffer pointer
}
}
else // rxd buffer overrun
{
ptr_rxd_buffer = 0; // reset rxd buffer
rxd_buffer_locked = FALSE; // unlock rxd buffer
}
 
}
 
 
// --------------------------------------------------------------------------
void AddCRC(unsigned int wieviele)
void AddCRC(uint16_t datalen)
{
unsigned int tmpCRC = 0,i;
for(i = 0; i < wieviele;i++)
{
tmpCRC += SendeBuffer[i];
}
tmpCRC %= 4096;
SendeBuffer[i++] = '=' + tmpCRC / 64;
SendeBuffer[i++] = '=' + tmpCRC % 64;
SendeBuffer[i++] = '\r';
UebertragungAbgeschlossen = 0;
UDR = SendeBuffer[0];
uint16_t tmpCRC = 0, i;
for(i = 0; i < datalen; i++)
{
tmpCRC += txd_buffer[i];
}
tmpCRC %= 4096;
txd_buffer[i++] = '=' + tmpCRC / 64;
txd_buffer[i++] = '=' + tmpCRC % 64;
txd_buffer[i++] = '\r';
txd_complete = FALSE;
UDR0 = txd_buffer[0]; // initiates the transmittion (continued in the TXD ISR)
}
 
 
 
// --------------------------------------------------------------------------
void SendOutData(unsigned char cmd,unsigned char modul, unsigned char *snd, unsigned char len)
void SendOutData(uint8_t cmd,uint8_t module, uint8_t *snd, uint8_t len)
{
unsigned int pt = 0;
unsigned char a,b,c;
unsigned char ptr = 0;
uint16_t pt = 0;
uint8_t a,b,c;
uint8_t ptr = 0;
 
SendeBuffer[pt++] = '#'; // Startzeichen
SendeBuffer[pt++] = modul; // Adresse (a=0; b=1,...)
SendeBuffer[pt++] = cmd; // Commando
txd_buffer[pt++] = '#'; // Start character
txd_buffer[pt++] = module; // Address (a=0; b=1,...)
txd_buffer[pt++] = cmd; // Command
 
while(len)
{
if(len) { a = snd[ptr++]; len--;} else a = 0;
if(len) { b = snd[ptr++]; len--;} else b = 0;
if(len) { c = snd[ptr++]; len--;} else c = 0;
SendeBuffer[pt++] = '=' + (a >> 2);
SendeBuffer[pt++] = '=' + (((a & 0x03) << 4) | ((b & 0xf0) >> 4));
SendeBuffer[pt++] = '=' + (((b & 0x0f) << 2) | ((c & 0xc0) >> 6));
SendeBuffer[pt++] = '=' + ( c & 0x3f);
}
AddCRC(pt);
while(len)
{
if(len) { a = snd[ptr++]; len--;} else a = 0;
if(len) { b = snd[ptr++]; len--;} else b = 0;
if(len) { c = snd[ptr++]; len--;} 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);
}
AddCRC(pt); // add checksum after data block and initates the transmission
}
 
 
// --------------------------------------------------------------------------
void Decode64(unsigned char *ptrOut, unsigned char len, unsigned char ptrIn,unsigned char max) // Wohin mit den Daten; Wie lang; Wo im RxdBuffer
void Decode64(uint8_t *ptrOut, uint8_t len, uint8_t ptrIn, uint8_t max)
{
unsigned char a,b,c,d;
unsigned char ptr = 0;
unsigned char x,y,z;
while(len)
{
a = RxdBuffer[ptrIn++] - '=';
b = RxdBuffer[ptrIn++] - '=';
c = RxdBuffer[ptrIn++] - '=';
d = RxdBuffer[ptrIn++] - '=';
if(ptrIn > max - 2) break; // nicht mehr Daten verarbeiten, als empfangen wurden
uint8_t a,b,c,d;
uint8_t ptr = 0;
uint8_t x,y,z;
while(len)
{
a = rxd_buffer[ptrIn++] - '=';
b = rxd_buffer[ptrIn++] - '=';
c = rxd_buffer[ptrIn++] - '=';
d = rxd_buffer[ptrIn++] - '=';
if(ptrIn > max - 2) break;
 
x = (a << 2) | (b >> 4);
y = ((b & 0x0f) << 4) | (c >> 2);
z = ((c & 0x03) << 6) | d;
x = (a << 2) | (b >> 4);
y = ((b & 0x0f) << 4) | (c >> 2);
z = ((c & 0x03) << 6) | d;
 
if(len--) ptrOut[ptr++] = x; else break;
if(len--) ptrOut[ptr++] = y; else break;
if(len--) ptrOut[ptr++] = z; else break;
}
 
if(len--) ptrOut[ptr++] = x; else break;
if(len--) ptrOut[ptr++] = y; else break;
if(len--) ptrOut[ptr++] = z; else break;
}
}
 
 
// --------------------------------------------------------------------------
void BearbeiteRxDaten(void)
void USART0_ProcessRxData(void)
{
if(!NeuerDatensatzEmpfangen) return;
// if data in the rxd buffer are not locked immediately return
if(!rxd_buffer_locked) return;
 
unsigned int tmp_int_arr1[1];
// unsigned int tmp_int_arr2[2];
// unsigned int tmp_int_arr3[3];
unsigned char tmp_char_arr2[2];
// unsigned char tmp_char_arr3[3];
// unsigned char tmp_char_arr4[4];
//if(!MotorenEin)
switch(RxdBuffer[2])
{
case 'K':// Kompasswert
Decode64((unsigned char *) &tmp_int_arr1[0],sizeof(tmp_int_arr1),3,AnzahlEmpfangsBytes);
KompassValue = tmp_int_arr1[0];
KompassRichtung = ((540 + KompassValue - KompassStartwert) % 360) - 180;
#if !defined (USE_KILLAGREG) && !defined (USE_NAVICTRL)
uint16_t tmp_int_arr1[1]; // local int buffer
#endif
uint8_t tmp_char_arr2[2]; // local char buffer
 
 
switch(rxd_buffer[2])
{
#if !defined (USE_KILLAGREG) && !defined (USE_NAVICTRL)
case 'K':// Compass value
Decode64((uint8_t *) &tmp_int_arr1[0], sizeof(tmp_int_arr1), 3, ReceivedBytes);
CompassHeading = tmp_int_arr1[0];
CompassOffCourse = ((540 + CompassHeading - CompassCourse) % 360) - 180;
break;
case 'a':// Texte der Analogwerte
Decode64((unsigned char *) &tmp_char_arr2[0],sizeof(tmp_char_arr2),3,AnzahlEmpfangsBytes);
DebugTextAnforderung = tmp_char_arr2[0];
PcZugriff = 255;
#endif
case 'a':// Labels of the Analog Debug outputs
Decode64((uint8_t *) &tmp_char_arr2[0], sizeof(tmp_char_arr2), 3, ReceivedBytes);
RequestDebugLabel = tmp_char_arr2[0];
PcAccess = 255;
break;
case 'b':
Decode64((unsigned char *) &ExternControl,sizeof(ExternControl),3,AnzahlEmpfangsBytes);
RemoteTasten |= ExternControl.RemoteTasten;
ConfirmFrame = ExternControl.Frame;
break;
case 'c':
Decode64((unsigned char *) &ExternControl,sizeof(ExternControl),3,AnzahlEmpfangsBytes);
RemoteTasten |= ExternControl.RemoteTasten;
ConfirmFrame = ExternControl.Frame;
DebugDataAnforderung = 1;
PcZugriff = 255;
break;
case 'h':// x-1 Displayzeilen
Decode64((unsigned char *) &tmp_char_arr2[0],sizeof(tmp_char_arr2),3,AnzahlEmpfangsBytes);
RemoteTasten |= tmp_char_arr2[0];
if(tmp_char_arr2[1] == 255) NurKanalAnforderung = 1; else NurKanalAnforderung = 0; // keine Displaydaten
DebugDisplayAnforderung = 1;
case 'b': // extern control
Decode64((uint8_t *) &ExternControl,sizeof(ExternControl), 3, ReceivedBytes);
RemoteButtons |= ExternControl.RemoteButtons;
ConfirmFrame = ExternControl.Frame;
break;
case 't':// Motortest
Decode64((unsigned char *) &MotorTest[0],sizeof(MotorTest),3,AnzahlEmpfangsBytes);
PcZugriff = 255;
case 'c': // extern control with debug request
Decode64((uint8_t *) &ExternControl,sizeof(ExternControl),3,ReceivedBytes);
RemoteButtons |= ExternControl.RemoteButtons;
ConfirmFrame = ExternControl.Frame;
RequestDebugData = TRUE;
PcAccess = 255;
break;
case 'k':// Keys von DubWise
Decode64((unsigned char *) &DubWiseKeys[0],sizeof(DubWiseKeys),3,AnzahlEmpfangsBytes);
case 'h':// x-1 display columns
Decode64((uint8_t *) &tmp_char_arr2[0],sizeof(tmp_char_arr2),3,ReceivedBytes);
RemoteButtons |= tmp_char_arr2[0];
if(tmp_char_arr2[1] == 255) RequestChannelOnly = TRUE;
else RequestChannelOnly = FALSE; // keine Displaydaten
RequestDisplay = TRUE;
break;
case 't':// motor test
Decode64((uint8_t *) &MotorTest[0],sizeof(MotorTest),3,ReceivedBytes);
PcAccess = 255;
break;
case 'k':// keys from DubWise
Decode64((uint8_t *) &DubWiseKeys[0],sizeof(DubWiseKeys),3,ReceivedBytes);
ConfirmFrame = DubWiseKeys[3];
PcZugriff = 255;
PcAccess = 255;
break;
case 'v': // Version-Anforderung und Ausbaustufe
GetVersionAnforderung = 1;
break;
case 'g':// "Get"-Anforderung für Debug-Daten
// Bei Get werden die vom PC einstellbaren Werte vom PC zurückgelesen
DebugGetAnforderung = 1;
break;
case 'q':// "Get"-Anforderung für Settings
// Bei Get werden die vom PC einstellbaren Werte vom PC zurückgelesen
Decode64((unsigned char *) &tmp_char_arr2[0],sizeof(tmp_char_arr2),3,AnzahlEmpfangsBytes);
while(!UebertragungAbgeschlossen);
if(tmp_char_arr2[0] != 0xff)
{
if(tmp_char_arr2[0] > 5) tmp_char_arr2[0] = 5;
ReadParameterSet(tmp_char_arr2[0], (unsigned char *) &EE_Parameter.Kanalbelegung[0], STRUCT_PARAM_LAENGE);
SendOutData('L' + tmp_char_arr2[0] -1,MeineSlaveAdresse,(unsigned char *) &EE_Parameter.Kanalbelegung[0],STRUCT_PARAM_LAENGE);
}
else
SendOutData('L' + GetActiveParamSetNumber()-1,MeineSlaveAdresse,(unsigned char *) &EE_Parameter.Kanalbelegung[0],STRUCT_PARAM_LAENGE);
break;
case 'l':
case 'm':
case 'n':
case 'o':
case 'p': // Parametersatz speichern
Decode64((unsigned char *) &EE_Parameter.Kanalbelegung[0],STRUCT_PARAM_LAENGE,3,AnzahlEmpfangsBytes);
WriteParameterSet(RxdBuffer[2] - 'l' + 1, (unsigned char *) &EE_Parameter.Kanalbelegung[0], STRUCT_PARAM_LAENGE);
eeprom_write_byte(&EEPromArray[EEPROM_ADR_ACTIVE_SET], RxdBuffer[2] - 'l' + 1); // aktiven Datensatz merken
Umschlag180Nick = (long) EE_Parameter.WinkelUmschlagNick * 2500L;
Umschlag180Roll = (long) EE_Parameter.WinkelUmschlagRoll * 2500L;
Piep(GetActiveParamSetNumber());
break;
}
// DebugOut.AnzahlZyklen = Debug_Timer_Intervall;
NeuerDatensatzEmpfangen = 0;
case 'v': // get version and board release
RequestVerInfo = TRUE;
break;
case 'g':// get external control data
RequestExternalControl = TRUE;
break;
case 'q':// get settings
Decode64((uint8_t *) &tmp_char_arr2[0],sizeof(tmp_char_arr2),3,ReceivedBytes);
while(!txd_complete);
if(tmp_char_arr2[0] != 0xff)
{
if(tmp_char_arr2[0] > 5) tmp_char_arr2[0] = 5; // limit to 5
// load requested parameter set
ParamSet_ReadFromEEProm(tmp_char_arr2[0]);
SendOutData('L' + tmp_char_arr2[0] -1,MySlaveAddr,(uint8_t *) &ParamSet.ChannelAssignment[0],PARAMSET_STRUCT_LEN);
}
else // send active parameter set
SendOutData('L' + GetParamByte(PID_ACTIVE_SET)-1,MySlaveAddr,(uint8_t *) &ParamSet.ChannelAssignment[0],PARAMSET_STRUCT_LEN);
 
break;
 
case 'l':
case 'm':
case 'n':
case 'o':
case 'p': // save parameterset
Decode64((uint8_t *) &ParamSet.ChannelAssignment[0],PARAMSET_STRUCT_LEN,3,ReceivedBytes);
ParamSet_WriteToEEProm(rxd_buffer[2] - 'l' + 1);
TurnOver180Pitch = (int32_t) ParamSet.AngleTurnOverPitch * 2500L;
TurnOver180Roll = (int32_t) ParamSet.AngleTurnOverRoll * 2500L;
Beep(GetActiveParamSet());
break;
 
 
}
// unlock the rxd buffer after processing
rxd_buffer_locked = FALSE;
}
 
//############################################################################
//Routine für die Serielle Ausgabe
int uart_putchar (char c)
int16_t uart_putchar (int8_t c)
//############################################################################
{
if (c == '\n')
uart_putchar('\r');
//Warten solange bis Zeichen gesendet wurde
loop_until_bit_is_set(USR, UDRE);
// wait until previous character was send
loop_until_bit_is_set(UCSR0A, UDRE0);
//Ausgabe des Zeichens
UDR = c;
UDR0 = c;
return (0);
}
 
// --------------------------------------------------------------------------
void WriteProgramData(unsigned int pos, unsigned char wert)
{
//if (ProgramLocation == IN_RAM) Buffer[pos] = wert;
// else eeprom_write_byte(&EE_Buffer[pos], wert);
// Buffer[pos] = wert;
}
 
//############################################################################
//INstallation der Seriellen Schnittstelle
void UART_Init (void)
//############################################################################
//---------------------------------------------------------------------------------------------
void USART0_TransmitTxData(void)
{
//Enable TXEN im Register UCR TX-Data Enable & RX Enable
if(!txd_complete) return;
 
UCR=(1 << TXEN) | (1 << RXEN);
// UART Double Speed (U2X)
USR |= (1<<U2X);
// RX-Interrupt Freigabe
UCSRB |= (1<<RXCIE);
// TX-Interrupt Freigabe
UCSRB |= (1<<TXCIE);
if(RequestExternalControl && txd_complete) // Bei Get werden die vom PC einstellbaren Werte vom PC zurückgelesen
{
SendOutData('G',MySlaveAddr,(uint8_t *) &ExternControl,sizeof(ExternControl));
RequestExternalControl = FALSE;
}
 
//Teiler wird gesetzt
UBRR=(SYSCLK / (BAUD_RATE * 8L) - 1);
//UBRR = 33;
//öffnet einen Kanal für printf (STDOUT)
//fdevopen (uart_putchar, 0);
//sbi(PORTD,4);
Debug_Timer = SetDelay(200);
Kompass_Timer = SetDelay(220);
}
#if !defined (USE_KILLAGREG) && !defined (USE_NAVICTRL)
if((CheckDelay(Compass_Timer)) && txd_complete)
{
ToMk3Mag.Attitude[0] = (int16_t) (IntegralPitch / 108); // approx. 0,1 Deg
ToMk3Mag.Attitude[1] = (int16_t) (IntegralRoll / 108); // approx. 0,1 Deg
ToMk3Mag.UserParam[0] = FCParam.UserParam1;
ToMk3Mag.UserParam[1] = FCParam.UserParam2;
ToMk3Mag.CalState = CompassCalState;
SendOutData('w',MySlaveAddr,(uint8_t *) &ToMk3Mag,sizeof(ToMk3Mag));
// the last state is 5 and should be send only once to avoid multiple flash writing
if(CompassCalState > 4) CompassCalState = 0;
Compass_Timer = SetDelay(99);
}
#endif
 
//---------------------------------------------------------------------------------------------
void DatenUebertragung(void)
{
if(!UebertragungAbgeschlossen) return;
if((CheckDelay(Debug_Timer) || RequestDebugData) && txd_complete)
{
SendOutData('D',MySlaveAddr,(uint8_t *) &DebugOut,sizeof(DebugOut));
RequestDebugData = FALSE;
Debug_Timer = SetDelay(MIN_DEBUG_INTERVALL);
}
 
if(DebugGetAnforderung && UebertragungAbgeschlossen) // Bei Get werden die vom PC einstellbaren Werte vom PC zurückgelesen
{
SendOutData('G',MeineSlaveAdresse,(unsigned char *) &ExternControl,sizeof(ExternControl));
DebugGetAnforderung = 0;
}
 
if((CheckDelay(Kompass_Timer)) && UebertragungAbgeschlossen)
{
WinkelOut.Winkel[0] = (int) (IntegralNick / 108); // etwa in 0,1 Grad
WinkelOut.Winkel[1] = (int) (IntegralRoll / 108); // etwa in 0,1 Grad
WinkelOut.UserParameter[0] = Parameter_UserParam1;
WinkelOut.UserParameter[1] = Parameter_UserParam2;
SendOutData('w',MeineSlaveAdresse,(unsigned char *) &WinkelOut,sizeof(WinkelOut));
if(WinkelOut.CalcState > 4) WinkelOut.CalcState = 6; // wird dann in SPI auf Null gesetzt
Kompass_Timer = SetDelay(99);
}
 
if((CheckDelay(Debug_Timer) || DebugDataAnforderung) && UebertragungAbgeschlossen)
{
SendOutData('D',MeineSlaveAdresse,(unsigned char *) &DebugOut,sizeof(DebugOut));
DebugDataAnforderung = 0;
Debug_Timer = SetDelay(MIN_DEBUG_INTERVALL);
}
if(DebugTextAnforderung != 255) // Texte für die Analogdaten
if(RequestDebugLabel != 255) // Texte für die Analogdaten
{
SendOutData('A',DebugTextAnforderung + '0',(unsigned char *) ANALOG_TEXT[DebugTextAnforderung],16);
DebugTextAnforderung = 255;
SendOutData('A',RequestDebugLabel + '0',(uint8_t *) ANALOG_LABEL[RequestDebugLabel],16);
RequestDebugLabel = 255;
}
if(ConfirmFrame && UebertragungAbgeschlossen) // Datensatz ohne CRC bestätigen
if(ConfirmFrame && txd_complete) // Datensatz ohne CRC bestätigen
{
SendeBuffer[0] = '#';
SendeBuffer[1] = ConfirmFrame;
SendeBuffer[2] = '\r';
UebertragungAbgeschlossen = 0;
txd_buffer[0] = '#';
txd_buffer[1] = ConfirmFrame;
txd_buffer[2] = '\r';
txd_complete = 0;
ConfirmFrame = 0;
UDR = SendeBuffer[0];
UDR0 = txd_buffer[0];
}
if(DebugDisplayAnforderung && UebertragungAbgeschlossen)
if(RequestDisplay && txd_complete)
{
Menu();
DebugDisplayAnforderung = 0;
if(++RemotePollDisplayLine == 4 || NurKanalAnforderung)
LCD_PrintMenu();
RequestDisplay = FALSE;
if(++RemotePollDisplayLine == 4 || RequestChannelOnly)
{
SendOutData('4',0,(unsigned char *)&PPM_in,sizeof(PPM_in)); // DisplayZeile übertragen
SendOutData('4',0,(uint8_t *)&PPM_in,sizeof(PPM_in)); // DisplayZeile übertragen
RemotePollDisplayLine = -1;
}
else SendOutData('0' + RemotePollDisplayLine,0,(unsigned char *)&DisplayBuff[20 * RemotePollDisplayLine],20); // DisplayZeile übertragen
}
if(GetVersionAnforderung && UebertragungAbgeschlossen)
{
SendOutData('V',MeineSlaveAdresse,(unsigned char *) &VersionInfo,sizeof(VersionInfo));
GetVersionAnforderung = 0;
}
else SendOutData('0' + RemotePollDisplayLine,0,(uint8_t *)&DisplayBuff[20 * RemotePollDisplayLine],20); // DisplayZeile übertragen
}
if(RequestVerInfo && txd_complete)
{
SendOutData('V',MySlaveAddr,(uint8_t *) &VersionInfo,sizeof(VersionInfo));
RequestVerInfo = FALSE;
}
 
}