Mini sumo robot

Başlatan MUHAFIZ, 23 Şubat 2014, 01:21:03

MUHAFIZ

Selamun aleyküm Ustalar...Öncelikle aşşagıda vermiş oldugum devrede bazı anlamadıgım yerleler oldu Bana yardımcı Olursanız sevinirim Burdaki S1 S2 S3 S4 S5 S6 girişlerinin ne oldugunu ve J2 J3 J4 J5 USB girişinin arkasındaki bi kutu gibi bişey var acaba o ned,r ve ve girişleri merak ediyorum ordaki butonlar nedir açıklarsanız sevinirim...









/*
Mini Sumo Robot: Katakulli
Created by MERT ÖZTOPRAK
mertoztoprak@gmail.com
For more information: mertoztoprak.wordpress.com
*/

#include "mouse.h"

#include <usb_bootloader.h>
#include <usb_cdc.h>
#include <stdlib.h>

#define solled pin_b5
#define ortaled pin_b6
#define sagled pin_b7
#define sagmotorgeri pin_b2
#define sagmotorileri pin_b3
#define solmotorgeri pin_b1
#define solmotorileri pin_b0                                                                                                                                         
//#define solsensor pin_a3
//#define ortasensor pin_a4
//#define sagsensor pin_a5
#define gerigidiyor pin_c7
#define ilerigidiyor pin_e3

#use fast_io (a)
//use fast_io (b)
#use fast_io (c)
char fare='e';
char data=0;
int16 zaman=0;
int1 yon=0;
int16 solmotor=0;
int16 sagmotor=0;
char RcvUSB;
int1 gerigitti=0;
long limit=0;
signed long i=0;
int1 x=0;
int1 yay=0;       


int1 solcizgi()
{
set_adc_channel(0);
delay_us(4);
if (read_adc()<40)
return 1;
else
return 0;
}

int1 sagcizgi()
{
set_adc_channel(1);
delay_us(4);
if (read_adc()<40)
return 1;
else
return 0;
}

void ileri(long solmotor,long sagmotor)
{
output_bit(solmotorileri,1);
output_bit(solmotorgeri,0);
output_bit(sagmotorileri,1);
output_bit(sagmotorgeri,0);
set_pwm1_duty(sagmotor);
set_pwm2_duty(solmotor);
}

void geri(long solmotor,long sagmotor)
{
output_bit(solmotorileri,0);
output_bit(solmotorgeri,1);
output_bit(sagmotorileri,0);
output_bit(sagmotorgeri,1);
set_pwm1_duty(sagmotor);
set_pwm2_duty(solmotor);
}

void sola(long solmotor,long sagmotor)
{
output_bit(solmotorileri,0);
output_bit(solmotorgeri,1);
output_bit(sagmotorileri,1);
output_bit(sagmotorgeri,0);
set_pwm1_duty(sagmotor);
set_pwm2_duty(solmotor);
}

void saga(long solmotor,long sagmotor)
{
output_bit(solmotorileri,1);
output_bit(solmotorgeri,0);
output_bit(sagmotorileri,0);
output_bit(sagmotorgeri,1);
set_pwm1_duty(sagmotor);
set_pwm2_duty(solmotor);
}

int1 solsensor()
{
if (input(pin_a3)==0)
return 1;
else
return 0;
}

int1 ortasensor()
{
if (input(pin_a4)==0)
return 1;
else
return 0;
}

int1 sagsensor()
{
if (input(pin_a5)==0)
return 1;
else
return 0;
}

void birsuresoladon()
{
enable_interrupts(INT_TIMER0);
enable_interrupts(GLOBAL);
   
output_bit(solled,1);
output_bit(ortaled,0);
output_bit(sagled,0);
   
   while((ortasensor()==0)&&(sagsensor()==0)&&(zaman<70))
   {
   output_bit(solmotorileri,0);
   output_bit(solmotorgeri,1);
   output_bit(sagmotorileri,1);
   output_bit(sagmotorgeri,0);
   solmotor=200;
   sagmotor=1000;   
   set_pwm1_duty(sagmotor);
   set_pwm2_duty(solmotor);
   }
   
disable_interrupts(INT_TIMER0);
disable_interrupts(GLOBAL);
zaman=0;

}   

void birsuresagadon()
{
//ilk 2 saniye boyunca birşey görene kadar dön
enable_interrupts(INT_TIMER0);
enable_interrupts(GLOBAL);
 
   output_bit(solled,0);
   output_bit(ortaled,0);
   output_bit(sagled,1);

   while((ortasensor()==0)&&(solsensor()==0)&&(zaman<70))
   {         
   output_bit(solmotorileri,1);
   output_bit(solmotorgeri,0);
   output_bit(sagmotorileri,0);
   output_bit(sagmotorgeri,1);
   solmotor=1000;
   sagmotor=200;//400
   set_pwm1_duty(sagmotor);
   set_pwm2_duty(solmotor);
   }       
   
disable_interrupts(INT_TIMER0);
disable_interrupts(GLOBAL);
zaman=0;

}

void gezerkencizgigorurse()
{

      if(sagcizgi()==1)
      {
      zaman=0;
      enable_interrupts(INT_TIMER0);
      enable_interrupts(GLOBAL);
      gerigitti=0; 
//         for(i=800;i>1;i=i-20)
//         {
//         ileri(i,i);
//         delay_us(1);
//         }
//         for(i=1;i<800;i=i+20)
//         {
//         geri(i,i);
//         delay_us(1);
//         }       
         
         while(zaman<36) //while((solsensor()==0)&&(ortasensor()==0)&&(sagsensor()==0)&&(zaman<30))
         {
         geri(800,800);
         gerigitti=1;
         }

         limit=(((rand())%4)+3)*10;
         for(i=800;i>=1;i--)
         {
         geri(800,i);
         delay_us(30);
         }
         for(i=1;i<=800;i++)
         {
         sola(800,i);
         delay_us(30);
         }
         zaman=0;
         while((solsensor()==0)&&(ortasensor()==0)&&(sagsensor()==0)&&(gerigitti==1)&&(zaman<limit))
         {
         sola(800,800);
         }
         disable_interrupts(INT_TIMER0);
         disable_interrupts(GLOBAL);
         zaman=0;
      }
     
     
      if(solcizgi()==1)
      {
      zaman=0;
      enable_interrupts(INT_TIMER0);
      enable_interrupts(GLOBAL);
      gerigitti=0;       
//         for(i=800;i>1;i=i-20)
//         {
//         ileri(i,i);
//         delay_us(1);
//         }
//         for(i=1;i<800;i=i+20)
//         {
//         geri(i,i);
//         delay_us(1);
//         }       
     
         while(zaman<36) //while((solsensor()==0)&&(ortasensor()==0)&&(sagsensor()==0)&&(zaman<30))
         {                 
         geri(800,800);
         gerigitti=1;
         }
         limit=(((rand())%4)+3)*10;
         for(i=800;i>=1;i--)
         {
         geri(i,800);
         delay_us(30);
         }
         for(i=1;i<=800;i++)
         {
         saga(800,i);
         delay_us(30);
         }
         zaman=0;
         while((solsensor()==0)&&(ortasensor()==0)&&(sagsensor()==0)&&(gerigitti==1)&&(zaman<limit))
         {
         saga(800,800);
         }
         disable_interrupts(INT_TIMER0);
         disable_interrupts(GLOBAL);
         zaman=0;
     
      }

}

void sensorgorupcizgigorurse()
{

if(sagcizgi()==1)
      {
      zaman=0;
      enable_interrupts(INT_TIMER0);
      enable_interrupts(GLOBAL);
      gerigitti=0; 
//         for(i=800;i>1;i=i-20)
//         {
//         ileri(i,i);
//         delay_us(1);
//         }
//         for(i=1;i<800;i=i+20)
//         {
//         geri(i,i);
//         delay_us(1);
//         }       
         
         while(zaman<36) //while((solsensor()==0)&&(ortasensor()==0)&&(sagsensor()==0)&&(zaman<30))
         {
         geri(800,800);
         gerigitti=1;
         }

         limit=(((rand())%4)+3)*10;
         for(i=800;i>=1;i--)
         {
         geri(800,i);
         delay_us(30);
         }
         for(i=1;i<=800;i++)
         {
         sola(800,i);
         delay_us(30);
         }
         zaman=0;
         while((solsensor()==0)&&(ortasensor()==0)&&(sagsensor()==0)&&(gerigitti==1)&&(zaman<limit))
         {
         sola(800,800);
         }
         disable_interrupts(INT_TIMER0);
         disable_interrupts(GLOBAL);
         zaman=0;
      }
     
     
      if(solcizgi()==1)
      {
      zaman=0;
      enable_interrupts(INT_TIMER0);
      enable_interrupts(GLOBAL);
      gerigitti=0;       
//         for(i=800;i>1;i=i-20)
//         {
//         ileri(i,i);
//         delay_us(1);
//         }
//         for(i=1;i<800;i=i+20)
//         {
//         geri(i,i);
//         delay_us(1);
//         }       
     
         while(zaman<36) //while((solsensor()==0)&&(ortasensor()==0)&&(sagsensor()==0)&&(zaman<30))
         {                 
         geri(800,800);
         gerigitti=1;
         }
         limit=(((rand())%4)+3)*10;
         for(i=800;i>=1;i--)
         {
         geri(i,800);
         delay_us(30);
         }
         for(i=1;i<=800;i++)
         {
         saga(800,i);
         delay_us(30);
         }
         zaman=0;
         while((solsensor()==0)&&(ortasensor()==0)&&(sagsensor()==0)&&(gerigitti==1)&&(zaman<limit))
         {
         saga(800,800);
         }
         disable_interrupts(INT_TIMER0);
         disable_interrupts(GLOBAL);
         zaman=0;
     
      }

}

void mousegerigidiyorsa()
{

if(input(gerigidiyor)==1)
      {
  enable_interrupts(INT_TIMER0);
  enable_interrupts(GLOBAL);
  zaman=0;
   while((zaman<50)&&(((solsensor()==1)&&(ortasensor()==1))||(ortasensor()==1)&&(sagsensor()==1)||(ortasensor()==1)))
   {
   ileri(1000,1000);
   }
   while((zaman>=50)&&(((solsensor()==1)&&(ortasensor()==1))||(ortasensor()==1)&&(sagsensor()==1)||(ortasensor()==1)))
   {
      ileri(1000,1000);
      if(input(gerigidiyor)==1)
      {
      geri(900,900);
      delay_ms(60);
      x=rand();
     
      if(x==1)
      {
     
      geri(1000,200);
      delay_ms(500);
      for(i=200;i>=1;i--)
      {
      geri(1000,i);
      delay_us(100);
      }
      for(i=1;i<=1000;i++)
      {
      sola(1000,i);
      delay_us(100);
      }
      while((solsensor()==0)&&(ortasensor()==0)&&(sagsensor()==0))
      {
      sola(1000,1000);
      }
      }
      else
      {
     
      geri(200,1000);
      delay_ms(500);
      for(i=200;i>=1;i--)
      {
      geri(i,1000);
      delay_us(100);
      }
      for(i=1;i<=1000;i++)
      {
      saga(i,1000);
      delay_us(100);
      }
      while((solsensor()==0)&&(ortasensor()==0)&&(sagsensor()==0))
      {
      saga(1000,1000);
      }
      }
     
      zaman=0;
      }
   
   }
   
   disable_interrupts(INT_TIMER0);
   disable_interrupts(GLOBAL);
   zaman=0;
     

      }}

void solayay()
{

ileri(0,1000);
delay_us(100);
ileri(700,1000);
delay_us(100);

}

void sagayay()
{

ileri(1000,0);
delay_us(100);
ileri(1000,700);
delay_us(100);

}


#int_TIMER0
void  TIMER0_isr()
{
   zaman++;
}

void main()
{


set_tris_a(0b00111111);
//set_tris_b(0b00011111);
//set_tris_d(0b00000000);
set_tris_c(0b10000001);
   setup_adc_ports(AN0_TO_AN1|VSS_VDD);
   setup_adc(ADC_CLOCK_INTERNAL);
   setup_spi (SPI_SS_DISABLED) ;
   setup_wdt (WDT_OFF) ;
   setup_timer_0(RTCC_INTERNAL|RTCC_DIV_2);
   setup_timer_1 (T1_DISABLED) ;
   setup_timer_2(T2_DIV_BY_16,239,1);
   setup_timer_3 (T3_DISABLED|T3_DIV_BY_1) ;
   setup_ccp1 (CCP_PWM);
   setup_ccp2 (CCP_PWM);
   set_pwm1_duty(solmotor);
   set_pwm2_duty(sagmotor);
   setup_comparator (NC_NC_NC_NC) ;
   setup_vref (FALSE) ;
 
  disable_interrupts(INT_TIMER0);
  disable_interrupts(GLOBAL);
 
  output_high(solled);
  output_low(ortaled);
  output_low(sagled);

  enable_interrupts(INT_TIMER0);
  enable_interrupts(GLOBAL);
  zaman=0;
  while(zaman<91)
  {
  if(input(pin_b4)==0)
  {
  yay=1;
  output_high(ortaled);
  }
  }
  while(zaman<91);
  zaman=0;
  disable_interrupts(INT_TIMER0);
  disable_interrupts(GLOBAL);

  delay_ms(4000); //Timerda geçen süre + 4 sn = 5 sn
 
output_low(pin_b5);
output_low(pin_b6);
output_low(pin_b7);

if (input(pin_c0)==0)
yon=0;
else
yon=1;

if(yay==1)
{
if (yon==0)
while((solsensor()==0)&&(ortasensor()==0)&&(sagsensor()==0))
{
solayay();
if((solcizgi()==1)||(sagcizgi()==1))
break;

}
else
while((solsensor()==0)&&(ortasensor()==0)&&(sagsensor()==0))
{
sagayay();
if((solcizgi()==1)||(sagcizgi()==1))
break;
}
}
else
{
if (yon==0)
while(1)
{                   

   birsuresoladon();
   if((solcizgi()==1)||(sagcizgi()==1))
   break;
   if((solsensor()==0)||(ortasensor()==0)||(sagsensor()==0))
   break;

}
else

while(1)
{                   

   birsuresagadon();
   if((solcizgi()==1)||(sagcizgi()==1))
   break;
   if((solsensor()==0)||(ortasensor()==0)||(sagsensor()==0))
   break;

}



}

basla:
while(1)
{

if((solsensor()==0)&&(ortasensor()==0)&&(sagsensor()==0))
{
  disable_interrupts(INT_TIMER0);
  disable_interrupts(GLOBAL);
  zaman=0;
ileri(800,800);
gezerkencizgigorurse();

}

if((solsensor()==1)&&(ortasensor()==0)&&(sagsensor()==0))
{
  disable_interrupts(INT_TIMER0);
  disable_interrupts(GLOBAL);
  zaman=0;
birsuresoladon();

}

if((solsensor()==0)&&(ortasensor()==0)&&(sagsensor()==1))
{
  disable_interrupts(INT_TIMER0);
  disable_interrupts(GLOBAL);
  zaman=0;

birsuresagadon();

}

if((solsensor()==0)&&(ortasensor()==1)&&(sagsensor()==0))
{

   ileri(1000,1000);
   
   //mousegerigidiyorsa();
   sensorgorupcizgigorurse();
   
   }

if((solsensor()==1)&&(ortasensor()==1)&&(sagsensor()==0))
{

ileri(800,1000);
   //mousegerigidiyorsa();
   sensorgorupcizgigorurse();
     
   }

if((solsensor()==0)&&(ortasensor()==1)&&(sagsensor()==1))
{

ileri(1000,800);

   //mousegerigidiyorsa();
   sensorgorupcizgigorurse();   

}

if((solsensor()==1)&&(ortasensor()==1)&&(sagsensor()==1))
{

ileri(1000,1000);
   
   //mousegerigidiyorsa();
   sensorgorupcizgigorurse();   
       
}



}

   //Setup_Oscillator parameter not selected from Intr Oscillotar Config tab
   // TODO: USER CODE!!


usb:

   usb_cdc_init();
   usb_init();

   while(!usb_cdc_connected()) {}

   do {
      usb_task();
      if (usb_enumerated()) {
         printf(usb_cdc_putc, "\r\nMerhaba !");
         RcvUSB = usb_cdc_getc();
         if (RcvUSB=='1')
         {


printf(usb_cdc_putc,"data= %c",fare);
delay_ms(50);
         }
         
         else if (RcvUSB=='2')
         {
 
         }
                  else if (RcvUSB=='3')
         {
       
         }
                else if (RcvUSB=='4')
         {

         }
                else if (RcvUSB=='5')
         {

         }
         else
            printf(usb_cdc_putc, "\r\nbu tusa bastin : %c",RcvUSB);
         
      }
   } while (TRUE);

while(1)
{
   for(i=1;i<900;i++)
   {
   ileri(i,i);
   delay_us(50);
   }
ileri(900,900);
delay_ms(500);
   for(i=900;i>1;i--)
   {
   ileri(i,i);
   delay_us(50);
   }
   for(i=1;i<900;i++)
   {
   geri(i,i);
   delay_us(50);
   }
geri(900,900);
delay_ms(500);
   for(i=900;i>1;i--)
   {
   geri(i,i);
   delay_us(50);
   }
}

while(1)
   
   {
output_bit(solmotorileri,1);
output_bit(solmotorgeri,0);
output_bit(sagmotorileri,0);
output_bit(sagmotorgeri,0);
solmotor=0;
sagmotor=600;
set_pwm1_duty(sagmotor);
set_pwm2_duty(solmotor);
delay_ms(2000);
output_bit(solmotorileri,0);
output_bit(solmotorgeri,1);
output_bit(sagmotorileri,0);
output_bit(sagmotorgeri,0);
solmotor=0;
sagmotor=600;
set_pwm1_duty(sagmotor);
set_pwm2_duty(solmotor);
delay_ms(2000);
output_bit(solmotorileri,0);
output_bit(solmotorgeri,0);
output_bit(sagmotorileri,1);
output_bit(sagmotorgeri,0);
solmotor=600;
sagmotor=600;
set_pwm1_duty(sagmotor);
set_pwm2_duty(solmotor);
delay_ms(2000);
output_bit(solmotorileri,0);
output_bit(solmotorgeri,0);
output_bit(sagmotorileri,0);
output_bit(sagmotorgeri,1);
solmotor=600;
sagmotor=600;
set_pwm1_duty(sagmotor);
set_pwm2_duty(solmotor);
delay_ms(2000);
   
   
   }
}
 

pıc de budur ben S1 S2 S3 S4 S5 S6 CONLARIN NE İŞE YARADIGINI BİDE BOOT NE İŞE YARADIGINI BULAMADIM