Die Version mit der USART-Ausgabe (war für das letzte posting zu umfangreich) ist :
Code:
/* >> Diese ersten 2 Zeilen können zum Compilieren entfernt werden (muss nicht)
  Sicherung 18dez07 1222 nach Datei ..C1..\2_drehzahlen\2_drehzahlen-x23ok.c
 ===================================================================================
 ========== Beachte: printout aus AVRStudio geht (nur) bis col 85 ==================
  Target MCU        : ATmega16
  Target Hardware   : RNControl
  Target cpu-frequ. : 16 MHz, externer Quarzoszillator
 ===================================================================================
  Enthaltene Routinen:
	static inline void setportdon/~off
	void ext_int_init (void)	// ISR ext1+2 initialisieren  <<< offen
	void tmr_int_init (void)	// Timer ISR  initialisieren  <<< offen
	################################# diese beiden Routinen sind ISR
					Timer fehlen
	void USART_Init( unsigned int baud ) 
	void sendchar(unsigned char c)
	void sendUSART(char *s)
	void Motst_aufab(void)		// Mot li+re, vor+zur, aufab
	SIGNAL (SIG_INTERRUPT0)		// ISR Motor/Speed1
	SIGNAL (SIG_INTERRUPT1)		// ISR Motor/Speed2
	int main(void)
 ===================================================================================
  *** Versionsgeschichte:
 ====================
 x23 18dez07 12:22 x21 wieder übernommen und ISR für Timer0 umbenannt von
 	SIGNAL(SIG_OVERFLOW0)  nach  SIGNAL(SIG_OUTPUT_COMPARE0)      OK
 x22 18dez07 12:05ff alles zusammenstreichen bis auf die "Grundversion" mit 
 	TMR_0_ ... und so     12:05 geht nix
 x21 18dez07 11:53
 	Nachtrag aus x14. Test: TMR_0_init() + sei() <==> dann läuft nix mehr :(
 x20 17dez07 23:43ff
 	Nachtrag der Berichtigungen aus der Testversion 2_drehzahlen-xxxok.c
 x14 18dez07 10:17 Bessere Dokumentation in TMR_0_init, LED auf PD4 wird getoggelt
 x12 18dez07 00:22 Läuft mit der richtigen Frequenz
 xxxok 17dez07 23:40 Testversion mit ordentlichem Interrupt - Frequenz stimmt nicht
 x11 17dez07 17:mmff Test - seltsame Ergebnisse - Timer timt nicht 
 x10 17dez07 15:43 Erster Codeausbau fertig zum Test (sichern und LED-Test mit 
 				dem Timer0
     18dez07 00:04 - - läuft noch nicht
 x01 16dez07 23:42 Sichern des ersten Standes - ohne Timer-Interrupt-Routine
 x00 16dez07 14:30ff erster Aufbau
 ===================================================================================
  *** Aufgabenstellung : Messen von 2 Motordrehzahlen
  Es werden Impulse von zwei Gabellichtschranken am µC erfasst. Daraus werden
    zwei Drehzahlen errechnet.
    Drehzahlbereich von 0 (Stillstand) bis 1kHz (60 000 Upm)

    Grundlage wird ein Timerinterrupt mit 

  Original: ...C1..\C-motst_x10\C_motst_x21_OK.c
 ===================================================================================
                                                                                  */
/* ============================================================================== */

#include <stdlib.h> 
#include <avr/io.h> 
#include <avr/interrupt.h>
/* Beachte C:\Programme\WinAVR-20070525\avr\include\avr\iom16.h */
#include "motstlib_x10_jwt.h"

#define MCU = ATMega16 

//   Mit Quarz 16 Mhz-CPU 
#define F_CPU  16000000 
#define BAUD 38400 
#define UBRR (unsigned int)(F_CPU / BAUD / 16 - 0.5) 

/* ============================================================================== */
/*   Interrupt-Handler und -Adressen
Address Labels Code Comments
siehe C:\Programme\WinAVR-20070525\avr\include\avr\iom16.h sowie
Interruptvektoren/-vektortabelle in *doc2466, S 45+46 von AVR                    */

/*### Variablenliste, global ###*/
// uint8_t i=1, k=1, max=120, min=35;
uint8_t i=1, kre=1, kli=1;
uint8_t min=15, max=122;
char id_MCU [30]; 

/* beachte: volatile!  und   Vorzeichenlos reicht für alle                   */
volatile uint16_t Iencdr1, Iencdr2;	/* Counter für Encoder-ticks
  Werden in der ISR hochgezählt und im main bei Gelegenheit
    (welcher? - nach 5 sec?) - spätestens aber beim Fahrtrichtungswechsel
    auf Null gesetzt. DAnn aber die Werte musv+musi entsprechend anpassen    */
volatile uint16_t Iz_ysecv1, Iz_ysecv2;	/* Zeitmarke "µsec"
  des vorletzten Interrupts in der Einheit 100 Mikrosekunden. Ist der Wert des
  hochlaufenden Timers zum Interruptzeitpunkt i-1                            */
volatile uint16_t Iz_yseci1, Iz_yseci2;	/* Zeitmarke "µsec"
    des letzten Interrupts in der Einheit 100 Mikrosekunden. Ist der Wert des
    hochlaufenden Timers zum Interruptzeitpunkt i (letzter Interrupt)        */
volatile uint16_t Iz_diff1, Iz_diff2;	/* Zeitdifferenz
  Beim Abarbeiten des Interrupts wird yseci mit time1 belegt und diff aus der
    Differenz yseci-ysecv errechnet. Danach wird yseci nach ysecv kopiert.
    Im main wird aus diff die Drehzahl berechnet.                            */
volatile uint16_t Izeit_1;			/* Timer läuft hoch
  Die Interruptroutine läuft mit 10 kHz (Möglicherweise sind 100 kHz besser)
    Beim Start des Timers läuft der Zähler time1 hoch und wird nach 5 sec -
    also beim Wert 50 000 - wieder auf Null gesetzt. Dabei werden die Werte
    ysecv und yseci angepasst                                                  */
/* ============================================================================== */
//   ### Portroutinen und waitms aus RNContr Demo C 
//   *### Ports setzen auf HIGH/LOW  ### 

  static inline void setportdon(const uint8_t n) 
  {PORTD |= (1<<n);}   //set PORTD.n high 
  static inline void setportdoff(const uint8_t n) 
  {PORTD &= ~(1<<n);}   //set PORTD.n low 
    static inline void setportcon(const uint8_t n) 
  {PORTC |= (1<<n);}   //set PORTC.n high 
  static inline void setportcoff(const uint8_t n) 
  {PORTC &= ~(1<<n);}   //set PORTC.n low 



/*### Senden per USART - RS232-Kommunikation ###*/
/*Zum senden von Zeichen im Hauptprogramm entweder
char irgendwas[] = "meintext";
sendUSART(irgendwas);		oder direkt
sendUSART("meinText");		verwenden.		*/ 

/*
 ===================================================================================						
   Dieser Codeschnipsel ähnlich 2313-doc, S 121 				  */
void USART_Init( unsigned int baud ) 
{ 					// Set baud rate
UBRRH = (unsigned char)(baud>>8); 
UBRRL = (unsigned char)baud;		// Enable receiver and transmitter
UCSRB = (1<<RXEN)|(1<<TXEN); 		// Set frame format: 8data, 2stop bit
UCSRC = (3<<UCSZ0); 
} 

// ------------------------------------------------------------------ 
void sendchar(unsigned char c) 
{ 
   while(!(UCSRA & (1<<UDRE))) //Warten, bis Senden möglich ist 
   { 
   } 
   UDR = c; //schreibt das Zeichen aus 'c' auf die Schnittstelle 
} 

// ------------------------------------------------------------------ 
void sendUSART(char *s) //*s funktiniert wie eine Art Array - auch bei 
         // einem String werden die Zeichen (char) 
         // einzeln ausgelesen - und auf die 
         // Sendeschnittstelle übertragen 
{ 
   while(*s) 
   { 
   sendchar(*s); 
   s++; 
   } 
} 



/*### Motortest mit tiny2313 auf exp2313-232/2 mit motL293-aufsteck/1
	Anschluss (1+3) als negativ (schwarz), Anschluss (2+4) als positiv
	hier für m16/RNControl
 ============================================================================== */
void Motst_aufab(void)	// Mot li+re, vor+zur, aufab
{
char worti[5], wortkli[5], wortkre[5];
	Mlinksvor();
	Mrechtsvor();

	setPWMlinks(0);
	setPWMrechts(0);
	waitms(40);
	sendUSART("\r\nMotortest ~x21\r\n");
	sendUSART("PWM-Stellwerte\r\n");
	sendUSART("_n__li__re\r\n"); 

	for(uint16_t i=10; i<199; i=i+1)
	{
		kre=i;
		kli=i+2;
		setPWMlinks(kli);
		setPWMrechts(kre);
		waitms(1000);
		utoa(i, worti, 10);
		utoa(kli, wortkli, 10);
		utoa(kre, wortkre, 10);
		sendUSART(worti);sendUSART("  ");
		sendUSART(wortkli);sendUSART("  ");
		sendUSART(wortkre);sendUSART("\r\n");
	}
	waitms(1000);
/*	sendUSART("tiny2313\r\n");
	sendUSART("PWM-Stellwerte\r\n");
	sendUSART("_n__li__re\r\n");
				Ausgeblendet wegen Speicherplatzbedarf  */
	for(uint16_t i=199; i>10; i=i-1)
	{
		kre=i;
		kli=i+2;
		setPWMlinks(kli);
		setPWMrechts(kre);
		waitms(1000);
//		utoa(i, worti, 10);
//		utoa(kli, wortkli, 10);
//		utoa(kre, wortkre, 10);
//		sendUSART(worti);sendUSART("  ");
//		sendUSART(wortkli);sendUSART("  ");
//		sendUSART(wortkre);sendUSART("\r\n");
	}
	setPWMlinks(0);
	setPWMrechts(0);

	Mlinksstop();
	Mrechtsstop();
	waitms(300);
}
/* ============================================================================== */




/* =================================================================================
   ##### Hier ISR und ISR - Initialisierung(en)
================================================================================= */
/* ===  Initialisierung fuer EXT_INT0/1 auf Pin 16+17/mega16(32)  ==================
$002 jmp SIG_INTERRUPT0 ; IRQ0 Handler und
$004 jmp SIG_INTERRUPT1 ; IRQ1 Handler                  */
void XTI_01_init( void )	
{				//Initialisiere beide Interrupts auf rising edge
				//  d.h. MCUCR ISC00,01,10+11 auf 1 (doc,S68)
    MCUCR |= (1<<ISC11)|(1<<ISC10)|(1<<ISC01)|(1<<ISC00);
    GICR  |= (1<<INT1)|(1<<INT0);	//  und erlaube diese I´s in GICR
}
/* ============================================================================== */


/* ===  Initialisierung fuer Timer mega16(32)  =====================================
SIGNAL (SIG_OVERFLOW0)
Beachte zu TIMSK:
                 OCIE2 TOIE2 TICIE1 OCIE1A OCIE1B TOIE1 OCIE0 TOIE0   TIMSK
Read/Write        R/W   R/W   R/W    R/W    R/W    R/W   R/W   R/W
Initial Value      0     0     0      0      0      0     0     0

RNControl          0     0     1      1      1      1     0     0     hex 3c
###>>> dieser Wert wird GESETZT, d.h. Bit 0, 1, 6 und 7 gehen auf NULL.
Hier wird: TIMSK |= (1<<OCIE0) mit ODER! eingeführt, d.h.
                                                          1
									*/
void TMR_0_init( void )	
{				//Initialisiere 8-Bit-Timer auf 10 kHz
    TCCR0 |= (1<<CS01 | 1<<CS00); // Prescaler 64 / Clock <- CPU
    TCCR0 |= (1<<WGM01 | 0<<WGM00);	// Timer im CTC-Mode
    OCR0 = 25;   			// Preset 25 für 100µs bei 16Mhz  
    TIMSK |= (1<<OCIE0); 		// Compare Match IRQ 
}
/* ============================================================================== */


/* ===  Nicht unterbrechbare ISR für EXT_INT0 auf Pin 16/PD2/mega16(32)  ======== */
/* Routine setzt einfach einen Zähler hoch. Der Zähler wird im main
     ausgelesen ##>> cli/sei setzen <<## und nach 2 (od. 5) hunderstel Sekunden
     auf den Speicher WEG_L/_R vorzeichenrichtig aufaddiert und dann zurückgesetzt.
     ##>> Beim Richtungswechsel (cli/sei) wird der Zähler ausgelesen und genullt,
     damit ist eine saubere Wegmessung möglich.
     Der zugehörige Motor auf RNControl auf PB0/PB1 = li,re und PD5 Geschwind.
     Der alternat.  Motor auf RNControl auf PC7/PC6 = li,re und PB4 PWM/Geschw.
$002 jmp EXT_INT0 ; IRQ0 Handler                  */
SIGNAL(SIG_INTERRUPT0)
{
    Iencdr1 ++;			//zähle Counter/encoder 1 hoch
    Iz_yseci1 = Izeit_1;		//Weise musi den akt. Timerwert zu
    Iz_diff1 = Iz_yseci1-Iz_ysecv1;	    //Neue Zeit-Differenz1 ausrechnen
    Iz_ysecv1 = Iz_yseci1;		//der aktuelle Zeitwert wird "Alter"
}
/* ============================================================================== */


/* ============================================================================== */
/* ===  Nicht unterbrechbare ISR für EXT_INT1 auf Pin 17/PD3/mega16(32)  ======== */
/* Routine setzt einfach einen Zähler hoch.
      Sonst wie ISR für EXT_INT0 für Motor auf PC7/PC6 = li,re und PB4 PWM/Geschw.

$004 jmp EXT_INT1 ; IRQ1 Handler                  */
SIGNAL(SIG_INTERRUPT1)
{
    Iencdr2 ++;			//zähle Counter/encoder 2 hoch
    Iz_yseci2 = Izeit_1;		//Weise Iz_yseci den akt. Timerwert zu
    Iz_diff2 = Iz_yseci2-Iz_ysecv2;	//Neue Zeit-Differenz2 ausrechnen
    Iz_ysecv2 = Iz_yseci2;		//der aktuelle Zeitwert wird "Alter"
}
/* ============================================================================== */


/* ============================================================================== */
/* ===  Nicht unterbrechbare ISR für timer ====================================== */
/* Diese Routine zählt hoch im Takt 10 kHz.setzen.
      Dieser Wert wird von den beiden anderen ISR ausgelesen und den Werten

*/
// SIGNAL(SIG_OVERFLOW0)
// #define SIG_OUTPUT_COMPARE0	//Interuptvektor, siehe Tabelle
SIGNAL(SIG_OUTPUT_COMPARE0)
{
    Izeit_1 ++;			//Zeitstand des Interupt-Timers

    PORTC ^= (1 << PC1);	//LED toggeln

}
/* ============================================================================== */




// ------------------------------------------------------------------ 
/*### Hauptschleife ###*/ 
int main(void) 
{
//  DDRB=0x3f;		// 0011 1111 -> Ports B für Motor als Ausgänge
//  DDRD=0x08;		// 0000 1000 -> PortsD 3 als Ausgang
/*  Im Unterschied zur Vorlage (für tiny2313 ist dieser Code für den ATMega16
    auf RNControl <==> nimm dortige Initialisierungen mit folgender Änderung
    Encoder-Eingang 1   PortA1
    Encoder-Eingang 2   PortA2
*/
	/*###Initialisierungsphase###      Direkt aus RNContorl-test.c importiert*/

	//Pins bzw. Ports als Ein-/Ausgänge konfigurieren
	DDRA |= 0x00;	//00000000 -> alle Analogports als Eingänge
	DDRB |= 0x03;	//00000011 -> PB0 und PB1 Kanäle des rechten Motors
	DDRC |= 0xFF;	//11111111 -> PC6 und PC7 linker Mot, Rest LEDs/Lauflicht
	DDRD |= 0xB0;	//10110000 -> D4 PWM linker Motors, PD5 rechter Mot
	
	//Initialisierungen
	setportcon(0); setportcon(1); setportcon(2); setportcon(3);
	setportcon(4); setportcon(5); setportcon(6); setportcon(7); //LEDs aus
	setportdoff(7);	//Speaker aus

	init_timer1();	//Initialisierung Timer für PWM
	USART_Init(UBRR);     //USART initialisieren 
    
	TMR_0_init();	//Initialisiere den Timer0-Interrupt (10 kHz)
	sei();		//Globalen Interrupt freigeben


   for(i=0; i<20; i++)
   {
       setportcoff(3);	//2 sek blinken nach dem Reset - damit man
       waitms(15);	//  kurze resets besser erkennt
       setportcon(3);
       waitms(85);
   }

for(;;){ 
       	setportcoff(3);
	waitms(1000);
	setportcon(3);
	waitms(1000);
	
/*	Mlinksstop();
	Mrechtsstop();
	setPWMlinks(0);
	setPWMrechts(0);
	Motst_aufab();		*/
	}
}
die lief aber nur ohne Interrupt (die Quelle ist relativ "roh", sorry).