Subversion Repositories BL-Ctrl

Compare Revisions

Ignore whitespace Rev 65 → Rev 66

/branches/V0.37_neueStruktur/src/BLMC.c
0,0 → 1,235
/*#######################################################################################
Flight Control
#######################################################################################*/
// ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
// + Regler für Brushless-Motoren
// + ATMEGA8 mit 8MHz
// + Nur für den privaten Gebrauch
// + Copyright (c) 12.2007 Holger Buss
// + www.MikroKopter.com
// ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
// + Es gilt für das gesamte Projekt (Hardware, Software, Binärfiles, Sourcecode und Dokumentation),
// + dass eine Nutzung (auch auszugsweise) nur für den privaten (nicht-kommerziellen) Gebrauch zulässig ist.
// + Sollten direkte oder indirekte kommerzielle Absichten verfolgt werden, ist mit uns (info@mikrokopter.de) Kontakt
// + bzgl. der Nutzungsbedingungen aufzunehmen.
// + Eine kommerzielle Nutzung ist z.B.Verkauf von MikroKoptern, Bestückung und Verkauf von Platinen oder Bausätzen,
// + Verkauf von Luftbildaufnahmen, usw.
// ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
// + Werden Teile des Quellcodes (mit oder ohne Modifikation) weiterverwendet oder veröffentlicht,
// + unterliegen sie auch diesen Nutzungsbedingungen und diese Nutzungsbedingungen incl. Copyright müssen dann beiliegen
// ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
// + Sollte die Software (auch auszugesweise) oder sonstige Informationen des MikroKopter-Projekts
// + auf anderen Webseiten oder sonstigen Medien veröffentlicht werden, muss unsere Webseite "http://www.mikrokopter.de"
// + eindeutig als Ursprung verlinkt werden
// ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
// + Keine Gewähr auf Fehlerfreiheit, Vollständigkeit oder Funktion
// + Benutzung auf eigene Gefahr
// + Wir übernehmen keinerlei Haftung für direkte oder indirekte Personen- oder Sachschäden
// ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
// + Die Portierung der Software (oder Teile davon) auf andere Systeme (ausser der Hardware von www.mikrokopter.de) ist nur
// + mit unserer Zustimmung zulässig
// ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
// + Die Funktion printf_P() unterliegt ihrer eigenen Lizenz und ist hiervon nicht betroffen
// ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
// + Redistributions of source code (with or without modifications) must retain the above copyright notice,
// + this list of conditions and the following disclaimer.
// + * Neither the name of the copyright holders nor the names of contributors may be used to endorse or promote products derived
// + from this software without specific prior written permission.
// + * The use of this project (hardware, software, binary files, sources and documentation) is only permittet
// + for non-commercial use (directly or indirectly)
// + Commercial use (for excample: selling of MikroKopters, selling of PCBs, assembly, ...) is only permitted
// + with our written permission
// + * If sources or documentations are redistributet on other webpages, out webpage (http://www.MikroKopter.de) must be
// + clearly linked as origin
// + * porting to systems other than hardware from www.mikrokopter.de is not allowed
// + THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
// + AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
// + IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
// + ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
// + LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
// + CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
// + SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
// + INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN// + CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
// + ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
// + POSSIBILITY OF SUCH DAMAGE.
// ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
#include "main.h"
 
volatile unsigned char Phase = 0,ShadowTCCR1A = 0;
volatile unsigned char CompFreigabeTimer = 100;
volatile unsigned char CompInterruptFreigabe = 0;
 
 
//############################################################################
//
SIGNAL(SIG_OVERFLOW2)
//############################################################################
{
}
 
//############################################################################
// + Interruptroutine
// + Wird durch den Analogkomperator ausgelöst
// + Dadurch wird das Kommutieren erzeugt
SIGNAL(SIG_COMPARATOR)
//############################################################################
{
unsigned char sense = 0;
do
{
if(SENSE_H) sense = 1; else sense = 0;
switch(Phase)
{
case 0:
STEUER_A_H;
if(sense)
{
STEUER_C_L;
if(ZeitZumAdWandeln) AdConvert();
SENSE_FALLING_INT;
SENSE_B;
Phase++;
CntKommutierungen++;
}
else
{
STEUER_B_L;
}
break;
case 1:
STEUER_C_L;
if(!sense)
{
STEUER_B_H;
if(ZeitZumAdWandeln) AdConvert();
SENSE_A;
SENSE_RISING_INT;
Phase++;
CntKommutierungen++;
}
else
{
STEUER_A_H;
}
 
break;
case 2:
STEUER_B_H;
if(sense)
{
STEUER_A_L;
if(ZeitZumAdWandeln) AdConvert();
SENSE_C;
SENSE_FALLING_INT;
Phase++;
CntKommutierungen++;
}
else
{
STEUER_C_L;
}
break;
case 3:
STEUER_A_L;
if(!sense)
{
STEUER_C_H;
if(ZeitZumAdWandeln) AdConvert();
SENSE_B;
SENSE_RISING_INT;
Phase++;
CntKommutierungen++;
}
else
{
STEUER_B_H;
}
 
break;
case 4:
STEUER_C_H;
if(sense)
{
STEUER_B_L;
if(ZeitZumAdWandeln) AdConvert();
SENSE_A;
SENSE_FALLING_INT;
Phase++;
CntKommutierungen++;
}
else
{
STEUER_A_L;
}
break;
case 5:
STEUER_B_L;
if(!sense)
{
STEUER_A_H;
if(ZeitZumAdWandeln) AdConvert();
SENSE_C;
SENSE_RISING_INT;
Phase = 0;
CntKommutierungen++;
}
else
{
STEUER_C_H;
}
break;
}
}
while((SENSE_L && sense) || (SENSE_H && !sense));
ZeitZumAdWandeln = 0;
}
 
//############################################################################
//
void Manuell(void)
//############################################################################
{
switch(Phase)
{
case 0:
STEUER_A_H;
STEUER_B_L;
SENSE_C;
SENSE_RISING_INT;
break;
case 1:
STEUER_A_H;
STEUER_C_L;
SENSE_B;
SENSE_FALLING_INT;
break;
case 2:
STEUER_B_H;
STEUER_C_L;
SENSE_A;
SENSE_RISING_INT;
break;
case 3:
STEUER_B_H;
STEUER_A_L;
SENSE_C;
SENSE_FALLING_INT;
break;
case 4:
STEUER_C_H;
STEUER_A_L;
SENSE_B;
SENSE_RISING_INT;
break;
case 5:
STEUER_C_H;
STEUER_B_L;
SENSE_A;
SENSE_FALLING_INT;
break;
}
}
 
/branches/V0.37_neueStruktur/src/BLMC.h
0,0 → 1,98
/*############################################################################
############################################################################*/
 
#ifndef BLMC_H_
#define BLMC_H_
 
extern volatile unsigned char Phase;
extern volatile unsigned char ShadowTCCR1A;
extern volatile unsigned char CompInterruptFreigabe;
 
void Blc(void);
void Manuell(void);
 
// anselm
/*
#define COM1A ((0 << COM1A0) | (1 << COM1A1)) // COM1A-> OC1A non inverting mode
#define COM1B ((0 << COM1B0) | (1 << COM1B1)) // COM1B-> OC1B non inverting mode
#define COM2 ((0 << COM20) | (1 << COM21)) // COM2-> OC2 non inverting mode
 
#ifdef _32KHZ
#define WGM1 ((1 << WGM10) | (0 << WGM11)) // WGM10:13-> fast PWM 8bit
#define WGMCS2 ((1 << WGM20) | (1 << WGM21) | (1 << CS20)) // WGM20:21-> fast PWM, no prescale
#endif
 
#ifdef _16KHZ
#define WGM1 ((1 << WGM10) | (0 << WGM11)) // WGM10:13-> phase corr, PWM 8bit
#define WGMCS2 ((1 << WGM20) | (0 << WGM21) | (1 << CS20)) // WGM20:21-> phase corr. PWM, no prescale
#endif
 
#define PWM_C_ON {TCCR1A = COM1A | WGM1 | COM1B; TCCR2 = WGMCS2;
DDRB = 0x02;} // Steuer_C+ output
#define PWM_B_ON {TCCR1A = COM1B | WGM1 | COM1A; TCCR2 = WGMCS2; \
DDRB = 0x04;} // Steuer_B+ output
#define PWM_A_ON {TCCR1A = WGM1; TCCR2 = COM2 | WGMCS2; \
DDRB = 0x08;} // Steuer_A+ output
#define PWM_OFF {TCCR1A = WGM1; \
TCCR2 = WGMCS2; \
PORTB &= ~0x0E; DDRB = 0x0E;} // OC1x & OC2 disconnected, Steuer_X+ output low
// anselm
*/
 
#ifdef _32KHZ
#define PWM_C_ON {TCCR1A = 0xAD; TCCR2 = 0x49;DDRB = 0x0A;}
#define PWM_B_ON {TCCR1A = 0xAD; TCCR2 = 0x49;DDRB = 0x0C;}
#define PWM_A_ON {TCCR1A = 0xAD; TCCR2 = 0x69;DDRB = 0x08;}
#define PWM_OFF {TCCR1A = 0x0D; TCCR2 = 0x49;PORTC &= ~0x0E;}
#endif
 
#ifdef _16KHZ
// #define PWM_C_ON {TCCR1A = 0xA2; TCCR2 = 0x41; DDRB = 0x0A;}
// #define PWM_B_ON {TCCR1A = 0xA2; TCCR2 = 0x41; DDRB = 0x0C;}
// #define PWM_A_ON {TCCR1A = 0xA2; TCCR2 = 0x61; DDRB = 0x08;}
 
// #define PWM_C_ON {TCCR2 = 0x41; if(PPM_Betrieb) { TCCR1A = 0xA1;DDRB = 0x0A;} else { TCCR1A = 0x81; DDRB = 0x0E;}}
// #define PWM_B_ON {TCCR2 = 0x41; if(PPM_Betrieb) { TCCR1A = 0xA1;DDRB = 0x0C;} else { TCCR1A = 0x21; DDRB = 0x0E;}}
// #define PWM_A_ON {TCCR2 = 0x61; if(PPM_Betrieb) { TCCR1A = 0xA1;DDRB = 0x08;} else { TCCR1A = 0x01; DDRB = 0x0E;}}
 
#define PWM_C_ON {TCCR1A = 0xA1; TCCR2 = 0x61; DDRB = 0x02;}
#define PWM_B_ON {TCCR1A = 0xA1; TCCR2 = 0x61; DDRB = 0x04;}
#define PWM_A_ON {TCCR1A = 0xA1; TCCR2 = 0x61; DDRB = 0x08;}
 
 
// #define PWM_C_ON {TCCR1A = 0x82; TCCR2 = 0x41; PORTB &= ~0x04; DDRB = 0x0E;}
// #define PWM_B_ON {TCCR1A = 0x22; TCCR2 = 0x41; PORTB &= ~0x02; DDRB = 0x0E;}
// #define PWM_A_ON {TCCR1A = 0x02; TCCR2 = 0x61; PORTB &= ~0x06; DDRB = 0x0E;}
 
 
#define PWM_OFF {TCCR1A = 0x01; TCCR2 = 0x41; DDRB = 0x0E; PORTB &= ~0x0E;}
#endif
 
#define STEUER_A_H {PWM_A_ON}
#define STEUER_B_H {PWM_B_ON}
#define STEUER_C_H {PWM_C_ON}
 
#define STEUER_A_L {PORTD &= ~0x30; PORTD |= 0x08;}
#define STEUER_B_L {PORTD &= ~0x28; PORTD |= 0x10;}
#define STEUER_C_L {PORTD &= ~0x18; PORTD |= 0x20;}
#define STEUER_OFF {PORTD &= ~0x38; PWM_OFF; }
#define FETS_OFF {PORTD &= ~0x38; PORTB &= ~0x0E; }
 
#define SENSE_A ADMUX = 0;
#define SENSE_B ADMUX = 1;
#define SENSE_C ADMUX = 2;
 
#define ClrSENSE ACSR |= 0x10
#define SENSE ((ACSR & 0x10))
#define SENSE_L (!(ACSR & 0x20))
#define SENSE_H ((ACSR & 0x20))
#define ENABLE_SENSE_INT {CompInterruptFreigabe = 1;ACSR |= 0x0A; }
#define DISABLE_SENSE_INT {CompInterruptFreigabe = 0; ACSR &= ~0x08; }
 
 
#define SENSE_FALLING_INT ACSR &= ~0x01
#define SENSE_RISING_INT ACSR |= 0x03
#define SENSE_TOGGLE_INT ACSR &= ~0x03
 
#endif //BLMC_H_
 
/branches/V0.37_neueStruktur/src/PPM_Decode.c
0,0 → 1,76
/*############################################################################
+ Regler für Brushless-Motoren
+ ATMEGA8 mit 8MHz
+ (c) 01.2007 Holger Buss
+ Nur für den privaten Gebrauch
+ Keine Garantie auf Fehlerfreiheit
+ Kommerzielle Nutzung nur mit meiner Zustimmung
+ Der Code ist für die Hardware BL_Ctrl V1.0 entwickelt worden
+ www.mikrocontroller.com
############################################################################*/
#include "main.h"
volatile unsigned int PPM_Signal = 0;
volatile unsigned char Timer1Overflow = 0;
volatile unsigned char PPM_Timeout = 0, anz_ppm_werte = 0; // Ungültig, wenn Null
 
//############################################################################
//
void InitPPM(void)
//############################################################################
{
TCCR1B |= (1<<ICES1)|(1<<ICNC1);
ICP_POS_FLANKE;
ICP_INT_ENABLE;
TIMER1_INT_ENABLE;
}
 
//############################################################################
//
SIGNAL(SIG_OVERFLOW1)
//############################################################################
{
Timer1Overflow++;
}
 
//############################################################################
//
SIGNAL(SIG_INPUT_CAPTURE1)
//############################################################################
{
static unsigned int tim_alt;
static unsigned int ppm;
if(TCCR1B & (1<<ICES1)) // Positive Flanke
{
Timer1Overflow = 0;
tim_alt = ICR1;
ICP_NEG_FLANKE;
PPM_Timeout = 100;
}
else // Negative Flanke
{
ICP_POS_FLANKE;
#ifdef _32KHZ
ppm = (ICR1 - tim_alt + (int) Timer1Overflow * 256) / 32;
#endif
#ifdef _16KHZ
ppm = (ICR1 - tim_alt + (int) Timer1Overflow * 512) / 32;
#endif
if(ppm < 280) ppm = 280;
ppm -= 280;
if(PPM_Signal < ppm) PPM_Signal++;
else if(PPM_Signal > ppm) PPM_Signal--;
if(FILTER_PPM) ppm = (PPM_Signal * FILTER_PPM + ppm) / (FILTER_PPM + 1); // Filtern
PPM_Signal = ppm;
if(anz_ppm_werte < 255) anz_ppm_werte++;
ZeitZumAdWandeln = 1;
}
}
 
//############################################################################
//
SIGNAL(SIG_INTERRUPT0)
//############################################################################
{
CLR_INT0_FLAG; // IntFlag Loeschen
}
 
/branches/V0.37_neueStruktur/src/PPM_Decode.h
0,0 → 1,27
/*############################################################################
############################################################################*/
 
extern volatile unsigned int PPM_Signal;
extern volatile unsigned char PPM_Timeout, anz_ppm_werte;
void InitPPM(void);
 
 
#define INT0_ENABLE GIMSK |= 0x40
#define INT0_DISABLE GIMSK &= ~0x40
#define TIM0_START TIMSK |= 0x01
#define TIM0_STOPP TIMSK &= ~0x01
#define ICP_INT_ENABLE TIMSK |= 0x20
#define ICP_INT_DISABLE TIMSK &= ~0x20
#define TIMER1_INT_ENABLE TIMSK |= 0x04
#define TIMER1_INT_DISABLE TIMSK &= ~0x04
#define TIMER2_INT_ENABLE TIMSK |= 0x40
#define TIMER2_INT_DISABLE TIMSK &= ~0x40
#define INT0_POS_FLANKE MCUCR |= 0x01
#define INT0_ANY_FLANKE MCUCR |= 0x01
#define INT0_NEG_FLANKE MCUCR &= ~0x01
#define CLR_INT0_FLAG GIFR &= ~0x40
#define INIT_INT0_FLANKE MCUCR &= ~0x03; MCUCR |= 0x02;
#define TIMER0_PRESCALER TCCR0
#define ICP_POS_FLANKE TCCR1B |= (1<<ICES1)
#define ICP_NEG_FLANKE TCCR1B &= ~(1<<ICES1)
 
/branches/V0.37_neueStruktur/src/analog.c
0,0 → 1,76
/*############################################################################
 
############################################################################*/
 
#include "main.h"
 
//############################################################################
//Init ADC
void ADC_Init(void)
//############################################################################
{
ADCSRA = 0xA6; // Free Run & 1MHZ
ADMUX = 7; // Kanal 7
ADCSRA |= 0x40; // Start
}
 
//############################################################################
//Strom Analogwerte lesen
void AdConvert(void)
//############################################################################
{
unsigned int i=0;
unsigned char sense;
sense = ADMUX; // Sense-Kanal merken
ADMUX = 0x06; // Kanal 6
SFIOR = 0x00; // Analog Comperator aus
ADCSRA = 0xD3; // Converter ein, single
ADCSRA |= 0x10; // Ready löschen
ADMUX = 0x06; // Kanal 6
ADCSRA |= 0x40; // Start
while (((ADCSRA & 0x10) == 0));
ADMUX = sense; // zurück auf den Sense-Kanal
i = ADCW * 4;
// if(i > 300) i = 300;
Strom = (i + Strom * 7) / 8;
if (Strom_max < Strom) Strom_max = Strom;
ADCSRA = 0x00;
SFIOR = 0x08; // Analog Comperator ein
}
 
 
 
//############################################################################
//Strom Analogwerte lesen
unsigned int MessAD(unsigned char channel)
//############################################################################
{
unsigned char sense;
sense = ADMUX; // Sense-Kanal merken
ADMUX = channel; // Kanal 6
SFIOR = 0x00; // Analog Comperator aus
ADCSRA = 0xD3; // Converter ein, single
ADCSRA |= 0x10; // Ready löschen
ADMUX = channel; // Kanal 6
ADCSRA |= 0x40; // Start
while (((ADCSRA & 0x10) == 0));
ADMUX = sense; // zurück auf den Sense-Kanal
ADCSRA = 0x00;
SFIOR = 0x08; // Analog Comperator ein
return(ADCW);
}
 
//############################################################################
//Strom Analogwerte lesen
void FastADConvert(void)
//############################################################################
{
unsigned int i=0;
i = MessAD(6) * 4;
// i = ADCW * 4;
if(i > 200) i = 200;
Strom = i;//(i + Strom * 1) / 2;
if (Strom_max < Strom) Strom_max = Strom;
ADCSRA = 0x00;
SFIOR = 0x08; // Analog Comperator ein
}
/branches/V0.37_neueStruktur/src/analog.h
0,0 → 1,6
 
extern void ADC_Init(void);
extern void GetAnalogWerte(void);
extern void AdConvert(void);
extern void FastADConvert(void);
 
/branches/V0.37_neueStruktur/src/main.c
0,0 → 1,721
/*#######################################################################################
Flight Control
#######################################################################################*/
// ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
// + Regler für Brushless-Motoren
// + ATMEGA8 mit 8MHz
// + Nur für den privaten Gebrauch
// + Copyright (c) 12.2007 Holger Buss
// + www.MikroKopter.com
// ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
// + Es gilt für das gesamte Projekt (Hardware, Software, Binärfiles, Sourcecode und Dokumentation),
// + dass eine Nutzung (auch auszugsweise) nur für den privaten (nicht-kommerziellen) Gebrauch zulässig ist.
// + Sollten direkte oder indirekte kommerzielle Absichten verfolgt werden, ist mit uns (info@mikrokopter.de) Kontakt
// + bzgl. der Nutzungsbedingungen aufzunehmen.
// + Eine kommerzielle Nutzung ist z.B.Verkauf von MikroKoptern, Bestückung und Verkauf von Platinen oder Bausätzen,
// + Verkauf von Luftbildaufnahmen, usw.
// ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
// + Werden Teile des Quellcodes (mit oder ohne Modifikation) weiterverwendet oder veröffentlicht,
// + unterliegen sie auch diesen Nutzungsbedingungen und diese Nutzungsbedingungen incl. Copyright müssen dann beiliegen
// ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
// + Sollte die Software (auch auszugesweise) oder sonstige Informationen des MikroKopter-Projekts
// + auf anderen Webseiten oder sonstigen Medien veröffentlicht werden, muss unsere Webseite "http://www.mikrokopter.de"
// + eindeutig als Ursprung verlinkt werden
// ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
// + Keine Gewähr auf Fehlerfreiheit, Vollständigkeit oder Funktion
// + Benutzung auf eigene Gefahr
// + Wir übernehmen keinerlei Haftung für direkte oder indirekte Personen- oder Sachschäden
// ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
// + Die Portierung der Software (oder Teile davon) auf andere Systeme (ausser der Hardware von www.mikrokopter.de) ist nur
// + mit unserer Zustimmung zulässig
// ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
// + Die Funktion printf_P() unterliegt ihrer eigenen Lizenz und ist hiervon nicht betroffen
// ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
// + Redistributions of source code (with or without modifications) must retain the above copyright notice,
// + this list of conditions and the following disclaimer.
// + * Neither the name of the copyright holders nor the names of contributors may be used to endorse or promote products derived
// + from this software without specific prior written permission.
// + * The use of this project (hardware, software, binary files, sources and documentation) is only permittet
// + for non-commercial use (directly or indirectly)
// + Commercial use (for excample: selling of MikroKopters, selling of PCBs, assembly, ...) is only permitted
// + with our written permission
// + * If sources or documentations are redistributet on other webpages, out webpage (http://www.MikroKopter.de) must be
// + clearly linked as origin
// + * porting to systems other than hardware from www.mikrokopter.de is not allowed
// + THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
// + AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
// + IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
// + ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
// + LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
// + CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
// + SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
// + INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN// + CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
// + ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
// + POSSIBILITY OF SUCH DAMAGE.
// ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
 
#include "main.h"
 
unsigned int PWM = 0;
unsigned int Strom = 0,RuheStrom; //ca. in 0,1A
unsigned char Strom_max = 0;
unsigned char Mittelstrom = 0;
unsigned int Drehzahl = 0; // in 100UPM 60 = 6000
unsigned int KommutierDelay = 10;
unsigned int I2C_Timeout = 0;
unsigned int SIO_Timeout = 0;
unsigned int SollDrehzahl = 0;
unsigned int IstDrehzahl = 0;
unsigned int DrehZahlTabelle[256];//vorberechnete Werte zur Drehzahlerfassung
unsigned char ZeitFuerBerechnungen = 1;
unsigned char MotorAnwerfen = 0;
unsigned char MotorGestoppt = 1;
unsigned char MaxPWM = MAX_PWM;
unsigned int CntKommutierungen = 0;
unsigned int SIO_Drehzahl = 0;
unsigned char ZeitZumAdWandeln = 1;
unsigned char MotorAdresse = 1;
unsigned char PPM_Betrieb = 1;
 
//############################################################################
//
void SetPWM(void)
//############################################################################
{
unsigned char tmp_pwm;
tmp_pwm = PWM;
if(tmp_pwm > MaxPWM) // Strombegrenzung
{
tmp_pwm = MaxPWM;
PORTC |= ROT;
}
if(Strom > MAX_STROM) // Strombegrenzung
{
OCR1A = 0; OCR1B = 0; OCR2 = 0;
PORTC |= ROT;
Strom--;
}
else
{
#ifdef _32KHZ
OCR1A = tmp_pwm; OCR1B = tmp_pwm; OCR2 = tmp_pwm;
#endif
 
#ifdef _16KHZ
//OCR1A = 2 * (int)tmp_pwm; OCR1B = 2 * (int)tmp_pwm; OCR2 = tmp_pwm;
OCR1A = tmp_pwm; OCR1B = tmp_pwm; OCR2 = tmp_pwm;
#endif
}
}
 
//############################################################################
//
void PWM_Init(void)
//############################################################################
{
PWM_OFF;
TCCR1B = (1 << CS10) | (0 << CS11) | (0 << CS12) | (0 << WGM12) |
(0 << WGM13) | (0<< ICES1) | (0 << ICNC1);
/* TCCR1B = (1 << CS10) | (0 << CS11) | (0 << CS12) | (1 << WGM12) |
(0 << WGM13) | (0<< ICES1) | (0 << ICNC1);
*/
}
 
//############################################################################
//
void Wait(unsigned char dauer)
//############################################################################
{
dauer = (unsigned char)TCNT0 + dauer;
while((TCNT0 - dauer) & 0x80);
}
 
//############################################################################
//
void Anwerfen(unsigned char pwm)
//############################################################################
{
unsigned long timer = 300,i;
DISABLE_SENSE_INT;
PWM = 5;
SetPWM();
Manuell();
Delay_ms(200);
PWM = pwm;
while(1)
{
for(i=0;i<timer; i++)
{
if(!UebertragungAbgeschlossen) SendUart();
else DatenUebertragung();
Wait(100); // warten
}
timer-= timer/15+1;
if(timer < 25) { if(TEST_MANUELL) timer = 25; else return; }
 
Manuell();
Phase++;
Phase %= 6;
AdConvert();
PWM = pwm;
SetPWM();
if(SENSE)
{
PORTD ^= GRUEN;
}
}
}
 
/*
#define SENSE_A ADMUX = 0;
#define SENSE_B ADMUX = 1;
#define SENSE_C ADMUX = 2;
 
#define ClrSENSE ACSR |= 0x10
#define SENSE ((ACSR & 0x10))
#define SENSE_L (!(ACSR & 0x20))
#define SENSE_H ((ACSR & 0x20))
*/
 
void RotBlink(unsigned char anz)
{
sei(); // Interrupts ein
while(anz--)
{
PORTC |= ROT;
Delay_ms(300);
PORTC &= ~ROT;
Delay_ms(300);
}
Delay_ms(1000);
}
 
#define TEST_STROMGRENZE 120
unsigned char DelayM(unsigned int timer)
{
while(timer--)
{
FastADConvert();
if(Strom > (TEST_STROMGRENZE + RuheStrom))
{
FETS_OFF;
return(1);
}
}
return(0);
}
 
unsigned char Delay(unsigned int timer)
{
while(timer--)
{
// if(SENSE_H) { PORTC |= ROT; } else { PORTC &= ~ROT;}
}
return(0);
}
 
/*
void ShowSense(void)
{
if(SENSE_H) { PORTC |= ROT; } else { PORTC &= ~ROT;}
 
}
*/
#define HIGH_A_EIN PORTB |= 0x08
#define HIGH_B_EIN PORTB |= 0x04
#define HIGH_C_EIN PORTB |= 0x02
#define LOW_A_EIN PORTD |= 0x08
#define LOW_B_EIN PORTD |= 0x10
#define LOW_C_EIN PORTD |= 0x20
 
void MotorTon(void)
//############################################################################
{
unsigned char ADR_TAB[5] = {0,0,2,1,3};
unsigned int timer = 300,i;
unsigned int t = 0;
unsigned char anz = 0,MosfetOkay = 0, grenze = 50;
 
PORTC &= ~ROT;
Delay_ms(300 * ADR_TAB[MotorAdresse]);
DISABLE_SENSE_INT;
cli();//Globale Interrupts Ausschalten
uart_putchar('\n');
STEUER_OFF;
Strom_max = 0;
DelayM(50);
RuheStrom = Strom_max;
// uart_putchar(RuheStrom + 'A');
//+++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
//+ High-Mosfets auf Kurzschluss testen
//+++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
Strom = 0;
LOW_B_EIN;
HIGH_A_EIN;
if(DelayM(3))
{
anz = 1;
uart_putchar('1');
}
FETS_OFF;
Delay(1000);
Strom = 0;
LOW_A_EIN;
HIGH_B_EIN;
if(DelayM(3))
{
anz = 2;
uart_putchar('2');
}
FETS_OFF;
Delay(1000);
Strom = 0;
LOW_B_EIN; // Low C ein
HIGH_C_EIN; // High B ein
if(DelayM(3))
{
anz = 3;
uart_putchar('3');
}
FETS_OFF;
Delay(1000);
LOW_A_EIN; // Low A ein; und A gegen C
HIGH_C_EIN; // High C ein
if(DelayM(3))
{
anz = 3;
uart_putchar('7');
}
FETS_OFF;
DelayM(10000);
if(anz) while(1) RotBlink(anz); // bei Kurzschluss nicht starten
 
//+++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
//+ LOW-Mosfets auf Schalten und Kurzschluss testen
//+++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
if(UDR == ' ') {t = 65535; grenze = 40; uart_putchar('_');} else t = 1000; // Ausführlicher Test
Strom = 0;
for(i=0;i<t;i++)
{
LOW_A_EIN;
DelayM(1);
FETS_OFF;
Delay(5);
HIGH_A_EIN;
DelayM(1);
FETS_OFF;
if(Strom > grenze + RuheStrom) {anz = 4; uart_putchar('4'); break;}
Delay(5);
}
Delay(10000);
 
Strom = 0;
for(i=0;i<t;i++)
{
LOW_B_EIN;
DelayM(1);
FETS_OFF;
Delay(5);
HIGH_B_EIN;
DelayM(1);
FETS_OFF;
if(Strom > grenze + RuheStrom) {anz = 5; uart_putchar('5'); break;}
Delay(5);
}
 
Strom = 0;
Delay(10000);
 
for(i=0;i<t;i++)
{
LOW_C_EIN;
DelayM(1);
FETS_OFF;
Delay(5);
HIGH_C_EIN;
DelayM(1);
FETS_OFF;
if(Strom > grenze + RuheStrom) {anz = 6; uart_putchar('6'); break;}
Delay(5);
}
 
//+++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
//+ High-Mosfets auf Schalten testen
//+++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
SENSE_A;
FETS_OFF;
LOW_B_EIN; // Low B ein
LOW_C_EIN; // Low C ein
Strom = 0;
#define TONDAUER 40000
#define SOUND_E 2
#define SOUND1_A 300
#define SOUND2_A 330
#define SOUND3_A 360
 
for(i=0; i< (TONDAUER / SOUND2_A) ; i++)
{
HIGH_A_EIN; // Test A
Delay(SOUND_E);
if(MessAD(0) > 50) { MosfetOkay |= 0x01; } else { MosfetOkay &= ~0x01;};
PORTB = 0;
Delay(SOUND1_A);
}
FETS_OFF;
 
LOW_A_EIN; // Low A ein
LOW_C_EIN; // Low C ein
for(i=0; i<(TONDAUER / SOUND1_A); i++)
{
HIGH_B_EIN; // Test B
Delay(SOUND_E);
if(MessAD(1) > 50) { MosfetOkay |= 0x02; } else { MosfetOkay &= ~0x02;};
PORTB = 0;
Delay(SOUND1_A);
}
 
FETS_OFF;
LOW_A_EIN; // Low A ein
LOW_B_EIN; // Low B ein
for(i=0; i<(TONDAUER / SOUND3_A); i++)
{
HIGH_C_EIN; // Test C
Delay(SOUND_E);
if(MessAD(2) > 50) { MosfetOkay |= 0x04; } else { MosfetOkay &= ~0x04;};
PORTB = 0;
Delay(SOUND2_A);
}
FETS_OFF;
//+++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
//+ Low-Mosfets auf Schalten testen
//+++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
SENSE_B;
LOW_A_EIN; // Low A ein
for(i=0; i< (TONDAUER / SOUND2_A) ; i++)
{
HIGH_B_EIN; // Test B
Delay(SOUND_E);
if(MessAD(0) > 50) { MosfetOkay &= ~0x08;} else { MosfetOkay |= 0x08;};
PORTB = 0;
Delay(SOUND2_A);
}
 
//++++++++++++++++++++++++++++++++++++
LOW_C_EIN; // Low C ein
for(i=0; i<(TONDAUER / SOUND1_A); i++)
{
HIGH_B_EIN; // Test B
Delay(SOUND_E);
if(MessAD(2) > 50) { MosfetOkay &= ~0x20;} else { MosfetOkay |= 0x20;};
PORTB = 0;
Delay(SOUND3_A);
}
FETS_OFF;
//++++++++++++++++++++++++++++++++++++
FETS_OFF;
LOW_B_EIN; // Low B ein
for(i=0; i<(TONDAUER / SOUND3_A); i++)
{
HIGH_C_EIN; // Test C
Delay(SOUND_E);
if(MessAD(1) > 50) { MosfetOkay &= ~0x10;} else { MosfetOkay |= 0x10;};
PORTB = 0;
Delay(SOUND3_A);
}
FETS_OFF;
//++++++++++++++++++++++++++++++++++++
 
//+++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
sei();//Globale Interrupts Einschalten
// Delay_ms(250 * MotorAdresse);
/*
LOW_A_EIN; // Low B ein
#define SOUND8_A 650
for(i=0; i<(TONDAUER / SOUND8_A); i++)
{
HIGH_B_EIN; // Test B
Delay(SOUND_E);
PORTB = 0;
Delay(SOUND8_A);
}
*/
Delay_ms(300 * (4-ADR_TAB[MotorAdresse]));
if(!(MosfetOkay & 0x01)) { anz = 1; UDR='A'; } else
if(!(MosfetOkay & 0x02)) { anz = 2; UDR='B'; } else
if(!(MosfetOkay & 0x04)) { anz = 3; UDR='C'; } else
if(!(MosfetOkay & 0x08)) { anz = 4; UDR='a'; } else
if(!(MosfetOkay & 0x10)) { anz = 5; UDR='b'; } else
if(!(MosfetOkay & 0x20)) { anz = 6; UDR='c'; }
 
if(anz) Delay_ms(1000);
 
RotBlink(anz);
uart_putchar('.');
}
 
//############################################################################
//
unsigned char SollwertErmittlung(void)
//############################################################################
{
static unsigned int sollwert = 0;
unsigned int ppm;
if(!I2C_Timeout) // bei Erreichen von 0 ist der Wert ungültig
{
if(SIO_Timeout) // es gibt gültige SIO-Daten
{
sollwert = (MAX_PWM * (unsigned int) SIO_Sollwert) / 200; // skalieren auf 0-200 = 0-255
PPM_Betrieb = 0;
ICP_INT_DISABLE;
PORTC &= ~ROT;
}
else
if(anz_ppm_werte > 20) // es gibt gültige PPM-Daten
{
PPM_Betrieb = 1;
ppm = PPM_Signal;
if(ppm > 300) ppm = 0; // ungültiges Signal
if(ppm > 200) ppm = 200;
if(ppm <= MIN_PPM) sollwert = 0;
else
{
sollwert = (int) MIN_PWM + ((MAX_PWM - MIN_PWM) * (ppm - MIN_PPM)) / (190 - MIN_PPM);
}
PORTC &= ~ROT;
}
else // Kein gültiger Sollwert
{
if(!TEST_SCHUB) { if(sollwert) sollwert--; }
PORTC |= ROT;
}
}
else // I2C-Daten sind gültig
{
sollwert = I2C_RXBuffer;
PPM_Betrieb = 0;
PORTC &= ~ROT;
ICP_INT_DISABLE;
}
if(sollwert > MAX_PWM) sollwert = MAX_PWM;
return(sollwert);
}
 
void DebugAusgaben(void)
{
DebugOut.Analog[0] = Strom;
DebugOut.Analog[1] = Mittelstrom;
DebugOut.Analog[2] = SIO_Drehzahl;
DebugOut.Analog[3] = PPM_Signal;
}
 
 
//############################################################################
//Hauptprogramm
int main (void)
//############################################################################
{
char altPhase = 0;
int test = 0;
unsigned int MinUpmPulse,Blink,TestschubTimer;
unsigned int Blink2,MittelstromTimer,DrehzahlMessTimer,MotorGestopptTimer;
 
DDRC = 0x08;
PORTC = 0x08;
DDRD = 0xBA;
PORTD = 0x00;
DDRB = 0x0E;
PORTB = 0x31;
#if (MOTORADRESSE == 0)
PORTB |= (ADR1 + ADR2); // Pullups für Adresswahl
for(test=0;test<500;test++);
if (PINB & ADR1)
{
if (PINB & ADR2) MotorAdresse = 1;
else MotorAdresse = 2;
}
else
{
if (PINB & ADR2) MotorAdresse = 3;
else MotorAdresse = 4;
}
#else
MotorAdresse = MOTORADRESSE;
#endif
UART_Init();
Timer0_Init();
sei();//Globale Interrupts Einschalten
// Am Blinken erkennt man die richtige Motoradresse
/*
for(test=0;test<5;test++)
{
if(test == MotorAdresse) PORTD |= GRUEN;
Delay_ms(150);
PORTD &= ~GRUEN;
Delay_ms(250);
}
 
Delay_ms(500);
*/
// UART_Init(); // war doppelt
PWM_Init();
 
InitIC2_Slave(0x50);
InitPPM();
 
Blink = SetDelay(101);
Blink2 = SetDelay(102);
MinUpmPulse = SetDelay(103);
MittelstromTimer = SetDelay(254);
DrehzahlMessTimer = SetDelay(1005);
TestschubTimer = SetDelay(1006);
while(!CheckDelay(MinUpmPulse))
{
if(SollwertErmittlung()) break;
}
;
PORTD |= GRUEN;
PWM = 0;
 
SetPWM();
 
SFIOR = 0x08; // Analog Comperator ein
ADMUX = 1;
 
MinUpmPulse = SetDelay(10);
DebugOut.Analog[1] = 1;
PPM_Signal = 0;
 
if(!SollwertErmittlung()) MotorTon();
//MotorTon();
PORTB = 0x31; // Pullups wieder einschalten
 
// zum Test der Hardware; Motor dreht mit konstanter Drehzahl ohne Regelung
if(TEST_MANUELL) Anwerfen(TEST_MANUELL); // kommt von dort nicht wieder
 
while (1)
{
//ShowSense();
 
if(!TEST_SCHUB) PWM = SollwertErmittlung();
//I2C_TXBuffer = PWM; // Antwort über I2C-Bus
if(MANUELL_PWM) PWM = MANUELL_PWM;
 
// ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
if(Phase != altPhase) // es gab eine Kommutierung im Interrupt
{
MotorGestoppt = 0;
ZeitFuerBerechnungen = 0; // direkt nach einer Kommutierung ist Zeit
MinUpmPulse = SetDelay(250); // Timeout, falls ein Motor stehen bleibt
altPhase = Phase;
}
// ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
if(!PWM) // Sollwert == 0
{
MotorAnwerfen = 0; // kein Startversuch
ZeitFuerBerechnungen = 0;
// nach 1,5 Sekunden den Motor als gestoppt betrachten
if(CheckDelay(MotorGestopptTimer))
{
DISABLE_SENSE_INT;
MotorGestoppt = 1;
STEUER_OFF;
}
}
else
{
if(MotorGestoppt) MotorAnwerfen = 1; // Startversuch
MotorGestopptTimer = SetDelay(1500);
}
 
if(MotorGestoppt && !TEST_SCHUB) PWM = 0;
SetPWM();
// +++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
if(!ZeitFuerBerechnungen++)
{
if(MotorGestoppt) PORTD |= GRUEN; //else PORTD &= ~GRUEN;
if(SIO_DEBUG)
{
DebugAusgaben(); // welche Werte sollen angezeigt werden?
if(!UebertragungAbgeschlossen) SendUart();
else DatenUebertragung();
}
// Berechnen des Mittleren Stroms zur (langsamen) Strombegrenzung
if(CheckDelay(MittelstromTimer))
{
MittelstromTimer = SetDelay(50); // alle 50ms
if(Mittelstrom < Strom) Mittelstrom++;// Mittelwert des Stroms bilden
else if(Mittelstrom > Strom) Mittelstrom--;
if(Strom > MAX_STROM) MaxPWM -= MaxPWM / 32;
if((Mittelstrom > LIMIT_STROM))// Strom am Limit?
{
if(MaxPWM) MaxPWM--;// dann die Maximale PWM herunterfahren
PORTC |= ROT;
}
else
{
if(MaxPWM < MAX_PWM) MaxPWM++;
}
}
 
if(CheckDelay(DrehzahlMessTimer)) // Ist-Drehzahl bestimmen
{
DrehzahlMessTimer = SetDelay(10);
SIO_Drehzahl = CntKommutierungen;//(6 * CntKommutierungen) / (POLANZAHL / 2);
CntKommutierungen = 0;
if(PPM_Timeout == 0) // keine PPM-Signale
ZeitZumAdWandeln = 1;
}
 
if(TEST_SCHUB)
{
if(CheckDelay(TestschubTimer))
{
TestschubTimer = SetDelay(1500);
switch(test)
{
case 0: PWM = 50; test++; break;
case 1: PWM = 130; test++; break;
case 2: PWM = 60; test++; break;
case 3: PWM = 140; test++; break;
case 4: PWM = 150; test = 0; break;
default: test = 0;
}
}
}
// Motor Stehen geblieben
if((CheckDelay(MinUpmPulse) && SIO_Drehzahl == 0) || MotorAnwerfen)
{
MotorGestoppt = 1;
DISABLE_SENSE_INT;
MinUpmPulse = SetDelay(100);
if(MotorAnwerfen)
{
PORTC &= ~ROT;
MotorAnwerfen = 0;
Anwerfen(10);
PORTD |= GRUEN;
MotorGestoppt = 0;
Phase--;
PWM = 1;
SetPWM();
SENSE_TOGGLE_INT;
ENABLE_SENSE_INT;
MinUpmPulse = SetDelay(20);
while(!CheckDelay(MinUpmPulse)); // kurz Synchronisieren
PWM = 15;
SetPWM();
MinUpmPulse = SetDelay(300);
while(!CheckDelay(MinUpmPulse)); // kurz Durchstarten
// Drehzahlmessung wieder aufsetzen
DrehzahlMessTimer = SetDelay(50);
altPhase = 7;
}
}
} // ZeitFuerBerechnungen
} // while(1) - Hauptschleife
}
 
/branches/V0.37_neueStruktur/src/main.h
0,0 → 1,138
#ifndef _MAIN_H
#define _MAIN_H
 
#define MOTORADRESSE 0 // Adresse (1-4) 0 = Motoradresse über Lötjumper auf BL-Ctrl V1.1
 
#define MANUELL_PWM 0 // zur manuellen Vorgabe der PWM Werte: 0-255
#define TEST_MANUELL 0 // zum Testen der Hardware ohne Kommutierungsdetektion Werte: 0-255 (PWM)
#define TEST_SCHUB 0 // Erzeugt ein Schubmuster Werte: 0 = normal 1 = Test
#define POLANZAHL 12 // Anzahl der Pole (Magnete) Wird nur zur Drehzahlausgabe über Debug gebraucht
#define MAX_PWM 255
#define MIN_PWM 3
#define MIN_PPM 10 // ab hier (PPM-Signal) schaltet der Regler erst ein
#define FILTER_PPM 7 // wie stark soll das PPM-Signal gefiltert werden (Werte: 0-30)?
 
#define SIO_DEBUG 0 // Testwertausgaben auf der seriellen Schnittstelle
#define X3D_SIO 0 // serielles Protokoll des X3D (38400Bd) Achtung: dann muss SIO_DEBUG = 0 sein
 
 
#define _16KHZ // Schaltfrequenz -- die gewünschte einkommentieren
//#define _32KHZ // Schaltfrequenz -- die gewünschte einkommentieren
 
#define FDD6637_IRLR7843 1 // bessere MosFet bestückt? bewirkt höhere Stromgrenzen
 
#ifdef _16KHZ
#ifdef FDD6637_IRLR7843 // bessere Fets = mehr Strom zulassen
#define MAX_STROM 200 // ab ca. 20A PWM ausschalten
#define LIMIT_STROM 120 // ab ca. 12A PWM begrenzen
#else
#define MAX_STROM 130 // ab ca. 13A PWM ausschalten
#define LIMIT_STROM 65 // ab ca. 6,5A PWM begrenzen
#endif
#endif
 
#ifdef _32KHZ
#define MAX_STROM 130 // ab ca. 13A PWM ausschalten
#define LIMIT_STROM 50 // ab ca. 5,0A PWM begrenzen
#endif
 
#define SYSCLK 8000000L //Quarz Frequenz in Hz
 
 
//Robbe Roxxy 2824-34 mit Todd 10x4,5 bei 16kHz
//PWM Strom Schub
//10 0,18A 21g
//20 0,30A 38g
//30 0,40A 49g
//40 0,54A 60g
//50 0,70A 83g
//60 0,95A 102g
//70 1,25A 128g
//80 1,50A 151g
//90 1,83A 175g
//100 2,25A 206g
//110 2,66A 228g
//120 3,10A 257g
//130 3,55A 278g
//140 4,00A 305g
//150 4,50A 330g
//160 5,30A 355g
//170 5,85A 387g
//180 6,40A 400g
//190 7,10A 425g
//200 7,60A 460g
 
//0,5A 63g 14%
//1,0A 110g 24%
//1,5A 170g 32%
//2,0A 195g 37%
//2,5A 230g 41%
//3,0A 260g 46%
//3,5A 290g 50%
//4,0A 310g 53%
//4,5A 340g 58%
//5,0A 360g 63%
//5,5A 380g 67%
//6,0A 400g 68%
//6,5A 420g 70%
//7,0A 450g 75%
//7,5A 460g 78%
//8,0A 475g 82%
//9,0A 550g 86%
//11 A 600g 100%
 
 
#include <stdio.h>
#include <stdlib.h>
#include <string.h>
#include <avr/io.h>
#include <avr/pgmspace.h>
#include <avr/interrupt.h>
#include <avr/eeprom.h>
#include <avr/boot.h>
#include <avr/wdt.h>
 
#include "twislave.h"
#include "old_macros.h"
#include "analog.h"
#include "uart.h"
#include "timer0.h"
#include "BLMC.h"
 
#include "PPM_Decode.h"
 
extern unsigned int I2C_Timeout;
extern unsigned int SIO_Timeout;
extern unsigned int PWM;
extern unsigned int Strom; //ca. in 0,1A
extern unsigned char Strom_max;
extern unsigned char Mittelstrom;
extern unsigned int CntKommutierungen;
extern unsigned char MotorAnwerfen;
extern unsigned char MotorGestoppt;
extern unsigned char ZeitZumAdWandeln;
extern unsigned char MaxPWM;
extern unsigned char MotorAdresse;
extern unsigned char PPM_Betrieb;
 
#define ROT 0x08
#define GRUEN 0x80
 
#define ADR1 0x40 // für Motoradresswahl
#define ADR2 0x80 //
 
#if defined(__AVR_ATmega8__)
# define OC1 PB1
# define DDROC DDRB
# define OCR OCR1A
# define PWM10 WGM10
# define PWM11 WGM11
#endif
 
 
#endif //_MAIN_H
 
 
 
 
 
/branches/V0.37_neueStruktur/src/old_macros.h
0,0 → 1,47
/*
For backwards compatibility only.
Ingo Busker ingo@mikrocontroller.com
*/
 
#ifndef cbi
#define cbi(sfr, bit) (_SFR_BYTE(sfr) &= ~_BV(bit))
#endif
 
#ifndef sbi
#define sbi(sfr, bit) (_SFR_BYTE(sfr) |= _BV(bit))
#endif
 
#ifndef inb
#define inb(sfr) _SFR_BYTE(sfr)
#endif
 
#ifndef outb
#define outb(sfr, val) (_SFR_BYTE(sfr) = (val))
#endif
 
#ifndef inw
#define inw(sfr) _SFR_WORD(sfr)
#endif
 
#ifndef outw
#define outw(sfr, val) (_SFR_WORD(sfr) = (val))
#endif
 
#ifndef outp
#define outp(val, sfr) outb(sfr, val)
#endif
 
#ifndef inp
#define inp(sfr) inb(sfr)
#endif
 
#ifndef BV
#define BV(bit) _BV(bit)
#endif
 
 
#ifndef PRG_RDB
#define PRG_RDB pgm_read_byte
#endif
 
/branches/V0.37_neueStruktur/src/timer0.c
0,0 → 1,59
/*****************************************************************************
*****************************************************************************/
#include "main.h"
volatile unsigned int CountMilliseconds = 0;
volatile unsigned char Timer0Overflow;
enum {
STOP = 0,
CK = 1,
CK8 = 2,
CK64 = 3,
CK256 = 4,
CK1024 = 5,
T0_FALLING_EDGE = 6,
T0_RISING_EDGE = 7
};
 
 
SIGNAL(SIG_OVERFLOW0)
{
static unsigned char cnt;
Timer0Overflow++;
if(!cnt--)
{
cnt = 3;
CountMilliseconds += 1;
if(I2C_Timeout) I2C_Timeout--;
if(PPM_Timeout) PPM_Timeout--; else anz_ppm_werte = 0;
if(SIO_Timeout) SIO_Timeout--;
}
}
 
 
void Timer0_Init(void)
{
TCCR0 = TIMER_TEILER;
// TCNT0 = -TIMER_RELOAD_VALUE; // reload
TIM0_START;
TIMER2_INT_ENABLE;
}
 
 
unsigned int SetDelay(unsigned int t)
{
return(CountMilliseconds + t - 1);
}
 
char CheckDelay (unsigned int t)
{
return(((t - CountMilliseconds) & 0x8000) >> 8);
}
 
void Delay_ms(unsigned int w)
{
unsigned int akt;
akt = SetDelay(w);
while (!CheckDelay(akt));
}
/branches/V0.37_neueStruktur/src/timer0.h
0,0 → 1,15
#if defined (__AVR_ATmega8__)
#define TIMER_TEILER CK8
//#define TIMER_RELOAD_VALUE 125
#endif
 
 
extern volatile unsigned int CountMilliseconds;
extern volatile unsigned char Timer0Overflow;
 
 
void Timer1_Init(void);
void Delay_ms(unsigned int);
unsigned int SetDelay (unsigned int t);
char CheckDelay (unsigned int t);
 
/branches/V0.37_neueStruktur/src/twislave.c
0,0 → 1,75
/*############################################################################
Slaveadr = 0x52 = Vorne, 0x54 = Hinten, 0x56 = Rechts, 0x58 = Links
############################################################################*/
 
#include <avr/io.h>
#include <util/twi.h>
#include "main.h"
 
unsigned char I2C_RXBuffer;
unsigned char Byte_Counter=0;
 
//############################################################################
//I2C (TWI) Interface Init
void InitIC2_Slave(uint8_t adr)
//############################################################################
{
TWAR = adr + (2*MotorAdresse); // Eigene Adresse setzen
TWCR = (1<<TWINT) | (1<<TWEN) | (1<<TWIE) | (1<<TWEA);
}
 
//############################################################################
//ISR, die bei einem Ereignis auf dem Bus ausgelöst wird. Im Register TWSR befindet
//sich dann ein Statuscode, anhand dessen die Situation festgestellt werden kann.
ISR (TWI_vect)
//############################################################################
{
switch (TWSR & 0xF8)
{
case SR_SLA_ACK:
TWCR |= (1<<TWINT);
Byte_Counter=0;
return;
// Daten Empfangen
case SR_PREV_ACK:
I2C_RXBuffer = TWDR;
I2C_Timeout = 500;
TWCR |= (1<<TWINT);
return;
// Daten Senden
case SW_SLA_ACK:
if (Byte_Counter==0)
{
TWDR = Mittelstrom;
Byte_Counter++;
}
else
{
TWDR = MaxPWM;
}
TWCR |= (1<<TWINT);
return;
// Daten Senden
case SW_DATA_ACK:
if (Byte_Counter==0)
{
TWDR = Mittelstrom;
Byte_Counter++;
}
else
{
TWDR = MaxPWM;
}
TWCR |= (1<<TWINT);
return;
// Bus-Fehler zurücksetzen
case TWI_BUS_ERR_2:
TWCR |=(1<<TWSTO) | (1<<TWINT);
// Bus-Fehler zurücksetzen
case TWI_BUS_ERR_1:
TWCR |=(1<<TWSTO) | (1<<TWINT);
}
TWCR =(1<<TWEA) | (1<<TWINT) | (1<<TWEN) | (1<<TWIE); // TWI Reset
}
 
 
/branches/V0.37_neueStruktur/src/twislave.h
0,0 → 1,32
#ifndef _TWI_SLAVE_H_
#define _TWI_SLAVE_H_
 
extern unsigned char I2C_RXBuffer;
extern unsigned char Byte_Counter;
 
extern void InitIC2_Slave (uint8_t adr);
 
#define TWI_BUS_ERR_1 0x00
#define TWI_BUS_ERR_2 0xF8
 
// Status Slave RX Mode
#define SR_SLA_ACK 0x60
#define SR_LOST_ACK 0x68
#define SR_GEN_CALL_ACK 0x70
#define GEN_LOST_ACK 0x78
#define SR_PREV_ACK 0x80
#define SR_PREV_NACK 0x88
#define GEN_PREV_ACK 0x90
#define GEN_PREV_NACK 0x98
#define STOP_CONDITION 0xA0
#define REPEATED_START 0xA0
 
// Status Slave TX mode
#define SW_SLA_ACK 0xA8
#define SW_LOST_ACK 0xB0
#define SW_DATA_ACK 0xB8
#define SW_DATA_NACK 0xC0
#define SW_LAST_ACK 0xC8
 
#endif
 
/branches/V0.37_neueStruktur/src/uart.c
0,0 → 1,277
// ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
// + Regler für Brushless-Motoren
// + ATMEGA8 mit 8MHz
// + (c) 01.2007 Holger Buss
// + Nur für den privaten Gebrauch
// + Keine Garantie auf Fehlerfreiheit
// + Kommerzielle Nutzung nur mit meiner Zustimmung
// + Der Code ist für die Hardware BL_Ctrl V1.0 entwickelt worden
// + www.mikrocontroller.com
// ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
 
#include "main.h"
#include "uart.h"
 
#define MAX_SENDE_BUFF 100
#define MAX_EMPFANGS_BUFF 100
 
unsigned volatile char SIO_Sollwert = 0;
unsigned volatile char SioTmp = 0;
unsigned volatile char SendeBuffer[MAX_SENDE_BUFF];
unsigned volatile char RxdBuffer[MAX_EMPFANGS_BUFF];
unsigned volatile char NeuerDatensatzEmpfangen = 0;
unsigned volatile char UebertragungAbgeschlossen = 1;
unsigned char MeineSlaveAdresse;
unsigned char MotorTest[4] = {0,0,0,0};
unsigned volatile char AnzahlEmpfangsBytes = 0;
 
struct str_DebugOut DebugOut;
 
 
int Debug_Timer;
 
 
SIGNAL(INT_VEC_TX)
{
}
 
void SendUart(void)
{
static unsigned int ptr = 0;
unsigned char tmp_tx;
if(!(UCSRA & 0x40)) return;
if(!UebertragungAbgeschlossen)
{
ptr++; // die [0] wurde schon gesendet
tmp_tx = SendeBuffer[ptr];
if((tmp_tx == '\r') || (ptr == MAX_SENDE_BUFF))
{
ptr = 0;
UebertragungAbgeschlossen = 1;
}
USR |= (1<TXC);
UDR = tmp_tx;
}
else ptr = 0;
}
 
// --------------------------------------------------------------------------
void Decode64(unsigned char *ptrOut, unsigned char len, unsigned char ptrIn,unsigned char max) // Wohin mit den Daten; Wie lang; Wo im RxdBuffer
{
unsigned char a,b,c,d;
unsigned char ptr = 0;
unsigned char x,y,z;
while(len)
{
a = RxdBuffer[ptrIn++] - '=';
b = RxdBuffer[ptrIn++] - '=';
c = RxdBuffer[ptrIn++] - '=';
d = RxdBuffer[ptrIn++] - '=';
if(ptrIn > max - 2) break; // nicht mehr Daten verarbeiten, als empfangen wurden
 
x = (a << 2) | (b >> 4);
y = ((b & 0x0f) << 4) | (c >> 2);
z = ((c & 0x03) << 6) | d;
 
if(len--) ptrOut[ptr++] = x; else break;
if(len--) ptrOut[ptr++] = y; else break;
if(len--) ptrOut[ptr++] = z; else break;
}
 
}
 
 
//+++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
//++ Empfangs-Part der Datenübertragung
//+++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
SIGNAL(INT_VEC_RX)
{
#if X3D_SIO == 1
static unsigned char serPacketCounter = 100;
SioTmp = UDR;
if(SioTmp == 0xF5) // Startzeichen
{
serPacketCounter = 0;
}
else
{
if(++serPacketCounter == MotorAdresse) // (1-4)
{
SIO_Sollwert = SioTmp;
SIO_Timeout = 200; // werte für 200ms gültig
}
else
{
if(serPacketCounter > 100) serPacketCounter = 100;
}
}
#else
static unsigned int crc;
static unsigned char crc1,crc2,buf_ptr;
static unsigned char UartState = 0;
unsigned char CrcOkay = 0;
SioTmp = UDR;
if(buf_ptr >= MAX_EMPFANGS_BUFF) UartState = 0;
if(SioTmp == '\r' && UartState == 2)
{
UartState = 0;
crc -= RxdBuffer[buf_ptr-2];
crc -= RxdBuffer[buf_ptr-1];
crc %= 4096;
crc1 = '=' + crc / 64;
crc2 = '=' + crc % 64;
CrcOkay = 0;
if((crc1 == RxdBuffer[buf_ptr-2]) && (crc2 == RxdBuffer[buf_ptr-1])) CrcOkay = 1; else { CrcOkay = 0; };
if(CrcOkay) // Datensatz schon verarbeitet
{
//NeuerDatensatzEmpfangen = 1;
AnzahlEmpfangsBytes = buf_ptr;
RxdBuffer[buf_ptr] = '\r';
if(/*(RxdBuffer[1] == MeineSlaveAdresse || (RxdBuffer[1] == 'a')) && */(RxdBuffer[2] == 'R')) wdt_enable(WDTO_250MS); // Reset-Commando
uart_putchar(RxdBuffer[2]);
if (RxdBuffer[2] == 't') // Motortest
{ Decode64((unsigned char *) &MotorTest[0],sizeof(MotorTest),3,AnzahlEmpfangsBytes);
SIO_Sollwert = MotorTest[MotorAdresse - 1];
SIO_Timeout = 500; // werte für 500ms gültig
}
}
}
else
switch(UartState)
{
case 0:
if(SioTmp == '#' && !NeuerDatensatzEmpfangen) UartState = 1; // Startzeichen und Daten schon verarbeitet
buf_ptr = 0;
RxdBuffer[buf_ptr++] = SioTmp;
crc = SioTmp;
break;
case 1: // Adresse auswerten
UartState++;
RxdBuffer[buf_ptr++] = SioTmp;
crc += SioTmp;
break;
case 2: // Eingangsdaten sammeln
RxdBuffer[buf_ptr] = SioTmp;
if(buf_ptr < MAX_EMPFANGS_BUFF) buf_ptr++;
else UartState = 0;
crc += SioTmp;
break;
default:
UartState = 0;
break;
}
 
#endif
};
 
 
// --------------------------------------------------------------------------
void AddCRC(unsigned int wieviele)
{
unsigned int tmpCRC = 0,i;
for(i = 0; i < wieviele;i++)
{
tmpCRC += SendeBuffer[i];
}
tmpCRC %= 4096;
SendeBuffer[i++] = '=' + tmpCRC / 64;
SendeBuffer[i++] = '=' + tmpCRC % 64;
SendeBuffer[i++] = '\r';
UebertragungAbgeschlossen = 0;
UDR = SendeBuffer[0];
}
 
 
// --------------------------------------------------------------------------
void SendOutData(unsigned char cmd,unsigned char modul, unsigned char *snd, unsigned char len)
{
unsigned int pt = 0;
unsigned char a,b,c;
unsigned char ptr = 0;
 
SendeBuffer[pt++] = '#'; // Startzeichen
SendeBuffer[pt++] = modul; // Adresse (a=0; b=1,...)
SendeBuffer[pt++] = cmd; // Commando
 
while(len)
{
if(len) { a = snd[ptr++]; len--;} else a = 0;
if(len) { b = snd[ptr++]; len--;} else b = 0;
if(len) { c = snd[ptr++]; len--;} else c = 0;
SendeBuffer[pt++] = '=' + (a >> 2);
SendeBuffer[pt++] = '=' + (((a & 0x03) << 4) | ((b & 0xf0) >> 4));
SendeBuffer[pt++] = '=' + (((b & 0x0f) << 2) | ((c & 0xc0) >> 6));
SendeBuffer[pt++] = '=' + ( c & 0x3f);
}
AddCRC(pt);
}
 
 
 
//############################################################################
//Routine für die Serielle Ausgabe
int uart_putchar (char c)
//############################################################################
{
if (c == '\n')
uart_putchar('\r');
//Warten solange bis Zeichen gesendet wurde
loop_until_bit_is_set(USR, UDRE);
//Ausgabe des Zeichens
UDR = c;
return (0);
}
 
// --------------------------------------------------------------------------
void WriteProgramData(unsigned int pos, unsigned char wert)
{
}
 
//############################################################################
//INstallation der Seriellen Schnittstelle
void UART_Init (void)
//############################################################################
{
//Enable TXEN im Register UCR TX-Data Enable & RX Enable
 
UCR=(1 << TXEN) | (1 << RXEN);
// UART Double Speed (U2X)
USR |= (1<<U2X);
// RX-Interrupt Freigabe
 
UCSRB |= (1<<RXCIE); // serieller Empfangsinterrupt
 
// TX-Interrupt Freigabe
// UCSRB |= (1<<TXCIE);
 
//Teiler wird gesetzt
UBRR= (SYSCLK / (BAUD_RATE * 8L) -1 );
//öffnet einen Kanal für printf (STDOUT)
fdevopen (uart_putchar, NULL);
Debug_Timer = SetDelay(200);
// Version beim Start ausgeben (nicht schön, aber geht... )
uart_putchar ('\n');uart_putchar ('B');uart_putchar ('L');uart_putchar (':');
uart_putchar ('V');uart_putchar (0x30 + VERSION_HAUPTVERSION);uart_putchar ('.');uart_putchar (0x30 + VERSION_NEBENVERSION/10); uart_putchar (0x30 + VERSION_NEBENVERSION%10);
uart_putchar ('\n');uart_putchar ('A');uart_putchar ('D');uart_putchar ('R'); uart_putchar (':'); uart_putchar (0x30 + MotorAdresse);
 
}
 
 
 
 
//---------------------------------------------------------------------------------------------
void DatenUebertragung(void)
{
if((CheckDelay(Debug_Timer) && UebertragungAbgeschlossen)) // im Singlestep-Betrieb in jedem Schtitt senden
{
SendOutData('D',MeineSlaveAdresse,(unsigned char *) &DebugOut,sizeof(DebugOut));
Debug_Timer = SetDelay(50); // Sendeintervall
}
}
/branches/V0.37_neueStruktur/src/uart.h
0,0 → 1,82
#ifndef _UART_H
#define _UART_H
 
extern unsigned volatile char SIO_Sollwert;
extern unsigned volatile char UebertragungAbgeschlossen;
extern unsigned volatile char PC_DebugTimeout;
extern unsigned char MeineSlaveAdresse;
extern int Debug_Timer;
extern void UART_Init (void);
extern int uart_putchar (char c);
extern void boot_program_page (uint32_t page, uint8_t *buf);
extern void SendUart(void);
extern void DatenUebertragung(void);
 
struct str_DebugOut
{
unsigned char Digital[13];
unsigned int AnzahlZyklen;
unsigned int Zeit;
unsigned char Sekunden;
unsigned int Analog[8]; // Debugwerte
};
 
extern struct str_DebugOut DebugOut;
//Die Baud_Rate der Seriellen Schnittstelle
//#define BAUD_RATE 9600 //Baud Rate für die Serielle Schnittstelle
//#define BAUD_RATE 14400 //Baud Rate für die Serielle Schnittstelle
//#define BAUD_RATE 28800 //Baud Rate für die Serielle Schnittstelle
 
#if X3D_SIO == 1
#define BAUD_RATE 38400 //Baud Rate für die Serielle Schnittstelle
#else
#define BAUD_RATE 57600 //Baud Rate für die Serielle Schnittstelle
#endif
 
//Anpassen der seriellen Schnittstellen Register wenn ein ATMega128 benutzt wird
#if defined (__AVR_ATmega128__)
# define USR UCSR0A
# define UCR UCSR0B
# define UDR UDR0
# define UBRR UBRR0L
# define EICR EICRB
#endif
 
#if defined (__AVR_ATmega8__)
# define USR UCSRA
# define UCR UCSRB
# define UBRR UBRRL
# define EICR EICRB
# define INT_VEC_RX SIG_UART_RECV
# define INT_VEC_TX SIG_UART_TRANS
#endif
 
 
#if defined (__AVR_ATmega32__)
# define USR UCSRA
# define UCR UCSRB
# define UBRR UBRRL
# define EICR EICRB
# define INT_VEC_RX SIG_UART_RECV
# define INT_VEC_TX SIG_UART_TRANS
#endif
 
#if defined (__AVR_ATmega644__)
# define USR UCSR0A
# define UCR UCSR0B
# define UDR UDR0
# define UBRR UBRR0L
# define EICR EICR0B
# define TXEN TXEN0
# define RXEN RXEN0
# define RXCIE RXCIE0
# define TXCIE TXCIE0
# define U2X U2X0
# define UCSRB UCSR0B
# define UDRE UDRE0
# define INT_VEC_RX SIG_USART_RECV
# define INT_VEC_TX SIG_USART_TRANS
#endif
 
 
#endif //_UART_H