Subversion Repositories FlightCtrl

Rev

Rev 130 | Only display areas with differences | Ignore whitespace | Details | Blame | Last modification | View Log | RSS feed

Rev 130 Rev 243
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
 
-
 
14
 
13
 
15
// neue Hardware
14
// neue Hardware
16
#define ROT_OFF   PORTB &=~0x01 
15
#define ROT_OFF   {if(PlatinenVersion == 10) PORTB &=~0x01; else  PORTB |= 0x01;}
17
#define ROT_ON    PORTB |= 0x01 
16
#define ROT_ON    {if(PlatinenVersion == 10) PORTB |= 0x01; else  PORTB &=~0x01;}
18
#define ROT_FLASH PORTB ^= 0x01
17
#define ROT_FLASH PORTB ^= 0x01
19
#define GRN_OFF   PORTB &=~0x02 
18
#define GRN_OFF   PORTB &=~0x02 
20
#define GRN_ON    PORTB |= 0x02 
19
#define GRN_ON    PORTB |= 0x02 
21
#define GRN_FLASH PORTD ^= 0x02
20
#define GRN_FLASH PORTB ^= 0x02
22
 
21
 
23
//#ifndef F_CPU
22
//#ifndef F_CPU
24
//#error ################## F_CPU nicht definiert oder ungültig #############
23
//#error ################## F_CPU nicht definiert oder ungültig #############
25
//#endif
24
//#endif
26
 
25
 
27
//+++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
26
//+++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
28
 
27
 
29
//#define ANZ_MITTELWERT   4
28
//#define ANZ_MITTELWERT   4
30
 
29
 
31
#define EEPROM_ADR_VALID            1
30
#define EEPROM_ADR_VALID            1
32
#define EEPROM_ADR_ACTIVE_SET       2
31
#define EEPROM_ADR_ACTIVE_SET       2
-
 
32
#define EEPROM_ADR_LAST_OFFSET      3
33
 
33
 
34
#define EEPROM_ADR_PARAM_BEGIN      100
34
#define EEPROM_ADR_PARAM_BEGIN      100
35
 
35
 
36
#define CFG_HOEHENREGELUNG  0x01
36
#define CFG_HOEHENREGELUNG  0x01
37
#define CFG_HOEHEN_SCHALTER 0x02
37
#define CFG_HOEHEN_SCHALTER 0x02
38
#define CFG_HEADING_HOLD    0x04
38
#define CFG_HEADING_HOLD    0x04
39
#define CFG_KOMPASS_AKTIV   0x08
39
#define CFG_KOMPASS_AKTIV   0x08
40
#define CFG_KOMPASS_FIX     0x10
40
#define CFG_KOMPASS_FIX     0x10
41
#define CFG_GPS_AKTIV       0x20
41
#define CFG_GPS_AKTIV       0x20
-
 
42
 
-
 
43
#define CFG_LOOP_OBEN       0x01
-
 
44
#define CFG_LOOP_UNTEN      0x02
-
 
45
#define CFG_LOOP_LINKS      0x04
-
 
46
#define CFG_LOOP_RECHTS     0x08
-
 
47
 
-
 
48
long durchschnitt_x;
-
 
49
long durchschnitt_y;
-
 
50
long durchschnitt_z;
-
 
51
 
-
 
52
int gps_h_d1;
-
 
53
int gps_h_d2;
-
 
54
 
-
 
55
long target_x, target_y, target_z;
-
 
56
 
-
 
57
volatile int  gps_error;
-
 
58
volatile int  gps_getpos;
-
 
59
 
-
 
60
volatile int gps_p;                     //P-Anteil
-
 
61
volatile int gps_d;                     //D-Anteil 
-
 
62
volatile int gps_acc;         //Acc-Anteil
-
 
63
 
-
 
64
int sticks_centered;
-
 
65
int stick_time;
-
 
66
 
-
 
67
long gps_home_x;
-
 
68
long gps_home_y;
-
 
69
long home_height;
-
 
70
 
-
 
71
int homing_state;
-
 
72
 
-
 
73
int way, way1, wayn, way2;
-
 
74
 
-
 
75
volatile int gpsmax;
-
 
76
 
-
 
77
volatile int komp_dreh;         // verdrehten Kompasseinbau kompensieren (+/-Grad)
-
 
78
volatile int gps_new;
-
 
79
volatile int skal;                      //Skalierungsfaktor der Regelung (alter Wert: 10) (20)
42
 
80
volatile int  gps_gethome;
43
 
81
 
44
//#define  SYSCLK  
82
//#define  SYSCLK  
45
//extern unsigned long SYSCLK;
83
//extern unsigned long SYSCLK;
46
extern volatile int i_Nick[20],i_Roll[20],DiffNick,DiffRoll;
84
extern volatile int i_Nick[20],i_Roll[20],DiffNick,DiffRoll;
47
extern volatile unsigned char SenderOkay;
85
extern volatile unsigned char SenderOkay;
48
extern unsigned char CosinusNickWinkel, CosinusRollWinkel;
86
extern unsigned char CosinusNickWinkel, CosinusRollWinkel;
-
 
87
extern unsigned char PlatinenVersion;
49
 
88
 
50
extern void ReadParameterSet (unsigned char number, unsigned char *buffer, unsigned char length);
89
extern void ReadParameterSet (unsigned char number, unsigned char *buffer, unsigned char length);
51
extern void WriteParameterSet(unsigned char number, unsigned char *buffer, unsigned char length);
90
extern void WriteParameterSet(unsigned char number, unsigned char *buffer, unsigned char length);
52
extern unsigned char GetActiveParamSetNumber(void);
91
extern unsigned char GetActiveParamSetNumber(void);
53
extern unsigned char EEPromArray[];
92
extern unsigned char EEPromArray[];
54
 
-
 
55
long durchschnitt_northing;
-
 
56
long durchschnitt_easting;
-
 
57
 
-
 
58
volatile int gps_p;                     //P-Anteil (10)
-
 
59
volatile int gps_d;                     //D-Anteil (4)
-
 
60
volatile int skal;                      //Skalierungsfaktor der Regelung (alter Wert: 10) (20)
-
 
61
 
-
 
62
volatile int  gps_gethome;
-
 
63
 
93
 
64
#include <stdlib.h>
94
#include <stdlib.h>
65
#include <string.h>
95
#include <string.h>
66
#include <avr/io.h>
96
#include <avr/io.h>
67
#include <avr/pgmspace.h>
97
#include <avr/pgmspace.h>
68
#include <avr/interrupt.h>
98
#include <avr/interrupt.h>
69
#include <avr/eeprom.h>
99
#include <avr/eeprom.h>
70
#include <avr/boot.h>
100
#include <avr/boot.h>
71
#include <avr/wdt.h>
101
#include <avr/wdt.h>
72
 
102
 
73
#include "old_macros.h"
103
#include "old_macros.h"
74
 
104
 
75
#include "_Settings.h"
105
#include "_settings.h"
76
#include "printf_P.h"
106
#include "printf_P.h"
77
#include "timer0.h"
107
#include "timer0.h"
78
#include "uart.h"
108
#include "uart.h"
79
#include "analog.h"
109
#include "analog.h"
80
#include "twimaster.h"
110
#include "twimaster.h"
81
#include "menu.h"
111
#include "menu.h"
82
#include "rc.h"
112
#include "rc.h"
83
#include "fc.h"
113
#include "fc.h"
84
#include "gps.h"
114
#include "gps.h"
85
 
115
 
86
#ifndef EEMEM
116
#ifndef EEMEM
87
#define EEMEM __attribute__ ((section (".eeprom")))
117
#define EEMEM __attribute__ ((section (".eeprom")))
88
#endif
118
#endif
89
 
119
 
90
#define DEBUG_DISPLAY_INTERVALL  123 // in ms
120
#define DEBUG_DISPLAY_INTERVALL  123 // in ms
91
 
121
 
92
 
122
 
93
#define DELAY_US(x)     ((unsigned int)( (x) * 1e-6 * F_CPU ))
123
#define DELAY_US(x)     ((unsigned int)( (x) * 1e-6 * F_CPU ))
94
       
124
       
95
#endif //_MAIN_H
125
#endif //_MAIN_H
96
 
126
 
97
 
127
 
98
 
128
 
99
 
129
 
100
 
130
 
101
 
131
 
102
 
132