Subversion Repositories svnkaklik

Rev

Rev 246 | Go to most recent revision | Only display areas with differences | Ignore whitespace | Details | Blame | Last modification | View Log

Rev 246 Rev 247
1
//********* Robot Camerus pro IstRobot 2007 ************
1
//********* Robot Camerus pro IstRobot 2007 ************
2
//"$Id: camerus.c 246 2007-04-22 15:43:09Z kakl $"
2
//"$Id: camerus.c 247 2007-04-22 19:31:58Z kakl $"
3
//*****************************************************
3
//*****************************************************
4
 
4
 
5
#include ".\camerus.h"
5
#include ".\camerus.h"
6
 
6
 
7
#USE FAST_IO (C)     // Brana C je ve FAST_IO modu, aby slo rychle cist z kamery
7
#USE FAST_IO (C)     // Brana C je ve FAST_IO modu, aby slo rychle cist z kamery
8
 
8
 
9
// Rychlostni konstanty
9
// Rychlostni konstanty
10
#define RR_CIHLA     30       // Rozumna rychlost pro objizdeni cihly
10
#define RR_CIHLA     30       // Rozumna rychlost pro objizdeni cihly
11
#define RR_PRERUSENI 20       // Rozumna rychlost pro priblizeni se k preruseni
11
#define RR_PRERUSENI 20       // Rozumna rychlost pro priblizeni se k preruseni
12
#define BRZDNA_DRAHA 0x20        // Jak daleko pred problemem se zacne brzdit
12
#define BRZDNA_DRAHA 0x20        // Jak daleko pred problemem se zacne brzdit
13
#define ODODO1 0x37
13
#define ODODO1 0xFFF
14
#define ODODO2 0x5E
14
#define ODODO2 0xFFF
15
 
15
 
16
// Adresy IIC periferii
16
// Adresy IIC periferii
17
#define COMPAS_ADR   0xC0
17
#define COMPAS_ADR   0xC0
18
#define CAMERA_ADR   0xDC
18
#define CAMERA_ADR   0xDC
19
#define SONAR_ADR    0xE0
19
#define SONAR_ADR    0xE0
20
 
20
 
21
// A/D vstupy
21
// A/D vstupy
22
#define  RMAX     4  // AN4/RA5 - leve cidlo na vyjeti z cary
22
#define  RMAX     4  // AN4/RA5 - leve cidlo na vyjeti z cary
23
#define  LMAX     3  // AN3/RA3 - prave cidlo na vyjeti z cary
23
#define  LMAX     3  // AN3/RA3 - prave cidlo na vyjeti z cary
24
#define  CERVENA  2  // AN2/RA2 - cervene kroutitko
24
#define  CERVENA  2  // AN2/RA2 - cervene kroutitko
25
#define  ZELENA   1  // AN1/RA0 - zelene kroutitko
25
#define  ZELENA   1  // AN1/RA0 - zelene kroutitko
26
#define  MODRA    0  // AN0/RA1 - modre kroutitko
26
#define  MODRA    0  // AN0/RA1 - modre kroutitko
27
 
27
 
28
// I/O
28
// I/O
29
#define HREF      PIN_C5      // Signal HREF z kamery (v H po celou dobu radku)
29
#define HREF      PIN_C5      // Signal HREF z kamery (v H po celou dobu radku)
30
#define PIX       PIN_C6      // Vstup pro body z kamery (za trivstupim hradlem OR (dig. komparator))
30
#define PIX       PIN_C6      // Vstup pro body z kamery (za trivstupim hradlem OR (dig. komparator))
31
#define SERVO     PIN_B4      // Vystup na servo (1 az 2ms po cca 20ms (synchronizovano snimkovym kmitoctem))
31
#define SERVO     PIN_B4      // Vystup na servo (1 az 2ms po cca 20ms (synchronizovano snimkovym kmitoctem))
32
#define MOT_L     PIN_B5      // Smer otaceni leveho motoru; druhy pol je RC2
32
#define MOT_L     PIN_B5      // Smer otaceni leveho motoru; druhy pol je RC2
33
#define MOT_R     PIN_B6      // Smer otaceni praveho motoru; druhy pol je RC1
33
#define MOT_R     PIN_B6      // Smer otaceni praveho motoru; druhy pol je RC1
34
#define MOT_1     PIN_C1      // PWM vystpy motoru
34
#define MOT_1     PIN_C1      // PWM vystpy motoru
35
#define MOT_2     PIN_C2      //
35
#define MOT_2     PIN_C2      //
36
#define DATA      PIN_B2      // K modulu LEDbar data
36
#define DATA      PIN_B2      // K modulu LEDbar data
37
#define CP        PIN_B1      // K modulu LEDbar hodiny
37
#define CP        PIN_B1      // K modulu LEDbar hodiny
38
//#define ODO       PIN_C0      // Ze snimace z odometrie z praveho kola na TIMER1
38
//#define ODO       PIN_C0      // Ze snimace z odometrie z praveho kola na TIMER1
39
                                // Jeden impuls je 31,25mm
39
                                // Jeden impuls je 31,25mm
40
#define IRRX      !input(PIN_B0)   // Vstup INT, generuje preruseni pri prekazce
40
#define IRRX      !input(PIN_B0)   // Vstup INT, generuje preruseni pri prekazce
41
#define IRTX      PIN_B3      // Modulovani vysilaci IR LED na detekci prekazky
41
#define IRTX      PIN_B3      // Modulovani vysilaci IR LED na detekci prekazky
42
#define PROXIMITY PIN_C7      // Cidlo kratkeho dosahu na cihlu
42
#define PROXIMITY PIN_C7      // Cidlo kratkeho dosahu na cihlu
43
#define BUMPER    !input(PIN_A4)  // Naraznik
43
#define BUMPER    !input(PIN_A4)  // Naraznik
44
 
44
 
45
#define CASMIN 6           // Rozsah radku snimace
45
#define CASMIN 6           // Rozsah radku snimace
46
#define CASMAX 192
46
#define CASMAX 192
47
#define CASAVR ((CASMAX+CASMIN) / 2)
47
#define CASAVR ((CASMAX+CASMIN) / 2)
48
 
48
 
49
#define EEMAX  255         // Konec EEPROM
49
#define EEMAX  255         // Konec EEPROM
50
#define MAXLOG 0x10        // Maximalni pocet zaznamu v logu
50
#define MAXLOG 0x10        // Maximalni pocet zaznamu v logu
51
#if  MAXLOG>(EEMAX/3)
51
#if  MAXLOG>(EEMAX/3)
52
   #error  Prekrocena velikost EEPROM
52
   #error  Prekrocena velikost EEPROM
53
#endif
53
#endif
54
 
54
 
55
#define OFFSETO   0x9F //0x9F         // Vystredeni serva pro objeti prekazky
55
#define OFFSETO   0x9F //0x9F         // Vystredeni serva pro objeti prekazky
56
 
56
 
57
#define THR 90    // Threshold pro UV cidla na caru
57
#define THR 90    // Threshold pro UV cidla na caru
58
 
58
 
59
#byte INTCON      = 0x0B         // Interrupt configuration register
59
#byte INTCON      = 0x0B         // Interrupt configuration register
60
   #bit GIE       = INTCON.7
60
   #bit GIE       = INTCON.7
61
   #bit PEIE      = INTCON.6
61
   #bit PEIE      = INTCON.6
62
   #bit TMR0IE    = INTCON.5
62
   #bit TMR0IE    = INTCON.5
63
   #bit INT0IE    = INTCON.4
63
   #bit INT0IE    = INTCON.4
64
   #bit RBIE      = INTCON.3
64
   #bit RBIE      = INTCON.3
65
   #bit TMR0IF    = INTCON.2
65
   #bit TMR0IF    = INTCON.2
66
   #bit INT0IF    = INTCON.1
66
   #bit INT0IF    = INTCON.1
67
   #bit RBIF      = INTCON.0
67
   #bit RBIF      = INTCON.0
68
 
68
 
69
enum stavy {start,rozjezd,jizda,cihla,pocihle,cil};
69
enum stavy {start,rozjezd,jizda,cihla,pocihle,cil};
70
stavy stav;       // Kde jsme na trati
70
stavy stav;       // Kde jsme na trati
71
int8 cas;         // Cas hrany bila/cerna v radce
71
int8 cas;         // Cas hrany bila/cerna v radce
72
int8 stred;       // Vystredeni kolecka
72
int8 stred;       // Vystredeni kolecka
73
int16 odocounter; // Zaznamenani aktualniho stavu pocitadla odometrie
73
int16 odocounter; // Zaznamenani aktualniho stavu pocitadla odometrie
74
int16 last_log_odo; // Posledni stav odometrie poznamenany do logu
74
int16 last_log_odo; // Posledni stav odometrie poznamenany do logu
75
int16 last_log;   // Cislo posledniho zaznamu v logu v EEPROM
75
int16 last_log;   // Cislo posledniho zaznamu v logu v EEPROM
76
int8 bb_h[MAXLOG];  // Cerna skrinka MSB
76
int8 bb_h[MAXLOG];  // Cerna skrinka MSB
77
int8 bb_l[MAXLOG];  // Cerna skrinka LSB
77
int8 bb_l[MAXLOG];  // Cerna skrinka LSB
78
int8 bb_f[MAXLOG];  // Cerna skrinka priznak (typ zaznamu)
78
int8 bb_f[MAXLOG];  // Cerna skrinka priznak (typ zaznamu)
79
int8 log;         // Pocitadlo pro cernou skrinku
79
int8 log;         // Pocitadlo pro cernou skrinku
80
int16 bb;         // Posledni nactena udalost z Black Boxu
80
int16 bb;         // Posledni nactena udalost z Black Boxu
81
int16 timer_pom;  // Pomocna promenna pro atomicke nacteni hodnoty timeru1
81
int16 timer_pom;  // Pomocna promenna pro atomicke nacteni hodnoty timeru1
82
int8 rr;          // Promenna na ulozeni Rozumne rychlost
82
int8 rr;          // Promenna na ulozeni Rozumne rychlost
83
int8 rrold;
83
int8 rrold;
84
int16 odo1, odo2; // Problemy na trati
84
int16 odo1, odo2; // Problemy na trati
85
 
85
 
86
// Zobrazeni jednoho byte na modulu LEDbar
86
// Zobrazeni jednoho byte na modulu LEDbar
87
inline void disp(int8 x)
87
inline void disp(int8 x)
88
{
88
{
89
   int n;
89
   int n;
90
 
90
 
91
   for(n=0;n<=7;n++)
91
   for(n=0;n<=7;n++)
92
   {
92
   {
93
      if (bit_test(x,0)) output_low(DATA); else output_high(DATA);
93
      if (bit_test(x,0)) output_low(DATA); else output_high(DATA);
94
      output_high(CP);
94
      output_high(CP);
95
      x>>=1;
95
      x>>=1;
96
      output_low(CP);
96
      output_low(CP);
97
   }
97
   }
98
}
98
}
99
 
99
 
100
// Blikani LEDbarem ve stilu Night Rider
100
// Blikani LEDbarem ve stilu Night Rider
101
void NightRider(int8 x)
101
void NightRider(int8 x)
102
{
102
{
103
   int n,i,j;
103
   int n,i,j;
104
 
104
 
105
   for(j=0;j<x;j++)
105
   for(j=0;j<x;j++)
106
   {
106
   {
107
      i=0x01;
107
      i=0x01;
108
      for(n=0;n<7;n++)
108
      for(n=0;n<7;n++)
109
      {
109
      {
110
         disp(i);
110
         disp(i);
111
         rotate_left(&i, 1);
111
         rotate_left(&i, 1);
112
         delay_ms(40);
112
         delay_ms(40);
113
      }
113
      }
114
      for(n=0;n<7;n++)
114
      for(n=0;n<7;n++)
115
      {
115
      {
116
         disp(i);
116
         disp(i);
117
         rotate_right(&i, 1);
117
         rotate_right(&i, 1);
118
         delay_ms(40);
118
         delay_ms(40);
119
      }
119
      }
120
   }
120
   }
121
   disp(i);
121
   disp(i);
122
   delay_ms(40);
122
   delay_ms(40);
123
   i=0;
123
   i=0;
124
   disp(i);
124
   disp(i);
125
}
125
}
126
 
126
 
127
// Zaznam LOGu do EEPROM
127
// Zaznam LOGu do EEPROM
128
void SaveLog(int8 log)
128
void SaveLog(int8 log)
129
{
129
{
130
   int8 n,i;
130
   int8 n,i;
131
 
131
 
132
   i=0;
132
   i=0;
133
   for(n=0;n<=(log*3);n+=3)   // Ulozeni Black Boxu do EEPROM
133
   for(n=0;n<=(log*3);n+=3)   // Ulozeni Black Boxu do EEPROM
134
   {
134
   {
135
      write_eeprom(n,bb_f[i]);
135
      write_eeprom(n,bb_f[i]);
136
      write_eeprom(n+1,bb_h[i]);
136
      write_eeprom(n+1,bb_h[i]);
137
      write_eeprom(n+2,bb_l[i]);
137
      write_eeprom(n+2,bb_l[i]);
138
      i++;
138
      i++;
139
   };
139
   };
140
   write_eeprom(EEMAX,log);  // Zapis poctu zaznamu na konec EEPROM
140
   write_eeprom(EEMAX,log);  // Zapis poctu zaznamu na konec EEPROM
141
}
141
}
142
 
142
 
143
// Brzdeni motorama stridou 1:1
143
// Brzdeni motorama stridou 1:1
144
void brzda()
144
void brzda()
145
{
145
{
146
   int8 n,i;
146
   int8 n,i;
147
 
147
 
148
   set_pwm1_duty(0);    // vypni PWM
148
   set_pwm1_duty(0);    // vypni PWM
149
   set_pwm2_duty(0);
149
   set_pwm2_duty(0);
150
   setup_ccp1(CCP_OFF);
150
   setup_ccp1(CCP_OFF);
151
   setup_ccp2(CCP_OFF);
151
   setup_ccp2(CCP_OFF);
152
   for (n=0;n<200;n++)
152
   for (n=0;n<200;n++)
153
   {
153
   {
154
      output_low(MOT_L);
154
      output_low(MOT_L);
155
      output_low(MOT_R);
155
      output_low(MOT_R);
156
      output_high(MOT_1);
156
      output_high(MOT_1);
157
      output_high(MOT_2);
157
      output_high(MOT_2);
158
      delay_us(200);
158
      delay_us(200);
159
      output_high(MOT_L);
159
      output_high(MOT_L);
160
      output_high(MOT_R);
160
      output_high(MOT_R);
161
      output_low(MOT_1);
161
      output_low(MOT_1);
162
      output_low(MOT_2);
162
      output_low(MOT_2);
163
      delay_us(200);
163
      delay_us(200);
164
   }
164
   }
165
   output_low(MOT_L); // smer vpred
165
   output_low(MOT_L); // smer vpred
166
   output_low(MOT_R);
166
   output_low(MOT_R);
167
   setup_ccp1(CCP_PWM); // RC1               // Zapni PWM pro motory
167
   setup_ccp1(CCP_PWM); // RC1               // Zapni PWM pro motory
168
   setup_ccp2(CCP_PWM); // RC2
168
   setup_ccp2(CCP_PWM); // RC2
169
}
169
}
170
 
170
 
171
void SetServo(int8 angle)
171
void SetServo(int8 angle)
172
{
172
{
173
   int8 n;
173
   int8 n;
174
 
174
 
175
   for(n=0; n<10; n++)
175
   for(n=0; n<10; n++)
176
   {
176
   {
177
      output_high(SERVO);        // Odvysilani impuzu 1 az 2ms pro servo
177
      output_high(SERVO);        // Odvysilani impuzu 1 az 2ms pro servo
178
      delay_us(1000);
178
      delay_us(1000);
179
      delay_us(stred);
179
      delay_us(stred);
180
      delay_us(stred);
180
      delay_us(stred);
181
      delay_us(stred);
181
      delay_us(stred);
182
      delay_us(angle);
182
      delay_us(angle);
183
      delay_us(angle);
183
      delay_us(angle);
184
      output_low(SERVO);
184
      output_low(SERVO);
185
      delay_ms(18);
185
      delay_ms(18);
186
   }
186
   }
187
}
187
}
188
 
188
 
189
inline void SetServoQ(int8 angle)
189
inline void SetServoQ(int8 angle)
190
{
190
{
191
   output_high(SERVO);        // Odvysilani impuzu 1 az 2ms pro servo
191
   output_high(SERVO);        // Odvysilani impuzu 1 az 2ms pro servo
192
   delay_us(1000);
192
   delay_us(1000);
193
   delay_us(stred);
193
   delay_us(stred);
194
   delay_us(stred);
194
   delay_us(stred);
195
   delay_us(stred);
195
   delay_us(stred);
196
   delay_us(angle);
196
   delay_us(angle);
197
   delay_us(angle);
197
   delay_us(angle);
198
   output_low(SERVO);
198
   output_low(SERVO);
199
}
199
}
200
 
200
 
201
// Couvni po narazu na naraznik
201
// Couvni po narazu na naraznik
202
inline void bum()
202
inline void bum()
203
{
203
{
204
   set_pwm1_duty(0);    // couvni, rovne dozadu
204
   set_pwm1_duty(0);    // couvni, rovne dozadu
205
   set_pwm2_duty(0);
205
   set_pwm2_duty(0);
206
   output_high(MOT_L);
206
   output_high(MOT_L);
207
   output_high(MOT_R);
207
   output_high(MOT_R);
208
   disp(0xA5);
208
   disp(0xA5);
209
   SetServo(CASAVR-CASMIN);
209
   SetServo(CASAVR-CASMIN);
210
}
210
}
211
 
211
 
212
//---------------------------- INT --------------------------------
212
//---------------------------- INT --------------------------------
213
#int_EXT
213
#int_EXT
214
EXT_isr()   // Preruseni od prekazky
214
EXT_isr()   // Preruseni od prekazky
215
{
215
{
216
   int8 bearing, bearing_offset, delta_bearing;
216
   unsigned int8 bearing, bearing_offset, delta_bearing;
217
   
217
 
218
   set_pwm1_duty(0);    // zabrzdi levym kolem, prave vypni
218
   set_pwm1_duty(0);    // zabrzdi levym kolem, prave vypni
219
   set_pwm2_duty(0);
219
   set_pwm2_duty(0);
220
   output_high(MOT_L);
220
   output_high(MOT_L);
221
   output_low(MOT_R);
221
   output_low(MOT_R);
222
   // Ujistime se, ze prijaty signal je z naseho IR vysilace
222
   // Ujistime se, ze prijaty signal je z naseho IR vysilace
223
   output_high(IRTX);   // Vypni LED na detekci prekazky
223
   output_high(IRTX);   // Vypni LED na detekci prekazky
224
   delay_ms(2);
224
   delay_ms(2);
225
   if (IRRX)    // stale nas signal?
225
   if (IRRX)    // stale nas signal?
226
   {
226
   {
227
      output_low(MOT_L); // je odraz -> vpred
227
      output_low(MOT_L); // je odraz -> vpred
228
      output_low(MOT_R);
228
      output_low(MOT_R);
229
      return;
229
      return;
230
   };
230
   };
231
   output_low(IRTX);    // Zapni LED na detekci prekazky
231
   output_low(IRTX);    // Zapni LED na detekci prekazky
232
 
232
 
233
   i2c_start();     // Cteni kompasu
233
   i2c_start();     // Cteni kompasu
234
   i2c_write(COMPAS_ADR);
234
   i2c_write(COMPAS_ADR);
235
   i2c_write(0x1);
235
   i2c_write(0x1);
236
   i2c_stop();
236
   i2c_stop();
237
   i2c_start();
237
   i2c_start();
238
   i2c_write(COMPAS_ADR+1);
238
   i2c_write(COMPAS_ADR+1);
239
   bearing_offset=i2c_read(0);
239
   bearing_offset=i2c_read(0);
240
   i2c_stop();
240
   i2c_stop();
241
 
241
 
242
   delay_ms(9);
242
   delay_ms(9);
243
   if (!IRRX)     // stale nas signal?
243
   if (!IRRX)     // stale nas signal?
244
   {
244
   {
245
      output_low(MOT_L); // neni odraz -> vpred
245
      output_low(MOT_L); // neni odraz -> vpred
246
      output_low(MOT_R);
246
      output_low(MOT_R);
247
      return;
247
      return;
248
   };
248
   };
249
 
249
 
250
   rr=rrold;      // Po cihle se pojede opet Rozumnou Rychlosti
250
   rr=rrold;      // Po cihle se pojede opet Rozumnou Rychlosti
251
   if(stav!=cihla)
251
   if(stav!=cihla)
252
   {
252
   {
253
      timer_pom=get_timer1();       // Obsah Timeru1 se musi nacist atomicky
253
      timer_pom=get_timer1();       // Obsah Timeru1 se musi nacist atomicky
254
      bb_l[log]=make8(timer_pom,0); // Zaznam do logu
254
      bb_l[log]=make8(timer_pom,0); // Zaznam do logu
255
      bb_h[log]=make8(timer_pom,1);
255
      bb_h[log]=make8(timer_pom,1);
256
      bb_f[log]=0xFF;   // Cihla
256
      bb_f[log]=0xFF;   // Cihla
257
      if(log<MAXLOG) log++;        // Ukazatel na dalsi zaznam
257
      if(log<MAXLOG) log++;        // Ukazatel na dalsi zaznam
258
   };
258
   };
259
 
259
 
260
//!!!   if(stav==cihla) while(true); // Zastav na furt, konec drahy
260
//!!!   if(stav==cihla) while(true); // Zastav na furt, konec drahy
261
//   if(stav==cihla) return; // Po druhe nic neobjizdej
261
//   if(stav==cihla) return; // Po druhe nic neobjizdej
262
// Pozor na rozjezd
262
// Pozor na rozjezd
263
 
263
 
264
   if((stav==jizda)||(stav==cihla))   // Objed cihlu
264
   if((stav==jizda)||(stav==cihla))   // Objed cihlu
265
   {
265
   {
266
      #include ".\objizdka_L.c"
266
      #include ".\objizdka_L.c"
267
   };
267
   };
268
   last_log_odo=get_timer1()+16;  // Pul metru po cihle nezaznamenavej do LOGu
268
   last_log_odo=get_timer1()+16;  // Pul metru po cihle nezaznamenavej do LOGu
269
}
269
}
270
 
270
 
271
 
271
 
272
//---------------------------------- MAIN --------------------------------------
272
//---------------------------------- MAIN --------------------------------------
273
void main()
273
void main()
274
{
274
{
275
   int8 offset;   // Promena pro ulozeni offsetu
275
   int8 offset;   // Promena pro ulozeni offsetu
276
   int8 r1;       // Rychlost motoru 1
276
   int8 r1;       // Rychlost motoru 1
277
   int8 r2;       // Rychlost motoru 2
277
   int8 r2;       // Rychlost motoru 2
278
 
278
 
279
   setup_adc_ports(ALL_ANALOG);              // Zapnuti A/D prevodniku pro cteni kroutitek
279
   setup_adc_ports(ALL_ANALOG);              // Zapnuti A/D prevodniku pro cteni kroutitek
280
   setup_adc(ADC_CLOCK_INTERNAL);
280
   setup_adc(ADC_CLOCK_INTERNAL);
281
   setup_timer_0(RTCC_INTERNAL|RTCC_DIV_1);  // Casovac pro mereni casu hrany W/B v radce
281
   setup_timer_0(RTCC_INTERNAL|RTCC_DIV_1);  // Casovac pro mereni casu hrany W/B v radce
282
   setup_timer_1(T1_EXTERNAL);               // Cita pulzy z odometrie z praveho kola
282
   setup_timer_1(T1_EXTERNAL);               // Cita pulzy z odometrie z praveho kola
283
   setup_timer_2(T2_DIV_BY_16,255,1);        // Casovac PWM motoru
283
   setup_timer_2(T2_DIV_BY_16,255,1);        // Casovac PWM motoru
284
   setup_ccp1(CCP_PWM); // RC1               // PWM pro motory
284
   setup_ccp1(CCP_PWM); // RC1               // PWM pro motory
285
   setup_ccp2(CCP_PWM); // RC2
285
   setup_ccp2(CCP_PWM); // RC2
286
   setup_comparator(NC_NC_NC_NC);
286
   setup_comparator(NC_NC_NC_NC);
287
   setup_vref(FALSE);
287
   setup_vref(FALSE);
288
 
288
 
289
   set_tris_c(0b11111001);     // Nastaveni vstup/vystup pro branu C, protoze se to nedela automaticky
289
   set_tris_c(0b11111001);     // Nastaveni vstup/vystup pro branu C, protoze se to nedela automaticky
290
 
290
 
291
   set_pwm1_duty(0);    // Zastav motory
291
   set_pwm1_duty(0);    // Zastav motory
292
   set_pwm2_duty(0);
292
   set_pwm2_duty(0);
293
   output_low(MOT_L);   // Nastav smer vpred
293
   output_low(MOT_L);   // Nastav smer vpred
294
   output_low(MOT_R);
294
   output_low(MOT_R);
295
 
295
 
296
   disp(0);    // Zhasni LEDbar
296
   disp(0);    // Zhasni LEDbar
297
   
-
 
298
/*!!!!
-
 
299
while(true)
-
 
300
{
-
 
301
   int8 ble;
-
 
302
 
-
 
303
   i2c_start();     // Cteni kompasu
-
 
304
   i2c_write(COMPAS_ADR);
-
 
305
   i2c_write(0x1);
-
 
306
   i2c_stop();
-
 
307
   i2c_start();
-
 
308
   i2c_write(COMPAS_ADR+1);
-
 
309
   ble=i2c_read(0);
-
 
310
   i2c_stop();
-
 
311
   disp(ble);
-
 
312
   delay_ms(200);
-
 
313
}
-
 
314
//*/           
-
 
315
 
297
 
316
   if(BUMPER)  // Kdyz nekdo na zacatku drzi naraznik, vymaz log
298
   if(BUMPER)  // Kdyz nekdo na zacatku drzi naraznik, vymaz log
317
   {
299
   {
318
      int8 n;
300
      int8 n;
319
 
301
 
320
      for(n=0;n<255;n++) write_eeprom(n,0);
302
      for(n=0;n<255;n++) write_eeprom(n,0);
321
      bb_l[0]=0;        // Zapis na pozici 0 vzdalenost 0
303
      bb_l[0]=0;        // Zapis na pozici 0 vzdalenost 0
322
      bb_h[0]=0;
304
      bb_h[0]=0;
323
      SaveLog(0);       // Zapis do EEPROM pocet zaznamu 0, tedy jeden zaznam
305
      SaveLog(0);       // Zapis do EEPROM pocet zaznamu 0, tedy jeden zaznam
-
 
306
      for(n=0;n<=4;n++)
-
 
307
      {
-
 
308
         disp(0x55);       // Blikni pro potvrzeni
-
 
309
         delay_ms(200);
-
 
310
         disp(0xAA);
-
 
311
         delay_ms(200);
-
 
312
      };
324
      while(true)
313
      while(true)
325
      {
314
      {
326
         if(!IRRX)
315
         if(!IRRX)
327
         {
316
         {
-
 
317
            int8 ble;
-
 
318
         
328
            disp(0x55);       // Blikni pro potvrzeni
319
            i2c_start();     // Cteni kompasu
-
 
320
            i2c_write(COMPAS_ADR);
-
 
321
            i2c_write(0x1);
-
 
322
            i2c_stop();
-
 
323
            i2c_start();
-
 
324
            i2c_write(COMPAS_ADR+1);
-
 
325
            ble=i2c_read(0);
329
            delay_ms(200);
326
            i2c_stop();
330
            disp(0xAA);
327
            disp(ble);
331
            delay_ms(200);
328
            delay_ms(200);
332
         }
329
         }
333
         else
330
         else
334
         {
331
         {
335
            disp(0x81);       // Diagnostika celniho IR senzoru na prekazku
332
            disp(0x81);       // Diagnostika celniho IR senzoru na prekazku
336
            delay_ms(200);
333
            delay_ms(200);
337
         }
334
         }
338
      }
335
      }
339
   }
336
   }
340
 
337
 
341
   output_low(IRTX);   // Zapni LED na detekci prekazky
338
   output_low(IRTX);   // Zapni LED na detekci prekazky
342
 
339
 
343
   NightRider(1);    // Aby se poznalo, ze byl RESET
340
   NightRider(1);    // Aby se poznalo, ze byl RESET
344
                     // taky se musi pockat, nez se rozjede kamera, nez se do ni zacnou posilat prikazy
341
                     // taky se musi pockat, nez se rozjede kamera, nez se do ni zacnou posilat prikazy
345
 
342
 
346
   //... Nastaveni sonaru ...
343
   //... Nastaveni sonaru ...
347
   i2c_start();
344
   i2c_start();
348
   i2c_write(SONAR_ADR);
345
   i2c_write(SONAR_ADR);
349
   i2c_write(0x02);  // dosah
346
   i2c_write(0x02);  // dosah
350
   i2c_write(0x03);  // n*43mm
347
   i2c_write(0x03);  // n*43mm
351
   i2c_stop();
348
   i2c_stop();
352
   i2c_start();
349
   i2c_start();
353
   i2c_write(SONAR_ADR);
350
   i2c_write(SONAR_ADR);
354
   i2c_write(0x01);  // zesileni
351
   i2c_write(0x01);  // zesileni
355
   i2c_write(0x01);  // male, pro eliminaci echa z minuleho mereni
352
   i2c_write(0x01);  // male, pro eliminaci echa z minuleho mereni
356
   i2c_stop();
353
   i2c_stop();
357
 
354
 
358
// pro ladeni sonaru
355
// pro ladeni sonaru
359
/*
356
/*
360
   while(true)
357
   while(true)
361
   {
358
   {
362
         i2c_start();     // Sonar Ping
359
         i2c_start();     // Sonar Ping
363
      i2c_write(0xE0);
360
      i2c_write(0xE0);
364
      i2c_write(0x0);
361
      i2c_write(0x0);
365
      i2c_write(0x51);  // 50 mereni v palcich, 51 mereni v cm, 52 v us
362
      i2c_write(0x51);  // 50 mereni v palcich, 51 mereni v cm, 52 v us
366
      i2c_stop();
363
      i2c_stop();
367
      delay_ms(100);
364
      delay_ms(100);
368
      i2c_start();     // Odraz ze sonaru
365
      i2c_start();     // Odraz ze sonaru
369
      i2c_write(0xE0);
366
      i2c_write(0xE0);
370
      i2c_write(0x3);
367
      i2c_write(0x3);
371
      i2c_stop();
368
      i2c_stop();
372
      i2c_start();
369
      i2c_start();
373
      i2c_write(0xE1);
370
      i2c_write(0xE1);
374
      cas=i2c_read(0);
371
      cas=i2c_read(0);
375
      i2c_stop();
372
      i2c_stop();
376
      disp(cas);
373
      disp(cas);
377
   }
374
   }
378
*/
375
*/
379
 
376
 
380
   //... Nastaveni kamery ...
377
   //... Nastaveni kamery ...
381
   i2c_start();      // Soft RESET kamery
378
   i2c_start();      // Soft RESET kamery
382
   i2c_write(CAMERA_ADR);        // Adresa kamery
379
   i2c_write(CAMERA_ADR);        // Adresa kamery
383
   i2c_write(0x12);        // Adresa registru COMH
380
   i2c_write(0x12);        // Adresa registru COMH
384
   i2c_write(0x80 | 0x24); // Zapis ridiciho slova
381
   i2c_write(0x80 | 0x24); // Zapis ridiciho slova
385
   i2c_stop();
382
   i2c_stop();
386
 
383
 
387
   i2c_start();      // BW
384
   i2c_start();      // BW
388
   i2c_write(CAMERA_ADR);
385
   i2c_write(CAMERA_ADR);
389
   i2c_write(0x28);
386
   i2c_write(0x28);
390
   i2c_write(0b01000001);
387
   i2c_write(0b01000001);
391
   i2c_stop();
388
   i2c_stop();
392
 
389
 
393
/*
390
/*
394
   i2c_start();      // Contrast (nema podstatny vliv na obraz)
391
   i2c_start();      // Contrast (nema podstatny vliv na obraz)
395
   i2c_write(CAMERA_ADR);
392
   i2c_write(CAMERA_ADR);
396
   i2c_write(0x05);
393
   i2c_write(0x05);
397
   i2c_write(0xA0);  // 48h
394
   i2c_write(0xA0);  // 48h
398
   i2c_stop();
395
   i2c_stop();
399
 
396
 
400
   i2c_start();      // Band Filter (pokud by byl problem se zarivkama 50Hz)
397
   i2c_start();      // Band Filter (pokud by byl problem se zarivkama 50Hz)
401
   i2c_write(CAMERA_ADR);
398
   i2c_write(CAMERA_ADR);
402
   i2c_write(0x2D);
399
   i2c_write(0x2D);
403
   i2c_write(0x04 | 0x03);
400
   i2c_write(0x04 | 0x03);
404
   i2c_stop();
401
   i2c_stop();
405
*/
402
*/
406
 
403
 
407
   i2c_start();      // Fame Rate
404
   i2c_start();      // Fame Rate
408
   i2c_write(CAMERA_ADR);
405
   i2c_write(CAMERA_ADR);
409
   i2c_write(0x2B);
406
   i2c_write(0x2B);
410
   i2c_write(0x00);  // cca 17ms (puvodni hodnota 5Eh = 20ms)
407
   i2c_write(0x00);  // cca 17ms (puvodni hodnota 5Eh = 20ms)
411
   i2c_stop();
408
   i2c_stop();
412
 
409
 
413
   i2c_start();      // VSTRT
410
   i2c_start();      // VSTRT
414
   i2c_write(CAMERA_ADR);
411
   i2c_write(CAMERA_ADR);
415
   i2c_write(0x19);
412
   i2c_write(0x19);
416
   i2c_write(118);   // prostredni radka
413
   i2c_write(118);   // prostredni radka
417
   i2c_stop();
414
   i2c_stop();
418
 
415
 
419
   i2c_start();      // VEND
416
   i2c_start();      // VEND
420
   i2c_write(CAMERA_ADR);
417
   i2c_write(CAMERA_ADR);
421
   i2c_write(0x1A);
418
   i2c_write(0x1A);
422
   i2c_write(118);
419
   i2c_write(118);
423
   i2c_stop();
420
   i2c_stop();
424
 
421
 
425
   NightRider(1);    // Musi se dat cas kamere na AGC a AEC
422
   NightRider(1);    // Musi se dat cas kamere na AGC a AEC
426
 
423
 
427
   { // Mereni expozice
424
   { // Mereni expozice
428
      int8 t1,t2;
425
      int8 t1,t2;
429
 
426
 
430
      i2c_start();      // Brightness, zacni od uplne tmy
427
      i2c_start();      // Brightness, zacni od uplne tmy
431
      i2c_write(CAMERA_ADR);
428
      i2c_write(CAMERA_ADR);
432
      i2c_write(0x06);
429
      i2c_write(0x06);
433
      i2c_write(0);  // 80h default
430
      i2c_write(0);  // 80h default
434
      i2c_stop();
431
      i2c_stop();
435
      delay_ms(50);
432
      delay_ms(50);
436
 
433
 
437
      for(offset=0x04;offset<(255-0x04);offset+=0x04)   // Zacni od jasu 10h
434
      for(offset=0x04;offset<(255-0x04);offset+=0x04)   // Zacni od jasu 10h
438
      {
435
      {
439
         i2c_start();      // Brightness
436
         i2c_start();      // Brightness
440
         i2c_write(CAMERA_ADR);
437
         i2c_write(CAMERA_ADR);
441
         i2c_write(0x06);
438
         i2c_write(0x06);
442
         i2c_write(offset);  // 80h default
439
         i2c_write(offset);  // 80h default
443
         i2c_stop();
440
         i2c_stop();
444
         disp(offset);
441
         disp(offset);
445
         delay_ms(50);
442
         delay_ms(50);
446
 
443
 
447
         t1=0;
444
         t1=0;
448
         t2=0;
445
         t2=0;
449
         while(!input(HREF));    // Cekej nez se zacnou posilat pixely z radky
446
         while(!input(HREF));    // Cekej nez se zacnou posilat pixely z radky
450
         delay_ms(5);
447
         delay_ms(5);
451
         while(!input(HREF));    // Cekej nez se zacnou posilat pixely z radky
448
         while(!input(HREF));    // Cekej nez se zacnou posilat pixely z radky
452
         set_timer0(0);          // Vynuluj pocitadlo casu
449
         set_timer0(0);          // Vynuluj pocitadlo casu
453
         if(!input(PIX)) continue;
450
         if(!input(PIX)) continue;
454
         while(input(PIX));
451
         while(input(PIX));
455
         t1=get_timer0();    // Precti cas z citace casu hrany
452
         t1=get_timer0();    // Precti cas z citace casu hrany
456
         set_timer0(0);          // Vynuluj pocitadlo casu
453
         set_timer0(0);          // Vynuluj pocitadlo casu
457
         while(!input(PIX));
454
         while(!input(PIX));
458
         t2=get_timer0();
455
         t2=get_timer0();
459
 
456
 
460
         if((t1>60) && (t1<140) && (t2>5) && (t2<=10)) break; // Vidis, co mas?
457
         if((t1>60) && (t1<140) && (t2>5) && (t2<=10)) break; // Vidis, co mas?
461
 
458
 
462
         delay_ms(2);   // Preskoc druhou radku z kamery
459
         delay_ms(2);   // Preskoc druhou radku z kamery
463
      };
460
      };
464
      delay_ms(1000);   // Nech chvili na displayi zmerenou hodnotu
461
      delay_ms(1000);   // Nech chvili na displayi zmerenou hodnotu
465
   }
462
   }
466
 
463
 
467
   set_adc_channel(CERVENA);   // --- Kroutitko pro jas ---
464
   set_adc_channel(CERVENA);   // --- Kroutitko pro jas ---
468
   delay_ms(1);
465
   delay_ms(1);
469
   offset=read_adc();
466
   offset=read_adc();
470
   offset &= 0b11111100;   // Dva nejnizsi bity ignoruj
467
   offset &= 0b11111100;   // Dva nejnizsi bity ignoruj
471
//   offset += 0x70;         // Jas nebude nikdy nizsi
468
//   offset += 0x70;         // Jas nebude nikdy nizsi
472
   disp(offset);
469
   disp(offset);
473
   i2c_start();            // Brightness
470
   i2c_start();            // Brightness
474
   i2c_write(CAMERA_adr);
471
   i2c_write(CAMERA_adr);
475
   i2c_write(0x06);
472
   i2c_write(0x06);
476
   i2c_write(offset);  // 80h default
473
   i2c_write(offset);  // 80h default
477
   i2c_stop();
474
   i2c_stop();
478
   delay_ms(1000);   // Nech hodnotu chvili na displayi
475
   delay_ms(1000);   // Nech hodnotu chvili na displayi
479
 
476
 
480
   set_adc_channel(ZELENA);   // --- Kroutitko pro vykon motoru ---
477
   set_adc_channel(ZELENA);   // --- Kroutitko pro vykon motoru ---
481
   delay_ms(1);
478
   delay_ms(1);
482
   rr=read_adc()>>2; // 0-63  // Pokud by se zvetsil rozsah, tak zkontrolovat jakonasobeni!
479
   rr=read_adc()>>2; // 0-63  // Pokud by se zvetsil rozsah, tak zkontrolovat jakonasobeni!
483
   rrold=rr;
480
   rrold=rr;
484
 
481
 
485
   cas=CASAVR-CASMIN;   // Inicializace promenych, aby neslo servo za roh
482
   cas=CASAVR-CASMIN;   // Inicializace promenych, aby neslo servo za roh
486
                        // a aby se to rozjelo jeste dneska
483
                        // a aby se to rozjelo jeste dneska
487
   stav=start;          // Jsme na startu
484
   stav=start;          // Jsme na startu
488
   set_timer1(0);       // Vynuluj citac odometrie
485
   set_timer1(0);       // Vynuluj citac odometrie
489
   log=0;               // Zacatek logu v cerne skrince
486
   log=0;               // Zacatek logu v cerne skrince
490
   last_log_odo=0;      // Posledni zaznam odometrie do logu
487
   last_log_odo=0;      // Posledni zaznam odometrie do logu
491
 
488
 
492
   last_log=read_eeprom(EEMAX); // Kolik zaznamu mame od minule poznamenano?
489
   last_log=read_eeprom(EEMAX); // Kolik zaznamu mame od minule poznamenano?
493
   bb=MAKE16(read_eeprom(1) & 0x7F,read_eeprom(0)); // Precti prvni zaznam
490
   bb=MAKE16(read_eeprom(1) & 0x7F,read_eeprom(0)); // Precti prvni zaznam
494
 
491
 
495
   odo1=ODODO1-BRZDNA_DRAHA;
492
   odo1=ODODO1-BRZDNA_DRAHA;
496
   odo2=ODODO2-BRZDNA_DRAHA;
493
   odo2=ODODO2-BRZDNA_DRAHA;
497
 
494
 
498
   // ........................... Hlavni smycka ................................
495
   // ........................... Hlavni smycka ................................
499
   while(true)
496
   while(true)
500
   {
497
   {
501
      int8 pom;
498
      int8 pom;
502
      int8 n;
499
      int8 n;
503
      int8 gap;
500
      int8 gap;
504
      int16 ododo;
501
      int16 ododo;
505
 
502
 
506
      gap=0;      // Vynuluj pocitadlo preruseni
503
      gap=0;      // Vynuluj pocitadlo preruseni
507
 
504
 
508
next_snap:
505
next_snap:
509
 
506
 
510
      pom=0;
507
      pom=0;
511
      disable_interrupts(GLOBAL);  //----------------------- Critical Section
508
      disable_interrupts(GLOBAL);  //----------------------- Critical Section
512
      while(input(HREF));     // Preskoc 1. radku
509
      while(input(HREF));     // Preskoc 1. radku
513
      while(!input(HREF));    // Cekej nez se zacnou posilat pixely z 2. radky
510
      while(!input(HREF));    // Cekej nez se zacnou posilat pixely z 2. radky
514
      set_timer0(0);          // Vynuluj pocitadlo casu
511
      set_timer0(0);          // Vynuluj pocitadlo casu
515
      while(input(HREF))      // Po dobu vysilani radky cekej na hranu W/B
512
      while(input(HREF))      // Po dobu vysilani radky cekej na hranu W/B
516
      {
513
      {
517
// !!!!Dodelat rozpoznani cerne cary napric pro zastaveni ?
514
// !!!!Dodelat rozpoznani cerne cary napric pro zastaveni ?
518
         if(!input(PIX))   // Pokud se X-krat za sebou precetla CERNA
515
         if(!input(PIX))   // Pokud se X-krat za sebou precetla CERNA
519
         if(!input(PIX))
516
         if(!input(PIX))
520
//         if(!input(PIX))
517
//         if(!input(PIX))
521
         {
518
         {
522
            pom=get_timer0();    // Precti cas z citace casu hrany
519
            pom=get_timer0();    // Precti cas z citace casu hrany
523
            break;
520
            break;
524
         };
521
         };
525
      };
522
      };
526
      while(input(HREF));      // Pockej na shozeni signalu HREF
523
      while(input(HREF));      // Pockej na shozeni signalu HREF
527
 
524
 
528
      if((pom<CASMAX) && (pom>CASMIN)) cas=pom;  // Orizni konce radku
525
      if((pom<CASMAX) && (pom>CASMIN)) cas=pom;  // Orizni konce radku
529
      // Na konci obrazovaho radku to blbne. Jednak chyba od apertury
526
      // Na konci obrazovaho radku to blbne. Jednak chyba od apertury
530
      // a vubec to nejak na kraji nefunguje.
527
      // a vubec to nejak na kraji nefunguje.
531
 
528
 
532
      output_high(SERVO);        // Odvysilani impuzu 1 az 2ms pro servo
529
      output_high(SERVO);        // Odvysilani impuzu 1 az 2ms pro servo
533
      delay_us(1000);
530
      delay_us(1000);
534
      delay_us(stred);
531
      delay_us(stred);
535
      delay_us(stred);
532
      delay_us(stred);
536
      delay_us(stred);
533
      delay_us(stred);
537
      delay_us(cas);
534
      delay_us(cas);
538
      delay_us(cas);
535
      delay_us(cas);
539
      output_low(SERVO);
536
      output_low(SERVO);
540
 
537
 
541
      // Elektronicky diferencial 1. cast
538
      // Elektronicky diferencial 1. cast
542
      if(cas<CASAVR) {r1=cas-CASMIN; r2=CASAVR-CASMIN;}; // Normovani vystupni hodnoty radkoveho snimace
539
      if(cas<CASAVR) {r1=cas-CASMIN; r2=CASAVR-CASMIN;}; // Normovani vystupni hodnoty radkoveho snimace
543
      if(cas==CASAVR) {r1=cas-CASMIN; r2=cas-CASMIN;};   // pro rizeni rychlosti motoru
540
      if(cas==CASAVR) {r1=cas-CASMIN; r2=cas-CASMIN;};   // pro rizeni rychlosti motoru
544
      if(cas>CASAVR) {r1=CASAVR-CASMIN; r2=CASMAX-cas;}; // Rozsah 1 az 92
541
      if(cas>CASAVR) {r1=CASAVR-CASMIN; r2=CASMAX-cas;}; // Rozsah 1 az 92
545
 
542
 
546
      enable_interrupts(GLOBAL);    //----------------------- End Critical Section
543
      enable_interrupts(GLOBAL);    //----------------------- End Critical Section
547
 
544
 
548
      if(pom==0) // Kamera nevidi caru, poznamenej to do logu
545
      if(pom==0) // Kamera nevidi caru, poznamenej to do logu
549
      {
546
      {
550
         if((cas>(CASMIN+30))&&(cas<(CASMAX-30))) // Nebyla minule cara moc u kraje?
547
         if((cas>(CASMIN+30))&&(cas<(CASMAX-30))) // Nebyla minule cara moc u kraje?
551
         if(last_log_odo<get_timer1()) // Aby nebyly zaznamy v logu prilis huste, musi se napred neco ujet od minuleho zaznamu
548
         if(last_log_odo<get_timer1()) // Aby nebyly zaznamy v logu prilis huste, musi se napred neco ujet od minuleho zaznamu
552
         {
549
         {
553
            gap++;
550
            gap++;
554
         }
551
         }
555
      }
552
      }
556
      else
553
      else
557
      {
554
      {
558
         if(gap>=2) // Trva preruseni cary alespon 2 snimky?
555
         if(gap>=2) // Trva preruseni cary alespon 2 snimky?
559
         {
556
         {
560
            timer_pom=get_timer1();          // Timer se musi vycist atomicky
557
            timer_pom=get_timer1();          // Timer se musi vycist atomicky
561
            bb_l[log]=make8(timer_pom,0); // Zaznam
558
            bb_l[log]=make8(timer_pom,0); // Zaznam
562
            bb_h[log]=make8(timer_pom,1);
559
            bb_h[log]=make8(timer_pom,1);
563
            bb_f[log]=gap;
560
            bb_f[log]=gap;
564
            last_log_odo=timer_pom+8;     // Dalsi mereni nejdrive po ujeti 24 cm
561
            last_log_odo=timer_pom+8;     // Dalsi mereni nejdrive po ujeti 24 cm
565
            if(log<MAXLOG) log++;         // Ukazatel na dalsi zaznam
562
            if(log<MAXLOG) log++;         // Ukazatel na dalsi zaznam
566
            rr=rrold;      // Preruseni cary skoncilo, znovu jed Rozumnou Rychlosti
563
            rr=rrold;      // Preruseni cary skoncilo, znovu jed Rozumnou Rychlosti
567
         }
564
         }
568
         gap=0;
565
         gap=0;
569
      }
566
      }
570
 
567
 
571
//ODODO
568
//ODODO
572
      ododo=get_timer1();
569
      ododo=get_timer1();
573
      if((ododo>odo1)&&(ododo<(odo1+8))) rr=RR_PRERUSENI;
570
      if((ododo>odo1)&&(ododo<(odo1+8))) rr=RR_PRERUSENI;
574
      if((ododo>odo2)&&(ododo<(odo2+8))) rr=RR_PRERUSENI;
571
      if((ododo>odo2)&&(ododo<(odo2+8))) rr=RR_PRERUSENI;
575
 
572
 
576
      // Elektronicky diferencial 2. cast
573
      // Elektronicky diferencial 2. cast
577
      if (r1>(CASAVR-CASMIN-rr)) r1=(r1<<1)+rr-(CASAVR-CASMIN);     // Neco jako nasobeni
574
      if (r1>(CASAVR-CASMIN-rr)) r1=(r1<<1)+rr-(CASAVR-CASMIN);     // Neco jako nasobeni
578
      if (r2>(CASAVR-CASMIN-rr)) r2=(r2<<1)+rr-(CASAVR-CASMIN);     // rozsah 1 az 92 pro rr=0
575
      if (r2>(CASAVR-CASMIN-rr)) r2=(r2<<1)+rr-(CASAVR-CASMIN);     // rozsah 1 az 92 pro rr=0
579
                                                                    // rozsah 1 az 154 pro rr=63
576
                                                                    // rozsah 1 az 154 pro rr=63
580
 
577
 
581
//      r1<<=1;     // Rychlost je dvojnasobna
578
//      r1<<=1;     // Rychlost je dvojnasobna
582
//      r2<<=1;     // Rozsah 2 az 184
579
//      r2<<=1;     // Rozsah 2 az 184
583
 
580
 
584
      if ((stav==jizda)||(stav==cihla)||(stav==rozjezd)) //||(stav==pocihle))      // Jizda
581
      if ((stav==jizda)||(stav==cihla)||(stav==rozjezd)) //||(stav==pocihle))      // Jizda
585
      {
582
      {
586
         set_pwm1_duty(r1);
583
         set_pwm1_duty(r1);
587
         set_pwm2_duty(r2);
584
         set_pwm2_duty(r2);
588
      }
585
      }
589
      else
586
      else
590
      {
587
      {
591
         set_pwm1_duty(0);       // Zastaveni
588
         set_pwm1_duty(0);       // Zastaveni
592
         set_pwm2_duty(0);
589
         set_pwm2_duty(0);
593
      };
590
      };
594
 
591
 
595
      if((stav==rozjezd)&&(get_timer1()>10)) // musi ujet alespon 31cm
592
      if((stav==rozjezd)&&(get_timer1()>10)) // musi ujet alespon 31cm
596
      {
593
      {
597
         ext_int_edge(H_TO_L);         // Nastav podminky preruseni od cihly
594
         ext_int_edge(H_TO_L);         // Nastav podminky preruseni od cihly
598
         INT0IF=0;                     // Zruseni predesle udalosti od startera
595
         INT0IF=0;                     // Zruseni predesle udalosti od startera
599
         enable_interrupts(INT_EXT);
596
         enable_interrupts(INT_EXT);
600
         enable_interrupts(GLOBAL);
597
         enable_interrupts(GLOBAL);
601
         stav=jizda;
598
         stav=jizda;
602
      };
599
      };
603
 
600
 
604
      if(stav==start)         // Snimkuje, toci servem a ceka na start
601
      if(stav==start)         // Snimkuje, toci servem a ceka na start
605
      {
602
      {
606
         set_adc_channel(MODRA);    // Kroutitko na vystredeni predniho kolecka
603
         set_adc_channel(MODRA);    // Kroutitko na vystredeni predniho kolecka
607
         Delay_ms(1);
604
         Delay_ms(1);
608
         stred=read_adc();
605
         stred=read_adc();
609
         if(!input(PROXIMITY))
606
         if(!input(PROXIMITY))
610
         {
607
         {
611
            disp(0x80);
608
            disp(0x80);
612
            while(input(PROXIMITY)); // Cekej, dokud starter neda ruku pryc
609
            while(input(PROXIMITY)); // Cekej, dokud starter neda ruku pryc
613
            set_timer1(0);         // Vynuluj citac odometrie
610
            set_timer1(0);         // Vynuluj citac odometrie
614
            set_pwm1_duty(255);    // Rychly rozjezd  !!! Zkontrolovat na oscyloskopu
611
            set_pwm1_duty(255);    // Rychly rozjezd  !!! Zkontrolovat na oscyloskopu
615
            set_pwm2_duty(255);
612
            set_pwm2_duty(255);
616
            disp(0x01);
613
            disp(0x01);
617
            while(get_timer1()<=4) // Ujed alespon 12cm
614
            while(get_timer1()<=4) // Ujed alespon 12cm
618
            {
615
            {
619
               set_adc_channel(LMAX);    // Levy UV sensor
616
               set_adc_channel(LMAX);    // Levy UV sensor
620
               delay_us(40);
617
               delay_us(40);
621
               if(read_adc()<THR) {cas=CASMIN; break;};  // Prejeli jsme caru vlevo
618
               if(read_adc()<THR) {cas=CASMIN; break;};  // Prejeli jsme caru vlevo
622
               set_adc_channel(RMAX);    // Pravy UV sensor
619
               set_adc_channel(RMAX);    // Pravy UV sensor
623
               delay_us(40);
620
               delay_us(40);
624
               if(read_adc()<THR) {cas=CASMAX; break;};  // Prejeli jsme caru vpravo
621
               if(read_adc()<THR) {cas=CASMAX; break;};  // Prejeli jsme caru vpravo
625
               cas=CASAVR-CASMIN;    // Cara je rovne
622
               cas=CASAVR-CASMIN;    // Cara je rovne
626
            };
623
            };
627
            stav=rozjezd;
624
            stav=rozjezd;
628
         };
625
         };
629
      }
626
      }
630
 
627
 
631
      pom=0x80;    // Zobrazeni pozice cary na displayi
628
      pom=0x80;    // Zobrazeni pozice cary na displayi
632
      for(n=CASMAX/8; n<cas; n+=CASMAX/8) pom>>=1;
629
      for(n=CASMAX/8; n<cas; n+=CASMAX/8) pom>>=1;
633
      disp(pom);
630
      disp(pom);
634
 
631
 
635
      while(true) // Ve zbytku casu snimku cti krajni UV senzory a naraznik
632
      while(true) // Ve zbytku casu snimku cti krajni UV senzory a naraznik
636
      {
633
      {
637
         if(BUMPER) // Sakra, do neceho jsme narazili a nevideli jsme to!
634
         if(BUMPER) // Sakra, do neceho jsme narazili a nevideli jsme to!
638
         {
635
         {
639
            bum();
636
            bum();
640
            SaveLog(log-1);      // Zapis Black Boxu do EEPROM
637
            SaveLog(log-1);      // Zapis Black Boxu do EEPROM
641
            set_pwm1_duty(140);   // pomalu vpred
638
            set_pwm1_duty(160);   // pomalu vpred
642
            set_pwm2_duty(140);
639
            set_pwm2_duty(160);
643
            output_low(MOT_L);
640
            output_low(MOT_L);
644
            output_low(MOT_R);
641
            output_low(MOT_R);
645
         };
642
         };
646
         set_adc_channel(LMAX);    // Levy UV sensor
643
         set_adc_channel(LMAX);    // Levy UV sensor
647
         for(n=0;n<20;n++) if(input(HREF)) goto next_snap;
644
         for(n=0;n<20;n++) if(input(HREF)) goto next_snap;
648
         if(read_adc()<THR) cas=CASMIN;
645
         if(read_adc()<THR) cas=CASMIN;
649
         set_adc_channel(RMAX);    // Pravy UV sensor
646
         set_adc_channel(RMAX);    // Pravy UV sensor
650
         for(n=0;n<20;n++) if(input(HREF)) goto next_snap;
647
         for(n=0;n<20;n++) if(input(HREF)) goto next_snap;
651
         if(read_adc()<THR) cas=CASMAX;
648
         if(read_adc()<THR) cas=CASMAX;
652
      };
649
      };
653
   }
650
   }
654
}
651
}