/* WILL-I V2.0 vezerlo program
Nyomogomb: PD4-es labra kotve
Bal mikrokapcsolo: PD2-es labra kotve (INT0)
Jobb mikrokapcsolo: PD3-es labra kotve (INT1)
Sharp IR szenzor: PC0-as (ADC0) labra kotve
*/
//---------------------------------------------------------------------
#define F_CPU 1000000UL // 1 MHz-es CPU orajel megadasa
#define jobbra 16 // Szervo jobb szelso pozicio
#define kozepre 23 // Szervo kozepso (Neutral) pozicio
#define balra 31 // Szervo bal szelso pozicio
#include <util/delay.h> // idozito, keslelteto rutinokat tart. fajl
#include <avr/io.h> //AVR konstansokat, beallitasokat tart. fájl
#include <avr/interrupt.h> // Megszakitasokat kezelo rutinokat tart. fajl
#include <util/dcmotor.h> // motorvezerlo utasitasokat tart. fajl
volatile int SharpIR = 0;
volatile int SharpIRjobb = 0;
volatile int SharpIRbal = 0;
volatile int Balkapcs = 0;
volatile int Jobbkapcs = 0;
void Konfig10bitADC() // ADC konfiguralas (beallitas)
{
ADMUX |= (1<<REFS0); // Vcc mint referencia
ADCSRA = (1<<ADEN) | (1<<ADPS1) | (1<<ADPS0); // ADC engedelyezese, ADC eloosztas = 8 (125 KHz)
}
unsigned int Beolvas10bitADC(unsigned char csatorna)
{
ADMUX = (ADMUX & 0b11110000) | csatorna;
ADCSRA |= (1<<ADSC); // elso ADC konverzio elinditasa
while (ADCSRA & (1<<ADSC)); // varas az atalakitasra
ADCSRA |= (1<<ADSC); // masodik ADC konverzió elindítás
while (ADCSRA & (1<<ADSC)); // varas az atalakitasra
return (ADCL | (ADCH<<8)); // ADC ertek kiolvasasa
}
void KonfigSzervo() // Szervo konfiguralas (beallitas)
{
DDRB = _BV(DDB3); // PORTB 3. lab kimenet (Szervo PWM)
TCCR2 = _BV(WGM20) // Timer2 8bites gyors PWM mod
| _BV(WGM21) // Timer2 8bites gyors PWM mod
| _BV(COM21) // nem-invertalt PWM
| _BV(CS22); // Timer2 eloosztas: 1/64 (61 Hz-es PWM impulzus frekvencia)
OCR2 = 23; // 1.5ms-os kezdeti PWM impulzus (Szervo kozepso (Neutral) pozicio)
}
void Szervo(unsigned char pozicio) // Szervo pozicionalo utasitas
{
OCR2 = pozicio;
}
ISR (INT0_vect) // INT0 megszakitas kiszolgalo rutin utasitasai (Bal mikrokapcsolo)
{
GICR &= ~(1<<INT0); // INT0 letiltasa (nyomogomb perges megakadalyozasa erdekeben)
motor_stop(mind); // Robot STOP!
Balkapcs = 1; //
}
ISR (INT1_vect) // INT1 megszakitas kiszolgalo rutin utasitasai (Jobb mikrokapcsolo)
{
GICR &= ~(1<<INT1); // INT1 letiltasa (nyomogomb perges megakadalyozasa erdekeben)
motor_stop(mind); //Robot STOP!
Jobbkapcs = 1; //
}
int main (void)
{
// portok beallitasa
PORTD |= (1<<PD4); // PD4-es lab bemenet, pull-up bekapcs (nyomogomb)
DDRC &= ~(1<<PC0); // PC0-as lab bemenet (Sharp IR szenzor)
PORTC = 0x00; // PORTC osszes laban a felhuzoellenallasok kikapcsolva
PORTD &= ~(1<<PD2); // PD2 bemenet
PORTD |= (1<<PD2); // PD2-hoz tartozo felhuzoellenallas be
PORTD &= ~(1<<PD3); // PD3 bemenet
PORTD |= (1<<PD3); // PD3-hoz tartozo felhuzoellenallas be
// az INT0 kulso interrupt beallitasa
GICR |= (1<<INT0); // INT0 engedelyezese (PD2-es lab)
MCUCR |= (1<<ISC01); // a lab lefuto elre adjon megszakítást
// az INT1 kulso interrupt beallitasa
GICR |= (1<<INT1); // INT0 engedelyezese (PD2-es lab)
MCUCR |= (1<<ISC11); // a lab lefuto elre adjon megszakítást
sei(); // megszakítások bekapcsolasa
KonfigSzervo(); // Szervo beallitas lefuttatasa
Konfig10bitADC(); // ADC beallitas lefuttatasa
while (PIND & (1<<PD4)); // varakozo cilkus amig PD4 erteke nem 0 (amig a gomb nincs lenyomva)
while (1)
{
// Ha INT0 megszakitas ki van kapcsolva, akkor egy kis varakozas utan bekapcsoljuk
if((GICR & (1<<INT0)) == 0)
{
// varakozas nehany szaz ms-ig, amig a nyomogomb befejezi a pergest
_delay_ms(250);
// minden tovabbi varakozo megszakitas torlese, majd a megszakitasok engedelyezese
GIFR |= (1<<INTF0); // INT0-hoz tartozo jelzobit torlese
GICR |= (1<<INT0); // INT0 megszakítás engedelyezese
}
// Ha INT1 megszakitas ki van kapcsolva, akkor egy kis varakozas utan bekapcsoljuk
if((GICR & (1<<INT1)) == 0)
{
// varakozas nehany szaz ms-ig, amig a nyomogomb befejezi a pergest
_delay_ms(250);
// minden tovabbi varakozo megszakitas torlese, majd a megszakitasok engedelyezese
GIFR |= (1<<INTF1); // INT1-hoz tartozo jelzobit torlese
GICR |= (1<<INT1); // INT1 megszakitas engedelyezese
}
if ( Balkapcs == 1 ) // Ha Bal oldali utkozes tortent, akkor
{
Balkapcs = 0; // Bal oldali utkozest jelzo valtozo torlese
hatra(100); // hatramenet
_delay_ms(1000); // 1.0 s kesleltetes
fordul_jobb(100); // fordulas jobbra
_delay_ms(500); // 0.5 s kesleltetes
}
if ( Jobbkapcs == 1 ) // Ha Jobb oldali utkozes tortent, akkor
{
Jobbkapcs = 0; // Jobb oldali utkozest jelzo valtozo torlese
hatra(100); // hatramenet
_delay_ms(1000); // 1.0 s kesleltetes
fordul_bal(100); // fordulas balra
_delay_ms(500); // 0.5 s kesleltetes
}
elore(100); // teljes gozzel elore!
SharpIR = Beolvas10bitADC(0);
if ( SharpIR > 200 )
{
motor_stop(mind);
Szervo(balra);
_delay_ms(500); // 0.5 s kesleltetes
SharpIRbal = Beolvas10bitADC(0);
_delay_ms(500); // 0.5 s kesleltetes
Szervo(jobbra);
_delay_ms(500); // 0.5 s kesleltetes
SharpIRjobb = Beolvas10bitADC(0);
_delay_ms(500); // 0.5 s kesleltetes
Szervo(kozepre);
if ( SharpIRbal > SharpIRjobb)
{
fordul_jobb(100); // fordulas balra 0.5 s
_delay_ms(500);
}
else
{
fordul_bal(100); //fordulas jobbra 0.5 s
_delay_ms(500);
}
}
else
{
_delay_ms(100); // 0.1 s kesleltetes
}
}
}