Subversion Repositories BL-Ctrl

Rev

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