#include <avr/io.h>
#include <avr/interrupt.h>
#include <avr/signal.h>
#include <inttypes.h>
#include <stdlib.h>
gehe zum Quellcode dieser Datei
Makrodefinitionen | |
#define | FALSE 0 |
#define | TRUE 1 |
#define | OFF 0 |
#define | ON 1 |
#define | GREEN 1 |
#define | RED 2 |
#define | YELLOW 3 |
#define | LEFT 0 |
#define | RIGHT 1 |
#define | CENTER 2 |
#define | K1 (1<<5) |
#define | K2 (1<<4) |
#define | K3 (1<<3) |
#define | K4 (1<<2) |
#define | K5 (1<<1) |
#define | K6 (1<<0) |
#define | Batterie Battery |
#define | OdometrieData OdometryData |
#define | GREEN_LED_ON PORTB |= GREEN_LED |
#define | GREEN_LED_OFF PORTB &= ~GREEN_LED |
#define | RED_LED_ON PORTD |= RED_LED |
#define | RED_LED_OFF PORTD &= ~RED_LED |
#define | FWD (1 << PB5) |
#define | RWD (1 << PB4) |
#define | BREAK 0x00 |
#define | FREE (1 << PB4) | (1 << PB5) |
#define | IRTX (1 << PB3) |
#define | GREEN_LED (1 << PB0) |
#define | RED_LED (1 << PD2) |
#define | PWM (1 << PB1) | (1 << PB2) |
#define | RIGHT_DIR (1 << PB4) | (1 << PB5) |
#define | LEFT_DIR (1 << PD4) | (1 << PD5) |
#define | SWITCHES (1 << PD3) |
#define | SWITCH_ON PORTD |= SWITCHES |
#define | SWITCH_OFF PORTD &= ~SWITCHES |
#define | BATTERIE (1 << MUX0) | (1 << MUX2) |
#define | SWITCH (1 << MUX2) |
#define | IR_LEFT (1 << MUX0) | (1 << MUX1) |
#define | IR_RIGHT (1 << MUX1) |
#define | FRONT_LED (1 << PD6) |
#define | ODOMETRIE_LED (1 << PD7) |
#define | ODOMETRIE_LED_ON PORTD |= ODOMETRIE_LED |
#define | ODOMETRIE_LED_OFF PORTD &= ~ODOMETRIE_LED |
#define | WHEEL_LEFT (1 << MUX0) |
#define | WHEEL_RIGHT 0 |
Funktionen | |
void | Init (void) |
Initialisiert die Hardware: Ports, A/D Wandler, Serielle Schnittstelle, PWM Die Init Funktion muss von jeden Programm beim Start aufgerufen werden. | |
unsigned long | Gettime (void) |
return time since system start in ms | |
void | Msleep (int ms) |
Wartefunktion in ms. | |
void | Sleep (unsigned char time36kHz) |
Wartefunktion. | |
void | EncoderInit (void) |
Den Interrupt Betrieb der Odometriesensoren-Messung initialisieren und starten. | |
void | EncoderSet (int setl, int setr) |
Interruptbetriebene Odometriesensoren Werte vorbelegen. | |
void | EncoderStop (void) |
Den Interrupt Betrieb der Odometriesensoren-Messung anhalten. | |
void | EncoderStart (void) |
Den Interrupt Betrieb der Odometriesensoren-Messung starten. | |
void | Go (int distance, int speed) |
Faehrt eine bestimmte Strecke mit einer bestimmten Geschwindigkeit. (Autor: stochri) Benutzt die Odometrie Sensoren im Interrupt Betrieb. Vor dem ersten Aufruf muss deshalb EncoderInit() aufgerufen werden. | |
void | Turn (int degree, int speed) |
Dreht um einen bestimmten Winkel mit einer bestimmten Geschwindigkeit. (Autor: stochri) Benutzt die Odometrie Sensoren im Interrupt Betrieb. Vor dem ersten Aufruf muss deshalb EncoderInit() aufgerufen werden. | |
int | Battery (void) |
Liest die Batteriespannung und gibt sie zurueck. Es erfolgt keine Konvertierung in einen Spannungswert. | |
void | LineData (unsigned int *data) |
Liest die Daten der beiden Linienverfolgungssensoren. Die Linien-Beleuchtungs-LED kann sowohl an- als auch ausgeschaltet sein. | |
void | OdometryData (unsigned int *data) |
Liest die Daten der beiden Odometriesensoren (Radsensoren). Diese Funktion schaltet die Odometrie-LED's immer an. Diese Funktion schaltet die Back-LED's immer aus. | |
void | StatusLED (unsigned char color) |
Steuert die (lustige) mehrfarbige Status-LED. | |
void | FrontLED (unsigned char status) |
Steuert die vorne, nach unten zeigende, Front-LED. | |
void | BackLED (unsigned char left, unsigned char right) |
Steuert die beiden hinteren Back-LED's Wenn diese Funktion aufgerufen wird, funktioniert die Odometriemessung nicht mehr, da die gleichen Port-Pins (Port C:Pin 0 und 1) des Prozessors hierfuer verwendet werden. | |
void | MotorDir (unsigned char left_dir, unsigned char right_dir) |
Steuert die Drehrichtung der Motoren. | |
void | MotorSpeed (unsigned char left_speed, unsigned char right_speed) |
Steuert die Geschwindigkeit der Motoren. | |
void | SetMotorPower (int8_t leftpwm, int8_t rightpwm) |
Steuert die Motorgeschwindigkeit und Drehrichtung der Motoren. | |
void | SerWrite (unsigned char *data, unsigned char length) |
Senden von Daten ueber die serielle Schnittstelle. | |
void | SerRead (unsigned char *data, unsigned char length, unsigned int timeout) |
Lesen von Daten ueber die serielle Schnittstelle. | |
void | UartPutc (unsigned char zeichen) |
Sendet einen einzelnen Character über die serielle Schnittstelle. | |
void | SerPrint (unsigned char *data) |
Sendet einen null-terminierten String ueber die serielle Schnittstelle. | |
void | PrintInt (int wert) |
Ausgabe eines Integer Wertes als String ueber die serielle Schnittstelle. | |
void | PrintLong (long wert) |
Ausgabe eines Long Wertes als String ueber die serielle Schnittstelle. | |
unsigned char | PollSwitch (void) |
Tastsensor Abfrage im 'Polling-Betrieb'. | |
void | StartSwitch (void) |
'Interrupt-Betrieb' zur Tastsensor Abfrage einschalten. | |
void | StopSwitch (void) |
'Interrupt-Betrieb' zur Tastsensor Abfrage anhalten. | |
void | Sound (uint16_t freq, uint16_t duration_msec, uint8_t amplitude) |
Soundausgabe ueber die Motoren. | |
Variablen | |
const char | version [5] |
int | switched |
Flag, dass der Interrupt SIG_INTERRUPT1 durch eine gedrueckte Taste ausgeloesst wurde. 0 = keine Taste, 1 = Taste gedrueckt. Kann im eigenen Programm immer abgefragt werden. | |
int | encoder [2] |
Odometriesensor Zaehler bei Interrupt Betrieb. encoder[0] links, encoder[1] = rechts. | |
volatile unsigned char | count36kHz |
Counter fuer 36kHz. | |
volatile unsigned long | timebase |
Sytemzeit in ms. | |
volatile int | autoencode |
Steuert, ob die Odometrie-Sensor Abfrage im Interrupt Betrieb laufen soll. |
#define BATTERIE (1 << MUX0) | (1 << MUX2) |
ADC5 A/D Wandler Port fuer Batterie Abfrage
Definiert in Zeile 515 der Datei inc/asuro.h.
#define Batterie Battery |
Definiert in Zeile 396 der Datei inc/asuro.h.
#define BREAK 0x00 |
Motor bremsen
Definiert in Zeile 500 der Datei inc/asuro.h.
#define CENTER 2 |
Definiert in Zeile 240 der Datei inc/asuro.h.
#define FALSE 0 |
Definiert in Zeile 227 der Datei inc/asuro.h.
#define FREE (1 << PB4) | (1 << PB5) |
Motor freilaufend
Definiert in Zeile 501 der Datei inc/asuro.h.
#define FRONT_LED (1 << PD6) |
PD6 Port fuer Front LED
Definiert in Zeile 519 der Datei inc/asuro.h.
#define FWD (1 << PB5) |
Motor vorwaerts
Definiert in Zeile 498 der Datei inc/asuro.h.
#define GREEN 1 |
Definiert in Zeile 233 der Datei inc/asuro.h.
#define GREEN_LED (1 << PB0) |
PB0 Port fuer Gruene Status LED
Definiert in Zeile 504 der Datei inc/asuro.h.
#define GREEN_LED_OFF PORTB &= ~GREEN_LED |
Gruene Status LED aus
Definiert in Zeile 494 der Datei inc/asuro.h.
#define GREEN_LED_ON PORTB |= GREEN_LED |
Gruene Status LED an
Definiert in Zeile 493 der Datei inc/asuro.h.
#define IR_LEFT (1 << MUX0) | (1 << MUX1) |
ADC3 A/D Wandler Port fuer Linienfolger Fototransistor links
Definiert in Zeile 517 der Datei inc/asuro.h.
#define IR_RIGHT (1 << MUX1) |
ADC2 A/D Wandler Port fuer Linienfolger Fototransistor rechts
Definiert in Zeile 518 der Datei inc/asuro.h.
#define IRTX (1 << PB3) |
PB3 Port fuer Infrarot Transmitter LED
Definiert in Zeile 503 der Datei inc/asuro.h.
#define K1 (1<<5) |
Definiert in Zeile 245 der Datei inc/asuro.h.
#define K2 (1<<4) |
Definiert in Zeile 246 der Datei inc/asuro.h.
#define K3 (1<<3) |
Definiert in Zeile 247 der Datei inc/asuro.h.
#define K4 (1<<2) |
Definiert in Zeile 248 der Datei inc/asuro.h.
#define K5 (1<<1) |
Definiert in Zeile 249 der Datei inc/asuro.h.
#define K6 (1<<0) |
Definiert in Zeile 250 der Datei inc/asuro.h.
#define LEFT 0 |
Definiert in Zeile 238 der Datei inc/asuro.h.
#define LEFT_DIR (1 << PD4) | (1 << PD5) |
PD4, PD5 Ports fuer Drehrichtung linker Motor
Definiert in Zeile 509 der Datei inc/asuro.h.
#define ODOMETRIE_LED (1 << PD7) |
PD7 Port fuer Odometrie LED
Definiert in Zeile 521 der Datei inc/asuro.h.
#define ODOMETRIE_LED_OFF PORTD &= ~ODOMETRIE_LED |
Odometrie LED aus
Definiert in Zeile 523 der Datei inc/asuro.h.
#define ODOMETRIE_LED_ON PORTD |= ODOMETRIE_LED |
Odometrie LED an
Definiert in Zeile 522 der Datei inc/asuro.h.
#define OdometrieData OdometryData |
Definiert in Zeile 397 der Datei inc/asuro.h.
#define OFF 0 |
Definiert in Zeile 230 der Datei inc/asuro.h.
#define ON 1 |
Definiert in Zeile 231 der Datei inc/asuro.h.
#define PWM (1 << PB1) | (1 << PB2) |
PB1, PB2 Ports fuer Pulsweitenmodulation der Motor Geschwindigkeit
Definiert in Zeile 507 der Datei inc/asuro.h.
#define RED 2 |
Definiert in Zeile 234 der Datei inc/asuro.h.
#define RED_LED (1 << PD2) |
PD2 Port fuer Rote Status LED
Definiert in Zeile 505 der Datei inc/asuro.h.
#define RED_LED_OFF PORTD &= ~RED_LED |
Rote Status LED aus
Definiert in Zeile 496 der Datei inc/asuro.h.
#define RED_LED_ON PORTD |= RED_LED |
Rote Status LED an
Definiert in Zeile 495 der Datei inc/asuro.h.
#define RIGHT 1 |
Definiert in Zeile 239 der Datei inc/asuro.h.
#define RIGHT_DIR (1 << PB4) | (1 << PB5) |
PB4, PB5 Ports fuer Drehrichtung rechter Motor
Definiert in Zeile 508 der Datei inc/asuro.h.
#define RWD (1 << PB4) |
Motor rueckwaerts
Definiert in Zeile 499 der Datei inc/asuro.h.
#define SWITCH (1 << MUX2) |
ADC4 A/D Wandler Port fuer Tastsensor
Definiert in Zeile 516 der Datei inc/asuro.h.
#define SWITCH_OFF PORTD &= ~SWITCHES |
Tastsensor aus
Definiert in Zeile 513 der Datei inc/asuro.h.
#define SWITCH_ON PORTD |= SWITCHES |
Tastsensor an
Definiert in Zeile 512 der Datei inc/asuro.h.
#define SWITCHES (1 << PD3) |
PD3 Port fuer Tastsensor
Definiert in Zeile 511 der Datei inc/asuro.h.
#define TRUE 1 |
Definiert in Zeile 228 der Datei inc/asuro.h.
#define WHEEL_LEFT (1 << MUX0) |
ADC1 A/D Wandler Port fuer Odometrie Sensor links
Definiert in Zeile 525 der Datei inc/asuro.h.
#define WHEEL_RIGHT 0 |
ADC0 A/D Wandler Port fuer Odometrie Sensor rechts
Definiert in Zeile 526 der Datei inc/asuro.h.
#define YELLOW 3 |
Definiert in Zeile 235 der Datei inc/asuro.h.
void BackLED | ( | unsigned char | left, | |
unsigned char | right | |||
) |
Steuert die beiden hinteren Back-LED's
Wenn diese Funktion aufgerufen wird, funktioniert die Odometriemessung
nicht mehr, da die gleichen Port-Pins (Port C:Pin 0 und 1) des Prozessors
hierfuer verwendet werden.
[in] | left | Schaltet die linke LED an bzw. aus. [ ON | OFF ] |
[in] | right | Schaltet die rechte LED an bzw. aus. [ ON | OFF ] |
Definiert in Zeile 155 der Datei leds.c.
00158 { 00159 if (left || right) 00160 { 00161 PORTD &= ~(1 << PD7); // Rad-LED's OFF 00162 DDRC |= (1 << PC0) | (1 << PC1); // Port als Output => KEINE Odometrie 00163 PORTC |= (1 << PC0) | (1 << PC1); 00164 } 00165 if (!left) 00166 PORTC &= ~(1 << PC1); 00167 if (!right) 00168 PORTC &= ~(1 << PC0); 00169 }
int Battery | ( | void | ) |
Liest die Batteriespannung und gibt sie zurueck.
Es erfolgt keine Konvertierung in einen Spannungswert.
keine |
// In Variable wert den 10-Bit-Bateriespannungswert lesen // und bei Unterschreitung von 810 eine alles_stop-Funktion // aufrufen. int wert; wert = Battery(); if (wert < 810) // 810 entsprechen ca. 4,455 Volt alles_stop (); // Spannung zu klein, Akkus schonen
Definiert in Zeile 83 der Datei adc.c.
00085 { 00086 int ec_bak = autoencode; // Sichert aktuellen Zustand 00087 int data; 00088 00089 /* 00090 Autoencode-Betrieb vom ADC-Wandler unterbinden. 00091 */ 00092 autoencode = FALSE; 00093 00094 ADMUX = (1 << REFS0) | (1 << REFS1) | BATTERIE; // interne 2.56V Referenz 00095 // Ref. mit ext. Kapazitaet 00096 ADCSRA |= (1 << ADSC); // Starte AD-Wandlung 00097 while (!(ADCSRA & (1 << ADIF))) // Ende der AD-Wandlung abwarten 00098 ; 00099 ADCSRA |= (1 << ADIF); // AD-Interupt-Flag zuruecksetzen 00100 data = ADCL + (ADCH << 8); // Ergebnis als 16-Bit-Wert 00101 /* 00102 Autoencode-Betrieb vom ADC-Wandler wiederherstellen. 00103 */ 00104 autoencode = ec_bak; 00105 return data; 00106 }
void EncoderInit | ( | void | ) |
Den Interrupt Betrieb der Odometriesensoren-Messung initialisieren und starten.
keine |
int main (void) { Init (); EncoderInit (); MotorDir (FWD, FWD); MotorSpeed (150, 150); while (1) ( // Dein Programm if (encoder [0] > 500) { EncoderStop (); MotorSpeed (0, 0); } } return 0; }
Definiert in Zeile 96 der Datei encoder_low.c.
00097 { 00098 /* 00099 Alle definierten Interrupts im Asuro sperren. 00100 */ 00101 cli(); 00102 00103 /* 00104 Port C als Input => dadurch gehen die Back-LED aus ... 00105 */ 00106 DDRC &= ~ ((1<<PC0) | (1<<PC1)); 00107 /* 00108 ... aber nun koennen die LED's am Rad eingeschaltet werden, und die 00109 Sensoren koennen gemessen werden. 00110 */ 00111 ODOMETRIE_LED_ON; 00112 00113 /* 00114 AD-Wandler einschalten, Parameter einstellen und Starten. (clk/128) 00115 Startet den ADC im 'free running'-Mode (ADFR). Das heisst, der Wandler 00116 nach einer Messung automatisch wieder ne startet. 00117 */ 00118 ADCSRA = (1<<ADEN) | (1<<ADFR) | (1<<ADIE) | (1<<ADSC) | (1<<ADPS0) | (1<<ADPS1) | (1<<ADPS2); 00119 00120 /* 00121 Linken Odometrie-Sensor auswaehlen. (AVCC ref. with external capacitor) 00122 */ 00123 ADMUX = (1<<ADLAR) | (1<<REFS0) | WHEEL_LEFT; 00124 00125 /* 00126 Odometrie im Interruptbetrieb weiter bearbeiten. 00127 */ 00128 autoencode = TRUE; 00129 00130 /* 00131 Alle definierten Interrupts im Asuro wieder zulassen. 00132 */ 00133 sei(); 00134 00135 /* 00136 Die Odometrie Hell-/Dunkel-Zaehler zuruecksetzen/initialisieren. 00137 */ 00138 EncoderSet (0, 0); 00139 }
void EncoderSet | ( | int | setl, | |
int | setr | |||
) |
Interruptbetriebene Odometriesensoren Werte vorbelegen.
[in] | setl | Wert fuer links |
[in] | setr | Wert fuer rechts |
Definiert in Zeile 222 der Datei encoder_low.c.
void EncoderStart | ( | void | ) |
Den Interrupt Betrieb der Odometriesensoren-Messung starten.
keine |
Definiert in Zeile 190 der Datei encoder_low.c.
00191 { 00192 autoencode = TRUE; 00193 }
void EncoderStop | ( | void | ) |
Den Interrupt Betrieb der Odometriesensoren-Messung anhalten.
keine |
Definiert in Zeile 166 der Datei encoder_low.c.
00167 { 00168 autoencode = FALSE; 00169 }
void FrontLED | ( | unsigned char | status | ) | [inline] |
Steuert die vorne, nach unten zeigende, Front-LED.
[in] | status | Schaltet die LED an bzw. aus. [ ON | OFF ] |
Definiert in Zeile 120 der Datei leds.c.
unsigned long Gettime | ( | void | ) |
return time since system start in ms
Da der Asuro keine Atomuhr hat, ist es die vergangene Zeit seitdem er eingeschaltet wurde.
Genauer: nachdem der Interrupt Timer2 aktiviert wurde.
keine |
Definiert in Zeile 78 der Datei time.c.
00079 { 00080 return ((timebase * 256) + count36kHz) / 36; 00081 }
void Go | ( | int | distance, | |
int | speed | |||
) |
Faehrt eine bestimmte Strecke mit einer bestimmten Geschwindigkeit. (Autor: stochri)
Benutzt die Odometrie Sensoren im Interrupt Betrieb.
Vor dem ersten Aufruf muss deshalb EncoderInit() aufgerufen werden.
[in] | distance | Distanz in mm (- rueckwaerts, + = vorwaerts) |
[in] | speed | Geschwindigkeit (Wertebereich 0...255) |
// Laesst den Asuro ein Quadrat von 200 mm fahren, // bei einer Geschwindigkeit von 150. EncoderInit (); for (int i = 0; i < 4; i++) { Go (200, 150); Turn (90, 150); }
Definiert in Zeile 112 der Datei encoder.c.
00115 { 00116 uint32_t enc_count; 00117 int tot_count = 0; 00118 int diff = 0; 00119 int l_speed = speed, r_speed = speed; 00120 00121 // calculation tics/mm 00122 enc_count=abs(distance)*10000L; 00123 enc_count/=MY_GO_ENC_COUNT_VALUE; 00124 EncoderSet(0,0); // reset encoder 00125 00126 MotorSpeed(l_speed,r_speed); 00127 if (distance<0) MotorDir(RWD,RWD); 00128 else MotorDir(FWD,FWD); 00129 00130 while (tot_count<enc_count) 00131 { 00132 tot_count += encoder[LEFT]; 00133 diff = encoder[LEFT] - encoder[RIGHT]; 00134 if (diff > 0) 00135 { //Left faster than right 00136 if ((l_speed > speed) || (r_speed > 244)) l_speed -= 10; 00137 else r_speed += 10; 00138 } 00139 if (diff < 0) 00140 { //Right faster than left 00141 if ((r_speed > speed) || (l_speed > 244)) r_speed -= 10; 00142 else l_speed += 10; 00143 } 00144 EncoderSet(0,0); // reset encoder 00145 MotorSpeed(l_speed,r_speed); 00146 Msleep(1); 00147 } 00148 MotorDir(BREAK,BREAK); 00149 Msleep(200); 00150 }
void Init | ( | void | ) |
Initialisiert die Hardware: Ports, A/D Wandler, Serielle Schnittstelle, PWM
Die Init Funktion muss von jeden Programm beim Start aufgerufen werden.
keine |
Definiert in Zeile 114 der Datei asuro.c.
00116 { 00117 /* 00118 Timer2, zum Betrieb mit der seriellen Schnittstelle, fuer die 00119 IR-Kommunikation auf 36 kHz eingestellt. 00120 */ 00121 TCCR2 = (1 << WGM20) | (1 << WGM21) | (1 << COM20) | (1 << COM21) | (1 << CS20); 00122 OCR2 = 0x91; // duty cycle fuer 36kHz 00123 TIMSK |= (1 << TOIE2); // 36kHz counter 00124 00125 /* 00126 Die serielle Schnittstelle wurde waerend der Boot-Phase schon 00127 programmiert und gestartet. Hier werden die Parameter auf 2400 1N8 gesetzt. 00128 */ 00129 UCSRA = 0x00; 00130 UCSRB = 0x00; 00131 UCSRC = 0x86; // 1 Stop Bit | No Parity | 8 Data Bit 00132 UBRRL = 0xCF; // 2400bps @ 8.00MHz 00133 00134 /* 00135 Datenrichtung der I/O-Ports festlegen. Dies ist durch die Beschaltung der 00136 Asuro-Hardware nicht aenderbar. 00137 Port B: Seriell Senden; Richtungsvorgabe Motor links; Takt fuer die 00138 Geschwindigkeit beider Motoren; Grueneanteil-Status-LED 00139 Port D: Richtungsvorgabe Motor rechts; Vordere LED; 00140 Odometrie-LED (Radsensor); Rotanteil-Status-LED 00141 */ 00142 DDRB = IRTX | LEFT_DIR | PWM | GREEN_LED; 00143 DDRD = RIGHT_DIR | FRONT_LED | ODOMETRIE_LED | RED_LED; 00144 00145 /* 00146 PWM-Kanaele OC1A und OC1B auf 8-Bit einstellen. 00147 Sie werden fuer die Geschwindigkeitsvorgaben der Motoren benutzt. 00148 */ 00149 TCCR1A = (1 << WGM10) | (1 << COM1A1) | (1 << COM1B1); 00150 TCCR1B = (1 << CS11); // tmr1-Timer mit MCU-Takt/8 betreiben. 00151 00152 /* 00153 Einstellungen des A/D-Wandlers auf MCU-Takt/64 00154 */ 00155 ADCSRA = (1 << ADEN) | (1 << ADPS2) | (1 << ADPS1); 00156 00157 /* 00158 Sonstige Vorbereitungen. 00159 - Alle LED's ausschalten 00160 - Motoren stoppen und schon mal auf Vorwaerts einstellen. 00161 - Globale Variable autoencoder ausschalten. 00162 */ 00163 ODOMETRIE_LED_OFF; 00164 FrontLED (OFF); 00165 BackLED (ON, ON); 00166 BackLED (OFF, OFF); 00167 StatusLED (GREEN); 00168 00169 MotorDir (FWD, FWD); 00170 MotorSpeed (0, 0); 00171 00172 autoencode = FALSE; 00173 00174 /* 00175 Funktion zum ALLGEMEINEN ZULASSEN von Interrupts. 00176 */ 00177 sei (); 00178 }
void LineData | ( | unsigned int * | data | ) |
Liest die Daten der beiden Linienverfolgungssensoren.
Die Linien-Beleuchtungs-LED kann sowohl an- als auch ausgeschaltet sein.
[out] | data | Zeiger auf die gelesenen Daten: data[0] linker Sensor (Bereich 0..1023) data[1] rechter Sensor (Bereich 0..1023) |
Definiert in Zeile 144 der Datei adc.c.
00146 { 00147 int ec_bak = autoencode; // Sichert aktuellen Zustand 00148 00149 /* 00150 Autoencode-Betrieb vom ADC-Wandler unterbinden. 00151 */ 00152 autoencode = FALSE; 00153 00154 /* 00155 Linken Linien-Sensor lesen 00156 */ 00157 ADMUX = (1 << REFS0) | IR_LEFT; // Referenz mit externer Kapazitaet 00158 Sleep (10); 00159 ADCSRA |= (1 << ADSC); // Starte AD-Wandlung 00160 while (!(ADCSRA & (1 << ADIF))) // Ende der AD-Wandlung abwarten 00161 ; 00162 ADCSRA |= (1 << ADIF); // AD-Interupt-Flag zuruecksetzen 00163 data [0] = ADCL + (ADCH << 8); // Ergebnis als 16-Bit-Wert 00164 00165 /* 00166 Rechten Linien-Sensor lesen 00167 */ 00168 ADMUX = (1 << REFS0) | IR_RIGHT; // Referenz mit externer Kapazitaet 00169 Sleep (10); 00170 ADCSRA |= (1 << ADSC); // Starte AD-Wandlung 00171 while (!(ADCSRA & (1 << ADIF))) // Ende der AD-Wandlung abwarten 00172 ; 00173 ADCSRA |= (1 << ADIF); // AD-Interupt-Flag zuruecksetzen 00174 data [1] = ADCL + (ADCH << 8); // Ergebnis als 16-Bit-Wert 00175 00176 /* 00177 Autoencode-Betrieb vom ADC-Wandler wiederherstellen. 00178 */ 00179 autoencode = ec_bak; 00180 }
void MotorDir | ( | unsigned char | left_dir, | |
unsigned char | right_dir | |||
) | [inline] |
Steuert die Drehrichtung der Motoren.
[in] | left_dir | Richtung des linken Motors [ FWD | RWD | BREAK | FREE ] |
[in] | right_dir | Richtung des rechten Motors [ FWD | RWD | BREAK | FREE ] |
Definiert in Zeile 126 der Datei motor_low.c.
00129 { 00130 PORTD = (PORTD &~ ((1 << PD4) | (1 << PD5))) | left_dir; 00131 PORTB = (PORTB &~ ((1 << PB4) | (1 << PB5))) | right_dir; 00132 }
void MotorSpeed | ( | unsigned char | left_speed, | |
unsigned char | right_speed | |||
) | [inline] |
Steuert die Geschwindigkeit der Motoren.
[in] | left_speed | Geschwindigkeit linker Motor (Bereich 0..255) |
[in] | right_speed | Geschwindigkeit rechter Motor (Bereich 0..255) |
// Setzt die Geschwindigkeit fuer den linken Motor // auf 150 und stoppt den rechten Motor. MotorSpeed (150, 0);
Definiert in Zeile 83 der Datei motor_low.c.
void Msleep | ( | int | dauer | ) |
Wartefunktion in ms.
Diese Funktion nutzt die Sleep()-Funktion um mit dem uebergeben Parameter
Pausen in ms-Einheiten zu erhalten.
[in] | dauer | Wartezeit in Millisekunden. |
// 1.5 Sekunde warten Msleep (1500);
Definiert in Zeile 143 der Datei time.c.
00145 { 00146 int z; 00147 for (z = 0; z < dauer; z++) 00148 Sleep (36); 00149 }
void OdometryData | ( | unsigned int * | data | ) |
Liest die Daten der beiden Odometriesensoren (Radsensoren).
Diese Funktion schaltet die Odometrie-LED's immer an.
Diese Funktion schaltet die Back-LED's immer aus.
[out] | data | Zeiger auf die gelesenen Daten: data[0] linker Sensor, data[1] rechter Sensor. (Bereich 0..1023) |
unsigned int data [2]; OdometryData (data); if (data [0] > data [1]) // 0 linker Sensor; 1 ist rechter Sensor fahre_links (); // Ein bisschen nach links fahren if (data [0] < data [1]) fahre_rechts (); // Ein bisschen nach rechts fahren BackLED (ON, OFF); // linke Back-LED mal wieder anschalten
Definiert in Zeile 221 der Datei adc.c.
00223 { 00224 int ec_bak = autoencode; // Sichert aktuellen Zustand 00225 00226 /* 00227 Autoencode-Betrieb vom ADC-Wandler unterbinden. 00228 */ 00229 autoencode = FALSE; 00230 /* 00231 Vorbereitung zum lesen der Odometrie-Sensoren. 00232 */ 00233 DDRC &= ~((1 << PC0) | (1 << PC1)); // Port auf Input=>Back-LEDs gehen aus 00234 ODOMETRIE_LED_ON; // Odometrie-LED's einschalten 00235 00236 /* 00237 Linken Odometrie-Sensor lesen 00238 */ 00239 ADMUX = (1 << REFS0) | WHEEL_LEFT; // Referenz mit externer Kapazitaet 00240 ADCSRA |= (1 << ADSC); // Starte AD-Wandlung 00241 while (!(ADCSRA & (1 << ADIF))) // Ende der AD-Wandlung abwarten 00242 ; 00243 ADCSRA |= (1 << ADIF); // AD-Interupt-Flag zuruecksetzen 00244 data [0] = ADCL + (ADCH << 8); // Ergebnis als 16-Bit-Wert 00245 00246 /* 00247 Rechten Odometrie-Sensor lesen 00248 */ 00249 ADMUX = (1 << REFS0) | WHEEL_RIGHT; // Referenz mit externer Kapazitaet 00250 ADCSRA |= (1 << ADSC); // Starte AD-Wandlung 00251 while (!(ADCSRA & (1 << ADIF))) // Ende der AD-Wandlung abwarten 00252 ; 00253 ADCSRA |= (1 << ADIF); // AD-Interupt-Flag zuruecksetzen 00254 data [1] = ADCL + (ADCH << 8); // Ergebnis als 16-Bit-Wert 00255 00256 /* 00257 Autoencode-Betrieb vom ADC-Wandler wiederherstellen. 00258 */ 00259 autoencode = ec_bak; 00260 }
unsigned char PollSwitch | ( | void | ) |
Tastsensor Abfrage im 'Polling-Betrieb'.
keine |
uint8_t t1, t2; unsigned char text [16]; while (1) { t1 = PollSwitch (); t2 = PollSwitch (); // 2x PollSwitch aufrufen und beide Rueckgabewerte auf Gleichheit ueberpruefen if (t1 && t2 && t1 == t2) // irgendeine Taste gedrueckt { itoa (t1, text, 10); // Tastenwert senden SerPrint (text); SerPrint ("\r\n"); // Zeilenvorschub } Msleep (500); // 0,5 sek warten }
Definiert in Zeile 83 der Datei switches.c.
00084 { 00085 unsigned int i; 00086 int ec_bak = autoencode; // Sichert aktuellen Zustand 00087 00088 /* 00089 Autoencode-Betrieb vom ADC-Wandler unterbinden. 00090 */ 00091 autoencode = FALSE; 00092 00093 DDRD |= SWITCHES; // Port-Bit SWITCHES als Output 00094 SWITCH_ON; // Port-Bit auf HIGH zur Messung 00095 ADMUX = (1 << REFS0) | SWITCH; // AVCC reference with external capacitor 00096 Sleep (10); 00097 00098 ADCSRA |= (1 << ADSC); // Starte AD-Wandlung 00099 while (!(ADCSRA & (1 << ADIF))) // Ende der AD-Wandlung abwarten 00100 ; 00101 ADCSRA |= (1 << ADIF); // AD-Interupt-Flag zuruecksetzen 00102 00103 i = ADCL + (ADCH << 8); // Ergebnis als 16-Bit-Wert 00104 00105 SWITCH_OFF; // Port-Bit auf LOW 00106 Sleep (5); 00107 00108 /* 00109 Autoencode-Betrieb vom ADC-Wandler wiederherstellen. 00110 */ 00111 autoencode = ec_bak; 00112 00113 /* 00114 Die Original Umrechenfunktion von Jan Grewe - DLR wurder ersetzt durch 00115 eine Rechnung ohne FLOAT-Berechnungen. 00116 return ((unsigned char) ((( 1024.0/(float)i - 1.0)) * 61.0 + 0.5)); 00117 00118 Wert 61L evtl. anpasssen, falls fuer K1 falsche Werte zurueckgegebn werden. 00119 */ 00120 return ((10240000L / (long)i - 10000L) * MY_SWITCH_VALUE + 5000L) / 10000; 00121 }
void PrintInt | ( | int | wert | ) |
Ausgabe eines Integer Wertes als String ueber die serielle Schnittstelle.
[in] | wert | Auszugebender Integer Wert (16Bit) |
2.60 - 28.09.2005 - m.a.r.v.i.n
strlen verwenden, anstelle fester Laenge
2.61 - 20.11.2006 - m.a.r.v.i.n
Initialisierung text String kann zu Fehler
beim Flashen mit RS232/IR Adapter fuehren
(Bug report von francesco)
2.70b- 07.01.2007 - m.a.r.v.i.n
SerPrint Funktion anstelle SerWrite verwenden
2.70rc2- 09.02.2007 - m.a.r.v.i.n
Text Laenge auf 7 erhoeht, fuer Ausgabe negativer Werte (Bug Report von HermannSW)
Definiert in Zeile 92 der Datei print.c.
00094 { 00095 char text [7]; // "-12345" 00096 00097 itoa (wert, text, 10); 00098 SerPrint (text); 00099 }
void PrintLong | ( | long | wert | ) |
Ausgabe eines Long Wertes als String ueber die serielle Schnittstelle.
[in] | wert | Auszugebender Long Wert (32Bit) |
Definiert in Zeile 131 der Datei print.c.
00133 { 00134 char text [12]; // '-'1234567891'\0' 00135 00136 ltoa (wert, text, 10); 00137 SerPrint (text); 00138 }
void SerPrint | ( | unsigned char * | data | ) |
Sendet einen null-terminierten String ueber die serielle Schnittstelle.
[in] | data | null-terminierter String |
// Beispiel fuer SerPrint SerPrint ("Hallo ASURO!\r\n");
Definiert in Zeile 200 der Datei print.c.
00202 { 00203 unsigned char i = 0; 00204 00205 while (data [i] != 0x00) 00206 UartPutc (data [i++]); 00207 }
void SerRead | ( | unsigned char * | data, | |
unsigned char | length, | |||
unsigned int | timeout | |||
) |
Lesen von Daten ueber die serielle Schnittstelle.
Die empfangenen Daten werden in der als Pointer uebergeben Variable data
dem Aufrufer zur verfuegung gestellt.
Der Aufrufer bestimmt ueber den Parameter Timeout, ob diese Funktion im
'blocking'- oder im 'nonblocking'-Mode laufen soll. Im 'blocking'-Mode
bleibt diese Funktion auf alle Faelle so lange aktiv, bis die, uber den
Parameter length, geforderte Anzahl Zeichen empfamgen wurde.
[out] | data | Zeiger auf die einzulesenden Daten |
[in] | length | Anzahl der zu lesenden Zeichen |
[in] | timeout | 0 = blockierender Mode Wird hier ein Wert groesser 0 uebergeben, wird nur eine gewisse Zeit lang versucht ein weiteres Zeichen ueber die Schnittstelle zu empfangen. Kommt in dieser Zeit kein weiteres Zeichen, wird im zurueckgegeben Parameter date das erste Zeichen auf 'T' gesetzt und die Funktion kehrt zum Aufrufer zurueck. Ansonsten wird die Funktion auf alle Faelle verlassen, wenn die als Parameter length geforderte Anzahl Zeichen empfangen werden konnten. |
Definiert in Zeile 135 der Datei uart.c.
00139 { 00140 unsigned char i = 0; 00141 unsigned int time = 0; 00142 00143 UCSRB = 0x10; // Empfaenger einschalten 00144 00145 if (timeout != 0) 00146 { 00147 /* 00148 Die Funktion wird auf alle Faelle, auch ohne empfangene Daten, wieder 00149 verlassen. --> nonblocking mode 00150 */ 00151 while (i < length && time++ < timeout) 00152 { 00153 if (UCSRA & 0x80) 00154 { 00155 data [i++] = UDR; 00156 time = 0; 00157 } 00158 } 00159 if (time > timeout) 00160 data [0] = 'T'; 00161 } 00162 else 00163 { 00164 /* 00165 Die Funktion wird auf alle Faelle erst nach dem Empfang von der 00166 vorgegebenen Anzahl Zeichen verlassen. blocking mode 00167 */ 00168 while (i < length) 00169 { 00170 if (UCSRA & 0x80) 00171 data [i++] = UDR; 00172 } 00173 } 00174 }
void SerWrite | ( | unsigned char * | data, | |
unsigned char | length | |||
) |
Senden von Daten ueber die serielle Schnittstelle.
Die zu senden Daten werden nicht als 0-terminierter C-String erwartet, sondern
es werden grundsaetzlich so viele Zeichen gesendet wie im 2.ten Parameter
angegeben werden.
[in] | data | Zu sendende Daten |
[in] | length | Die Anzahl der zu sendenden Zeichen. |
// Senden eines 'wunderbaren Textes' ueber die Schnittstelle. SerWrite ("Hello world", 11);
Definiert in Zeile 68 der Datei uart.c.
00071 { 00072 unsigned char i = 0; 00073 00074 UCSRB = 0x08; // Sender einschalten 00075 while (length > 0) // so lange noch Daten da sind 00076 { 00077 if (UCSRA & 0x20) 00078 { // warten, bis der Sendebuffer leer ist 00079 UDR = data[i++]; 00080 length --; 00081 } 00082 } 00083 while (!(UCSRA & 0x40)) // abwarten, bis das letzte Zeichen 00084 ; // uebertragen wurde. 00085 00086 for (i = 0; i < 0xFE; i++) // warten auf irgendwas; keiner weiss 00087 for (length = 0; length < 0xFE; length++); // wofuer 00088 }
void SetMotorPower | ( | int8_t | leftpwm, | |
int8_t | rightpwm | |||
) |
Steuert die Motorgeschwindigkeit und Drehrichtung der Motoren.
[in] | leftpwm | linker Motor (-rückwaerts, + vorwaerts) (Wertebereich -128...127) |
[in] | rightpwm | rechter Motor (-rückwaerts, + vorwaerts) (Wertebereich -128...127) |
// Setzt die Geschwindigkeit fuer den linken Motor auf 60 (vorwaerts), // und für den rechten Motor auf -60 (rueckwaerts) // Asuro soll auf der Stelle drehen. SetMotorPower (60, -600);
Definiert in Zeile 91 der Datei motor.c.
00094 { 00095 unsigned char left, right; 00096 00097 if (leftpwm < 0) // Ein negativer Wert fuehrt ... 00098 { 00099 left = RWD; // ... zu einer Rueckwaertsfahrt, ... 00100 leftpwm = -leftpwm; // aber immer positiv PWM-Wert 00101 } 00102 else 00103 left = FWD; // ... sonst nach vorne, ... 00104 if (leftpwm == 0) 00105 left = BREAK; // ... oder bei 0 zum Bremsen. 00106 00107 if (rightpwm < 0) 00108 { 00109 right = RWD; 00110 rightpwm = -rightpwm; 00111 } 00112 else 00113 right = FWD; 00114 if (rightpwm == 0) 00115 right = BREAK; 00116 00117 MotorDir (left, right); // Drehrichtung setzen 00118 00119 /* 00120 Die Geschwindigkeitsparameter mit 2 multiplizieren, da der Absolutwert 00121 der Parameter dieser Funktion nur genau die Haelfte von der MotorSpeed()- 00122 Funktion betraegt. 00123 */ 00124 MotorSpeed (leftpwm * 2, rightpwm * 2); 00125 }
void Sleep | ( | unsigned char | time36kHz | ) |
Wartefunktion.
Die maximale Wartezeit betraegt 7ms. Fuer laengere Wartezeiten siehe Msleep().
Diese Funktion nutzt den Timer 2-Interrupt um ein 'zeitgefuehl' zu erhalten.
Der Interrupt wird mit 36 kHz, durch die Init()-Funktion initialisiert,
aufgerufen und zaehlt dort die globale Variablen count36kHz weiter.
Diese Funktion nutzt diesen Zaehler und berechnet daraus mit dem uebergeben
Parameter den Zeitpunkt wann die Pausenzeit erreicht ist, Danach bricht sie
ab, und im Hauptprogramm ist eben eine Wartezeit eingelegt worden.
[in] | time36kHz | Wartezeit x/36kHz (sec) |
// 1 Millisekunde warten Sleep (36);
Definiert in Zeile 111 der Datei time.c.
00113 { 00114 unsigned char ziel = (time36kHz + count36kHz) & 0x00FF; 00115 00116 while (count36kHz != ziel) 00117 ; 00118 }
void Sound | ( | uint16_t | freq, | |
uint16_t | duration_msec, | |||
uint8_t | amplitude | |||
) |
Soundausgabe ueber die Motoren.
[in] | freq | Frequenz in Hz |
[in] | duration_msec | Laenge in Millisekunden |
[in] | amplitude | Amplitude |
// Laesst den Asuro einen Ton von 1kHz für eine 1/2 Sekunde // mit max. Amplitude (255) spielen. Sound (1000, 500, 255);
Definiert in Zeile 62 der Datei sound.c.
00066 { 00067 uint16_t n,k,wait_tics; 00068 uint32_t period_usec,dauer_usec; 00069 00070 period_usec = 1000000L / freq; 00071 dauer_usec = 1000 * duration_msec; 00072 k = dauer_usec / period_usec; 00073 00074 //IR Interuptfreq=36KHz 00075 //Wavefreq=18KHz 00076 00077 wait_tics = 18000 / freq; 00078 00079 MotorSpeed (amplitude, amplitude); 00080 00081 for (n = 0; n < k; n++) 00082 { 00083 MotorDir (FWD, FWD); 00084 Sleep (wait_tics); 00085 MotorDir (RWD, RWD); 00086 Sleep (wait_tics); 00087 } 00088 MotorSpeed (0, 0); 00089 }
void StartSwitch | ( | void | ) |
'Interrupt-Betrieb' zur Tastsensor Abfrage einschalten.
keine |
StartSwitch (); while (!switched) // wartet auf Tastendruck ; // an dieser Stelle kann mit Pollswitch geprüft werden // welche Taste gedrückt wurde, wenn nötig. switched = FALSE; // Vorbereitung für neuen Aufruf von StartSwitch()
Definiert in Zeile 156 der Datei switches.c.
00157 { 00158 SWITCH_OFF; // Port-Bit auf LOW 00159 DDRD &= ~SWITCHES; // Port-Bit SWITCHES als INPUT 00160 MCUCR &= ~((1 << ISC11) | (1 << ISC10)); // Low level erzeugt Interrupt 00161 GICR |= (1 << INT1); // Externen Interrupt 1 zulassen 00162 }
void StatusLED | ( | unsigned char | color | ) | [inline] |
Steuert die (lustige) mehrfarbige Status-LED.
[in] | color | Zu setzende Farbe. [ OFF | GREEN | RED | YELLOW ] Bei einem nicht definierten Wert von 'color' aendert sich nichts an der LED. |
Definiert in Zeile 68 der Datei leds.c.
00070 { 00071 if (color == OFF) 00072 { 00073 GREEN_LED_OFF; 00074 RED_LED_OFF; 00075 } 00076 if (color == GREEN) 00077 { 00078 GREEN_LED_ON; 00079 RED_LED_OFF; 00080 } 00081 if (color == YELLOW) 00082 { 00083 GREEN_LED_ON; 00084 RED_LED_ON; 00085 } 00086 if (color == RED) 00087 { 00088 GREEN_LED_OFF; 00089 RED_LED_ON; 00090 } 00091 }
void StopSwitch | ( | void | ) |
'Interrupt-Betrieb' zur Tastsensor Abfrage anhalten.
keine |
Definiert in Zeile 185 der Datei switches.c.
void Turn | ( | int | degree, | |
int | speed | |||
) |
Dreht um einen bestimmten Winkel mit einer bestimmten Geschwindigkeit. (Autor: stochri)
Benutzt die Odometrie Sensoren im Interrupt Betrieb.
Vor dem ersten Aufruf muss deshalb EncoderInit() aufgerufen werden.
[in] | degree | Winkel (- rechts, + links) |
[in] | speed | Geschwindigkeit (Wertebereich 0...255) |
In der globale Variable encoder, werden die Hell-/Dunkelwechsel der
Encoderscheiben im Interruptbetrieb gezaehlt.
// Laesst den Asuro ein Quadrat von 200 mm fahren, // bei einer Geschwindigkeit von 150. EncoderInit (); for (int i = 0; i < 4; i++) { Go (200, 150); Turn (90, 150); }
Definiert in Zeile 215 der Datei encoder.c.
00218 { 00219 long enc_count; 00220 enc_count=abs(degree)*MY_TURN_ENC_COUNT_VALUE; 00221 enc_count /= 360L; 00222 00223 int tot_count = 0; 00224 int diff = 0; 00225 int l_speed = speed, r_speed = speed; 00226 00227 00228 EncoderSet(0,0); // reset encoder 00229 00230 MotorSpeed(l_speed,r_speed); 00231 if (degree<0) MotorDir(RWD,FWD); 00232 else MotorDir(FWD,RWD); 00233 00234 while (tot_count<enc_count) 00235 { 00236 tot_count += encoder[LEFT]; 00237 diff = encoder[LEFT] - encoder[RIGHT]; 00238 if (diff > 0) 00239 { //Left faster than right 00240 if ((l_speed > speed) || (r_speed > 244)) l_speed -= 10; 00241 else r_speed += 10; 00242 } 00243 if (diff < 0) 00244 { //Right faster than left 00245 if ((r_speed > speed) || (l_speed > 244)) r_speed -= 10; 00246 else l_speed += 10; 00247 } 00248 EncoderSet(0,0); // reset encoder 00249 MotorSpeed(l_speed,r_speed); 00250 Msleep(1); 00251 } 00252 MotorDir(BREAK,BREAK); 00253 Msleep(200); 00254 }
void UartPutc | ( | unsigned char | zeichen | ) |
Sendet einen einzelnen Character über die serielle Schnittstelle.
[in] | zeichen | auszugebendes Zeichen |
Definiert in Zeile 166 der Datei print.c.
00168 { 00169 UCSRB = 0x08; // enable transmitter 00170 UCSRA |= 0x40; // clear transmitter flag 00171 while (!(UCSRA & 0x20)) // wait for empty transmit buffer 00172 ; 00173 UDR = zeichen; 00174 while (!(UCSRA & 0x40)) // Wait for transmit complete flag (TXC) 00175 ; 00176 }
volatile int autoencode |
Steuert, ob die Odometrie-Sensor Abfrage im Interrupt Betrieb laufen soll.
volatile unsigned char count36kHz |
int encoder[2] |
Odometriesensor Zaehler bei Interrupt Betrieb.
encoder[0] links, encoder[1] = rechts.
int switched |
Flag, dass der Interrupt SIG_INTERRUPT1 durch eine gedrueckte Taste
ausgeloesst wurde. 0 = keine Taste, 1 = Taste gedrueckt.
Kann im eigenen Programm immer abgefragt werden.
volatile unsigned long timebase |