Subversion Repositories BL-Ctrl

Rev

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

Rev 52 Rev 92
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 / NON-COMMERCIAL USE ONLY
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 int SIO_Timeout = 0;
21
unsigned int 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
unsigned char MotorAdresse = 1;
32
unsigned char MotorAdresse = 1;
33
unsigned char PPM_Betrieb = 1;
33
unsigned char PPM_Betrieb = 1;
34
 
34
 
35
//############################################################################
35
//############################################################################
36
//
36
//
37
void SetPWM(void)
37
void SetPWM(void)
38
//############################################################################
38
//############################################################################
39
{
39
{
40
    unsigned char tmp_pwm;
40
    unsigned char tmp_pwm;
41
    tmp_pwm = PWM;
41
    tmp_pwm = PWM;
42
    if(tmp_pwm > MaxPWM)    // Strombegrenzung
42
    if(tmp_pwm > MaxPWM)    // Strombegrenzung
43
        {
43
        {
44
        tmp_pwm = MaxPWM;
44
        tmp_pwm = MaxPWM;
45
        PORTC |= ROT;
45
        PORTC |= ROT;
46
        }
46
        }
47
    if(Strom > MAX_STROM)   // Strombegrenzung
47
    if(Strom > MAX_STROM)   // Strombegrenzung
48
        {
48
        {
49
        OCR1A = 0; OCR1B = 0; OCR2  = 0;
49
        OCR1A = 0; OCR1B = 0; OCR2  = 0;
50
        PORTC |= ROT;
50
        PORTC |= ROT;
51
        Strom--;
51
        Strom--;
52
        }
52
        }
53
    else
53
    else
54
        {
54
        {
55
        #ifdef  _32KHZ 
55
        #ifdef  _32KHZ 
56
        OCR1A =  tmp_pwm; OCR1B =  tmp_pwm; OCR2  = tmp_pwm;
56
        OCR1A =  tmp_pwm; OCR1B =  tmp_pwm; OCR2  = tmp_pwm;
57
        #endif 
57
        #endif 
58
 
58
 
59
        #ifdef  _16KHZ 
59
        #ifdef  _16KHZ 
60
        //OCR1A = 2 * (int)tmp_pwm; OCR1B = 2 * (int)tmp_pwm; OCR2  = tmp_pwm;
60
        //OCR1A = 2 * (int)tmp_pwm; OCR1B = 2 * (int)tmp_pwm; OCR2  = tmp_pwm;
61
        OCR1A =  tmp_pwm; OCR1B =  tmp_pwm; OCR2  = tmp_pwm;
61
        OCR1A =  tmp_pwm; OCR1B =  tmp_pwm; OCR2  = tmp_pwm;
62
        #endif 
62
        #endif 
63
        }
63
        }
64
}
64
}
65
 
65
 
66
//############################################################################
66
//############################################################################
67
//
67
//
68
void PWM_Init(void)
68
void PWM_Init(void)
69
//############################################################################
69
//############################################################################
70
{
70
{
71
    PWM_OFF;
71
    PWM_OFF;
72
    TCCR1B = (1 << CS10) | (0 << CS11) | (0 << CS12) | (0 << WGM12) |
72
    TCCR1B = (1 << CS10) | (0 << CS11) | (0 << CS12) | (0 << WGM12) |
73
             (0 << WGM13) | (0<< ICES1) | (0 << ICNC1);
73
             (0 << WGM13) | (0<< ICES1) | (0 << ICNC1);
74
/*    TCCR1B = (1 << CS10) | (0 << CS11) | (0 << CS12) | (1 << WGM12) |
74
/*    TCCR1B = (1 << CS10) | (0 << CS11) | (0 << CS12) | (1 << WGM12) |
75
             (0 << WGM13) | (0<< ICES1) | (0 << ICNC1);
75
             (0 << WGM13) | (0<< ICES1) | (0 << ICNC1);
76
*/
76
*/
77
}
77
}
78
 
78
 
79
//############################################################################
79
//############################################################################
80
//
80
//
81
void Wait(unsigned char dauer)
81
void Wait(unsigned char dauer)
82
//############################################################################
82
//############################################################################
83
{
83
{
84
    dauer = (unsigned char)TCNT0 + dauer;
84
    dauer = (unsigned char)TCNT0 + dauer;
85
    while((TCNT0 - dauer) & 0x80);
85
    while((TCNT0 - dauer) & 0x80);
86
}
86
}
87
 
87
 
88
//############################################################################
88
//############################################################################
89
//
89
//
90
void Anwerfen(unsigned char pwm)
90
void Anwerfen(unsigned char pwm)
91
//############################################################################
91
//############################################################################
92
{
92
{
93
    unsigned long timer = 300,i;
93
    unsigned long timer = 300,i;
94
    DISABLE_SENSE_INT;
94
    DISABLE_SENSE_INT;
95
    PWM = 5;
95
    PWM = 5;
96
    SetPWM();
96
    SetPWM();
97
    Manuell();
97
    Manuell();
98
    Delay_ms(200);
98
    Delay_ms(200);
99
    PWM = pwm;
99
    PWM = pwm;
100
    while(1)
100
    while(1)
101
        {
101
        {
102
        for(i=0;i<timer; i++)
102
        for(i=0;i<timer; i++)
103
            {
103
            {
104
            if(!UebertragungAbgeschlossen)  SendUart();
104
            if(!UebertragungAbgeschlossen)  SendUart();
105
            else DatenUebertragung();
105
            else DatenUebertragung();
106
            Wait(100);  // warten
106
            Wait(100);  // warten
107
            }
107
            }
108
        timer-= timer/15+1;
108
        timer-= timer/15+1;
109
        if(timer < 25) { if(TEST_MANUELL) timer = 25; else return; }
109
        if(timer < 25) { if(TEST_MANUELL) timer = 25; else return; }
110
 
110
 
111
        Manuell();
111
        Manuell();
112
        Phase++;
112
        Phase++;
113
        Phase %= 6;
113
        Phase %= 6;
114
        AdConvert();
114
        AdConvert();
115
        PWM = pwm;
115
        PWM = pwm;
116
        SetPWM();
116
        SetPWM();
117
        if(SENSE)
117
        if(SENSE)
118
            {
118
            {
119
            PORTD ^= GRUEN;
119
            PORTD ^= GRUEN;
120
            }
120
            }
121
        }
121
        }
122
}
122
}
123
 
123
 
124
/*
124
/*
125
#define SENSE_A ADMUX = 0;
125
#define SENSE_A ADMUX = 0;
126
#define SENSE_B ADMUX = 1;
126
#define SENSE_B ADMUX = 1;
127
#define SENSE_C ADMUX = 2;
127
#define SENSE_C ADMUX = 2;
128
 
128
 
129
#define ClrSENSE            ACSR |= 0x10
129
#define ClrSENSE            ACSR |= 0x10
130
#define SENSE               ((ACSR & 0x10))
130
#define SENSE               ((ACSR & 0x10))
131
#define SENSE_L             (!(ACSR & 0x20))
131
#define SENSE_L             (!(ACSR & 0x20))
132
#define SENSE_H             ((ACSR & 0x20))
132
#define SENSE_H             ((ACSR & 0x20))
133
*/
133
*/
134
 
134
 
135
void RotBlink(unsigned char anz)
135
void RotBlink(unsigned char anz)
136
{
136
{
137
sei(); // Interrupts ein
137
sei(); // Interrupts ein
138
 while(anz--)
138
 while(anz--)
139
  {
139
  {
140
   PORTC |= ROT;
140
   PORTC |= ROT;
141
   Delay_ms(300);    
141
   Delay_ms(300);    
142
   PORTC &= ~ROT;
142
   PORTC &= ~ROT;
143
   Delay_ms(300);    
143
   Delay_ms(300);    
144
  }
144
  }
145
   Delay_ms(1000);    
145
   Delay_ms(1000);    
146
}
146
}
147
 
147
 
148
#define TEST_STROMGRENZE 90
148
#define TEST_STROMGRENZE 90
149
unsigned char DelayM(unsigned int timer)
149
unsigned char DelayM(unsigned int timer)
150
{
150
{
151
 while(timer--)
151
 while(timer--)
152
  {
152
  {
153
   FastADConvert();
153
   FastADConvert();
154
   if(Strom > TEST_STROMGRENZE)
154
   if(Strom > TEST_STROMGRENZE)
155
       {
155
       {
156
        FETS_OFF;
156
        FETS_OFF;
157
        return(1);
157
        return(1);
158
       }
158
       }
159
  }
159
  }
160
 return(0);  
160
 return(0);  
161
}
161
}
162
 
162
 
163
unsigned char Delay(unsigned int timer)
163
unsigned char Delay(unsigned int timer)
164
{
164
{
165
 while(timer--)
165
 while(timer--)
166
  {
166
  {
167
//   if(SENSE_H) { PORTC |= ROT; } else { PORTC &= ~ROT;}
167
//   if(SENSE_H) { PORTC |= ROT; } else { PORTC &= ~ROT;}
168
  }
168
  }
169
 return(0);  
169
 return(0);  
170
}
170
}
171
 
171
 
172
void ShowSense(void)
172
void ShowSense(void)
173
{
173
{
174
 if(SENSE_H) { PORTC |= ROT; } else { PORTC &= ~ROT;}
174
 if(SENSE_H) { PORTC |= ROT; } else { PORTC &= ~ROT;}
175
 
175
 
176
}
176
}
177
 
177
 
178
#define HIGH_A_EIN PORTB |= 0x08
178
#define HIGH_A_EIN PORTB |= 0x08
179
#define HIGH_B_EIN PORTB |= 0x04
179
#define HIGH_B_EIN PORTB |= 0x04
180
#define HIGH_C_EIN PORTB |= 0x02
180
#define HIGH_C_EIN PORTB |= 0x02
181
#define LOW_A_EIN  PORTD |= 0x08
181
#define LOW_A_EIN  PORTD |= 0x08
182
#define LOW_B_EIN  PORTD |= 0x10
182
#define LOW_B_EIN  PORTD |= 0x10
183
#define LOW_C_EIN  PORTD |= 0x20
183
#define LOW_C_EIN  PORTD |= 0x20
184
 
184
 
185
void MotorTon(void)
185
void MotorTon(void)
186
//############################################################################
186
//############################################################################
187
{
187
{
188
    unsigned char ADR_TAB[5] = {0,0,2,1,3};
188
    unsigned char ADR_TAB[5] = {0,0,2,1,3};
189
    unsigned int timer = 300,i;
189
    unsigned int timer = 300,i;
190
    unsigned int t = 0;
190
    unsigned int t = 0;
191
    unsigned char MosfetKurzschluss = 0, MosfetOkay = 0,anz = 0;
191
    unsigned char MosfetKurzschluss = 0, MosfetOkay = 0,anz = 0;
192
 
192
 
193
    PORTC &= ~ROT;
193
    PORTC &= ~ROT;
194
    Delay_ms(300 * ADR_TAB[MotorAdresse]);    
194
    Delay_ms(300 * ADR_TAB[MotorAdresse]);    
195
    DISABLE_SENSE_INT;
195
    DISABLE_SENSE_INT;
196
    cli();//Globale Interrupts Ausschalten
196
    cli();//Globale Interrupts Ausschalten
197
    uart_putchar('\n');
197
    uart_putchar('\n');
198
    STEUER_OFF;
198
    STEUER_OFF;
199
 
199
 
200
//+++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
200
//+++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
201
//+ High-Mosfets auf Kurzschluss testen
201
//+ High-Mosfets auf Kurzschluss testen
202
//+++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
202
//+++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
203
    Strom = 0;
203
    Strom = 0;
204
    LOW_B_EIN;
204
    LOW_B_EIN;
205
    HIGH_A_EIN;
205
    HIGH_A_EIN;
206
    if(DelayM(3))
206
    if(DelayM(3))
207
       {
207
       {
208
        anz = 1;
208
        anz = 1;
209
        uart_putchar('1');
209
        uart_putchar('1');
210
       }
210
       }
211
    FETS_OFF;
211
    FETS_OFF;
212
    Delay(1000);
212
    Delay(1000);
213
    Strom = 0;
213
    Strom = 0;
214
    LOW_A_EIN;
214
    LOW_A_EIN;
215
    HIGH_B_EIN;
215
    HIGH_B_EIN;
216
    if(DelayM(3))
216
    if(DelayM(3))
217
       {
217
       {
218
        anz = 2;
218
        anz = 2;
219
        uart_putchar('2');
219
        uart_putchar('2');
220
       }
220
       }
221
    FETS_OFF;
221
    FETS_OFF;
222
    Delay(1000);
222
    Delay(1000);
223
    Strom = 0;
223
    Strom = 0;
224
    LOW_B_EIN; // Low C ein
224
    LOW_B_EIN; // Low C ein
225
    HIGH_C_EIN; // High B ein
225
    HIGH_C_EIN; // High B ein
226
    if(DelayM(3))
226
    if(DelayM(3))
227
       {
227
       {
228
        anz = 3;
228
        anz = 3;
229
        uart_putchar('3');
229
        uart_putchar('3');
230
       }
230
       }
231
    FETS_OFF;
231
    FETS_OFF;
232
    Delay(1000);
232
    Delay(1000);
233
    LOW_A_EIN; // Low  A ein; und A gegen C
233
    LOW_A_EIN; // Low  A ein; und A gegen C
234
    HIGH_C_EIN; // High C ein
234
    HIGH_C_EIN; // High C ein
235
    if(DelayM(3))
235
    if(DelayM(3))
236
       {
236
       {
237
        anz = 3;
237
        anz = 3;
238
        MosfetKurzschluss = 0x01;
238
        MosfetKurzschluss = 0x01;
239
        uart_putchar('7');
239
        uart_putchar('7');
240
       }
240
       }
241
    FETS_OFF;
241
    FETS_OFF;
242
    DelayM(10000);
242
    DelayM(10000);
243
if(anz) while(1) RotBlink(anz);  // bei Kurzschluss nicht starten
243
if(anz) while(1) RotBlink(anz);  // bei Kurzschluss nicht starten
244
 
244
 
245
//+++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
245
//+++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
246
//+ LOW-Mosfets auf Schalten und Kurzschluss testen
246
//+ LOW-Mosfets auf Schalten und Kurzschluss testen
247
//+++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
247
//+++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
248
 if(UDR == ' ') {t = 65535; uart_putchar('_');} else t = 1000; // Ausführlicher Test
248
 if(UDR == ' ') {t = 65535; uart_putchar('_');} else t = 1000; // Ausführlicher Test
249
 Strom = 0;
249
 Strom = 0;
250
 for(i=0;i<t;i++)
250
 for(i=0;i<t;i++)
251
 {
251
 {
252
  LOW_A_EIN;
252
  LOW_A_EIN;
253
  DelayM(1);
253
  DelayM(1);
254
  FETS_OFF;
254
  FETS_OFF;
255
  Delay(5);
255
  Delay(5);
256
  HIGH_A_EIN;
256
  HIGH_A_EIN;
257
  DelayM(1);
257
  DelayM(1);
258
  FETS_OFF;
258
  FETS_OFF;
259
  if(Strom > 40) {anz = 4; uart_putchar('4'); break;}
259
  if(Strom > 40) {anz = 4; uart_putchar('4'); break;}
260
  Delay(5);
260
  Delay(5);
261
 }
261
 }
262
 Delay(10000);
262
 Delay(10000);
263
 
263
 
264
 Strom = 0;
264
 Strom = 0;
265
 for(i=0;i<t;i++)
265
 for(i=0;i<t;i++)
266
 {
266
 {
267
  LOW_B_EIN;
267
  LOW_B_EIN;
268
  DelayM(1);
268
  DelayM(1);
269
  FETS_OFF;
269
  FETS_OFF;
270
  Delay(5);
270
  Delay(5);
271
  HIGH_B_EIN;
271
  HIGH_B_EIN;
272
  DelayM(1);
272
  DelayM(1);
273
  FETS_OFF;
273
  FETS_OFF;
274
  if(Strom > 40) {anz = 5; uart_putchar('5'); break;}
274
  if(Strom > 40) {anz = 5; uart_putchar('5'); break;}
275
  Delay(5);
275
  Delay(5);
276
 }
276
 }
277
 
277
 
278
 Strom = 0;
278
 Strom = 0;
279
 Delay(10000);
279
 Delay(10000);
280
 
280
 
281
 for(i=0;i<t;i++)
281
 for(i=0;i<t;i++)
282
 {
282
 {
283
  LOW_C_EIN;
283
  LOW_C_EIN;
284
  DelayM(1);
284
  DelayM(1);
285
  FETS_OFF;
285
  FETS_OFF;
286
  Delay(5);
286
  Delay(5);
287
  HIGH_C_EIN;
287
  HIGH_C_EIN;
288
  DelayM(1);
288
  DelayM(1);
289
  FETS_OFF;
289
  FETS_OFF;
290
  if(Strom > 40) {anz = 6; uart_putchar('6'); break;}
290
  if(Strom > 40) {anz = 6; uart_putchar('6'); break;}
291
  Delay(5);
291
  Delay(5);
292
 }
292
 }
293
 
293
 
294
//+++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
294
//+++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
295
//+ High-Mosfets auf Schalten testen
295
//+ High-Mosfets auf Schalten testen
296
//+++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
296
//+++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
297
    SENSE_A;
297
    SENSE_A;
298
    FETS_OFF;
298
    FETS_OFF;
299
    LOW_B_EIN; // Low B ein
299
    LOW_B_EIN; // Low B ein
300
    LOW_C_EIN; // Low C ein
300
    LOW_C_EIN; // Low C ein
301
    Strom = 0;
301
    Strom = 0;
302
#define TONDAUER  40000    
302
#define TONDAUER  40000    
303
#define SOUND_E 2
303
#define SOUND_E 2
304
#define SOUND1_A 300
304
#define SOUND1_A 300
305
#define SOUND2_A 330
305
#define SOUND2_A 330
306
#define SOUND3_A 360
306
#define SOUND3_A 360
307
 
307
 
308
    for(i=0; i< (TONDAUER / SOUND2_A) ; i++)
308
    for(i=0; i< (TONDAUER / SOUND2_A) ; i++)
309
     {
309
     {
310
      HIGH_A_EIN; // Test A
310
      HIGH_A_EIN; // Test A
311
      Delay(SOUND_E);
311
      Delay(SOUND_E);
312
      if(MessAD(0) > 50) { MosfetOkay |= 0x01; } else { MosfetOkay &= ~0x01;};
312
      if(MessAD(0) > 50) { MosfetOkay |= 0x01; } else { MosfetOkay &= ~0x01;};
313
      PORTB = 0;
313
      PORTB = 0;
314
      Delay(SOUND1_A);
314
      Delay(SOUND1_A);
315
     }
315
     }
316
    FETS_OFF;
316
    FETS_OFF;
317
 
317
 
318
    LOW_A_EIN; // Low A ein
318
    LOW_A_EIN; // Low A ein
319
    LOW_C_EIN; // Low C ein
319
    LOW_C_EIN; // Low C ein
320
    for(i=0; i<(TONDAUER / SOUND1_A); i++)
320
    for(i=0; i<(TONDAUER / SOUND1_A); i++)
321
     {
321
     {
322
      HIGH_B_EIN; // Test B
322
      HIGH_B_EIN; // Test B
323
      Delay(SOUND_E);
323
      Delay(SOUND_E);
324
      if(MessAD(1) > 50) { MosfetOkay |= 0x02; } else { MosfetOkay &= ~0x02;};
324
      if(MessAD(1) > 50) { MosfetOkay |= 0x02; } else { MosfetOkay &= ~0x02;};
325
      PORTB = 0;
325
      PORTB = 0;
326
      Delay(SOUND1_A);
326
      Delay(SOUND1_A);
327
     }
327
     }
328
 
328
 
329
    FETS_OFF;
329
    FETS_OFF;
330
    LOW_A_EIN; // Low A ein
330
    LOW_A_EIN; // Low A ein
331
    LOW_B_EIN; // Low B ein
331
    LOW_B_EIN; // Low B ein
332
    for(i=0; i<(TONDAUER / SOUND3_A); i++)
332
    for(i=0; i<(TONDAUER / SOUND3_A); i++)
333
     {
333
     {
334
      HIGH_C_EIN; // Test C
334
      HIGH_C_EIN; // Test C
335
      Delay(SOUND_E);
335
      Delay(SOUND_E);
336
      if(MessAD(2) > 50) { MosfetOkay |= 0x04; } else { MosfetOkay &= ~0x04;};
336
      if(MessAD(2) > 50) { MosfetOkay |= 0x04; } else { MosfetOkay &= ~0x04;};
337
      PORTB = 0;
337
      PORTB = 0;
338
      Delay(SOUND2_A);
338
      Delay(SOUND2_A);
339
     }
339
     }
340
    FETS_OFF;
340
    FETS_OFF;
341
//+++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
341
//+++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
342
//+ Low-Mosfets auf Schalten testen
342
//+ Low-Mosfets auf Schalten testen
343
//+++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
343
//+++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
344
    SENSE_B;
344
    SENSE_B;
345
    LOW_A_EIN; // Low A ein
345
    LOW_A_EIN; // Low A ein
346
#define SOUND2_A 500
346
#define SOUND2_A 500
347
    for(i=0; i< (TONDAUER / SOUND2_A) ; i++)
347
    for(i=0; i< (TONDAUER / SOUND2_A) ; i++)
348
     {
348
     {
349
      HIGH_B_EIN; // Test B
349
      HIGH_B_EIN; // Test B
350
      Delay(SOUND_E);
350
      Delay(SOUND_E);
351
      if(MessAD(0) > 50) { MosfetOkay &= ~0x08;} else { MosfetOkay |= 0x08;};
351
      if(MessAD(0) > 50) { MosfetOkay &= ~0x08;} else { MosfetOkay |= 0x08;};
352
      PORTB = 0;
352
      PORTB = 0;
353
      Delay(SOUND2_A);
353
      Delay(SOUND2_A);
354
     }
354
     }
355
 
355
 
356
//++++++++++++++++++++++++++++++++++++
356
//++++++++++++++++++++++++++++++++++++
357
    LOW_C_EIN; // Low C ein
357
    LOW_C_EIN; // Low C ein
358
    for(i=0; i<(TONDAUER / SOUND1_A); i++)
358
    for(i=0; i<(TONDAUER / SOUND1_A); i++)
359
     {
359
     {
360
      HIGH_B_EIN; // Test B
360
      HIGH_B_EIN; // Test B
361
      Delay(SOUND_E);
361
      Delay(SOUND_E);
362
      if(MessAD(2) > 50) { MosfetOkay &= ~0x20;} else { MosfetOkay |= 0x20;};
362
      if(MessAD(2) > 50) { MosfetOkay &= ~0x20;} else { MosfetOkay |= 0x20;};
363
      PORTB = 0;
363
      PORTB = 0;
364
      Delay(SOUND3_A);
364
      Delay(SOUND3_A);
365
     }
365
     }
366
    FETS_OFF;
366
    FETS_OFF;
367
//++++++++++++++++++++++++++++++++++++
367
//++++++++++++++++++++++++++++++++++++
368
    FETS_OFF;
368
    FETS_OFF;
369
    LOW_B_EIN; // Low B ein
369
    LOW_B_EIN; // Low B ein
370
    for(i=0; i<(TONDAUER / SOUND3_A); i++)
370
    for(i=0; i<(TONDAUER / SOUND3_A); i++)
371
     {
371
     {
372
      HIGH_C_EIN; // Test C
372
      HIGH_C_EIN; // Test C
373
      Delay(SOUND_E);
373
      Delay(SOUND_E);
374
      if(MessAD(1) > 50) { MosfetOkay &= ~0x10;} else { MosfetOkay |= 0x10;};
374
      if(MessAD(1) > 50) { MosfetOkay &= ~0x10;} else { MosfetOkay |= 0x10;};
375
      PORTB = 0;
375
      PORTB = 0;
376
      Delay(SOUND3_A);
376
      Delay(SOUND3_A);
377
     }
377
     }
378
    FETS_OFF;
378
    FETS_OFF;
379
//++++++++++++++++++++++++++++++++++++
379
//++++++++++++++++++++++++++++++++++++
380
 
380
 
381
//+++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
381
//+++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
382
    sei();//Globale Interrupts Einschalten
382
    sei();//Globale Interrupts Einschalten
383
//    Delay_ms(250 * MotorAdresse);    
383
//    Delay_ms(250 * MotorAdresse);    
384
/*
384
/*
385
    LOW_A_EIN; // Low B ein
385
    LOW_A_EIN; // Low B ein
386
#define SOUND8_A 650
386
#define SOUND8_A 650
387
    for(i=0; i<(TONDAUER / SOUND8_A); i++)
387
    for(i=0; i<(TONDAUER / SOUND8_A); i++)
388
     {
388
     {
389
      HIGH_B_EIN; // Test B
389
      HIGH_B_EIN; // Test B
390
      Delay(SOUND_E);
390
      Delay(SOUND_E);
391
      PORTB = 0;
391
      PORTB = 0;
392
      Delay(SOUND8_A);
392
      Delay(SOUND8_A);
393
     }
393
     }
394
*/
394
*/
395
 if(!(MosfetOkay & 0x01))  { anz = 1; uart_putchar('A'); } else
395
 if(!(MosfetOkay & 0x01))  { anz = 1; uart_putchar('A'); } else
396
 if(!(MosfetOkay & 0x02))  { anz = 2; uart_putchar('B'); } else
396
 if(!(MosfetOkay & 0x02))  { anz = 2; uart_putchar('B'); } else
397
 if(!(MosfetOkay & 0x04))  { anz = 3; uart_putchar('C'); } else
397
 if(!(MosfetOkay & 0x04))  { anz = 3; uart_putchar('C'); } else
398
 if(!(MosfetOkay & 0x08))  { anz = 4; uart_putchar('a'); } else
398
 if(!(MosfetOkay & 0x08))  { anz = 4; uart_putchar('a'); } else
399
 if(!(MosfetOkay & 0x10))  { anz = 5; uart_putchar('b'); } else
399
 if(!(MosfetOkay & 0x10))  { anz = 5; uart_putchar('b'); } else
400
 if(!(MosfetOkay & 0x20))  { anz = 6; uart_putchar('c'); }  
400
 if(!(MosfetOkay & 0x20))  { anz = 6; uart_putchar('c'); }  
401
 Delay_ms(300 * (4-ADR_TAB[MotorAdresse]));    
401
 Delay_ms(300 * (4-ADR_TAB[MotorAdresse]));    
402
 
402
 
403
 if(MosfetOkay != 0x3f) Delay_ms(1000);
403
 if(MosfetOkay != 0x3f) Delay_ms(1000);
404
 
404
 
405
 RotBlink(anz);
405
 RotBlink(anz);
406
 uart_putchar('.');
406
 uart_putchar('.');
407
}
407
}
408
 
408
 
409
//############################################################################
409
//############################################################################
410
//
410
//
411
unsigned char SollwertErmittlung(void)
411
unsigned char SollwertErmittlung(void)
412
//############################################################################
412
//############################################################################
413
{
413
{
414
    static unsigned int sollwert = 0;
414
    static unsigned int sollwert = 0;
415
    unsigned int ppm;
415
    unsigned int ppm;
416
    if(!I2C_Timeout)   // bei Erreichen von 0 ist der Wert ungültig
416
    if(!I2C_Timeout)   // bei Erreichen von 0 ist der Wert ungültig
417
        {
417
        {
418
        if(SIO_Timeout)  // es gibt gültige SIO-Daten
418
        if(SIO_Timeout)  // es gibt gültige SIO-Daten
419
            {
419
            {
420
             sollwert =  (MAX_PWM * (unsigned int) SIO_Sollwert) / 200;  // skalieren auf 0-200 = 0-255
420
             sollwert =  (MAX_PWM * (unsigned int) SIO_Sollwert) / 200;  // skalieren auf 0-200 = 0-255
421
             PPM_Betrieb = 0;
421
             PPM_Betrieb = 0;
422
             ICP_INT_DISABLE;
422
             ICP_INT_DISABLE;
423
             PORTC &= ~ROT;
423
             PORTC &= ~ROT;
424
            }
424
            }
425
        else
425
        else
426
            if(anz_ppm_werte > 20)  // es gibt gültige PPM-Daten
426
            if(anz_ppm_werte > 20)  // es gibt gültige PPM-Daten
427
                {
427
                {
428
                PPM_Betrieb = 1;
428
                PPM_Betrieb = 1;
429
                ppm = PPM_Signal;
429
                ppm = PPM_Signal;
430
                if(ppm > 300) ppm =   0;  // ungültiges Signal
430
                if(ppm > 300) ppm =   0;  // ungültiges Signal
431
                if(ppm > 200) ppm = 200;
431
                if(ppm > 200) ppm = 200;
432
                if(ppm <= MIN_PPM) sollwert = 0;
432
                if(ppm <= MIN_PPM) sollwert = 0;
433
                else
433
                else
434
                    {
434
                    {
435
                    sollwert = (int) MIN_PWM + ((MAX_PWM - MIN_PWM) * (ppm - MIN_PPM)) / (190 - MIN_PPM);
435
                    sollwert = (int) MIN_PWM + ((MAX_PWM - MIN_PWM) * (ppm - MIN_PPM)) / (190 - MIN_PPM);
436
                    }
436
                    }
437
                PORTC &= ~ROT;
437
                PORTC &= ~ROT;
438
                }
438
                }
439
            else   // Kein gültiger Sollwert
439
            else   // Kein gültiger Sollwert
440
                {
440
                {
441
                 if(!TEST_SCHUB) { if(sollwert) sollwert--; }  
441
                 if(!TEST_SCHUB) { if(sollwert) sollwert--; }  
442
                 PORTC |= ROT;
442
                 PORTC |= ROT;
443
                }
443
                }
444
        }
444
        }
445
    else // I2C-Daten sind gültig
445
    else // I2C-Daten sind gültig
446
        {
446
        {
447
        sollwert = I2C_RXBuffer;
447
        sollwert = I2C_RXBuffer;
448
        PPM_Betrieb = 0;
448
        PPM_Betrieb = 0;
449
        PORTC &= ~ROT;
449
        PORTC &= ~ROT;
450
        ICP_INT_DISABLE;
450
        ICP_INT_DISABLE;
451
        }
451
        }
452
    if(sollwert > MAX_PWM) sollwert = MAX_PWM;
452
    if(sollwert > MAX_PWM) sollwert = MAX_PWM;
453
    return(sollwert);
453
    return(sollwert);
454
}
454
}
455
 
455
 
456
void DebugAusgaben(void)
456
void DebugAusgaben(void)
457
{
457
{
458
    DebugOut.Analog[0] = Strom;
458
    DebugOut.Analog[0] = Strom;
459
    DebugOut.Analog[1] = Mittelstrom;
459
    DebugOut.Analog[1] = Mittelstrom;
460
    DebugOut.Analog[2] = SIO_Drehzahl;
460
    DebugOut.Analog[2] = SIO_Drehzahl;
461
    DebugOut.Analog[3] = PPM_Signal;
461
    DebugOut.Analog[3] = PPM_Signal;
462
}
462
}
463
 
463
 
464
 
464
 
465
//############################################################################
465
//############################################################################
466
//Hauptprogramm
466
//Hauptprogramm
467
int main (void)
467
int main (void)
468
//############################################################################
468
//############################################################################
469
{
469
{
470
    char altPhase = 0;
470
    char altPhase = 0;
471
    int test = 0;
471
    int test = 0;
472
    unsigned int MinUpmPulse,Blink,TestschubTimer;
472
    unsigned int MinUpmPulse,Blink,TestschubTimer;
473
    unsigned int Blink2,MittelstromTimer,DrehzahlMessTimer,MotorGestopptTimer;
473
    unsigned int Blink2,MittelstromTimer,DrehzahlMessTimer,MotorGestopptTimer;
474
 
474
 
475
    DDRC  = 0x08;
475
    DDRC  = 0x08;
476
    PORTC = 0x08;
476
    PORTC = 0x08;
477
    DDRD  = 0xBA;
477
    DDRD  = 0xBA;
478
    PORTD = 0x00;
478
    PORTD = 0x00;
479
    DDRB  = 0x0E;
479
    DDRB  = 0x0E;
480
    PORTB = 0x31;
480
    PORTB = 0x31;
481
       
481
       
482
#if (MOTORADRESSE == 0)
482
#if (MOTORADRESSE == 0)
483
    PORTB |= (ADR1 + ADR2);   // Pullups für Adresswahl
483
    PORTB |= (ADR1 + ADR2);   // Pullups für Adresswahl
484
    for(test=0;test<500;test++);
484
    for(test=0;test<500;test++);
485
    if (PINB & ADR1)
485
    if (PINB & ADR1)
486
         {
486
         {
487
           if (PINB & ADR2) MotorAdresse = 1;
487
           if (PINB & ADR2) MotorAdresse = 1;
488
            else MotorAdresse = 2;
488
            else MotorAdresse = 2;
489
         }
489
         }
490
         else
490
         else
491
         {
491
         {
492
           if (PINB & ADR2) MotorAdresse = 3;
492
           if (PINB & ADR2) MotorAdresse = 3;
493
            else MotorAdresse = 4;
493
            else MotorAdresse = 4;
494
         }
494
         }
495
#else
495
#else
496
    MotorAdresse  = MOTORADRESSE;
496
    MotorAdresse  = MOTORADRESSE;
497
#endif
497
#endif
498
   
498
   
499
    UART_Init();
499
    UART_Init();
500
    Timer0_Init();
500
    Timer0_Init();
501
    sei();//Globale Interrupts Einschalten
501
    sei();//Globale Interrupts Einschalten
502
   
502
   
503
    // Am Blinken erkennt man die richtige Motoradresse
503
    // Am Blinken erkennt man die richtige Motoradresse
504
/*
504
/*
505
    for(test=0;test<5;test++)
505
    for(test=0;test<5;test++)
506
        {
506
        {
507
        if(test == MotorAdresse) PORTD |= GRUEN;
507
        if(test == MotorAdresse) PORTD |= GRUEN;
508
        Delay_ms(150);
508
        Delay_ms(150);
509
        PORTD &= ~GRUEN;
509
        PORTD &= ~GRUEN;
510
        Delay_ms(250);
510
        Delay_ms(250);
511
        }      
511
        }      
512
 
512
 
513
    Delay_ms(500);
513
    Delay_ms(500);
514
*/  
514
*/  
515
   // UART_Init();  // war doppelt
515
   // UART_Init();  // war doppelt
516
    PWM_Init();
516
    PWM_Init();
517
 
517
 
518
    InitIC2_Slave(0x50);                           
518
    InitIC2_Slave(0x50);                           
519
    InitPPM();
519
    InitPPM();
520
 
520
 
521
    Blink             = SetDelay(101);    
521
    Blink             = SetDelay(101);    
522
    Blink2            = SetDelay(102);
522
    Blink2            = SetDelay(102);
523
    MinUpmPulse       = SetDelay(103);
523
    MinUpmPulse       = SetDelay(103);
524
    MittelstromTimer  = SetDelay(254);
524
    MittelstromTimer  = SetDelay(254);
525
    DrehzahlMessTimer = SetDelay(1005);
525
    DrehzahlMessTimer = SetDelay(1005);
526
    TestschubTimer    = SetDelay(1006);
526
    TestschubTimer    = SetDelay(1006);
527
    while(!CheckDelay(MinUpmPulse))
527
    while(!CheckDelay(MinUpmPulse))
528
    {
528
    {
529
     if(SollwertErmittlung()) break;
529
     if(SollwertErmittlung()) break;
530
    }
530
    }
531
    ;
531
    ;
532
    PORTD |= GRUEN;
532
    PORTD |= GRUEN;
533
    PWM = 0;
533
    PWM = 0;
534
 
534
 
535
    SetPWM();
535
    SetPWM();
536
 
536
 
537
    SFIOR = 0x08;  // Analog Comperator ein
537
    SFIOR = 0x08;  // Analog Comperator ein
538
    ADMUX = 1;
538
    ADMUX = 1;
539
 
539
 
540
    MinUpmPulse = SetDelay(10);
540
    MinUpmPulse = SetDelay(10);
541
    DebugOut.Analog[1] = 1;
541
    DebugOut.Analog[1] = 1;
542
    PPM_Signal = 0;
542
    PPM_Signal = 0;
543
 
543
 
544
    if(!SollwertErmittlung()) MotorTon();
544
    if(!SollwertErmittlung()) MotorTon();
545
 
545
 
546
    // zum Test der Hardware; Motor dreht mit konstanter Drehzahl ohne Regelung
546
    // zum Test der Hardware; Motor dreht mit konstanter Drehzahl ohne Regelung
547
    if(TEST_MANUELL)    Anwerfen(TEST_MANUELL);  // kommt von dort nicht wieder
547
    if(TEST_MANUELL)    Anwerfen(TEST_MANUELL);  // kommt von dort nicht wieder
548
 
548
 
549
    while (1)
549
    while (1)
550
        {
550
        {
551
//ShowSense();
551
//ShowSense();
552
 
552
 
553
        if(!TEST_SCHUB)   PWM = SollwertErmittlung();
553
        if(!TEST_SCHUB)   PWM = SollwertErmittlung();
554
        //I2C_TXBuffer = PWM; // Antwort über I2C-Bus
554
        //I2C_TXBuffer = PWM; // Antwort über I2C-Bus
555
        if(MANUELL_PWM)   PWM = MANUELL_PWM;
555
        if(MANUELL_PWM)   PWM = MANUELL_PWM;
556
 
556
 
557
        // ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
557
        // ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
558
        if(Phase != altPhase)   // es gab eine Kommutierung im Interrupt
558
        if(Phase != altPhase)   // es gab eine Kommutierung im Interrupt
559
            {
559
            {
560
            MotorGestoppt = 0;
560
            MotorGestoppt = 0;
561
            ZeitFuerBerechnungen = 0;    // direkt nach einer Kommutierung ist Zeit 
561
            ZeitFuerBerechnungen = 0;    // direkt nach einer Kommutierung ist Zeit 
562
            MinUpmPulse = SetDelay(50);  // Timeout, falls ein Motor stehen bleibt
562
            MinUpmPulse = SetDelay(50);  // Timeout, falls ein Motor stehen bleibt
563
            altPhase = Phase;
563
            altPhase = Phase;
564
            }
564
            }
565
        // ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
565
        // ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
566
        if(!PWM)    // Sollwert == 0
566
        if(!PWM)    // Sollwert == 0
567
            {
567
            {
568
            MotorAnwerfen = 0;      // kein Startversuch
568
            MotorAnwerfen = 0;      // kein Startversuch
569
            ZeitFuerBerechnungen = 0;
569
            ZeitFuerBerechnungen = 0;
570
            // nach 1,5 Sekunden den Motor als gestoppt betrachten 
570
            // nach 1,5 Sekunden den Motor als gestoppt betrachten 
571
            if(CheckDelay(MotorGestopptTimer))
571
            if(CheckDelay(MotorGestopptTimer))
572
                {
572
                {
573
                DISABLE_SENSE_INT;
573
                DISABLE_SENSE_INT;
574
                MotorGestoppt = 1;  
574
                MotorGestoppt = 1;  
575
                STEUER_OFF;
575
                STEUER_OFF;
576
                }
576
                }
577
            }
577
            }
578
        else
578
        else
579
            {
579
            {
580
            if(MotorGestoppt) MotorAnwerfen = 1;        // Startversuch
580
            if(MotorGestoppt) MotorAnwerfen = 1;        // Startversuch
581
            MotorGestopptTimer = SetDelay(1500);
581
            MotorGestopptTimer = SetDelay(1500);
582
            }
582
            }
583
 
583
 
584
        if(MotorGestoppt && !TEST_SCHUB) PWM = 0;
584
        if(MotorGestoppt && !TEST_SCHUB) PWM = 0;
585
        SetPWM();
585
        SetPWM();
586
        // +++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
586
        // +++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
587
        if(!ZeitFuerBerechnungen++)
587
        if(!ZeitFuerBerechnungen++)
588
            {
588
            {
589
            if(MotorGestoppt) PORTD |= GRUEN; //else PORTD &= ~GRUEN;
589
            if(MotorGestoppt) PORTD |= GRUEN; //else PORTD &= ~GRUEN;
590
            if(SIO_DEBUG)
590
            if(SIO_DEBUG)
591
                {
591
                {
592
                DebugAusgaben();  // welche Werte sollen angezeigt werden?
592
                DebugAusgaben();  // welche Werte sollen angezeigt werden?
593
                if(!UebertragungAbgeschlossen)  SendUart();
593
                if(!UebertragungAbgeschlossen)  SendUart();
594
                else DatenUebertragung();
594
                else DatenUebertragung();
595
                }
595
                }
596
            // Berechnen des Mittleren Stroms zur (langsamen) Strombegrenzung
596
            // Berechnen des Mittleren Stroms zur (langsamen) Strombegrenzung
597
            if(CheckDelay(MittelstromTimer))  
597
            if(CheckDelay(MittelstromTimer))  
598
                {
598
                {
599
                MittelstromTimer = SetDelay(50); // alle 50ms
599
                MittelstromTimer = SetDelay(50); // alle 50ms
600
                if(Mittelstrom <  Strom) Mittelstrom++;// Mittelwert des Stroms bilden
600
                if(Mittelstrom <  Strom) Mittelstrom++;// Mittelwert des Stroms bilden
601
                else if(Mittelstrom >  Strom) Mittelstrom--;
601
                else if(Mittelstrom >  Strom) Mittelstrom--;
602
       
602
       
603
                if(Mittelstrom > LIMIT_STROM)// Strom am Limit?
603
                if(Mittelstrom > LIMIT_STROM)// Strom am Limit?
604
                    {
604
                    {
605
                    MaxPWM--;// dann die Maximale PWM herunterfahren
605
                    MaxPWM--;// dann die Maximale PWM herunterfahren
606
                    PORTC |= ROT;
606
                    PORTC |= ROT;
607
                    }
607
                    }
608
                else
608
                else
609
                    {
609
                    {
610
                    if(MaxPWM < MAX_PWM) MaxPWM++;
610
                    if(MaxPWM < MAX_PWM) MaxPWM++;
611
                    }
611
                    }
612
                }
612
                }
613
 
613
 
614
            if(CheckDelay(DrehzahlMessTimer))   // Ist-Drehzahl bestimmen
614
            if(CheckDelay(DrehzahlMessTimer))   // Ist-Drehzahl bestimmen
615
                {
615
                {
616
                DrehzahlMessTimer = SetDelay(10);
616
                DrehzahlMessTimer = SetDelay(10);
617
                SIO_Drehzahl = (6 * CntKommutierungen) / (POLANZAHL / 2);
617
                SIO_Drehzahl = (6 * CntKommutierungen) / (POLANZAHL / 2);
618
                CntKommutierungen = 0;
618
                CntKommutierungen = 0;
619
                if(PPM_Timeout == 0) // keine PPM-Signale
619
                if(PPM_Timeout == 0) // keine PPM-Signale
620
                ZeitZumAdWandeln = 1;
620
                ZeitZumAdWandeln = 1;
621
                }
621
                }
622
 
622
 
623
 
623
 
624
            if(CheckDelay(TestschubTimer))  
624
            if(CheckDelay(TestschubTimer))  
625
                {
625
                {
626
                TestschubTimer = SetDelay(1500);
626
                TestschubTimer = SetDelay(1500);
627
                if(TEST_SCHUB)
627
                if(TEST_SCHUB)
628
                    {
628
                    {
629
                    switch(test)
629
                    switch(test)
630
                        {
630
                        {
631
                        case 0: PWM = 50; test++; break;
631
                        case 0: PWM = 50; test++; break;
632
                        case 1: PWM = 130; test++; break;
632
                        case 1: PWM = 130; test++; break;
633
                        case 2: PWM = 60;  test++; break;
633
                        case 2: PWM = 60;  test++; break;
634
                        case 3: PWM = 140; test++; break;
634
                        case 3: PWM = 140; test++; break;
635
                        case 4: PWM = 150; test = 0; break;
635
                        case 4: PWM = 150; test = 0; break;
636
                        default: test = 0;
636
                        default: test = 0;
637
                        }
637
                        }
638
                    }
638
                    }
639
                }
639
                }
640
            // Motor Stehen geblieben
640
            // Motor Stehen geblieben
641
            if((CheckDelay(MinUpmPulse) && SIO_Drehzahl == 0) || MotorAnwerfen)
641
            if((CheckDelay(MinUpmPulse) && SIO_Drehzahl == 0) || MotorAnwerfen)
642
                {
642
                {
643
                MotorGestoppt = 1;    
643
                MotorGestoppt = 1;    
644
                DISABLE_SENSE_INT;
644
                DISABLE_SENSE_INT;
645
                MinUpmPulse = SetDelay(100);        
645
                MinUpmPulse = SetDelay(100);        
646
                if(MotorAnwerfen)
646
                if(MotorAnwerfen)
647
                    {
647
                    {
648
                    PORTC &= ~ROT;
648
                    PORTC &= ~ROT;
649
                    MotorAnwerfen = 0;
649
                    MotorAnwerfen = 0;
650
                    Anwerfen(10);
650
                    Anwerfen(10);
651
                    PORTD |= GRUEN;
651
                    PORTD |= GRUEN;
652
                    MotorGestoppt = 0;    
652
                    MotorGestoppt = 0;    
653
                    Phase--;
653
                    Phase--;
654
                    PWM = 1;
654
                    PWM = 1;
655
                    SetPWM();
655
                    SetPWM();
656
                    SENSE_TOGGLE_INT;
656
                    SENSE_TOGGLE_INT;
657
                    ENABLE_SENSE_INT;
657
                    ENABLE_SENSE_INT;
658
                    MinUpmPulse = SetDelay(20);
658
                    MinUpmPulse = SetDelay(20);
659
                    while(!CheckDelay(MinUpmPulse)); // kurz Synchronisieren
659
                    while(!CheckDelay(MinUpmPulse)); // kurz Synchronisieren
660
                    PWM = 15;
660
                    PWM = 15;
661
                    SetPWM();
661
                    SetPWM();
662
                    MinUpmPulse = SetDelay(300);
662
                    MinUpmPulse = SetDelay(300);
663
                    while(!CheckDelay(MinUpmPulse)); // kurz Durchstarten
663
                    while(!CheckDelay(MinUpmPulse)); // kurz Durchstarten
664
                   
664
                   
665
                                    // Drehzahlmessung wieder aufsetzen
665
                                    // Drehzahlmessung wieder aufsetzen
666
                    DrehzahlMessTimer = SetDelay(50);
666
                    DrehzahlMessTimer = SetDelay(50);
667
                    altPhase = 7;
667
                    altPhase = 7;
668
                    }
668
                    }
669
                }
669
                }
670
            } // ZeitFuerBerechnungen
670
            } // ZeitFuerBerechnungen
671
        } // while(1) - Hauptschleife
671
        } // while(1) - Hauptschleife
672
}
672
}
673
 
673
 
674
 
674