Subversion Repositories BL-Ctrl

Rev

Rev 37 | Rev 39 | Go to most recent revision | Only display areas with differences | Ignore whitespace | Details | Blame | Last modification | View Log | RSS feed

Rev 37 Rev 38
1
/*############################################################################
1
/*############################################################################
2
 + Regler für Brushless-Motoren
2
 + Regler für Brushless-Motoren
3
 + ATMEGA8 mit 8MHz
3
 + ATMEGA8 mit 8MHz
4
 + (c) 01.2007 Holger Buss
4
 + (c) 01.2007 Holger Buss
5
 + Nur für den privaten Gebrauch
5
 + Nur für den privaten Gebrauch
6
 + Keine Garantie auf Fehlerfreiheit
6
 + Keine Garantie auf Fehlerfreiheit
7
 + Kommerzielle Nutzung nur mit meiner Zustimmung
7
 + Kommerzielle Nutzung nur mit meiner Zustimmung
8
 + Der Code ist für die Hardware BL_Ctrl V1.0 entwickelt worden
8
 + Der Code ist für die Hardware BL_Ctrl V1.0 entwickelt worden
9
 + www.mikrocontroller.com
9
 + www.mikrocontroller.com
10
/############################################################################*/
10
/############################################################################*/
11
 
11
 
12
#include "main.h"
12
#include "main.h"
13
 
13
 
14
unsigned int  PWM = 0;
14
unsigned int  PWM = 0;
15
unsigned int  Strom = 0; //ca. in 0,1A
15
unsigned int  Strom = 0; //ca. in 0,1A
16
unsigned char Strom_max = 0;
16
unsigned char Strom_max = 0;
17
unsigned char Mittelstrom = 0;
17
unsigned char Mittelstrom = 0;
18
unsigned int  Drehzahl = 0;  // in 100UPM  60 = 6000
18
unsigned int  Drehzahl = 0;  // in 100UPM  60 = 6000
19
unsigned int  KommutierDelay = 10;
19
unsigned int  KommutierDelay = 10;
20
unsigned int  I2C_Timeout = 0;
20
unsigned int  I2C_Timeout = 0;
21
unsigned char SIO_Timeout = 0;
21
unsigned char SIO_Timeout = 0;
22
unsigned int  SollDrehzahl = 0;
22
unsigned int  SollDrehzahl = 0;
23
unsigned int  IstDrehzahl = 0;
23
unsigned int  IstDrehzahl = 0;
24
unsigned int  DrehZahlTabelle[256];//vorberechnete Werte zur Drehzahlerfassung
24
unsigned int  DrehZahlTabelle[256];//vorberechnete Werte zur Drehzahlerfassung
25
unsigned char ZeitFuerBerechnungen = 1;
25
unsigned char ZeitFuerBerechnungen = 1;
26
unsigned char MotorAnwerfen = 0;
26
unsigned char MotorAnwerfen = 0;
27
unsigned char MotorGestoppt = 1;
27
unsigned char MotorGestoppt = 1;
28
unsigned char MaxPWM = MAX_PWM;
28
unsigned char MaxPWM = MAX_PWM;
29
unsigned int  CntKommutierungen = 0;
29
unsigned int  CntKommutierungen = 0;
30
unsigned int  SIO_Drehzahl = 0;
30
unsigned int  SIO_Drehzahl = 0;
31
unsigned char ZeitZumAdWandeln = 1;
31
unsigned char ZeitZumAdWandeln = 1;
32
 
32
 
33
 
33
 
34
//############################################################################
34
//############################################################################
35
//
35
//
36
void SetPWM(void)
36
void SetPWM(void)
37
//############################################################################
37
//############################################################################
38
{
38
{
39
    unsigned char tmp_pwm;
39
    unsigned char tmp_pwm;
40
    tmp_pwm = PWM;
40
    tmp_pwm = PWM;
41
    if(tmp_pwm > MaxPWM)    // Strombegrenzung
41
    if(tmp_pwm > MaxPWM)    // Strombegrenzung
42
        {
42
        {
43
        tmp_pwm = MaxPWM;
43
        tmp_pwm = MaxPWM;
44
        PORTC |= ROT;
44
        PORTC |= ROT;
45
        }
45
        }
46
    if(Strom > MAX_STROM)   // Strombegrenzung
46
    if(Strom > MAX_STROM)   // Strombegrenzung
47
        {
47
        {
48
        OCR1A = 0; OCR1B = 0; OCR2  = 0;
48
        OCR1A = 0; OCR1B = 0; OCR2  = 0;
49
        PORTC |= ROT;
49
        PORTC |= ROT;
50
        Strom--;
50
        Strom--;
51
        }
51
        }
52
    else
52
    else
53
        {        
53
        {        
54
        OCR1A =  tmp_pwm; OCR1B =  tmp_pwm; OCR2  = tmp_pwm;        
54
        OCR1A =  tmp_pwm; OCR1B =  tmp_pwm; OCR2  = tmp_pwm;        
55
        }
55
        }
56
}
56
}
57
 
57
 
58
//############################################################################
58
//############################################################################
59
//
59
//
60
void PWM_Init(void)
60
void PWM_Init(void)
61
//############################################################################
61
//############################################################################
62
{
62
{
63
    PWM_OFF;
63
    PWM_OFF;
64
 
64
 
65
#ifdef _16KHZ
65
#ifdef _16KHZ
66
        TCCR1B = (1 << CS10) | (0 << CS11) | (0 << CS12) | (0 << WGM12) |
66
        TCCR1B = (1 << CS10) | (0 << CS11) | (0 << CS12) | (0 << WGM12) |
67
             (0 << WGM13) | (0<< ICES1) | (0 << ICNC1);
67
             (0 << WGM13) | (0<< ICES1) | (0 << ICNC1);
68
#endif
68
#endif
69
 
69
 
70
#ifdef _32KHZ
70
#ifdef _32KHZ
71
        TCCR1B = (1 << CS10) | (0 << CS11) | (0 << CS12) | (1 << WGM12) |
71
        TCCR1B = (1 << CS10) | (0 << CS11) | (0 << CS12) | (1 << WGM12) |
72
             (0 << WGM13) | (0<< ICES1) | (0 << ICNC1);
72
             (0 << WGM13) | (0<< ICES1) | (0 << ICNC1);
73
#endif    
73
#endif    
74
}
74
}
75
 
75
 
76
//############################################################################
76
//############################################################################
77
//
77
//
78
void Wait(unsigned char dauer)
78
void Wait(unsigned char dauer)
79
//############################################################################
79
//############################################################################
80
{
80
{
81
    dauer = (unsigned char)TCNT0 + dauer;
81
    dauer = (unsigned char)TCNT0 + dauer;
82
    while((TCNT0 - dauer) & 0x80);
82
    while((TCNT0 - dauer) & 0x80);
83
}
83
}
84
 
84
 
85
//############################################################################
85
//############################################################################
86
//
86
//
87
void Anwerfen(unsigned char pwm)
87
void Anwerfen(unsigned char pwm)
88
//############################################################################
88
//############################################################################
89
{
89
{
90
    unsigned long timer = 300,i;
90
    unsigned long timer = 300,i;
91
    DISABLE_SENSE_INT;
91
    DISABLE_SENSE_INT;
92
    PWM = 5;
92
    PWM = 5;
93
    SetPWM();
93
    SetPWM();
94
    Manuell();
94
    Manuell();
95
    Delay_ms(200);
95
    Delay_ms(200);
96
    PWM = pwm;
96
    PWM = pwm;
97
    while(1)
97
    while(1)
98
        {
98
        {
99
        for(i=0;i<timer; i++)
99
        for(i=0;i<timer; i++)
100
            {
100
            {
101
            if(!UebertragungAbgeschlossen)  SendUart();
101
            if(!UebertragungAbgeschlossen)  SendUart();
102
            else DatenUebertragung();
102
            else DatenUebertragung();
103
            Wait(100);  // warten
103
            Wait(100);  // warten
104
            }
104
            }
105
        timer-= timer/15+1;
105
        timer-= timer/15+1;
106
        if(timer < 25) { if(TEST_MANUELL) timer = 25; else return; }
106
        if(timer < 25) { if(TEST_MANUELL) timer = 25; else return; }
107
 
107
 
108
        Manuell();
108
        Manuell();
109
        Phase++;
109
        Phase++;
110
        Phase %= 6;
110
        Phase %= 6;
111
        AdConvert();
111
        AdConvert();
112
        PWM = pwm;
112
        PWM = pwm;
113
        SetPWM();
113
        SetPWM();
114
        if(SENSE)
114
        if(SENSE)
115
            {
115
            {
116
            PORTD ^= GRUEN;
116
            PORTD ^= GRUEN;
117
            }
117
            }
118
        }
118
        }
119
}
119
}
120
 
120
 
121
//############################################################################
121
//############################################################################
122
//
122
//
123
unsigned char SollwertErmittlung(void)
123
unsigned char SollwertErmittlung(void)
124
//############################################################################
124
//############################################################################
125
{
125
{
126
    static unsigned int sollwert = 0;
126
    static unsigned int sollwert = 0;
127
    unsigned int ppm;
127
    unsigned int ppm;
128
    if(!I2C_Timeout)   // bei Erreichen von 0 ist der Wert ungültig
128
    if(!I2C_Timeout)   // bei Erreichen von 0 ist der Wert ungültig
129
        {
129
        {
130
        if(SIO_Timeout)  // es gibt gültige SIO-Daten
130
        if(SIO_Timeout)  // es gibt gültige SIO-Daten
131
            {
131
            {
132
            sollwert =  (MAX_PWM * (unsigned int) SIO_Sollwert) / 200;  // skalieren auf 0-200 = 0-255
132
            sollwert =  (MAX_PWM * (unsigned int) SIO_Sollwert) / 200;  // skalieren auf 0-200 = 0-255
133
            }
133
            }
134
        else
134
        else
135
            if(PPM_Timeout)  // es gibt gültige PPM-Daten
135
            if(PPM_Timeout)  // es gibt gültige PPM-Daten
136
                {
136
                {
137
                ppm = PPM_Signal;
137
                ppm = PPM_Signal;
138
                if(ppm > 300) ppm =   0;  // ungültiges Signal
138
                if(ppm > 300) ppm =   0;  // ungültiges Signal
139
                if(ppm > 200) ppm = 200;
139
                if(ppm > 200) ppm = 200;
140
                if(ppm <= MIN_PPM) sollwert = 0;
140
                if(ppm <= MIN_PPM) sollwert = 0;
141
                else
141
                else
142
                    {
142
                    {
143
                    sollwert = (int) MIN_PWM + ((MAX_PWM - MIN_PWM) * (ppm - MIN_PPM)) / (190 - MIN_PPM);
143
                    sollwert = (int) MIN_PWM + ((MAX_PWM - MIN_PWM) * (ppm - MIN_PPM)) / (190 - MIN_PPM);
144
                    }
144
                    }
145
                PORTC &= ~ROT;
145
                PORTC &= ~ROT;
146
                }
146
                }
147
            else   // Kein gültiger Sollwert
147
            else   // Kein gültiger Sollwert
148
                {
148
                {
149
                if(!TEST_SCHUB) { if(sollwert) sollwert--; }  
149
                if(!TEST_SCHUB) { if(sollwert) sollwert--; }  
150
                PORTC |= ROT;
150
                PORTC |= ROT;
151
                }
151
                }
152
        }
152
        }
153
    else // I2C-Daten sind gültig
153
    else // I2C-Daten sind gültig
154
        {
154
        {
155
        sollwert = I2C_RXBuffer;
155
        sollwert = I2C_RXBuffer;
156
        PORTC &= ~ROT;
156
        PORTC &= ~ROT;
157
        }
157
        }
158
    if(sollwert > MAX_PWM) sollwert = MAX_PWM;
158
    if(sollwert > MAX_PWM) sollwert = MAX_PWM;
159
    return(sollwert);
159
    return(sollwert);
160
}
160
}
161
 
161
 
162
void DebugAusgaben(void)
162
void DebugAusgaben(void)
163
{
163
{
164
    DebugOut.Analog[0] = Strom;
164
    DebugOut.Analog[0] = Strom;
165
    DebugOut.Analog[1] = Mittelstrom;
165
    DebugOut.Analog[1] = Mittelstrom;
166
    DebugOut.Analog[2] = SIO_Drehzahl;
166
    DebugOut.Analog[2] = SIO_Drehzahl;
167
    DebugOut.Analog[3] = PPM_Signal;
167
    DebugOut.Analog[3] = PPM_Signal;
168
}
168
}
169
 
169
 
170
 
170
 
171
//############################################################################
171
//############################################################################
172
//Hauptprogramm
172
//Hauptprogramm
173
int main (void)
173
int main (void)
174
//############################################################################
174
//############################################################################
175
{
175
{
176
    char altPhase = 0;
176
    char altPhase = 0;
177
    int test = 0;
177
    int test = 0;
178
    unsigned int MinUpmPulse,Blink,TestschubTimer;
178
    unsigned int MinUpmPulse,Blink,TestschubTimer;
179
    unsigned int Blink2,MittelstromTimer,DrehzahlMessTimer,MotorGestopptTimer;
179
    unsigned int Blink2,MittelstromTimer,DrehzahlMessTimer,MotorGestopptTimer;
180
 
180
 
181
    DDRC  = 0x08;
181
    DDRC  = 0x08;
182
    PORTC = 0x08;
182
    PORTC = 0x08;
183
    DDRD  = 0xBA;
183
    DDRD  = 0xBA;
184
    PORTD = 0x80;
184
    PORTD = 0x80;
185
    DDRB  = 0x0E;
185
    DDRB  = 0x0E;
186
    PORTB = 0x31;
186
    PORTB = 0x31;
187
   
187
   
188
    UART_Init();
188
    UART_Init();
189
    Timer0_Init();
189
    Timer0_Init();
190
    sei ();//Globale Interrupts Einschalten
190
    sei ();//Globale Interrupts Einschalten
191
   
191
   
192
        PORTD &= ~GRUEN;
192
        PORTD &= ~GRUEN;
193
        Delay_ms(500);
193
        Delay_ms(500);
194
    // Am Blinken erkennt man die richtige Motoradresse
194
    // Am Blinken erkennt man die richtige Motoradresse
195
    for(test=0;test<MOTORADRESSE;test++)
195
    for(test=0;test<MOTORADRESSE;test++)
196
    {
196
    {
197
        PORTD |= GRUEN;
197
        PORTD |= GRUEN;
198
                Delay_ms(200);
198
        Delay_ms(200);
199
                PORTD &= ~GRUEN;
199
        PORTD &= ~GRUEN;
200
                Delay_ms(200);
200
        Delay_ms(200);
201
        }
201
    }
202
       
202
       
203
    UART_Init();
203
    UART_Init();
204
    PWM_Init();
204
    PWM_Init();
205
 
205
 
206
    InitIC2_Slave(0x50);                           
206
    InitIC2_Slave(0x50);                           
207
    InitPPM();
207
    InitPPM();
208
 
208
 
209
    Blink             = SetDelay(101);    
209
    Blink             = SetDelay(101);    
210
    Blink2            = SetDelay(102);
210
    Blink2            = SetDelay(102);
211
    MinUpmPulse       = SetDelay(103);
211
    MinUpmPulse       = SetDelay(103);
212
    MittelstromTimer  = SetDelay(254);
212
    MittelstromTimer  = SetDelay(254);
213
    DrehzahlMessTimer = SetDelay(1005);
213
    DrehzahlMessTimer = SetDelay(1005);
214
    TestschubTimer    = SetDelay(1006);
214
    TestschubTimer    = SetDelay(1006);
215
    while(!CheckDelay(MinUpmPulse));
215
    while(!CheckDelay(MinUpmPulse));
216
    PORTD |= GRUEN;
216
    PORTD |= GRUEN;
217
    PWM = 0;
217
    PWM = 0;
218
 
218
 
219
    SetPWM();
219
    SetPWM();
220
 
220
 
221
    SFIOR = 0x08;  // Analog Comperator ein
221
    SFIOR = 0x08;  // Analog Comperator ein
222
    ADMUX = 1;
222
    ADMUX = 1;
223
 
223
 
224
    MinUpmPulse = SetDelay(10);
224
    MinUpmPulse = SetDelay(10);
225
    DebugOut.Analog[1] = 1;
225
    DebugOut.Analog[1] = 1;
226
    PPM_Signal = 0;
226
    PPM_Signal = 0;
227
 
227
 
228
    // zum Test der Hardware; Motor dreht mit konstanter Drehzahl ohne Regelung
228
    // zum Test der Hardware; Motor dreht mit konstanter Drehzahl ohne Regelung
229
    if(TEST_MANUELL)    Anwerfen(TEST_MANUELL);  // kommt von dort nicht wieder
229
    if(TEST_MANUELL)    Anwerfen(TEST_MANUELL);  // kommt von dort nicht wieder
230
 
230
 
231
    while (1)
231
    while (1)
232
        {
232
        {
233
        if(!TEST_SCHUB)   PWM = SollwertErmittlung();
233
        if(!TEST_SCHUB)   PWM = SollwertErmittlung();
234
        //I2C_TXBuffer = PWM; // Antwort über I2C-Bus
234
        //I2C_TXBuffer = PWM; // Antwort über I2C-Bus
235
        if(MANUELL_PWM)   PWM = MANUELL_PWM;
235
        if(MANUELL_PWM)   PWM = MANUELL_PWM;
236
 
236
 
237
        // ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
237
        // ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
238
        if(Phase != altPhase)   // es gab eine Kommutierung im Interrupt
238
        if(Phase != altPhase)   // es gab eine Kommutierung im Interrupt
239
            {
239
            {
240
            MotorGestoppt = 0;
240
            MotorGestoppt = 0;
241
            ZeitFuerBerechnungen = 0;    // direkt nach einer Kommutierung ist Zeit 
241
            ZeitFuerBerechnungen = 0;    // direkt nach einer Kommutierung ist Zeit 
242
            MinUpmPulse = SetDelay(50);  // Timeout, falls ein Motor stehen bleibt
242
            MinUpmPulse = SetDelay(50);  // Timeout, falls ein Motor stehen bleibt
243
            altPhase = Phase;
243
            altPhase = Phase;
244
            }
244
            }
245
        // ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
245
        // ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
246
        if(!PWM)    // Sollwert == 0
246
        if(!PWM)    // Sollwert == 0
247
            {
247
            {
248
            MotorAnwerfen = 0;      // kein Startversuch
248
            MotorAnwerfen = 0;      // kein Startversuch
249
            ZeitFuerBerechnungen = 0;
249
            ZeitFuerBerechnungen = 0;
250
            // nach 1,5 Sekunden den Motor als gestoppt betrachten 
250
            // nach 1,5 Sekunden den Motor als gestoppt betrachten 
251
            if(CheckDelay(MotorGestopptTimer))
251
            if(CheckDelay(MotorGestopptTimer))
252
                {
252
                {
253
                DISABLE_SENSE_INT;
253
                DISABLE_SENSE_INT;
254
                MotorGestoppt = 1;  
254
                MotorGestoppt = 1;  
255
                STEUER_OFF;
255
                STEUER_OFF;
256
                }
256
                }
257
            }
257
            }
258
        else
258
        else
259
            {
259
            {
260
            if(MotorGestoppt) MotorAnwerfen = 1;        // Startversuch
260
            if(MotorGestoppt) MotorAnwerfen = 1;        // Startversuch
261
            MotorGestopptTimer = SetDelay(1500);
261
            MotorGestopptTimer = SetDelay(1500);
262
            }
262
            }
263
 
263
 
264
        if(MotorGestoppt && !TEST_SCHUB) PWM = 0;
264
        if(MotorGestoppt && !TEST_SCHUB) PWM = 0;
265
        SetPWM();
265
        SetPWM();
266
        // +++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
266
        // +++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
267
        if(!ZeitFuerBerechnungen++)
267
        if(!ZeitFuerBerechnungen++)
268
            {
268
            {
269
            if(MotorGestoppt) PORTD |= GRUEN; //else PORTD &= ~GRUEN;
269
            if(MotorGestoppt) PORTD |= GRUEN; //else PORTD &= ~GRUEN;
270
            if(SIO_DEBUG)
270
            if(SIO_DEBUG)
271
                {
271
                {
272
                DebugAusgaben();  // welche Werte sollen angezeigt werden?
272
                DebugAusgaben();  // welche Werte sollen angezeigt werden?
273
                if(!UebertragungAbgeschlossen)  SendUart();
273
                if(!UebertragungAbgeschlossen)  SendUart();
274
                else DatenUebertragung();
274
                else DatenUebertragung();
275
                }
275
                }
276
            // Berechnen des Mittleren Stroms zur (langsamen) Strombegrenzung
276
            // Berechnen des Mittleren Stroms zur (langsamen) Strombegrenzung
277
            if(CheckDelay(MittelstromTimer))  
277
            if(CheckDelay(MittelstromTimer))  
278
                {
278
                {
279
                MittelstromTimer = SetDelay(50); // alle 50ms
279
                MittelstromTimer = SetDelay(50); // alle 50ms
280
                if(Mittelstrom < Strom) Mittelstrom++;// Mittelwert des Stroms bilden
280
                if(Mittelstrom < Strom) Mittelstrom++;// Mittelwert des Stroms bilden
281
                else if(Mittelstrom > Strom) Mittelstrom--;
281
                else if(Mittelstrom > Strom) Mittelstrom--;
282
       
282
       
283
                if(Mittelstrom > LIMIT_STROM)// Strom am Limit?
283
                if(Mittelstrom > LIMIT_STROM)// Strom am Limit?
284
                    {
284
                    {
285
                    MaxPWM--;// dann die Maximale PWM herunterfahren
285
                    MaxPWM--;// dann die Maximale PWM herunterfahren
286
                    PORTC |= ROT;
286
                    PORTC |= ROT;
287
                    }
287
                    }
288
                else
288
                else
289
                    {
289
                    {
290
                    if(MaxPWM < MAX_PWM) MaxPWM++;
290
                    if(MaxPWM < MAX_PWM) MaxPWM++;
291
                    }
291
                    }
292
                }
292
                }
293
 
293
 
294
            if(CheckDelay(DrehzahlMessTimer))   // Ist-Drehzahl bestimmen
294
            if(CheckDelay(DrehzahlMessTimer))   // Ist-Drehzahl bestimmen
295
                {
295
                {
296
                DrehzahlMessTimer = SetDelay(10);
296
                DrehzahlMessTimer = SetDelay(10);
297
                SIO_Drehzahl = (6 * CntKommutierungen) / (POLANZAHL / 2);
297
                SIO_Drehzahl = (6 * CntKommutierungen) / (POLANZAHL / 2);
298
                CntKommutierungen = 0;
298
                CntKommutierungen = 0;
299
                if(PPM_Timeout == 0) // keine PPM-Signale
299
                if(PPM_Timeout == 0) // keine PPM-Signale
300
                ZeitZumAdWandeln = 1;
300
                ZeitZumAdWandeln = 1;
301
                }
301
                }
302
 
302
 
303
 
303
 
304
            if(CheckDelay(TestschubTimer))  
304
            if(CheckDelay(TestschubTimer))  
305
                {
305
                {
306
                TestschubTimer = SetDelay(1500);
306
                TestschubTimer = SetDelay(1500);
307
                if(TEST_SCHUB)
307
                if(TEST_SCHUB)
308
                    {
308
                    {
309
                    switch(test)
309
                    switch(test)
310
                        {
310
                        {
311
                        case 0: PWM = 50; test++; break;
311
                        case 0: PWM = 50; test++; break;
312
                        case 1: PWM = 60; test++; break;
312
                        case 1: PWM = 60; test++; break;
313
                        case 2: PWM = 128;  test++; break;
313
                        case 2: PWM = 128;  test++; break;
314
                        case 3: PWM = 200; test++; break;
314
                        case 3: PWM = 200; test++; break;
315
                        case 4: PWM = 255; test = 0; break;
315
                        case 4: PWM = 255; test = 0; break;
316
                        default: test = 0;
316
                        default: test = 0;
317
                        }
317
                        }
318
                    }
318
                    }
319
                }
319
                }
320
            // Motor Stehen geblieben
320
            // Motor Stehen geblieben
321
            if((CheckDelay(MinUpmPulse) && SIO_Drehzahl == 0) || MotorAnwerfen)
321
            if((CheckDelay(MinUpmPulse) && SIO_Drehzahl == 0) || MotorAnwerfen)
322
                {
322
                {
323
                MotorGestoppt = 1;    
323
                MotorGestoppt = 1;    
324
                DISABLE_SENSE_INT;
324
                DISABLE_SENSE_INT;
325
                MinUpmPulse = SetDelay(100);        
325
                MinUpmPulse = SetDelay(100);        
326
                if(MotorAnwerfen)
326
                if(MotorAnwerfen)
327
                    {
327
                    {
328
                    PORTC &= ~ROT;
328
                    PORTC &= ~ROT;
329
                    MotorAnwerfen = 0;
329
                    MotorAnwerfen = 0;
330
                    Anwerfen(10);
330
                    Anwerfen(10);
331
                    PORTD |= GRUEN;
331
                    PORTD |= GRUEN;
332
                    MotorGestoppt = 0;    
332
                    MotorGestoppt = 0;    
333
                    Phase--;
333
                    Phase--;
334
                    PWM = 1;
334
                    PWM = 1;
335
                    SetPWM();
335
                    SetPWM();
336
                    SENSE_TOGGLE_INT;
336
                    SENSE_TOGGLE_INT;
337
                    ENABLE_SENSE_INT;
337
                    ENABLE_SENSE_INT;
338
                    MinUpmPulse = SetDelay(100);
338
                    MinUpmPulse = SetDelay(100);
339
                    while(!CheckDelay(MinUpmPulse)); // kurz Synchronisieren
339
                    while(!CheckDelay(MinUpmPulse)); // kurz Synchronisieren
340
                    PWM = 10;
340
                    PWM = 10;
341
                    SetPWM();
341
                    SetPWM();
342
                    DrehzahlMessTimer = SetDelay(200);
342
                    DrehzahlMessTimer = SetDelay(200);
343
                    while(!CheckDelay(MinUpmPulse)); // kurz Durchstarten
343
                    while(!CheckDelay(MinUpmPulse)); // kurz Durchstarten
344
                    MinUpmPulse = SetDelay(1000);
344
                    MinUpmPulse = SetDelay(1000);
345
                    altPhase = 7;
345
                    altPhase = 7;
346
                    }
346
                    }
347
                }
347
                }
348
            } // ZeitFuerBerechnungen
348
            } // ZeitFuerBerechnungen
349
        } // while(1) - Hauptschleife
349
        } // while(1) - Hauptschleife
350
}
350
}
351
 
351
 
352
 
352