Code:
	/*
    Eine 8-kanalige PWM mit intelligentem Lösungsansatz
 
    ATmega16 @ 16 MHz
 
*/
 
 
#define BAUD 56000UL
#define UBRR_VAL ((F_CPU+BAUD*8)/(BAUD*16)-1)
// Defines an den Controller und die Anwendung anpassen
 
#define F_CPU         16000000L           // Systemtakt in Hz
#define F_PWM         500L               // PWM-Frequenz in Hz
#define PWM_PRESCALER 8                  // Vorteiler für den Timer
#define PWM_STEPS     256                // PWM-Schritte pro Zyklus(1..256)
#define PWM_PORT      PORTD             // Port für PWM
#define PWM_DDR       DDRD               // Datenrichtungsregister für PWM
#define PWM_PORT_2    PORTC             // Port für PWM
#define PWM_DDR_2     DDRC               // Datenrichtungsregister für PWM
#define PWM_PORT_3    PORTA             // Port für PWM
#define PWM_DDR_3    DDRA               // Datenrichtungsregister für PWM
#define PWM_CHANNELS  20               // Anzahl der PWM-Kanäle
 
// ab hier nichts ändern, wird alles berechnet
 
#define T_PWM (F_CPU/(PWM_PRESCALER*F_PWM*PWM_STEPS)) // Systemtakte pro PWM-Takt
//#define T_PWM 1   //TEST
 
#if ((T_PWM*PWM_PRESCALER)<(111+5))
    #error T_PWM zu klein, F_CPU muss vergrössert werden oder F_PWM oder PWM_STEPS verkleinert werden
#endif
 
#if ((T_PWM*PWM_STEPS)>65535)
    #error Periodendauer der PWM zu gross! F_PWM oder PWM_PRESCALER erhöhen.   
#endif
// includes
 
#include <avr/io.h>
#include <avr/interrupt.h>
#include <util/delay.h>
#include <stdlib.h>
#include <string.h>
#include <stdint.h>
 
// globale Variablen
 
uint32_t pwm_timing[PWM_CHANNELS+1];          // Zeitdifferenzen der PWM Werte
uint32_t pwm_timing_tmp[PWM_CHANNELS+1];      
 
uint32_t  pwm_mask[PWM_CHANNELS+1];            // Bitmaske für PWM Bits, welche gelöscht werden sollen
uint32_t  pwm_mask_tmp[PWM_CHANNELS+1];        // ändern uint16_t oder uint32_t für mehr Kanäle
 
uint8_t  pwm_setting[PWM_CHANNELS];           // Einstellungen für die einzelnen PWM-Kanäle
uint8_t  pwm_setting_tmp[PWM_CHANNELS+1];     // Einstellungen der PWM Werte, sortiert
                                              // ändern auf uint16_t für mehr als 8 Bit Auflösung  
 
volatile uint8_t pwm_cnt_max=1;               // Zählergrenze, Initialisierung mit 1 ist wichtig!
volatile uint8_t pwm_sync;                    // Update jetzt möglich
 
 
char s[4];
char buffer[10];
volatile uint8_t uart_str_count=0;
volatile uint8_t servo=0;
volatile uint8_t uart_str_complete = 0;
// Pointer für wechselseitigen Datenzugriff
 
uint32_t *isr_ptr_time  = pwm_timing;
uint32_t *main_ptr_time = pwm_timing_tmp;
 
uint32_t *isr_ptr_mask  = pwm_mask;              // Bitmasken fuer PWM-Kanäle
uint32_t *main_ptr_mask = pwm_mask_tmp;          // ändern uint16_t oder uint32_t für mehr Kanäle
 
// Zeiger austauschen
// das muss in einem Unterprogramm erfolgen,
// um eine Zwischenspeicherung durch den Compiler zu verhindern
void geradeausGehen(uint8_t * pos,uint8_t tempo);
void aufAb(uint8_t *pos,uint8_t tempo);
void tausche_zeiger(void) {
    uint32_t *tmp_ptr16;
    uint32_t *tmp_ptr8;                          // ändern uint16_t oder uint32_t für mehr Kanäle
 
    tmp_ptr16 = isr_ptr_time;
    isr_ptr_time = main_ptr_time;
    main_ptr_time = tmp_ptr16;
    tmp_ptr8 = isr_ptr_mask;
    isr_ptr_mask = main_ptr_mask;
    main_ptr_mask = tmp_ptr8;
}
 
// PWM Update, berechnet aus den PWM Einstellungen
// die neuen Werte für die Interruptroutine
 
void pwm_update(void) {
    
    uint8_t i, j, k;
    uint32_t m1, m2, tmp_mask;                   // ändern uint16_t oder uint32_t für mehr Kanäle    
    uint8_t min, tmp_set;                       // ändern auf uint16_t für mehr als 8 Bit Auflösung
 
    // PWM Maske für Start berechnen
    // gleichzeitig die Bitmasken generieren und PWM Werte kopieren
 
    m1 = 1;
    m2 = 0;
    for(i=1; i<=(PWM_CHANNELS); i++) {
        main_ptr_mask[i]=~m1;                       // Maske zum Löschen der PWM Ausgänge
        pwm_setting_tmp[i] = pwm_setting[i-1];
        if (pwm_setting_tmp[i]!=0) m2 |= m1;        // Maske zum setzen der IOs am PWM Start
        m1 <<= 1;
    }
    main_ptr_mask[0]=m2;                            // PWM Start Daten 
 
    // PWM settings sortieren; Einfügesortieren
 
    for(i=1; i<=PWM_CHANNELS; i++) {
        min=PWM_STEPS-1;
        k=i;
        for(j=i; j<=PWM_CHANNELS; j++) {
            if (pwm_setting_tmp[j]<min) {
                k=j;                                // Index und PWM-setting merken
                min = pwm_setting_tmp[j];
            }
        }
        if (k!=i) {
            // ermitteltes Minimum mit aktueller Sortiertstelle tauschen
            tmp_set = pwm_setting_tmp[k];
            pwm_setting_tmp[k] = pwm_setting_tmp[i];
            pwm_setting_tmp[i] = tmp_set;
            tmp_mask = main_ptr_mask[k];
            main_ptr_mask[k] = main_ptr_mask[i];
            main_ptr_mask[i] = tmp_mask;
        }
    }
 
    // Gleiche PWM-Werte vereinigen, ebenso den PWM-Wert 0 löschen falls vorhanden
 
    k=PWM_CHANNELS;             // PWM_CHANNELS Datensätze
    i=1;                        // Startindex
 
    while(k>i) {
        while ( ((pwm_setting_tmp[i]==pwm_setting_tmp[i+1]) || (pwm_setting_tmp[i]==0))  && (k>i) ) {
 
            // aufeinanderfolgende Werte sind gleich und können vereinigt werden
            // oder PWM Wert ist Null
            if (pwm_setting_tmp[i]!=0)
                main_ptr_mask[i+1] &= main_ptr_mask[i];        // Masken vereinigen
 
            // Datensatz entfernen,
            // Nachfolger alle eine Stufe hochschieben
            for(j=i; j<k; j++) {
                pwm_setting_tmp[j] = pwm_setting_tmp[j+1];
                main_ptr_mask[j] = main_ptr_mask[j+1];
            }
            k--;
        }
        i++;
    }
    
    // letzten Datensatz extra behandeln
    // Vergleich mit dem Nachfolger nicht möglich, nur löschen
    // gilt nur im Sonderfall, wenn alle Kanäle 0 sind
    if (pwm_setting_tmp[i]==0) k--;
 
    // Zeitdifferenzen berechnen
    
    if (k==0) { // Sonderfall, wenn alle Kanäle 0 sind
        main_ptr_time[0]=(uint16_t)T_PWM*PWM_STEPS/2;
        main_ptr_time[1]=(uint16_t)T_PWM*PWM_STEPS/2;
        k=1;
    }
    else {
        i=k;
        main_ptr_time[i]=(uint16_t)T_PWM*(PWM_STEPS-pwm_setting_tmp[i]);
        tmp_set=pwm_setting_tmp[i];
        i--;
        for (; i>0; i--) {
            main_ptr_time[i]=(uint16_t)T_PWM*(tmp_set-pwm_setting_tmp[i]);
            tmp_set=pwm_setting_tmp[i];
        }
        main_ptr_time[0]=1000+(uint16_t)T_PWM*tmp_set;
    }
 
    // auf Sync warten
 
    pwm_sync=0;             // Sync wird im Interrupt gesetzt
    while(pwm_sync==0);
 
    // Zeiger tauschen
    cli();
    tausche_zeiger();
    pwm_cnt_max = k;
    sei();
}
 
// Timer 1 Output COMPARE A Interrupt
 
ISR(TIMER1_COMPA_vect) {
    static uint32_t pwm_cnt;                     // ändern auf uint16_t für mehr als 8 Bit Auflösung
    uint32_t tmp;                                // ändern uint16_t oder uint32_t für mehr Kanäle
 
    OCR1A += isr_ptr_time[pwm_cnt];
    tmp    = isr_ptr_mask[pwm_cnt];
    
    if (pwm_cnt == 0) {
        PWM_PORT = tmp;                         // Ports setzen zu Begin der PWM
		PWM_PORT_2 = tmp>>8;   					// zusätzliche PWM-Ports hier setzen
		PWM_PORT_3 = tmp>>16;
        pwm_cnt++;
    }
    else {
        PWM_PORT &= tmp;                        // Ports löschen
		PWM_PORT_2 &= tmp>>8;                                       // zusätzliche PWM-Ports hier setzen
        PWM_PORT_3 &= tmp>>16;
		if (pwm_cnt == pwm_cnt_max) {
           
			OCR1A+=36000;
			pwm_sync = 1;                       // Update jetzt möglich
            pwm_cnt  = 0;
			
        }
        else pwm_cnt++;
    }
}
void uart_init(void)   
{
   UBRRH = UBRR_VAL>>8;
   UBRRL = UBRR_VAL;
   /* evtl. verkuerzt falls Register aufeinanderfolgen (vgl. Datenblatt)
      UBRR = UBRR_VALUE;
   */
 UCSRB = (1 << RXEN) | (1 << TXEN) |(1<<RXCIE);
 UCSRC = (1 << URSEL) | (1 << UCSZ1) | (1 << UCSZ0);
}
void adc_init(void){
	ADCSRA = (1<<ADEN) | (1<<ADPS2) | (1<<ADPS1);
	ADMUX=0 | (0<<REFS1) | (1<<REFS0);
}
int uart_putc(unsigned char c)
{
    while (!(UCSRA & (1<<UDRE)))  /* warten bis Senden moeglich */
    {
    }                             
 
    UDR = c;                      /* sende Zeichen */
    return 0;
}
uint8_t uart_getc(void)
{
    while (!(UCSRA & (1<<RXC)))   // warten bis Zeichen verfuegbar
        ;
    return UDR;                   // Zeichen aus UDR an Aufrufer zurueckgeben
}
void uart_puts (char *st)
{
    while (*st)
    {   /* so lange *s != '\0' also ungleich dem "String-Endezeichen(Terminator)" */
        uart_putc(*st);
        st++;
    }
	//uart_putc(' ');
}
int main(void) {
 
 
	//uart_init();
	//adc_init();
    // PWM Port einstellen
    
    PWM_DDR = 0xFF;         // Port als Ausgang
    // zusätzliche PWM-Ports hier setzen
	PWM_DDR_2=0xFF;
	PWM_DDR_3=0xFF;
    
    // Timer 1 OCRA1, als variablen Timer nutzen
 
    TCCR1B = 2;             // Timer läuft mit Prescaler 8
    TIMSK |= (1<<OCIE1A);   // Interrupt freischalten
 
    sei();                  // Interrupts global einschalten
 
 
/******************************************************************/
// nur zum testen, in der Anwendung entfernen
// Test values
volatile uint8_t tmp;
// Bein 1
// 2 mitte bein 80 -200		links 
// 3 mitte fuß 50 -130  	links
// 4 hinten gelenk 70 - 120	links
// Bein 2
// 5 hinten fuß 50 -130		links
// 6 hinten bein 200 -80	links
// 7 mitte gelenk 70 -120	links
// Bein 3
// 8 vorne bein 80 -200		links
// 9 vorne fuß 50 -130		links
// 10 vorne gelenk 70 - 120	links
// Bein 4
// 11
// 12
// 13
// Bein 5
// 14
// 15
// 16
// Bein 6
// 17
// 18
// 19
//                      0    1    /2   3    4 /  5   6    7 / 8   9  10  /11  12 13 /14  15 16 /17 18  19
const uint8_t t1[20]={100, 100,  30, 80, 140, 90, 30, 120,30,  90,120,230,180,120,230,180,120,180,230,130};
const uint8_t t2[20]={60, 60, 120, 100, 140, 120, 110, 120,110,120,120,110,170,120,120,160,100,150,120,120};
const uint8_t t3[8]={27, 40, 3, 17, 3, 99, 3, 0};
const uint8_t t4[8]={0, 0, 0, 0, 0, 0, 0, 0};
const uint8_t t5[8]={9, 1, 1, 1, 1, 1, 1, 1};
const uint8_t t6[8]={33, 33, 33, 33, 33, 33, 33, 33};
const uint8_t t7[8]={0, 0, 0, 0, 0, 0, 0, 88};
 
 
// Messung der Interruptdauer
    tmp =1;
    tmp =2;
    tmp =3;
 
// Debug 
 
  memcpy(pwm_setting, t2, 20);
    pwm_update();
 
    
/******************************************************************/
	/*
	uint8_t tmp1[10];
	memcpy(tmp1,t1,10);
    while(1){
	tmp1[6]-=1;
	tmp1[4]-=1;
	if(tmp1[6]<=80) tmp1[6]=130;
	if(tmp1[4]<=70) tmp1[4]=120;
	 memcpy(pwm_setting, tmp1, 10);
    pwm_update();
	_delay_ms(50);
	};
	*/
	uint8_t pos[20];
	memcpy(pos,t2,20);
	
	//startPos();
	
	while(1)
	{
	//
	aufAb(pos,20);
	//geradeausGehen(pos,20);
	}
	
	
	while(1){
	
	
	
	}
    return 0;
}
ISR(USART_RXC_vect)
  {
  uart_putc(UDR);
 if (servo==1)servoSteuer();
 else{
 unsigned char nextChar;
  // Daten aus dem Puffer lesen
  nextChar = UDR;
 if (nextChar=='s'){
 servo=1;
 
 }else{
  	if( uart_str_complete == 0 ) {
    // Daten werden erst in uart_string geschrieben, wenn nicht String-Ende/max Zeichenlänge erreicht ist/string gerade verarbeitet wird
    if( nextChar != '\n' &&
        nextChar != '\r' &&
        uart_str_count < 9 ) {
      buffer[uart_str_count] = nextChar;
      uart_str_count++;
    }
    else {
      buffer[uart_str_count] = '\0'; 
      uart_str_count=0;
	  uart_str_complete=1;
	  
         }
  }
  }
  }
}
void servoSteuer(void){
	
	static uint8_t servo_count;
	uint8_t nextChar;
	
  // Daten aus dem Puffer lesen
  nextChar = UDR;
  uart_putc(nextChar);
	
	if(nextChar !='s'){
	 if(
       nextChar != '\r'){
			
		
			
			memcpy(pwm_setting[3],nextChar,8);
			servo_count++;
						
		
		}else{
		servo_count=0;
		servo=0;
		uart_puts("finish");
		pwm_update();
	  }
	  
	}
}
void geradeausGehen(uint8_t* pos,uint8_t tempo)
{
	
	
	pos[8]=120;
	pos[6]=120;
	pos[14]=120;
		
	pos[2]=140;
	pos[18]=100;
	pos[11]=100;
	
	
	memcpy(pwm_setting, pos, 20);
		pwm_update();
		_delay_ms(1000);
		
	while(pos[10] <= 140){
		pos[4]++;
		pos[7]--;
		pos[10]++;
		
		pos[19]--;
		pos[16]++;
		pos[13]++;
		if((pos[10]-80)%4==0 && (pos[10]-80)<=35){
			pos[5]--;
			pos[9]--;
			pos[15]++;
			}
		else if((pos[10]-80)%4==0)
		{
			pos[5]++;
			pos[9]++;
			pos[15]--;
			}
		memcpy(pwm_setting, pos, 20);
		pwm_update();
		_delay_ms(tempo);
		}
		
	
			
		//Beine
		pos[2]=120;
		pos[18]=120;
		pos[11]=120;
		
		//Füße
		pos[9]=100;
		pos[5]=100;
		pos[15]=180;
		memcpy(pwm_setting, pos, 20);
		pwm_update();
		_delay_ms(1000);
		
		pos[8]=140;
		pos[6]=140;
		pos[14]=100;
		
		//Füße
		pos[17]=170;
		pos[12]=190;
		pos[3]=80;
		memcpy(pwm_setting, pos, 20);
		pwm_update();
		_delay_ms(1000);	
		
		while(pos[16] >= 80){
		pos[4]--;
		pos[7]++;
		pos[10]--;
		
		pos[19]++;
		pos[16]--;
		pos[13]--;
		if((pos[16]-50)%4==0 && (pos[16]-50)<=75){
			pos[17]--;
			pos[12]--;
			pos[3]++;
			}
		else if((pos[16]-50)%4==0)
		{
			pos[17]++;
			pos[12]++;
			pos[3]--;
			}
		memcpy(pwm_setting, pos, 20);
		pwm_update();
		_delay_ms(tempo);
		}
		
}
void startPos(void){
	//                      0    1   /2   3    4 /5   6    7 / 8   9  10  /11  12 13 /14  15   16/  17  18  19
	uint8_t startPos[20]={60, 60, 150, 100, 140, 120,140, 120,140,120,120,80,170,120,90,150,100,150,90,120};
	memcpy(pwm_setting, startPos, 20);
	pwm_update();
	_delay_ms(1000);
	for(int i=0; i<15;i++){
	
	startPos[2]-=2;
	startPos[6]-=2;
	startPos[8]-=2;
	startPos[9]--;
	startPos[5]--;
	startPos[3]--;
	startPos[18]+=2;
	startPos[11]+=2;
	startPos[14]+=2;
	startPos[17]++;
	startPos[12]++;
	startPos[15]++;
	memcpy(pwm_setting, startPos, 20);
	pwm_update();
	_delay_ms(50);
	
	}
	const uint8_t endStartPos[20]={100, 100,30, 80, 140, 90, 30, 120,30,90,120,230,180,120,230,180,120,180,230,130};
	
	//aufAb(endStartPos,50);
}
void aufAb(uint8_t *pos,uint8_t tempo){
	uint8_t i=0;
	
	while (i<80){
	i++;
	pos[8]--;
	pos[6]--;
	pos[2]--;
	pos[18]++;
	pos[11]++;
	pos[14]++;
	
	pos[9]++;
	pos[5]++;
	pos[3]++;
	pos[17]--;
	pos[12]--;
	pos[15]--;
	
	memcpy(pwm_setting, pos, 20);
		pwm_update();
		_delay_ms(tempo);
	}
	
		while (i>0){
	i--;
	pos[8]++;
	pos[6]++;
	pos[2]++;
	pos[18]--;
	pos[11]--;
	pos[14]--;
	
	pos[9]--;
	pos[5]--;
	pos[3]--;
	pos[17]++;
	pos[12]++;
	pos[15]++;
	
	memcpy(pwm_setting, pos, 20);
		pwm_update();
		_delay_ms(tempo);
	}
}
 
						
Lesezeichen