Subversion Repositories FlightCtrl

Compare Revisions

Ignore whitespace Rev 1024 → Rev 1025

/branches/V0.70d_flinkflash/include/Settings.h
--- include/_Settings.h (nonexistent)
+++ include/_Settings.h (revision 1025)
@@ -0,0 +1,44 @@
+// ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
+// Abstimmung
+// ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
+#define ACC_AMPLIFY 12
+#define FAKTOR_P 1
+#define FAKTOR_I 0.0001
+
+
+// ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
+// Debug-Interface
+// ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
+#define SIO_DEBUG 1 // Soll der Debugger aktiviert sein?
+#define MIN_DEBUG_INTERVALL 250 // in diesem Intervall werden Degugdaten ohne Aufforderung gesendet
+
+// ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
+// Sender
+// ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
+ #define K_NICK 0
+ #define K_ROLL 1
+ #define K_GAS 2
+ #define K_GIER 3
+ #define K_POTI1 4
+ #define K_POTI2 5
+ #define K_POTI3 6
+ #define K_POTI4 7
+// +++++++++++++++++++++++++++++++
+// + Getestete Settings:
+// +++++++++++++++++++++++++++++++
+// Setting: Kamera
+// Stick_P:3
+// Stick_D:0
+// Gyro_P: 175
+// Gyro_I: 175
+// Ki_Anteil: 10
+// +++++++++++++++++++++++++++++++
+// + Getestete Settings:
+// +++++++++++++++++++++++++++++++
+// Setting: Normal
+// Stick_P:2
+// Stick_D:8
+// Gyro_P: 80
+// Gyro_I: 150
+// Ki_Anteil: 5
+
/branches/V0.70d_flinkflash/include/analog.h
0,0 → 1,26
/*#######################################################################################
 
#######################################################################################*/
 
extern volatile int UBat;
extern volatile int AdWertNick, AdWertRoll, AdWertGier;
extern volatile int AdWertAccRoll,AdWertAccNick,AdWertAccHoch;
extern volatile int Aktuell_Nick,Aktuell_Roll,Aktuell_Gier,Aktuell_ax, Aktuell_ay,Aktuell_az;
extern volatile long Luftdruck;
extern volatile char messanzahl_Druck;
extern volatile unsigned int ZaehlMessungen;
extern unsigned char DruckOffsetSetting;
extern volatile int HoeheD;
extern volatile unsigned int MessLuftdruck;
extern volatile int StartLuftdruck;
extern volatile char MessanzahlNick;
extern unsigned char AnalogOffsetNick,AnalogOffsetRoll,AnalogOffsetGier;
 
unsigned int ReadADC(unsigned char adc_input);
void ADC_Init(void);
void SucheLuftruckOffset(void);
void SucheGyroOffset(void);
 
 
#define ANALOG_OFF ADCSRA=0
#define ANALOG_ON ADCSRA=(1<<ADEN)|(1<<ADSC)|(1<<ADATE)|(1<<ADPS2)|(1<<ADPS1)|(1<<ADPS0)|(1<<ADIE)
/branches/V0.70d_flinkflash/include/fc.h
0,0 → 1,172
/*#######################################################################################
Flight Control
#######################################################################################*/
 
#ifndef _FC_H
#define _FC_H
//#define GIER_GRAD_FAKTOR 1450L // Abhängigkeit wzischen GyroIntegral und Winkel
#define GIER_GRAD_FAKTOR 1550L // Abhängigkeit wzischen GyroIntegral und Winkel
#define STICK_GAIN 4
 
#define FLAG_MOTOR_RUN 1
#define FLAG_FLY 2
#define FLAG_CALIBRATE 4
#define FLAG_START 8
extern unsigned char MikroKopterFlags;
 
extern volatile unsigned int I2CTimeout;
extern unsigned char Sekunde,Minute;
extern long IntegralNick,IntegralNick2;
extern long IntegralRoll,IntegralRoll2;
extern long Mess_IntegralNick,Mess_IntegralNick2;
extern long Mess_IntegralRoll,Mess_IntegralRoll2;
extern long IntegralAccNick,IntegralAccRoll;
extern volatile long Mess_Integral_Hoch;
extern long Integral_Gier,Mess_Integral_Gier,Mess_Integral_Gier2;
extern volatile int KompassValue;
extern volatile int KompassStartwert;
extern volatile int KompassRichtung;
extern long ErsatzKompass;
extern int ErsatzKompassInGrad; // Kompasswert in Grad
extern int HoehenWert;
extern int SollHoehe;
extern volatile int MesswertNick,MesswertRoll,MesswertGier;
extern int AdNeutralNick,AdNeutralRoll,AdNeutralGier, Mittelwert_AccNick, Mittelwert_AccRoll;
extern int NeutralAccX, NeutralAccY,Mittelwert_AccHoch;
extern volatile float NeutralAccZ;
extern long Umschlag180Nick, Umschlag180Roll;
extern signed int ExternStickNick,ExternStickRoll,ExternStickGier;
extern unsigned char Parameter_UserParam1,Parameter_UserParam2,Parameter_UserParam3,Parameter_UserParam4,Parameter_UserParam5,Parameter_UserParam6,Parameter_UserParam7,Parameter_UserParam8;
extern int NaviAccNick,NaviAccRoll,NaviCntAcc;
extern unsigned int modell_fliegt;
void MotorRegler(void);
void SendMotorData(void);
void CalibrierMittelwert(void);
void Mittelwert(void);
void SetNeutral(void);
void Piep(unsigned char Anzahl);
extern void DefaultKonstanten(void);
void DefaultKonstanten1(void);
void DefaultKonstanten2(void);
 
extern unsigned char h,m,s;
extern volatile unsigned char Timeout ;
extern unsigned char CosinusNickWinkel, CosinusRollWinkel;
extern volatile int DiffNick,DiffRoll;
extern int Poti1, Poti2, Poti3, Poti4;
extern volatile unsigned char Motor_Vorne,Motor_Hinten,Motor_Rechts,Motor_Links, Count;
extern volatile unsigned char SenderOkay;
extern int StickNick,StickRoll,StickGier;
extern char MotorenEin;
extern void DefaultKonstanten1(void);
extern void DefaultKonstanten2(void);
 
#define STRUCT_PARAM_LAENGE 83
struct mk_param_struct
{
unsigned char Kanalbelegung[8]; // GAS[0], GIER[1],NICK[2], ROLL[3], POTI1, POTI2, POTI3
unsigned char GlobalConfig; // 0x01=Höhenregler aktiv,0x02=Kompass aktiv, 0x04=GPS aktiv, 0x08=Heading Hold aktiv
unsigned char Hoehe_MinGas; // Wert : 0-100
unsigned char Luftdruck_D; // Wert : 0-250
unsigned char MaxHoehe; // Wert : 0-32
unsigned char Hoehe_P; // Wert : 0-32
unsigned char Hoehe_Verstaerkung; // Wert : 0-50
unsigned char Hoehe_ACC_Wirkung; // Wert : 0-250
unsigned char Stick_P; // Wert : 1-6
unsigned char Stick_D; // Wert : 0-64
unsigned char Gier_P; // Wert : 1-20
unsigned char Gas_Min; // Wert : 0-32
unsigned char Gas_Max; // Wert : 33-250
unsigned char GyroAccFaktor; // Wert : 1-64
unsigned char KompassWirkung; // Wert : 0-32
unsigned char Gyro_P; // Wert : 10-250
unsigned char Gyro_I; // Wert : 0-250
unsigned char UnterspannungsWarnung; // Wert : 0-250
unsigned char NotGas; // Wert : 0-250 //Gaswert bei Empängsverlust
unsigned char NotGasZeit; // Wert : 0-250 // Zeitbis auf NotGas geschaltet wird, wg. Rx-Problemen
unsigned char UfoAusrichtung; // X oder + Formation
unsigned char I_Faktor; // Wert : 0-250
unsigned char UserParam1; // Wert : 0-250
unsigned char UserParam2; // Wert : 0-250
unsigned char UserParam3; // Wert : 0-250
unsigned char UserParam4; // Wert : 0-250
unsigned char ServoNickControl; // Wert : 0-250 // Stellung des Servos
unsigned char ServoNickComp; // Wert : 0-250 // Einfluss Gyro/Servo
unsigned char ServoNickMin; // Wert : 0-250 // Anschlag
unsigned char ServoNickMax; // Wert : 0-250 // Anschlag
unsigned char ServoNickRefresh; //
unsigned char LoopGasLimit; // Wert: 0-250 max. Gas während Looping
unsigned char LoopThreshold; // Wert: 0-250 Schwelle für Stickausschlag
unsigned char LoopHysterese; // Wert: 0-250 Hysterese für Stickausschlag
unsigned char AchsKopplung1; // Wert: 0-250 Faktor, mit dem Gier die Achsen Roll und Nick koppelt (NickRollMitkopplung)
unsigned char AchsGegenKopplung1; // Wert: 0-250 Faktor, mit dem Gier die Achsen Roll und Nick Gegenkoppelt (NickRollGegenkopplung)
unsigned char WinkelUmschlagNick; // Wert: 0-250 180°-Punkt
unsigned char WinkelUmschlagRoll; // Wert: 0-250 180°-Punkt
unsigned char GyroAccAbgleich; // 1/k (Koppel_ACC_Wirkung)
unsigned char Driftkomp;
unsigned char DynamicStability;
unsigned char UserParam5; // Wert : 0-250
unsigned char UserParam6; // Wert : 0-250
unsigned char UserParam7; // Wert : 0-250
unsigned char UserParam8; // Wert : 0-250
//---Output ---------------------------------------------
unsigned char J16Bitmask; // for the J16 Output
unsigned char J16Timing; // for the J16 Output
unsigned char J17Bitmask; // for the J17 Output
unsigned char J17Timing; // for the J17 Output
//---NaviCtrl---------------------------------------------
unsigned char NaviGpsModeControl; // Parameters for the Naviboard
unsigned char NaviGpsGain;
unsigned char NaviGpsP;
unsigned char NaviGpsI;
unsigned char NaviGpsD;
unsigned char NaviGpsACC;
unsigned char NaviGpsMinSat;
unsigned char NaviStickThreshold;
//---Ext.Ctrl---------------------------------------------
unsigned char ExternalControl; // for serial Control
//------------------------------------------------
unsigned char LoopConfig; // Bitcodiert: 0x01=oben, 0x02=unten, 0x04=links, 0x08=rechts / wird getrennt behandelt
unsigned char ServoNickCompInvert; // Wert : 0-250 0 oder 1 // WICHTIG!!! am Ende lassen
unsigned char Reserved[4];
char Name[12];
};
 
 
/*
unsigned char ServoNickMax; // Wert : 0-250
unsigned char ServoNickRefresh; //
unsigned char LoopGasLimit; // Wert: 0-250 max. Gas während Looping
unsigned char LoopThreshold; // Wert: 0-250 Schwelle für Stickausschlag
//------------------------------------------------
unsigned char LoopConfig; // Bitcodiert: 0x01=oben, 0x02=unten, 0x04=links, 0x08=rechts / wird getrennt behandelt
unsigned char ServoNickCompInvert; // Wert : 0-250 0 oder 1 // WICHTIG!!! am Ende lassen
unsigned char Reserved[4];
char Name[12];
*/
extern struct mk_param_struct EE_Parameter;
 
extern unsigned char Parameter_Luftdruck_D;
extern unsigned char Parameter_MaxHoehe;
extern unsigned char Parameter_Hoehe_P;
extern unsigned char Parameter_Hoehe_ACC_Wirkung;
extern unsigned char Parameter_KompassWirkung;
extern unsigned char Parameter_Gyro_P;
extern unsigned char Parameter_Gyro_I;
extern unsigned char Parameter_Gier_P;
extern unsigned char Parameter_ServoNickControl;
extern unsigned char Parameter_AchsKopplung1;
extern unsigned char Parameter_AchsGegenKopplung1;
extern unsigned char Parameter_J16Bitmask; // for the J16 Output
extern unsigned char Parameter_J16Timing; // for the J16 Output
extern unsigned char Parameter_J17Bitmask; // for the J17 Output
extern unsigned char Parameter_J17Timing; // for the J17 Output
extern unsigned char Parameter_NaviGpsModeControl; // Parameters for the Naviboard
extern unsigned char Parameter_NaviGpsGain;
extern unsigned char Parameter_NaviGpsP;
extern unsigned char Parameter_NaviGpsI;
extern unsigned char Parameter_NaviGpsD;
extern unsigned char Parameter_NaviGpsACC;
#endif //_FC_H
 
/branches/V0.70d_flinkflash/include/gps.h
0,0 → 1,7
extern signed int GPS_Nick;
extern signed int GPS_Roll;
extern signed int GPS_Nick2;
extern signed int GPS_Roll2;
 
void GPS_Neutral(void);
void GPS_BerechneZielrichtung(void);
/branches/V0.70d_flinkflash/include/led.h
0,0 → 1,11
#include <avr/io.h>
 
#define J16_ON PORTC |= (1<<PORTC2)
#define J16_OFF PORTC &= ~(1<<PORTC2)
#define J16_TOGGLE PORTC ^= (1<<PORTC2)
#define J17_ON PORTC |= (1<<PORTC3)
#define J17_OFF PORTC &= ~(1<<PORTC3)
#define J17_TOGGLE PORTC ^= (1<<PORTC3)
 
extern void LED_Init(void);
extern void LED_Update(void);
/branches/V0.70d_flinkflash/include/main.h
0,0 → 1,103
#ifndef _MAIN_H
#define _MAIN_H
 
//Hier die Quarz Frequenz einstellen
#if defined (__AVR_ATmega32__)
#define SYSCLK 20000000L //Quarz Frequenz in Hz
#endif
 
#if defined (__AVR_ATmega644__)
#define SYSCLK 20000000L //Quarz Frequenz in Hz
//#define SYSCLK 16000000L //Quarz Frequenz in Hz
#endif
 
// neue Hardware
#define ROT_OFF {if(PlatinenVersion == 10) PORTB &=~0x01; else PORTB |= 0x01;}
#define ROT_ON {if(PlatinenVersion == 10) PORTB |= 0x01; else PORTB &=~0x01;}
#define ROT_FLASH PORTB ^= 0x01
#define GRN_OFF {if(PlatinenVersion < 12) PORTB &=~0x02; else PORTB |= 0x02;}
#define GRN_ON {if(PlatinenVersion < 12) PORTB |= 0x02; else PORTB &=~0x02;}
#define GRN_FLASH PORTB ^= 0x02
 
#define F_CPU SYSCLK
//#ifndef F_CPU
//#error ################## F_CPU nicht definiert oder ungültig #############
//#endif
//+++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
 
#define EEPROM_ADR_VALID 1
#define EEPROM_ADR_ACTIVE_SET 2
#define EEPROM_ADR_LAST_OFFSET 3
 
#define EEPROM_ADR_ACC_NICK 4
#define EEPROM_ADR_ACC_ROLL 6
#define EEPROM_ADR_ACC_Z 8
 
#define EEPROM_ADR_PARAM_BEGIN 100
 
#define CFG_HOEHENREGELUNG 0x01
#define CFG_HOEHEN_SCHALTER 0x02
#define CFG_HEADING_HOLD 0x04
#define CFG_KOMPASS_AKTIV 0x08
#define CFG_KOMPASS_FIX 0x10
#define CFG_GPS_AKTIV 0x20
#define CFG_ACHSENKOPPLUNG_AKTIV 0x40
#define CFG_DREHRATEN_BEGRENZER 0x80
 
#define CFG_LOOP_OBEN 0x01
#define CFG_LOOP_UNTEN 0x02
#define CFG_LOOP_LINKS 0x04
#define CFG_LOOP_RECHTS 0x08
 
//#define SYSCLK
//extern unsigned long SYSCLK;
extern volatile int i_Nick[20],i_Roll[20],DiffNick,DiffRoll;
extern volatile unsigned char SenderOkay;
extern unsigned char CosinusNickWinkel, CosinusRollWinkel;
extern unsigned char PlatinenVersion;
extern unsigned char SendVersionToNavi;
void ReadParameterSet (unsigned char number, unsigned char *buffer, unsigned char length);
void WriteParameterSet(unsigned char number, unsigned char *buffer, unsigned char length);
extern unsigned char GetActiveParamSetNumber(void);
extern unsigned char EEPromArray[];
 
#include <stdlib.h>
#include <string.h>
#include <avr/io.h>
#include <avr/pgmspace.h>
#include <avr/interrupt.h>
#include <avr/eeprom.h>
#include <avr/boot.h>
#include <avr/wdt.h>
 
#include "old_macros.h"
 
#include "_Settings.h"
#include "printf_P.h"
#include "timer0.h"
#include "uart.h"
#include "analog.h"
#include "twimaster.h"
#include "menu.h"
#include "rc.h"
#include "fc.h"
#include "gps.h"
#include "spi.h"
#include "led.h"
 
#ifndef EEMEM
#define EEMEM __attribute__ ((section (".eeprom")))
#endif
 
#define DEBUG_DISPLAY_INTERVALL 123 // in ms
 
 
#define DELAY_US(x) ((unsigned int)( (x) * 1e-6 * F_CPU ))
#endif //_MAIN_H
 
 
 
 
 
 
/branches/V0.70d_flinkflash/include/menu.h
0,0 → 1,6
extern void Menu(void);
extern void LcdClear(void);
extern char DisplayBuff[80];
extern unsigned char DispPtr;
extern unsigned char RemoteTasten;
 
/branches/V0.70d_flinkflash/include/printf_P.h
0,0 → 1,19
#ifndef _PRINTF_P_H_
#define _PRINTF_P_H_
 
#include <avr/pgmspace.h>
 
#define OUT_V24 0
#define OUT_LCD 1
 
 
void _printf_P (char, char const *fmt0, ...);
extern char PrintZiel;
 
 
#define printf_P(format, args...) _printf_P(OUT_V24,format , ## args)
#define printf(format, args...) _printf_P(OUT_V24,PSTR(format) , ## args)
#define LCD_printfxy(x,y,format, args...) { DispPtr = y * 20 + x; _printf_P(OUT_LCD,PSTR(format) , ## args);}
#define LCD_printf(format, args...) { _printf_P(OUT_LCD,PSTR(format) , ## args);}
 
#endif
/branches/V0.70d_flinkflash/include/rc.h
0,0 → 1,29
/*#######################################################################################
Derkodieren eines RC Summen Signals
#######################################################################################*/
 
#ifndef _RC_H
#define _RC_H
 
#if defined (__AVR_ATmega32__)
#define TIMER_TEILER CK64
#define TIMER_RELOAD_VALUE 250
#endif
 
#if defined (__AVR_ATmega644__)
//#define TIMER_TEILER CK64
#define TIMER_RELOAD_VALUE 250
//#define TIMER_TEILER CK256 // bei 20MHz
//#define TIMER_RELOAD_VALUE -78 // bei 20MHz
#endif
 
#define GAS PPM_in[2]
 
 
extern void rc_sum_init (void);
 
extern volatile int PPM_in[11];
extern volatile int PPM_diff[11]; // das diffenzierte Stick-Signal
extern volatile unsigned char NewPpmData;
 
#endif //_RC_H
/branches/V0.70d_flinkflash/include/spi.h
0,0 → 1,123
// ######################## SPI - FlightCtrl ###################
#ifndef _SPI_H
#define _SPI_H
 
#include <util/delay.h>
 
#define USE_SPI_COMMUNICATION
 
#define SPI_PROTOCOL_COMP 1
 
//-----------------------------------------
#define DDR_SPI DDRB
#define DD_SS PB4
#define DD_SCK PB7
#define DD_MOSI PB5
#define DD_MISO PB6
 
// for compatibility reasons gcc3.x <-> gcc4.x
#ifndef SPCR
#define SPCR SPCR0
#endif
#ifndef SPE
#define SPE SPE0
#endif
#ifndef MSTR
#define MSTR MSTR0
#endif
#ifndef SPR1
#define SPR1 SPR01
#endif
#ifndef SPR0
#define SPR0 SPR00
#endif
#ifndef SPIE
#define SPIE SPIE0
#endif
#ifndef SPDR
#define SPDR SPDR0
#endif
#ifndef SPIF
#define SPIF SPIF0
#endif
#ifndef SPSR
#define SPSR SPSR0
#endif
// -------------------------
 
#define SLAVE_SELECT_DDR_PORT DDRC
#define SLAVE_SELECT_PORT PORTC
#define SPI_SLAVE_SELECT PC5
 
 
#define SPI_CMD_USER 10
#define SPI_CMD_STICK 11
#define SPI_CMD_CAL_COMPASS 12
#define SPI_CMD_PARAMETER1 13
struct str_ToNaviCtrl
{
unsigned char Sync1, Sync2;
unsigned char Command;
signed int IntegralNick;
signed int IntegralRoll;
signed int AccNick;
signed int AccRoll;
signed int GyroCompass;
signed int GyroNick;
signed int GyroRoll;
signed int GyroGier;
union
{ char Byte[12];
int Int[6];
long Long[3];
float Float[3];
} Param;
unsigned char Chksum;
};
 
#define SPI_CMD_OSD_DATA 100
#define SPI_CMD_GPS_POS 101
#define SPI_CMD_GPS_TARGET 102
struct str_FromNaviCtrl
{
unsigned char Command;
signed int GPS_Nick;
signed int GPS_Roll;
signed int GPS_Gier;
signed int CompassValue;
signed int Status;
unsigned char BeepTime;
union
{ char Byte[12];
int Int[6];
long Long[3];
float Float[3];
} Param;
unsigned char Chksum;
};
 
 
#ifdef USE_SPI_COMMUNICATION
 
extern struct str_ToNaviCtrl ToNaviCtrl;
extern struct str_FromNaviCtrl FromNaviCtrl;
extern unsigned char SPI_CommandCounter;
 
//#define SPI_CMD_VALUE 0x03
 
extern void SPI_MasterInit(void);
extern void SPI_StartTransmitPacket(void);
extern void UpdateSPI_Buffer(void);
extern void SPI_TransmitByte(void);
#else
 
 
// -------------------------------- Dummy -----------------------------------------
#define SPI_MasterInit() ;
#define SPI_StartTransmitPacket() ;
#define UpdateSPI_Buffer() ;
#define SPI_TransmitByte() ;
#endif
 
 
#endif
/branches/V0.70d_flinkflash/include/timer0.h
0,0 → 1,17
 
#define TIMER_TEILER CK8
#define TIMER_RELOAD_VALUE 250
 
void Timer_Init(void);
void Delay_ms(unsigned int);
void Delay_ms_Mess(unsigned int);
unsigned int SetDelay (unsigned int t);
char CheckDelay (unsigned int t);
 
extern volatile unsigned int CountMilliseconds;
extern volatile unsigned char UpdateMotor;
extern volatile unsigned int beeptime;
extern volatile unsigned int cntKompass;
extern unsigned int ServoValue;
extern unsigned int BeepMuster;
extern volatile unsigned char SendSPI;
/branches/V0.70d_flinkflash/include/twimaster.h
0,0 → 1,33
/*############################################################################
############################################################################*/
 
#ifndef _I2C_MASTER_H
#define _I2C_MASTER_H
 
//############################################################################
 
// I2C Konstanten
#define SCL_CLOCK 200000L
#define I2C_TIMEOUT 30000
#define I2C_START 0x08
#define I2C_REPEATED_START 0x10
#define I2C_TX_SLA_ACK 0x18
#define I2C_TX_DATA_ACK 0x28
#define I2C_RX_SLA_ACK 0x40
#define I2C_RX_DATA_ACK 0x50
 
//############################################################################
 
extern volatile unsigned char twi_state;
extern unsigned char motor;
extern unsigned char motorread;
extern unsigned char motor_rx[8];
 
void i2c_reset(void);
extern void i2c_init (void); // I2C initialisieren
extern char i2c_start (void); // Start I2C
extern void i2c_stop (void); // Stop I2C
extern char i2c_write_byte (char byte); // 1 Byte schreiben
extern void i2c_reset(void);
 
#endif
/branches/V0.70d_flinkflash/include/uart.h
0,0 → 1,117
#ifndef _UART_H
#define _UART_H
 
#define MAX_SENDE_BUFF 150
#define MAX_EMPFANGS_BUFF 150
#define DUB_KEY_UP 4
#define DUB_KEY_DOWN 8
#define DUB_KEY_RIGHT 32
#define DUB_KEY_LEFT 16
#define DUB_KEY_FIRE 64
 
void BearbeiteRxDaten(void);
 
extern unsigned char DebugGetAnforderung;
extern unsigned volatile char SendeBuffer[MAX_SENDE_BUFF];
extern unsigned volatile char RxdBuffer[MAX_EMPFANGS_BUFF];
extern unsigned volatile char UebertragungAbgeschlossen;
extern unsigned volatile char PC_DebugTimeout;
extern unsigned volatile char NeueKoordinateEmpfangen;
extern unsigned char MeineSlaveAdresse;
extern unsigned char PcZugriff;
extern unsigned char RemotePollDisplayLine;
extern int Debug_Timer,Kompass_Timer;
extern void UART_Init (void);
extern int uart_putchar (char c);
extern void boot_program_page (uint32_t page, uint8_t *buf);
extern void DatenUebertragung(void);
extern void DecodeNMEA(void);
extern void BearbeiteRxDaten(void);
extern unsigned char MotorTest[4];
extern unsigned char DubWiseKeys[4];
struct str_DebugOut
{
unsigned char Digital[2];
signed int Analog[32]; // Debugwerte
};
 
extern struct str_DebugOut DebugOut;
 
struct str_WinkelOut
{
signed int Winkel[2];
unsigned char UserParameter[2];
unsigned char CalcState;
unsigned char Orientation;
};
extern struct str_WinkelOut WinkelOut;
 
struct str_ExternControl
{
unsigned char Digital[2];
unsigned char RemoteTasten;
signed char Nick;
signed char Roll;
signed char Gier;
unsigned char Gas;
signed char Hight;
unsigned char free;
unsigned char Frame;
unsigned char Config;
};
extern struct str_ExternControl ExternControl;
 
struct str_VersionInfo
{
unsigned char Hauptversion;
unsigned char Nebenversion;
unsigned char PCKompatibel;
unsigned char Hardware;
unsigned char Rserved[6];
};
extern struct str_VersionInfo VersionInfo;
 
//Die Baud_Rate der Seriellen Schnittstelle ist 9600 Baud
//#define BAUD_RATE 9600 //Baud Rate für die Serielle Schnittstelle
//#define BAUD_RATE 14400 //Baud Rate für die Serielle Schnittstelle
//#define BAUD_RATE 28800 //Baud Rate für die Serielle Schnittstelle
//#define BAUD_RATE 38400 //Baud Rate für die Serielle Schnittstelle
#define BAUD_RATE 57600 //Baud Rate für die Serielle Schnittstelle
 
//Anpassen der seriellen Schnittstellen Register wenn ein ATMega128 benutzt wird
#if defined (__AVR_ATmega128__)
# define USR UCSR0A
# define UCR UCSR0B
# define UDR UDR0
# define UBRR UBRR0L
# define EICR EICRB
#endif
 
#if defined (__AVR_ATmega32__)
# define USR UCSRA
# define UCR UCSRB
# define UBRR UBRRL
# define EICR EICRB
# define INT_VEC_RX SIG_UART_RECV
# define INT_VEC_TX SIG_UART_TRANS
#endif
 
#if defined (__AVR_ATmega644__)
# define USR UCSR0A
# define UCR UCSR0B
# define UDR UDR0
# define UBRR UBRR0L
# define EICR EICR0B
# define TXEN TXEN0
# define RXEN RXEN0
# define RXCIE RXCIE0
# define TXCIE TXCIE0
# define U2X U2X0
# define UCSRB UCSR0B
# define UDRE UDRE0
# define INT_VEC_RX SIG_USART_RECV
# define INT_VEC_TX SIG_USART_TRANS
#endif
 
 
#endif //_UART_H