Subversion Repositories svnkaklik

Rev

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

Rev 226 Rev 228
1
//********* Robot Camerus pro IstRobot 2007 ************
1
//********* Robot Camerus pro IstRobot 2007 ************
2
//"$Id: camerus.c 226 2007-04-08 08:03:04Z kakl $"
2
//"$Id: camerus.c 228 2007-04-08 21:36:13Z 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
// A/D vstupy
9
// A/D vstupy
10
#define  RMAX     4  // AN4/RA5 - leve cidlo na vyjeti z cary
10
#define  RMAX     4  // AN4/RA5 - leve cidlo na vyjeti z cary
11
#define  LMAX     3  // AN3/RA3 - prave cidlo na vyjeti z cary
11
#define  LMAX     3  // AN3/RA3 - prave cidlo na vyjeti z cary
12
#define  CERVENA  2  // AN2/RA2 - cervene kroutitko
12
#define  CERVENA  2  // AN2/RA2 - cervene kroutitko
13
#define  ZELENA   1  // AN1/RA0 - zelene kroutitko
13
#define  ZELENA   1  // AN1/RA0 - zelene kroutitko
14
#define  MODRA    0  // AN0/RA1 - modre kroutitko
14
#define  MODRA    0  // AN0/RA1 - modre kroutitko
15
 
15
 
16
// I/O
16
// I/O
17
#define HREF      PIN_C5      // Signal HREF z kamery (v H po celou dobu radku)
17
#define HREF      PIN_C5      // Signal HREF z kamery (v H po celou dobu radku)
18
#define PIX       PIN_C6      // Vstup pro body z kamery (za trivstupim hradlem OR (dig. komparator))
18
#define PIX       PIN_C6      // Vstup pro body z kamery (za trivstupim hradlem OR (dig. komparator))
19
#define SERVO     PIN_B4      // Vystup na servo (1 az 2ms po cca 20ms (synchronizovano snimkovym kmitoctem))
19
#define SERVO     PIN_B4      // Vystup na servo (1 az 2ms po cca 20ms (synchronizovano snimkovym kmitoctem))
20
#define MOT_L     PIN_B5      // Smer otaceni leveho motoru; druhy pol je RC2
20
#define MOT_L     PIN_B5      // Smer otaceni leveho motoru; druhy pol je RC2
21
#define MOT_R     PIN_B6      // Smer otaceni praveho motoru; druhy pol je RC1
21
#define MOT_R     PIN_B6      // Smer otaceni praveho motoru; druhy pol je RC1
22
#define MOT_1     PIN_C1      // PWM vystpy motoru
22
#define MOT_1     PIN_C1      // PWM vystpy motoru
23
#define MOT_2     PIN_C2      //
23
#define MOT_2     PIN_C2      //
24
#define DATA      PIN_B2      // K modulu LEDbar data
24
#define DATA      PIN_B2      // K modulu LEDbar data
25
#define CP        PIN_B1      // K modulu LEDbar hodiny
25
#define CP        PIN_B1      // K modulu LEDbar hodiny
26
//#define ODO       PIN_C0      // Ze snimace z odometrie z praveho kola na TIMER1
26
//#define ODO       PIN_C0      // Ze snimace z odometrie z praveho kola na TIMER1
27
                                // Jeden impuls je 31,25mm
27
                                // Jeden impuls je 31,25mm
28
#define IRRX      PIN_B0      // Vstup INT, generuje preruseni pri prekazce
28
#define IRRX      PIN_B0      // Vstup INT, generuje preruseni pri prekazce
29
#define IRTX      PIN_B3      // Modulovani vysilaci IR LED na detekci prekazky
29
#define IRTX      PIN_B3      // Modulovani vysilaci IR LED na detekci prekazky
30
#define PROXIMITY PIN_C7      // Cidlo kratkeho dosahu na cihlu
30
#define PROXIMITY PIN_C7      // Cidlo kratkeho dosahu na cihlu
31
 
31
 
32
#define CASMIN 6           // Rozsah radku snimace
32
#define CASMIN 6           // Rozsah radku snimace
33
#define CASMAX 192
33
#define CASMAX 192
34
#define CASAVR ((CASMAX+CASMIN) / 2)
34
#define CASAVR ((CASMAX+CASMIN) / 2)
35
 
35
 
36
#define OFFSETO   0x9F //0x9F         // Vystredeni serva pro objeti prekazky
36
#define OFFSETO   0x9F //0x9F         // Vystredeni serva pro objeti prekazky
37
 
37
 
38
#define THR 90    // Threshold pro UV cidla na caru
38
#define THR 90    // Threshold pro UV cidla na caru
39
 
39
 
40
#byte INTCON      = 0x0B         // Interrupt configuration register
40
#byte INTCON      = 0x0B         // Interrupt configuration register
41
   #bit GIE       = INTCON.7
41
   #bit GIE       = INTCON.7
42
   #bit PEIE      = INTCON.6
42
   #bit PEIE      = INTCON.6
43
   #bit TMR0IE    = INTCON.5
43
   #bit TMR0IE    = INTCON.5
44
   #bit INT0IE    = INTCON.4
44
   #bit INT0IE    = INTCON.4
45
   #bit RBIE      = INTCON.3
45
   #bit RBIE      = INTCON.3
46
   #bit TMR0IF    = INTCON.2
46
   #bit TMR0IF    = INTCON.2
47
   #bit INT0IF    = INTCON.1
47
   #bit INT0IF    = INTCON.1
48
   #bit RBIF      = INTCON.0
48
   #bit RBIF      = INTCON.0
49
 
49
 
50
enum stavy {start,rozjezd,jizda,cihla,pocihle,cil};
50
enum stavy {start,rozjezd,jizda,cihla,pocihle,cil};
51
stavy stav;       // Kde jsme na trati
51
stavy stav;       // Kde jsme na trati
52
int8 cas;         // Cas hrany bila/cerna v radce
52
int8 cas;         // Cas hrany bila/cerna v radce
53
int8 stred;       // Vystredeni kolecka
53
int8 stred;       // Vystredeni kolecka
54
int16 odocounter;  // Zaznamenani aktualniho stavu pocitadla odometrie
54
int16 odocounter;  // Zaznamenani aktualniho stavu pocitadla odometrie
55
int8 rr;       // Promenna na ulozeni Rozumne rychlost
55
int8 rr;       // Promenna na ulozeni Rozumne rychlost
56
int8 rrold;
56
int8 rrold;
57
 
57
 
58
// Zobrazeni jednoho byte na modulu LEDbar
58
// Zobrazeni jednoho byte na modulu LEDbar
59
inline void disp(int8 x)
59
inline void disp(int8 x)
60
{
60
{
61
   int n;
61
   int n;
62
 
62
 
63
   for(n=0;n<=7;n++)
63
   for(n=0;n<=7;n++)
64
   {
64
   {
65
      if (x & 1 == 1) output_low(DATA); else output_high(DATA);
65
      if (x & 1 == 1) output_low(DATA); else output_high(DATA);
66
      output_high(CP);
66
      output_high(CP);
67
      x>>=1;
67
      x>>=1;
68
      output_low(CP);
68
      output_low(CP);
69
   }
69
   }
70
}
70
}
71
 
71
 
72
// Blikani LEDbarem ve stilu Night Rider
72
// Blikani LEDbarem ve stilu Night Rider
73
void NightRider(int8 x)
73
void NightRider(int8 x)
74
{
74
{
75
   int n,i,j;
75
   int n,i,j;
76
 
76
 
77
   for(j=0;j<x;j++)
77
   for(j=0;j<x;j++)
78
   {
78
   {
79
      i=0x01;
79
      i=0x01;
80
      for(n=0;n<7;n++)
80
      for(n=0;n<7;n++)
81
      {
81
      {
82
         disp(i);
82
         disp(i);
83
         rotate_left(&i, 1);
83
         rotate_left(&i, 1);
84
         delay_ms(40);
84
         delay_ms(40);
85
      }
85
      }
86
      for(n=0;n<7;n++)
86
      for(n=0;n<7;n++)
87
      {
87
      {
88
         disp(i);
88
         disp(i);
89
         rotate_right(&i, 1);
89
         rotate_right(&i, 1);
90
         delay_ms(40);
90
         delay_ms(40);
91
      }
91
      }
92
   }
92
   }
93
   disp(i);
93
   disp(i);
94
   delay_ms(40);
94
   delay_ms(40);
95
   i=0;
95
   i=0;
96
   disp(i);
96
   disp(i);
97
}
97
}
98
 
98
 
99
// Brzdeni motorama stridou 1:1
99
// Brzdeni motorama stridou 1:1
100
void brzda()
100
void brzda()
101
{
101
{
102
   int8 n,i;
102
   int8 n,i;
103
 
103
 
104
   set_pwm1_duty(0);    // vypni PWM
104
   set_pwm1_duty(0);    // vypni PWM
105
   set_pwm2_duty(0);
105
   set_pwm2_duty(0);
106
   setup_ccp1(CCP_OFF);
106
   setup_ccp1(CCP_OFF);
107
   setup_ccp2(CCP_OFF);
107
   setup_ccp2(CCP_OFF);
108
   for (n=0;n<200;n++)
108
   for (n=0;n<200;n++)
109
   {
109
   {
110
      output_low(MOT_L);
110
      output_low(MOT_L);
111
      output_low(MOT_R);
111
      output_low(MOT_R);
112
      output_high(MOT_1);
112
      output_high(MOT_1);
113
      output_high(MOT_2);
113
      output_high(MOT_2);
114
      delay_us(200);
114
      delay_us(200);
115
      output_high(MOT_L);
115
      output_high(MOT_L);
116
      output_high(MOT_R);
116
      output_high(MOT_R);
117
      output_low(MOT_1);
117
      output_low(MOT_1);
118
      output_low(MOT_2);
118
      output_low(MOT_2);
119
      delay_us(200);
119
      delay_us(200);
120
   }
120
   }
121
   output_low(MOT_L); // smer vpred
121
   output_low(MOT_L); // smer vpred
122
   output_low(MOT_R);
122
   output_low(MOT_R);
123
   setup_ccp1(CCP_PWM); // RC1               // Zapni PWM pro motory
123
   setup_ccp1(CCP_PWM); // RC1               // Zapni PWM pro motory
124
   setup_ccp2(CCP_PWM); // RC2
124
   setup_ccp2(CCP_PWM); // RC2
125
}
125
}
126
 
126
 
127
void SetServo(int8 angle)
127
void SetServo(int8 angle)
128
{
128
{
129
   int8 n;
129
   int8 n;
130
 
130
 
131
   for(n=0; n<14; n++)
131
   for(n=0; n<14; n++)
132
   {
132
   {
133
      output_high(SERVO);        // Odvysilani impuzu 1 az 2ms pro servo
133
      output_high(SERVO);        // Odvysilani impuzu 1 az 2ms pro servo
134
      delay_us(1000);
134
      delay_us(1000);
135
      delay_us(stred);
135
      delay_us(stred);
136
      delay_us(stred);
136
      delay_us(stred);
137
      delay_us(stred);
137
      delay_us(stred);
138
      delay_us(angle);
138
      delay_us(angle);
139
      delay_us(angle);
139
      delay_us(angle);
140
      output_low(SERVO);
140
      output_low(SERVO);
141
      delay_ms(18);
141
      delay_ms(18);
142
   }
142
   }
143
}
143
}
144
 
144
 
145
inline void SetServoQ(int8 angle)
145
inline void SetServoQ(int8 angle)
146
{
146
{
147
   output_high(SERVO);        // Odvysilani impuzu 1 az 2ms pro servo
147
   output_high(SERVO);        // Odvysilani impuzu 1 az 2ms pro servo
148
   delay_us(1000);
148
   delay_us(1000);
149
   delay_us(stred);
149
   delay_us(stred);
150
   delay_us(stred);
150
   delay_us(stred);
151
   delay_us(stred);
151
   delay_us(stred);
152
   delay_us(angle);
152
   delay_us(angle);
153
   delay_us(angle);
153
   delay_us(angle);
154
   output_low(SERVO);
154
   output_low(SERVO);
155
}
155
}
156
 
156
 
157
//---------------------------- INT --------------------------------
157
//---------------------------- INT --------------------------------
158
#int_EXT
158
#int_EXT
159
EXT_isr()   // Preruseni od prekazky
159
EXT_isr()   // Preruseni od prekazky
160
{
160
{
161
   set_pwm1_duty(0);    // zabrzdi levym kolem, prave vypni
161
   set_pwm1_duty(0);    // zabrzdi levym kolem, prave vypni
162
   set_pwm2_duty(0);
162
   set_pwm2_duty(0);
163
   output_high(MOT_L);
163
   output_high(MOT_L);
164
   output_low(MOT_R);
164
   output_low(MOT_R);
165
   // Ujistime se, ze prijaty signal je z naseho IR vysilace
165
   // Ujistime se, ze prijaty signal je z naseho IR vysilace
166
   output_high(IRTX);   // Vypni LED na detekci prekazky
166
   output_high(IRTX);   // Vypni LED na detekci prekazky
167
   delay_ms(2);
167
   delay_ms(2);
168
   if (!input(IRRX))    // stale nas signal?
168
   if (!input(IRRX))    // stale nas signal?
169
   {
169
   {
170
      output_low(MOT_L); // je odraz -> vpred
170
      output_low(MOT_L); // je odraz -> vpred
171
      output_low(MOT_R);
171
      output_low(MOT_R);
172
      return;
172
      return;
173
   };
173
   };
174
   output_low(IRTX);    // Zapni LED na detekci prekazky
174
   output_low(IRTX);    // Zapni LED na detekci prekazky
175
   delay_ms(10);
175
   delay_ms(10);
176
   if (input(IRRX))     // stale nas signal?
176
   if (input(IRRX))     // stale nas signal?
177
   {
177
   {
178
      output_low(MOT_L); // neni odraz -> vpred
178
      output_low(MOT_L); // neni odraz -> vpred
179
      output_low(MOT_R);
179
      output_low(MOT_R);
180
      return;
180
      return;
181
   };
181
   };
182
 
182
 
183
//!!!   if(stav==cihla) while(true); // Zastav na furt, konec drahy
183
//!!!   if(stav==cihla) while(true); // Zastav na furt, konec drahy
184
//   if(stav==cihla) return; // Po druhe nic neobjizdej
184
//   if(stav==cihla) return; // Po druhe nic neobjizdej
185
// Pozor na rozjezd
185
// Pozor na rozjezd
186
 
186
 
187
   if(stav==jizda)   // Objed cihlu
187
   if(stav==jizda)   // Objed cihlu
188
   {
188
   {
189
      #include ".\objizdka_L.c"
189
      #include ".\objizdka_L.c"
190
   }
190
   }
191
}
191
}
192
 
192
 
193
 
193
 
194
//---------------------------------- MAIN --------------------------------------
194
//---------------------------------- MAIN --------------------------------------
195
void main()
195
void main()
196
{
196
{
197
   int8 offset;   // Promena pro ulozeni offsetu
197
   int8 offset;   // Promena pro ulozeni offsetu
198
   int8 r1;       // Rychlost motoru 1
198
   int8 r1;       // Rychlost motoru 1
199
   int8 r2;       // Rychlost motoru 2
199
   int8 r2;       // Rychlost motoru 2
200
 
200
 
201
   setup_adc_ports(ALL_ANALOG);              // Zapnuti A/D prevodniku pro cteni kroutitek
201
   setup_adc_ports(ALL_ANALOG);              // Zapnuti A/D prevodniku pro cteni kroutitek
202
   setup_adc(ADC_CLOCK_INTERNAL);
202
   setup_adc(ADC_CLOCK_INTERNAL);
203
   setup_timer_0(RTCC_INTERNAL|RTCC_DIV_1);  // Casovac pro mereni casu hrany W/B v radce
203
   setup_timer_0(RTCC_INTERNAL|RTCC_DIV_1);  // Casovac pro mereni casu hrany W/B v radce
204
   setup_timer_1(T1_EXTERNAL);               // Cita pulzy z odometrie z praveho kola
204
   setup_timer_1(T1_EXTERNAL);               // Cita pulzy z odometrie z praveho kola
205
   setup_timer_2(T2_DIV_BY_16,255,1);        // Casovac PWM motoru
205
   setup_timer_2(T2_DIV_BY_16,255,1);        // Casovac PWM motoru
206
   setup_ccp1(CCP_PWM); // RC1               // PWM pro motory
206
   setup_ccp1(CCP_PWM); // RC1               // PWM pro motory
207
   setup_ccp2(CCP_PWM); // RC2
207
   setup_ccp2(CCP_PWM); // RC2
208
   setup_comparator(NC_NC_NC_NC);
208
   setup_comparator(NC_NC_NC_NC);
209
   setup_vref(FALSE);
209
   setup_vref(FALSE);
210
 
210
 
211
   set_tris_c(0b11111001);     // Nastaveni vstup/vystup pro branu C, protoze se nedela automaticky
211
   set_tris_c(0b11111001);     // Nastaveni vstup/vystup pro branu C, protoze se nedela automaticky
212
 
212
 
213
   set_pwm1_duty(0);    // Zastav motory
213
   set_pwm1_duty(0);    // Zastav motory
214
   set_pwm2_duty(0);
214
   set_pwm2_duty(0);
215
   output_low(MOT_L);   // Nastav smer vpred
215
   output_low(MOT_L);   // Nastav smer vpred
216
   output_low(MOT_R);
216
   output_low(MOT_R);
217
 
217
 
218
   output_low(IRTX);   // Zapni LED na detekci prekazky
218
   output_low(IRTX);   // Zapni LED na detekci prekazky
219
 
219
 
220
   NightRider(1);    // Aby se poznalo, ze byl RESET
220
   NightRider(1);    // Aby se poznalo, ze byl RESET
221
                     // taky se musi pockat, nez se rozjede kamera, nez se do ni zacnou posilat prikazy
221
                     // taky se musi pockat, nez se rozjede kamera, nez se do ni zacnou posilat prikazy
222
 
222
 
-
 
223
   //... Nastaveni sonaru ...
-
 
224
   i2c_start();     
-
 
225
   i2c_write(0xE0);
-
 
226
   i2c_write(0x02);  // dosah
-
 
227
   i2c_write(0x02);  // 86mm
-
 
228
   i2c_stop();
-
 
229
   i2c_start();     
-
 
230
   i2c_write(0xE0);
-
 
231
   i2c_write(0x01);  // zesileni
-
 
232
   i2c_write(0x00);
-
 
233
   i2c_stop();
-
 
234
 
223
   //... Nastaveni kamery ...
235
   //... Nastaveni kamery ...
224
   i2c_start();      // Soft RESET kamery
236
   i2c_start();      // Soft RESET kamery
225
   i2c_write(0xC0);        // Pro single slave musi mit vsechny zapisy adresu C0h
237
   i2c_write(0xC0);        // Pro single slave musi mit vsechny zapisy adresu C0h
226
   i2c_write(0x12);        // Adresa registru COMH
238
   i2c_write(0x12);        // Adresa registru COMH
227
   i2c_write(0x80 | 0x24); // Zapis ridiciho slova
239
   i2c_write(0x80 | 0x24); // Zapis ridiciho slova
228
   i2c_stop();
240
   i2c_stop();
229
 
241
 
230
   i2c_start();      // BW
242
   i2c_start();      // BW
231
   i2c_write(0xC0);
243
   i2c_write(0xC0);
232
   i2c_write(0x28);
244
   i2c_write(0x28);
233
   i2c_write(0b01000001);
245
   i2c_write(0b01000001);
234
   i2c_stop();
246
   i2c_stop();
235
 
247
 
236
/*
248
/*
237
   i2c_start();      // Contrast (nema podstatny vliv na obraz)
249
   i2c_start();      // Contrast (nema podstatny vliv na obraz)
238
   i2c_write(0xC0);
250
   i2c_write(0xC0);
239
   i2c_write(0x05);
251
   i2c_write(0x05);
240
   i2c_write(0xA0);  // 48h
252
   i2c_write(0xA0);  // 48h
241
   i2c_stop();
253
   i2c_stop();
242
 
254
 
243
   i2c_start();      // Band Filter (pokud by byl problem se zarivkama 50Hz)
255
   i2c_start();      // Band Filter (pokud by byl problem se zarivkama 50Hz)
244
   i2c_write(0xC0);
256
   i2c_write(0xC0);
245
   i2c_write(0x2D);
257
   i2c_write(0x2D);
246
   i2c_write(0x04 | 0x03);
258
   i2c_write(0x04 | 0x03);
247
   i2c_stop();
259
   i2c_stop();
248
*/
260
*/
249
 
261
 
250
   i2c_start();      // Fame Rate
262
   i2c_start();      // Fame Rate
251
   i2c_write(0xC0);
263
   i2c_write(0xC0);
252
   i2c_write(0x2B);
264
   i2c_write(0x2B);
253
   i2c_write(0x00);  // cca 17ms (puvodni hodnota 5Eh = 20ms)
265
   i2c_write(0x00);  // cca 17ms (puvodni hodnota 5Eh = 20ms)
254
   i2c_stop();
266
   i2c_stop();
255
 
267
 
256
   i2c_start();      // VSTRT
268
   i2c_start();      // VSTRT
257
   i2c_write(0xC0);
269
   i2c_write(0xC0);
258
   i2c_write(0x19);
270
   i2c_write(0x19);
259
   i2c_write(118);   // prostredni radka
271
   i2c_write(118);   // prostredni radka
260
   i2c_stop();
272
   i2c_stop();
261
 
273
 
262
   i2c_start();      // VEND
274
   i2c_start();      // VEND
263
   i2c_write(0xC0);
275
   i2c_write(0xC0);
264
   i2c_write(0x1A);
276
   i2c_write(0x1A);
265
   i2c_write(118);
277
   i2c_write(118);
266
   i2c_stop();
278
   i2c_stop();
267
 
279
 
268
   NightRider(1);    // Musi se dat cas kamere na AGC a AEC
280
   NightRider(1);    // Musi se dat cas kamere na AGC a AEC
269
 
281
 
270
   { // Mereni expozice
282
   { // Mereni expozice
271
      int8 t1,t2;
283
      int8 t1,t2;
272
 
284
 
273
      i2c_start();      // Brightness, zacni od uplne tmy
285
      i2c_start();      // Brightness, zacni od uplne tmy
274
      i2c_write(0xC0);
286
      i2c_write(0xC0);
275
      i2c_write(0x06);
287
      i2c_write(0x06);
276
      i2c_write(0);  // 80h default
288
      i2c_write(0);  // 80h default
277
      i2c_stop();
289
      i2c_stop();
278
      delay_ms(50);
290
      delay_ms(50);
279
 
291
 
280
      for(offset=0x04;offset<(255-0x04);offset+=0x04)   // Zacni od jasu 10h
292
      for(offset=0x04;offset<(255-0x04);offset+=0x04)   // Zacni od jasu 10h
281
      {
293
      {
282
         i2c_start();      // Brightness
294
         i2c_start();      // Brightness
283
         i2c_write(0xC0);
295
         i2c_write(0xC0);
284
         i2c_write(0x06);
296
         i2c_write(0x06);
285
         i2c_write(offset);  // 80h default
297
         i2c_write(offset);  // 80h default
286
         i2c_stop();
298
         i2c_stop();
287
         disp(offset);
299
         disp(offset);
288
         delay_ms(50);
300
         delay_ms(50);
289
 
301
 
290
         t1=0;
302
         t1=0;
291
         t2=0;
303
         t2=0;
292
         while(!input(HREF));    // Cekej nez se zacnou posilat pixely z radky
304
         while(!input(HREF));    // Cekej nez se zacnou posilat pixely z radky
293
         delay_ms(5);
305
         delay_ms(5);
294
         while(!input(HREF));    // Cekej nez se zacnou posilat pixely z radky
306
         while(!input(HREF));    // Cekej nez se zacnou posilat pixely z radky
295
         set_timer0(0);          // Vynuluj pocitadlo casu
307
         set_timer0(0);          // Vynuluj pocitadlo casu
296
         if(!input(PIX)) continue;
308
         if(!input(PIX)) continue;
297
         while(input(PIX));
309
         while(input(PIX));
298
         t1=get_timer0();    // Precti cas z citace casu hrany
310
         t1=get_timer0();    // Precti cas z citace casu hrany
299
         set_timer0(0);          // Vynuluj pocitadlo casu
311
         set_timer0(0);          // Vynuluj pocitadlo casu
300
         while(!input(PIX));
312
         while(!input(PIX));
301
         t2=get_timer0();
313
         t2=get_timer0();
302
 
314
 
303
         if((t1>60) && (t1<140) && (t2>5) && (t2<=10)) break; // Vidis, co mas?
315
         if((t1>60) && (t1<140) && (t2>5) && (t2<=10)) break; // Vidis, co mas?
304
 
316
 
305
         delay_ms(2);   // Preskoc druhou radku z kamery
317
         delay_ms(2);   // Preskoc druhou radku z kamery
306
      };
318
      };
307
      delay_ms(1000);   // Nech chvili na displayi zmerenou hodnotu
319
      delay_ms(1000);   // Nech chvili na displayi zmerenou hodnotu
308
   }
320
   }
309
 
321
 
310
   set_adc_channel(CERVENA);   // --- Kroutitko pro jas ---
322
   set_adc_channel(CERVENA);   // --- Kroutitko pro jas ---
311
   delay_ms(1);
323
   delay_ms(1);
312
   offset=read_adc();
324
   offset=read_adc();
313
   offset &= 0b11111100;   // Dva nejnizsi bity ignoruj
325
   offset &= 0b11111100;   // Dva nejnizsi bity ignoruj
314
//   offset += 0x70;         // Jas nebude nikdy nizsi
326
//   offset += 0x70;         // Jas nebude nikdy nizsi
315
   disp(offset);
327
   disp(offset);
316
   i2c_start();            // Brightness
328
   i2c_start();            // Brightness
317
   i2c_write(0xC0);
329
   i2c_write(0xC0);
318
   i2c_write(0x06);
330
   i2c_write(0x06);
319
   i2c_write(offset);  // 80h default
331
   i2c_write(offset);  // 80h default
320
   i2c_stop();
332
   i2c_stop();
321
   delay_ms(1000);   // Nech hodnotu chvili na displayi
333
   delay_ms(1000);   // Nech hodnotu chvili na displayi
322
 
334
 
323
   set_adc_channel(ZELENA);   // --- Kroutitko pro vykon motoru ---
335
   set_adc_channel(ZELENA);   // --- Kroutitko pro vykon motoru ---
324
   delay_ms(1);
336
   delay_ms(1);
325
   rr=read_adc()>>2; // 0-31  // Pokud by se zvetsil rozsah, tak zkontrolovat jakonasobeni !!!
337
   rr=read_adc()>>2; // 0-31  // Pokud by se zvetsil rozsah, tak zkontrolovat jakonasobeni !!!
326
   rrold=rr;
338
   rrold=rr;
327
 
339
 
328
   cas=CASAVR-CASMIN;   // Inicializace promenych, aby neslo servo za roh
340
   cas=CASAVR-CASMIN;   // Inicializace promenych, aby neslo servo za roh
329
                        // a aby se to rozjelo jeste dneska
341
                        // a aby se to rozjelo jeste dneska
330
   stav=start;          // Jsme na startu
342
   stav=start;          // Jsme na startu
331
   set_timer1(0);       // Vynuluj citac odometrie
343
   set_timer1(0);       // Vynuluj citac odometrie
332
 
344
 
333
   // ........................... Hlavni smycka ................................
345
   // ........................... Hlavni smycka ................................
334
   while(true)
346
   while(true)
335
   {
347
   {
336
      int8 pom;
348
      int8 pom;
337
      int8 n;
349
      int8 n;
338
 
350
 
339
next_snap:
351
next_snap:
340
 
352
 
341
      pom=0;
353
      pom=0;
342
      disable_interrupts(GLOBAL);  //----------------------- Critical
354
      disable_interrupts(GLOBAL);  //----------------------- Critical
343
      while(input(HREF));     // Preskoc 1. radku
355
      while(input(HREF));     // Preskoc 1. radku
344
      while(!input(HREF));    // Cekej nez se zacnou posilat pixely z 2. radky
356
      while(!input(HREF));    // Cekej nez se zacnou posilat pixely z 2. radky
345
      set_timer0(0);          // Vynuluj pocitadlo casu
357
      set_timer0(0);          // Vynuluj pocitadlo casu
346
      while(input(HREF))      // Po dobu vysilani radky cekej na hranu W/B
358
      while(input(HREF))      // Po dobu vysilani radky cekej na hranu W/B
347
      {
359
      {
348
// !!!!Dodelat rozpoznani cerne cary napric pro zastaveni ?
360
// !!!!Dodelat rozpoznani cerne cary napric pro zastaveni ?
349
         if(!input(PIX))   // Pokud se X-krat za sebou precetla CERNA
361
         if(!input(PIX))   // Pokud se X-krat za sebou precetla CERNA
350
         if(!input(PIX))
362
         if(!input(PIX))
351
//         if(!input(PIX))
363
//         if(!input(PIX))
352
         {
364
         {
353
            pom=get_timer0();    // Precti cas z citace casu hrany
365
            pom=get_timer0();    // Precti cas z citace casu hrany
354
            break;
366
            break;
355
         };
367
         };
356
      };
368
      };
357
      while(input(HREF));      // Pockej na shozeni signalu HREF
369
      while(input(HREF));      // Pockej na shozeni signalu HREF
358
 
370
 
359
      if((pom<CASMAX) && (pom>CASMIN)) cas=pom;  // Orizni konce radku
371
      if((pom<CASMAX) && (pom>CASMIN)) cas=pom;  // Orizni konce radku
360
      // Na konci obrazovaho radku to blbne. Jednak chyba od apertury
372
      // Na konci obrazovaho radku to blbne. Jednak chyba od apertury
361
      // a vubec to nejak na kraji nefunguje.
373
      // a vubec to nejak na kraji nefunguje.
362
 
374
 
363
      output_high(SERVO);        // Odvysilani impuzu 1 az 2ms pro servo
375
      output_high(SERVO);        // Odvysilani impuzu 1 az 2ms pro servo
364
      delay_us(1000);
376
      delay_us(1000);
365
      delay_us(stred);
377
      delay_us(stred);
366
      delay_us(stred);
378
      delay_us(stred);
367
      delay_us(stred);
379
      delay_us(stred);
368
      delay_us(cas);
380
      delay_us(cas);
369
      delay_us(cas);
381
      delay_us(cas);
370
      output_low(SERVO);
382
      output_low(SERVO);
371
 
383
 
372
      // Elektronicky diferencial
384
      // Elektronicky diferencial
373
      if(cas<CASAVR) {r1=cas-CASMIN; r2=CASAVR-CASMIN;}; // Normovani vystupni hodnoty radkoveho snimace
385
      if(cas<CASAVR) {r1=cas-CASMIN; r2=CASAVR-CASMIN;}; // Normovani vystupni hodnoty radkoveho snimace
374
      if(cas==CASAVR) {r1=cas-CASMIN; r2=cas-CASMIN;};   // pro rizeni rychlosti motoru
386
      if(cas==CASAVR) {r1=cas-CASMIN; r2=cas-CASMIN;};   // pro rizeni rychlosti motoru
375
      if(cas>CASAVR) {r1=CASAVR-CASMIN; r2=CASMAX-cas;}; // Rozsah 1 az 92
387
      if(cas>CASAVR) {r1=CASAVR-CASMIN; r2=CASMAX-cas;}; // Rozsah 1 az 92
376
 
388
 
377
      enable_interrupts(GLOBAL);    //----------------------- Critical
389
      enable_interrupts(GLOBAL);    //----------------------- Critical
378
 
390
 
379
      if (r1>(CASAVR-CASMIN-rr)) r1=(r1<<1)+rr-(CASAVR-CASMIN);     // Neco jako nasobeni
391
      if (r1>(CASAVR-CASMIN-rr)) r1=(r1<<1)+rr-(CASAVR-CASMIN);     // Neco jako nasobeni
380
      if (r2>(CASAVR-CASMIN-rr)) r2=(r2<<1)+rr-(CASAVR-CASMIN);
392
      if (r2>(CASAVR-CASMIN-rr)) r2=(r2<<1)+rr-(CASAVR-CASMIN);
381
 
393
 
382
//      r1<<=1;     // Rychlost je dvojnasobna
394
//      r1<<=1;     // Rychlost je dvojnasobna
383
//      r2<<=1;     // Rozsah 2 az 184
395
//      r2<<=1;     // Rozsah 2 az 184
384
 
396
 
385
/* Nerozumna rychlost po cihle
397
/* Nerozumna rychlost po cihle
386
      if ((stav==cihla)&&(get_timer1()>(odocounter+5))) // Snizime rychlost po ujeti
398
      if ((stav==cihla)&&(get_timer1()>(odocounter+5))) // Snizime rychlost po ujeti
387
      {
399
      {
388
         rr=rrold;
400
         rr=rrold;
389
         stav=pocihle;
401
         stav=pocihle;
390
      };
402
      };
391
*/
403
*/
392
      if ((stav==jizda)||(stav==cihla)||(stav==rozjezd)) //||(stav==pocihle))      // Jizda
404
      if ((stav==jizda)||(stav==cihla)||(stav==rozjezd)) //||(stav==pocihle))      // Jizda
393
      {
405
      {
394
         set_pwm1_duty(r1);
406
         set_pwm1_duty(r1);
395
         set_pwm2_duty(r2);
407
         set_pwm2_duty(r2);
396
      }
408
      }
397
      else
409
      else
398
      {
410
      {
399
         set_pwm1_duty(0);       // Zastaveni
411
         set_pwm1_duty(0);       // Zastaveni
400
         set_pwm2_duty(0);
412
         set_pwm2_duty(0);
401
      };
413
      };
402
 
414
 
403
      if((stav==rozjezd)&&(get_timer1()>10)) // musi ujet alespon 31cm
415
      if((stav==rozjezd)&&(get_timer1()>10)) // musi ujet alespon 31cm
404
      {
416
      {
405
         ext_int_edge(H_TO_L);         // Nastav podminky preruseni od cihly
417
         ext_int_edge(H_TO_L);         // Nastav podminky preruseni od cihly
406
         INT0IF=0;                     // Zruseni predesle udalosti od startera
418
         INT0IF=0;                     // Zruseni predesle udalosti od startera
407
         enable_interrupts(INT_EXT);
419
         enable_interrupts(INT_EXT);
408
         enable_interrupts(GLOBAL);
420
         enable_interrupts(GLOBAL);
409
         stav=jizda;
421
         stav=jizda;
410
      };
422
      };
411
 
423
 
412
      if(stav==start)         // Snimkuje, toci servem a ceka na start
424
      if(stav==start)         // Snimkuje, toci servem a ceka na start
413
      {
425
      {
414
         set_adc_channel(MODRA);    // Kroutitko na vystredeni predniho kolecka
426
         set_adc_channel(MODRA);    // Kroutitko na vystredeni predniho kolecka
415
         Delay_ms(1);
427
         Delay_ms(1);
416
         stred=read_adc();
428
         stred=read_adc();
417
         if(!input(PROXIMITY))
429
         if(!input(PROXIMITY))
418
         {
430
         {
419
            disp(0x80);
431
            disp(0x80);
420
            while(input(PROXIMITY)); // Cekej, dokud starter neda ruku pryc
432
            while(input(PROXIMITY)); // Cekej, dokud starter neda ruku pryc
421
            set_timer1(0);         // Vynuluj citac odometrie
433
            set_timer1(0);         // Vynuluj citac odometrie
422
            set_pwm1_duty(255);    // Rychly rozjezd  !!! Zkontrolovat na oscyloskopu
434
            set_pwm1_duty(255);    // Rychly rozjezd  !!! Zkontrolovat na oscyloskopu
423
            set_pwm2_duty(255);
435
            set_pwm2_duty(255);
424
            disp(0x01);
436
            disp(0x01);
425
            while(get_timer1()<=4) // Ujed alespon 12cm
437
            while(get_timer1()<=4) // Ujed alespon 12cm
426
            {
438
            {
427
               set_adc_channel(LMAX);    // Levy UV sensor
439
               set_adc_channel(LMAX);    // Levy UV sensor
428
               delay_us(40);
440
               delay_us(40);
429
               if(read_adc()<THR) {cas=CASMIN; break;};  // Prejeli jsme caru vlevo
441
               if(read_adc()<THR) {cas=CASMIN; break;};  // Prejeli jsme caru vlevo
430
               set_adc_channel(RMAX);    // Pravy UV sensor
442
               set_adc_channel(RMAX);    // Pravy UV sensor
431
               delay_us(40);
443
               delay_us(40);
432
               if(read_adc()<THR) {cas=CASMAX; break;};  // Prejeli jsme caru vpravo
444
               if(read_adc()<THR) {cas=CASMAX; break;};  // Prejeli jsme caru vpravo
433
               cas=CASAVR-CASMIN;    // Cara je rovne
445
               cas=CASAVR-CASMIN;    // Cara je rovne
434
            };
446
            };
435
            stav=rozjezd;
447
            stav=rozjezd;
436
         };
448
         };
437
      }
449
      }
438
 
450
 
439
      pom=0x80;    // Zobrazeni pozice cary na displayi
451
      pom=0x80;    // Zobrazeni pozice cary na displayi
440
      for(n=CASMAX/8; n<cas; n+=CASMAX/8) pom>>=1;
452
      for(n=CASMAX/8; n<cas; n+=CASMAX/8) pom>>=1;
441
      disp(pom);
453
      disp(pom);
442
 
454
 
443
      while(true) // Ve zbytku casu snimku cti krajni UV senzory
455
      while(true) // Ve zbytku casu snimku cti krajni UV senzory
444
      {
456
      {
445
         set_adc_channel(LMAX);    // Levy UV sensor
457
         set_adc_channel(LMAX);    // Levy UV sensor
446
         for(n=0;n<20;n++) if(input(HREF)) goto next_snap;
458
         for(n=0;n<20;n++) if(input(HREF)) goto next_snap;
447
         if(read_adc()<THR) cas=CASMIN;
459
         if(read_adc()<THR) cas=CASMIN;
448
         set_adc_channel(RMAX);    // Pravy UV sensor
460
         set_adc_channel(RMAX);    // Pravy UV sensor
449
         for(n=0;n<20;n++) if(input(HREF)) goto next_snap;
461
         for(n=0;n<20;n++) if(input(HREF)) goto next_snap;
450
         if(read_adc()<THR) cas=CASMAX;
462
         if(read_adc()<THR) cas=CASMAX;
451
      };
463
      };
452
   }
464
   }
453
}
465
}