Rev 2248 |
Blame |
Compare with Previous |
Last modification |
View Log
| RSS feed
/*****************************************************************************************************************************
* File: main.h
* Purpose: header of main.c
*****************************************************************************************************************************/
#ifndef _MAIN_H
#define _MAIN_H
#define QUADRO
//---------------------------------------------------------------------------------
// Quadro:
// 1
// 4 3
// 2
//---------------------------------------------------------------------------------
// Hier wird die Quarz Frequenz angegeben = 20 MHz
#if defined (__AVR_ATmega644__)
#define SYSCLK 20000000L //Quarz Frequenz in Hz
#endif
#if defined (__AVR_ATmega644P__)
#define SYSCLK 20000000L //Quarz Frequenz in Hz
#endif
// Definitionen für Hardware und LEDs
#define ROT_OFF {if((PlatinenVersion == 10)||(PlatinenVersion == 20)) PORTB &=~0x01; else PORTB |= 0x01;} // rote LED aus // PORTB0 aus
#define ROT_ON {if((PlatinenVersion == 10)||(PlatinenVersion == 20)) PORTB |= 0x01; else PORTB &=~0x01;} // rote LED an // PORTB0 ein
#define ROT_FLASH PORTB ^= 0x01
#define GRN_OFF {if((PlatinenVersion < 12)) PORTB &=~0x02; else PORTB |= 0x02;} // grüne LED aus // PORTB1 aus
#define GRN_ON {if((PlatinenVersion < 12)) PORTB |= 0x02; else PORTB &=~0x02;} // grüne LED an // PORTB1 ein
#define GRN_FLASH PORTB ^= 0x02
#define CFG_HOEHENREGELUNG 0x01 // Höhenregler aktiv
#define CFG_HOEHEN_SCHALTER 0x02 // Höhenschalter - wo wird dieser Parameter geschaltet ?
#define CFG_HEADING_HOLD 0x04 // Heading Hold aktiv
#define CFG_KOMPASS_AKTIV 0x08 // Kompass aktiv
#define CFG_KOMPASS_FIX 0x10 // Orientation fix
#define CFG_GPS_AKTIV 0x20 // GPS aktiv
#define CFG_ACHSENKOPPLUNG_AKTIV 0x40 // Axis Decoupling
#define CFG_DREHRATEN_BEGRENZER 0x80 // Rotationraten Limiter
#define CFG_LOOP_OBEN 0x01
#define CFG_LOOP_UNTEN 0x02
#define CFG_LOOP_LINKS 0x04
#define CFG_LOOP_RECHTS 0x08
#define CFG_MOTOR_BLINK 0x10
#define CFG_MOTOR_OFF_LED1 0x20
#define CFG_MOTOR_OFF_LED2 0x40
#define CFG_RES4 0x80
#define CFG2_HEIGHT_LIMIT 0x01
#define CFG2_VARIO_BEEP 0x02
#define CFG_SENSITIVE_RC 0x04
#define J3High PORTD |= 0x20 // Servosausgang PORTPD5
#define J3Low PORTD &= ~0x20
#define J4High PORTD |= 0x10 // Servosausgang PORTPD4
#define J4Low PORTD &= ~0x10
#define J5High PORTD |= 0x08 // Servosausgang PORTPD3
#define J5Low PORTD &= ~0x08
//------------------------------------------ extern Variables --------------------------------
extern volatile unsigned char SenderOkay;
extern unsigned char BattLowVoltageWarning;
extern unsigned char CosinusNickWinkel, CosinusRollWinkel;
extern unsigned char PlatinenVersion;
extern unsigned char SendVersionToNavi;
extern unsigned int FlugMinuten,FlugMinutenGesamt;
//----------------------------------------- declaration of functions --------------------------
void LipoDetection(unsigned char print);
//----------------------------------------------------------------------------------------------
#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 "eeprom.h"
#include "twimaster.h"
#include "menu.h"
#include "rc.h"
#include "fc.h"
#include "led.h"
// #define DEBUG_DISPLAY_INTERVALL 123 // in ms
#define DELAY_US(x) ((unsigned int)( (x) * 1e-6 * F_CPU ))
#endif
// *** EOF: main.h ***********************************************************************************************************