summaryrefslogtreecommitdiffstats
path: root/source/ct-Bot/mcu
diff options
context:
space:
mode:
Diffstat (limited to 'source/ct-Bot/mcu')
-rw-r--r--source/ct-Bot/mcu/TWI_driver.c194
-rw-r--r--source/ct-Bot/mcu/adc.c70
-rw-r--r--source/ct-Bot/mcu/bot-2-pc.c111
-rw-r--r--source/ct-Bot/mcu/delay.c69
-rw-r--r--source/ct-Bot/mcu/display.c272
-rw-r--r--source/ct-Bot/mcu/ena.c128
-rw-r--r--source/ct-Bot/mcu/ir-rc5.c163
-rw-r--r--source/ct-Bot/mcu/led.c74
-rw-r--r--source/ct-Bot/mcu/mini-fat.c93
-rw-r--r--source/ct-Bot/mcu/mmc-low.S482
-rw-r--r--source/ct-Bot/mcu/mmc.c420
-rw-r--r--source/ct-Bot/mcu/motor-low.c242
-rw-r--r--source/ct-Bot/mcu/mouse.c183
-rw-r--r--source/ct-Bot/mcu/sensor-low.c229
-rw-r--r--source/ct-Bot/mcu/shift.c93
-rw-r--r--source/ct-Bot/mcu/srf10.c171
-rw-r--r--source/ct-Bot/mcu/timer-low.c87
-rw-r--r--source/ct-Bot/mcu/uart.c206
18 files changed, 3287 insertions, 0 deletions
diff --git a/source/ct-Bot/mcu/TWI_driver.c b/source/ct-Bot/mcu/TWI_driver.c
new file mode 100644
index 0000000..db4c0fb
--- /dev/null
+++ b/source/ct-Bot/mcu/TWI_driver.c
@@ -0,0 +1,194 @@
+/*
+ * c't-Sim - Robotersimulator fuer den c't-Bot
+ *
+ * This program is free software; you can redistribute it
+ * and/or modify it under the terms of the GNU General
+ * Public License as published by the Free Software
+ * Foundation; either version 2 of the License, or (at your
+ * option) any later version.
+ * This program is distributed in the hope that it will be
+ * useful, but WITHOUT ANY WARRANTY; without even the implied
+ * warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR
+ * PURPOSE. See the GNU General Public License for more details.
+ * You should have received a copy of the GNU General Public
+ * License along with this program; if not, write to the Free
+ * Software Foundation, Inc., 59 Temple Place, Suite 330, Boston,
+ * MA 02111-1307, USA.
+ *
+ */
+
+/*! @file TWI_driver.c
+ * @brief TWI-Treiber (I2C)
+ * @author Chris efstathiou hendrix@otenet.gr & Carsten Giesen (info@cnau.de)
+ * @date 08.04.06
+*/
+
+#ifdef MCU
+#include <avr/io.h>
+#include "TWI_driver.h"
+#include "global.h"
+
+
+/*!
+ * TWI Bus initialsieren
+ * @return Resultat der Aktion
+ */
+
+int8 Init_TWI(void){
+ TWAR = OWN_ADR; /*!< Eigenen Slave Adresse setzen */
+ TWBR = 12; /*!< Setze Baudrate auf 100 KHz */
+ /*!< 4 MHz xtal */
+ TWCR = (1<<TWEN); /*!< TWI-Interface einschalten */
+
+ return 1;
+}
+
+/*!
+ * TWI Buss schliesen
+ * @return Resultat der Aktion
+ */
+
+int8 Close_TWI(void){
+ TWCR = (0<<TWEN); /*!< TWI-Interface ausschalten */
+
+ return 0;
+}
+
+/*!
+ * Warte auf TWI interrupt
+ */
+
+void Wait_TWI_int(void){
+ while (!(TWCR & (1<<TWINT)))
+ ;
+}
+
+/*!
+ * Sende Start Sequence
+ * @return Resultat der Aktion
+ */
+
+uint8 Send_start(void){
+ TWCR = ((1<<TWINT)+(1<<TWSTA)+(1<<TWEN)); /*!< Sende START */
+
+ Wait_TWI_int(); /*!< Warte auf TWI interrupt */
+
+ if((TWSR != START)&&(TWSR != REP_START)) /*!< Ist der Status ein Anderer als Start (0x08) oder wiederholter Start (0x10) */
+ return TWSR; /*!< -> error und Rueckgabe TWSR. */
+ return SUCCESS; /*!< wenn OK Rueckgabe SUCCESS */
+}
+
+/*!
+ * Sende Stop Sequence
+ */
+
+void Send_stop(void){
+ TWCR = ((1<<TWEN)+(1<<TWINT)+(1<<TWSTO));
+}
+
+/*!
+ * Hier wird der eigentliche TWI-Treiber angesprochen
+ * @param *data_pack Container mit den Daten fuer den Treiber
+ * @return Resultat der Aktion
+ */
+uint8 Send_to_TWI(tx_type *data_pack){
+ uint8 state,i,j;
+
+ state = SUCCESS;
+
+ for(i=0;(data_pack[i].slave_adr != OWN_ADR)&&(state == SUCCESS);i++) {
+ state = Send_start();
+ if (state == SUCCESS)
+ state = Send_adr(data_pack[i].slave_adr);
+
+ /*!
+ * Abhaengig von W/R senden oder empfangen
+ */
+ if(!(data_pack[i].slave_adr & R)) {
+ if (state == SUCCESS){
+ /*!
+ * Wenn W bis alle Daten gesendet sind
+ */
+ for(j=0;((j<data_pack[i].size)&&(state == SUCCESS));j++)
+ state = Send_byte(data_pack[i].data_ptr[j]);
+ }
+ }
+ else{
+ if (state == MRX_ADR_NACK) {
+ state = Send_start();
+ }
+
+ if (state == SUCCESS){
+ /*!
+ * Wenn R bis alle Daten empfangen sind
+ */
+ for(j=0;((j<data_pack[i].size)&&(state == SUCCESS));j++){
+ /*!
+ * Wenn wir keine Daten mehr erwarten NACK senden
+ */
+ if(j == data_pack[i].size-1)
+ state = Get_byte(data_pack[i].data_ptr++,0);
+ else
+ state = Get_byte(data_pack[i].data_ptr++,1);
+ }
+ }
+ }
+ Send_stop();
+ }
+ Close_TWI();
+
+ return state;
+}
+
+/*!
+ * Sende ein Byte
+ * @param data das zu uebertragende Byte
+ */
+
+uint8 Send_byte(uint8 data){
+ Wait_TWI_int();
+ TWDR = data;
+ TWCR = ((1<<TWINT)+(1<<TWEN));
+ Wait_TWI_int();
+ if(TWSR != MTX_DATA_ACK)
+ return TWSR;
+ return SUCCESS;
+}
+
+/*!
+ * Sende Slave Adresse
+ * @param adr die gewuenschte Adresse
+ * @return Resultat der Aktion
+ */
+
+uint8 Send_adr(uint8 adr){
+ Wait_TWI_int();
+ TWDR = adr;
+ TWCR = ((1<<TWINT)+(1<<TWEN));
+ Wait_TWI_int();
+ if((TWSR != MTX_ADR_ACK)&&(TWSR != MRX_ADR_ACK))
+ return TWSR;
+ return SUCCESS;
+}
+
+/*!
+ * Empfange ein Byte
+ * @param *rx_ptr Container fuer die Daten
+ * @param last_byte Flag ob noch Daten erwartet werden
+ * @return Resultat der Aktion
+ */
+
+uint8 Get_byte(uint8 *rx_ptr,uint8 last_byte){
+ Wait_TWI_int();
+ if(last_byte)
+ TWCR = ((1<<TWINT)+(1<<TWEA)+(1<<TWEN));
+ else
+ TWCR = ((1<<TWINT)+(1<<TWEN));
+ Wait_TWI_int();
+ *rx_ptr = TWDR;
+ if(((TWSR == MRX_DATA_NACK)&&(last_byte == 0))||(TWSR == MRX_DATA_ACK))
+ return SUCCESS;
+ return TWSR;
+}
+
+#endif
diff --git a/source/ct-Bot/mcu/adc.c b/source/ct-Bot/mcu/adc.c
new file mode 100644
index 0000000..1fb63d1
--- /dev/null
+++ b/source/ct-Bot/mcu/adc.c
@@ -0,0 +1,70 @@
+/*
+ * c't-Bot
+ *
+ * This program is free software; you can redistribute it
+ * and/or modify it under the terms of the GNU General
+ * Public License as published by the Free Software
+ * Foundation; either version 2 of the License, or (at your
+ * option) any later version.
+ * This program is distributed in the hope that it will be
+ * useful, but WITHOUT ANY WARRANTY; without even the implied
+ * warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR
+ * PURPOSE. See the GNU General Public License for more details.
+ * You should have received a copy of the GNU General Public
+ * License along with this program; if not, write to the Free
+ * Software Foundation, Inc., 59 Temple Place, Suite 330, Boston,
+ * MA 02111-1307, USA.
+ *
+ */
+
+/*! @file adc.c
+ * @brief Routinen zum Einlesen der AnalogeingÄnge
+ * @author Benjamin Benz (bbe@heise.de)
+ * @date 26.12.05
+*/
+
+#ifdef MCU
+
+#include <avr/io.h>
+#include <avr/interrupt.h>
+//#include <avr/signal.h>
+
+#include "adc.h"
+
+/*!
+ * Initialisert den AD-Umsetzer.
+ * @param channel Für jeden Kanal, den man nutzen möchte,
+ * muss das entsprechende Bit in channel gesetzt sein
+ * Bit0 = Kanal 0 usw.
+ */
+void adc_init(uint8 channel){
+ DDRA &= ~ channel; // Pin als input
+ PORTA &= ~ channel; // Alle Pullups aus.
+}
+
+/*!
+ * Liest einen analogen Kanal aus
+ * @param channel Kanal - hex-Wertigkeit des Pins (0x01 fuer PA0; 0x02 fuer PA1, ..)
+ */
+uint16 adc_read(uint8 channel){
+ uint16 result = 0x00;
+
+ // interne Refernzspannung AVCC, rechts Ausrichtung
+ ADMUX= _BV(REFS0) ;//| _BV(REFS1); //|(0<<ADLAR);
+
+ ADMUX |= (channel & 0x07); // Und jetzt Kanal waehlen, nur single ended
+
+ ADCSRA= (1<<ADPS2) | (1<<ADPS1)| // prescale faktor= 128 ADC laeuft
+ (1 <<ADPS0) | // mit 14,7456MHz/ 128 = 115,2kHz
+ (1 << ADEN)| // ADC an
+ (1 << ADSC); // Beginne mit der Konvertierung
+
+ while ( (ADCSRA & (1<<ADSC)) != 0){asm volatile("nop");} //Warten bis konvertierung beendet
+ // Das sollte 25 ADC-Zyklen dauern!
+ // also 1/4608 s
+ result= ADCL;
+ result+=(ADCH <<8); // Ergebnis zusammenbauen
+
+ return result;
+}
+#endif
diff --git a/source/ct-Bot/mcu/bot-2-pc.c b/source/ct-Bot/mcu/bot-2-pc.c
new file mode 100644
index 0000000..377f117
--- /dev/null
+++ b/source/ct-Bot/mcu/bot-2-pc.c
@@ -0,0 +1,111 @@
+/*
+ * c't-Sim - Robotersimulator fuer den c't-Bot
+ *
+ * This program is free software; you can redistribute it
+ * and/or modify it under the terms of the GNU General
+ * Public License as published by the Free Software
+ * Foundation; either version 2 of the License, or (at your
+ * option) any later version.
+ * This program is distributed in the hope that it will be
+ * useful, but WITHOUT ANY WARRANTY; without even the implied
+ * warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR
+ * PURPOSE. See the GNU General Public License for more details.
+ * You should have received a copy of the GNU General Public
+ * License along with this program; if not, write to the Free
+ * Software Foundation, Inc., 59 Temple Place, Suite 330, Boston,
+ * MA 02111-1307, USA.
+ *
+ */
+
+/*! @file bot-2-pc.c
+ * @brief Verbindung zwischen c't-Bot und PC
+ * @author Benjamin Benz (bbe@heise.de)
+ * @date 28.2.06
+*/
+
+#include "ct-Bot.h"
+#include "command.h"
+#include "uart.h"
+#include "bot-2-pc.h"
+#include "sensor.h"
+#include "motor.h"
+#include "led.h"
+#include "mouse.h"
+#include "log.h"
+#include <stdlib.h>
+
+#ifdef MCU
+#ifdef BOT_2_PC_AVAILABLE
+
+/*!
+ * Diese Funktion nimmt die Daten vom PC entgegen
+ * und wertet sie aus. dazu nutzt er die Funktion command_evaluate()
+ */
+void bot_2_pc_listen(void){
+// LOG_DEBUG(("%d bytes recvd",uart_data_available()));
+ if (uart_data_available() >= sizeof(command_t)){
+// LOG_DEBUG(("%d bytes recvd",uart_data_available()));
+ if (command_read() ==0){
+ LOG_DEBUG(("command received"));
+ command_evaluate();
+ }else {
+ // TODO Fehlerbehandlung
+ }
+ }
+}
+
+/*!
+ * Diese Funktion informiert den PC ueber alle Sensor und Aktuator-Werte
+ */
+void bot_2_pc_inform(void){
+ int16 value1, value2;
+
+ command_write(CMD_AKT_MOT, SUB_CMD_NORM ,(int16*)&speed_l,(int16*)&speed_r,0);
+ value1=(int16)led;
+ command_write(CMD_AKT_LED, SUB_CMD_NORM ,&value1,&value1,0);
+
+ command_write(CMD_SENS_IR, SUB_CMD_NORM ,(int16*)&sensDistL,(int16*)&sensDistR,0);
+ command_write(CMD_SENS_ENC, SUB_CMD_NORM ,(int16*)&sensEncL,(int16*)&sensEncR,0);
+ command_write(CMD_SENS_BORDER, SUB_CMD_NORM ,(int16*)&sensBorderL,(int16*)&sensBorderR,0);
+ command_write(CMD_SENS_LINE, SUB_CMD_NORM ,(int16*)&sensLineL,(int16*)&sensLineR,0);
+
+ command_write(CMD_SENS_LDR, SUB_CMD_NORM ,(int16*)&sensLDRL,(int16*)&sensLDRR,0);
+
+ value1= (int16) sensTrans; value2=0;
+ command_write(CMD_SENS_TRANS, SUB_CMD_NORM ,&value1,&value2,0);
+
+ value1= (int16) sensDoor;
+ command_write(CMD_SENS_DOOR, SUB_CMD_NORM ,&value1,&value2,0);
+
+ #ifdef MAUS_AVAILABLE
+ value1=(int16)sensMouseDX;
+ value2=(int16)sensMouseDY;
+ command_write(CMD_SENS_MOUSE, SUB_CMD_NORM ,&value1,&value2,0);
+ #endif
+
+ value1=(int16)sensError; value2=0;
+ command_write(CMD_SENS_ERROR, SUB_CMD_NORM ,&value1,&value2,0);
+// command_write(CMD_SENS_RC5, SUB_CMD_NORM ,(int16*)&RC5_Code,&value2,0);
+}
+
+
+
+#include <stdio.h>
+#include <string.h>
+
+/*!
+ * Meldet den Bot am c't-Sim an
+ */
+void bot_2_pc_init(void){
+ int16 null =0;
+ uint8 j;
+
+ uart_init();
+
+ for(j=0;j<5;j++)
+ command_write(CMD_WELCOME, SUB_WELCOME_REAL ,&null,&null,0);
+}
+
+#endif
+#endif
+
diff --git a/source/ct-Bot/mcu/delay.c b/source/ct-Bot/mcu/delay.c
new file mode 100644
index 0000000..4d7ade3
--- /dev/null
+++ b/source/ct-Bot/mcu/delay.c
@@ -0,0 +1,69 @@
+/*
+ * c't-Bot
+ *
+ * This program is free software; you can redistribute it
+ * and/or modify it under the terms of the GNU General
+ * Public License as published by the Free Software
+ * Foundation; either version 2 of the License, or (at your
+ * option) any later version.
+ * This program is distributed in the hope that it will be
+ * useful, but WITHOUT ANY WARRANTY; without even the implied
+ * warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR
+ * PURPOSE. See the GNU General Public License for more details.
+ * You should have received a copy of the GNU General Public
+ * License along with this program; if not, write to the Free
+ * Software Foundation, Inc., 59 Temple Place, Suite 330, Boston,
+ * MA 02111-1307, USA.
+ *
+ */
+
+/*! @file delay.c
+ * @brief Hilfsroutinen
+ * @author Benjamin Benz (bbe@heise.de)
+ * @date 20.12.05
+*/
+
+#ifdef MCU
+
+#include "ct-Bot.h"
+
+#ifdef NEW_AVR_LIB
+ #include <util/delay.h>
+#else
+ #include <avr/delay.h>
+#endif
+
+#include "timer.h"
+
+/*!
+ * Warte 100 ms
+ */
+void delay_100ms(void){
+ char counter;
+ //wait (10 * 120000) cycles = wait 1200000 cycles
+ counter = 0;
+ while (counter != 5)
+ {
+ //wait (30000 x 4) cycles = wait 120000 cycles
+ _delay_loop_2(30000);
+ counter++;
+ }
+}
+
+
+/*!
+ * Delays for ms milliseconds
+ * @param ms Anzahl der Millisekunden
+ */
+void delay(uint16 ms){
+ uint32 start = TIMER_GET_TICKCOUNT_32;
+ if ((uint8)start != TIMER_GET_TICKCOUNT_8) start = TIMER_GET_TICKCOUNT_32;
+ uint32 ticksToWait = MS_TO_TICKS((uint32)ms);
+ uint32 now;
+ do {
+ now = TIMER_GET_TICKCOUNT_32;
+ if ((uint8)now != TIMER_GET_TICKCOUNT_8) now = TIMER_GET_TICKCOUNT_32;
+ } while (now-start < ticksToWait);
+
+}
+#endif
diff --git a/source/ct-Bot/mcu/display.c b/source/ct-Bot/mcu/display.c
new file mode 100644
index 0000000..f94ce16
--- /dev/null
+++ b/source/ct-Bot/mcu/display.c
@@ -0,0 +1,272 @@
+/*
+ * c't-Bot
+ *
+ * This program is free software; you can redistribute it
+ * and/or modify it under the terms of the GNU General
+ * Public License as published by the Free Software
+ * Foundation; either version 2 of the License, or (at your
+ * option) any later version.
+ * This program is distributed in the hope that it will be
+ * useful, but WITHOUT ANY WARRANTY; without even the implied
+ * warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR
+ * PURPOSE. See the GNU General Public License for more details.
+ * You should have received a copy of the GNU General Public
+ * License along with this program; if not, write to the Free
+ * Software Foundation, Inc., 59 Temple Place, Suite 330, Boston,
+ * MA 02111-1307, USA.
+ *
+ */
+
+/*! @file display.c
+ * @brief Routinen zur Displaysteuerung
+ * @author Benjamin Benz (bbe@heise.de)
+ * @date 20.12.05
+*/
+#include "global.h"
+#include "ct-Bot.h"
+
+#ifdef MCU
+#ifdef DISPLAY_AVAILABLE
+
+#include <avr/io.h>
+#ifdef NEW_AVR_LIB
+ #include <util/delay.h>
+#else
+ #include <avr/delay.h>
+#endif
+#include <stdarg.h>
+#include <stdio.h>
+#include "command.h"
+
+#include "display.h"
+#include "led.h"
+#include "delay.h"
+#include "shift.h"
+#include "display.h"
+
+/*! Puffergroesse fuer eine Zeile in bytes */
+#define DISPLAY_BUFFER_SIZE (DISPLAY_LENGTH + 1)
+
+uint8 display_update=0; /*!< Muss das Display aktualisiert werden? */
+#ifdef DISPLAY_SCREENS_AVAILABLE
+ #ifdef LOG_DISPLAY_AVAILABLE
+ uint8 display_screen=4; /*!< Muss das Display aktualisiert werden? */
+ #else
+ uint8 display_screen=0; /*!< Muss das Display aktualisiert werden? */
+ #endif
+#endif
+static char display_buf[DISPLAY_BUFFER_SIZE]; /*!< Pufferstring fuer Displayausgaben */
+
+#define DISPLAY_CLEAR 0x01 /*!< Kommando zum Löschen */
+#define DISPLAY_CURSORHOME 0x02 /*!< Kommando für den Cursor */
+
+#define DISPLAY_OUT 0x07 /*!< Output-Pins Display */
+#define DISPLAY_IN (1<<5) /*!< Input-Pins Display */
+
+#define DISPLAY_PORT PORTC /*!< Port an dem das Display hängt */
+#define DISPLAY_DDR DDRC /*!< Port an dem das Display hängt */
+#define DPC (DISPLAY_PORT & ~DISPLAY_OUT) /*!< Port des Displays */
+//#define DRC (DDRC & ~DISPLAY_PINS)
+
+//#define DISPLAY_READY_PINR PINC /*!< Port an dem das Ready-Flag des Display hängt */
+#define DISPLAY_READY_DDR DDRC /*!< Port an dem das Ready-Flag des Display hängt */
+#define DISPLAY_READY_PIN (1<<5) /*!< Pin an dem das Ready-Flag des Display hängt */
+
+/*! RS-Leitung
+ * legt fest, ob die Daten an das Display in den Textpuffer (RS=1) kommen
+ * oder als Steuercode interpretiert werden (RS=0)
+ */
+#define DISPLAY_RS (1<<0) /*!< Pin an dem die RS-Leitung des Displays hängt */
+
+/*! RW-Leitung
+ * legt fest, ob zum Display geschrieben wird (RW=0)
+ * oder davon gelesen wird (RW=1)
+ */
+#define DISPLAY_RW (1<<1) /*!< Pin an dem die RW-Leitung des Displays hängt */
+
+/*! Enable Leitung
+ * schaltet das Interface ein (E=1).
+ * Nur wenn Enable auf High-Pegel liegt, läßt sich das Display ansprechen
+ */
+#define DISPLAY_EN (1<<2) /*!< Pin an dem die EN-Leitung des Displays hängt */
+
+/*
+ * Im Moment der Low-High-Flanke von ENABLE liest das Dislplay
+ * die Werte von RS und R/W ein. Ist zu diesem Zeitpunkt R/W=0,
+ * dann liest das Display mit der folgenden High-Low-Flanke von ENABLE
+ * den Datenbus ein (Schreibzyklus).
+ * War aber R/W=1, dann legt das Display ein Datenword auf den
+ * Datenbus (Lese-Zyklus), solange bis die High-Low-Flanke von ENABLE
+ * das Interface wieder deaktiviert.
+ */
+
+/*!
+ * Übertrage Kommando an das Display
+ * @param cmd Kommando
+ */
+void display_cmd(uint8 cmd){ //ein Kommando cmd an das Display senden
+ uint8 i;
+ shift_data_out(cmd,SHIFT_LATCH,SHIFT_REGISTER_DISPLAY);
+ // Enable muss für mind. 450 ns High bleiben, bevor es fallen darf!
+ // ==> Also mind. 8 Zyklen warten
+ for (i=0; i<150; i++){
+ asm volatile("nop");
+ }
+ DISPLAY_PORT=DPC; // Alles zurück setzen ==> Fallende Flanke von Enable
+}
+
+
+/*!
+ * Ein Zeichen auf das Display schreiben
+ * @param data Das Zeichen
+ */
+void display_data(char data){ //ein Zeichen aus data in den Displayspeicher schreiben
+ uint8 i;
+ shift_data_out(data,SHIFT_LATCH,SHIFT_REGISTER_DISPLAY|DISPLAY_RS);
+
+ // Enable muss für mind. 450 ns High bleiben, bevor es fallen darf!
+ // ==> Also mind. 8 Zyklen warten
+ for (i=0; i<150; i++){
+ asm volatile("nop");
+ }
+ DISPLAY_PORT=DPC; // Alles zurück setzen ==> Fallende Flanke von Enable
+}
+
+/*!
+ * Löscht das ganze Display
+ */
+void display_clear(void){
+ display_cmd(DISPLAY_CLEAR); // Display loeschen, Cursor Home
+ #ifdef DISPLAY_REMOTE_AVAILABLE
+ command_write(CMD_AKT_LCD, SUB_LCD_CLEAR, NULL, NULL,0);
+ #endif
+}
+
+/*!
+ * Positioniert den Cursor
+ * @param row Zeile
+ * @param column Spalte
+ */
+void display_cursor (uint8 row, uint8 column) {
+ switch (row) {
+ case 1:
+ display_cmd (0x80 + column - 1);
+ break;
+ case 2:
+ display_cmd (0xc0 + column - 1);
+ break;
+ case 3:
+ display_cmd (0x94 + column - 1);
+ break;
+ case 4:
+ display_cmd (0xd4 + column - 1);
+ break;
+ default: break;
+ }
+
+ #ifdef DISPLAY_REMOTE_AVAILABLE
+ int16 r=row-1;
+ int16 c=column-1;
+ command_write(CMD_AKT_LCD, SUB_LCD_CURSOR, &c,&r,0);
+ #endif
+
+}
+
+/*!
+ * Init Display
+ */
+void display_init(void){
+ shift_init();
+
+ DISPLAY_DDR |= DISPLAY_OUT; // Ausgänge
+ DISPLAY_DDR &= ~DISPLAY_IN; // Eingänge
+
+ delay(12); // Display steht erst 10ms nach dem Booten bereit
+
+ // Register in 8-Bit-Modus 3x Übertragen, dazwischen warten
+ shift_data_out(0x38,SHIFT_LATCH,SHIFT_REGISTER_DISPLAY);
+ DISPLAY_PORT= DPC;
+ delay(5);
+ shift_data_out(0x38,SHIFT_LATCH,SHIFT_REGISTER_DISPLAY);
+ DISPLAY_PORT= DPC;
+ delay(5);
+ shift_data_out(0x38,SHIFT_LATCH,SHIFT_REGISTER_DISPLAY);
+ DISPLAY_PORT= DPC;
+ delay(5);
+
+ display_cmd(0x0f); //Display On, Cursor On, Cursor Blink
+
+ display_cmd(DISPLAY_CLEAR); // Display loeschen, Cursor Home
+
+ display_data('i');
+}
+
+/*!
+ * Zeigt einen String an
+ * @return -1 falls string zuende 0 falls Zeile (20 zeichen) zuende
+ */
+/*int display_string(char data[20]){
+ int i=0;
+
+ while ((i<20) && (data[i] != 0x00)){ // Abbruch, sobald ein Nullstring erreicht wird
+ // oder 20 Zeichen gesendet sind
+ display_data(data[i++]); // einzelnes Zeichen schicken
+ }
+
+ // return -1 falls string zuende, 0 falls zeile (20 zeichen) zuende
+ if (data[i]==0x00) return -1; else return 0;
+}
+*/
+
+/*!
+ * Schreibt einen String auf das Display.
+ * @param format Format, wie beim printf
+ * @param ... Variable Argumentenliste, wie beim printf
+ */
+void display_printf(char *format, ...) {
+
+ unsigned int run = 0;
+ va_list args;
+
+ /* Sicher gehen, das der zur Verfuegung stehende Puffer nicht
+ * ueberschrieben wird.
+ */
+ va_start(args, format);
+ vsnprintf(display_buf, DISPLAY_BUFFER_SIZE, format, args);
+ va_end(args);
+
+ /* Ausgeben bis Puffer leer ist */
+ while(display_buf[run] != '\0') {
+ display_data(display_buf[run]);
+ run++;
+ }
+
+ #ifdef DISPLAY_REMOTE_AVAILABLE
+ command_write_data(CMD_AKT_LCD, SUB_LCD_DATA, NULL, NULL, display_buf);
+ #endif
+
+ return;
+}
+
+/*
+void display_test(){
+ shift_init();
+
+// shift_data_out(0xAA,SHIFT_LATCH,SHIFT_REGISTER_DISPLAY);
+
+ display_cmd(0x38); //Display auf 8 Bit Betrieb
+ for(;;){}
+ display_cmd(0x0f); //Display On, Cursor On, Cursor Blink
+
+ display_cmd(DISPLAY_CLEAR); // Display l�schen, Cursor Home
+ display_cursor(2,2);
+
+ display_string("Hallo");
+ for(;;){
+ }
+}
+*/
+
+#endif
+
+#endif
diff --git a/source/ct-Bot/mcu/ena.c b/source/ct-Bot/mcu/ena.c
new file mode 100644
index 0000000..17ee859
--- /dev/null
+++ b/source/ct-Bot/mcu/ena.c
@@ -0,0 +1,128 @@
+/*
+ * c't-Bot
+ *
+ * This program is free software; you can redistribute it
+ * and/or modify it under the terms of the GNU General
+ * Public License as published by the Free Software
+ * Foundation; either version 2 of the License, or (at your
+ * option) any later version.
+ * This program is distributed in the hope that it will be
+ * useful, but WITHOUT ANY WARRANTY; without even the implied
+ * warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR
+ * PURPOSE. See the GNU General Public License for more details.
+ * You should have received a copy of the GNU General Public
+ * License along with this program; if not, write to the Free
+ * Software Foundation, Inc., 59 Temple Place, Suite 330, Boston,
+ * MA 02111-1307, USA.
+ *
+ */
+
+/*! @file ena.c
+ * @brief Routinen zur Steuerung der Enable-Leitungen
+ * @author Benjamin Benz (bbe@heise.de)
+ * @date 26.12.05
+*/
+
+#ifdef MCU
+
+#include <avr/io.h>
+#include "ena.h"
+#include "ct-Bot.h"
+#include "shift.h"
+#include "mouse.h"
+
+#ifdef ENA_AVAILABLE
+
+
+uint8 ena =0; /*!< Sichert den Zustand der Enable-Leitungen */
+
+/*!
+ * Initialisiert die Enable-Leitungen
+ */
+void ENA_init(){
+ DDRD |= 4;
+ shift_init();
+ ENA_set(0x00);
+}
+
+
+//void maus_sens_write(int8 adr, uint8 data);
+/*!
+ * Schaltet einzelne Enable-Transistoren an
+ * andere werden nicht beeinflusst
+ * Achtung, die Treiber-Transistoren sind Low-Aktiv!!!
+ * ENA_on schaltet einen Transistor durch
+ * Daher zieht es die entsprechende ENA_XXX-Leitung (mit Transistor) auf Low und NICHT auf High
+ * @param enable Bitmaske der anzuschaltenden LEDs
+ */
+void ENA_on(uint8 enable){
+// uint8 i;
+ // Maussensor und MMC-Karte haengen zusammen
+ if (enable == ENA_MOUSE_SENSOR){ // Maus sensor an, MMC aus
+
+// if ((ena & ENA_MMC) ==0){ // War die MMC-Karte an?
+ ena |= ENA_MMC; // MMC aus
+
+// PORTD |= 4; // Fliplops takten
+// PORTD &= ~4;
+//
+// for (i=0; i<200; i++){ // Ein paar flanken schocken, damit auch sicher danach ruhe ist
+// PORTB &= ~(1<<7);
+// PORTB |= (1<<7);
+// }
+// }
+
+ // Und dann den Maussensor an
+ ena &= ~ENA_MOUSE_SENSOR;
+ } else if (enable == ENA_MMC) { // Maus sensor aus, MMC aan
+ #ifdef MAUS_AVAILABLE
+ if ((ena & ENA_MOUSE_SENSOR) ==0){ // War der Maussensor an?
+ maus_sens_highZ(); // Der Maussensor muss die Datenleitung freigeben
+ ena |= ENA_MOUSE_SENSOR; // Maus aus
+ }
+ #endif
+ ena &= ~enable;
+ } else {
+ ena |= enable;
+ }
+
+ ENA_set(ena);
+
+ if ( (enable & (ENA_MOUSE_SENSOR | ENA_MMC)) != 0 ){
+ PORTD |= 4; // Fliplops takten
+ PORTD &= ~4;
+ }
+}
+
+/*!
+ * Schaltet einzelne Enable-Transistoren aus
+ * andere werden nicht beeinflusst
+ * Achtung, die Treiber-Transistoren sind Low-Aktiv!!!
+ * ENA_off schaltet einen Transistor ab
+ * Daher zieht es die entsprechende ENA_XXX-Leitung (mit Transistor) auf High und NICHT auf Low
+ * @param enable Bitmaske der anzuschaltenden LEDs
+ */
+void ENA_off(uint8 enable){
+ ena &= ~enable;
+ ENA_set(ena);
+
+ if ( (enable & (ENA_MOUSE_SENSOR | ENA_MMC)) != 0 ){
+ PORTD |= 4; // Fliplops takten
+ PORTD &= ~4;
+ }
+}
+
+/*!
+ * Schaltet die Enable-Transistoren
+ * Achtung, die Treiber-Transistoren sind Low-Aktiv!!!
+ * ENA_set bezieht sich auf die Transistor
+ * Daher zieht es die entsprechende ENA_XXX-Leitung auf ~enable
+ * @param LED Wert der gezeigt werden soll
+ */
+void ENA_set(uint8 enable){
+ ena=enable;
+ shift_data(~enable,SHIFT_REGISTER_ENA);
+}
+
+#endif
+#endif
diff --git a/source/ct-Bot/mcu/ir-rc5.c b/source/ct-Bot/mcu/ir-rc5.c
new file mode 100644
index 0000000..8bb17b0
--- /dev/null
+++ b/source/ct-Bot/mcu/ir-rc5.c
@@ -0,0 +1,163 @@
+/*
+ * c't-Bot
+ *
+ * This program is free software; you can redistribute it
+ * and/or modify it under the terms of the GNU General
+ * Public License as published by the Free Software
+ * Foundation; either version 2 of the License, or (at your
+ * option) any later version.
+ * This program is distributed in the hope that it will be
+ * useful, but WITHOUT ANY WARRANTY; without even the implied
+ * warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR
+ * PURPOSE. See the GNU General Public License for more details.
+ * You should have received a copy of the GNU General Public
+ * License along with this program; if not, write to the Free
+ * Software Foundation, Inc., 59 Temple Place, Suite 330, Boston,
+ * MA 02111-1307, USA.
+ *
+ */
+
+/*! @file ir-rc5.c
+ * @brief Routinen für die Dekodierung von RC5-Fernbedienungs-Codes
+ * @author Benjamin Benz (bbe@heise.de)
+ * @date 20.12.05
+*/
+
+// Infos ueber RC6: http://www.xs4all.nl/~sbp/knowledge/ir/rc6.htm
+// http://www.xs4all.nl/~sbp/knowledge/ir/ir.htm
+
+// ========================================================================
+// RC5 Infrarot-Empf�nger
+// ========================================================================
+#include "ct-Bot.h"
+#ifdef MCU
+#ifdef IR_AVAILABLE
+
+#include <avr/io.h>
+#include "ir-rc5.h"
+#include "timer.h"
+
+
+// -----------------------------------------------------------------------------
+// Timing
+// -----------------------------------------------------------------------------
+#define IR_SAMPLES_PER_BIT 10 /*!< 10 Samples per Bit */
+#define IR_SAMPLES_PER_BIT_EARLY 8 /*!< Flanke fr�hestens nach 8 Samples */
+#define IR_SAMPLES_PER_BIT_LATE 12 /*!< Flanke sp�testens nach 12 Samples */
+#define IR_SAMPLES_PER_BIT_MIN 3 /*!< Flanke vor 3 Samples -> paket verwerfen */
+#define IR_PAUSE_SAMPLES 250 /*!< Startbit ist erst nach 250 Samples ohne */
+ // Pegel�nderung g�ltig -- eigentlich m�sste
+ // man rund 500 Samples abwarten (50 x
+ // Bitzeit), doch weil der Samplez�hler ein
+ // Byte ist, beschr�nken wir uns hier auf ein
+ // Minimum von 250 Samples
+
+#define IR_PORT PORTB /*!< Port B */
+#define IR_DDR DDRB /*!< DDR of Port B */
+#define IR_PINR PINB /*!< Port B input */
+#define IR_PIN 1 /*!< Pin 1 */
+
+
+
+static byte ir_lastsample = 0; /*!< zuletzt gelesenes Sample */
+static byte ir_bittimer = 0; /*!< zählt die Aufrufe von ir_isr() */
+
+static uint16 ir_data_tmp = 0; /*!< RC5-Bitstream */
+static byte ir_bitcount = 0; /*!< anzahl gelesener bits */
+
+volatile uint16 ir_data = 0; /*!< letztes komplett gelesenes RC5-paket */
+
+/*!
+ * Interrupt Serviceroutine
+ * wird ca alle 177.8us aufgerufen
+ */
+void ir_isr(void) {
+ // sample lesen
+ byte sample = 1;
+
+ if ((IR_PINR & (1<<IR_PIN)) != 0) {
+ sample = 0;
+ }
+
+ // bittimer erhoehen (bleibt bei 255 stehen)
+ if (ir_bittimer<255) {
+ ir_bittimer++;
+ }
+
+ // flankenerkennung
+ if ( ir_lastsample != sample) {
+ if (ir_bittimer<=IR_SAMPLES_PER_BIT_MIN) {
+ // flanke kommt zu frueh: paket verwerfen
+ ir_bitcount=0;
+ } else {
+ // Startbit
+ if (ir_bitcount==0) {
+ if ( (sample==1) && (ir_bittimer>IR_PAUSE_SAMPLES) ) {
+ // Startbit speichern
+ ir_data_tmp = 1;
+ ir_bitcount++;
+ } else {
+ // error
+ ir_data_tmp = 0;
+ }
+
+ // bittimer-reset
+ ir_bittimer = 0;
+
+ // Bits 2..14: nur Flanken innerhalb des Bits beruecksichtigen
+ } else {
+ if (ir_bittimer >= IR_SAMPLES_PER_BIT_EARLY) {
+ if(ir_bittimer<=IR_SAMPLES_PER_BIT_LATE){
+ // Bit speichern
+ ir_data_tmp = (ir_data_tmp<<1) | sample;
+ ir_bitcount++;
+ } else {
+ // zu sp�t: paket verwerfen
+ ir_bitcount = 0;
+ }
+
+ // bittimer-reset
+ ir_bittimer = 0;
+ }
+ }
+ }
+
+ } else {
+ // keine flanke innerhalb bitzeit?
+ if (ir_bittimer > IR_SAMPLES_PER_BIT_LATE) {
+ // 14 bits gelesen?
+ if (ir_bitcount==14) {
+ ir_data = ir_data_tmp;
+ }
+ // paket verwerfen
+ ir_bitcount = 0;
+ }
+ }
+
+ // sample im samplepuffer ablegen
+ ir_lastsample = sample;
+
+
+}
+
+
+/*!
+ * IR-Daten lesen
+ * @return wert von ir_data, löscht anschliessend ir_data
+ */
+uint16 ir_read(void) {
+ uint16 retvalue = ir_data;
+ ir_data = 0;
+ return retvalue;
+}
+
+/*!
+ * Init IR-System
+ */
+void ir_init(void) {
+ IR_DDR &= ~IR_PIN; // Pin auf Input
+ IR_PORT |= IR_PIN; // Pullup an
+ timer_2_init(); // Für IR-Krams
+}
+#endif
+#endif
diff --git a/source/ct-Bot/mcu/led.c b/source/ct-Bot/mcu/led.c
new file mode 100644
index 0000000..8668106
--- /dev/null
+++ b/source/ct-Bot/mcu/led.c
@@ -0,0 +1,74 @@
+/*
+ * c't-Bot
+ *
+ * This program is free software; you can redistribute it
+ * and/or modify it under the terms of the GNU General
+ * Public License as published by the Free Software
+ * Foundation; either version 2 of the License, or (at your
+ * option) any later version.
+ * This program is distributed in the hope that it will be
+ * useful, but WITHOUT ANY WARRANTY; without even the implied
+ * warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR
+ * PURPOSE. See the GNU General Public License for more details.
+ * You should have received a copy of the GNU General Public
+ * License along with this program; if not, write to the Free
+ * Software Foundation, Inc., 59 Temple Place, Suite 330, Boston,
+ * MA 02111-1307, USA.
+ *
+ */
+
+/*! @file led.c
+ * @brief Routinen zur LED-Steuerung
+ * @author Benjamin Benz (bbe@heise.de)
+ * @date 26.12.05
+*/
+
+#ifdef MCU
+
+#include <avr/io.h>
+#include "led.h"
+#include "ct-Bot.h"
+#include "shift.h"
+
+#ifdef LED_AVAILABLE
+
+uint8 led=0;
+/*!
+ * Initialisiert die LEDs
+ */
+void LED_init(){
+ shift_init();
+ LED_off(LED_ALL);
+}
+
+/*!
+ * Schaltet einzelne LEDs an
+ * andere werden nicht beeinflusst
+ * @param LED Bitmaske der anzuschaltenden LEDs
+ */
+void LED_on(uint8 LED){
+ led |= LED;
+ LED_set(led);
+}
+
+/*!
+ * Schaltet einzelne LEDs aus
+ * andere werden nicht beeinflusst
+ * @param LED Bitmaske der anzuschaltenden LEDs
+ */
+void LED_off(uint8 LED){
+ led &= ~LED;
+ LED_set(led);
+}
+
+/*!
+ * Zeigt eine 8-Bit Variable mit den LEDs an
+ * @param LED Wert der gezeigt werden soll
+ */
+void LED_set(uint8 LED){
+ led=LED;
+ shift_data(led,SHIFT_REGISTER_LED);
+}
+
+#endif
+#endif
diff --git a/source/ct-Bot/mcu/mini-fat.c b/source/ct-Bot/mcu/mini-fat.c
new file mode 100644
index 0000000..9fa96ee
--- /dev/null
+++ b/source/ct-Bot/mcu/mini-fat.c
@@ -0,0 +1,93 @@
+/*
+ * c't-Bot
+ *
+ * This program is free software; you can redistribute it
+ * and/or modify it under the terms of the GNU General
+ * Public License as published by the Free Software
+ * Foundation; either version 2 of the License, or (at your
+ * option) any later version.
+ * This program is distributed in the hope that it will be
+ * useful, but WITHOUT ANY WARRANTY; without even the implied
+ * warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR
+ * PURPOSE. See the GNU General Public License for more details.
+ * You should have received a copy of the GNU General Public
+ * License along with this program; if not, write to the Free
+ * Software Foundation, Inc., 59 Temple Place, Suite 330, Boston,
+ * MA 02111-1307, USA.
+ *
+ */
+
+/*! @file mini-fat.c
+ * @brief Routinen zum Auffinden von markierten Files auf einer MMC-Karte.
+ * Dies ist keine vollstaendige FAT-Unterstuetzung, sondern sucht nur eien Datei, die mit einer 3-Zeichen Sequenz beginnt.
+ * @author Benjamin Benz (bbe@heise.de)
+ * @author Ulrich Radig (mail@ulrichradig.de) www.ulrichradig.de
+ * @date 07.11.06
+*/
+
+#include "ct-Bot.h"
+
+#ifdef MCU
+#ifdef MINI_FAT_AVAILABLE
+
+#include "mmc.h"
+#include "display.h"
+#include "mini-fat.h"
+
+/*!
+ * Sucht einen Block auf der MMC-Karte, dessen erste drei Bytes dem key entsprechen
+ * liefert dann den folgenden Block zurueck.
+ * Achtung das prinzip geht nur, wenn die Dateien nicht fragmentiert sind
+ * @param key 3 Byte zur Identifikation
+ * @param buffer Zeiger auf 512 Byte Puffer im SRAM
+ */
+uint32 mini_fat_find_block(const char* filename, uint8* buffer){
+
+ // Suche nach der Datei fuer die Katrte
+ int8 found = False;
+
+ uint32 card_size= mmc_get_size() >> 9; // groesse der Karte in Bloecken
+
+ #ifdef DISPLAY_AVAILABLE
+ display_cursor(2,1);
+ display_printf("Find %s: 0x",filename);
+ uint16 i=0, j=0;
+ #endif
+
+ uint32 block=0;
+ while(found == False && block < card_size){
+ #ifdef DISPLAY_AVAILABLE
+ display_cursor(2,13);
+ display_printf("%02x%04x",j,i );
+ if (i==65535)
+ j++;
+ i++;
+ #endif
+ mmc_read_sector(block++,buffer);
+ uint8 i;
+ for (i=0; i<MMC_FILENAME_MAX; i++)
+ if (filename[i] == '\0'){
+ found = True;
+ break;
+ } else if (filename[i] != buffer[i]) break;
+ }
+
+ if (found == False)
+ return 0xFFFFFFFF;
+
+ #ifdef DISPLAY_AVAILABLE
+ i= block & 0xFFFF;
+ j= (block >> 16) & 0xFFFF;
+ display_cursor(2,1);
+ display_printf("Found %s: 0x%02x%04x",filename,j,i);
+ #endif
+
+ // auf der Karte markieren, dass wir sie in der Hand hatten
+// buffer[3]++;
+// mmc_write_sector(block-1,buffer,0);
+
+ return block;
+}
+
+#endif
+#endif
diff --git a/source/ct-Bot/mcu/mmc-low.S b/source/ct-Bot/mcu/mmc-low.S
new file mode 100644
index 0000000..b4ef6f5
--- /dev/null
+++ b/source/ct-Bot/mcu/mmc-low.S
@@ -0,0 +1,482 @@
+/*
+ * c't-Bot
+ *
+ * This program is free software; you can redistribute it
+ * and/or modify it under the terms of the GNU General
+ * Public License as published by the Free Software
+ * Foundation; either version 2 of the License, or (at your
+ * option) any later version.
+ * This program is distributed in the hope that it will be
+ * useful, but WITHOUT ANY WARRANTY; without even the implied
+ * warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR
+ * PURPOSE. See the GNU General Public License for more details.
+ * You should have received a copy of the GNU General Public
+ * License along with this program; if not, write to the Free
+ * Software Foundation, Inc., 59 Temple Place, Suite 330, Boston,
+ * MA 02111-1307, USA.
+ *
+ */
+
+#ifdef MCU
+; Hinweis:
+; Sollte der Build-Prozess an dieser Datei scheitern, bitte auch die
+; Datei ".settings/org.eclipse.core.runtime.prefs" aus dem CVS laden, oder
+; selbst veranlassen, dass .S-Dateien ebenfalls vom gcc verarbeitet werden
+; (und nicht direkt vom Assembler).
+
+/*!
+ * @file mmc-low.s
+ * @brief Low-Level-Routinen zum Lesen/Schreiben einer MMC / SD-Card
+ * @author Timo Sandmann (mail@timosandmann.de)
+ * @date 14.11.2006
+ */
+
+#include "mmc-low.h"
+#include "ct-Bot.h"
+#include "ena.h"
+#ifdef MMC_AVAILABLE
+#include <avr/io.h>
+
+; Portkonfiguration umrechnen
+.equ PORT_OUT, _SFR_IO_ADDR(MMC_PORT_OUT)
+.equ PORT_IN, _SFR_IO_ADDR(MMC_PORT_IN)
+.equ DDR, _SFR_IO_ADDR(MMC_DDR)
+.equ SPI_CLK_MASK, _BV(SPI_CLK) ; 1<<SPI_CLK
+
+/*!
+ * Schreibt ein Byte an die Karte
+ * @param data Das zu sendende Byte
+ * @author Timo Sandmann (mail@timosandmann.de)
+ * @date 14.11.2006
+ */
+.global mmc_write_byte
+ .type mmc_write_byte, @function
+mmc_write_byte:
+ in r25, PORT_OUT ; MMC_PORT_OUT einlesen
+ cbr r25, SPI_CLK_MASK ; CLK auf low
+ bst r24, 7 ; Bit 7 der Daten
+ bld r25, SPI_DO ; Daten nach DO
+ out PORT_OUT, r25 ; Daten senden
+ sbi PORT_OUT, SPI_CLK ; CLK auf high
+ bst r24, 6 ; Bit 6 der Daten
+ bld r25, SPI_DO
+ out PORT_OUT, r25
+ sbi PORT_OUT, SPI_CLK
+ bst r24, 5 ; Bit 5 der Daten
+ bld r25, SPI_DO
+ out PORT_OUT, r25
+ sbi PORT_OUT, SPI_CLK
+ bst r24, 4 ; Bit 4 der Daten
+ bld r25, SPI_DO
+ out PORT_OUT, r25
+ sbi PORT_OUT, SPI_CLK
+ bst r24, 3 ; Bit 3 der Daten
+ bld r25, SPI_DO
+ out PORT_OUT, r25
+ sbi PORT_OUT, SPI_CLK
+ bst r24, 2 ; Bit 2 der Daten
+ bld r25, SPI_DO
+ out PORT_OUT, r25
+ sbi PORT_OUT, SPI_CLK
+ bst r24, 1 ; Bit 1 der Daten
+ bld r25, SPI_DO
+ out PORT_OUT, r25
+ sbi PORT_OUT, SPI_CLK
+ bst r24, 0 ; Bit 0 der Daten
+ bld r25, SPI_DO
+ out PORT_OUT, r25
+ sbi PORT_OUT, SPI_CLK
+ sbi PORT_OUT, SPI_DO ; DO auf high
+ ret
+
+/*!
+ * Liest ein Byte von der Karte
+ * @return Das gelesene Byte
+ * @author Timo Sandmann (mail@timosandmann.de)
+ * @date 14.11.2006
+ */
+.global mmc_read_byte
+ .type mmc_read_byte, @function
+mmc_read_byte:
+ in r19, PORT_OUT ; MMC_PORT_OUT einlesen
+ cbr r19, SPI_CLK_MASK ; CLK low
+ out PORT_OUT, r19 ; CLK auf low
+ mov r18, r19 ; CLK high
+ sbr r18, SPI_CLK_MASK
+ in r25, PORT_IN ; Bit 7 lesen
+ out PORT_OUT, r18 ; CLK Flanke
+ out PORT_OUT, r19
+ bst r25, SPI_DI ; Bit 7 speichern
+ bld r24, 7
+ in r25, PORT_IN ; Bit 6
+ out PORT_OUT, r18
+ out PORT_OUT, r19
+ bst r25, SPI_DI
+ bld r24, 6
+ in r25, PORT_IN ; Bit 5
+ out PORT_OUT, r18
+ out PORT_OUT, r19
+ bst r25, SPI_DI
+ bld r24, 5
+ in r25, PORT_IN ; Bit 4
+ out PORT_OUT, r18
+ out PORT_OUT, r19
+ bst r25, SPI_DI
+ bld r24, 4
+ in r25, PORT_IN ; Bit 3
+ out PORT_OUT, r18
+ out PORT_OUT, r19
+ bst r25, SPI_DI
+ bld r24, 3
+ in r25, PORT_IN ; Bit 2
+ out PORT_OUT, r18
+ out PORT_OUT, r19
+ bst r25, SPI_DI
+ bld r24, 2
+ in r25, PORT_IN ; Bit 1
+ out PORT_OUT, r18
+ out PORT_OUT, r19
+ bst r25, SPI_DI
+ bld r24, 1
+ in r25, PORT_IN ; Bit 0
+ out PORT_OUT, r18
+ bst r25, SPI_DI
+ bld r24, 0
+ clr r25 ; return ist in 8 Bit und wir sind ordentlich ;)
+ ret
+
+/*!
+ * Schaltet die Karte aktiv und checkt dabei die Initialisierung
+ * @return 0 wenn alles ok ist, 1 wenn Init nicht moeglich
+ * @author Timo Sandmann (mail@timosandmann.de)
+ * @date 09.12.2006
+ */
+.global mmc_enable
+ .type mmc_enable, @function
+mmc_enable:
+ lds r24, mmc_init_state ; Initialisierung der Karte checken
+ tst r24
+ breq 1f
+ call mmc_init ; neu initialisieren
+ tst r24
+ breq 1f
+ ret ; kein Init moeglich => Fehler
+ 1:
+ ldi r24, lo8(ENA_MMC) ; Karte aktiv schalten
+ call ENA_on
+ ldi r24, lo8(ENA_MMC) ; Karte inaktiv schalten
+ call ENA_off
+ cbi DDR, SPI_DI ; DI auf input
+ sbi DDR, SPI_DO ; DO auf output
+ ldi r24, lo8(-1)
+ call mmc_write_byte ; sendet 8 CLK-Flanken
+ ldi r24, lo8(ENA_MMC) ; Karte aktiv schalten
+ call ENA_on
+ ldi r24, 0
+ ret ; alles ok
+
+/*!
+ * Schreibt einen 512-Byte Sektor auf die Karte
+ * @param addr Nummer des 512-Byte Blocks
+ * @param Buffer Zeiger auf den Puffer
+ * @param async 0: synchroner, 1: asynchroner Aufruf, siehe MMC_ASYNC_WRITE in mmc-low.h
+ * @return 0 wenn alles ok ist, 1 wenn Init nicht moeglich oder Timeout vor / nach Kommando 24, 2 wenn Timeout bei busy
+ * @author Timo Sandmann (mail@timosandmann.de)
+ * @date 16.11.2006
+ */
+.global mmc_write_sector
+ .type mmc_write_sector, @function
+mmc_write_sector:
+ push r13 ; allgemeine Register retten
+ push r14
+ push r15
+ push r16
+ push r28
+ push r29
+ movw r14, r22 ; Byte 1 und 2 von Parameter addr sichern
+ mov r16, r24 ; Byte 3 von Parameter addr sichern
+ movw r28, r20 ; Parameter Buffer sichern
+ mov r13, r18 ; Parameter async sichern
+ call mmc_enable ; Karte aktiv schalten
+ tst r24
+ breq 1f
+ rjmp 4f ; Karte kann nicht initialisiert werden => Fehler
+ 1:
+ lsl r14 ; Block in Bytes umrechnen
+ rol r15
+ rol r16
+#if MMC_ASYNC_WRITE == 1
+ clr r27 ; r27 = 0
+ 1:
+ clr r26 ; r26 = 0
+ 2:
+ call mmc_read_byte ; warten, ob Karte noch busy
+ cpi r24, lo8(-1)
+ breq 3f ; == 0xff?
+ dec r26 ; r26--
+ brne 2b ; r26 == 0?
+ dec r27 ; r27--
+ brne 1b ; r27 == 0?
+ rjmp 4f ; Timeout :(
+ 3:
+#endif
+ ldi r24, 88 ; Kommando 24 zum Schreiben eines Blocks senden, Byte 0
+ call mmc_write_byte
+ mov r24, r16 ; Byte 1
+ call mmc_write_byte
+ mov r24, r15 ; Byte 2
+ call mmc_write_byte
+ mov r24, r14 ; Byte 3
+ call mmc_write_byte
+ ldi r24, 0 ; Byte 4
+ call mmc_write_byte
+ ldi r24, lo8(-1) ; Byte 5 (CRC)
+ call mmc_write_byte
+ ldi r26, lo8(-1) ; Timeout nach 256 Versuchen
+ 1:
+ call mmc_read_byte
+ cpi r24, lo8(-1) ; !0xff = Antwort
+ brne 3f
+ dec r26 ; r26--
+ brne 1b
+ 3:
+ tst r24 ; Fehler oder Abbruch durch Timeout?
+ breq 1f
+ rjmp 4f ; Return-Code 1
+ 1:
+ ldi r24, lo8(-2) ; Start-Byte an Karte senden
+ call mmc_write_byte
+ in r26, PORT_OUT ; MMC_PORT_OUT einlesen
+ cbr r26, SPI_CLK_MASK ; CLK auf low
+ ldi r18, 2 ; r18 = 2
+ clr r27 ; r27 = 0
+ 1:
+ ld r25, Y+ ; Byte aus SRAM lesen
+ bst r25, 7 ; Bit 7
+ bld r26, SPI_DO
+ out PORT_OUT, r26 ; Daten senden
+ sbi PORT_OUT, SPI_CLK ; CLK auf high
+ bst r25, 6 ; Bit 6
+ bld r26, SPI_DO
+ out PORT_OUT, r26
+ sbi PORT_OUT, SPI_CLK
+ bst r25, 5 ; Bit 5
+ bld r26, SPI_DO
+ out PORT_OUT, r26
+ sbi PORT_OUT, SPI_CLK
+ bst r25, 4 ; Bit 4
+ bld r26, SPI_DO
+ out PORT_OUT, r26
+ sbi PORT_OUT, SPI_CLK
+ bst r25, 3 ; Bit 3
+ bld r26, SPI_DO
+ out PORT_OUT, r26
+ sbi PORT_OUT, SPI_CLK
+ bst r25, 2 ; Bit 2
+ bld r26, SPI_DO
+ out PORT_OUT, r26
+ sbi PORT_OUT, SPI_CLK
+ bst r25, 1 ; Bit 1
+ bld r26, SPI_DO
+ out PORT_OUT, r26
+ sbi PORT_OUT, SPI_CLK
+ bst r25, 0 ; Bit 0
+ bld r26, SPI_DO
+ out PORT_OUT, r26
+ sbi PORT_OUT, SPI_CLK
+ inc r27 ; r27++
+ breq 2f ; r27 == 0?
+ rjmp 1b
+ 2:
+ dec r18 ; r18--
+ breq 3f ; r18 == 0?
+ rjmp 1b
+ 3:
+ sbi PORT_OUT, SPI_DO ; DO auf high
+ call mmc_write_byte ; crc-Dummy schreiben
+ call mmc_write_byte
+#if MMC_ASYNC_WRITE == 1
+ tst r13 ; wollten wir asynchron schreiben?
+ brne 3f ; wenn ja, nicht auf busy warten
+#endif
+ 1:
+ clr r28 ; r28 = 0
+ 2:
+ call mmc_read_byte ; warten, ob Karte noch busy
+ cpi r24, lo8(-1)
+ breq 3f ; == 0xff?
+ dec r28 ; r28--
+ brne 2b ; r28 == 0?
+ dec r27 ; r27--
+ brne 1b ; r27 == 0?
+ rjmp 5f ; Timeout :(
+ 3:
+ ldi r16, 0 ; Alles ok, also Return-Code 0 laden :)
+ rjmp 6f
+ 4:
+ ldi r16, 1 ; Fehler, Return-Code 1 laden
+ sts mmc_init_state, r16 ; Initstatus auf Fehler setzen
+ rjmp 6f
+ 5:
+ ldi r16, 2 ; Fehler, Return-Code 2 laden
+ sts mmc_init_state, r16 ; Initstatus auf Fehler setzen
+ 6:
+ ldi r24, lo8(ENA_MMC) ; Karte inaktiv schalten
+ call ENA_off
+ mov r24, r16 ; Return-Code laden
+ ldi r25, 0
+ pop r29 ; allgemeine Register wiederherstellen
+ pop r28
+ pop r16
+ pop r15
+ pop r14
+ pop r13
+ ret
+
+/*!
+ * Liest einen Block von der Karte
+ * @param addr Nummer des 512-Byte Blocks
+ * @param Buffer Puffer von mindestens 512 Byte
+ * @return 0 wenn alles ok ist, 1 wenn Init nicht moeglich oder Timeout vor / nach Kommando 17
+ * @author Timo Sandmann (mail@timosandmann.de)
+ * @date 17.11.2006
+ */
+.global mmc_read_sector
+ .type mmc_read_sector, @function
+mmc_read_sector:
+ push r14 ; allgemeine Register retten
+ push r15
+ push r16
+ push r28
+ push r29
+ movw r14, r22 ; Byte 1 und 2 von Parameter addr sichern
+ mov r16, r24 ; Byte 3 von Parameter addr sichern
+ movw r28, r20 ; Parameter Buffer sichern
+ call mmc_enable ; Karte aktiv schalten
+ tst r24
+ breq 1f
+ rjmp 5f ; Karte kann nicht initialisiert werden => Fehler
+ 1:
+ lsl r14 ; Block in Bytes umrechnen
+ rol r15
+ rol r16
+#if MMC_ASYNC_WRITE == 1
+ clr r27 ; r27 = 0
+ 1:
+ clr r26 ; r26 = 0
+ 2:
+ call mmc_read_byte ; warten, ob Karte noch busy
+ cpi r24, lo8(-1)
+ breq 3f ; == 0xff?
+ dec r26 ; r26--
+ brne 2b ; r26 == 0?
+ dec r27 ; r27--
+ brne 1b ; r27 == 0?
+ rjmp 5f ; Timeout :(
+ 3:
+#endif
+ ldi r24, 81 ; Kommando 17 zum Lesen eines Blocks senden, Byte 0
+ call mmc_write_byte
+ mov r24, r16 ; Byte 1
+ call mmc_write_byte
+ mov r24, r15 ; Byte 2
+ call mmc_write_byte
+ mov r24, r14 ; Byte 3
+ call mmc_write_byte
+ ldi r24, 0 ; Byte 4
+ call mmc_write_byte
+ ldi r24,lo8(-1) ; Byte 5 (CRC)
+ call mmc_write_byte
+ ldi r16, lo8(-1) ; Timeout bei 256
+ 1:
+ call mmc_read_byte
+ cpi r24, lo8(-2) ; 0xfe = Startbyte
+ breq 2f
+ call mmc_read_byte ; Noch ein Versuch
+ cpi r24, lo8(-2)
+ breq 2f
+ dec r16
+ brne 1b
+ rjmp 4f ; Timeout, also abbrechen :(
+ 2:
+ in r20, PORT_OUT ; MMC_PORT_OUT einlesen
+ cbr r20, SPI_CLK_MASK ; CLK low
+ out PORT_OUT, r20 ; CLK auf low
+ mov r19, r20 ; CLK high
+ sbr r19, SPI_CLK_MASK
+ ldi r18, 2 ; Schleifenzaehler laden
+ clr r24
+ 1:
+ in r26, PORT_IN ; Bit 7 lesen
+ out PORT_OUT, r19 ; CLK Flanke
+ out PORT_OUT, r20
+ bst r26, SPI_DI ; Bit 7 speichern
+ bld r25, 7
+ in r26, PORT_IN ; Bit 6
+ out PORT_OUT, r19
+ out PORT_OUT, r20
+ bst r26, SPI_DI
+ bld r25, 6
+ in r26, PORT_IN ; Bit 5
+ out PORT_OUT, r19
+ out PORT_OUT ,r20
+ bst r26, SPI_DI
+ bld r25, 5
+ in r26, PORT_IN ; Bit 4
+ out PORT_OUT, r19
+ out PORT_OUT, r20
+ bst r26, SPI_DI
+ bld r25, 4
+ in r26, PORT_IN ; Bit 3
+ out PORT_OUT, r19
+ out PORT_OUT, r20
+ bst r26, SPI_DI
+ bld r25, 3
+ in r26, PORT_IN ; Bit 2
+ out PORT_OUT, r19
+ out PORT_OUT, r20
+ bst r26, SPI_DI
+ bld r25, 2
+ in r26, PORT_IN ; Bit 1
+ out PORT_OUT, r19
+ out PORT_OUT, r20
+ bst r26, SPI_DI
+ bld r25, 1
+ in r26, PORT_IN ; Bit 0
+ out PORT_OUT, r19
+ out PORT_OUT, r20
+ bst r26, SPI_DI
+ bld r25, 0
+ st Y+, r25 ; Byte ins SRAM kopieren
+ inc r24 ; r24++
+ breq 2f ; r24 == 0?
+ rjmp 1b
+ 2:
+ dec r18 ; r18--
+ breq 3f ; r18 == 0?
+ rjmp 1b
+ 3:
+ out PORT_OUT, r19 ; CLK auf high
+ call mmc_read_byte ; crc-Dummy lesen
+ call mmc_read_byte
+ 4:
+ tst r16 ; Abbruch durch Timeout?
+ breq 5f ; r27 == 0?
+ ldi r16, 0 ; Alles ok, also Return-Code 0 laden :)
+ rjmp 6f
+ 5:
+ ldi r16, 1 ; Fehler, also Return-Code 1 laden
+ sts mmc_init_state, r16 ; Initstatus auf Fehler setzen
+ 6:
+ ldi r24, lo8(ENA_MMC) ; Karte inaktiv schalten
+ call ENA_off
+ mov r24, r16 ; Return-Code laden
+ ldi r25, 0
+ pop r29 ; allgemeine Register wiederherstellen
+ pop r28
+ pop r16
+ pop r15
+ pop r14
+ ret
+#endif // MMC_AVAILABLE
+#endif // MCU
diff --git a/source/ct-Bot/mcu/mmc.c b/source/ct-Bot/mcu/mmc.c
new file mode 100644
index 0000000..3dbf183
--- /dev/null
+++ b/source/ct-Bot/mcu/mmc.c
@@ -0,0 +1,420 @@
+/*
+ * c't-Bot
+ *
+ * This program is free software; you can redistribute it
+ * and/or modify it under the terms of the GNU General
+ * Public License as published by the Free Software
+ * Foundation; either version 2 of the License, or (at your
+ * option) any later version.
+ * This program is distributed in the hope that it will be
+ * useful, but WITHOUT ANY WARRANTY; without even the implied
+ * warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR
+ * PURPOSE. See the GNU General Public License for more details.
+ * You should have received a copy of the GNU General Public
+ * License along with this program; if not, write to the Free
+ * Software Foundation, Inc., 59 Temple Place, Suite 330, Boston,
+ * MA 02111-1307, USA.
+ *
+ */
+
+/*! @file mmc.c
+ * @brief Routinen zum Auslesen/Schreiben einer MMC-Karte
+ * @author Benjamin Benz (bbe@heise.de)
+ * @author Ulrich Radig (mail@ulrichradig.de) www.ulrichradig.de
+ * @date 07.11.06
+ */
+
+
+/* Die (zeitkritischen) Low-Level-Funktionen read_ und write_byte bzw. _sector liegen jetzt
+ * in mmc-low.S. Der Assembler-Code ist a) wesentlich schneller und macht b) das Timing
+ * unabhaengig vom verwendeten Compiler.
+ * Die Portkonfiguration findet sich in mmc-low.h.
+ */
+
+//TODO: * kleine Doku machen
+
+#include "ct-Bot.h"
+
+#ifdef MCU
+#ifdef MMC_AVAILABLE
+
+#include "mmc.h"
+#include <avr/io.h>
+#include "ena.h"
+#include "timer.h"
+#include "display.h"
+
+#include <avr/interrupt.h>
+#ifndef NEW_AVR_LIB
+ #include <avr/signal.h>
+#endif
+
+#include "mmc-low.h"
+#include "mmc-vm.h"
+#include <stdlib.h>
+
+#define MMC_Disable() ENA_off(ENA_MMC);
+#define MMC_Enable() ENA_on(ENA_MMC);
+
+#define MMC_prepare() { MMC_DDR &=~(1<<SPI_DI); MMC_DDR |= (1<<SPI_DO); }
+
+volatile uint8 mmc_init_state=1; /*!< Initialierungsstatus der Karte, 0: ok, 1: Fehler */
+
+/*!
+ * Checkt die Initialisierung der Karte
+ * @return 0, wenn initialisiert
+ */
+inline uint8 mmc_get_init_state(void){
+ return mmc_init_state;
+}
+
+/*!
+ * Schreibt ein Byte an die Karte
+ * @param data Das zu sendende Byte
+ * @author Timo Sandmann (mail@timosandmann.de)
+ * @date 14.11.2006
+ * @see mmc-low.s
+ */
+void mmc_write_byte(uint8 data);
+
+
+/*!
+ * Liest ein Byte von der Karte
+ * @return Das gelesene Byte
+ * @author Timo Sandmann (mail@timosandmann.de)
+ * @date 14.11.2006
+ * @see mmc-low.s
+ */
+ uint8 mmc_read_byte(void);
+
+
+/*!
+ * Schickt ein Kommando an die Karte
+ * @param cmd Ein Zeiger auf das Kommando
+ * @return Die Antwort der Karte oder 0xFF im Fehlerfall
+ */
+uint8 mmc_write_command(uint8 *cmd){
+ uint8 result = 0xff;
+ uint16 timeout = 0;
+
+ mmc_enable(); // MMC / SD-Card aktiv schalten
+
+ // sendet 6 Byte Kommando
+ uint8 i;
+ for (i=0; i<6; i++) // sendet 6 Byte Kommando zur MMC/SD-Karte
+ mmc_write_byte(*cmd++);
+
+ // Wartet auf eine gueltige Antwort von der MMC/SD-Karte
+ while (result == 0xff){
+ result = mmc_read_byte();
+ if (timeout++ > MMC_TIMEOUT)
+ break; // Abbruch da die MMC/SD-Karte nicht antwortet
+ }
+
+ return result;
+}
+
+
+/*!
+ * Initialisiere die SD/MMC-Karte
+ * @return 0 wenn allles ok, sonst Nummer des Kommandos bei dem abgebrochen wurde
+ */
+uint8 mmc_init(void){
+ uint16 timeout = 0;
+ uint8 i;
+ mmc_init_state = 0;
+
+ // Konfiguration des Ports an der die MMC/SD-Karte angeschlossen wurde
+ MMC_CLK_DDR |= _BV(SPI_CLK); // Setzen von Pin MMC_Clock auf Output
+
+ MMC_prepare();
+
+ MMC_Enable();
+ MMC_Disable();
+
+ // Initialisiere MMC/SD-Karte in den SPI-Mode
+ for (i=0; i<0x0f; i++) // Sendet min 74+ Clocks an die MMC/SD-Karte
+ mmc_write_byte(0xff);
+
+ // Sendet Kommando CMD0 an MMC/SD-Karte
+ uint8 cmd[] = {0x40,0x00,0x00,0x00,0x00,0x95};
+ while (mmc_write_command(cmd) != 1){
+ if (timeout++ > MMC_TIMEOUT){
+ MMC_Disable();
+ mmc_init_state = 1;
+ return 1; // Abbruch bei Kommando 1 (Return Code 1)
+ }
+ }
+
+ // Sendet Kommando CMD1 an MMC/SD-Karte
+ timeout = 0;
+ cmd[0] = 0x41; // Kommando 1
+ cmd[5] = 0xFF;
+ while (mmc_write_command (cmd) !=0){
+ if (timeout++ > 3*MMC_TIMEOUT){
+ MMC_Disable();
+ mmc_init_state = 1;
+ return 2; // Abbruch bei Kommando 2 (Return Code 2)
+ }
+ }
+
+ // set MMC_Chip_Select to high (MMC/SD-Karte Inaktiv)
+ MMC_Disable();
+ return 0;
+}
+
+
+/*!
+ * Liest einen Block von der Karte
+ * @param cmd Zeiger auf das Kommando, das erstmal an die Karte geht
+ * @param Buffer Ein Puffer mit mindestens count Bytes
+ * @param count Anzahl der zu lesenden Bytes
+ */
+uint8 mmc_read_block(uint8 *cmd, uint8 *buffer, uint16 count){
+ /* Initialisierung checken */
+ if (mmc_init_state != 0)
+ if (mmc_init() != 0) return 1;
+
+ // Sendet Kommando cmd an MMC/SD-Karte
+ if (mmc_write_command(cmd) != 0) {
+ mmc_init_state = 1;
+ return 1;
+ }
+
+ // Wartet auf Start Byte von der MMC/SD-Karte (FEh/Start Byte)
+ uint8 timeout=1;
+ while (mmc_read_byte() != 0xfe){
+ if (timeout++ == 0) break;
+ };
+
+ uint16 i;
+ // Lesen des Blocks (max 512 Bytes) von MMC/SD-Karte
+ for (i=0; i<count; i++)
+ *buffer++ = mmc_read_byte();
+
+ // CRC-Byte auslesen
+ mmc_read_byte(); //CRC - Byte wird nicht ausgewertet
+ mmc_read_byte(); //CRC - Byte wird nicht ausgewertet
+
+ // set MMC_Chip_Select to high (MMC/SD-Karte inaktiv)
+ MMC_Disable();
+ if (timeout == 0) {
+ mmc_init_state = 1;
+ return 1; // Abbruch durch Timeout
+ }
+ return 0; // alles ok
+}
+
+#ifdef MMC_INFO_AVAILABLE
+/*!
+ * Liest das CID-Register (16 Byte) von der Karte
+ * @param Buffer Puffer von mindestens 16 Byte
+ */
+void mmc_read_cid (uint8 *buffer){
+ // Kommando zum Lesen des CID Registers
+ uint8 cmd[] = {0x4A,0x00,0x00,0x00,0x00,0xFF};
+ mmc_read_block(cmd, buffer, 16);
+}
+
+/*!
+ * Liest das CSD-Register (16 Byte) von der Karte
+ * @param Buffer Puffer von mindestens 16 Byte
+ */
+void mmc_read_csd (uint8 *buffer){
+ // Kommando zum lesen des CSD Registers
+ uint8 cmd[] = {0x49,0x00,0x00,0x00,0x00,0xFF};
+ mmc_read_block(cmd, buffer, 16);
+}
+
+/*!
+ * Liefert die Groesse der Karte zurueck
+ * @return Groesse der Karte in Byte. Bei einer 4 GByte-Karte kommt 0xFFFFFFFF zurueck
+ */
+uint32 mmc_get_size(void){
+ uint8 csd[16];
+
+ mmc_read_csd(csd);
+
+ uint32 size = (csd[8]>>6) + (csd[7] << 2) + ((csd[6] & 0x03) << 10); // c_size
+ size +=1; // Fest in der Formel drin
+
+ uint8 shift = 2; // eine 2 ist fest in der Formel drin
+ shift += (csd[10]>>7) + ((csd[9] & 0x03) <<1); // c_size_mult beruecksichtigen
+ shift += csd[5] & 0x0f; // Blockgroesse beruecksichtigen
+
+ size = size << shift;
+
+ return size;
+}
+
+
+#endif //MMC_INFO_AVAILABLE
+
+#ifdef MMC_WRITE_TEST_AVAILABLE
+ /*! Testet die MMC-Karte. Schreibt nacheinander 2 Sektoren a 512 Byte mit Testdaten voll und liest sie wieder aus
+ * !!! Achtung loescht die Karte
+ * @return 0, wenn alles ok
+ */
+ uint8 mmc_test(void){
+ static uint32 sector = 0xf000;
+ /* Initialisierung checken */
+ if (mmc_init_state != 0)
+ if (mmc_init() != 0){
+ sector = 0;
+ return 1;
+ }
+ #ifdef MMC_VM_AVAILABLE // Version mit virtuellen Aressen
+ uint16 i;
+ static uint16 pagefaults = 0;
+ static uint16 old_pf;
+ /* virtuelle Adressen holen */
+ static uint32 v_addr1 = 0;
+ static uint32 v_addr2 = 0;
+ static uint32 v_addr3 = 0;
+ static uint32 v_addr4 = 0;
+ if (v_addr1 == 0) v_addr1 = mmcalloc(512, 1); // Testdaten 1
+ if (v_addr2 == 0) v_addr2 = mmcalloc(512, 1); // Testdaten 2
+ if (v_addr3 == 0) v_addr3 = mmcalloc(512, 1); // Dummy 1
+ if (v_addr4 == 0) v_addr4 = mmcalloc(512, 1); // Dummy 2
+ /* Zeitmessung starten */
+ uint16 start_ticks=TIMER_GET_TICKCOUNT_16;
+ uint8 start_reg=TCNT2;
+ /* Pointer auf Puffer holen */
+ uint8* p_addr = mmc_get_data(v_addr1); // Cache-Hit, CB 0
+ if (p_addr == NULL) return 2;
+ /* Testdaten schreiben */
+ for (i=0; i<512; i++)
+ p_addr[i] = (i & 0xff);
+ /* Pointer auf zweiten Speicherbereich holen */
+ p_addr = mmc_get_data(v_addr2); // Cache-Hit, CB 1
+ if (p_addr == NULL) return 3;
+ /* Testdaten Teil 2 schreiben */
+ for (i=0; i<512; i++)
+ p_addr[i] = 255 - (i & 0xff);
+ /* kleiner LRU-Test */
+// p_addr = mmc_get_data(v_addr1); // Cache-Hit, CB 0
+// p_addr = mmc_get_data(v_addr4); // Cache-Miss, => CB 1
+// p_addr = mmc_get_data(v_addr1); // Cache-Hit, CB 0
+// p_addr = mmc_get_data(v_addr3); // Cache-Miss, => CB 1
+// p_addr = mmc_get_data(v_addr1); // Cache-Hit, CB 0
+// p_addr = mmc_get_data(v_addr4); // Cache-Miss, => CB 1
+ /* Pointer auf Testdaten Teil 1 holen */
+ p_addr = mmc_get_data(v_addr1); // Cache-Hit, CB 0
+ if (p_addr == NULL) return 4;
+ /* Testdaten 1 vergleichen */
+ for (i=0; i<512; i++)
+ if (p_addr[i] != (i & 0xff)) return 5;
+ /* Pointer auf Testdaten Teil 2 holen */
+ p_addr = mmc_get_data(v_addr2); // Cache-Miss, => CB 1
+ if (p_addr == NULL) return 6;
+ /* Testdaten 2 vergleichen */
+ for (i=0; i<512; i++)
+ if (p_addr[i] != (255 - (i & 0xff))) return 7;
+
+ p_addr = mmc_get_data(v_addr4);
+ /* Zeitmessung beenden */
+ int8 timer_reg=TCNT2;
+ uint16 end_ticks=TIMER_GET_TICKCOUNT_16;
+ timer_reg -= start_reg;
+ #ifdef VM_STATS_AVAILABLE
+ /* Pagefaults merken */
+ old_pf = pagefaults;
+ pagefaults = mmc_get_pagefaults();
+ #endif
+ /* kleine Statistik ausgeben */
+ display_cursor(3,1);
+ display_printf("Pagefaults: %5u ", pagefaults);
+ display_cursor(4,1);
+ display_printf("Bei %3u PF: %5u us", pagefaults - old_pf, (end_ticks-start_ticks)*176 + timer_reg*4);
+ #else // alte Version
+ uint8 buffer[512];
+ uint16 i;
+ uint8 result=0;
+
+ /* Zeitmessung starten */
+ uint16 start_ticks=TIMER_GET_TICKCOUNT_16;
+ uint8 start_reg=TCNT2;
+
+ #if MMC_ASYNC_WRITE == 1
+ /* async-Test (wurde im letzten Durchlauf korrekt geschrieben?) */
+ if (sector > 0xf){
+ result= mmc_read_sector(sector-1, buffer);
+ if (result != 0){
+ return result*10 + 9;
+ }
+ for (i=0; i<512; i++)
+ if (buffer[i] != (i & 0xFF)){
+ return 10;
+ }
+ }
+ #endif // MMC_ASYNC_WRITE
+
+ // Puffer vorbereiten
+ for (i=0; i< 512; i++) buffer[i]= (i & 0xFF);
+ // und schreiben
+ result= mmc_write_sector(sector, buffer, 0);
+ if (result != 0){
+ return result*10 + 2;
+ }
+
+ // Puffer vorbereiten
+ for (i=0; i< 512; i++) buffer[i]= 255 - (i & 0xFF);
+ // und schreiben
+ result= mmc_write_sector(sector+1, buffer, 0);
+ if (result != 0){
+ return result*10 + 3;
+ }
+
+ // Puffer lesen
+ result= mmc_read_sector(sector++, buffer);
+ if (result != 0){
+ sector--;
+ return result*10 + 4;
+ }
+
+ // und vergleichen
+ for (i=0; i<512; i++)
+ if (buffer[i] != (i & 0xFF)){
+ return 5;
+ }
+
+// sector++;
+ // Puffer lesen
+ result= mmc_read_sector(sector++, buffer);
+ if (result != 0){
+ sector--;
+ return result*10 + 6;
+ }
+ // und vergleichen
+ for (i=0; i<512; i++)
+ if (buffer[i] != (255- (i & 0xFF))){
+ return 7;
+ }
+
+ #if MMC_ASYNC_WRITE == 1
+ for (i=0; i< 512; i++)
+ buffer[i]= (i & 0xFF);
+ result= mmc_write_sector(sector-1, buffer, MMC_ASYNC_WRITE);
+ if (result != 0){
+ return result*10 + 8;
+ }
+ #endif // MMC_ASYNC_WRITE
+
+ /* Zeitmessung beenden */
+ int8 timer_reg=TCNT2;
+ uint16 end_ticks=TIMER_GET_TICKCOUNT_16;
+ timer_reg -= start_reg;
+ /* kleine Statistik ausgeben */
+ display_cursor(3,1);
+ display_printf("Dauer: %5u us ", (end_ticks-start_ticks)*176 + timer_reg*4);
+ display_cursor(4,1);
+ display_printf("Sektor:%6u/", sector-2);
+ display_printf("%6u", sector-1);
+ #endif // MMC_VM_AVAILABLE
+ // hierher kommen wir nur, wenn alles ok ist
+ return 0;
+ }
+#endif //MMC_WRITE_TEST_AVAILABLE
+
+#endif
+#endif
diff --git a/source/ct-Bot/mcu/motor-low.c b/source/ct-Bot/mcu/motor-low.c
new file mode 100644
index 0000000..98e5f9f
--- /dev/null
+++ b/source/ct-Bot/mcu/motor-low.c
@@ -0,0 +1,242 @@
+/*
+ * c't-Bot
+ *
+ * This program is free software; you can redistribute it
+ * and/or modify it under the terms of the GNU General
+ * Public License as published by the Free Software
+ * Foundation; either version 2 of the License, or (at your
+ * option) any later version.
+ * This program is distributed in the hope that it will be
+ * useful, but WITHOUT ANY WARRANTY; without even the implied
+ * warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR
+ * PURPOSE. See the GNU General Public License for more details.
+ * You should have received a copy of the GNU General Public
+ * License along with this program; if not, write to the Free
+ * Software Foundation, Inc., 59 Temple Place, Suite 330, Boston,
+ * MA 02111-1307, USA.
+ *
+ */
+
+/*! @file motor-low.c
+ * @brief Low-Level Routinen fuer die Motorsteuerung des c't-Bots
+ * @author Benjamin Benz (bbe@heise.de)
+ * @date 01.12.05
+*/
+#ifdef MCU
+
+#include "ct-Bot.h"
+
+#include <avr/io.h>
+#include <avr/interrupt.h>
+#ifndef NEW_AVR_LIB
+ #include <avr/signal.h>
+#endif
+#include <stdlib.h>
+
+#include "global.h"
+#include "motor.h"
+#include "timer.h"
+#include "sensor.h"
+#include "display.h"
+#include "motor-low.h"
+
+//Drehrichtung der Motoren
+#define BOT_DIR_L_PIN (1<<6) // PC7
+#define BOT_DIR_L_PORT PORTC
+#define BOT_DIR_L_DDR DDRC
+
+#define BOT_DIR_R_PIN (1<<7) // PC6
+#define BOT_DIR_R_PORT PORTC
+#define BOT_DIR_R_DDR DDRC
+
+#define PWM_L OCR1A
+#define PWM_R OCR1B
+
+#define PWM_CLK_0 (_BV(CS02) | _BV(CS00)) /*!< Prescaler fuer PWM 0 = 1024*/
+//#define PWM_CLK_2 (_BV(CS22) | _BV(CS21) |_BV(CS20)) /*!< Prescaler fuer PWM 2 =1024 */
+
+int16 motor_left; /*!< zuletzt gestellter Wert linker Motor */
+int16 motor_right; /*!< zuletzt gestellter Wert rechter Motor */
+
+
+void pwm_0_init(void);
+void pwm_1_init(void);
+// void pwm_2_init(void); // Kollidiert mit Timer2 fuer IR-Fernbedienung
+
+/*!
+ * Initialisiert alles fuer die Motosteuerung
+ */
+void motor_low_init(){
+ BOT_DIR_L_DDR|=BOT_DIR_L_PIN;
+ BOT_DIR_R_DDR|=BOT_DIR_R_PIN;
+
+ pwm_0_init();
+ pwm_1_init();
+// pwm_2_init(); // Kollidiert mit Timer2 fuer IR-Fernbedienung
+ bot_motor(0,0);
+}
+
+/*!
+ * unmittelbarere Zugriff auf die beiden Motoren
+ * normalerweise NICHT verwenden!!!!!
+ * @param left Speed links
+ * @param right Speed rechts
+*/
+void bot_motor(int16 left, int16 right){
+ // Vorzeichenbehaftete PWM-Werte sichern
+ motor_left=left;
+ motor_right=right;
+
+ PWM_L = 255-abs(left);
+ PWM_R = 255-abs(right);
+
+ if (left > 0 ){
+ BOT_DIR_L_PORT |= BOT_DIR_L_PIN;
+ direction.left= DIRECTION_FORWARD;
+ } else
+ BOT_DIR_L_PORT &= ~BOT_DIR_L_PIN;
+
+ if (left < 0 )
+ direction.left= DIRECTION_BACKWARD;
+
+
+ if (right <= 0 ) // Einer der Motoren ist invertiert, da er ja in die andere Richtung schaut
+ BOT_DIR_R_PORT |= BOT_DIR_R_PIN;
+ else {
+ BOT_DIR_R_PORT &= ~BOT_DIR_R_PIN;
+ direction.right= DIRECTION_FORWARD;
+ }
+ if (right < 0 )
+ direction.right= DIRECTION_BACKWARD;
+}
+
+/*!
+ * Stellt die Servos
+ * Sinnvolle Werte liegen zwischen 8 und 16
+ */
+void servo_low(uint8 servo, uint8 pos){
+ if (servo== SERVO1) {
+ if (pos == SERVO_OFF) {
+ #ifdef __AVR_ATmega644__
+ TCCR0B &= ~PWM_CLK_0 ; // PWM aus
+ #else
+ TCCR0 &= ~PWM_CLK_0 ; // PWM aus
+ #endif
+ } else {
+ #ifdef __AVR_ATmega644__
+ TCCR0B |= PWM_CLK_0; // PWM an
+ OCR0A=pos;
+ #else
+ TCCR0 |= PWM_CLK_0; // PWM an
+ OCR0=pos;
+ #endif
+ }
+
+ }
+
+// if (servo== SERVO2) {
+// if (pos == 0) {
+// TCCR2 &= ~ (_BV(CS22) | _BV(CS21) | _BV(CS20)); // PWM an
+// } else {
+// TCCR2 |= PWM_CLK_2; // PWM an
+// OCR2=pos;
+// }
+// }
+
+}
+
+/*!
+ * Interrupt Handler for Timer/Counter 0
+ */
+#ifdef __AVR_ATmega644__
+ SIGNAL (TIMER0_COMPA_vect){
+#else
+ SIGNAL (SIG_OUTPUT_COMPARE0){
+#endif
+}
+
+/*!
+ * Timer 0: Kontrolliert den Servo per PWM
+ * PWM loescht bei erreichen. daher steht in OCR0 255-Speed!!!
+ * initilaisiert Timer 0 und startet ihn
+ */
+void pwm_0_init(void){
+
+ DDRB |= (1<<3); // PWM-Pin als Output
+ TCNT0 = 0x00; // TIMER0 vorladen
+
+ #ifdef __AVR_ATmega644__
+ TCCR0A = _BV(WGM00) | // Normal PWM
+ _BV(COM0A1); // Clear on Compare , Set on Top
+ //PWM_CLK_0;
+
+ OCR0A = 8;
+ #else
+ TCCR0 = _BV(WGM00) | // Normal PWM
+ _BV(COM01) ; // Clear on Compare , Set on Top
+
+ OCR0 = 8; // PWM loescht bei erreichen. daher steht in OCR0 255-Speed!!!
+ #endif
+ // TIMSK |= _BV(OCIE0); // enable Output Compare 0 overflow interrupt
+ //sei(); // enable interrupts
+}
+
+// ---- Timer 1 ------
+
+/*!
+ * Interrupt Handler for Timer/Counter 1A
+ */
+SIGNAL (SIG_OUTPUT_COMPARE1A){
+}
+
+/*!
+ * Interrupt Handler for Timer/Counter 1B
+ */
+SIGNAL (SIG_OUTPUT_COMPARE1B){
+}
+
+/*!
+ * Timer 1: Kontrolliert die Motoren per PWM
+ * PWM loescht bei erreichen. daher steht in OCR1A/OCR1B 255-Speed!!!
+ * initilaisiert Timer 0 und startet ihn
+ */
+void pwm_1_init(void){
+ DDRD |= 0x30 ; // PWM-Pins als Output
+ TCNT1 = 0x0000; // TIMER1 vorladen
+
+ TCCR1A = _BV(WGM10) | // Fast PWM 8 Bit
+ _BV(COM1A1) |_BV(COM1A0) | // Clear on Top, Set on Compare
+ _BV(COM1B1) |_BV(COM1B0); // Clear on Top, Set on Compare
+
+ TCCR1B = _BV(WGM12) |
+ _BV(CS12) | _BV(CS10); // Prescaler = 1024
+// _BV(CS10); // Prescaler = 1
+
+ OCR1A = 255; // PWM loescht bei erreichen. daher steht in OCR1A 255-Speed!!!
+ OCR1B = 255; // PWM loescht bei erreichen. daher steht in OCR1B 255-Speed!!!
+
+ // TIMSK|= _BV(OCIE1A) | _BV(OCIE1B); // enable Output Compare 1 overflow interrupt
+ // sei(); // enable interrupts
+}
+
+/*!
+ * Timer 0: Kontrolliert den Servo per PWM
+ * PWM loescht bei erreichen. daher steht in OCR0 255-Speed!!!
+ * initilaisiert Timer 0 und startet ihn
+ */
+/* Kollidiert derzeit mit Timer2 fuer IR
+void pwm_2_init(void){
+ DDRD |= 0x80; // PWM-Pin als Output
+ TCNT2 = 0x00; // TIMER0 vorladen
+
+ TCCR2 = _BV(WGM20) | // Normal PWM
+ _BV(COM21); // Clear on Top, Set on Compare
+// _BV(CS22) | _BV(CS21) |_BV(CS20); // Prescaler = 1024
+
+ OCR2 = 8; // PWM löscht bei erreichen. daher steht in OCR0 255-Speed!!!
+ // TIMSK |= _BV(OCIE0); // enable Output Compare 0 overflow interrupt
+ //sei(); // enable interrupts
+}
+*/
+
+#endif
diff --git a/source/ct-Bot/mcu/mouse.c b/source/ct-Bot/mcu/mouse.c
new file mode 100644
index 0000000..f04ec13
--- /dev/null
+++ b/source/ct-Bot/mcu/mouse.c
@@ -0,0 +1,183 @@
+/*
+ * c't-Bot
+ *
+ * This program is free software; you can redistribute it
+ * and/or modify it under the terms of the GNU General
+ * Public License as published by the Free Software
+ * Foundation; either version 2 of the License, or (at your
+ * option) any later version.
+ * This program is distributed in the hope that it will be
+ * useful, but WITHOUT ANY WARRANTY; without even the implied
+ * warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR
+ * PURPOSE. See the GNU General Public License for more details.
+ * You should have received a copy of the GNU General Public
+ * License along with this program; if not, write to the Free
+ * Software Foundation, Inc., 59 Temple Place, Suite 330, Boston,
+ * MA 02111-1307, USA.
+ *
+ */
+
+/*! @file mouse.c
+ * @brief Routinen fuer die Ansteuerung eines opt. Maussensors
+ * @author Benjamin Benz (bbe@heise.de)
+ * @date 26.12.05
+*/
+#include "global.h"
+
+
+#ifdef MCU
+
+#include <avr/io.h>
+#include "ct-Bot.h"
+#include "mouse.h"
+#include "delay.h"
+#include "ena.h"
+
+#ifdef MAUS_AVAILABLE
+
+#define MAUS_DDR DDRB /*!< DDR fuer Maus-SCLK */
+#define MAUS_PORT PORTB /*!< PORT fuer Maus-SCLK */
+#define MAUS_SCK_PIN (1<<7) /*!< PIN fuer Maus-SCLK */
+
+#define MAUS_SDA_NR 6 /*!< Pin an dem die SDA-Leitung haengt */
+#define MAUS_SDA_PINR PINB /*!< Leseregister */
+#define MAUS_SDA_PIN (1<<MAUS_SDA_NR) /*!< Bit-Wert der SDA-Leitung */
+
+#define MOUSE_Enable() ENA_on(ENA_MOUSE_SENSOR)
+
+/*!
+ * Uebertraegt ein Byte an den Sensor
+ * @param data das Byte
+ */
+void maus_sens_writeByte(uint8 data){
+ int8 i;
+ MAUS_DDR |= MAUS_SDA_PIN; // SDA auf Output
+
+ for (i=7; i>=0; i--){
+ MAUS_PORT &= ~MAUS_SCK_PIN; // SCK auf Low, vorbereiten
+
+ //Daten rausschreiben
+ MAUS_PORT = (MAUS_PORT & (~MAUS_SDA_PINR)) | ((data >> (7 - MAUS_SDA_NR)) & MAUS_SDA_PIN);
+ data = data <<1; // naechstes Bit vorbereiten
+ asm volatile("nop"); // Etwas warten
+
+ MAUS_PORT |= MAUS_SCK_PIN; // SCK =1 Sensor uebernimmt auf steigender Flanke
+ }
+}
+
+/*!
+ * Liest ein Byte vom Sensor
+ * @return das Byte
+ */
+uint8 maus_sens_readByte(void){
+ int i;
+ char data=0;
+
+ MAUS_DDR &= ~MAUS_SDA_PIN; // SDA auf Input
+
+ for (i=7; i>-1; i--){
+ MAUS_PORT &= ~MAUS_SCK_PIN; // SCK =0 Sensor bereitet Daten auf fallender Flanke vor !
+ data=data<<1; // Platz schaffen
+
+ asm volatile("nop"); // Etwas warten
+ MAUS_PORT |= MAUS_SCK_PIN; // SCK =1 Daten lesen auf steigender Flanke
+
+ data |= (MAUS_SDA_PINR >> MAUS_SDA_NR) & 0x01; //Daten lesen
+ }
+
+ return data;
+}
+
+/*!
+ * Uebertraegt ein write-Kommando an den Sensor
+ * @param adr Adresse
+ * @param data Datum
+ */
+void maus_sens_write(int8 adr, uint8 data){
+ int16 i;
+
+ MOUSE_Enable();
+
+ maus_sens_writeByte(adr|=0x80); //rl MSB muss 1 sein Datenblatt S.12 Write Operation
+ maus_sens_writeByte(data);
+ for (i=0; i<300; i++){ asm volatile("nop"); } // mindestens 100 Mikrosekunden Pause!!!
+}
+
+/*!
+ * Schickt ein Lesekommando an den Sensor
+ * und liest ein Byte zurueck
+ * @param adr die Adresse
+ * @return das Datum
+ */
+uint8 maus_sens_read(uint8 adr){
+ MOUSE_Enable();
+ int16 i;
+ maus_sens_writeByte(adr);
+ for (i=0; i<300; i++){asm volatile("nop");} // mindestens 100 Mikrosekunden Pause!!!
+
+ return maus_sens_readByte();
+}
+
+/*!
+ * Initialisiere Maussensor
+ */
+void maus_sens_init(void){
+ delay(100);
+
+ MAUS_DDR |= MAUS_SCK_PIN; // SCK auf Output
+ MAUS_PORT &= ~MAUS_SCK_PIN; // SCK auf 0
+
+ delay(10);
+
+ maus_sens_write(MOUSE_CONFIG_REG,MOUSE_CFG_RESET); //Reset sensor
+ maus_sens_write(MOUSE_CONFIG_REG,MOUSE_CFG_FORCEAWAKE); //Always on
+}
+
+/*! muessen wir nach dem ersten Pixel suchen?*/
+static uint8 firstRead;
+/*!
+ * Bereitet das auslesen eines ganzen Bildes vor
+ */
+void maus_image_prepare(void){
+ maus_sens_write(MOUSE_CONFIG_REG,MOUSE_CFG_FORCEAWAKE); //Always on
+
+ maus_sens_write(MOUSE_PIXEL_DATA_REG,0x00); // Frame grabben anstossen
+ firstRead=1; //suche erstes Pixel
+}
+
+/*!
+ * Liefert bei jedem Aufruf das naechste Pixel des Bildes
+ * Insgesamt gibt es 324 Pixel
+ * <pre>
+ * 18 36 ... 324
+ * .. .. ... ..
+ * 2 20 ... ..
+ * 1 19 ... 307
+ * </pre>
+ * Bevor diese Funktion aufgerufen wird, muss maus_image_prepare() aufgerufen werden!
+ * @return Die Pixeldaten (Bit 0 bis Bit5), Pruefbit, ob Daten gueltig (Bit6), Markierung fuer den Anfang eines Frames (Bit7)
+ */
+int8 maus_image_read(void){
+ int8 pixel=maus_sens_read(MOUSE_PIXEL_DATA_REG);
+ if ( firstRead ==1){
+ while ( (pixel & 0x80) != 0x80){
+ pixel=maus_sens_read(MOUSE_PIXEL_DATA_REG);
+// if ((pixel & 0x70) != 0x70)
+// return 0;
+ }
+ firstRead=0;
+ }
+
+ return pixel;
+}
+
+/*!
+ * Gibt den SQUAL-Wert zurueck. Dieser gibt an, wieviele Merkmale der Sensor
+ * im aktuell aufgenommenen Bild des Untergrunds wahrnimmt
+ */
+uint8 maus_get_squal(void) {
+ return maus_sens_read(MOUSE_SQUAL_REG);
+}
+
+#endif
+#endif
diff --git a/source/ct-Bot/mcu/sensor-low.c b/source/ct-Bot/mcu/sensor-low.c
new file mode 100644
index 0000000..3e7d3a7
--- /dev/null
+++ b/source/ct-Bot/mcu/sensor-low.c
@@ -0,0 +1,229 @@
+/*
+ * c't-Bot
+ *
+ * This program is free software; you can redistribute it
+ * and/or modify it under the terms of the GNU General
+ * Public License as published by the Free Software
+ * Foundation; either version 2 of the License, or (at your
+ * option) any later version.
+ * This program is distributed in the hope that it will be
+ * useful, but WITHOUT ANY WARRANTY; without even the implied
+ * warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR
+ * PURPOSE. See the GNU General Public License for more details.
+ * You should have received a copy of the GNU General Public
+ * License along with this program; if not, write to the Free
+ * Software Foundation, Inc., 59 Temple Place, Suite 330, Boston,
+ * MA 02111-1307, USA.
+ *
+ */
+
+/*! @file sensor-low.c
+ * @brief Low-Level Routinen für die Sensor Steuerung des c't-Bots
+ * @author Benjamin Benz (bbe@heise.de)
+ * @date 01.12.05
+*/
+
+#ifdef MCU
+
+#include <avr/io.h>
+#include "adc.h"
+#include "global.h"
+
+#include "ena.h"
+#include "sensor.h"
+#include "mouse.h"
+#include "motor.h"
+#include "timer.h"
+#include "sensor_correction.h"
+#include "bot-logic/available_behaviours.h"
+#ifdef BEHAVIOUR_SERVO_AVAILABLE
+ #include "bot-logic/behaviour_servo.h"
+#endif
+
+// ADC-PINS
+#define SENS_ABST_L 0 /*!< ADC-PIN Abstandssensor Links */
+#define SENS_ABST_R 1 /*!< ADC-PIN Abstandssensor Rechts */
+#define SENS_M_L 2 /*!< ADC-PIN Liniensensor Links */
+#define SENS_M_R 3 /*!< ADC-PIN Liniensensor Rechts */
+#define SENS_LDR_L 4 /*!< ADC-PIN Lichtsensor Links */
+#define SENS_LDR_R 5 /*!< ADC-PIN Lichtsensor Rechts */
+#define SENS_KANTE_L 6 /*!< ADC-PIN Kantensensor Links */
+#define SENS_KANTE_R 7 /*!< ADC-PIN Kantensensor Rechts */
+
+// Sonstige Sensoren
+#define SENS_DOOR_PINR PIND /*!< Port an dem der Klappensensor hängt */
+#define SENS_DOOR_DDR DDRD /*!< DDR für den Klappensensor */
+#define SENS_DOOR 6 /*!< Pin an dem der Klappensensor hängt */
+
+#define SENS_ENCL_PINR PINB /*!< Port an dem der linke Encoder hängt */
+#define SENS_ENCL_DDR DDRB /*!< DDR für den linken Encoder */
+#define SENS_ENCL 4 /*!< Pin an dem der linke Encoder hängt */
+
+#define SENS_ENCR_PINR PIND /*!< Port an dem der rechte Encoder hängt */
+#define SENS_ENCR_DDR DDRD /*!< DDR für den rechten Encoder */
+#define SENS_ENCR 3 /*!< Pin an dem der rechte Encoder hängt */
+
+#define SENS_ERROR_PINR PINB /*!< Port an dem die Fehlerüberwachung hängt */
+#define SENS_ERROR_DDR DDRB /*!< DDR für die Fehlerüberwachung */
+#define SENS_ERROR 2 /*!< Pin an dem die Fehlerüberwachung hängt */
+
+#define SENS_TRANS_PINR PINB /*!< Port an dem die Transportfachueberwachung haengt */
+#define SENS_TRANS_PORT PORTB /*!< Port an dem die Transportfachueberwachung haengt */
+#define SENS_TRANS_DDR DDRB /*!< DDR für die Transportfachueberwachung */
+#define SENS_TRANS 0 /*!< Pin an dem die Transportfachueberwachung haengt */
+
+#define ENC_L ((SENS_ENCL_PINR >> SENS_ENCL) & 0x01) /*!< Abkuerzung zum Zugriff auf Encoder */
+#define ENC_R ((SENS_ENCR_PINR >> SENS_ENCR) & 0x01) /*!< Abkuerzung zum Zugriff auf Encoder */
+
+#define ENC_ENTPRELL 12 /*!< Nur wenn der Encoder ein paar mal den gleichen wert gibt uebernehmen */
+
+
+/*!
+ * Initialisiere alle Sensoren
+ */
+void bot_sens_init(void){
+ ENA_init();
+ adc_init(0xFF); // Alle ADC-Ports aktivieren
+
+ ENA_set(ENA_RADLED); // Alle Sensoren bis auf die Radencoder deaktivieren
+ ENA_on(ENA_ABSTAND); // Die Abstandssensoren ebenfalls dauerhaft an, da sie fast 50 ms zum booten brauchen
+
+ SENS_DOOR_DDR &= ~ (1<<SENS_DOOR); // Input
+
+ SENS_ENCL_DDR &= ~ (1<<SENS_ENCL); // Input
+ SENS_ENCR_DDR &= ~(1<<SENS_ENCR); // Input
+
+ SENS_ERROR_DDR &= ~(1<<SENS_ERROR); // Input
+
+ SENS_TRANS_DDR &= ~(1<<SENS_TRANS); // Input
+ SENS_TRANS_PORT |= (1<<SENS_TRANS); // Pullup an
+
+ SENS_ENCL_DDR &= ~(1<<SENS_ENCL); // Input
+ SENS_ENCR_DDR &= ~(1<<SENS_ENCR); // Input
+
+ timer_2_init();
+}
+
+
+/*!
+ * Alle Sensoren aktualisieren
+ * Derzeit pollt diese Routine alle Sensoren. Insbesondere bei den
+ * analogen dauert das eine Weile. Daher kann man hier einiges
+ * an Performance gewinnen, wenn man die Routine aufspaltet und
+ * zumindest die analogen Sensoren per Interrupt bearbeitet,
+ * denn im Moment blockiert adc_read so lange, bis ein Sensorwert ausgelesen ist.
+ * Die digitalen Sensoren liefern ihre Werte dagegen unmittelbar
+ * Aber Achtung es lohnt auch nicht, immer alles so schnell als moeglich
+ * zu aktualiseren, der Bot braucht auch Zeit zum nachdenken ueber Verhalten
+ */
+void bot_sens_isr(void){
+
+ ENA_on(ENA_KANTLED|ENA_MAUS|ENA_SCHRANKE|ENA_KLAPPLED);
+
+ #ifdef MAUS_AVAILABLE
+ // Aktualisiere die Position des Maussensors
+ sensMouseDX = maus_sens_read(MOUSE_DELTA_X_REG);
+ sensMouseDY = maus_sens_read(MOUSE_DELTA_Y_REG);
+
+ #endif
+
+ // ---------- analoge Sensoren -------------------
+ sensLDRL = adc_read(SENS_LDR_L);
+ sensLDRR = adc_read(SENS_LDR_R);
+
+ sensBorderL = adc_read(SENS_KANTE_L);
+ sensBorderR = adc_read(SENS_KANTE_R);
+ ENA_off(ENA_KANTLED);
+
+ sensLineL = adc_read(SENS_M_L);
+ sensLineR = adc_read(SENS_M_R);
+ ENA_off(ENA_MAUS);
+
+ // Aktualisiere Distanz-Sensoren
+ // Die Distanzsensoren sind im Normalfall an, da sie 50 ms zum booten brauchen
+ // Abfrage nur alle 100ms
+ static uint16 old_dist; // Zeit der letzten Messung der Distanzsensoren
+ static uint8 measure_count;
+ static int16 distLeft[3];
+ static int16 distRight[3];
+
+ register uint16 dist_ticks = TIMER_GET_TICKCOUNT_16;
+ if (dist_ticks-old_dist > MS_TO_TICKS(100)){
+ // Zeit fuer naechste Messung merken
+ old_dist=dist_ticks;
+
+ // wenn Kalibrierung gewuenscht, den Part Messen und Korrigieren kommentieren
+ // und Kalibrieren auskommentieren
+ // Kalibirieren
+ //distL=adc_read(SENS_ABST_L);
+ //distR=adc_read(SENS_ABST_R);
+
+ // Messwert merken
+ distLeft[measure_count]=adc_read(SENS_ABST_L);
+ #ifdef BEHAVIOUR_SERVO_AVAILABLE
+ if ((servo_active & SERVO1) == 0) // Wenn die Transportfachklappe bewegt wird, stimmt der Messwert des rechten Sensor nicht
+ #endif
+ distRight[measure_count]=adc_read(SENS_ABST_R);
+
+ measure_count++;
+ if (measure_count==3) measure_count=0;
+
+ // Schnittwert bilden
+ sensor_abstand((distLeft[0]+distLeft[1]+distLeft[2])/3,(distRight[0]+distRight[1]+distRight[2])/3);
+ }
+
+
+ // ------- digitale Sensoren ------------------
+ sensDoor = (SENS_DOOR_PINR >> SENS_DOOR) & 0x01;
+ sensTrans = (SENS_TRANS_PINR >> SENS_TRANS) & 0x01;
+ ENA_off(ENA_SCHRANKE|ENA_KLAPPLED);
+
+ sensError = (SENS_ERROR_PINR >> SENS_ERROR) & 0x01;
+
+ sensor_update(); // Weiterverarbeitung der rohen Sensordaten
+}
+
+/*!
+ * Kuemmert sich um die Radencoder
+ * Das muss schneller gehen als die anderen Sensoren,
+ * daher Update per Timer-Interrupt und nicht per Polling
+ */
+void bot_encoder_isr(void){
+ static uint8 enc_l=0; /*!< Puffer fuer die letzten Encoder-Staende */
+ static uint8 enc_r=0; /*!< Puffer fuer die letzten Encoder-Staende */
+ static uint8 enc_l_cnt=0; /*!< Entprell-Counter fuer L-Encoder */
+ static uint8 enc_r_cnt=0; /*!< Entprell-Counter fuer R-Encoder */
+ // --------------------- links ----------------------------
+ //Rad-Encoder auswerten
+ if ( ENC_L != enc_l){ // uns interesieren nur Veraenderungen
+ enc_l=ENC_L; // neuen wert sichern
+ enc_l_cnt=0; // Counter zuruecksetzen
+ } else { // Zaehlen, wie lange Pegel bleibt
+ if (enc_l_cnt <= ENC_ENTPRELL) // Nur bis zur Entprell-Marke
+ enc_l_cnt++;
+ }
+
+ if (enc_l_cnt == ENC_ENTPRELL){// wenn lange genug konst
+ if (direction.left == DIRECTION_FORWARD) // Drehrichtung beachten
+ sensEncL++; //vorwaerts
+ else
+ sensEncL--; //rueckwaerts
+ }
+
+ // --------------------- rechts ----------------------------
+ if (ENC_R != enc_r){ // uns interesieren nur Veraenderungen
+ enc_r=ENC_R; // neuen wert sichern
+ enc_r_cnt=0;
+ } else{ // Zaehlen, wie lange Pegel bleibt
+ if (enc_r_cnt <= ENC_ENTPRELL) // Nur bis zur Entprell-Marke
+ enc_r_cnt++;
+ }
+
+ if (enc_r_cnt == ENC_ENTPRELL){// wenn lange genug konst
+ if (direction.right == DIRECTION_FORWARD) // Drehrichtung beachten
+ sensEncR++; //vorwaerts
+ else
+ sensEncR--; //rueckwaerts
+ }
+}
+#endif
diff --git a/source/ct-Bot/mcu/shift.c b/source/ct-Bot/mcu/shift.c
new file mode 100644
index 0000000..735f3ac
--- /dev/null
+++ b/source/ct-Bot/mcu/shift.c
@@ -0,0 +1,93 @@
+/*
+ * c't-Bot
+ *
+ * This program is free software; you can redistribute it
+ * and/or modify it under the terms of the GNU General
+ * Public License as published by the Free Software
+ * Foundation; either version 2 of the License, or (at your
+ * option) any later version.
+ * This program is distributed in the hope that it will be
+ * useful, but WITHOUT ANY WARRANTY; without even the implied
+ * warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR
+ * PURPOSE. See the GNU General Public License for more details.
+ * You should have received a copy of the GNU General Public
+ * License along with this program; if not, write to the Free
+ * Software Foundation, Inc., 59 Temple Place, Suite 330, Boston,
+ * MA 02111-1307, USA.
+ *
+ */
+
+/*! @file shift.c
+ * @brief Routinen zur Ansteuerung der Shift-Register
+ * @author Benjamin Benz (bbe@heise.de)
+ * @date 20.12.05
+*/
+#include "global.h"
+#include "ct-Bot.h"
+
+#include "shift.h"
+
+#ifdef MCU
+#ifdef SHIFT_AVAILABLE
+
+#include <avr/io.h>
+#ifdef NEW_AVR_LIB
+ #include <util/delay.h>
+#else
+ #include <avr/delay.h>
+#endif
+
+
+#define SHIFT_OUT 0x1F /*!< Alle Pins die Ausgänge sind */
+#define SHIFT_PORT PORTC /*!< Port an dem die Register haengen */
+#define SHIFT_DDR DDRC /*!< DDR des Ports an dem die Register haengen */
+
+/*!
+ * Initialisert die Shift-Register
+ */
+void shift_init(){
+ SHIFT_DDR |= SHIFT_OUT; // Ausgänge Schalten
+ SHIFT_PORT &= ~SHIFT_OUT; // Und auf Null
+}
+
+/*!
+ * Schiebt Daten durch eines der drei 74HC595 Schieberegister
+ * Achtung den Port sollte man danach noch per shift_clear() zurücksetzen
+ * @param data Das Datenbyte
+ * @param latch_data der Pin an dem der Daten-latch-Pin des Registers (PIN 11) hängt
+ * @param latch_store der Pin an dem der latch-Pin zum transfer des Registers (PIN 12) hängt
+ */
+void shift_data_out(uint8 data, uint8 latch_data, uint8 latch_store){
+ int8 i;
+
+ SHIFT_PORT &= ~SHIFT_OUT; // und wieder clear
+ for (i=8; i>0; i--){
+ SHIFT_PORT |= ((data >> 7)& 0x01); // Das oberste Bit von data auf PC0.0 (Datenleitung Schieberegister)
+ SHIFT_PORT |= latch_data ; // und ins jeweilige Storageregister latchen
+ data= data << 1; // data links schieben
+ SHIFT_PORT &= ~SHIFT_OUT; // und wieder clear
+ }
+
+ SHIFT_PORT |= latch_store; // alles vom Storage ins Output register latchen
+}
+
+/*!
+ * Schiebt Daten durch eines der drei 74HC595 Schieberegister
+ * vereinfachte Version, braucht kein shift_clear()
+ * geht NICHT für das Shift-register, an dem das Display-hängt!!!
+ * @param data Das Datenbyte
+ * @param latch_data der Pin an dem der Daten-latch-Pin des Registers (PIN 11) hängt
+ */
+void shift_data(uint8 data, uint8 latch_data){
+ shift_data_out(data, latch_data, SHIFT_LATCH);
+ shift_clear();
+}
+
+/*!
+ * Setzt die Shift-Register wieder zurück
+ */
+void shift_clear(){
+ SHIFT_PORT &= ~SHIFT_OUT; // und wieder clear
+}
+#endif
+#endif
diff --git a/source/ct-Bot/mcu/srf10.c b/source/ct-Bot/mcu/srf10.c
new file mode 100644
index 0000000..ca5a4bb
--- /dev/null
+++ b/source/ct-Bot/mcu/srf10.c
@@ -0,0 +1,171 @@
+/*
+ * c't-Sim - Robotersimulator fuer den c't-Bot
+ *
+ * This program is free software; you can redistribute it
+ * and/or modify it under the terms of the GNU General
+ * Public License as published by the Free Software
+ * Foundation; either version 2 of the License, or (at your
+ * option) any later version.
+ * This program is distributed in the hope that it will be
+ * useful, but WITHOUT ANY WARRANTY; without even the implied
+ * warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR
+ * PURPOSE. See the GNU General Public License for more details.
+ * You should have received a copy of the GNU General Public
+ * License along with this program; if not, write to the Free
+ * Software Foundation, Inc., 59 Temple Place, Suite 330, Boston,
+ * MA 02111-1307, USA.
+ *
+ */
+
+/*! @file srf10.c
+ * @brief Ansteuerung des Ultraschall Entfernungssensors SRF10
+ * @author Carsten Giesen (info@cnau.de)
+ * @date 08.04.06
+*/
+#ifdef MCU
+#include <avr/io.h>
+#include "TWI_driver.h"
+#include "srf10.h"
+#include "delay.h"
+
+static uint8 address=SRF10_UNIT_0;
+
+/*!
+ * SRF10 initialsieren
+ */
+
+void srf10_init(void){
+ srf10_set_range(SRF10_MAX_RANGE);
+ //srf10_set_range(6); //Mit diesem Wert muss man spielen um das Optimum zu ermitteln
+return;
+}
+
+/*!
+ * Verstaerkungsfaktor setzen
+ * @param gain Verstaerkungsfaktor
+ */
+
+void srf10_set_gain(unsigned char gain){
+ if(gain>16) { gain=16; }
+
+ uint8 temp[2];
+ uint8 state;
+ tx_type tx_frame[2];
+
+ state = SUCCESS;
+
+ tx_frame[0].slave_adr = address+W;
+ tx_frame[0].size = 2;
+ tx_frame[0].data_ptr = temp;
+ tx_frame[0].data_ptr[0] = 1;
+ tx_frame[0].data_ptr[1] = gain;
+
+ tx_frame[1].slave_adr = OWN_ADR;
+
+ state = Send_to_TWI(tx_frame);
+}
+
+/*!
+ * Reichweite setzen, hat auch Einfluss auf die Messdauer
+ * @param millimeters Reichweite in mm
+ */
+
+void srf10_set_range(unsigned int millimeters){
+ uint8 temp[2];
+ uint8 state;
+ tx_type tx_frame[2];
+
+ state = SUCCESS;
+
+ millimeters= (millimeters/43);
+
+ tx_frame[0].slave_adr = address+W;
+ tx_frame[0].size = 2;
+ tx_frame[0].data_ptr = temp;
+ tx_frame[0].data_ptr[0] = 2;
+ tx_frame[0].data_ptr[1] = millimeters;
+
+ tx_frame[1].slave_adr = OWN_ADR;
+
+ state = Send_to_TWI(tx_frame);
+}
+
+/*!
+ * Messung ausloesen
+ * @param metric_unit 0x50 in Zoll, 0x51 in cm, 0x52 ms
+ * @return Resultat der Aktion
+ */
+
+uint8 srf10_ping(uint8 metric_unit){
+ uint8 temp[2];
+ uint8 state;
+ tx_type tx_frame[2];
+
+ state = SUCCESS;
+
+ tx_frame[0].slave_adr = address+W;
+ tx_frame[0].size = 2;
+ tx_frame[0].data_ptr = temp;
+ tx_frame[0].data_ptr[0] = SRF10_COMMAND;
+ tx_frame[0].data_ptr[1] = metric_unit;
+
+ tx_frame[1].slave_adr = OWN_ADR;
+
+ state = Send_to_TWI(tx_frame);
+
+ return state;
+}
+
+/*!
+ * Register auslesen
+ * @param srf10_register welches Register soll ausgelsen werden
+ * @return Inhalt des Registers
+ */
+
+uint8 srf10_read_register(uint8 srf10_register){
+ uint8 temp;
+ uint8 value;
+ uint8 state;
+ tx_type tx_frame[3];
+
+ state = SUCCESS;
+ value = 0;
+
+ tx_frame[0].slave_adr = address+W;
+ tx_frame[0].size = 1;
+ tx_frame[0].data_ptr = &temp;
+ tx_frame[0].data_ptr[0] = srf10_register;
+
+ tx_frame[1].slave_adr = address+R;
+ tx_frame[1].size = 1;
+ tx_frame[1].data_ptr = &value;
+
+ tx_frame[2].slave_adr = OWN_ADR;
+
+ state = Send_to_TWI(tx_frame);
+
+ return value;
+}
+
+/*!
+ * Messung starten Ergebniss aufbereiten und zurueckgeben
+ * @return Messergebniss
+ */
+
+uint16 srf10_get_measure(){
+ char hib;
+ char lob;
+ char state;
+
+ state = SUCCESS;
+
+ state = srf10_ping(SRF10_CENTIMETERS);
+ delay(10); //Optimierungs Potential
+ lob=srf10_read_register(SRF10_LOB);
+ delay(10); //Optimierungs Potential
+ hib=srf10_read_register(SRF10_HIB);
+
+ return (hib*256)+lob;
+}
+
+#endif
diff --git a/source/ct-Bot/mcu/timer-low.c b/source/ct-Bot/mcu/timer-low.c
new file mode 100644
index 0000000..f83bd1b
--- /dev/null
+++ b/source/ct-Bot/mcu/timer-low.c
@@ -0,0 +1,87 @@
+/*
+ * c't-Bot
+ *
+ * This program is free software; you can redistribute it
+ * and/or modify it under the terms of the GNU General
+ * Public License as published by the Free Software
+ * Foundation; either version 2 of the License, or (at your
+ * option) any later version.
+ * This program is distributed in the hope that it will be
+ * useful, but WITHOUT ANY WARRANTY; without even the implied
+ * warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR
+ * PURPOSE. See the GNU General Public License for more details.
+ * You should have received a copy of the GNU General Public
+ * License along with this program; if not, write to the Free
+ * Software Foundation, Inc., 59 Temple Place, Suite 330, Boston,
+ * MA 02111-1307, USA.
+ *
+ */
+
+/*! @file timer-low.c
+ * @brief Timer und counter für den Mikrocontroller
+ * @author Benjamin Benz (bbe@heise.de)
+ * @date 26.12.05
+*/
+
+#ifdef MCU
+
+#include "ct-Bot.h"
+
+#include <avr/io.h>
+#include <avr/interrupt.h>
+#ifndef NEW_AVR_LIB
+ #include <avr/signal.h>
+#endif
+
+
+#include "ct-Bot.h"
+
+#include "timer.h"
+#include "ir-rc5.h"
+#include "sensor-low.h"
+#include "bot-local.h"
+
+// ---- Timer 2 ------
+
+/*!
+ Interrupt Handler fuer Timer/Counter 2(A)
+ */
+#ifdef __AVR_ATmega644__
+ SIGNAL (TIMER2_COMPA_vect){
+#else
+ SIGNAL (SIG_OUTPUT_COMPARE2){
+#endif
+
+ /* - FERNBEDIENUNG - */
+ #ifdef IR_AVAILABLE
+ ir_isr();
+ #endif
+ /* ----- TIMER ----- */
+ tickCount.u32++; // TickCounter [176 us] erhoehen
+ /* --- RADENCODER --- */
+ bot_encoder_isr();
+}
+
+/*!
+ * initilaisiert Timer 0 und startet ihn
+ */
+void timer_2_init(void){
+ TCNT2 = 0x00; // TIMER vorladen
+
+ // aendert man den Prescaler muss man die Formel fuer OCR2 anpassen !!!
+ // Compare Register nur 8-Bit breit --> evtl. teiler anpassen
+ #ifdef __AVR_ATmega644__
+ TCCR2A = _BV(WGM21); // CTC Mode
+ TCCR2B = _BV(CS22); // Prescaler = CLK/64
+ OCR2A = ((XTAL/64/TIMER_2_CLOCK) - 1); // Timer2A
+ TIMSK2 |= _BV(OCIE2A); // TIMER2 Output Compare Match A Interrupt an
+ #else
+ // use CLK/64 prescale value, clear timer/counter on compare match
+ TCCR2 = _BV(WGM21) | _BV(CS22);
+ OCR2 = ((XTAL/64/TIMER_2_CLOCK) - 1);
+ TIMSK |= _BV(OCIE2); // enable Output Compare 0 overflow interrupt
+ #endif
+
+ sei(); // enable interrupts
+}
+#endif
diff --git a/source/ct-Bot/mcu/uart.c b/source/ct-Bot/mcu/uart.c
new file mode 100644
index 0000000..c9c36c6
--- /dev/null
+++ b/source/ct-Bot/mcu/uart.c
@@ -0,0 +1,206 @@
+/*
+ * c't-Bot
+ *
+ * This program is free software; you can redistribute it
+ * and/or modify it under the terms of the GNU General
+ * Public License as published by the Free Software
+ * Foundation; either version 2 of the License, or (at your
+ * option) any later version.
+ * This program is distributed in the hope that it will be
+ * useful, but WITHOUT ANY WARRANTY; without even the implied
+ * warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR
+ * PURPOSE. See the GNU General Public License for more details.
+ * You should have received a copy of the GNU General Public
+ * License along with this program; if not, write to the Free
+ * Software Foundation, Inc., 59 Temple Place, Suite 330, Boston,
+ * MA 02111-1307, USA.
+ *
+ */
+
+/*! @file uart.c
+ * @brief Routinen zur seriellen Kommunikation
+ * @author Benjamin Benz (bbe@heise.de)
+ * @date 26.12.05
+*/
+
+#ifdef MCU
+
+#include "ct-Bot.h"
+
+#include <avr/io.h>
+#include <avr/interrupt.h>
+#ifndef NEW_AVR_LIB
+ #include <avr/signal.h>
+#endif
+#include "ct-Bot.h"
+#include "uart.h"
+#include "command.h"
+#include "log.h"
+
+#ifdef UART_AVAILABLE
+
+#define BAUDRATE 57600
+
+#define UART_RX_BUFFER_SIZE 16 /*!< Größe des UART-Puffers */
+
+#define UART_RX_BUFFER_MASK ( UART_RX_BUFFER_SIZE - 1 )
+#if ( UART_RX_BUFFER_SIZE & UART_RX_BUFFER_MASK )
+ #error RX buffer size is not a power of 2
+#endif
+
+//#define UART_TIMEOUT 20000 /*!< Timeout. Wartet UART_TIMEOUT CPU-Takte */
+
+static uint8 UART_RxBuf[UART_RX_BUFFER_SIZE]; /*!< UART-Puffer */
+static volatile uint8 UART_RxHead; /*!< Zeiger für UART-Puffer */
+static volatile uint8 UART_RxTail; /*!< Zeiger für UART-Puffer */
+
+//char uart_timeout; /*!< 0, wenn uart_read/uart_send erfolgreich 1, wenn timeout erreicht */
+
+/*!
+ * Initialisiere UART
+ */
+void uart_init(void){
+ #ifdef __AVR_ATmega644__
+ /* Senden und Empfangen ermöglichen + RX Interrupt an */
+ UCSR0B= (1<<RXEN0) | (1<<TXEN0)|(1<<RXCIE0);
+ /* 8 Bit, 1 Stop, Keine Parity */
+ UCSR0C=0x86;
+ #else
+ /* Senden und Empfangen ermöglichen + RX Interrupt an */
+ UCSRB= (1<<RXEN) | (1<<TXEN)|(1<<RXCIE);
+ /* 8 Bit, 1 Stop, Keine Parity */
+ UCSRC=0x86;
+ #endif
+
+ /* UART auf 9600 baud */
+// UBRRH=0;
+// UBRRL= 103; /* Werte stehen im Datenblatt tabelarisch */
+ #ifdef __AVR_ATmega644__
+ UBRR0L = (uint8) (( ((uint32)F_CPU) / 16 / ((uint32)BAUDRATE) - 1) & 0xFF);
+ UBRR0H = (uint8) (( ((uint32)F_CPU) / 16 / ((uint32)BAUDRATE) - 1) >> 8);
+ #else
+ UBRRL = (uint8) (( ((uint32)F_CPU) / 16 / ((uint32)BAUDRATE) - 1) & 0xFF);
+ UBRRH = (uint8) (( ((uint32)F_CPU) / 16 / ((uint32)BAUDRATE) - 1) >> 8);
+ #endif
+
+ /* Puffer leeren */
+ UART_RxTail = 0;
+ UART_RxHead = 0;
+}
+
+/*!
+ * Interrupt Handler fuer den Datenempfang per UART
+ */
+#ifdef __AVR_ATmega644__
+ SIGNAL (USART0_RX_vect){
+#else
+ SIGNAL (SIG_UART_RECV){
+#endif
+
+ /* Pufferindex berechnen */
+ UART_RxHead++; /* erhoehen */
+ UART_RxHead %= UART_RX_BUFFER_MASK; /* Und bei Bedarf umklappen, da Ringpuffer */
+
+ if (UART_RxHead == UART_RxTail){
+ /* TODO Fehler behandeln !!
+ * ERROR! Receive buffer overflow */
+ }
+ #ifdef __AVR_ATmega644__
+ UART_RxBuf[UART_RxHead] = UDR0; /* Daten lesen und sichern*/
+ #else
+ UART_RxBuf[UART_RxHead] = UDR; /* Daten lesen und sichern*/
+ #endif
+}
+
+/*!
+ * Prüft, ob daten verfügbar
+ * @return Anzahl der verfuegbaren Bytes
+ */
+uint8 uart_data_available(void){
+ if (UART_RxHead == UART_RxTail) /* Puffer leer */
+ return 0;
+ else if (UART_RxHead > UART_RxTail) /* Schreibzeiger vor Lesezeiger */
+ return UART_RxHead - UART_RxTail;
+ else /* Schreibzeiger ist schon umgelaufen */
+ return UART_RxHead - UART_RxTail + UART_RX_BUFFER_SIZE;
+}
+
+
+/*!
+ * Überträgt ein Zeichen per UART
+ * Achtung ist noch blockierend!!!!
+ * TODO: umstellen auf nicht blockierend und mehr als ein Zeichen
+ * @param data Das Zeichen
+ */
+void uart_send_byte(uint8 data){ // Achtung ist noch blockierend!!!!
+ #ifdef __AVR_ATmega644__
+ while ((UCSR0A & _BV(UDRE0)) ==0){asm volatile("nop"); } // warten bis UART sendebereit
+ UDR0= data;
+ #else
+ while ((UCSRA & _BV(UDRE)) ==0){asm volatile("nop"); } // warten bis UART sendebereit
+ UDR= data;
+ #endif
+}
+
+/*!
+ * Sende Kommando per UART im Little Endian
+ * @param cmd Zeiger auf das Kommando
+ * @return Anzahl der gesendete Bytes
+ */
+//#define uart_send_cmd(cmd) uart_write(cmd,sizeof(command_t));
+
+/*
+int uart_send_cmd(command_t *cmd){
+ int i;
+ char * ptr = (char*) cmd;
+ for (i=0; i<sizeof(command_t); i++)
+ uart_send_byte(*ptr++);
+
+ return sizeof(command_t);
+}
+*/
+
+/*!
+ * Sende Daten per UART im Little Endian
+ * @param data Datenpuffer
+ * @param length Groesse des Datenpuffers in bytes
+ * @return Anzahl der gesendete Bytes
+ */
+int uart_write(uint8 * data, int length){
+ int i;
+ char * ptr = (char*) data;
+ for (i=0; i<length; i++)
+ uart_send_byte(*ptr++);
+
+ return length;
+}
+
+/*!
+ * Liest Zeichen von der UART
+ * @param data Der Zeiger an die die gelesenen Zeichen kommen
+ * @param length Anzahl der zu lesenden Bytes
+ * @return Anzahl der tatsaechlich gelesenen Zeichen
+ */
+int uart_read(void* data, int length){
+ uint8 i;
+ char* ptr = data;
+
+ uint8 count= uart_data_available();
+
+// LOG_DEBUG(("%d/%d av/sel",count,length));
+
+ if (count > length)
+ count=length;
+
+ for (i=0; i<count; i++){
+ UART_RxTail++;
+ UART_RxTail %= UART_RX_BUFFER_MASK;
+ *ptr++ = UART_RxBuf[UART_RxTail];
+
+ }
+
+ return count;
+}
+
+#endif
+#endif