Rev 463 | Only display areas with differences | Ignore whitespace | Details | Blame | Last modification | View Log | RSS feed
Rev 463 | Rev 477 | ||
---|---|---|---|
1 | #ifndef _MAIN_H |
1 | #ifndef _MAIN_H |
2 | #define _MAIN_H |
2 | #define _MAIN_H |
3 | 3 | ||
4 | //Hier die Quarz Frequenz einstellen |
4 | //Hier die Quarz Frequenz einstellen |
5 | #if defined (__AVR_ATmega32__) |
5 | #if defined (__AVR_ATmega32__) |
6 | #define SYSCLK 20000000L //Quarz Frequenz in Hz |
6 | #define SYSCLK 20000000L //Quarz Frequenz in Hz |
7 | #endif |
7 | #endif |
8 | 8 | ||
9 | #if defined (__AVR_ATmega644__) |
9 | #if defined (__AVR_ATmega644__) |
10 | #define SYSCLK 20000000L //Quarz Frequenz in Hz |
10 | #define SYSCLK 20000000L //Quarz Frequenz in Hz |
11 | //#define SYSCLK 16000000L //Quarz Frequenz in Hz |
11 | //#define SYSCLK 16000000L //Quarz Frequenz in Hz |
12 | #endif |
12 | #endif |
13 | 13 | ||
14 | 14 | ||
15 | // neue Hardware |
15 | // neue Hardware |
16 | #define ROT_OFF PORTB &=~(1<<PB0) |
16 | #define ROT_OFF PORTB &=~(1<<PB0) |
17 | #define ROT_ON PORTB |= (1<<PB0) |
17 | #define ROT_ON PORTB |= (1<<PB0) |
18 | #define ROT_FLASH PORTB ^= (1<<PB0) |
18 | #define ROT_FLASH PORTB ^= (1<<PB0) |
19 | #define GRN_OFF PORTB &=~(1<<PB1) |
19 | #define GRN_OFF PORTB &=~(1<<PB1) |
20 | #define GRN_ON PORTB |= (1<<PB1) |
20 | #define GRN_ON PORTB |= (1<<PB1) |
21 | #define GRN_FLASH PORTB ^= (1<<PB1) |
21 | #define GRN_FLASH PORTB ^= (1<<PB1) |
22 | 22 | ||
23 | //#ifndef F_CPU |
23 | //#ifndef F_CPU |
24 | //#error ################## F_CPU nicht definiert oder ungültig ############# |
24 | //#error ################## F_CPU nicht definiert oder ungültig ############# |
25 | //#endif |
25 | //#endif |
26 | 26 | ||
27 | //+++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++ |
27 | //+++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++ |
28 | 28 | ||
29 | //#define ANZ_MITTELWERT 4 |
29 | //#define ANZ_MITTELWERT 4 |
30 | 30 | ||
31 | #define EEPROM_ADR_VALID 1 |
31 | #define EEPROM_ADR_VALID 1 |
32 | #define EEPROM_ADR_ACTIVE_SET 2 |
32 | #define EEPROM_ADR_ACTIVE_SET 2 |
33 | #define EEPROM_ADR_LAST_OFFSET 3 |
33 | #define EEPROM_ADR_LAST_OFFSET 3 |
34 | 34 | ||
35 | #define CFG_HOEHENREGELUNG 0x01 |
35 | #define CFG_HOEHENREGELUNG 0x01 |
36 | #define CFG_HOEHEN_SCHALTER 0x02 |
36 | #define CFG_HOEHEN_SCHALTER 0x02 |
37 | #define CFG_HEADING_HOLD 0x04 |
37 | #define CFG_HEADING_HOLD 0x04 |
38 | #define CFG_KOMPASS_AKTIV 0x08 |
38 | #define CFG_KOMPASS_AKTIV 0x08 |
39 | #define CFG_KOMPASS_FIX 0x10 |
39 | #define CFG_KOMPASS_FIX 0x10 |
40 | #define CFG_GPS_AKTIV 0x20 |
40 | #define CFG_GPS_AKTIV 0x20 |
41 | 41 | ||
42 | - | ||
43 | //#define SYSCLK |
- | |
44 | //extern unsigned long SYSCLK; |
- | |
45 | extern volatile int i_Nick[20],i_Roll[20],DiffNick,DiffRoll; |
- | |
46 | extern volatile unsigned char SenderOkay; |
- | |
47 | extern unsigned char CosinusNickWinkel, CosinusRollWinkel; |
- | |
48 | 42 | ||
49 | extern void ReadParameterSet (unsigned char number, unsigned char *buffer, unsigned char length); |
43 | extern void ReadParameterSet (unsigned char number, unsigned char *buffer, unsigned char length); |
50 | extern void WriteParameterSet(unsigned char number, unsigned char *buffer, unsigned char length); |
44 | extern void WriteParameterSet(unsigned char number, unsigned char *buffer, unsigned char length); |
51 | extern unsigned char GetActiveParamSetNumber(void); |
45 | extern unsigned char GetActiveParamSetNumber(void); |
52 | extern unsigned char EEPromArray[]; |
46 | extern unsigned char EEPromArray[]; |
53 | 47 | ||
54 | #include <stdlib.h> |
48 | #include <stdlib.h> |
55 | #include <string.h> |
49 | #include <string.h> |
56 | #include <avr/io.h> |
50 | #include <avr/io.h> |
57 | #include <avr/pgmspace.h> |
51 | #include <avr/pgmspace.h> |
58 | #include <avr/interrupt.h> |
52 | #include <avr/interrupt.h> |
59 | #include <avr/eeprom.h> |
53 | #include <avr/eeprom.h> |
60 | #include <avr/boot.h> |
54 | #include <avr/boot.h> |
61 | #include <avr/wdt.h> |
55 | #include <avr/wdt.h> |
62 | 56 | ||
63 | #include "old_macros.h" |
57 | #include "old_macros.h" |
64 | 58 | ||
65 | #include "_settings.h" |
59 | #include "_settings.h" |
66 | #include "printf_P.h" |
60 | #include "printf_P.h" |
67 | #include "compass.h" |
61 | #include "compass.h" |
68 | #include "timer0.h" |
62 | #include "timer0.h" |
69 | #include "uart.h" |
63 | #include "uart.h" |
70 | #include "analog.h" |
64 | #include "analog.h" |
71 | #include "twimaster.h" |
65 | #include "twimaster.h" |
72 | #include "menu.h" |
66 | #include "menu.h" |
73 | #include "rc.h" |
67 | #include "rc.h" |
74 | #include "fc.h" |
68 | #include "fc.h" |
75 | #include "gps.h" |
69 | #include "gps.h" |
76 | #include "math.h" |
70 | #include "math.h" |
77 | 71 | ||
78 | #ifndef EEMEM |
72 | #ifndef EEMEM |
79 | #define EEMEM __attribute__ ((section (".eeprom"))) |
73 | #define EEMEM __attribute__ ((section (".eeprom"))) |
80 | #endif |
74 | #endif |
81 | 75 | ||
82 | #define DEBUG_DISPLAY_INTERVALL 123 // in ms |
76 | #define DEBUG_DISPLAY_INTERVALL 123 // in ms |
83 | 77 | ||
84 | 78 | ||
85 | #define DELAY_US(x) ((unsigned int)( (x) * 1e-6 * F_CPU )) |
79 | #define DELAY_US(x) ((unsigned int)( (x) * 1e-6 * F_CPU )) |
86 | 80 | ||
87 | #endif //_MAIN_H |
81 | #endif //_MAIN_H |
88 | 82 | ||
89 | 83 | ||
90 | 84 | ||
91 | 85 | ||
92 | 86 | ||
93 | 87 | ||
94 | 88 |