inc/asuro.h

gehe zur Dokumentation dieser Datei
00001 
00031 /***************************************************************************
00032 *
00033 *it is not allowed to remove the nicknames of the contributers to this software
00034 * from the function header
00035 */
00036 /***************************************************************************
00037 *                                                                         *
00038 *   This program is free software; you can redistribute it and/or modify  *
00039 *   it under the terms of the GNU General Public License as published by  *
00040 *   the Free Software Foundation; either version 2 of the License, or     *
00041 *   any later version.                                                    *
00042 ***************************************************************************/
00043 
00044 /****************************************************************************
00045 *
00046 * File Name:   asuro.c
00047 *
00048 *
00049 * Ver.     Date         Author           Comments
00050 * -------  ----------   --------------   ------------------------------
00051 * 1.00     14.08.2003   Jan Grewe    build
00052 * 2.00     14.10.2003   Jan Grewe        RIGHT_VEL -> MotorSpeed(unsigned char left_speed, unsigned char right_speed);
00053 *                                        LeftRwd(),LeftFwd(),RightRwd(), LEFT_VEL,
00054 *                                        RigthFwd() -> MotorDir(unsigned char left_dir, unsigned char right_dir);
00055 *                                        GREEN_ON,GREEN_OFF,RED_ON,RED_OFF -> StatusLED(unsigned char color);
00056 *                                        LED_RED_ON, LED_RED_OFF -> FrontLED(unsigned char color);
00057 *                                        Blink(unsigned char left, unsigned char right) ->
00058 *                                         BackLED(unsigned char left, unsigned char right);
00059 *                                        Alles in Funktionen gefasst => leichter verständlich ?!?!
00060 * 2.10     17.10.2003   Jan Grewe        new Timer funktion void Sleep(unsigned char time36kHz)
00061 *
00062 *
00063 * Copyright (c) 2003 DLR Robotics & Mechatronics
00064 *****************************************************************************/
00065 /****************************************************************************
00066 *
00067 * File Name:   asuro.c
00068 * Project  :   asuro library "Robotrixer Buxtehude"
00069 *
00070 * Description: This file contains additional functions:
00071 *
00072 * signal (SIG_ADC)                 interrupt/signal routine for encoder-counter
00073 * signal (SIG_INTERRUPT1)          signal for switches
00074 * EncoderInit()                    initializing encoder-counter
00075 * EncoderStart()                   start autoencoding
00076 * EncoderStop()                    stop autoencoding
00077 * EncoderSet(int,int)              set encodervalue
00078 * Msleep(int delay)                wait for delay in milliseconds
00079 * Gettime()                        get systemtime in milliseconds
00080 * PrintInt(int)
00081 *
00082 * modifications in Sleep, SIG_OUTPUT_COMPARE2, PollSwitch, LineData
00083 *
00084 * Ver.     Date         Author           Comments
00085 * -------  ----------   --------------   ------------------------------
00086 * beta1    31.03.2005   Robotrixer   asuro library
00087 * -------  ----------   --------------   ------------------------------
00088 * the encoder source is based on RechteckDemo.c ver 2.0 by Jan Grewe 22.10.2003
00089 * Copyright (c) 2003 DLR Robotics & Mechatronics
00090 
00091 *****************************************************************************/
00092 /****************************************************************************
00093 *
00094 * File Name:   asuro.c
00095 * Project  :   asuro library modified for IR collision detector
00096 *
00097 * Description: modifications made in following functions:
00098 *
00099 * SIGNAL (SIG_OUTPUT_COMPARE2)  ->  SIGNAL (SIG_OVERFLOW2)
00100 * Gettime()       counts now 36kHz
00101 * Init()        timer2 modified for adjustable duty cycle
00102 * Batterie()        bug fixed
00103 * Sleep()       counts now 36kHz
00104 * Msleep()        counts now 36kHz
00105 *
00106 * Ver.     Date         Author           Comments
00107 * -------  ----------   --------------   ------------------------------
00108 * beta2    11.06.2005   Waste      asuro library
00109 * -------  ----------   --------------   ------------------------------
00110 *****************************************************************************/
00111 /****************************************************************************
00112 *
00113 * File Name:   asuro.c
00114 * Project  :   asuro library
00115 *
00116 * Description: This file contains additional functions:
00117 *
00118 * motor control functions 29.7.2005 stochri
00119 * void Go(int distance)
00120 * void Turn(int degree)
00121 *
00122 * unsigned char Wheelspeed[2]   measured Wheelspeed by interupt
00123 *
00124 * Ver.     Date         Author           Comments
00125 * -------  ----------   --------------   ------------------------------------------
00126 * sto1     29.07.2005   stochri    asuro library with motor control functions
00127 * -------  ----------   --------------   ------------------------------------------
00128 *****************************************************************************/
00129 /****************************************************************************
00130 *
00131 * File Name:   asuro.c
00132 * Project  :   asuro library "Robotrixer Buxtehude"
00133 *
00134 * Description: modifications made in following function:
00135 *
00136 * Go (int distance, int speed)           Added Speed and Odometrie
00137 * Turn (int degree, int speed)           Added Speed and Odometrie
00138 *
00139 * modifications in Sleep, SIG_OUTPUT_COMPARE2, PollSwitch, LineData
00140 *
00141 * Ver.     Date         Author           Comments
00142 * -------  ----------   --------------   ------------------------------
00143 * And1     31.07.2005   Andun    See above
00144 * -------  ----------   --------------   ------------------------------
00145 *
00146 *****************************************************************************/
00147 /****************************************************************************
00148 *
00149 * File Name:   asuro.c
00150 * Project  :   asuro library
00151 *
00152 * Description: modifications made in following functions:
00153 *
00154 * void PrintInt(int wert)
00155 *
00156 * unsigned char Wheelspeed[2]    removed
00157 *
00158 * Ver.     Date         Author           Comments
00159 * -------  ----------   --------------   ------------------------------------------
00160 * 2.60     28.09.2005   m.a.r.v.i.n      doxygen comments
00161 * -------  ----------   --------------   ------------------------------------------
00162 *****************************************************************************/
00163 /****************************************************************************
00164 *
00165 * File Name:   asuro.c
00166 * Project  :   asuro library
00167 *
00168 * Description: modifications made in following functions:
00169 *
00170 * SIGNAL (SIG_ADC)
00171 * void PrintInt(int wert)
00172 *
00173 *
00174 * Ver.     Date         Author           Comments
00175 * -------  ----------   --------------   ------------------------------------------
00176 * 2.61     20.11.2006   m.a.r.v.i.n      SIGNAL (SIG_ADC): static Variable toggle initialisiert
00177 *                                        auf False (Bug report von Rolf_Ebert)
00178 *                                        PrintInt: Initialisierung text String kann zu Fehler
00179 *                                        beim Flashen mit RS232/IR Adapter fuehren
00180 *                                        (Bug report von francesco)
00181 * -------  ----------   --------------   ------------------------------------------
00182 *****************************************************************************/
00183 /****************************************************************************
00184 *
00185 * File Name:   asuro.c
00186 * Project  :   asuro library
00187 *
00188 * Description: new functions has been added:
00189 *
00190 * void uart_putc(unsigned char zeichen)
00191 * void SerPrint(unsigned char *data)
00192 * void SetMotorPower(int8_t left_speed, int8_t right_speed )
00193 * void sound(uint16_t freq, uint16_t duration_msec, uint8_t amplitude)
00194 *
00195 * Description: modifications made in following functions:
00196 *
00197 * void Go(int distance, int power)
00198 * void Turn(int degree, int speed)
00199 * void PrintInt(int wert)
00200 *
00201 *
00202 * Ver.     Date         Author           Comments
00203 * -------  ----------   --------------   ------------------------------------------
00204 * 2.70     07.01.2007   stochri          new functions:
00205 *                                        uart_putc: send single character
00206 *                                        SerPrint: send 0-terminated string
00207 *                                        SetMotorPower: set Motor speed and direction
00208 *                                        sound: Sound Ausgabe ueber Motor PWM
00209 *                                        Go: distance in mm
00210 *                                        Turn: comments
00211 *                       m.a.r.v.i.n      PrintInt: SerWrite ersetzt durch SerPrint
00212 * -------  ----------   --------------   ------------------------------------------
00213 *****************************************************************************/
00214 
00215 
00216 #ifndef ASURO_H
00217 #define ASURO_H
00218 
00219 #include <avr/io.h>
00220 #include <avr/interrupt.h>
00221 #ifndef SIGNAL
00222   #include <avr/signal.h>   // header file obsolete in actual avr-libc
00223   #include <inttypes.h>
00224 #endif
00225 #include <stdlib.h>
00226 
00227 #define  FALSE  0
00228 #define  TRUE   1
00229 
00230 #define  OFF    0
00231 #define  ON     1
00232 
00233 #define GREEN   1
00234 #define RED     2
00235 #define YELLOW  3
00236 
00237 /* neue Funktionen und Variablen*/
00238 #define LEFT    0
00239 #define RIGHT   1
00240 #define CENTER  2
00241 
00242 /* Definitionen fuer Taster 
00243  * (Zaehlweise der Taster erfolgt von libks nachs rechts, 
00244  * wenn der Asuro mit den Tastern nach oben zeigt) */
00245 #define K1 (1<<5)
00246 #define K2 (1<<4)
00247 #define K3 (1<<3)
00248 #define K4 (1<<2)
00249 #define K5 (1<<1)
00250 #define K6 (1<<0)
00251 
00252 /* --- Globale Variablen -----------------------------------*/
00256 extern const char version[5];
00257 
00258 /*
00259  * Tastsensor Wert bei Interrupt Betrieb. 0=keine Taste, 1= Taste gedrueckt
00260  */
00269 extern int switched;
00270 
00271 /*
00272  * Odometriesensor Zaehler bei Interrupt Betrieb.
00273  * encoder[0] links, encoder[1] = rechts.
00274  */
00282 extern int encoder[2];
00283 
00284 /*
00285  * Counter fuer 36kHz.
00286  * Wird in der Interrupt Funktion SIG_OVERFLOW2 hochgezaehlt\n
00287  * und in der Sleep() Funktion abgefragt.
00288  */
00289 extern volatile unsigned char count36kHz;
00290 
00291 /*
00292  * Sytemzeit in ms.
00293  * Wird in der Interrupt Funktion SIG_OVERFLOW2 hochgezaehlt
00294  * und in der Gettime() Funktion verwendet.
00295  */
00296 extern volatile unsigned long timebase;
00297 
00298 /*
00299  * Odometrie Sensor Abfrage im Interrupt Betrieb.
00300  * Wird in der Interrupt Funktion SIG_ADC abgefragt,
00301  * in der EncoderInit() und EncoderStart() Funktion gesetzt
00302  * und in der EncoderStop() Funktion geloescht.
00303  */
00304 extern volatile int autoencode;
00305 
00306 /* --- Funktions Prototypen -----------------------------------*/
00307 
00313 void Init(void);
00314 
00315 /**************** Zeit- und Delay Funktionen time.c *********/
00320 unsigned long Gettime(void);
00326 void Msleep(int ms);
00332 void Sleep(unsigned char time36kHz);
00333 
00334 /**************** Low Level Encoder Funktionen encoder_low.c */
00340 void EncoderInit(void);
00347 void EncoderSet(int setl,int setr);
00352 void EncoderStop(void);
00357 void EncoderStart(void);
00358 
00359 /**************** Encoder Funktionen encoder.c **************/
00366 void Go(int distance, int speed);
00373 void Turn(int degree, int speed);
00374 
00375 /**************** A/D Wandler Funktionen adc.c **************/
00381 int Battery(void);
00387 void LineData(unsigned int *data);
00393 void OdometryData(unsigned int *data);
00394 
00395 // aus Nostalgiegruenden Defines fuer alte Funktionsnamen 
00396 #define Batterie Battery 
00397 #define OdometrieData OdometryData
00398 
00399 /**************** LED Funktionen led.c **********************/
00405 inline void StatusLED(unsigned char color);
00411 inline void FrontLED(unsigned char status);
00418 void BackLED(unsigned char left, unsigned char right);
00419 
00420 /**************** Low Level Motorsteuerungs Funktionen motor_low.c */
00428 inline void MotorDir(unsigned char left_dir, unsigned char right_dir);
00436 inline void MotorSpeed(unsigned char left_speed, unsigned char right_speed);
00437 
00438 /**************** Motorsteuerungs Funktionen motor.c **************/
00439 void SetMotorPower(int8_t leftpwm, int8_t rightpwm);
00440 
00441 /******************** Low Level UART Funktionen uart.c ************/
00448 void SerWrite(unsigned char *data,unsigned char length);
00456 void SerRead(unsigned char *data, unsigned char length, unsigned int timeout);
00457 
00458 /**************** UART Funktionen serielle Ausgabe uart.c ********/
00459 void UartPutc(unsigned char zeichen);
00460 void SerPrint(unsigned char *data);
00461 void PrintInt(int wert);
00462 void PrintLong(long wert);
00463 
00464 /**************** Taster Funktionen switches.c ******************/
00470 unsigned char PollSwitch (void);
00477 void StartSwitch(void);
00484 void StopSwitch(void);
00485 
00486 /**************** Soundausgabe sound.c **************************/
00487 void Sound(uint16_t freq, uint16_t duration_msec, uint8_t amplitude);
00488 
00489 /* ----------- END ------------ */
00490 
00491 
00492 /* --------------- INTERNAL ------------- */
00493 #define GREEN_LED_ON  PORTB |=  GREEN_LED 
00494 #define GREEN_LED_OFF PORTB &= ~GREEN_LED 
00495 #define RED_LED_ON    PORTD |=  RED_LED   
00496 #define RED_LED_OFF   PORTD &= ~RED_LED   
00498 #define FWD (1 << PB5)                    
00499 #define RWD (1 << PB4)                    
00500 #define BREAK 0x00                        
00501 #define FREE  (1 << PB4) | (1 << PB5)     
00503 #define IRTX        (1 << PB3)            
00504 #define GREEN_LED   (1 << PB0)            
00505 #define RED_LED     (1 << PD2)            
00507 #define PWM       (1 << PB1) | (1 << PB2) 
00508 #define RIGHT_DIR (1 << PB4) | (1 << PB5) 
00509 #define LEFT_DIR  (1 << PD4) | (1 << PD5) 
00511 #define SWITCHES   (1 << PD3)             
00512 #define SWITCH_ON  PORTD |= SWITCHES      
00513 #define SWITCH_OFF PORTD &= ~SWITCHES     
00515 #define BATTERIE  (1 << MUX0) | (1 << MUX2)   
00516 #define SWITCH    (1 << MUX2)                 
00517 #define IR_LEFT   (1 << MUX0) | (1 << MUX1)   
00518 #define IR_RIGHT  (1 << MUX1)                 
00519 #define FRONT_LED (1 << PD6)                  
00521 #define ODOMETRIE_LED     (1 << PD7)              
00522 #define ODOMETRIE_LED_ON  PORTD |= ODOMETRIE_LED  
00523 #define ODOMETRIE_LED_OFF PORTD &= ~ODOMETRIE_LED 
00525 #define WHEEL_LEFT   (1 << MUX0)              
00526 #define WHEEL_RIGHT  0                        
00528 #endif /* ASURO_H */

Erzeugt am Mon Apr 9 13:28:39 2007 für ASURO Library von  doxygen 1.5.1-p1