#include "main.h"

// NEPOUZIVAT PINY B6 A B7, JSOU VYHRAZENY PRO SERIOVOU KOMUNIKACI
// BAUD RATE = 9600
// ========================== PRIPRAVA DAT A VYSTUPU ===========================
// pomocne konstanty
#define  LEFT  0
#define  RIGHT 1

// konstanty a promenne pro sledovani cary
#define  SPACE 10                         // urcuje, za jak dlouho robot vi, ze nic nevidi
#define  SPD1  100                        // rychlost pomalejsiho motoru, kdyz je cara hodne z osy
#define  SPD2  200                        // rychlost pomalejsiho motoru, kdyz je cara z osy
#define  SPD3  200                        // rychlost rychlejsiho motoru pro vsechny pripady   
#define  SPD4  255                        // pro oba motory - rovinka
// oblasti cary 
#define  L1    20                         // nejvice vlevo
#define  L2    40
#define  L3    48 
#define  R1    52
#define  R2    60
#define  R3    80                         // nejvice vpravo

int8  action;                             // akce pro nastaveni motoru

// univerzalni LED diody
#define  LED1     PIN_E0
#define  LED2     PIN_E1

// piezo pipak
#DEFINE SOUND_HI   PIN_B4
#DEFINE SOUND_LO   PIN_B5

// radkovy senzor
#define  SDIN     PIN_D4                  // seriovy vstup
#define  SDOUT    input(PIN_C5)           // seriovy vystup
#define  SCLK     PIN_D5                  // takt

#define  LINE_PX  4                       // pocet pixelu pro jiste urceni cary
#define  OLSA_LEV 0x60                    // rozhodovaci uroven (cca 10 odpovida cerne)

// pro komunikaci s OLSA, prvni se posila LSB
int main_reset[8]={1,1,0,1,1,0,0,0};      // hlavni reset 0x1B
int set_mode_rg[8]={1,1,1,1,1,0,1,0};     // zapis do MODE registru 0x5F
int clear_mode_rg[8]={0,0,0,0,0,0,0,0};   // nulovani MODE registru 0x00

int left_offset[8]={0,0,0,0,0,0,1,0};     // offset leveho segmentu senzoru 0x40
int mid_offset[8]={0,1,0,0,0,0,1,0};      // offset prostredniho segmentu senzoru 0x42
int right_offset[8]={0,0,1,0,0,0,1,0};    // offset praveho segmentu senzoru 0x44
int offset[8]={1,0,0,0,0,0,0,1};          // minus jedna - pouzit pro vsechny segmenty 0x81

int left_gain[8]={1,0,0,0,0,0,1,0};       // zisk leveho segmentu 0x41
int mid_gain[8]={1,1,0,0,0,0,1,0};        // zisk leveho segmentu 0x43
int right_gain[8]={1,0,1,0,0,0,1,0};      // zisk leveho segmentu 0x45
int gain[8]={1,0,1,0,0,0,0,0};            // zisk = 5 - pouzit pro vsechny segmenty 0x5

int start_int[8]={0,0,0,1,0,0,0,0};       // zacatek integrace 0x08
int stop_int[8]={0,0,0,0,1,0,0,0};        // konec integrace 0x10
int readout[8]={0,1,0,0,0,0,0,0};         // cteni senzoru 0x02

int olsa_lseg[51]={0};                    // leva cast radky (pixely 0 - 50)
int olsa_rseg[51]={0};                    // prava cast radky (pixely 51 - 101)
int8  *lp;                                // ukazatel pro levou polovinu radky
int8  *rp;                                // ukazatel pro levou polovinu radky

int8  position;                           // ulozeni pozice cary
int8  old_position;                       // ulozeni predchozi pozice cary
int1  line_sector;                        // cara je vlevo/vpravo
int8  gap;                                // pocita, jak dlouho neni videt cara

// ================================= NARAZNIK ==================================
#define  BUMPL    input(PIN_D6)
#define  BUMPR    input(PIN_D7)

// ============================= NOUZOVE SENZORY ===============================
#define  LINEL    0
#define  LINER    1
#define  BLUE_LEV 200                     // rozhodovaci uroven (zmereno 0 - cerna, 255 cerna)
int8  line_l;
int8  line_r;

// ================================== MOTORY ===================================
#define  LMF   PIN_D0
#define  LMB   PIN_D1
#define  RMF   PIN_D2
#define  RMB   PIN_D3

int8 lm_speed;
int8 rm_speed;
int8 m;

// =============================== PODPROGRAMY =================================

// ================================= OLSA01A ===================================

void  olsa_pulses(int count)              // vytvori impulzy pro ridici logiku
{
   int8 ct;
   for(ct=0;ct<=count;ct++)
   {
      output_high(SCLK);
      output_low(SCLK);
   }
} 

void olsa_pulse()                         // vytvori jeden impulz
{
   output_high(SCLK);
   output_low(SCLK);
}

void olsa_send(int8 info[8])              // USART komunikace s modulem OLSA01A - poslani zpravy
{
   int *ip;                               // ukazatel na pole s informaci
   int8 i;                                // pomocna promenna pro nastaveni 0 nebo 1 na SDIN
   output_low(SDIN);                      // start bit
   olsa_pulse();
   for(ip=0;ip<8;ip++)                    // predani informace - 8 bit, LSB prvni > MSB posledni
   {
      i=info[ip];                         // ziskani hodnoty z pole
      if(i==1)                            // vyhodnoceni obsahu informace - nastav 1
      {
         output_high(SDIN);
      }
      else                                // vyhodnoceni obsahu informace - nastav 0
      {
         output_low(SDIN);
      }
      olsa_pulse();   
   }
   output_high(SDIN);                     // stop bit
   olsa_pulse();
}

void olsa_reset()                         // hlavni RESET - provadi se po zapnuti
{
   output_low(SDIN);
   output_low(SCLK);
   olsa_pulses(30);                       // reset radkoveho senzoru
   output_high(SDIN);
   olsa_pulses(10);                       // start bit - synchronizace
   olsa_send(main_reset);
   olsa_pulses(5);
   olsa_send(set_mode_rg);
   olsa_send(clear_mode_rg);
}
   
void olsa_setup()                         // kompletni nastaveni, provadi se po resetu
{
   olsa_send(left_offset);                // nastaveni leveho segmentu (offset a zisk)
   olsa_send(offset);
   olsa_send(left_gain);
   olsa_send(gain);
   olsa_send(mid_offset);                 // nastaveni prostredniho segmentu (offset a zisk)
   olsa_send(offset);
   olsa_send(mid_gain);
   olsa_send(gain); 
   olsa_send(right_offset);               // nastaveni praveho segmentu (offset a zisk)
   olsa_send(offset);
   olsa_send(right_gain);
   olsa_send(gain); 
}
   
void olsa_integration()                   // snimani pixelu
{
   olsa_send(start_int);                  // zacatek integrace senzoru
   olsa_pulses(22);
   olsa_send(stop_int);                   // konec integrace senzoru
   olsa_pulses(5);
}

void read_olsa()
{
   int8  cpixel;                          // pocet prectenych pixelu
   int8  cbit;                            // pocet prectenych bitu
   int8  pixel;                           // hodnota precteneho pixelu      
   cpixel=0;
   lp=0;
   rp=0;
   olsa_integration();
   olsa_send(readout);
   do                                     // precte 102 pixelu
   {
      if(!SDOUT)                          // zacatek prenosu - zachycen start bit
      {  
         pixel=0;
         for(cbit=0;cbit<8;cbit++)        // cte jednotlive bity (8 bitu - 0 az 7)         
         {
            olsa_pulse();                 // impulz pro generovani dalsiho bitu
            if(SDOUT)                     // zachycena 1                        
            {
               pixel|=1;                  // zapise do bitu pixelu 1 - OR
            }
            else                          // zachycena 0
            {
               pixel|=0;                  // zapise do bitu pixelu 0 - OR
            }
            pixel<<=1;                    // posune pixel
         }
         olsa_pulse();                    // generuje stop bit
         if(cpixel<52)                    // ulozeni do pole
         {
            olsa_lseg[lp]=pixel;          // leva polovina radky - leve pole
            lp++;
         }
         else
         {
            olsa_rseg[rp]=pixel;          // prava polovina cary - prave pole
            rp++;
         }
         cpixel++;
      }
      else
      {
         olsa_pulse();                    // generuje start bit, nebyl-li poslan
      }
   }
   while(cpixel<102);                     // precte 102 pixelu
}

void olsa_position()                      // vyhodnoti pozici cary
{
   int8  searchp;                         // ukazatel na pole
   int8  search;                          // ulozeni prectene hodnoty
   int8  protect_count;                   // opravdu vidime caru 
   position=0;                            // nuluje pozici, pokud cara neni, ulozena 0
   for(searchp=0;searchp<52;searchp++)    // prohlizi levou cast cary
   {
      search=olsa_lseg[searchp];          // vybira pixel
      if(search==OLSA_LEV)                // cerna nebo bila?
      {
         protect_count++;                 // pokud nasleduje cerna, pricte 1 k poctu cernych pixelu
      }
      else
      {
         protect_count=0;                 // pokud nasleduje bila, pocet cernych pixelu vynuluje
      }
      if(protect_count>LINE_PX)           // vidim caru
      {
         position=searchp;                // zapis presnou pozici
         line_sector=LEFT;                // cara je v leve polovine
         searchp=55;                      // ukonci hledani
      }
   }
   for(searchp=0;searchp<52;searchp++)    // prohlizi pravou cast cary
   {
      search=olsa_rseg[searchp];          // vybira pixel
      if(search==OLSA_LEV)
      {
         protect_count++;                 // pokud nasleduje cerna, pricte 1 k poctu cernych pixelu
      }
      else
      {
         protect_count=0;                 // pokud nasleduje bila, pocet cernych pixelu vynuluje
      }
      if(protect_count>LINE_PX)           // vidim caru
      {
         position=(searchp+50);           // zapis presnou pozici
         line_sector=RIGHT;               // cara je v prave polovine                   
         searchp=55;                      // ukonci hledani
      }
   }
}

// ============================ ZACHRANNE SENZORY ==============================

void read_blue_sensors()                        // cteni nouzovych senzoru
{
   set_adc_channel(LINEL);                      // cti levy nouzovy senzor
   delay_us(10);
   line_l=read_adc();     
   set_adc_channel(LINER);                      // cti pravy nouzovy senzor
   delay_us(10);
   line_r=read_adc();
}
   
// ================================== PIPAK ====================================

void beep(int16 period,int16 length)
{
   int16 bp;                                    // promenna pro nastaveni delky
   for(bp=length;bp>0;bp--)                     // prepina vystupy tolikrat, jakou jsme zadali delku
   {
      output_high(SOUND_HI);
      output_low(SOUND_LO);
      delay_us(period);
      output_high(SOUND_LO);
      output_low(SOUND_HI);
      delay_us(period);
   }
}   

// ================================== MOTORY ===================================

void l_motor_fwd(int8 speedl)                   // levy motor dopredu
{
   output_high(LMF);
   output_low(LMB);
   set_pwm2_duty(speedl);
}

void l_motor_bwd(int8 speedl)                   // levy motor dozadu
{
   output_high(LMB);
   output_low(LMF);
   set_pwm2_duty(speedl);
}

void r_motor_fwd(int8 speedr)                   // pravy motor dopredu
{
   output_high(RMF);
   output_low(RMB);
   set_pwm1_duty(speedr);
}

void r_motor_bwd(int8 speedr)                   // pravy motor dozadu
{
   output_high(RMB);
   output_low(RMF);
   set_pwm1_duty(speedr);
}

void l_motor_off()                              // levy motor vypnut
{
   output_low(LMF);
   output_low(LMB);
   set_pwm2_duty(0);
}
   
void r_motor_off()                              // pravy motor vypnut
{  
   output_low(RMF);
   output_low(RMB);
   set_pwm1_duty(0);
}

void motor_test()                               // TEST MOTORU
{
   int8  i;
   beep(100,200);
   printf("TEST MOTORU\r\n");
   delay_ms(1000);
   printf("LEVY MOTOR DOPREDU\r\n");
   delay_ms(1000);
   for(i=0;i<255;i++)                           // levy motor dopredu - zrychluje
   {
      l_motor_fwd(i);
      printf("RYCHLOST: %u\r\n",i);
      delay_ms(5);
   }
   for(i=255;i>0;i--)                           // levy motor dopredu - zpomaluje
   {
      l_motor_fwd(i);
      printf("RYCHLOST: %u\r\n",i);
      delay_ms(5);
   }   
   printf("LEVY MOTOR DOZADU\r\n");             // levy motor dozadu - zrychluje
   delay_ms(1000);
   for(i=0;i<255;i++)
   {
      l_motor_bwd(i);
      printf("RYCHLOST: %u\r\n",i);
      delay_ms(5);
   }   
   for(i=255;i>0;i--)                           // levy motor dozadu - zpomaluje
   {
      l_motor_bwd(i);
      printf("RYCHLOST: %u\r\n",i);
      delay_ms(5);
   }   
   printf("PRAVY MOTOR DOPREDU\r\n");     
   delay_ms(1000);
   for(i=0;i<255;i++)                           // pravy motor dopredu - zrychluje
   {
      r_motor_fwd(i);
      printf("RYCHLOST: %u\r\n",i);
      delay_ms(5);
   }   
   for(i=255;i>0;i--)                           // pravy motor dopredu - zpomaluje
   {
      r_motor_fwd(i);
      printf("RYCHLOST: %u\r\n",i);
      delay_ms(5);
   }   
   printf("PRAVY MOTOR DOZADU\r\n");
   delay_ms(1000);
   for(i=0;i<255;i++)                           // pravy motor dozadu - zrychluje
   {
      r_motor_bwd(i);
      printf("RYCHLOST: %u\r\n",i);
      delay_ms(5);
   }   
   for(i=255;i>0;i--)                           // pravy motor dozadu - zpomaluje
   {
      r_motor_bwd(i);
      printf("RYCHLOST: %u\r\n",i);
      delay_ms(5);
   }
   l_motor_off();                               // po ukonceni testu vypnout motory    
   r_motor_off();
   printf("KONEC TESTU MOTORU\r\n");      
   delay_ms(1000);
}

// ================================ DIAGNOSTIKA ================================

void diag()                                     // diagnostika - vypis senzoru s moznosti prepnuti na test motoru
{
   read_blue_sensors();
   read_olsa();
   olsa_position();
   printf("LEVA: %u \t",line_l);                // tiskne z leveho senzoru
   printf("PRAVA: %u \t",line_r);               // tiskne z praveho senzoru
   printf("POLOHA: %u\t",position);             // tiskne pozici OLSA 
   printf("L_NARAZ: %u \t",BUMPL);              // leve tlacitko narazniku
   printf("P_NARAZ: %u \r\n",BUMPR);            // prave tlacitko narazniku
   if(BUMPL&&BUMPR)                             // po zmacknuti stran narazniku spusti test motoru
   {
      beep(100,1000);
      printf("Levy naraznik - test OLSA\r\n");
      printf("Pravy naraznik - test motoru\r\n");
      delay_ms(500);
      while(true)
      {
         if(BUMPR)
         {
            beep(100,500);                      // pipni pri startu
            motor_test();
         }
         if(BUMPL)
         {
            beep(100,500);
            printf("TEST OLSA\r\n");
            while(true)
            {
               int8  tisk;
               int8  *tiskp;
               read_olsa();
               printf("cteni\r\n");             // po precteni vsech pixelu odradkuje
               for(tiskp=0;tiskp<52;tiskp++)    // tisk leve casti radky
               {
                  tisk=olsa_lseg[tiskp];
                  printf("%x ",tisk);
               }
               for(tiskp=0;tiskp<52;tiskp++)    // tisk prave casti radky
               {
                  tisk=olsa_rseg[tiskp];
                  printf("%x ",tisk);
               }
            }
         }     
      }
   }   
}

// ============================== HLAVNI SMYCKA ================================

void main()
{
   printf("POWER ON \r\n");
   // NASTAVENI > provede se pouze pri zapnuti
   setup_adc_ports(sAN0-sAN1-sAN2);                   // aktivní analogové vstupy RA0, RA1 a RA2         
   setup_adc(ADC_CLOCK_INTERNAL);                     // interni hodniny pro AD prevodnik
   setup_spi(SPI_SS_DISABLED);
   setup_timer_0(RTCC_INTERNAL|RTCC_DIV_1);
   setup_timer_1(T1_DISABLED);
   setup_timer_2(T2_DIV_BY_16,255,1);                 // casovac pro PWM
   setup_ccp1(CCP_PWM);                               // povoli PWM na pinu RC2
   setup_ccp2(CCP_PWM);                               // povolí PWM na pinu RC1
   setup_comparator(NC_NC_NC_NC);
   setup_vref(FALSE);
   l_motor_off();                                     // vypne levy motor
   r_motor_off();                                     // vypne pravy motor
   output_high(LED1);                                 // zhasne LED1
   output_high(LED2);                                 // zhasne LED2
   olsa_reset();
   olsa_setup();
   beep(100,500);                                     // pipni pri startu
   printf("OK! \r\n");
   delay_ms(500);
   printf("VYBRAT MOD... \r\n");
   while(true)
   {
// ============================ HLAVNI CAST PROGRAMU ===========================
      if(BUMPR)                                       // spusteni hledani pravym naraznikem
      { 
         beep(100,500);
         while(true)
         {
// =============================== SLEDOVANI CARY ==============================
            old_position=position;                    // zaznamena predhozi polohu cary
            read_olsa();                              // precte a ulozi hodnoty z olsa
            olsa_position();                          // vyhodnoti pozici cary
            read_blue_sensors();                      // cte nouzove senzory
            if(line_l==0)                             // robot najede na levy nouzovy senzor
            {
               l_motor_bwd(150);                      // prudce zatoc doleva
               r_motor_fwd(255);
               line_sector=LEFT;                      // pamatuj, kde je cara
               delay_ms(200);
            }
            if(line_r==0)                             // robot najede na pravy nouzovy senzor
            {
               l_motor_fwd(255);                      // prudce zatoc doprava
               r_motor_bwd(150);
               line_sector=RIGHT;                     // pamatuj, kde je cara
               delay_ms(200);
            }
            if(position==0)                           // pokud neni videt cara
            {
               position=old_position;                 // nastav predchozi pozici
               gap++;                                 // pocita, jak dlouho neni videt cara
            }
            else                                      // pokud je videt cara
            {     
               gap=0;                                 // vynuluje citani
               m=0;                                   // pry svetsovani hulu zataceni
            }
            if(gap>SPACE)                             // dlouho neni nic videt
            {
               if(line_sector==LEFT)                  // cara byla naposledy vlevo
               {
                  l_motor_bwd(50+m);                  // zatacej doleva
                  r_motor_fwd(200);
                  m++;
               }
               else                                   // cara byla naposledy vpravo
               {
                  r_motor_bwd(50+m);                  // zatacej doprava
                  l_motor_fwd(200);
                  m++;
               }
            }
            if(position>0)                            // urceni akci pro rizeni, pokud cara je videt                           
            {
               if(position>L1)                        // cara je hodne vlevo                                              
               {
                  if(position>L2)                     // cara je vlevo
                  {
                     if(position>L3)                  // cara je mirne vlevo
                     {
                        if(position>R1)               // cara je mirne vpravo
                        {
                           if(position>R2)            // cara je vpravo
                           {
                              if(position>R3)         // cara je hodne vpravo
                              {
                                 action=6;
                              }
                           }
                           else
                           {
                              action=5;
                           }
                        }
                        else
                        {
                           action=4;
                        }
                     }
                     else
                     {
                        action=3;
                     }
                  }
                  else
                  {
                     action=2;
                  }
               }
               else
               {
                  action=1;
               }
            }
            if(L3<position>R1)                        // cara je uprostred
            {
               action=7;
            }
            switch(action)                            // reakce na pohyb cary
            {
               case 1:                                // cara je hodne vlevo
                  rm_speed=(SPD3+position);
                  lm_speed=(SPD1+position);
                  r_motor_fwd(rm_speed);
                  l_motor_bwd(lm_speed);
                  break;
               case 2:                                // cara je vlevo
                  rm_speed=(SPD3+position);
                  r_motor_fwd(rm_speed);
                  l_motor_off();
                  break;
               case 3:                                // cara je mirne vlevo
                  rm_speed=(SPD3+position);
                  lm_speed=(SPD2-position);
                  r_motor_fwd(rm_speed);
                  l_motor_fwd(lm_speed);
                  break;
               case 4:                                // cara je mirne vpravo
                  lm_speed=(SPD3+(position/2));
                  rm_speed=(SPD2-(position/2));
                  l_motor_fwd(lm_speed);
                  r_motor_fwd(rm_speed);
                  break;
               case 5:                                // cara je vpravo
                  lm_speed=(SPD3+(position/2));
                  l_motor_fwd(lm_speed);
                  r_motor_off();
                  break;
               case 6:                                // cara je hodne vpravo
                  lm_speed=(SPD3+(position/2));
                  rm_speed=(SPD2-(position/2));
                  l_motor_fwd(lm_speed);
                  r_motor_bwd(rm_speed);
                  break;
               case 7:                                // cara je uprostred 
                  l_motor_fwd(SPD4);
                  r_motor_fwd(SPD4);
                  break;
            }
         }
      }
   }
}