Rev 2248 | Details | Compare with Previous | Last modification | View Log | RSS feed
Rev | Author | Line No. | Line |
---|---|---|---|
2248 | - | 1 | /***************************************************************************************************************************** |
2 | * File: main.h |
||
3 | * Purpose: header of main.c |
||
4 | *****************************************************************************************************************************/ |
||
5 | #ifndef _MAIN_H |
||
6 | #define _MAIN_H |
||
7 | |||
8 | #define QUADRO |
||
9 | //--------------------------------------------------------------------------------- |
||
10 | // Quadro: |
||
11 | // 1 |
||
12 | // 4 3 |
||
13 | // 2 |
||
14 | //--------------------------------------------------------------------------------- |
||
15 | |||
16 | |||
17 | // Hier wird die Quarz Frequenz angegeben = 20 MHz |
||
18 | #if defined (__AVR_ATmega644__) |
||
19 | #define SYSCLK 20000000L //Quarz Frequenz in Hz |
||
20 | #endif |
||
21 | |||
22 | #if defined (__AVR_ATmega644P__) |
||
23 | #define SYSCLK 20000000L //Quarz Frequenz in Hz |
||
24 | #endif |
||
25 | |||
26 | |||
27 | // Definitionen für Hardware und LEDs |
||
28 | #define ROT_OFF {if((PlatinenVersion == 10)||(PlatinenVersion == 20)) PORTB &=~0x01; else PORTB |= 0x01;} // rote LED aus // PORTB0 aus |
||
29 | #define ROT_ON {if((PlatinenVersion == 10)||(PlatinenVersion == 20)) PORTB |= 0x01; else PORTB &=~0x01;} // rote LED an // PORTB0 ein |
||
30 | #define ROT_FLASH PORTB ^= 0x01 |
||
31 | |||
32 | #define GRN_OFF {if((PlatinenVersion < 12)) PORTB &=~0x02; else PORTB |= 0x02;} // grüne LED aus // PORTB1 aus |
||
33 | #define GRN_ON {if((PlatinenVersion < 12)) PORTB |= 0x02; else PORTB &=~0x02;} // grüne LED an // PORTB1 ein |
||
34 | #define GRN_FLASH PORTB ^= 0x02 |
||
35 | |||
36 | #define CFG_HOEHENREGELUNG 0x01 // Höhenregler aktiv |
||
37 | #define CFG_HOEHEN_SCHALTER 0x02 // Höhenschalter - wo wird dieser Parameter geschaltet ? |
||
38 | #define CFG_HEADING_HOLD 0x04 // Heading Hold aktiv |
||
39 | #define CFG_KOMPASS_AKTIV 0x08 // Kompass aktiv |
||
40 | #define CFG_KOMPASS_FIX 0x10 // Orientation fix |
||
41 | #define CFG_GPS_AKTIV 0x20 // GPS aktiv |
||
42 | #define CFG_ACHSENKOPPLUNG_AKTIV 0x40 // Axis Decoupling |
||
43 | #define CFG_DREHRATEN_BEGRENZER 0x80 // Rotationraten Limiter |
||
44 | |||
45 | #define CFG_LOOP_OBEN 0x01 |
||
46 | #define CFG_LOOP_UNTEN 0x02 |
||
47 | #define CFG_LOOP_LINKS 0x04 |
||
48 | #define CFG_LOOP_RECHTS 0x08 |
||
49 | #define CFG_MOTOR_BLINK 0x10 |
||
50 | #define CFG_MOTOR_OFF_LED1 0x20 |
||
51 | #define CFG_MOTOR_OFF_LED2 0x40 |
||
52 | #define CFG_RES4 0x80 |
||
53 | |||
54 | #define CFG2_HEIGHT_LIMIT 0x01 |
||
55 | #define CFG2_VARIO_BEEP 0x02 |
||
56 | #define CFG_SENSITIVE_RC 0x04 |
||
57 | |||
58 | #define J3High PORTD |= 0x20 // Servosausgang PORTPD5 |
||
59 | #define J3Low PORTD &= ~0x20 |
||
60 | #define J4High PORTD |= 0x10 // Servosausgang PORTPD4 |
||
61 | #define J4Low PORTD &= ~0x10 |
||
62 | #define J5High PORTD |= 0x08 // Servosausgang PORTPD3 |
||
63 | #define J5Low PORTD &= ~0x08 |
||
64 | |||
65 | |||
66 | //------------------------------------------ extern Variables -------------------------------- |
||
67 | extern volatile unsigned char SenderOkay; |
||
68 | extern unsigned char BattLowVoltageWarning; |
||
69 | extern unsigned char CosinusNickWinkel, CosinusRollWinkel; |
||
70 | extern unsigned char PlatinenVersion; |
||
71 | extern unsigned char SendVersionToNavi; |
||
72 | extern unsigned int FlugMinuten,FlugMinutenGesamt; |
||
73 | |||
74 | //----------------------------------------- declaration of functions -------------------------- |
||
75 | |||
76 | |||
77 | void LipoDetection(unsigned char print); |
||
78 | |||
79 | //---------------------------------------------------------------------------------------------- |
||
80 | |||
81 | #include <stdlib.h> |
||
82 | #include <string.h> |
||
83 | #include <avr/io.h> |
||
84 | #include <avr/pgmspace.h> |
||
85 | #include <avr/interrupt.h> |
||
86 | #include <avr/eeprom.h> |
||
87 | #include <avr/boot.h> |
||
88 | #include <avr/wdt.h> |
||
89 | |||
90 | #include "old_macros.h" |
||
91 | |||
92 | #include "_Settings.h" |
||
93 | #include "printf_P.h" |
||
94 | #include "timer0.h" |
||
95 | #include "uart.h" |
||
96 | #include "analog.h" |
||
97 | #include "eeprom.h" |
||
98 | #include "twimaster.h" |
||
99 | #include "menu.h" |
||
100 | #include "rc.h" |
||
101 | #include "fc.h" |
||
102 | #include "led.h" |
||
103 | |||
104 | |||
105 | // #define DEBUG_DISPLAY_INTERVALL 123 // in ms |
||
106 | |||
107 | #define DELAY_US(x) ((unsigned int)( (x) * 1e-6 * F_CPU )) |
||
108 | |||
109 | #endif |
||
110 | // *** EOF: main.h *********************************************************************************************************** |
||
111 | |||
112 | |||
113 |