Subversion Repositories BL-Ctrl

Rev

Rev 1 | Rev 23 | Go to most recent revision | Details | Compare with Previous | Last modification | View Log | RSS feed

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